From 2d90bd5a52cdd58b635e95ec5d5ef3d59a239caf Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Jan 2019 02:01:51 +0900 Subject: [PATCH 0001/1027] 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 0002/1027] 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 0003/1027] 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 0004/1027] 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 0005/1027] 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 0006/1027] 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 d88b6467a544ee96b7d53d88c364ceff86f0c609 Mon Sep 17 00:00:00 2001 From: Andrew Tu Date: Tue, 23 Apr 2019 16:37:01 -0400 Subject: [PATCH 0007/1027] added pynb file. started formatting and write up --- SLAM/EKFSLAM/animation.png | Bin 0 -> 113851 bytes SLAM/EKFSLAM/ekf_slam.ipynb | 1502 ++++++++++++++++++++++++++++++++ SLAM/FastSLAM1/FastSLAM1.ipynb | 2 +- 3 files changed, 1503 insertions(+), 1 deletion(-) create mode 100644 SLAM/EKFSLAM/animation.png create mode 100644 SLAM/EKFSLAM/ekf_slam.ipynb diff --git a/SLAM/EKFSLAM/animation.png b/SLAM/EKFSLAM/animation.png new file mode 100644 index 0000000000000000000000000000000000000000..905ad102f2e6ef948b91a437590e47e3c77db599 GIT binary patch literal 113851 zcmeFZWmFx@)-H?(4Fq?0x8Uvsmjs94?!i65-Q6L$ySoOr;1b;3^)@^E$QWQ0Obz2caLByQRKx1As;k|c2~j=SP;T{f!3=-utH?HZ*u}rD88yi zJ!)o}**#chnuS%8p*sRCZ$OyC`eO`1Gne77N`ySoHz(R4D~m-4<3Tco{W&5T)?o<4 zeVwJXS7^!n9Xp6N;L=OlZH+>0&YjgrRJB4r3}opwvL>+ayjb+V#J6bn+Q4&jm=LQO zv{V_*)oXB8XU8T&*=CTEkfZB)1g-`_Qo98z6iK{G%B>TZxwCtFi1k_Mkb2EeOwa<> zwt!O05!m#$e#v+4jID+<$ar!-+2WDf^nF|C-+0f(OBC#>{Y0AX*3m6FZHOH zo}Z_y$S{rFkL4kvK~(#xOlDaeoKSj}fl247zLd2HMoP5nJ@AVIsAoSOEeWqtJ`f8{ zKhA|pt2wvyX~$C#lwoL4Birkg@gNHRK4yF^MI3Ay~tgK8vfYHmYW*UDGX8nUvmg;8)LpJaQsLgT0#hV?2!ubU^6kWa+pla zN6;vw0r5v6KeE4E|8-k2= z6w`LBNi@YT$q&}=-6tHv@OtCEDvBw5rFyI5X2xym7G6Q=c5fIk-Dnhg8OOqW;ov@s zk%r#kHa#0Zr+5hB_?A0Jt0VlgjJF?Ne{v<;VF7YPN%pF8u?dHI3v~wW0LimBPda&C zRgB%N>#X){#C{`~Zq)e`G)Hx=y}>%I0%!=r>Z1_4N*4jQ|JL#THk|i4cebZYt6otX zBJ{<&PSYa_$Zfo!;ZGf|^!FeE1mGRc7YU>HWbQnlKy7Nil}Dl#IW(LLfhgZPFoX1U z;HrYZQH|g}1$!pM^z{iML?`{K%n0tN1~FR=KMZxzp(hXfqm#MmWZK?!I)UBbRVNWBmalH))`-08N@E!8X_F!?qIr-3VAj@^#IrFuF=!C2MYCaWvWc5Vz3cT6Kfcf&3 zsxxU#d<{7dsS3Ip=DRO!*V`_lF05PDE2I^qAQAG3^j(CEK4m>NTY6hgTNGP{Gl8SD2YB&V?_|E_#P6p$Pbb@l5P_Hk}49sxlRUjRgm*(xU#Y&QUg*0Xq(HM`kOSH z6q|y<^u6)x;z8e`DeWm~s1~W{Vuxb!e-M6*Fq1>bBv-613@MD8hT6y4=iR5Fqobpt z(5 zbq{{eZRvllYFSn%;FjfB>zH$mcC^EVil>2BHwvGomj;^#&XwSB|Anf_u?bfz{TOW7 zY`MFM-Qmq8rmK}}rK^kU(3RtX*0@`d++_U};uOYi!mjlc|M%6A4$PnMZ@-P*`d6me z`cLQ!uvW0IVH@DY;yfCRTa8;6SaYl}&Q}anESwhTVxZ_RFf|TqZhzSJ+(y_AP%z4w z%kj;L4>QAbFr3!NnGov~6Ut%EX%(9dJT{QaVdhi%p7Rc>b124l4hb>;Q#I|5G7 zb^}fY4h`E9UoLHjZI?FZe))2_a0R6nrO|WejB1bS?Z}L#=|k(g_e=Cmhd1sC+3Pl= zHcdD4;11#9@H!688@^_2D=eQ%E8UTs}? zN`A9UvZS9SUfmyZHoD=r!5-1RHF%o3d6#BfyhFiY&5)$>O{Kg(%&EyK>_&zFJcA=+ zi*LsRrj4i#&LiTs?dIZ~=5+DoCcizzEBwXkB_HLG0-C}iV;t`@S_j-5_Bh%AtTf^y zQ3cHab0CH?&L!m>mnu>V$t}!cRNBZ&wUsP|f6^G|yI?;t-*~^efV}`R zzmI;r(Dkrmu;qv+5vQSvIJU&mNLXl%T<7Gop+h@AZ67FH&vO8KHK5;xWJT~Z%qfqqAl%+p%tk8LCKQ=;$bq)J2 z!&oB=Bdd_F$k<6JlGc(RkjhDwNqMFqCs&bwH~-Nr!M#ytVWjb(dneY6c@s@$n@wo?k5t4c$FcXfi$GOKR0xvk4Xa3gm|0sRZd5h#OfCdZwVHRI?aU zvXePk<8w0bo>YkFM3Zpx4!M7tD3L9!u2EiyJ4tBgYu7<1TO<r}wft;2ClW+2KtcOK*1ots>MH zJPE*YJ}Z~fOej%1zfXy^R{t>k0X^=E7tWcbN1p}w^Qxs< zFasKcrOtMx#YWYb;n%8=t+Fk&ErNuL1f9o~qlX_S0iO)YOmy~Y?JlU-sRxU2iobn2 zQO~K*bC$VTkTl1ct^65R>elMHeGiAWK~rauX(ey5TNGMmv0_qfJJT2OF}vtshG@pk zT-rQ-re&FQ?u()Q>9#+ek;adD_glfo?$XkC8aU=hW;Av0>d~y+T6kR^8VNi+OBQvj za@_m#)1uR~n%AAu$}Y-^7cHCI40+Yd3r?0_CaEUdbA>`5j&uWWmId$bz`vA*uM9{1kxkbyfw6~BNzHom?1Y&Ar`Yv~pLsheb(ZRBklB^at@7=4)=*2y(zMCsW8iQ%K*=-$1C|}6}Jt;lc5p3HaxmC6s`y@m?pb(v)!5M*@jtq zt%$}I7m~fc(v&GH$7SRtS6A+v>kw`~C#VzpCh-OpN1YqbUht_mwJ&y$vn%xFWjTn# z1a-V0oWInktUevG-&qs5eZZe0P~oX`R=k;h+KXB_T?t>!e_pwezPG3-zeH^1H%sT{ z;lDLL&9Hn@x_8qa(1vf-eExAeGdjDWQ~$OHfyX)K#^}^?o_oWodF7#n|AuI*JEn7< zK$3ulpVQOq4)^MAMSf*GGL~Yaunr6p*Tje%guw|+K+exC;4Mgj(##G|9N~U-A*|1f z?~JivoHJ+z3#NCjD2PZm?++sm3!=QvX1n5aOn7<3h^VZ0E_ngX$stg3JiboC!sWvt zgtZ{2l5DK34W=f$Q;vy;mLRg5#bXH{h`Opf5yd`CJ1Swg)4f2g4tvV{$}rgmQVSRx z2{n5V5OlKFUru1mh`#?)_R8Y&XzX7w?RO7oVkFvmWE$+ z37su1tn9g*d5Qn}1{d)DwV8pK@UO3YG3O;#m60bDwze}Qd{56x&q&M%OGrq_V`pH* zr6?ly_vOGDFR{s&FE(5Z3{Fl?^iC}F)^^4WOq`sY42;YS%*=GaH|XqLtiI?v(^=V* z{JzOQ?jvGouWx5+^TpKKitzQmx_Z_QUwDa$Umx_(pWpp7bT<9hldSCj9u_b_hSyIR znCKZ9{&{cUQl8gVE_qXDLkm?AQ%gfDd*B&-OiXO7JbzvAKR)``BmeDEwSQg8!Or~e zSN_{4e_zSN@H&Ej8_{oZ{nZM{iw~BE;h(bSgH7z9jsm6w*HlDK890Ky&J8egHNYRr z-^bVY&)^%fn&2QH0w9tig38XIhiPw8QAELeb?o9c)^=NI*pdk;31vjzi3&n+tG+`M zlvj9%q%2RRSMH4(X9lhy2q}srpG=@AVoFTdYL7d6K0>=vnc_G1mwK^qtc;tVnARb|Mc?qe<%9C-TE`3 zK=*+6H&A54KfkcWrvG%y*XMZqfFO{7zlHj9r@SFdFcrZ6JRSisC@|Jgcn-|}<)O%# zx*`aF9175g2|dopy!QEzl6Y!z#f7@e1M;HTRxl}Iw(17I}*!G{aAaB(y$KdZ_#8<9U2DZ}JqUPOAUfMH=_skXT{#{bNfL?NZ1 za2x5DK!)}Oxk7~|+lKK4sr~C13!GC@ZNvSe{jc-FuAzGC)wV}8K5nODk?$YkU{8#) zchgKU{R&uaj+aBuw}#AXU!HDO3qF;q2d)Io^nv*(<;&_0Mw6*4rLbFv=jP_Bny@Wm z5`#@E1$Oj(uANqdcXWkLk>>S7vV#94!`u5gKcHf8S_%3Wb&)#%^GdZb;*U6*{DSSd zGJk)Cz!({S6t$=+ zPxwWjl;pCAaZ;`nUw_79zXpZSfTxI~>A7sGSAl>g@WeuHnfI%Q} zphbAU2Pp-(eSc6mh}+02kT6kqv@nr3^|Ov6uA#mvkusF zj1G@9E6~gg6FUC{-0X3^QZ)NjCK6f+^lkzdz6+kFpf>|NpjYtJIuG&KZbeIC0 zJdsp@E(xOV&=W>p&hw0Mf)r>bWi+~x0-h1lj~;Y?#tsZcOX$Bs`L9s^t116oKL52T z|24FL_vu52p-+ITieP4DwmILFJi1AK-wwn;-x^N4;E1NK_|NkUIoR1}Nr1Qsf5j6S z1tlsqH8eMu^r(J#!-fOESk;-sLLncK09Vza8*K`BFjE8CwE(~!z6qC!zTB|J7Tf3Y z^N-?+_fNk3`d!yRpxYY~%w0mwyN{R;a8-O0lyZ?`qZ2vem0mBNhl}-c4@vx9eA;eD zwU0MuGevPm@LS*W^YhL7AwmS|$tJ3skFFO}kT2v*;AbtvJKwH!^;h@q zL;i2wgGh}`N(%b+2GI;ElJ(oBaogjD0T4kgjD_QIS9m-)TCB8S&Ckz+&f*|oeVI2z(eN;KM&os*ixq|k=oZUOA0N~z^&sQvwafy6u0<~Zgg-?uzr1@wai0n|R)2@Lfa2k%_IE(xHSxa&6npU4cW-*D4BG>r z+`Pfxy#2h<7dBU+3;wB0GboMQDSgl+M+FEfCqq#icOqGpH%}TG8Xjj|Y|rDjq$%%6 zZiJ(s=#9AtTf>QuTu(dSoZTOkn?Ep#F0@{Ff>U&i<#nhr8FxYy>_v2Ub}`(dcu@GRE@_(3S@SlpnsZ zXw;cTBgv}mp1k3>oY}2$sWMZg8tj%qpU&2MYdyYgdJ5QCXA+ABo3wA4n?e^ha^YyRDr1w9hZ7X zcBAH+{en`kn%PE8Thb2&p?6h12(_DYj$V*oaQIWm9Q8`sWEb31|8)oo9doe565Ry? zB0rgTU&BUh;dm}#Z^S|t+FNR8u*z%-Q@zLMhZ7*O=M)RW_Vaqaqi}ZCHsd&HxsWea zf3IAq2sw!w&2P7w{u-sbT@SRnZI)#E`a&>#C*h`+lbZB38_)DH!X0c)+q9s25?eh- zWN&PrD${BvOt>m+QLncOOVDmFFo;WfOT|D#k+aVtb^~$92>3JKb@rYn3Rw z$cT)*-1W(a-%@|h{@qsN^834 zBiu}}%Iq+a%Y9O40)@XCXZVWoj)>~lk931}=bVj}i)^8|oXGau!!S)-cI2ND=(TLF zW>kceB_=yI(9|GG_Nl7W2b&QvK=-LMbM-eoUX`@^KPah>$wUl~r{_%3$7Ci}>lL06 z(rB^pnPS;Au7>SobDL4lowdX2F|iTs_X>?443ASb-k4CB+5P+lq*AgrfgP=oFl%AbiZrzioUQv6S%iUJh$ zWHkA`IqNr*=f}HSK&_^|9G4l*jI4r$YrYvaHV$ z3+&(14_9mdlgS_!m9x{qbupVC<9~rSMH)%x#j*Pol|%!WbIZj#(V=*{S~YSzEVU$N z!(rvl7Efr@`1sAd#mU{p8dH?bbV;cMdIaaYEFMwWQJ!diMI1DmPnT0d)1-rDZ>)M(6j+%7rKV}ppdFnLn@aR z({y*-d~!NSk&(Et)*_R_)^OH`Gf}3+ZAnFJoJ@rr;AeK2O#xRwO3X$oz&l@|M0^_$ zXpvL;f6yXO?mbET**1%LW?Iz>kPNS9&ga_=#EhFGIzg)sbT@d>57RX!6JS^SGdY5r z2+D!$hq>Qd$hSwNAI|y-Y7Il|_Oe6aHlrU@)3lp@3Qi%9xD8TD66t!^BkZed#pP|V&WsE=q;F2oA!s>qM6gB9DIFU5 z5z4!Wrh z@LbP&F_3M)}Asl(QxP0~g`;7R5vCW|*aoxCmh z0YEM}8ueBU092#U?&&eo0AE1Jl0=MT>dHLBVf2<85ar=O&OJgQFsuI%<@^uE{kh7V zxuk&w`{ z%0_}Tm?3lS+X@&x{o|#^L^ez8pQRcYNXtzQ2kR?tCo|VSiWG9h1Pl|Y7{Q`S@;lTA zG=BkV=@;X8*^Y5#@WS`=Z}DqjiD76v6FuLwznJ#p3}FcXnk@=A)*Ag7l~Q#-z#*Aa zWDjifKc03wZ-lYCM`QB3vfkgElz$&Wpv!Pxhfyy6gs@m|Ju6MxSntzf(AJOdChb;w zPVnkI3rTTO9L|W){sKy*Sj5xe^LH1XZe1gtQmI`=uo5}F!n{2>B_5W?53~9P0o+ro>Qng&R;7vqGyBAXly1#F-bV^)ryNW)T(w~hQ(r(X+B%#(&_CrBv`i;vAby9?pGq5 zu86iv7DjFQa|qN42xSy$GT>2Ajp@VP)_LPo{QbXL>Jo)h+O%vz(0 z(RVM87joaF2w$W4T-l0Bbrb-STe#R>c)G7*KO2ZPKJzTbn8-Qv(1x>~s{jQoxDQjQ z2l03vhqgH%ghw);g)|D$U1O8&hL~kt9&3>2%acMS*U@KhS@3@>*lz}Z)vN%p4;b1qLp!B%;|SbCzXm?noyjVJ)dIU0VB{_C5AUyptE{Di$TWW1L!6w;wN9QKt5 zo;q`rl*h@~T@t)926%BAS0}L4r>C&c-O+degYE2J@(Uhxe-9q6xoz^d$@?D29J)!M z3*;%YY^rh4Kg)F@F2?v*1@!MP_Zqh1HEJ4MF17_dg^v%Sacb+#XJw`0#rId-FGkv` zTzjMh@0+iW7T>sBmbGjS(iE}JT;Hrnhwy=&6V=*neJItn%W--lKc1LXucO2S+fb1c zC@1?iru=INVlqYaoUuA7z+1;|G?r#9?$JFa0Cix@pphV|`xj*S4c;Z5|+#;Z3ASjin z5n#?_Z4)5~J%d*1dpPmbRUeVv?gZQ&K}ACvB2#I-z(sqkkHmY>BpnGwd%ov^nf7W? zYA^ZZLZ@Up?v4`;r*W&WL~O2NLTcH~Z+qM<=N~yuSLk*pvTNLx&`2;zvkL=|uyBYA z9I*f|nn=Ov)OShcR#%53F(A%5hbIWTvyEE*HiNG9-Vocp z?+LD(gCUW7bQ*QjUkTh#1)nW)TE2L-kHClX-EE@8Qh)rR;~-7)TF^FxXj^(h)4p?> zOuAo^$>FJ{)CxWK;s$khfrb987scB4eQ>44#s0|0V%z?7c;xgWC5(X~x6Q2$@mqY^ zE}}bo)_39&{pS2+H%Ed`X+smcyK)6vs^9b*O;vq9six0i1_^=0RlSJzE_uD%`O#-A z%Doj9l|bLr^LZ8sChNXp4A^^Dq)v~eBwa2jn)p) z<#1WR^p=wnJt3?nmljnHy)b)}LRka@1?h7GTQk+RK6D96dH|@1I3?E-%fD5s{_lGO#_iG7vIn4(g>%I|(*-8FBfi`W$=u?Cq<7j!0x zJb(5hI=T(wI9%3&aJxb4Ob3_bAe7GX5Rb07DY)fK@<;S{&JGEKbf}c`2#Gy28h-Scv zQYSq}BjgyaJLD0vaYmth%R>4`EQ0=<9+g5m-=J8(*d-;(WH;oX^(+6){kd4pkDGRx zdfVFY3omc!`{X3-a!K&j^1X1oXpy%kwN*YorcZ<64889vs~!`r47R1z-~!+JVUYQy z5T2AAb5XA$2nll2XdZ~`X5veM+(Tn{pW3;dTE{m4+SwH~B8q`G<^YmbA_N-^%#Y-@EhxklCgNkBy)9S8=AVw}o~Ihd=rsghA!QSG5hN?*lF=1}PUBc2KhOK?4gkzxyD zur`|51O`&^jI_=hd&NqIdgf7?Ig_HpmBZ*;?i-%Ki;umyMWhzAt}yY_N1^BM6%|^8 z;cCqr<%|8nKhk7qGaDD#!6mVGOu3Egvn5F7KrdRleIRwewInl>DA z_4H7fpWfvS3f}X~)azla7wiJ27Z2m9f#7}(Q*ptjZD`yvnVwnB`nANI zhQ!Z1s4UsJFgqe2CJYRw`3S;8a5C*$6*-FYz~2{hN7@)o#wRS4h#z5WXQtYcCd>|D zO+aelaeYCOI(7>*%u)&B&FtBhQ*b_0!|+Q}50uGHhkfUX+V&m@re%S0Un8lEme>3O zV>C-}S;IQ)E4;G6z67LmkX()}E7k`tACiH>TBtk_^^2PHqfJ^4kueS>F!aw=>J!}< z)0m)tduDsMItXCW@7v9}<-!CDKPj&4UDD*V`1+Bxm(RYmhFV#!}MZXB~6)zmvC zoRsy)oVS$RQ>c;cYPLaYqTr{FID8%0fPJlRp&=Sssy{(oEb$qriC*iGqx*K;tJSeKrcA~Bv(}fTdY5Vp#N%Cr`!^WDup`V zeCUZ4tZ|dw!8pUCuFkhqGKM@7N8_Ps(|_(5I-TK|kofbV)$s}=YOPj*?`(5i6$0BMQ)eJ?XwB^67}_dVNAm(ovvx~Mg!^@Dx(Vs`|r7+%g1l5ny?Dw znG%!T6Gle+3cZ|uIc2pEubVbVq<%;y4UY>5>@G{|$k1!gQd8=IamUI(2*jW$HWiy# z&PSlUNhVVLku9sva@_;8{rFb`#OU{g1RQO*b|w$_Ic>^?)Q;on~tix>2NS_`UP#XLuYo zX`1u)mnX!lgV`I(Hlq=2R+Djokc7Jow`0x-o=%ZhaF-G@nwAFUlt>iMnWO?hk&XmF ztWEtnTueTaG1)ECL#>|2*3|W0#ANWd6KwNvFIEJ=CVb!8U~1#A0hwnA_daN5h>X-a zJ!jDWHI-$lHp8^&0vD}CVJmoiVuJgE5}n35w^0)0HFn^gN<%MRNP`nRC9r|?;*&Ud z(F?EZZoy@l>s&m}d)y_}JDld`Gej>wz_vQkYV4CCBOU>Eu^mkJ)mOn~>myQ%{@w?S zE-BMXk2}Z;w|WjDc}(T?&6yIVM!l-o+tv-8+@oi-Af)PKT5Yv;rwTwfXu@ltnhHZElkObu?5MkBrFi z;slWGjkr%*Bh$Wg4~>v)K`op|&@=*DTFhpK+rm~KU+Em@A;CeQ0EvPcM1m=Hs{qp% z5swSCyyZOjI%`Gn!%uDyetJKwF6W&GFFQkQ2uhtu8Qsl29=wXnRgbuW}p`aoLQ zRZvirwlFWwjyMc3*RhBSiM7V5Pu1uuJ}2T21tcVzzsIl5V_3L7~QK zUto$n`=mH2!>2}SxGtGV-=FQkq&Ss#Yp3a#KhAi*9Kq2VQaVAHMaqjQ{v%VX>KU3@`gZ~dO zsn&E#ETxD}CJRW*^m_u|Ez~!4*9B~CF__s;;yu<3)4bmf;KePt$hhVm!7LkyLXw6Rg4E2urU8RDS zQ!bIm&kxS~*mb)#mb7O|rSkxGb@^)*+6UL^gF^X&zT*^tclA$Fmf6AdUn#ymPOZNJ zK2R(|*99tQ3!%iET`2m%ka5#c}(JW<+Y@&de<5cKgv+QAAd4l5k05O5zMd$YOz8+M?c*AoW!5= zONT{%tP%d>`U^tAj9ZnI?f_)9eCbDrnv%LV7)GT+mCSm=JFsZ7)_s~{p^y5Tljc;^ z2qY{|&YG#)Y)7Oj92Fz{3SCA`Sv$5W@#P*auw*rt1H8gtd-)lChx64QZIb2Mtu;x} zE^ZaAZHF>ERh#pVh9+&WO$VmuCj{%y8BlAr+rs1dd);lpqF-8;pmt~D8gGv&FxqaZ zFk~Db1I4Gre|;6Pm2L^5SxoXxm8_1M9!O_lm1Y%{{NzL@x(rWJ9J`sfaNt+Bxo5@i zP9YomFp@)FdH=3_^KDPjW)sJ@bZ2D)s)a;Ru#&A_eCFbegmY9Hy;G)#2E}O6p4SOU zcjdkS=)$laVb2)RVfiynSPXam%|6T{PkF~Ar{1^AS~UbFmc38z^5^QQ zq1>%4$~vbOmA!K#mUs>Kb`<-8BU2uw+X*bF0PwBCYPq1SvvhDkrIcqvG2PccM1lr) z@}H*M1QTs|K=JJ>#H%JWAjAb^AA6rg_J%h4BQ}oeSAWX-$Fe}QXdNxoP7RYb23azy zupaE?&UJ|%i?eDZim-Uu3Z^EOX^~aG)n8b7V{5w}-7(%9LS|ID0Gbfu5lC+-88h&v z*5qe&1i3~?{7Zg+ATJufJNMc-h5g2<$2G!$4XU8+?7Q4`O5{kGH<}9(k2fc|P;+(~ zIyJ52Xc#|lS_|)iDpRoM)BT;t34lzm`C(|k!vA!2M%1ZFGXRHCtLOiT7)d7-3~*>) zvAl&zW*39H`qz5wLQpusz;xsAuD{Qgk+UP8hzPM~GEaxgDCN*c-l~1dM!`9qnBbNt z^7PV<{dF@qO)cTvfVj?p?8c7A0fNf#cKV&vD6C7J-!F1Y>_9d;Kiujifde`wx6`zD zKUT~njm$MQT#$c|agQH;cw^Pj2L$dHd>0bw1&;lAPPZP`jbj_9zq%(%)L6(e*gaQ= z>7rciz`H)n167L5)5;1QfGCL&i16)qodQqfPvnabZ(_T~fo?>8_{O`E`eL9&pRDlZ z;iw)U2~TLCOW96jQrIGqe|nA&k!$<%OSqC@LejRYrT(A{-2PNi)|!;_ImIk@XtT(U z4c8+Bq70cO2=>m|b=gvMddOs4F$+ZJ5`|G0w?c+CjK>9cfCJP3c1LL#zsinx%Ng<{ zZZB2maw%HxYV-ZuFBT^vGt}ugM&)YNVh@K=Z@%3&H8~yy1K#Xcs{QC$oTv-WRW7cn zG_WVR_sb29_3K&TIqYwy%jx8w7#|jzo8F1N=Rmc*YnD$G=r<;_h=ss%KH}u$WNbZY z^i_>v3S5R)Tu6{kbA@nd<#IW7zT?JEl2tQ`g!eY|f?Kz|$7z8`qAR7lridMFKQj90 zv&h9^JM!^uEVU_X#HSL~EV^%LG_p+gZKkOFim>Jt@8(KkX3<<>NsLLv9`W`NQ~Ady*>h zB_E-Y^%-osK&~m(EqXwq|C8R`=4==1!X-w}J0pQgy>)TgxL6hhzn~4|y|?^B3+M*g zVGl#Cf#5L4U+A64_NT{vj@h}!vy)i76w{V)A6~290P<2JQ`K6_NJa)pA{N@wdb5Hv zi2^J<0Oc}{1GzGY!yR%V5#V*n(JSZpowKxM{fVhDUorp`A8W9L;m~PMU5$a#{tT1> zzyLWg)anEwh$%j>odr*m~^2P+)G zN5b)5H6i}Z37f6rOpKhpbv6$^tf%!2>k`nInk1+yV_rNi zQns@6m=Gs^2i+Je`VF%?H2e z6PF5vGfJ$YH>IDV+fXkbESC?JgwW6ocMLXUYfl+&#_5G*H#c!i)P*Ufbi@+H_jv$Z zrexbM>%IvN8QGyrm~NW`Q6`hQL1V6^r1El~3MxYx00JBXb7;K~Fgzi;7Q^55nmK?3 z{y(YPu#JJN0d0@xQkHk~{4b9iS627eN5w}3#O(ENcMREi2j@lF%Z7V5ljw(UKMs@I zeVaHQVCHesV;q&douca%XHX(*xn zyob!RxXbeSm;%4?E%%Rgc_V6MJc>%*dN%a_`p&P}GPaCmnCrbSbs{Qt*GgRUI5Oph zzBtEJ<(9FnI<#&$yskAy&O`I!D`m|mZ8*Z|SYP+w7r9BX;feDmiS>bbLIYg$HO4_! zz=X0^Rbc#P6?Dt}$%NAM5WhS>Fyvyf>i5ByJJ|vZfeoO*Dg=~cTk`_ACh1+HV=(wI zs)MvslFbukVrQS>WUV>_zl~*yt|PiAK)$r?X|L^d3J3{xx+Ia9fH_Vmjw1xc!#W;< zSnY%0&KnnsPNHLPV27?QUUxjzbB-VCQLtG*OR?1D%Viwb$~H>A0EMOqaeNmDyYigR z^!rqpuCxcT-mZ2OT{et>FZjIcmtXSRjM)FljHnZ#MpXyrN|Lgd@i`tQ_TvFNGByBE zr(erynd~vNi-i?dL+<6!=2u8%v$vd4j_bCVdz#(*yabDsF&d^FQtf3HFm?)Q@1+9v zOeqV9P~)CKWAs(vsJCsYZ)y(A!)>2RUU3)$8i>A-J`AH!0!Mj8 zzXZA8g;0V&GIDh3tITKVk8rN#_|7zuiLJMQ%5f)9c#^Nw>t$R`+F3;NPv5+jX)hV* zJy!^sFu2la;IOUigm2>hCG4({jkcd_-4_sWB0Az*n$AwIUz9-+nx)%8CgbA==cBOh zP{bj)PsLPRpu5Wsf8(iCiKBt39;~%MuHNRtVl(6*aQ_a)FI27Hm_L+a=teZ01yt16 zelaJFL$|b;qtNCqKiRg%en(c{=S4`X*>NWH4B-0#yVNlxdGB(%S*w96c6CqUDgmH; z1bA+_dw*@%xccLU4LWJj%@Sf$V~{PJs;oRsu&Lh&kHnmwK+5`IU$1A8O(^hOea)k-iqE4 zT3Kv%c+}_WPjopk*{lf|4D!YtO&8-g8^<8Dj&Kd-~t*! zD|O|6&*is2&n2bZ>6#!9Kmtf)HI1HiaszlTOeW)mxp{f6G7KdHHoKC?a;!(yxS?rZ zP}z@Czq)Ca6Ve^$-jQ=}_`G=lcM53@3J$F9aG4Jl;HWVuh7undk%$qe$3b~OG;KF* z=0mF{$#Cg0hwC@G=|n*zKr=OtPp&P3S#msjTRD3zAf3k5Yu=d7>!t@F2oh3K7s7I$?+xB>`vU5EUg^B#PeU>w+H26 zR^Pn=0^d3i>h*k2(B6;Q#uxm5A47qJt1B140x80Ke{@8*S(4rP?M;q}LM22`o(kn< zjeP>#iQH)K;)Q0z^LPYi+yvbB^>8<`$URgRKd5j4Jx<$AkCS8Vi?yE*J`_+OK|w21 zSmtnGS>w@k*yuy-m7Zy;&vzUZreSih{q`tlrpLU_r3UO4GG*CYG$>xUGaKo>kJdU@ z>aw2nZ!sAKq){(w<8F?w0F?KCEBg(DIaSb zkJKX;0DeZ1N5~2QFh{U9ixx~z)wOE@8{O&2861h2DDbQgvBK$L2<|MZijNR%;NQ8u zi=%en8q=%n|Iu^SaY7>-FxDn;SoT0TzRjHBz}U$Lp=>tDSGt}?$c}L)2K(-pkws+y=y5T3(N{8Zi?mEP8$V*$`jYsp#wD&B=e%)8hAht|Bpi_qb{ zEx=Bx7QM=kxxb@`**``RsOV8CO>Nf;=FR|A)6-U&F7O)fOlUA#Pk$S_L3!8o z;Vp)?2Lnb7dSj1&V@I60S1%2PYmVKc6(SgYA+M=udH-j@#XFK`>JZp{hQA!r-FF$C?*Rlfeh1^@_a-^LU zh}0W#U^RAnxrt*;%nC^?O;!{*j4GMO|e&MScWP0}wg}bHo~>4tj!60P2Xi z5(TJ>GU|5V=gS)X{6vLIPkKI8=LJgYWDnf(V~>fOl594-p7Z!lJ%a41p-){)%57SK zFc3N4kyf#bRRq@}_`OpW!ROZ-x&eeN0X&Bhg5<}F-{mq()SU`qC7EKA_+FjmqTbS+ zZGm=-@Dvo{>Lsi_gp@QfBY{1V8>exVaPy| z$Sci?_h#vvv+e znvYh;sR31I0lYYP4A=Os$7pN!;l{GM=fk~;&=jB5rQWTqB(^;9>Y2_bzku$9Y-La0 zE;pj+1(=_)pbre625mkJn~%3XQsRzr1#XxVAf-<@;kzg)D%OmtnKliDxSk921QG(# zj9`bp0wS^LiwhdY)k z2T4w{QnM2i7SW245A=_t!frhRmQW<=_1QU z=zswAOZS=!K0dN3aoswVZ}pUz~2 z?1T6Z_^0=b<%2F!EV6at5ot8GtQYky1&^y?IP5>A@1GuS%xzgi&nHg(M8O{2|35EP zY4kxf@N}nD4~$l~8}v62E}r0g0GsskWK}2ioL)K#y8Ura^6(@qDZ?mhAu`?M9Y4cq zJexTjJPxRG0g^M;cBnJha}DZQm_GP0iYm3y8(w#eNZT&s`Ly}1v$d@ITf0@#2%htc zkDjC2o_AXfmy=SQ-2>l{NQRNtc4Dy9hc%D@;y0m?Uq;z))h75Ks{Oiw6Ge2BeF2g0 zmhhED6QKy~`RKabo08_F_)z5R}zVsCeumMSb8mWjG+Y5&*32a8N+9KRxdzM^x}RPS@gT#B!B964M@o2 zN`0~Y&geo(4nT)#`Yz%)t|fQyEYVX{yRhP`jf{@&LBR2$>-TREH3Ya-2*RSFc25T4TQwqjgw5%TpJmf6z^S2=5waSH*J-VMgmvklQ2Huj7?zC>ln zpKV1;wi19&ZvOv_80-B{Uz(Fd3_Ne#U!Zqb_hY6Mmc`&Fwg+UU$Xk{3n?4ri)tdf3 z1eLNa_vw`}Px5mpC8e7+BSUMfMKfjV^VZLkEcZAYvsgS$Q&xxmGt9^{4J3By ztjq>h-kYiyI}?4hdM!;;juDg)@4!X!4Sc z2sOB))Yu7{+sdKdJjwUR$tkg}%4Un%;iO!)N4*{JmTEb;SK0IS@_*)blYRJD*Y}jx@d#*;#jMHp&es!UD^Id<0pVQ z>_-(wl8^8|_{&tK*}$J>{J3wLh+AhlNl~8>%6=%WIiL} z5B0ki5ZteiB_8_eyw0k!<-ymvMoMfELF)G&{-7GTJsGr+w!7Q5MTjK_ZJd`~fk%i~qxGe98Io z!c>d6?-!WRGB&|G{}z*<*?fC83#c6lmGt+u?=q15B~}d&x+L}9)O($mbfoe@Rnu_<()+^b$UUS5gZSCt$XNXf%J z9xUHGyKo&|l{BmR!P_{GtNKQiLzm6ji1@qKv&OGEFR;beCl8S1Kw z>`Q?FoL&z-M05H@Nw_Lbffe^@Zj?!ZAKXE`;(J?KUEoI5{ zxxWjEjy{(RUxjb@xmW7&!qwZI`76-{zDPB(L}P% z?0d=a;Xt-6KfP1x<0n?)3vdKTzPBg6q7vz;qRJG*r7%Ff)8OK~KfpAB#=$uqlO0g_=e>Bk1$ z^g~QkRsN1@V>PiUicaGm_21cWf3Kjq+9|xoXT7q?bS4ntJvDA?7et3H_)NN3Speq; z2_|tED-gerTtu=T5f1JnwC$1aUYkUW4|Fi*S_`?L?k zC!{$nNZ^iT{4ao0G70{Zx@@)y}ljZ)~ zc`n2RM*IDP-4wHEi^`m$mK`JLA9XP5xSjQC~H2`+F58_i1|c1tOlmRqQ^c<7fmFV(XMM53qT#}H z-KL)B@Pt^D*rrGY>DkH4(V{QYHN76!g*0fE5fzfYT90s-wKV_TJmfrfcl|7t89{T? zHETMLj@l=2Jqm$Sodm1}q6m^@QKUVaRdEJ)|GZP|X4+|X7=Yqn&_#3tAHjz8zlLuT z@MlI0Oc+YIxYUwmfl29$qXCw&Od%){Pf@r|%!oHg_nlMz-a_A6S{3=;@h8*Vt&UNu z_Z`{4Ji;Em6endKrg%dl#J_2A;0)N$&-xpcC43MQ?s3xJslA^>xIOJ1awtdL?lPUu zInOn^npq&NG=9r;8*4@AS|p$P$!jY%4MS19ttLIYChr8{DVZ=+vf&zCe@b38g8*CqV^w%n^7`R^l@Cpl>NCHAkYbybbB!4wIKV zC1XW~J3N<|;r6zfW!~+D64{f8DRpO_U`wI=ZVn0r2Yosy)ExTfptK1=-yVeDzQg<( zN{O;6nZ({kqiZ-R0p2s2Znex0%o!~vnWba+97y!(-56G9^EU@)-DErL$(|y=Vt-bD z4>589X=wOH9%j*?3IV9qAZQF~kwQ?pUzy-JX6zuXxA?rA-`^i()NwvB-Ql;ZIf#&B znX`E#y@PfxOh~VKV9Md9(jEd&o+&Di@m+V`(i}wktl!1iE`K6DVs`%a-vir%jIVOX zCng*gyv_~4qz>^a7>VNtqdOFqTy?`YX56SwEx0%nKF8+UAm5!hnW&ck0W4l#Lm zx|N|Dv=&>v7@{$$-0t+L0~vTwWTrKy5MOrw&>8WDYBMr3eLKn!l#0_SIft;HKd!YF zGp^zn?bGLbX;ob%ureH$!zLAvy8K((*>1Fw(hWb6rFaKDIduvOe53ath8Xkj*J*f4 z<_xIQUtr4Q0(1_ed|$QBmVb4NoyP0T-YMazzp#@Ld$Rh5c2DNqynE-@9_{5YdX06C z>BmWpAMtP+;?T0bT8Q{$45JtdW%-c=vECEUCHsa)n~^GL7~rP%UZSPod!tHtR^HTj zPw}#5+7Wgdq%>vw`a1H9L11yU^8x~!x6wZFk&Mfc`zw6R;!yTtQer{$bYHyfwsBXPnI`YMJJFQ+S*iq=zZ75+Wv8ig}zZFTwZ&1cr;JxCrb>Gk~Qg^abr_;|tei9fv7 z*3^e_4XDsD`2)YecyjPzWTx+YCz#(Cd$94p9s(`0&qDtUprd@B4?81>2F=INO)ES7|t8)L~nRmJ*4BJmEg8E?Dd z_@Y-c$qi-Yh1v}bfOZm9tLrE8IKkc%rwjCPzAqACAH5D6%K>31lh)w zY{Sr>a8POWTaNDt7L5HrH7g(l$jAr&q;GLE0B1!E_gvgB{?mSwsx9=w0(8Ll8h(9f zWn&aJuJnYgJc;>PYeP`hboAQ#XANEJ?U5Mx-Up!jABM7m{(Vw=2j zMm#R{Ohsg5TF^)mn-FJ)MNcgD+uFPxBxO!C0}!~V(UtgT>gSrii~=@IxI@*X^fAgC z{~hJg8PEzrTtfQz#szN`nd0^b&~_M1;(!B;*@T3|yj3M9#jHcwRj)5)Y1g!4DD4+#uT(D9}o%J#Yr zD9mmIvo(RBf0^(>9imHoQMyt+ws^MG{-$<%duV@v+3yrhM!dKMmrn2f+Fej(Ce1k) z2O&NP>*n>{mZb(`@dJTI%K2@Fo<6y}UIfRWk;UHbsON&Z6z_G2Y(;+S>H|y;)uOcE zU~~_oByF0?d?4+Xkfa}r3cRcT9PcbR0dQU*Hul6)NFY0vechrTOnrgX6^_f@DPg$y zUE3)3R$VKBoH%l*NUU+RbwmZ8pZ#{9>CpNvEwvy& z9W4I)tw*Hvh6MKl`)&K0i$N`D;V2jHTVWiNh5Kmw;JBU7ln_e=T~&d zcce{ghU3h11Y^75gJIj+hj(UIoTDm#>3d0T4c=o#R#YfAJu-jax_pL!*8!MlAlFs6 zYf{4JO*q(FY+ZCG&gplSfT~QJmniSddTp{G{nIeJ!+O5=+i3hy?7`W4QbB$g2o@Q! z$L5yIf6j?dq6CO7v0zl9nD}@jQu5YaFOU^?7IMaVF-A^T!N=>)h6mX#1S4UoeuUT$8yonUhJZ7z4jmE{zu+_J%fOWZngNyhpYOg) zcG`ujw+I^F0&XbY_&g8}e1)aTp{Au7usxq&Wq(x!{$aQyY!L%EmQh0w|Q?!!*E?A1tn zWfzz_!_ZA*1EI5D$2qHVc#xFkT~^yY5TgLkzPj>)gwq=Ijfi-1p`ySgvsQtBpvuglMJBCtZw!e_-P?|Acq7h zO&vgICf+B-OBsu;$kM{W-tQ2vmiE}usf3f5IT&jyEc)!7M0fD%6aO26Ritw0olKf? z?(W`@2l0v4*+;|qS6684Am+&AX(Z4>dFW`GzL>cPu7{BcR5l)Xy4YM7%V&n4%JUX6 z`OXyeM*}QXPZaEU(|%~y2tm};SZ2Px{jvwPjIS2`Cyckya&4erB5y1NgMwAR&G#my z^*J5tiq!`ZjQm5*Q#rX;FW+R9e<+v3)9)s5C{P*uMAM4d0^UjE23<+yT1sF9_}=U_ z{q%pnH(f_Rp7@pmzSW<$saO<|H3ZQsk=J_&hbI&A9-KEojG|KnjUT(gbPPA6<9R{d z4e6<{*InMEmT@K$6Cw{lUp#&(b&dv&+E|JHd$NiuiOxWG@x2kHA^h zJ&G`%;+p-H`J(rs6@pgG#j{zvb93j^3x7U7zF7(ZLvk+LfbDLErev`f%y8aJ?pRx1 zN1RH<;pM3|E@D;b){;)M}&Y_P$C1=0ofqB>gPWcJ6zJ=)Isc3O!AAj z)V5zYsmqx@_=HI8eDQhZ$oIwnc+^$|i`{XBmEv4?r{zxf#3Kt46BD_w7D2Qq-5M%} zJ5JtLt6!oW7ZHA1QGQ+~$80?A!20*NfHvdEJz+c_{Aaki=tjGBxoH8RK%Vv}cSMJH zO)q$W$H@YU3oQTOaq@!fe~P)H%ObCtxwq#U>m;o7+Gh+dhyd+>kig~&^1}{GS9*AXz+lC~kR1~MLZdw4P z3;$HMly}XF)G%m?(pVl-ZhG$2vN^+jdW&(kkq5>ZJZ#Ez<&-|b;Xv^PyX@@P>pLh= zeLq4Lvw4I$0sp`p3p6@C0*zL{2)cqcD<<>``B)00ZVH>5q=~nyX}9T`B`i{P2P9*{yY|jak~-7n+~mvzqc_-MmkKiU6bi`2Qyc7JCx&T2{6z6pQAi*5y`l zxuuV_2c@V&=LZ;Vh2nS89Yp&ha#%g|ES-FI2|~AD=UXkfuq%W}<4%mBbedpZf#bch z|74u(I|t~Mx$T*18i9*ND3Muwm9l{SuF#Cn9~s}T1hb%6U{#ZdwuZ?sZ5{hLaXhGW4k+)% z;LBsh+IRB$b4NEd@rHJd$tIH)GzD)|Fh1R>5x)KymbxzHEkb@EM!7);S=qhA^q`gG z{#eZZM^;LZ@@4L-W3_IxyPHi~YX81fQt}ieSGdk`zo!oCnVbWClta#5P6J)a^fN1Qp8M;v)EjgwvE)Hwka%no4&OiI41xN;b;&x$FvipiS zO0+Xdvq$8qv4ziMH?-Wg^KMz;GrKGWR1-Qh&_W_J=PgDCvwVLY>Jw{>zrP zdDD@=Na~0~cdkPz`TIUkP3igYKV{U=_nprYfg7Y};_A@76Y*|(iMo% z85(9wc;<=@lGHpY71)k~u1gYY{ZNmCJ4_VSX($ytj@{w)Q&T>Oz@+UAyvEsgilTG+ zxtp7d?f&MowM=T|x;Be9?KmHo_I$YUms|RGBFH|IbgiuxX?fBen%`(K%JbE6fg7X^ z^pl*3|CU!>g#M7SJW+K>e6(fzzinB6DmXz}reS{~KYHo=r=~S9$O}*PT69v0$p)c4 zuhln_pwh8>p`dk{3a#2)wQDa~b2Xyw-oo6?Yw2#b%-yk7K4=&C!YUsUv2h~t>~t{N z8u*k+OMiQ^^s->0v)Bt)MOfH-FbS7|gGIbGj%E2gp<0oV_+sk|&-Y@Hi49~j=W=pI z`7N!HWEHH;bQLUBy^KdHP490iZTgh#^ruyM77$AgdfJC4#^Ogs4lyuX_lXuy z4Fv3*MN0R0>?ZAbQe&;2_I1yw$_un}wAVgdrHicSyhiSp#YCPg5D3CM+h52S@p8OW zabjTNVmxvr8j=!ktZBH&k(8wj?dePXm}dTqwJL)_H(7H-F}5gQ7_Nul;588F4eL^i zeZ0#zB7dd-5PSj;N-lw*kseP=xkQ7lM57XNJ@suAnE*ND_GCL17yaoe|GwV3v&3#v z2N{=fSjgH%qZHp(-@+~XPzyNa^_eW?ye8$g6tlDy$aGiPZQS~3x()#NYI1zhxo&FZ zaOLA-`cYz={jCFOR>G$~M9-`DSWGEmcgJF2Ig&R~pF6#^i>D93aq%=*ja`p@5vQns z!>^sQn7F){8?NVk*MlVOat67KI`s-E$#z+xf!d-q9X}2&d1`GA+)1>VH-fY#^gIJk!hATVTdZ#47K1FbmyoF7 zqR;6o&FNpOTRXOvken~YLV75~v^K`H1s zb^ycQFzwWz2L&-6kE%e0Tj+g99US|zew8(@M~PO7NyG6Of_bmKpRXb;U2Tjr$S@8k z0fi@1V*4iy&Y@IDdlMoK27%#$Ww(QYzYEcUd$I~4NcAV zj#8ej@0@xm0mGp^tnbs83-QHLBA!_E855ZvY+Z$=PrJ?(sWMp4REd$!7pt=jk_aGs zGi^bzq$94kplpYvx05h9c%O|-aLJrVeCcm_0gHe#HFki*zZnt|=JNi@W*>rv?(3pI z7uzI93U2pSBrsunKTOFppez530Q;oZ1x!;jF`$NC&%Jg%^D#6Izyil5*81Re-nbpif_(cZK% z{H*-+>1Y`S`kkYnwZwZ>gE>~#ZTNs|8WG>ByfIiU_*uX1&w6^}@zPId<5eJYX$pCq z>11wiWKk*HLi!9SqdzOeX;rMUVvfcvK|YbB%)gyN9+>^h{2Lqe9IDcpQsr=d`l z2)I@lurp7u#j{A`Ep$?~`DG`8dG(bn^i}ZT>sQe=OE>jU1*6m~(Z@f0xldP%WlDcC zkH@Kc=w`TFXQu;I(D$G;;y3hNm1M5*T@NnNPbjZ>)$E*iszw&wS6=Tg@w8{-tCPgF z^RIJ+H68J1{CEzdS+@E@*OZm|z$1_2wYn@ye^6I_w_p-Qc6hO#;S;lVK&F3jy^PScg>yhP znOpps(PA|?H*CWEoRHu(wko8PIrU<(`#7>M=4&cJ_qZ_SkKewJEC8bq{`9vw9dwg+ zxriD8b;QrQUJr{3O0`=(j|-!?JulW|GYx+86klo|qPp6gp74xZ8s>7JtcDX7%096O zRUwV{E#C^=O?^7mjc&a*1{ztHxScU8j*c~G&jYxGXBQjJ<|dS8e7(Z0UHM5~L>l^q z(R@=s#g>0dr)37-WEzAtt?r*Ui6E$lBLto%V_@9(_f)~LzCp;i@UHGLhRW+8=!SrY zkMJc8C|Gqz;8Aqq&Fe>Hqip+9Wpru&=qWrV8)}~uJX&=~Kkt&1-|oZ3Q%cdrBxQ=l zG{!tI;cs?5Bp*g0pEg^N9rysVm7uN=mXXI+n<47$+o$<;md)%ntY>Ry5aCRpg)v-Q z@2i%Qe9>gNd}mTY_i>1#Rq`Kyt_|+vKi76b`UR-ZRGi{`mjFtcl|Tbv+PdFLuA0!Q z6@nUBd9U4QA)uQ2C7NU~c1j&YgJa5PF{Q0d3x26WP8>r?@M%R{!YvqnZ@XWCRSU8F z9xhovN_jG&;kYd1>xlzx68)~Ht6BB}jQwcN%6r{22{1c{FO=xya!k04`$gp_AXEs0 z%D3sFsFf3e7mZ(zm=P|}*(s#xD{T$N?bEm&Ps0Rv*ib9uLfL#*yS0@(GFffNa zB5Sv5WNDpTnk>Y zZ9!n%P%3?5kH(G0{Eu-L3T+*(^b{y$K{D&9%{#U5-Xy?qM-%gh9sQnha*HR-7=muO z;T-OtM;-|EFqs$X`uv9J6fYS+DE}n4g*wnH9{6mS;sRblB5>bZr=`G}wLWs=?l zcDE%WrPNcn*)_=iuGQdjly(LGCW$kizvVrTlFsYqRmEk-mC9Plp$fMgmMX zCzmY4bj~h#`_(NO)?r9Py)5Hm5|9IZRZm3IcJY8Ajo7=a({HWYIX-I;Q5pnsGB%h~ z`XRJSby&{4f5|3U2~)PBvyl>s#mTI5aYA+5NWD%{f;#6~d5lLb9)?l5> z+fk!Ptxa7*;MYVg5+jh&sxt4{{%*~%xd|jVX_a!}zkPbU@dI2ZYAV0S+3)p*);U#&SXgozQOZug4QA*SAz=&@yCeG_R;a{PhO)7&hrlXZt?L`<_r{6z*U?8kEF8 z1~uvtW0;YN!=kHG?*N_{!*Ir{Xi&>&R4`&Oxzuzcn9VD*KcrJ6F>+s%E4aM^z3x)+ zi1|zw8>KYT!e7jDq@cU0>T^L3*!ajo9hh@ci!6nYJ_W=z`R(=iwVNh z7S=Y9TvK$7p#*)SyTL-uvNdF4C6gOi2G997MPgq&qm%N#kbHKo{unH8MgMk78!sfm zZ$}0@S-KnEt_LJPBrrf}7;8DgRupFhrS(7|D;baD2A8Uurag}ZGSgaIBv@Ebo*zTs z3WJnMv$*xtw)DqIrvS|UbR`9F>vWkWE`WyC?dHEC*vKBdYo?AG+gY9H&3*RCiET39 z2P+)zDo0g0Ts{Mbc3cA&3NFbOv*PCh4Yz|ERpVp$`Re<(cN%>gW4Mhql*A!XkXUh% zXWv~f{(Z9afZ(!4p`9Y@IcvcI;*MG^sa(eVxA3P3DjU?iu&C^Fq?zjr)Z9g4nzFCk z!ra|24#-}AWR3)_Ku5Y@!v95?PRsk$2FI2N<;j=A8R>0@UN0jl+ET^cICKT;nP9kN z4<&wtt#Ue6RA#3W+T`n90>5;W)X%K=c$H57;Erb4LQuNQQKT?2kp1x>7j3PY$|5yb z6Sg+bA3`{db5~>&LXpVzMZOV>qlF=ChisKm$(e14RjDJhLL2(zYIaraGi|j6f`+QR zHO=_zM0$i0s?|%g(6XLclLQ(4Vv#LuJF%y@nzp?YgA)o4snQd%thL# zEC!8yONwZO2#qBvK#&Yls(b&RAer>feHz7l^*Con#AS{Eu>KGq1_oy7TOblV0>Y9* z5ZcZ)aqKN0(lEK&I-Pg?=wgZ-t!{#Cs?k{%v3r;sN>!T~#*4<%zG>6V`pPfwP+kgmV_0e7@of1Aj}KO;?e z<|x7Q)C+YmsW;~?N;1?CFM7p7(9%O^DWYu;r^YrT@wBr`2*Lt<>~V!HwV1~z$@&i> zs)8#FM8eHhFV_{8g+(O{84yhlwL8)r({2&p8f>&@VJ@Lh zHW5B?+Yw)#ZqpnX5h!;?i0GNb2SaJQeGQ>~#fkhYYNasSj3UxvGdRnu^!g~^r1Q5B z1Om7>Owui#fX92&|M%Wt3)lPQ7=SEkI}inRWtvVnpU9Wb5e>zBIlST5i!-qF$}2)) zs5FbIvUU=gF(XA(lTw98OdJ`q>I6GSgPlndJid0hsmi`wnrSm!;Hr?|66MQ?;IuEU zfQWqWN0tlyc?m{hn+} zL5ik@E4=b~IH$Gavpyrbgxsf$FCw5hjq3#kCrO`!YM&>l2MME0o0;#t<(wewmvvIf zKvj?@z0z}ack)_!rO`;A#xC8@$#keCX0q95g_4Ox5Cmd3>zgGk95Vjqoo)v8vgs)% z!)+AaD8MrMmU8s!9vv9n>FBqs*jBYgRXp85zoCmpQh*(}J+`6MlH|8Mnh+o&1l zu*qzLAy6^~gL#or3c|qfMAnDXa#p6bB+`CDncZU%75b(iA z0JahTl5oA%f_FU=ELa;Xs4S?;rs@Bv+U$&@6oV1(+vpyqNjx)2C8$+pyRbdxIIhh3 zV{}yEy1w)-;3X?7I>^jLBqb%CzO~*#S|-8?XB^j?Nd{^a)-E}Q{d!sE>7sue_k>cq zJI7N%(EaF=`OF+jN}jlDcf9M5k90&ZNKNWBz@~Y6PVwUbvR}U})qUUS|9!PDp3O9( zeoelFJ5fC7=7Nn}i_35K+)9{4-SJ%UAuN2)=EqI{Y)dPl?I=`Un6nvDZ zqD69+a5hJ2EgnO1uHH^ZWQumSQ8VffSpCp&nbPEB`H{+pAM^pnK|sef|BWxvVYPBYP!bR1afQk!FrdN4`vk#od{4XFr;2sFaQ3 za1Xk4);*aT;-_jgtqCY{|j zJs8;7(6y{Cc``|aifz?qf@UWCIpH)p;ItV_c#7QS47OBAwLR5h6=<~K`nZ*CW@Zm|F_Y%{SdMQgDtK=i93+N8!R%YTn>O1XZKbV5VE?;Q^Qp&r){NsR{eVG0Ybr>m5QR?gV6GxPUt@rB%%=j8wQC^d|#^dM^uC?5(P3((C8#OQ0#&5T!y?`TFH^f%jewY21!hOQt*Rsa8tUExUo>tM1Cwgl~-7IR{b-3 zad~Fl_f?wz*Eh$6CHlM*GzsQhOSJ2vXliDx&mtL*)`kXFTr>4p^zWbAicc#omSWF3 z2#7iT@Msau$d8aRV>Q5jRG+1?ZOgikPqO?M^+-A2 z@RkOM&(UTK64e`1vXELQt7}xWjbZ>3GmeiDTT*XI5p00Jnh7>FogL1_`ZM`@?frT|DWCoe zba%u7uO{;vQzR3Pl$Kni3AwT$+@dk4$r1I`X{G>(j>+ zV@mIzr}{z25@?3#hwBwZ6Y;rZ0_CMG+Lb^+YYs~44-{!QUo)^%D3!hmH||30=9R!G z!y3(|nUc;=RU-#6Ude8IL2W$VrTanl*K(?i$@mk88R`QR1-H50Uov;z2$7%gk;Q@V zvocBh>FP`@Kb8Gz$`jBqC_#=T9-A&RZ2?=xzS-B7c3fonh)1?r{&w}Gl|oxLm&de< z*#QbiK=vaXK=4l82|>x+&jM^8B}c4%2BoPHmLZuTXz(?x^5s2@sZ z_T9fEpX8=7YCmZ-8Tjz9Gin6X3g+q^pfsyZe>=Qv>z;kX=ZhEb_sZ_j{OL6MB=Ow) z{OJ{~kB1%K{3m>(@%;VmV@64FFfjZc!Y7y^TciS8 ze6%#TkFa_!#hKBrMkiB<0ukUgi8qKQXQ$4t+!NC;Kowc6c5{C|(vPO_}k)!oP-o znkJVZDD3|o)P*C#@-RdbM(tW;uubdfGP21_FUS*>yq*j`a+UBG;a{n=5$=mrD|Ixb z+ehAgP(uH?X+uHA@78GRUlc`o9{W zI13;}0}eNOF!~f<+>-s0`hX*qP0#k7HhU*$VPfK^u$>xw(4n60vzPP75yTR#=bXnOe4k^9EI$pyb@Cmstgi8H57q;!TsA^z;-X&vef+ zI%TvS&CBD{`Goy={OFhehMp#nDcsur4++BgpZd@;elFOs5$gE6AK^2~fB8{l6DKz~ z9tXjKaXk!+QTkKfR9Vd@9my94C#1*osfZ{X6&N4Wk#*h_CHsNXA^&63!_VhlRY2AQ%k_Zo)v1T88g`$HOyzBx_(}($ z=W~2tnBBysyVfZQLV`*mbOr-TE8CTp0P+GMLPjxVKDz=ZLJAZcDYShJkhp;{ox@PPTVKJrhA zkH>G9Brxy9|CbiP1K<0=_8D**Q_`}B6{~_(f{!XMi33FSnwiud#s;972v3j|9qsuPfYVpE2 zkcO-fRkuDE!*Jym8~B8~8CRmf=yI=X%Va51vl?!N5{grAaQdso))*xP=NF?-YFHLSW1gsKmSwx>s*?1-hBXf zd*iv$$SEk?ghYan+avHe>WR$se;O|qUw)%o+zhpx}s0MG`us!z&C{yDW!3ImXz6ntRpra=f~F*pi05tuwVgpPe4%1rS>8j zp2Mq`>9lW`w+^ou!Z5#q*7^~Ob1Sl;ZJy%HoIa~W{tkb!_vaJvKQSa3P)LGy5PW5| zh!f)*Tjf6qimp%W-_?&Op{@K3Z@|y@%Mkrw17&TQWKJm@qY6@wiJ7l-_LrRH(;O!1 zHIR72%WiSsd1^a@JlzIQC*!y~b0LD$HBS2sjK}3TCBH~X!*0Tp6vA%y-9~u=b`;ob zAYjT4zD=)h?NpyaM~@`pi6189Ij$TrOgX^> z?zQf~jk5ZY@rn88Uaezzoi@+`cNYk>WREf5`};dw9+~7y-ZzI5 zDkU0k(0^Ux8SaH3*9AUJrL zp!#T4qyNWs{a4+XOR_Ra6u`H_7!T0(XFir4h;ByfZ!>e9SM_PFHQM!yZE#?w%A^Qw zJOx5+IlOP=jaX`AKBUvc3f*{%57Bts{&^*hwxoNU$TiqlLkk89ZGY9bBbBI?;-eDs z#9U|vTTj*O+4$kgyXkT<@JQqhgdE7f&rb67>Mye}ogPa#>1>RF!~`r1rQr7l_(x{1 z{U2r&?BVinayusHecO^}!iAt3DeU*q3j{L%zvam^@R zn8H?{C@0Lc@2BXyux`=~&wrN0MTkk)fnIO7egsrd@_+lKlkF)q03@&+s{+fypEA*R z;`L8g6FmE_S}>k9s%4H}1&y_ED3YW>LVD|pfGe44aIC~OMi&fqA~`l9@;2HDcm z)aQF1zOE6`R@Yk0hbH(1I2Kv=xY3yqNFok~Kppl%#b~aL(Wz1&Onutxm z=MOt~a-pB^UMQ7I#o~89HV~J->SC>;k}zk`x%ZinhL-a)Zj}xC&pSQb>;71oV`_D3)AE z_=LV(j%}Ln%Jqds?Gu;2lb(atT)bE%yx|caGm)Uoi~Tt_aTdT)>-z3>e53@Q;%%Qn zt~?3ePXm<-eW3)f+retGq_S=vCm4f(7UY10EX|CXRiw^a-w)H@od#%CaCY>nhD{Ei zUmO}Wfdzj0#Ew1fcNt(q6gDV#Z-%hX?^m?9MSW?~efO<8%V`ZtlHe0${uB)Dee0nz z_5miu*UdvrSCS@1i@sYqeh>A_9iDp8CYXm39LO5F;%Ve}&KayHo%QueF$Zw%{9pxy z+~XErSbtCiX>TQ1FRJSb?Ek@mQc8b_=;eVyUx=k}*<8FZebs-9 zHh*n^ZK{3+f6EZEJ$Mj6jU1DHvdMXtT?m?(gqOhf5{Z1d{v9$VxNA6s^R|iKUgb}`nGSI4Mr!6#7LlpaN1=fUc&BxyMh(tv@Br9jlwp#< zX`v*ca?|R=z~X250YX^sfU`B=w?v?IBgUqgNGN05c`;PN+|-4I2zZh~8?YIL(3^c1 zZ=_HuysiN3zp@W}cyN+5y#hMc0Hw9f-@QPsy_0c&W@YX4Od@!) zJ6TKyTzdF_yYyrO%D*#LOfvhOX|{(DE&1H-$Qb;O?Zjr&c;fwE@nh{0gRWd0>hGc)wk-u(M>Sk>JFdUD&Ha6mo98W)z$ctx56SiL0ILo*VSz=VmH(H;8 zMc7d`iB0A3(0v?oGAb8s)iUhUdCSs4Hy`x$rRIMhx?w?KL;lFW3Hp4JXS68YULMMLd znt9Xwe4j*TT-oX4HU`-0S8z)#{N@a--W)4Xq;OWbS<3K%{P|sdn4vMhnYRUD`~7_T z%8ptzzV{~qIsfCnSj~0dAcuXK)Lw%3MD$1}Hr*Y$1uJ?MOmolbd7UO!#29;8tc01p zm)WTIxfck-rZbcWvxBX^{3jDa(3li$^EZ`som>81VP|0WWCd^pXB*?6r3q|NC|bi` zQ7q1Nf7>B=iV9Mi=z>Uwz7m z!hydqrng>TTs!m$FzY0kk)t~ssPrBggva)9yB?TuWdP-zr)~>P%;1OK_NR)1PVpM` z1Q2zu2F!@Wt=|=b%sU5=UA-TeQqrEKnAEr(n=)$Ez*~thcz-D(@8$lkx7$A z0QH>_E!5=YJ55res4ieO8_g8eM%+Fn*$6q#%loRI3 zDDNk|Wthi13wio=O@&qvI^+pPNXC;CG2Ye1XQFCI5ppLlF(tFyW1@{rF{BBfJqrOF zC1%VNCCu{BF+yY)!9Vpvdl;(%1~Yhb7uu$o$I%bj$Lle zI=cmN&&Ott8y zlW5WuJlh;(>B!{&^@AGQcblC_@0d$VaIua6Vk6Y$!f ztz!Y*Sl^VZe&Y+=o+w{4J}1W06LeeBG7#0vbv;9qKlD+&)4+f61ZljkE6rGwtz-#D zg%Rr(Gn6Lx2?i;osGtPoD(g608TdgpnOYV45I|wwNWTADv-|0ITx5Qh{5TIHq9o}9 zPvbj8y&RrGZ&Gzy_t4qj>c_Fgsd4|sD#rMyxnCPl)2*zW6-Oo!Eysmng=LQ@qJbjI zE;6SS)EbBH4>f*}=w)YggQ}pb4kv_5vEV%Wu{;&U^Schz>GZ2brmw_W>|@ejPK1Np zS{QV_2Zj^z*pp5M5eP#jVz3(FTNmRN8fN>y3R3IooXRsC%46(bKOQ@rhmTEf5}JEg zF6GYdy)aH=adi@FLL|P^p33xoNI=$VA`fMqLuQD}%Ab^YZ8c=Z@9_ zWt*8aNya#ohpE$?+a`mj%`Kh?iltkEmlWT&iHbbKCh0exsO=6%tF#>6e4Aa9h7j56 z`}jn=fGL;iGL7i%6sLC}kLk0@FJ?vR<-_rx_+W`ic(exffU*`V-sB~r7S_ie#vYHf=Ef&nn{-RIxz)oMpmV5afS?dy)f1`YCgO^c zju0|r1cdfCzqPH;Du!#>Ke`n>@aIX!UgeCnQEG#MWiw8P4R3Sa5pw(@{mfHw;9|3Q zt`~@!g!!DRgLWq2i3DA{OeA|iLAkhZk^v8SI_lmQ}V=Gc?{iVXe=A5b$hx_AtW<& zuah&9%eF{`LAnGHNkO_p1OXA1QV^vZqFKz=3ABbT-TJ{OgNmHFO2vz3pcC;HWuu(`K4zhq^O>;Bv&&e z4;#^2KW#Ws1BBQG&zq*8W_oGN?*)k;Q+?2OS)o{Djs1hR?%W2!cOl!%PT2pi*$cTS zf%!X;h?A2;`$Orm<#_%Y6{@s3hAoW?NszoTFBw>rm)cIlhIReO$ICOngiLCsieq`} z=et-Gb{?@;@f2g&x4sQk+PJU#>|RGJ1;4S77-a&9E~f*u_&X@Al!(eI=XHNFzt?7Z zS@BScBA8D}cugfUKQ^PPNY3yXRITIWEzSuPSq&?7E^8THy%-AV1x9luf}~zI6~FRy z-lA5~#YI$ItjR9-fkY8_h2dP)^(Vo+9Xte_-Y6hgjw@9lj}RpV-9nJ}dUF;%=3pB! z%2mS#LaMHsTTyj<&$2OIJQyU@-F>ph;Ev<|&U}f;Fb7xQ3bqE>0@*W}r^wh8%IX+D zWORqmzPl&8nMn9UQI4nplHH9TfYw(vfBd@h%dX*fI~#4Zo*I+U0axTU>11ODR(WzE zc6C!wGm9(=#EwIG|hbFi#Nyk+`+_ud02id z(oBIREzLZR^w4u?_x9;$sz!U;bb)$$P@BUsis!~-Qt^RdlEYtUS$Q);o7>Q=<#(8F zqD92Xk~4Py32%D)JQM@Ym{GZ*HiDIq+<$owRMU;uv!4C7QtHn|fFv!DC#pi^c;vv=(p2OQF^4XX`ky>R|fHk$l9;sbIx00r$#xwyuu=L=L)4Ke52e0Z0Ug z{QeEhN}9muB0o7VJ>d#*78Tx%+DP+zckzzNF?mL&pQ`)gZIt6a=(fd4X-@N=^{%?V zKElrhaT%fNS%v;D6!^iKrXiol-$HEtGImv&tCaKCA4Uk=@r^;yQh<%xMA@;hd_WS` z*8~a$o1{o7-!A+%7&c1Q zOQpRd;Scqgk7j&xDGt|$J``ILRuJDPILtK_X6++Uc6bkDk*>(coi}~ANd?K7I?vjO zWe+?DOtw{T8wGJQdv5+vqL%QU5H|>2L24D30BX-AC?g&inWu0&(U6idN1I3dA**ZR z3YmAgoAnp?o7Y^{xWh>Je#h zia}a!R-aXw^zLKTJ-hn-tLtyBh29%SXYhBz^$?wI#HK7DC={FWqkWkf%N#&TdjB(& zPCie5>ZL?3@N<5RWjwcl%zRSve`MyD227aCtfsjC%=fsxxfLjk) z{(yqvI6Q1;3;39?yq5hzV%%-?Rq&kDS2_X)8TrAc>pw1L`Kq8r|_4F%pxMqKa|IOA@;Z?;mE=8_|nl zPf9*bgRo+UvMuR+7FLj1|C4rS=En5XofNmn(Sk$Jz*nrP9V_7D>8&-XpGx-vIaWFO z@a#)n6+)QW_s}A;SZB3!s2(yvE+QQ|YzadR!^+CuZ$Zy63${r~x7s*HL1XfQLnswg z{-L6hvJ~oHxqESJ6!lQ$_>eKjFxWERZfL*7P*i_AQ+@Y)9_y@2-5LIR5dNP`p~!r^ znss-W4KckIQb(rOk7h`hcXC8Bn859by5X<4Vr8xsxF#I!RF?nUfs_XmxooMII;ALy z3fjf|k~z%JpseQ4jmzNS=O^9YoU61aoMlU2$r6BaF8Iaqn|mtX+B7q~?JZ@h@NXNx z(Tm(w2oTBGpoqto&f* zg*e?4GXBWhx)nDiTT0w{k?D$a&Qb<8iy1_G=Nsnh1owpymiNZ4k?N=OIU@SCS}Lk} z*Ux?oWfpUb@4KcqTg(X;?PaBC&jnwzB~;_BmabxGUZDR&^Wq(qdWLBE)rJ#D7#?GQ z8|wrCf?67*7VChIsUt1*k!HHq>aKh`Lc-)$!yg7L%fF@2w^_p(FBRuF0u5wfBj+PF z3B4FgzrtGO@>HTNAxW<|r^gd6qb6z)-+7$!)jLxhnS%_2k;(Poj0T=O_mX-p`stIM zOvE$TWB+@4V$$``ZJ%J!=hw=E@llAi)j`N9&LygKe}e?b$GbrbvP+4I27RV48fk`nKVvI3*1x!pKuY;Uhz-n8DPm0OfNPk5iNwy7XFW@c@9$79}Wo#kpy0`!_K1a z)Cru?3=*RWHMVa+TPnODIet)HJSx6(i)%^`=LPXe*p*x2VLbTAW%Ip4?+c$PLY^Ln z6(5GO(0j;;fYjKB2(cCoeS@-BWN*Eb;acFQi=8I`N z)E$nlVuSBhtRD&uZf&pr^y|blz4x5aoM^o^!(2DL?;15Y^6zguK3-%Lb89~Qe3=?S zpC8H{3cm&UBqjJ($5)S)g^ONHC>*T`X4pGgUUI@uwR@xT0Co2jzHerfQB8b?kUNwy z5Qva8e=(i~B22`9;J;@BBUvI5Y!~>;8dmzv+vkoOhUB@X96? zF>%{0KYG&<%AQSnj8n|1C)ePI9@;lg!X%1yKH9_WDoLvUgR>K!h35w}P@01d zu-%{N_?txIYt4!yH5qVx`~|!-(jF(W0E5Dg*WQr#`4*8-Z;>T2ug@k|57R)+$I3X2P@J*t-*G0 zpV3_-ovqkuPuvkO#~OAxsePo&yUqAbQ*2=ri(`xs9`nDDIiY*P-bb$BxT5sf046s6 zT?wW9oWnB|x(Ez`mxOV=g_=I&j4yGDgBvsVb5)hR5IHj1^0}@#qCIw=bC|?y*x>3n zX6S(j9E5Kx8Q07(p5kgc6FAJQf2Pm>NN%yoeib!$8l&RjPgNh}=Trsl-MN;|u_TlC zKj+bo#G7DibeaQGqL)!=jtA_0cK#3CnRp{vBOClfE=*HP-_4QNr{KAt_u7o=9SPN3 z@TOH%mSia5%i9z&me*b}L-rsYx!Iur*#jNrY{wZ9rOc@3KL;!I`#x7$kw62tYkYZ8 z1c~-i-arQWlv`bmZ|*RHgY*8!7YCDSJcd^O`kvO#{$@B?Dud?abvT(-n`|gQ@L8?U z=CaM9pV0{$9QQ{7R`Z2t^Vq=Aw=wWpHkWgwXH<;Ew-WV{C@&KkzoX5ytBUF6HMbTs zcV1!EVsD5bDxrKiq+cP%RaI`vD*xm%Rb%S@zP1+a@q3lQ@n?S&+e&l4l}+m@XXmEPVlspt{=?(7hyWNNThb3j+T-`icrbi79EUr&(Rf-bcTmW4-VEQP zow^WE5!vw~U*N}krqh+oq#A9ieKgSm)_vVVVmx`sQC{O;b9XPDC%s(hescjID_0Zr|eQAU2IEyFF0(cqhPjkQP5@ltvF8VBjc96tV2groRZ zk9s_fRh^cHHSYb-BLn_uT&=!H6P+((-^n|Zay{LgR4a&2MoUcgZGJ5+vjuoZDzq@U z^BPvZkQV{c!vfN1n_OH*#MnOY`_RT2-a8;#C=UkGkqid>b?n9S>Nqq9CnB z8XvyZidlNZQyV?ufj3N|aPxm8dgpq_<$DGChK-Kd`9sYe z7}N&>l5X)mx$NIi(VWKO33zfYTQWiR*A=Q|1=BjiUA^%yauTY8Atw)pY-8hH#dE_i zQDtg$dasaHrf=1>dt5eeBucuF?@wSNCE-(L&9H`kaY3m?^&h-6b}q>H>eoAS+gpRA z1bSNL2Z|3~F<)Qf?@6W~^GlerRotZW{TVqo*=Z9z^dR_jCHw#Xrlo_Ie2zAPj~)4UZw)xujMv;uarhB3c2KfJ-+7ON5`Sw&|kJ7hza;x3i4t%W+%D zUkvuTcBj?kMD16E>!R-0RtSy?%nZ8(KJ&EF+22Z>y~YR}IPL@y6O_EdzpRk#j$-WXNmq|_i~OQvQdt4nFz&t(*!!3Fe#2}qVFsB z&4=&iXEH8J-uYLhU3)wZin@^VrR%*0Gy=g9eDfS1_Y&@MNJglaXcg~b&`Wu*&gd$4 zDc_OK&P2a$Qu2#oj)_16)_t7uuJDYrw0h3!Jii)OhAAg;g+hOJ%Q=cxj0&b8XKFZ+ zCox`}Qe#ZnV;0?)xp%>XCei=*x6QXm3kDN!hn@SFGNBt3XQaz9^bH&z#u|ORZuGYK z1pavC1A@g*x}QXJXnwCwI=b1)FHfT4F1M+eIVLN!W#%6zaa|fHt71@a{!OmVEauSg z4{jw>07|n5E)*{=xqWX#C*{7QLo?^3pDd+ZHzX6lAvu2`TO2z0v3W|Uo+5tt$+3++ zdp^jii+2P+%K>_~(hW}KR3T(U_STRH3J_ z6TOfhaQxckiSJ`nw)D&G!B~pmQp&RngcN+Meo$Xke$E4*u+6i z-uONNP>t4?eD!M8+Rwb04!e3zwPhzxc+B(x%f}VtXUm%dL>pxs?BMXs3JsNtO z>LFm|h%!-gJC5g4|Lpt+GW zu7;U1VwqK;*+Xe@vr`Xq{6)2GozZLCAdhgP_zY^<1w90p2RG~>=`U8_r~f*nakznc zDsRx6GGHAExvtZ{nZ#D4$@|Gs8BQiYcm*eXQzjtc#v=|3hCGcU+0#if-xf)ihbnH7 zYLdkn5mWlbnXllD{JXN=hdv1pNDUeeQ42r*1|;OyUncY&*}A-Xdq0E~kyK!GH@(i5 z^d2j`5uf2IsQLGWujeq9-Y2xa46z%Z=~%nVLFxnag4<2r?r_@1Xpxo5=9{)`u{MZL zKYb!Q_zl~+Ufotgm3p@8Cf(IU6#2{aH`V3sm`C3;!TD%gZ2(ith?pLIV>c!JYN9SM zj25(UAaElE`Bi^v!dEOX2BUh4aSpW5of zfXP>=Och}kE!vS|y_es3pE_es%JmLuk2_hcx4=t^)wRu;vH!!jbCfUIOx3Hg`Le$L zU1q8VoC~&~_EBIsvQ>c2K4Z&Bvm5upS27b_4YB&;PI{jz8|mP-54r-8@o%(WtU1s;F|ih?sJ?VhB;k6@y0b2Wwa@skJ&_{hhjW-shi%o# zxARz$+5cbrVALlKa`yk~!)Nk&!~CMYpi;%Dq7r3Z2HO&uE*sl=S+}ahVtj_V4 zL_Sf2q6!9uWb=}8CR>)fM_o_9*$ntxQFosaItO07^ClaqTYP#Y1BlE|q7e-7VeAU2 zFq-QRNek4T_gRm;Hj#lGAaa}+MGNCa<`pE{rLDz4PC>KVyvKT}n>4<(*N=F-sJWfr zf8TSJ49oCLC%UeF39L;(EkPN6#tW#)D^@?AQ*JnXwV8TY!UQdu-AIYMCtSAmGoDl@ zO}RpcYn44n3CcdWUiIek)3gKAxiJ}N>HkoeiCf6Z%QMFIAN}p5j2G~qA;mpy}M|q9(bCZ0}uF?<8y~{o>>0e2ad|2(Z zp#oC=hYBc@7op5D(;0rj)^s2@UDy%FVU-HLWA!u=9el&GsLE^$4L)L z_b!>7S{4Qh$f*@8s5mWRs7@KySBMSsubVs{;&c@q@UoB@pdPq-x%Wbj?*f+MQ2fH3 zn-@O?K&C=a{E0h$+x%72DR6sZfR6LMvI@XLTKmSGq$NDJgY7vCnqu|IpK`eE9p9R2 z%bAea`v1f$2Vpg$!b`o!x_9ZQYQ`@FLvS}WU-dj-(|yqlw*I>P|v4rYX3&R_Jz zYv;pimwt^6C9L4?8;=Jt1&01*ZYO9SzQ-L*S8Q34T1=T?TPzTY&{259%&D;y@XT^d z+S^MvIXep(yS9`SwI;Oq2My%yYma`9mc(WBk5vMMA_c7@*Um3?R?Drv}wu zq1s-tU(6E-!P(+KPTu)3dS|3FQV}qL4#R8q&tV2^47-b)fQP>btL%Q-V&md=z|>VFNTzKH zr6MO|zG(FD^}82XOpRUYC(rP%+_M(%CY5FV0x=GK`!?F$Pw@)|YIrd>eXE$$imKl+ ziKSMa!hl%>tViAK`_&td38O~gOPTW$KKKc}WeJ51+wM=C)HbgR6qY>g>O6XF8dZ~g zFOL;d>>mb+GkFevuSM56CfY6<(SV0<1u_y%!M0H{2D@|n&MowBnV1dYFj`z8rLeA7 z5m8%y9qENOa4ugHA}4Q~Gl+lGS%Js#^|oeT2OvJg56nAAVcV)KuqlIzk3ppw_}Z@t z3%_WHJId_LNN=K8sn7Z-@%h(dqr5>&8x_GN`1go=*EYr>E;o$k zL2Zj^f5Bk89Kf!LB$`K7G0*re=x>K=BsSH^>0i_#xEXc`fdYjRu#1J>J0V5YR513! z@1JA-4B$+D6JGNi_~m9HcW2%fh1u5kh z1fV3fTAeedFG6+aBA#^9t>S#uU$m>yUE9LX`mgZn-d0=c)hW&G1Gw6%H@?d2^iCe@ z*6s$7!mgQiU`_dg^1|%r^7-o_dtfACeO{ktn_VAvvs!WG*hv|`Z$t9F(gYq)oR@SB z2jVs7N6|EevkY(fT+1M3Dn-mg0OT}!#x-Bv6^4do`nWq`juwSi}N&&&gJyU9}lYplCB zy2pjDKcp_O@UFYelxE;0v(LqSlge9U08XaHMY;gp+4%5pqA54ePWJ8JC$qy#k$z!L z;V1d8oHh}LZq1UIUMhHnB?_p@YA)oh(fOe#)v*tTk8R&H-Aj~$g)1h;)%W< zZodeM$w}|^l_Yt0;`RT@u>SY)5aSCeUyW~MTY!Jjw5dPP!%TbpzQAzFP3XEJ9wpN9 zo$it?E?y)#f3?{)=7nX4ZDA?}voF5d?iE}t4{OQ5CvzvTMcx7|r8F-hHL6iG4R{4* zcVS;_i*w?Wg%nX_{c4_DpZ*dnvNZTakm(b*ZfBKOsK3Y7h6jI6@S7W3$r*-{bq>S3 zR^4jnNhN64KOVztp$teK;UC1@9gUwrOZlEgb&*C8I#Iy2%Ox|iTKEEyhnL4`xT`1g ze7KY)D>JzIf}fS12L&S15fTDLFi}yKlbK0J%XT9Jv}-nm-urF!{jyw192_>K4wkXb zap>V?*0!^>Tf@;P5JZ0ZLWT&dQFWpp?t)+fnBuafp&$nsSu{_v7D(?;yN zGGhE+^_dQ!0uxkNczAM<`E2~?C7Fr=N06%&KTmFZ6qwY4=pUL+Et%A5itJ^H{Z3*( zDY_Heh!cKDFV^`!$n+lIfsZ58SRKzoNwny>sj3mG<-;RDMPExuMj^DzEJq3=+dr=8 zZP8b+d1U#p8b(huRpcsuVwyNv7L#zY%Umb5%Sb^HSAh@enS^v*l?=|v6{mv_{|aw2 z{#%zd{2J%j+4;$OLEv|<@jO2jLyV^p4U!kz%*0B}i_&7|$z^`^P7%6%;z0%Zp8VhE zd)G=gVEH_(fZlK{tMA+0ft+uo@#Ztk7dw4l<>;D@jv{my3qP0^kr6j~x9leh{OEaQ z6E7c}k8SxWKA&B4wi@w_vt_NS5DfzsiwP&#twVF?joo|B6v(kA>Rku~4345`GK5~W z4Qja5(uG=W#Zcjx zSIJQ`BY){ScrFbx;&7;7QBO){<~j(G;lufYC^bi_&!_Z1bQTYd6vPHODg%`h*uKN( zqxnq!xjyz+xQ_I7t<`pQzx_w9et2>?oyUw3+a0n0fexG;B9N)q=il)s7&}52u=(7w zBw;rp>_P`1{0y)^=$ve7US*Z?|WZt zU)K5skvpI(3rb_|7V#OLxq~G-FZ`JlawLLJ!Sf?lq>o+dPC_XvU6#K@)b&oEd>7vx zO}$OQ_K4@T-o$SKD09RA9wIPPo&^q!V*F*iwzeGmTOb1*EjaBt!n86Zs<^X=eDpeC z%*w9gk!MPE^yHM_yQf+#Gu{`v`7~OH(fF5oiTR6SSK)%|WTH2_VD33gsUv+C266nq zw+CE{QBi?e`b^u#a(i1gLHj-$JtF!(hm$F<2ylg{MM&sVig z!bl6lo0hcDdm;S?kW`xr$^bS-7Am_4P;Q{V78yrtgPx?$tYILv@Nj zQazoG>i2wlqd`ylLXK&V-Ak(3XpCyJGEYbYi~b=EEa0E=KD0&D;$zQ+V}Lc>X4{B( z6m1OU#ckB`?}86=l>$BsYL^ph2eM$ni(s+TV44IL%j00$xkyk}A&n1lTXC6k!-O5` zGkC_<;uY0&lOk%FC?WzxVQjHK*%m+IwQf6<8-+n*ROcV+?*hKhKvfbmv+t+IH0akn z4t>UCSZ4G-KnFK?=r81Ltf`Vg`|_P;#j=xY26fMN%xj)%dWiv9@Q1?>aWARi_%)|B zD2)*fv#Bg#AN`r22m1=a%DT(&ty4S0i}A9lZj_6Il>*X{>BLXy>|OqcqH!T2WqPJ^ zC!AKoJ0gKy+x;c?GYt0Kdp>h#=p?3C0kVf z3SMTNa@1z09DFD8i;i8-C46XEl-aED8%2&t?FVudqL(j)2+iC*py4C_ynTJpow*8w zD(GcPFZ2lCF(D?cs7d}_b)(Cv3ur?K(AdzvhK~yRaq+qH_(6VvRy!L>4TsP_c06rex9G>xw{BoL+ z36ZAh3%K+B;jTnh?bfNUjNJ##=ZB>l#u&sLRR6))M<}5M)d^gCw?4=)wZurwMjACs)12L9#Z*2Ngd_#KcFVsltg{MH$j=D6BLEs zEj6BL-h_{5U@?m*is?4}D$}P3i7%pe$w@H&r2OC zj`{o0_G4x$^dM%!tmgk+EA3jM!^VspEaa0d+G-Cbh!yv8XHc_e8j^bW?!K{(y zv=vD6!t0TAnKn)2MiV^@P97IupjuWnAj16lRU^l8TSOjwY{)+Z0S+@@gTXY&g)+x~ zVLBchG4u4*kC1s>h|30EeAq0a+2p?5xD-4!*3K0-G0OFQvrYHc8R4KGqh~>sr#ha_-8r=B7lRmf z%0I<+3#YXy8fch*e*zMu%%Bj}W~+`)Op_;Ik0Ss3`)D0y5(!IyPs@q0Kmr%paZMy^ zmTx{bb1|#RNOso^(7*eE%dMP70Z_DQV82TfY;gG8=pk6PhiC(UNRr(Rn!PRcto!T? z1_RsV>q7M0R2)V>%hKt@N}g>q8#A6`M7PUE(<32?l_<$d=|FSw{M7liNTPfj?Mx8M zooMt(9&-b(k1K4os9SjG+Ug`>5yW|YVh?0wz`wP8G`KNPc<*EYtdkYJhh7Xm10L;s1z_=@gf52i5Fvx)xeAq(Chtw~ zCeL_MIff8$N3J}c;V-}xW}tR5ZoWd(_rQ*=ebqL{b@!S#-)nj^&idobL0h(?u6L=U z{|5`CG6Qk@Hk%v-ZRX|G<0H}2P`#XhgbE?SJ7Ywjuh^b4y^SJj-XbTCF}V%L>a8#@ z`aS>-SXd=um{rzyJAshKF~bAs-B4&_3RsUjfC4NTi*mxFl!4PvJ|wkXH+uvDXA|%L zipf`hn7wr4Y9Y`X(PaNAWL*RQ6bwzpt%HirGGIaX*{Wj@U&>>=tmeOR$>RHxUbp@C z*4nydisD;ghDSpVQQo1FrtXZ=vXY$OgKudis9k_EluY@jiZ%d5)Z(5gdg-NjU;b2w zG<(MUuT6qtxV6f|@`a-w&sCZ%aDm|cqn;RP-xG1A)*@?$v-wAvbJBZV{PO>*T&EEW z>j0$`es`C{UU?5aiBw6<~E-I>ve@rbdfDMP(Hs#jc zu{T`oj*7VqS3a?xys<~!;S>q0I-LRm;R#@H^5q&-^@i zjE^o^4!2~2E<7dg1dF6k<^)TTkM|j;ZR0$r4F|z{o`>DSW!CUN8$fV-JU-$Vi1DJx z>+suHGgH|x=xGRv|K?pByYMaGY7$eP*Ubnz6Q%hs*LxgaRKHoEnOtVSIW{`H1gNC3qVmbH| zBlG9Av(*t{ToKT?Qi^L)j=^QT5=R~z5ds4lB#guf^tb)gvtDN{&I`!aAe;awUNilbyzMUz3b5tLPWuD8B-;uR^^H;M8i@-&?-cIWeg`R zDOigqPA7#Y0I5vv$2(ujVuo2@;fNy;i;ee;d;vNkT{-mQBq1oN58OORcD zsIXA6Ds*mJNd8!RttDf#_J>7ntBc z-Mw^;9np_wx`nzCOO0(NYKKhRPrj7$z4mH+DZ%%O{OOOCsFF09*qBG^;xx3Bl%Z8t zBgzt&6)5np=p?Y^oiM-(z$Th*J&)kT2;U0^{cr~7`GRHB;^Brqdx-`t{%%A>aI22Sk zex$QX8(C5)2Ut8w+YUL&;wTZUUg<}pB{0ml2O~Tdzi-~A+kCFp5`|as{^GTj57(y& z8#Z(ZyYQp(jhTCSzH`InHL$pzE?NIEtl4vhRo*ZJglvSa%kD_RC8{sa9)yxM=e;sS zU)0s1>W@G6NY_usu6yi&%=9-OXi>L7l`>uAiSk0zZYWc}WEq3AQvHU+!m;58+5WyS z)SVT`Mx|l7|CiHfLNIa*U=XPXouGz;#S-xqmoOtOi6bO_)w=|ePOqg_13p)2d)<6r zNb`&C4KsY4-Z(Lf!k22k<>os?n^2u)99cI+?Cxd<)3!mIA>rXh&Dc_a=wv>V0GVq} z*6`Gql$oM*`wRXyr}gVr)KRow?63aH8N<0uMN0@bhHClZuH22&0%LPpPaOH5-5OvXj&1h4Q7b_~o=(0nb|0 zeZe%XRU!trpiwgF}m% zf1@N>zeqDgu}L)DONoYijFxC9bbL62)7S&oW0us&InigF081#GRbpPG-tro}zi_;e zOqbw|AHPuN3l0(UyMQBJEQ1Ql43tNdGZ<$3DZh2Tm6V<#@Y*u1&$geMN*Q9ocXQmt zW|9$ISWWCRZn-f#1-m7e?MtI(TIiL;2$0g*!C@n{o-#$0vC9i}p96zWeO?dNZK5k>5-po?6dI-H0kkaAshEZVgsbg#)a{*mlw z+N!p7VBRXFG|YnVN}9w%hAE^G4ZgpMixFR?j?tpD0-r|280Hfyw9UGs$?{zK_-7WVod)wQ*#EPaB#wxKOQg3zs%8GIi*|Fsfxjng0 zfafe}ZZ%h?H&BHsVZq^Rf%^L^*=Ws01$jo>uT^0Lc*H!?zGJLRRi3jY&wb$Q*yFOD zbKwFUAVde%-#c-jyO06e8(&jK%vQ-rB2xS1Y5LoDxV%fn5VCCDv>vKy7F@?;Mv{qf%FnwisoT`8wv6q@ z+Iv!GY0;U2@bT2K)(?JQSAQ(c{d1&fF}OK>4sI*dB>!0dt_u0Pcc~#~4%RQfxzvnU zG)zcD^qt3RH+4AqV^@;O#_|i~3UwEo!~A>+t8w;@krgWo6;(75zl0g~4}+<{TztTg zRtd&1t984yzeOLx=J{xl1!ZUb+UVh;njw0-m(Toe0~Y_QS313^v!XNp?L4(#*b_XC zME);_>jFZ#2I#ot`v}@iNCIUzQPhZ{w<&KpuhoaH-^s0c*!AE zgL#m>ezKs?qG7#18p0mUWl==fEBv8VmT?wWR?o*3D(JV#!~I#DBJ|KsPkuKK?^-Y} zBvhc&|=1GWZVVllC68DjV|*eL3dyG#qgb*c@$Zb5}p5oGO~ zB;uCzo5zg>f792d>ry%;UH66~0xa+lLAi?mW$LFtrxTR_uUiCKMz=ru z1@lvob_)SqKFfpwA#9JY!rLy4iu9b4mH4=Nfd9lUth25$@-emz8594kw(Sz%siLBpP> z2fM;o6n7pvI}ycyov8ZZXdCzj^HcGYJ+msyA?dG8s?5i6A|p;heJ8K=ofqC@Da363 zV6fto0w2yC$%-TY%CfxwB63$8rwA9HvhRj@LW<7;>pi{-7*-(s-A7CJ{02&WbIfRR z#}nyj(c}DM?I>EjoRf7l36zv--eo_A=pppRb&|L!IX(^Bw*v#8Kr$_708^5wJ^FN;>(RX` zOU?XKputMLby`Reos^H$8=kSfXi&J1Wpw}I??+Pe`~A1KmvjUDW9_n>R6`-kuxpmz zI(vBy<=K!VsN}QQwrKHaeb67?J6vmy6?VLzZ-0yG4VaR{oHC<~M%A*tjRu>vy8Fgb zx=m;(rk~`n>kNrJL0i#urlUF6B;6~5hb0k(m}WmfuP_|?+?=c)Cr54wJg#@d)~2R0 zZo1?i@9&~{4p)IStp@!QJyps}YOQRP4EHG*;L3>ZG;NHYT^Yu|uZ$C$K$+D_@sAGK z#!P2EH}On31B7Dbj56Fg6^?uEdA6rH!-*pCIz`ZxO!4>almRK2oy&tY-x? z8VsR505jUI+;kZPOPqmufldC7IHc*gXZ4mn+*%~^IlmtFv{sYInnE}V#!F;Gd2JKhH&`y(9O}N3&)n^O zyVG5;wxQv@gZ;u>t)Je{2U}=HDJ7OPf`Z%-!mt~1v~E0+u_%iS@oP#Lhv)zdWNsgX z5p-^28IaB2oM^!2w@16%SoBed;+S;miU4M?c=_??uCcO<0{js~U{MrTja<*t;7iEo zEQ$qh#ATUhpNqywtFGx7!-7mr>&_|P6&l`5@#w5?^emYe*g{O-LRdA`T6-v2el9Vz z=nu<;ii0c9*pA!uX@-u731DKIvhooWexNU*G@jd0YH%7NuQ$-QID{?5mbitcX8&HY zRZ+{NjRcX-NpnA0`m5ACpU&kWlooNRg*0|cVYH_&GJbMjy1*V$@JckuQ`@yn9giEqgS#sY zsS`jgMXT)hz0z({q+!o=#ytXFZM)&PSJYVdXo+NFm@*$rrM$_C|FY{#ojZu{{lA+x zqJmPPf}M-)u#3Qa8nNRICbE>q$FMh8p4hyn(xIBvTj+}i&HJGH``4@L2xb+i9~1e$6kwf8s5Vi zUlv#PGy)|&kx9OyXWz5NktfC_vBO?3=;me=nP&!D!Va^0i^Y@SWP*cL2s&i5Lke`d z19QL}R!kmvH`ev@J@RFOBMl#;XLcfx;GR1FI&5R+oBnaSs4Yp*7s@=@qNuO%B^Oc@)xHjTCI#ek3M4sOtQ zghv*>kxZ@U%*(Sx6YJlJW`QR%N9hPpJP_~3Y%ehU)ObcZ%Sszv)5p-1cO{xKlDOm- z=RIQop?ssQQvXP-!L47^Hn1nRj%bnxuzJA-aPK)|}6x5upJSHjNxSz)6yQ7~W1$*a_0=|KC z;Q(O9^m(IWVls({P%$uka(l1hsWfRhPDMaB&U(mBOfc6Fp-F@q%^!1iv$ki9k1_Dx1TiuDP=5NGIwwrCUvG8;eh>r?N z!-7L-a1aKBIoy_<5(5ZxZ$eP|z9;G#w!&a4^Ptu4@)y^o(l>c4nlm4yzP<0596Pza zeSk~bo8n7iq`|Wp!p`{x8+`Y%VtCHJ-%)})k^|PRMf1Z?FGHc1tUQhbFYcm2 z2?y`gk*@Ot`MY$g9@{jY&9M(-1KR?xz>$W6Le)gzNKTSD;dXGO$s&}ta@grfA!wH_ znv9_A@2z*Bmst44c0}v>V(2DP?bC_`rM!;Vn~vf^+wijq!oxd;RBm{%PcP%_JIVW< zb56nt(m%9_!k6`6@T}ZvLCea3!C`HeCQz5_sWEfUD!`ASr^bd|y%4J@mH+T%#L{e_^G#8>jetrmqixn z!A~KFUU>^K&nXuNt2@tH5tuwMIQZF+eQWo1>3)c|(YsrA-N7?E+a>E$Ieinlw;4=bm=KV1&wh8m@0IMC!<(Px$2xwijqt%AH1}x10c#J)Eo)sO`#CrBaikEXa!T)OV=`exQMQL>sjd_v ztjr?{C_}BLt+T>F5dXi7oQQ}>$ay(sc??AG5WCgDnut#C-a|7wQFFFi{2w1V-_62joH&<-$lcH*qfs3}M3@C}s`2ZuBU180&o}olVOaUqf&M3oLUt zB+k6ktmHXxCmkwZ{JYKG_jWlsIB+1LPp%mx5wu5%%}=xoK`(Q8a3wg%%YUd!^R^aadhc5x)=W)h=Gks6HD|De z_e=To)i~>=`BFI=B?*u)8wY~@$Xo7r>7CgR#d-UIl{j6OJ+}8DeM1mgpB&VU)F7FU zeX5XfnURT+7^Cb!4>oC^H`a;Pv9HNvB4Pd(2xgt`Yf@tZX5HSS---^Izy%@XJERG1 z;=iR8HxFu`Tqx4HYjxkQF>+q$OAWmM0r9#o9D-I-Wsc+QZGAiM8!e7b4%d28`3i?w zW0Rq)$ud~j_4azpw+^}5!A??{e9u$S`^TgGgbD2LX(T*F#J%^r-9~1E1MUx9;Y;EY z;qm^;-4&mSpH4p6WbZ%pW*Vt9Gg&NL2}?Tj=`S7&X?Fyu{}1U0<&0GhC=+pb5v$V# z1;V!LtTF;rd;UZ((hGt=-#EpNs|VKVL}5P8i3nmu!a#oO)M6$}2xQ%o1eX zq0CoFoha9IhO>^V{>|4YWfRtT#TOko$(W;zBQRUi?QyyEz*Y$k0>*J#B7 zMELUBJ}l4j1b>82XF$ZPwmFgqXT~aX-dGbDoMlUlnwys6KVMq`1&!evWyWk%E40ZP zZtvr@4d;23m+nPZyr+pC8t@Fqz5_m^0=#B`+TV%6Yxa=e{-6%8Ia4>wRV{@Fd9CU2 zmFRPj6)*u0KfEiXd4qUw2lKX<@dvbJwkZ_MPmq*pr2Ov*$Dif|FZj%$WJ7nQ-4~FS zf39`NttyQR@j13Y^QlyDeqd#zu#HC-Vr1h_L_o}=45yI~9h#}{@m>IKm3Oay9OhrA;0Hn6rlQKfMo0|k=G*gaFwV0!mZ$jv}^WhZ);*_Bm>aW z3Bj?D@bn9)0?Ix3`zf;8J=Af%-x1U&;FfwB(#2E`A~9=F7fZx zsm{i*xmcEyr_007A{vK|9$iHs4DOISD_mtisAGasRUu?f9&+c14>-8fU^Doz>oAFx z#Ks`y+U3h#HR8GC7x>jqkWvISYuJf}9n%%=KBBl%N+4JBQke*k7~;to>%A1u#k{jq zvHjPn4FA=^vw}2{@P@Pg3ZapfAm=TG)!Iypu>o{F>2i`x#WZZ<4=P|hQ0WZPfboC} z7L*3aBk-2--U*1E_M{1xJ?2G>0l-jJf~ZUvP<_KY@NUXZQc=G7?)ubJsGJckIuMic zVblOKJ)(d<7W)59!c-^+MYnKa_>b{$8&*K(f`}75GHFjGFTEvh*@+2`dMAPR+HBtD zi2$o3H$u&m3t?aaklH#Z#+abyk+(#DT1K%2%wu*|$NgaoQZ5~hUOpR9L!^-C_))6- zQ`|$|M7fV`grw}Mt&098(t=PKI^}Mr=Kd*q8cedzRTzCh@DOb}-Zl7A2&}1GZ?7Fa z_S^IAfqQWW*~*Tj(Q3;}yC`cp16{P@%NI|pnu)=VnxoQp4&LimOr`8OMpLMth`ML| z7Sk?Jt$nhTWFt9|4B)C7WX{D&=qE?_Zmm%9VscgpwlsZVV7nLh$EfWPAya;iPvOi9 zwf~nF(gb7{+NE;4R16&P z-H=xDs6xwkDc(*;-0|aC?u?s667kBYIf{f;?Hlk!giH!Y9F4z>qhB7iwDgk=U3dqIN2wU8}K2QY!UyApbm5h90& z-k+Nm%%jKx{SHyB90`95dZs)|Eqrxmq}-&)Fws92<>^!AM?V%d6W)nxEKZv zN0qvBjp-D<^EQcu5XhcI;DV0U^zl zJe1bw$l@Jv$}{q(1umm2n|s;i@xltV|+N`2yGfl|DDZ>7J(AX#PW|3}(;hjZD#|KnC> zQZ^YOdxS)`$WF2%G9!CdW_D!nqU;q)Mu_Yg$tGJuWs|-6o)^83@B1@;-(S7&n^P4}f%Dw_+83;>8oH~3C6f|ART zbk^0uMAYRzYoH8t?$=u8S24LacC-r6RGE_nQ@t3kF8(r0q;Q7Te#S)EPbw#|bgBjMCyx0B9{?7mi}Xna*i@PrY$x zmq^fnwV*uK!+gs(?dC~SWOaroB7*0Iphp@MI3Lgqjg8cFZf4|UiDu4ZSmR2;!{ z*$In-i>B6BKMx?>v}w%ac+X$ou9?X4t;D==Y~~x^ym>GW)Zo$Q+cY1xtZz}9M}pb{ ze!bUqGF|xfNcF@Fzy9Ve)Svurn^q?6Y5dm1g95oLb9@8GXoV70c$h@!uZ_5ko7{S? zk;gt)vi619`k2#rDnyRJ>dxV>GTHIc!}3jxcWSS{COipNPsP4rq$8ua!$npD5+j_C z?o?teE}Z=VowFB z$^xs2R7i(>j&560SDk+1m*Y|_SBnoug#h>fBQTC-&t&^Td5o2T^6(Bci|TnEJaV~@ zG-e{(Hmt)5qnXgw#3MAeWCkRsel-D2b&e_FoU@}bgH@}Y9I0t2u1w2Mt$-^b3$lcT zaxv4pLMkGzvzf8n&}4QeIk1l*<%E-TtHqI-RJpd&l5!O^Xs1`${feYwO0D-gr(U~l zE?ff$GVudt$MI)q*jCMygwZt@`rCSFCULH?(@ZkCIyD_;({2?GSE=-RGbw!$(Z2Z2 zABEY(2BlC-0Gzaq`oq3!;H1%2QOdFHvmrNJZG$Crp#Zfh0)QMG>b+d^OvCi!#>ZNb zF)$+f8yVLnav!ksH-6A%xb5PDJ#vV_FM}@MNdF?=oCDtS_G0OH1edOm5?6H2wG&#N zX2pvr1d`xWsS80;BG*)FJlwO2A%XBQO>+6D$K_~b2{pIcc*ZIE3%b+;Ru$TU{mp_- zO9`{V78ScA9KEs^GVwlarxi@n*`!qzS3WTj=T|Q$qt(OUId8Q*i*<^1hYvU?)N{(? zkJm!SGC`Hn`U)j)t}p~6iqL?Akx_EwJS48RGds4rg*Zyk>-8N6DwQ+Pe-ZJ1;)ylc z8$J!iI{r_Q8akN=m z_<~FJs~ZFQpIr>1j9zXA7Y{c;KqhsqK8afwAbSJ`mTTgRK+D>gERuiZQ}T zY}#dZsgH+S%ugwKM{a}xZF}$2+u-P2#W;4EXMSJiWJsi*_t+%~55{Dn3Ii76N3<$Y<#)fQN-Ql(Z%4SXj>; z6_IgjW2}6woH`qv*_kLjV5q(HU^|5Osw?ODv_qZq()C=ehX;{07-5^|Ie<3&zX#FB z4#08kOcFJ5YG`P9ws-lC!37nYHg4m+orK&%#`1I8ew`@>7X!H`g1pY2KU_;bLMF-A zwk*s=OHazDUpvY(%`gWBnQ&7GCa)GS#eV9$C{Z_a*oAnpk|gd)cJnRf3u;AQpdrt& z)(dr2*%6xFh?s{-<%_@3(e&C5FVR$2ZJsUH)d@75$y#6idVgf{@dpQlpsuArt=^mn zIlUGNrbNLgH0Yxs1S-8L}wu4Os;#c+fy&I`Rq}Cvx!Wk2s6)H zH7aes$RY6EYG@z;lWZsqwP)!Z`YtA)#O=D)F2Dmb_5wD7owvhK^yMqW7tkSiyuA`K zivQHHo0H3RG3>c*YttE5;G3g7_rdcumDx{aSZ6*d3$$6^Rl0t#d-lFQb+z$1DLrXySBe0$aT!VvLv`=f$Ws4-GBALj#GLSex z{Z=@-iLn!R_--!0a7cxB`CQu)X~^w%zWFXW0wy^LM(#@%VnR#u`-T);{oFu%l3Da+ zr}9g%f58C;=`mxw$UZ7FxqU3(nh!&l4kfQ~z`MmvXMGpoxSxwy+Y=qEvTJrvY-5aI z;wQg$&sE3MD!$vEE{(>8ZKwJZ?M(1#C=V#=rA-A8N(AMUS)pSfwtWx`>28Khyi#~X zQwL3U>l1%}Q>BmN&c|EaCye+Dt?$lhEVGh>M?Zr#*~GWMp=&C=;~>Gl#a%8Q0q>G9 zm|T3dg~3r9Qk^9C2_Dm#>pO8g_ZFJO57vnqg?sN)4}1L}lDV&Pr8E&f=hVU0cx)(G zH%v3vdBB=?rhA5I|5n2I-4T#%5spBe41CUK-gC8b zdlnr@CXzuTgMtQ!7`YJC6bzHZ&BjSp_AMqB&f*ybTNC)zY#Z^uizq4Lr`|ynn%`55 z-YTzH*1{HVldLDseWkXOdrR+X(Ebxva&fNIFF%u!a7A9>H~Nc_U~sW3AnQ6+ zK51YgS?hD9>L1%68=n|ly|o>jrPwBdC?Z;Jy!%pGQPj7LHv9{u^GtvVhX#cK#Gmv~0#_myBzI|` zWLa%%9Cn?|VaN~5O2RnY*5L2{4OFvZVx}949^=YU5~_vSKSP-dEE^r~a5?sqiu1$X ztdYZEzHNRva`$&`v_c?PCx^{v^we*A+qv(p4jE({AKqoZ zDWij|`W(=K{t*#p_j=`EQ8Rb=>$k_`JTJ*x^H3N}dIt7D$1Eai=Ru_&1?MXyYG!z7 zIN5tkCq230Q&Le^(Sv|z<)5mz5&POVPT5b14`CE1zbHOOKlLdb^K)aK$L?&F*>G`= zmC9&^?bzIp#=XVOTFvt&@pwiRY06)n3h!%i&-H=31RS0jsZT^cyi3a9*_!2Hc~p8) z&*cZnK4dvFU8(3F!>I9AF8Ex1l1%}5xKP8~)VBsx<0@PI;UI?{`i%DLbH8({=C2Mu zkwMF;ZO&TAfe|=bv3gI2jnAel0-K=$z=vT%=aJ z9#wt5)AHBN;ulBVNTPW8)60Q=WZ@R0;`0{F>9!ZXfcq(oCaUW$-N6DcxPvsob#%tps&sPZYF%EO*%M5*yr}>?qw! zPyYB|;`6VeI0F$4sL`D4(2F+ve0#gykGQc5v!zbOe=`$?O?BQt9Z9wcq^GAxFLJZf z+?=V*VE?&aNU28uG);$ui)iBW%x~<25Q>;5&i9O;xfI@4QFywI#X))n+Tk86G;N9$ z>V;~p3tb)DzjOvsU^ob2h;ja6u48fCb_(U6phmyYZgV?a0KIB{0SwyOBa)tslq}T9 za-PhFmbBKe(`P)3#Ez3*j@LimGZ;xU`cEMP2)??`b3QfC>70Sx+ONJ`ey6P(_BRZJL z?ksO?0&D{LC#DMBT(Mi9<3u4O<9}xt3ymM+)sW2Ox1%f=xAYq`{{O zU>Ui!xelxS^6-_6w>i~BqBFBn>fTpOK7d9f8xu+4Wt1!|A8~3!H9px-dI!@I`}tfHc{-%QQ7| zm*P74zo{-0+!EmcdVu=$J5g=XI;O{0oNwRfL6m9m$w;W5Q-FSlS2DO7uyxo+j@#x? zIMD(Vt-gPP5)wz$bv**!5FNUAN$|7RCJ(5ZS40I7wGDuU`G8XGbSR&^o2&or-CV4? zb`Fmt$d8oMDM2{+$*U53!E%&(sr(B{wS2vYpakN~8PRl@MOEO=HL z!+VU(ka^v##c+0n&b&g{G3fH#2x~;(tFsiqp#0VtuBEXW=|n!aKGX_Q4aMmFgp>Tg zRaU$*0G-8H>wp9(*J|G4McAe%+4h3e)|ktohC$oaEsu5QZvdfBdlR7cqHsUIA@#}M z3Vs5?eR2Rgv4kB5J=S-(v`THLU-Dbeaf|Lf9)Hi&(?juYY2f|9wwrWrqvo4G;im2d zPy?`N|94BE!~p;^=77f}QhMm6JdT*5F`*oPIwM>L zPW)F@V1BFqH1kZ1way9(7k@1}kGS7Fk?Cv$x~P(N9p|a}{$;K+EIJZ70~}*Q#Adfp zqh(dNRcpJtlz^}p%YOVb`y}*`|5w6-2U#l(>pAhRy+4)SbOf!!u#|zL%nfsZ``wK; z3!do76XK))yPVM99}B}sY{V<#F!5Xn@pT3|Ql&U7KIeYl=XZWw zyI32agk|5i+$nhZUrO*^Ux8Ja0k5GaPNe*}`Qyjo&E;Q4=;5Lj-Z%5*;s&O8)8&$) z<3bmXOF+IeIMUHMI&Z^_L|WEUm^SO zgSTD+Bj`;*Ze46|M6$uS*HXeNcc$C5c#~&+N9m_#>&_nllxN~S4=lyCQ7PEg0CF97 zWqy0UauEx^{D$&#b=exASO$I9|C7H%e!&mL*9s&VB-R-v2Lti?-$Z7x-e6#&GA7Y8 zSf?6?XV+d8Op<;L<#Q(6lGo9_kSs6SNn_?RnDP%dUG`@zs~RTr%>=~Xc^`Ny$9{S} zZ=`pv;_KRVK5_pGg+yiYI@@jYi~96Q;&46@h50 zaQtzkKvl#0)}rb2*XU`IBmv{YaZ!{|K21gK%f8VFl`6_C=+{xS19s<3DEz)KCp+p z3reU)0-=G3pmYP8FZgRr@9r^1$b=O|Q14tdX(fiSs!~ZhFf5SUY3Z){`J4NW_}S-D z)!Abf$&GqUnmR`sVjffePg%u2Eegufkwf7M{=ZhZFC@BDYN#DGi#wV1%lTeMe}T(N z@zU&8B)$2?)bA?F3aK~~nruRVG!cL=V z)3-&N)zb+Ff}U3`-!5y9R}Hwi>p7K(bqp~x3aq2)f5h2`DP({^Sm=F4=u+kcJD(Lx zZbLileSp-o03ZDNB%aUQhmcVL!*n$v#~!UO+CIZuNsjZBxQJTD1@!2tDUQx-9r_v|O;ba-)M|O-W;i@6e%=pzZHvNWL-K z4Vt#4l=<23-vo;=J)ibMZraqA;1JzI%zTCfDOb!LGM&MHlRDQii?V#oy&?uZywg3$fznU?KW8 z&TL{_O>nkzoG+wpBFoS?EHg%)m;;{y2cMl1qfFjhV(P3c{NoIin8Y}@6oYC9$DW~V zd=Fw~^~I;;tA#^ZbXp_gr;*KoiF;USoR3#|x+@`*nQKH6voUy6MI1M1wTbNJ{%7}<={1`A6H zUak&J(J^(f?0N#UiJPN{fFHKgcIB~?_19pH4k}Udb6X3&92>(F%}+DD=xrz+h;k&x zI>8pzF}V}(ANheX<*IO2!>ka?#o2BN4b}i@zv_FXjuR^T^i@xU`H+-~=f|4v zG*);wr`Z({v%t}ed`Noy<~ULD86I$C-bgbrCzm(V>b_8`q<~KO^eSOW5>+>Mikz3W zD#pj9JdA8+O%Zvr(GwJmu6;gS{7~WruSo`fX3)k|=f;nO236Xo8ofEMa^`MsRijTG zgs6w^QFe_c(juO{+`OgN;VTu!@CJg_T}(BU_C*n3#W$mxl!Nzly}^qf)k6Lpc|`?0 z_3p|=-7Z(h$c@wK`crq{G4yeC%xb3#~jhEJmhQt!xKFQ zNV5Bt(s?&MMA-}jCKt+Y8!l=ae2dh-BOIr8I!j~3XOTT9^*RovjP?ydmT>q=O*Lm5 z*973b%}Y15P${xTvuIJu5K`Xe!?ug=@%l&?25(E2?=%Zx%5!4x!U}dU4HD&^Q)FCs z13>CHxCUec_3d0O!+{dq(lcmZwTuW3E~K+!CT6g6^}q}s=Mj*UTZ z^Kags9pJsr&?&j#@+DuNHeSH?J=|FW0hED9&;6C!DZEQ5o$Bhd!e1F)j5L&f2It8k zT&t;ZK70iRC;m6q5VD?|c6UDYi%@=BTUUO138tgFb@mOTObMjxfA3Ts9k|AqzMe~vF9asnGsGGxW#a&=jC~B;E`$~e!qWkw(8Ahuc$tjxQ zMP}qf54F1JYHO5*`u3?Al4{J!U))pvb6Ze7b(xp<);nYQ0R3xwlfjql=5n&;+8=aS z8Pv15S>4R;D;V9|&b$7ojkcQRt#+bpL(8iMpEGcwdQyKblOOvbDmQSkS_&_&*TLbt z3ev85#m8Xsow2_tAu5<=C=rQLl7SsErVGwC&pC>18)D2kGbC)J|WVB%_q*J8ouXQS3^6HaVi_%Cdp1n8%W zpkgrSoP{p%W^@7(gMnvwBkxfYbrc%ro{f8b9^Uuf1@v|EoxLUywj(+!QI|Jkub zcD_d!y6-u<-L$P-!Q`smHmbGCk{sviBL0F%=xs223ZBzPJ;m!j2i8WD76G*T)5;K=ra|t;9 zUT4Jq;(HP8FMA#ZgZ5`=ObW;NVIHM^f2}8lQQYSbnH~ zWT^isCB*b`I+_hnO#jzkn7$HhU@t72&#PG28FiitMY`+G&A z4;?yKigkJj#E;|}TKwxJZ@}AQWqMqF`Xs}k`$aQ zkV+(A^nvmMw%mO3JmY#o)z#{&w>T326KHmn|EQkTNn-z)8L~_$(v{Fx?O57 z$tFE57I-7lky}YKpTr(M75+KJFaskdaSZ#{a`gGc?SR0Oasi^wAD0W*F!!9C)_pxv zG#22DRLy)nh}XXs1!_&&GwINKUrjaL8#dgUduV+BP`W`btwDhUu}Mtg z!X_ttk%7<1e!}*9fWc;i(z=iIk;x9P!FJ8UlDG+Vs9N{|`P=zd1}nX@DM?m*9OM@y zL@B&x>~T*bwbh?TYC^FxAa@d+^k&$Nk1Bh5d+i}y6JOF3sgYlFZ#Dil`*eZFl6N@$ zv%RvRdMxp%7z;QN$ghatc%Lw&Z65?2ze}yZ_;$bQpcJA6%(59II)9( zy35dS3EN<9d+IURU_EayZSHKN3@~i|>V1hUGgaXSF-?%p)SMYNtENv7i9^ z(|o%gOIdi459XeKNoo$hR2_i0WGKFD%1F1rwJ^ufe6FTe?%NR%^W+r0M6!`_BL@90 z_AO;DyUB|ekDsLjzu-?3EJC4e*b*=~lOF#3X8}afgoi!ysycno^gU3yMDSYLOP-#F z9At=E*l_N^+{L;t8vH&w6ba~OMQ@&*%=a%&CW(ch?$8ZhpCkq8P9ZFs$jCgfUK;c^ z!z;Rv620`^?dV0cKT-Hl2&>fRG@a?bO2@fR9~*p7p&UjHpvgL^nd^{z{|{^CR9{e; zaQmO3w&+ZSu2knA&omdxRqJ-uRpwvSDvu8}=(R2co`0=e`*FxTTjMfgexmEUl>!4V zlnrB)v}V?mFk0{zVRXg-vbh4QAzrsLpyh3(b{aJtc!qnDXGty9VYKCU6Y1y4$+nJr zoTGK+JZHrC4_sxzHA`Kf0D{}vZn&KRDXbJ+^Tl%2iRf_euZbCSikHi$LfL5>r-;HI zH-)-Joh>AUYM)icOYAh+u{S~e3vXiR3vTNiXg;mRJuNIOzODtg#<1QiWhL?0=UIPN zEYlNl=MMTUhf%rp%DLrfvOCx2?;hVctc1U~ark1pGwEeNp6e{^ z*?xIV@)c-DNbSm;PXDUEyjhStN}Qmxq|5PApNP4CXL`>pm1V=2!Ke-eYF3o%;c6%T z#NaRdNkJXRSPec!F>W4&Qwx)VRQdh9f*-91%5XA)7D4slbjgJ^p^#jcOVxTW!n&Tu zE|6^)ryKl(2S(I|goISWt6JX4zhc>+VxqW{`emn3a-3NdrR}AK(;mA3iK)h**K?&e z-vY71MQU2+Bt(bew74a_TzOHtr-)DTp~1h%hm7rdUnyPPTPRv|Q^q-XGF0upcPsC% zAf%OcYWm;CNH!x}UbwF;&pA!a>ZsX&`BC2-EGe4Je4Ypo6MPKj1=j@0lMe|%&mX(a z(_)aLmw|g;bSw3sXy5hYThy!(tKECEI5G8Lxd~k(uYnA&_tx9FNO%|2|M+Rpw@L&H z@(Pv@lH8W+;&@V@-kz^?aPVR>MaA+ckqy83;z{YvrJxPPp2he3Xd5xgKFdsSxc@LN z;N3SdNd;vVtn*57UuM_LyAA^&;SL(EnM#B!X3$Mjmz<%l_)?$P@EuNg$*cl36B2MrbfxdSaT099;(-Gt;`H4I%1g|WQDk234uTT4to?}_No)J$s? z%$nR`u20rCew2}P@osJ-Kyg9mQV1HFj-jpEzi`&sDJ9PVNtKe3@pm7G(a@4GcLu`4 zM75ijpYn**VXOv47VRD#&0K8I`8*s?kH{~PuJ7y%|H0|9kv(nQ#pY^zNos0pg&;sf zX2aP8m)p&pwYw&IVLo7I-FefxtZ4Xxl`9wi6=k`=xFFY{0Kd?e5O$U9#Lf^Mdv5Q) z@Z70BL`*ko5qZ0t4d@jR@iTlvtqM|d=MvG2!UCsE)d#(Bzq~d$h-%T7EfP{w=I13n zeKsZOw8Z*VzmwvG|IdpP91<&-75^0?{azB%Bn@5LBk%%RDXC;jL4BzdAsbh&OK_@;fq`;YkET!u(-?;kjB?mA69ms7BJ>w|j@37dK? zOwEW$TH4>>sd$i4|INF0E_Sg+ZOE7BL;tPEE80Sm;W7@7RS@o=3-as#3=hB|s@&+; zF?2u0dGrOwXp5}1UEa|s*&4l@q9*(;zH`yuX$tlG`kZ%RdLq2iN3W8sjQ>eCPak)l z*V*FBYd_Fl4Q~m19zI@Q80yVqCrL`i3aOH!bkHpnoY`xXHuLcQ3?YI6+}inn;@0S4 zv!r9fRZXD1nK-WL+S!J|B}6v3 zRn#|n>EKR`**I>v^1~ycmsbK@qq_b{4n^k!Wm?jaLYk%o}(-@gxTm4i~G*k)`vPgbL#+Q;$W zO6^n2#ijB4{gUbT#w92?ZaUtTK_c6JFi8?2b{<2f*Bn$ra=Z+N~{LbWa zSB@I=fx8eT+b8^fm2Y7_jr;Nm(?W(B6AF7tFq{gFl$jzFP^UKJip)}zS}QRZA9=w8j268#bVtpW!M44j~^KTisb!oMgm@_Z>MD3G-dXJ|ys z#`qZ_l4*Xn zedMi5|HHRx!vZr`B%h~h`k6h^2 zOOwnY7kzRY5f;UWapu7J#1|k;?jO<&ll)~cX6P<-N%tHyIcR-$*|*QQSux&G%DHCD zK~X@-;D7z-*gTCHjQ=fcENdNNx;&1@i3NCER*?zeRb?a4W1h#Wdy$Sj%~4erlQ`4D zn4RgxQLNmXk@OhNdYc!S+6Sud#awEkhqbVsYO&nH&~v1NrPR__)arh}#NF*(xdbid zCY#__5~9*lf$nL5&Ppr3p4t5kHhKSf;$3$7{{8!D03o{&ly%h9nI^lF!dS~s`LC;N zM*|Wph3H8>Y?kd=h=f;YzAu>XCe6+=lP}cggE(x)LSjvO{2E8K|C}`@imihdNiyi` zja^dOOCfa~d~|b5G4ka`Y~m#bfm4^pcNohz*zT1|>!c*5F*bR0LyD1>s$T5gxK_G3 zo|={@c~>tH-r;BZKX{eDc!8P`W>R`-Y+Cs}O7YjQW&RM{x}l-kCc3HFtmO>4q9Uxc zHGdTr&6^fsuO&sL{Q?uyfMk-!d5v9h@-j(%{^DgKiT)3FYHMhH*{lMV2oDquiMrwC z1&5;FKH8{mU7=VkEMDWg;hyrOkH*>$t~T+Wv=m%%f7R~IbH_>B+f#pW#mOE+BScs3 zoy)V;FqZKs6$BWnI_l3-OHtVMiz_^yxe#(?Zwl$X)FN!>k}Da}!0n61<=o^9LD^6z zPfZIy!9x3i#r)Gctqc$8rXUdc<>jsqGYcAmNZ1kQiH_yPwBeP|HPCbD5?Xh?(oT}# z@u7u~>c&3(E#)1)9UC9ON_^5v1y7Erh z@0KQ$-zs+7vY~QYC`4XsGwrEYN(B{poo3!)&Fyv5NIhy1G?u5GlB6D3SaTjwh0vRi z8&A$?Df#Cy>Fz1p>Ye)tOSLIlVmnTgUvpRvRud8JJNlVRrqxMjkuI3m?Vj{g`?!^Y z!>r(3V*uG={sG7~iUG@9!=dGifq|i+I_nf3X$r&#N71?Zmjd3`1{B6@Z+c=@WtB=r zukq39tt<1-$=A331DvJ|r}|etUX-AEt`^S%w9i33rB>10l@;8TdZpk&yy((MoA!*y zoX&RV=cW=`$He3i*H-2_CnETS{~10yiXrT{5CClV$X0KSrzg_DgPhLuE7q3@{?Ip!f**|LxF%4*SEviiGdVwPLVr@RU%i2$km zU%0s3rTc7*#*AGclse_Q6RMo#${WU4fRmG1%T>ipl$9h>XTbrTxq3kZ`krGQ12Dap zL#v=RPgZw(N%*@S<*pE=!y=v91DTXVBJ}RvH1!J3ezXl>s=~-XaX=rs&GFlD2K>3> zq{p`zd5@o!;1KkX;5Uen@m`Ys16_3Xa!DpU(zEjIxbCK4za5L zCu{^gKFk>@iMwnX=1%ZvuCESR0lmKdu!8e-{cx$5_kf&kaw|b98z)OXLu?~-28+V8d`LHoz1b}xO$5na!Y z*8#z=Yr@0z*@IOx7w$8hn)`$;!?g1h9(kmCl2*SZ`*S}nO-d#7kcGx$+i-SQ`)MI- zw09P5)aq#kH^M7>`avUyiA*K&*$8OID=P+ul6-x?8cy}LMrB2~gud!Br3}pk8L-|h z3@xY%pOx4of)^XqbC_u_V0|a-Qm(NC^`(Eq?Sy$I4Lo&|egwt~XK& zk_goLvT)uGsl6%E$zbW(RLhKP9D}0ZNQ~L^3rr_$3-+I1?x2fi2e{gh zKxA6l!a5Ms#7EEjZkzr1dEWa`zWmrrnhnwpTPJ#&^3HvT19&RRgf_R0AY*C5?s__L zg7tp;^ZT|<)7H@;gG@gL#BgsIHfS`!5Uxdt=)28N#dKpB9*O^q%P%x^#Ocd1IRqcz z2SvQVKPciK6L9HQQ^5d*n7q9@EZT3Q4>~~}@w!i#D|ckd^iqB82c`O9r7O3TU&--? zOG9GhNqqv+_Xq#+U8B+W6%-US>(8b5>Ure8SB`A(f;=T6Ds4M3MYqE1{RC65fU>)n zP`kz8juKfmbMJNE#BkT3qm2{7<8Mr`8WW~81cR_nVc>4jeI>2J z6?h!DX1sd!Q$Tv_a5}lg>@IE71A>tQQ_}-H{MgaJ%X6$As-HT}>Uz5dg%P<)0}2up zrlztvf{P{hrKJ|8*I1xmcJsZ!tbb~;MByZiV{%*QWdicqNqvm|!Km%oU_|xeG zgHjibl%z`f^KF%VYWw*W$FQJHmDwK)OjbCZn@BWkc>`AUvl1OC#r761XJlnf!wEgU zp&VNDU^6PXG?r_2+5;xMDUao8jDk@vQJqhMtoDf5NcZPw_ zW>l-ZAL;Xlh>*kiQlbASRBG49Ty?&-h>&I8_ z!v+W%{*Y~Kjx_+2DMVWOv_Txy1h#Xl(%Bwy%TD8T(><@`r1QqyHDs`;s%BXEtiJi` z5SOz7KyUhQMI}v^o`-!}Z&x1??3?1XZdx;kRvhhrA-^)km(xCv zyYc6wT+$o{VOom3~jU8Rxo6 zY?~6Lrs%D0)5)wT>Jm1%f);r=whwby(~Lhwh25jaJVT2~naJYjXq@D=K(aj1DD?G+ z_ocJpoP0)|LoOsjS~#xaddG=SbG-jKFi8s|rcRL3uAa8OK%}PZeb-T$Nr}_N=SqQm zPFC8TUEne%^D362xNHvCUT(~rz0UWY%1UV)#mY3aP2@h!sZYyRvZIokw4XwiV0jBn zu%9oa@=kh&K*&<%+D#bt-5jZxqnc?qYTqpQ@ez8O!43|CZV*+hvRAyi7*2IOpvx~( zTBt}-EdqtO<$)xWzr1@lQcQOpV4Lity{qf9X;Psb*UhP7xDI>OY*Q_YqBHr$+4`bs zV|*Xr&#@j3Xp4BR5rG1peHK3*rrb|H*RkP|k<=I-0w-SPBbyM<_}3`6l4A*?H6+HgJ%I3GQA z$UJhs--_|Sxnj;;ynaFtXS^W2(`~In`ciW5s9CV*M#V=5A0>99eOU<|+bCT~_u48= zGm<_6zOmXlTS7FDPb&;m^#7S8>7K~H@FCT&Fkf>Ldah#Ol37*QqTbZIdShS`1X99_={VA zmQKXjnre*Pr}ulF$+~zN{8hn(jKM!4bcfzj-gNjMq+9e?ZXt*z2JYWCi#o+VkD$Oj zqsB`7chJ#fHdV`ux}|Ulns733s5Yb*J*!P z7#GAYSwqZGo%v}*MmftYmq^H=S4sYiO~V1VDDht-UyetnJf2cuF(-MaydZ62+B94vP64dUF5O^5e=QLztw zW8+;{J=$eMDg9tP;|STi8}##n$q)`pMsV3PtPW2%?X`4@3zh84Zf7>~Y#ZD@6DIt= z;Phc5(zt{5gAK_p_-dklwo{(!=YD6Woy_(UR_4*%`Hb=!7(SlXNvYE9F3Wpb=Omzz+V(H-WonH0@al7U**N~^b4TmR`l|WZ(HSvgB;QNDu4uQ9;cba`C**c zjW}+)8p^S~grV9eDvsleFCN+3Yx+JBhaUG5GDm619QPGo ze%Qb*HZ-=5V2}-KOaA~VwU#)u#T+AoRItw9Gfv+l-T-8)fZ=Z$hLi?&@58 zqHu}vbJMOO73Ht2-x8g^dT->?ub7B#yFx#=k=n$MuC-tfTW6Zq>3!p^#KetDeMy3p zoG(dNI@5-n)}6dv*-)N*iG!#BdzMrFqzg^|g`$CP);I zq_OVrcRk4FU0YV3p597!+@(6L)yGytDX`q9Hp(HbI*JWW^D|3QjZ*UBl;`HxF+&4< zhWXS17{wuTf95DA;Zgsc!D91hl~$zXheG;%i!sFV4+}|3FI^$xej|ifuH&H0d_&a5 zcMBBEP0%`UiP3ZCM`qdn>P=N0!)FQZHB)xc{w#?OgG=R%MKE7p*MIKI6as+Yt155u z{tse5x`$gEh?bWEwqeD^Ed*bSJRI_2YfHiIoqQO+H31aUXZHBraHNaoRW_yofk4i; zyehKGSxJ>Clx+!ps@wx(Z|W`8K{&4A(Ng zdj2~T;tk*G*Re(1b4Fvb%`UNN(xX>>x3zwhmc-xkFu)2R?HwNNFnc#!*j1B?cV3sz z{@>l_Nx9?7_||Z}iAGXkYVJpy~a5SR(0ROayZ zjt>8gFPGPGdCOCcy_A)gdztT@-@w;;Pao(m zj{L6V|NFampUR3KcUtXI39i~g+g&zBG(0bw&o?nx8+UUzK1p=LIBcfUWzDYr%77eB zvfGm2`qG#VWHk{2n^@epn%?&1-Z{tsNx{Ce<9YSZqZR_T?N>?0m394tFL7Fz zHd#U`Ht{l0IT22!s1{%TTD#4I@&F9yFQMNU~ufH^oD-<=@Yo;Vk+Q<{``e#E{Aokm=|GbJmnoes?`Rzn2;Y#N!pg(73?IOpW7X4S;#meF_~_AZ z65}txF+WVxwm5H?-Xnj2jQ<0ILB`@iF4a|(hgRqdJ9N39&-69mBy-4G1WpMddyC)F)x4N#i{I?{eYulp zx7)L)a?lsFqlB|^Q@5+Hx zf-^gpZ=Y0xe<5)Vr~~!-RLJFyS{Ti@=nUQNzaVaU*cGh+6x7#(ENX;hqJ3aVwXz==J81g^}qOb^~e&#SpCgGSG zppdl2cl*}Y=Cojg$D1#;(|kk_dpE&ZU;1-0#y?a^7JO@_^$dB?At-CH+?z!JGd@Um zaqp}rQv;BZp8M5{xsUD2-_Dyt~NSIt6(Jhi9s1V!!c{@gUlcj?59A2LqeV+FI z*UKBkHI~tyrpM0~dp0-@&+gzh!bCd5>FJHq(V(FUw_vd37Su_p0fTf3Xnm?NDTADB z@OSmNRUswVBnhNS1f~c`ZVSW=i5KU)>h4xPIK(dg{DK{Sr^EwGUHhu8g<>P_MohpP z(weOsqD{-g-^X7d(IZBganp%Xrtoq|91=#;0|ExKC7@dpjl+>M24%y=GI;r4vjEgt z=p6&1P)djySsa6dAjFa|JqDQOD#*kl?}27_^w``hCAmGw zZI9pKk|%K8jg>(FKj%{Jb=QMl-1A9i?dMqOp0gU-M1f1p{EcJ&g-dinmevrLjyeSQ ztw4#^?1hS+!C%^%7b>16nZKsObVY4$b6&JaCCAc8d`3Ir?8e0&1Hs$ynQ}3zXfGW{ zn5n<$WcZ5y7HQHjHZd8Z)+sjg78rj_G&?)%7_UP&m4DYt47yQUU8LsTR~?LH?{z7u z>ZEDHmDR7?F87>ct?p;&89Ro)Be7>oy19F%ZqKkFCWYJ7bjA;+4QOCr@P7t*IF#T+ zekdj1(Vo(oKw*CQ-NJ&^U58JMS|t|G#y+{~bpya?@ItP;n)GfBnkfJJvvOOpS9l#- z!X$F?k;6n)lA?^exE}`&)Rb3BXd;)6n>mB7%OU-HG^LWVNK3mq3zs9y6SzW>C_K5> zyx5)6ad-P)2u*ZCPcQ!@t_~g(q9~87}W46+dRze=ZSDn_Cs()PHtwj~a#h*h zQbi_zmcq>$bm=4EqAOva$Jie2yjFEfD0Zd1mG-1B=?2Lh>xpQ=TJZ;2+M6&i@L@eo5Fa08@^ z4;XYR^V82<*Jr$uMOPNVT00YNRCB}BnOmM@q++Ax%nD+>thu5?l-XIvI^AiB1RLtb z`{^Ib5l2XjUpTYd#T^tD?QrS%m@D=YsBlbN6vHb_aEEVfU)6$R;&5w)yg(j00kdj& zj9VfY@KaS`${Qjk&*3zJj>(9jLeZduYGIDb8XLu!`17td-72zvO;K;XT@~Jwa1QU> zQkMQK{_@Q+a@Bn{IFA57eda3b)^P(Z1uYga44HV1a`yH;Fx#dl;l8J!gBHcNDGsP( zPlnOs;nZecRP(6Uk19Jvx9&pcKi7Ios$`Pj!~;lz{%J(_5|`?vwt#(tU-MIbG$<%4`kK%u zIu4ufC`FE6z8v{rYD4be7bk1AXc3p5nJ7{Et1s7Pu=>%~(vr}M`l@flxUQahaD(hv zqhut>iVyP@Cb%`vA(w_~Am#of6G`8*t@~g5q6O~y#y!)G^~GD&k$bd96|VkCt(QrML>uV=u}!faAD%`;uH!H0C` z9*X+m_~7%LgOaX(`m@1t0!-!bXP_*`9p(O-^RPqXhSt-BeNAXuTY)0?+Y_RjEw;Fx z`iO-7k=9;vswwHlRSSxb?P5e5$^=Pwj8SpkCDmip`6HIW!>}&meOwKm5df6&4@Q>w zyk?%C=trc&uxIX~*rn=i`n<|jg&fXYURR7?t5i8IviFrvv+c3i(0KB5S;w zHR;B^kuosmkX#p)?!g&pgHpZCZk;#y_zj2g{oxyal?AVN zVxg$>BZ&8{xN_)Xn|Xr)aW*cMX8T@Qh9T%Q=CdBdAk(Y)g4s}FN}zE4#lsjj5_9!} zVV_r725<9@iZYY-P4ir(5qpw*mh`}rQl`VoC@27eDlx1XI0Gq?G({ZH_b)Oi7Vh?` z77UE9FZgC;!P@KwpnJg+>(s-N#fL}(ylTAqrw*AVbfO4ereYxJ)Hg-R| zTm6xgpUvgGPe#^v-KOmq6dT0imJ<(|k39qt1jxWK+kXG&==me^ z)s73AK51DO@(Yt6WF_rqymjI{K4Z9Hh6<#;Dm-1sQdiUzROLD)wr^ z#Gy)Dw)^BteUdFH|AC965?-7 zTLyF2x_aSE0eD2^dYkNcQ$u5yNR%K870o&(}T#sIhE@ z=H?66)w4FWs%na;I(Fe%@e8iQh4-*>l?fNeDm3XoSbSkCHt&_OVAmQFG{JeTRCB7y z@9ACf=quRfPUB(o`8U}I6F1I!8xIhX4e3KhS5x^Y?^s4Mdp1PG-(SU;i>DMBZ$%6x zAv2`d&N$?!pd-79V#c^n_5ZZ@o>5U{TiYlgD1v|}NRBEwDIgLGPy{6BEJ<=!5ReQi zisX!>BIleXgD5%Y3~G^+0!1h&xU0&3&-qTc$9~T@?vFc0_mA$e2VHxwyyo-FIiHyt zw{QfD(osV3`hdf64Xl+3 zti=Z~aOouSAR|tG_=*dcHS6StgZn{OF7pQ2&_yEJU|`m(e*%*H1tJ&nfDV{yz5emG zu<2nPp4ExVjKZ-$f5#Q^AOR`*M(pOm*nwNa9(UJShef8AiNJ)?^_M+Ct2hPvXNmx0 zrMFF60mVn6oCg7k>PB(%QNUpUH6k!owPp?P*`CUbQc+UNQTzhxs^2mP0bO_~>Vev+ z_YU~%)JI}Lffo|i?F{u@Y^O1afjZ10Z>bDwslNotF=#SgeJll${J@mx2~2}yY@xS3 zXaoO_F9%OFfUWe|`KS)Zr&G>~%x1o-KQQP`a^HPr&Euph*ZRb@#5~#7-5r!VAF6e- zxEu!$vK;5m8Y|M%vK}aa!7!Z6ZyvVRM?_Mw;g`@=gtmT;S}~segkaIv#VuWZOh2^` zyRUN56BrN2uLQG$etkGC`XZ2WdG?_Ibs(9B+9>lrkHTB;_TY6`@1iPx&@0P{^L(r^ z(dq8m8Ylws7G70B-Ghx-F@qFzT04MJ2i{Sq-Y3e7RsN28xd#iu?&MzU)V&FMq@>;N z{HGSh>EridJd*cLK%t6rfc=nT*O5n55=Y?A6aFC~2Zl)px88ftqS@-J89q1f|41z}umo7a~8mPkw8>4+SVNN0)^4;>rR6{z) zt=G`>B)0lvkb1j|=@=aM>%(tYujCltYT?mABaB;9M$5oh`kUwHbzGb--h6_G;P*!p zBS3a607wjeFDPk>^2E>$pu7I@(MqYf^2V6xh#P^qER2 z=j#zAPP+_5=Q(5es=H$X*$f~%;Ocy{8pUiV#F`iGw1WaRVJ_;ZRc#kceMAHZiRf1{ z;AoLaXziEe#PL8X42VX+E4lYs(||DQGGtH}HVi5<_X1gS09c>yEi4I3V{t>s=4q{K zYhd3$ZZGwy?7d8oB*v5+`q1ef_|$##8!y;P7K@Z|Xr_`6L+A?7;lp4WH%FbzPqVsy z0!AD2pBQbg^mSAGRo>FLV` z7;?3#lGz$6UcquD{Gmkpx{Pt)<~mB5PI@vS4$TJeF-Vb1wXtB4TvtHvBznqCYOs?U z&$2CmmB>Un>p80WY+^nro;e*#NPXWIs3u%1&?<=yPx9EV1%R0pL_{-Jt!O+XYU^)0 zRn0{H$Rg2;AG-YACb+fGq9ENxAwlvQb%-qEx{OHz^*0cG+QmG0=gBY3jA`nZ2H-iy z9Su^HRZKFrxcrrg6up#3qsY`>$4BYnE!TPQZ#)_qq4PQQ11Ug@Ap-N^;Yp6&tS>>p zxk{C_MjoW(ntQ*>INU3|$tj3LI65k{Lh*=_Jw;X`S(h*9*8PN-Mu{wOI-{d~p%un4fyVu8fS@BBDqhYlxBQWI@z&MEdg?_z@MwVCT@vi`S03#qT z|3AC8m;<3r=Vu;C&pur?CI@tM@*#Cb0>91MFF&RWIvc+;y*c~J`Q^YO?sHKL+4t>Z zf+Js>_wt)DkA~DXdCe}0fscAChi*}#KWfYIWr#2M5#_}m^u3EsHK-2m-MSyN3c#m~ zYl|_WDu?;x1yN2Cu6wyRLDADMfyAt+c>Y|C0?n736NV8^#uAy!rm|%;@ytf*eS$A7 z``_QMrWDh;)p|!+1{*^0fl2KMupGOWUtEd%g?BJ?j93UVu*BsxP(Go%lKdat0Qhj- zYWyGwhvAGFEoa8Qs@*o|6Pkzb+jJfY0w>c=MIYe8%LUpkpC@a$J$Ik-CTX#4u418)b0q=fCK(i1Kl7P+D@<-Q1E}MDU8@<2TC|z{ z16Cjkk@@bO>L8Rob5ox1k^pO9%Pp|2ZuJ?hq{pInE?t;A!oI`R(&;&sCy>w_e!;Gh z{|0q4@LP|DPZ!B<0|_iKcevD4FJ0SH!1#AI+T#Y!-6MI-c~qNGx@{ZaCoZzi`gZM^ zB{48<0$*aLe{4YS8Jtpt1N=4+7TV6+<7Z`)SIl!8GhDi<;g`1LF z`i`i`VH$W6Wz#CT1Jr(fy4o%X#8*G&wVQ7cM3vmtPT^rY>P|Wl2@Gj2GUD~_6UB2d z5W?4I;{W_9CuLMN9xjCKQy7$p9t7q$$r? zkuK+a>PZ4zgwWo35__WD@@~$P9X@H0~5ws6+}u?vEIc#EZDy zeS3xCRWwQKQM?!#xqwKagLfORw9@A#xnij$lQ(ycA2glFrn2nAHn8397=qq5eH*X) zfbOk7&o_F|+p^E|EGUS%De@ZXm#98SYUFY@8l?k$&@aV_;|A{=m~(*8+<%4v?w@v` z5|-7aeQ^i~we~;@?u)7fqFt| zxmW%RGovxZz5FbB99YeThRp^EQe{uS0PUUf21A)Btf{H{_l?NA8|oih_m_CST&A() zbKp@u?o9W*C3&`;0}b>nZ@?S?y@lQkJ;p-cKfU+2uz^w(i8(&n#xSG$Yzu6RkL&Y& z0QZI34c=9gd!YB+VPzu@imG9X;^L2h3P;vuja+3+l>Q)y%HXI1bl4A@utepxnJPz* z+-l|mtb-SIG&y2}m(q5M{l82pzra2nRvYRI*E)y-Tj_s~c)eHGDwM<|W?bxyX_!81 z0j?ZXrxKMu|CHC!`}A_N{`dvy^I8S#8n){}kN_7a_w-f@zQ9k5pC7!Ya}RuNwR_{g zgehB9(0NeuqY}_>?}+GPvj+iJ(@>J8QDUHPEwPS?0Pije~>D>SYjjk=_K zAt6#1Z}pQ0pB*>6(x?>+s1WdO_Je>fe0EKc*3Mde;_saMQpq7&wkvYFsC&gsc=7X8 zhVpK-E(oUkOoRziHpD7m$wwgFU^l4p%o%+fdWGUh5A(1+{;aHzvYRE8FC@JMIlE*F zuk+ME6>$PfS!>o*{GFl7#z8fEdoDI`CxPfi|G6qSyCt}s_)rRvU+yjJF|Kpg;ozhg zBJIpMZK=yKk{v{$VeF9sUo5`hL%yuYyJ>j?atZ|V&hVqYn=z>!m|;c!p6^O5+SI_k zmzoDmjTc`b3HRVI;z^9`tXMS1FjWaHEP{cIZ=2>zdx=N1E70O-ku7v6rR_Ass9FBB1-Lk z{-y1yZGa&b6Y!OSp+5fahFW254aBInp>6~ay!2+y3RqZe@|jEQjy&d@1KQ^{CLr!L zqP;=Q2De|&kt#6m{!=a)8twObSlRm|HP>Mw$H42qOIkDj1wF-_Z-_4eBpPu0Kni_Q zu2Ae>0Xw-Eqhc=y+Pizj@t!p++WcYK-v^oOsX!&Nv$HeYo`;i@02B`uN9n-0Y;+8_ z%lEeL*Es&{-Bwvul|NgbuD;>A2(zm3CE_TLxUJs$271lJ<6LANfn=>J=aN zpUg;oI;5tkNJ#7X<3TX_9mY*cl)g8he3k26?1T^CHMOfw9`{_%KGI$Hfd)grm`~j) z_#qv|b>AAH4!}yx=lsvUwp&IM;BGv>6gl5PZ)kku&kq1g z`1F0F3fNp3lWrFw7XO;}6;feE@#$>6n#3aF-(*We- zUca!h7fql0)>Kqbt4aCKjkg1L)(*es8hScSerR~Rr;Eu8{hkxVI3n{wlLmYq_A;Xh zSbm<;#hwq)pQlLqjzK9EYWWl&O~g{kgYks_8D2;NA4Xd}=k^zO#yZ?OWq`{hr_2O&5NbJRCG zGZu|xgmocH%gf6Y4?#);XQ2hz`w~!U*93&iS%Pse*rU62?p+FJci8^&E#>5E;kT54 zxv=P&Cz!zv__>-}kE!G?E70pgZtvf6+iL3e&s(eT zif2*ip%#XlLamf}RplP&yE!b=gg^;tgx;uRNExq>4qnK^Z$O1Nf;8clyCH=W%!!WA zk;zl{5josB@$VWEAsRC?0pO)Zwg!GCwlz)!cb;3Nd1RDrx|OluatMg5L@kAoXGS(Ca^w zLDz*Hm+;Z`3c8P|FAefIKDw?aj^1(Fj(k41Ls0S0=c{*mcsr+Zv*=5jj%&$AN5I+o zFokX1UrF?`k1`y5J3!EBc@b~~9d(C}&kjEr@_1NCk8&I|?u9tl5`NsE^~ULoS5}q8 zTh9X(J7xIA6x;th+IkOeio}}+QBFg^@nC9h{#M@tRGTE{HNSEu@&xNpp}QU5fu^M) z<>L2G-wN6g%lt{>xa7pZP2xl;4SLRc8Me`t@B~n1;%zLfaZ@!iDoRah<4xgc8#UyP zEj@7e-!i8}(|>JzojPFWp{&wm_qzjpxfFR>sl^Qfd)52 zVAyOS4LMeLf^+4fOcg5G3g?9L6x~n*~C9s~2e%1elpGjpQhG0MTCK z82qMoz#w2w%mz3g7D;zcYkcIfqX?DlW0~YEfl`4oJ>6<)hT=BU98Z%%T2T`5tvWVh z=CY9E2ZGf$XslOOMj}1JbIppJ0|n|$uiA>M0a6)lo~?J?EX9G?C@6?PaI22NxfddSy!({5=T^8h5T;@IBjmTS>o&SyCh~uxU&1b1 z)BZrBQRrJbD% z0gSk8j%2i6_X!2x_#TmkUcdJ6>MPv$U)RL1hF_JDe@xHt#&pGSj7MT@TYXDip)cDN z!Q1rB-c@5lv3a9s|G>e+osu`!?M$JSCHW3c#*5hT$L2gW4(U5qv5+&fUb= zfiClvzGx&NE$cetEn3_c>@6E=HIH84UZq#U)K1JTK!0=YmNJj5g;j{@#n@L7l5G#) zU|h<><-7MBFPxc~fWQySl=W(1>RcS~VS%dB>*a^cS2mdq>4fE(s^J^Mng(}vLXb=G zCQS_QQp!TEkSiPXXkpipEyD9WZn}?hi9@Yxrqv;Rdk%O~Yvz8hRD|SgZt<3q1anZ{ zV8p)vSTeQjy_&Cxpp_*q3B8=35za<&30vJ-b|UP0%F&}Z$U>u1L9fq5?0VEdz9Cm- zaYopaiXNZNRB? zX61-t6qWtQv~`08;pdT?cPyR9?ltamcbsci3&OwmyHH+TRrH<6*?wb5L`<*5pqrRo z@@w3ve?M**a{~6WEU4l(p2t0gu>hO6PMLU>4IY~ig%8+QPg-v%%W>Pys*V%Vaod=0 zvhE}Zs(}hT4sc^kzpI!ADGw`GXOc18))g&BY7$o#NP>s^F8y|eBs83ugh7}L5yNq& zK!rp9;Dww93j)#k-0^hT%T#&eVu9CG`&Y-d%X>=!0|#;b_~+qO3MrzX5LVXbhq<6m zQ`*!0!^`2!DT<=gz37Qse)HS0RG3DBdojGIdOE*neodIjE4?U;TEP0vrdXxIw63f^ zVwJQc3F&YbrgrJ)omCBIZ3@(4ETo>%xK6J$roLO%kDfJqdlvGnib|=w7eKk(bYq5x zzOU7>DHHGGbVfzJeJhSxPJ%mbItQN_Kpbq@Y>j1(--w^gkt8G^HU#yN9<^6ZZJDn` z)_ryE>9Pp&Ji{i2L)`8~Ox<)%!4wsJwz$iLB0vj%iKaxTlPwEB% zJ~0+`Cgb4bXI61&5+5HnUU-&xDbrf97;`K*fC`{-*7WLl9l&|Ha{b%w~YpwP)H zqlDM`crt>K85jq{nX&@A>S>FK*jO-DOhyTH>`pa*#+ro>=xI~9{@ZDDcXQQe0jV+d zu$hIkYEb;UV>)p|nkb@ej8w8oT3W84lJ@9w1h2kF{0aVYuaA2vexX z4bS1aRjX$V^-<%I6@Y+sqN95=-Y?6@bg1+yL(2m;tPq7H(0LgNiBt?7JnW6EIbk6o z7|=&*^jr~Mh^XIbnwbvrvtIkmVCUF+)K>&w{xlu26N$-uT2XmA@_;eX&itOvLKJh* zYkwiI&60g>?ZFBOx*3Q6Yb@1%Kb8jL`ecFIAHNeGkJmKaKAiU`fp6Am9#RWA1hqO2 zmOi+ft5h(iX`o%bQg+vRIY+X3L9||4#jSCJ-OaJ9R8-1WOzRJdwMflU+^bjKNrobVI}JR7_SdGt(W#*sp2Nmc7|hDdOjK zwwVrZ3FuRRKoY>}&HhxU4SLQ#;WQJE-YKWn{Uy!*1W_8!7xmqelCtp?bUq$HY>_~AL0b+j{s zzpjbo-yUs=rS(l>LqNqSL0^FnNP2F>Ur~``&aX*A_I&s{MJlOjQsw_X>QR65W78bg zG2M)bh#X6ydxebR(EQX=HeFv4$r1SE+h6-+^S4`b276AcP@AFo=nFRtINZZSBr6o?*il()G{>|u!Of>i)6t$5SFmK z)yt3T&ta@Z7B{7M2bx*Qv#x_%@i#L{x)#wLy_Gpd|J$zGJUayO zt)>pbsDkLTZY#;VF%OV1J-v|JEj#mNr<0ae#`6^_#*B^+HdJR2H|zV))4Va<*hXIn zcv^I+wY}ds!$g0qPLTbAGEcs8CbAu@){M$(N$QZ->ckd}&rjr`loooG5naRCDbKyG zZ+rG8 zu9S|iNX+fsld)fi1N66tgQkV+7Q~{T`nWHqIeh5cDN5dY=jP7lLiQPa>%h)pZ;4*V zyI0G!WS~(_%Kj@C%h)l=#&nX%*q4s>WUyJ7uin_WMz7@j6W-bWYx%-{JEuXbX8zL~y?$@b=4SU;Pdna-3@O4G%py+ykOS+DXFAUjx9^@+&_%~i-^;U_m3qOb6r#+z z{Q;Ku(P<$7!VI1igtLDc#GJpqH?23%fQVri=Hh#s%LjE-W*RLD`oB=apOChQ~GJA&nEPyTCs7lEZn{=8Q## zJl!nQ$VGUZ{>ADZBj>R6ZQ2cl0|W9vOdLU-FS@kpwSIBDXwG3|?gL~>5$dj5f9!L^ z&H7Amy9;tl36e*1Sb;XUp1&QdPB&6lxZNs*vX!s--tfdFRK+0@|2D_0^!@?92(?bW z!!CU1(!|-ymg5fmTuD*qo>n#8AXCvWV+Nwi+|Vn-f#W>~<>?)Y(w*(Q&(H15S_o$X zf~lBmeHP*^ayp|fy~{QN=dOJFMOx6S)-IW-Uq)@_?~K|jg#dn-ox2oy9)Hd#A~^Rb zFy2i|yHMm@>`yrMW4KbOE8tvMZMvFbXMLP~A}Yr~(5}{N7{*$oHo~4l?$&)?`D+jL zk^N?7>n?e$=PfxR;uj+PgP`FSDNUR+Mjz^q_d5`W5p!cRec6PY+#UoJgGljw=?)iR zxsBQdvMJ+t35dgLMOa=3+3^G;~+Y&XaDv+}5s0$lN*> zKF+zMq^J0v(D~^e zuZ%t)U`3%Y{6YJ?F^-GL8^+)T@C2bus$HLAUaFiT)_?T%#G_k5e1Nll4tqr?I zvLhY(Q{=$Jmi#fXW1~135`=<}>}!{9tc~P^ovyWtSbQi)-%ht6HTNCO3oyBS%|@?>%RaAd3qSId2GPda`zt?s`05 zp7{pji_JbawohQIc->NJv}@l*dUmNbtw@Ur{~v7!_>RRQ>A4hBmE};n?9W`@IiM2_ zL&fxK4y1?~W-F!4*UF8Sqgt%;#?};Y7k7D%s_g;v5@5K{a69~v!)}tke1GS*+xprB z*l2P2HPMZ?l*HfyQ(wz!cZcAvJzQHorjP015oYgcdvq^$B@p$7|D+RBM#w`s%8zp& z-6S*l(6Ew6UNI=*Ap=dY;Myx?hOrV=Ecy_l*1*kXjmI`4H-ftzq(@Q$szJiyrk&N8 z(GAWgx71uTQ$*5f$qYTqKnP!jZq1@IYWi{Z${sKS%QjhDyAU7?)W!F<>TT{1auD&3dwAuRI>ba2fpA6yq%C$ljS=Y*j_Dx65M`QWJ5r)SNIuO)M<=Q+ zHF{iKUPW_zDpmB0tz|(c!mllJ$5>isgMs(ad{HsEYRaqjn~Fwi%dFcJ6&g?grJxo$ zhY*3?=ySn8?w*otPVx{c0mWDj9Y&D;7}lFCJi%HGgb$`{EBeY0xV?V{IZm0y37)*= z`v4Fg38VCaHGr=9d8J&M03&sm>04m3%k6lT>}%28W2oPru1$2Rl^``3FLcw7J^!wu zQ}#_mr+SmrZEdH(?8|UW`Fd8IS-kGyY@pWYgir2)S^3i?xpMchpxt&GpD5K1IqN6R zZ4BSj7Sz2h_2>jGk1(d}lz8k`~)}r%r4GKM`fo^IWdD>pjqz>Eq#1N;@txceAc5iKuWj?yHtezPWsT6vC1+ux*&RW1`-Z zaeI+$7)536dRkK?isI7yVqoF!U-YApHYhB{u9IxyE!007m=p-BN4PcT7kBIIPj94` z^y@UGNyOSs<~FShJg<6OFXT;VX&3R;OV8|0ose`hWK)03uH38{+Niqnp1^LmF)~B`Z**9R6D1-=b4J*+rNhWNy@36aBH#~0? z^Q*}mW7qaN$>t!3e})9-J2f?qH>}+dX!M@(-}#2U|6qOIW2f&Pv_Aw?r=H3On2?Rc zQ!S@OXJz)5>%v}XWj>WS-E5tzqUYC(6q8RE0)$}FFXZR-bq7xCIzN;#+SxhGtLx60 zD33Sf&#z>kt?j@e*aIgC)>?<8l+8t*!Zm8=qZ99UUhXXjk4_l3J@n@Aa$;<;QB!0} zmw{e%vyOb<+hre~lO+FU#R^bS4Y&I)kWP+9s@F!H4GS%mzQn{2iR$QtVbOjy+8M874xj9Z!h zv~OOkr{#zp_ebTxGW}`7IY?dBsmi~@@)!#JX`)5`{v>mWf1tVc6AO(UxDdD+emoQe zf&q8)fM=yERCrrk!w$siJAS&%Y-)$NKD5lWe+JA0=~?Qc&BF7oKhQD_Dn*qjCpA60J&Z4_3(fPUvz`gj^w@&aIC zO#$Il4oW!npe#-h4YM`OZH~Uv@4T`#!2>rW|KG^TIKZjsyeeS@zza{ZodvKIU>m4` z`<^5)gr*G*`TFa?m?h+%R`VfUD#aj2%u`m~im|gXS_Z5@D8RFNJ5r7-0-S|Y)+H9L zC@AcHYf2OUSvcb*R&dkE_B{=gj17dG=N&>tvTkr5yoBXV?xnczbg5Yn?SKDemLK19 zZe0bgzBnLb*Innl0n$Mk99wb7OtnbX&KDi()|igBU7HhS6cg_$fVh0-3zrDxnQVaT zK;`cEC&JGU@=Mhg!fBY52#h&lsit}1BlD%nOiBb9oUj(y-=7rjm7?JWh0Wglew{oY zz^L(eOx`w}?)EHcjBA1NWDt*P5cM~&Yq;|YWl+Ga%ORIo?}n@Tiev#ttG4OiTmCdm z8v3_RDTqOT;YJ5FLt}OG;X|gn_51=DfTSc|V-Zb}mMh7wu{T5SKMWN`Si&zGAL?gd zVDPBRJbIwsy#C$mx)^#D1naeY1*_oMFxAH%Sf1ZU9I6BkQrk~d4fU|R))pKpsL0=+ zF25B(u`9PRyles<0(ksPuZ1=g7K z6l1~i3NG7x12fa052E|fmUfQf?>K3mIuAgG$GvM82k;G7%C!U#hP$xzp~A@N zKYlSt&LR%QYF*t1Hn{=x317l5n)>o@K-vHNf|l|EXg59iTq8J7d!mA*e%Xnvza#c1FFHuZWwQtC{>M}@lZE_3FlrC~n*9Ihw)kuE|JwO~?fk!v{lAX=zwZ41|K0gQ*tEL4 zrSdfOPH~#aIY6S#Y$Hc0g$r2Fm57hk6+&gcEqYiDqDx|Ue-N6If7%>i!xF38VZOUJ z@6cW7)x@6Sv-49k3@A8uez;>|3SzwOns#0VSkEfU^2IS-NjUc`(z(_Y(cIm&BiuC| zii4eh`3C~H8w@x8i1&E=Tc_y%*ip&Y`=k#?icgfy>{il;d`>%jI)|j`^sSoD5F1NB z+KA#D%W`Lb4tgYqr*j zUC(Rr0$upc=EJh2WhR>bX)|$%;aR`nN@v*lT{+FhnvCI$h0}?p z5Gunw4!NACL*_oVF)Bn2IwC^5oi~?2)W^Y$*D;|V8(0MYD@XkQF-E|v*##<=nt>d( z;aZkk=M}mz*NwT21xkm()Cc9B$BtGG4kf$Swf$QX(M#>}f3ehp$hc#HOpc6f)^K7` za`COmiBS#d3%U#Qx(HF$ZoG;Q3kbIv^APoHxd*q&b)k*tvM)F8 zf^t)+q~@hFVj>;M44o5CEz$G&?*+lVY}mG79&N)!xc+c-Uj5UUTKKX^CCoV9W$qoD z&A{Zk({2IpnHtpR%xx&;l?%{@=>e5!Dh_~es|P4Enl1OnJAT0zs|l3y5!xk;7jjwY zzVG>3oF9BWKM!V;{A?`XudpDx= z)}}P;j8GalYrtm(d{sKoxl=bmxSvDM?U8d0MehX}4JmWd|9+4OF}<=>s@UJu^+eeS zcZ3-`x8l_GsI|H|mYw{CkU?PIU-Za-j@SH)8$+>ae<9?*5c0oA$eBPzrt{GD(#J?!1eA(>KFJR4?1U z_Qq~wM7bi-{>VT6<;zeC>OFyQ9hzW%PbzltRu;|T#I5E2WOkrSVkppPDfP>fh;}Fb z@+qnV$DXQ8;II2^|8#Gl2lzkBo$=`mSTZ_-tEY9u=^wQ;d{%A72&Lp_Gj&2R8lhs8 zLBuk4rz*`$+i4Ks>das)NduZrC~|KLIOFQVVfJ4@f{`hxzB#owZC}5YSyaU7I#4Dc z%77vk|=FTrGv=rCwi1odXV#SDcHbrg^?m^DX+|=`-izAnfl?W~)!|m3gcO_kW}h z|Mj^)hW7t%FuURVKVZNU{rC0rYY{=oQjJFUmQNp{+|>X0NBRk{z#JhE5y5}`Tj~l9 z3pu<&P>lE=e}j5OCu+{0C=n?U{_EdX-7xW_AP)UXkN)Xn;L(v2ton(OwkU~z{hPai z?<nx~}YzL|t@ozcjspsd>B`2sY0z4EAw7zuhK@!mB z$9upp3@Qr+QoF$-rZ!|eJUpDX?|a0^r)FhkWtRcVbdbY>-#J@N4X;qU?BUtzidYY* z*~Ni>gCkscr$G&r=1bVJ>D_4sb51x3 zV_Q&1Eag4h54`LkkdGY#n)Z@mk#zMm;hXMwiJV9v=VJF;1G-(0AHc?!GeoXyC70;C zHA4R{~$)&hqtZ|-YCA(r}2nN?L)u5CXzGqAheW&m7XD(~Ui3oYBKo^hYCvQ_j0 z9_T08ipgvn<3&*n5^p;}a*0=bQ^yOPLqy#sTln69nAps74Zdyz*NcSIlSx-MHRiCE z*n|5;Pi&7jEyOmc9a?-b`3;@7sNcLb;8gApoPRG9#bnmp{KR$6c}mp(iShnxx>NCf zk-c79VWe;b8?9OM^*k)s1KoR|&Q77ip)inbsn|JgUcUY~f_V=w14!g}41C!?P8BuS z6;IW|+aH(Jf~Fjnc*6@K*{E;_+Ogc__>E6$A4oxykAl37vqfG?gG+RAv+7}^S5@VYum1Yg%|Nw{ zt>iX{F_ejO(WFT)qNdzKzf&yJi;hB|9ni!@bLW zBOt9sQ_%0^(C7RxU%13a1qiXKk2?U?qGbAAOdq#+Ywq#NM<_)7@M>N|EGptqd-H7pxvmDu}fKIImEbrJ+i70kZL_R{&1)>grqK(vgB)8Q&yhD~it#&q4j`Vg z2|JV9c-}#yl>j+0pMN@!D%>OR?>u6mt8<* zf6c_TFJHy&i<-BoFv=7gdbv?l!v(@nYxscl`0zWi)33vlWcuoelZEqnYVl3UG}LuC zxc@F`aU;jH=~)cXv$3Z2PeXt#o0srt4eJULe+-4XEys6ri!L0s3pCUNrJZis1(2)L zGvCB_F9$SMeG8u5pqMg?Qd{b~++rYzvtO2-m^JLNl}tzM;3|GGS6S&?}`)*#1%#o&bdxWxmw;Ill zHg-F@G)I(~-=v>?O5|S)yRYfvUoalxtibW(y^`m{(VVtUY4GDsxU5$`G`C>X^yjxP zsPv^kM37JQ;X2-}+Vis$N#yOK_xzLmYT~5PlKRhMi-dlDzFr~nVJo?Lf51tq8e7eP3A@pqxFfnjuulrSb_MET3M%8hIGET1Jdf+R_n3y3 z8HKY;b{Z@8!@W#bATv6Zes+~ThN;@2`h5?cY8uW|c1nzgh8;JCLM&XkF1_MLT}&@V17ba?0& zE`kc!j7fUo%1w-1lUkSLIB`At`c5E?x_&gd1?YSv>+k32uQkJBdDFd*T@JF+ji&IsQvq+aeg&SNy|S|cG>%EFGY*$l`{@0ZX+XT*0IcOx%Ds_ z1O7P!(f&NK=$9wMlhjygZo?i$C7%0pB>K$+s?CxL7BZx5a!o|ZR)mrV={h)gC$W{g zeyPwB27wGh!PXLfTXP0+jUt=5U~ht}xy;f_c2qIU&SsC7$mpE?BV2cY&broGK{3zn zLDut;%h9}Q0~6s5@gDgOFP@xXQy}-;e46q`W)}+B#n?)S*6}jzU0qI(e(Lx*`>WJ= zt@(n}*sJa9?&Y|q5@I6kZmcxsBdsUTC70lG`VZ7;v)3npMW%tsXAjOlFgA0#{AM|C zym11jV|T||47sL+Y85U_*7wzro|anlxe4JhrQ@fufL9TUkxg*{-u(zjIb!`PZK4$Y zErH^uknZb;JkxyfmM|q}GZs^?$MZrvLB~OdAk%HSHhu}nNzqCv2$cygfHWo1I>%4& zVL9%l)2ZEkcUk&<>=X}j_-OBbf6DcQ9Nj}zL)NL`;mF3fG|xX1SJ_L6VLRSdp7cQ9 za2hL`aLBy{PbUhIm(LVlznOK)&c<9=&lL4y@(3$57~MIc6ZL%AxxBA%D||%+DC}wO zdok`yc*!QL9{#MS1zI~VT^1b4W;kpnI`V)jWbahmMQl$jgm$LrvdBjI zPF8grq3}`Nh~`zlL682`33jg%4&>mW#pt2c3&@N5rkYsq)$jVp-crS9g*!;FUhqH$ zcL^t?331cM#iu&lZY@Zh3)@kn$@&}fNG^Nueg|m*z1jKx3=Zn%`=V&Ay3|{y2a{A`lw3nD@`z6_ck}I# zlfLnMspf{u$~^076qg~bB}-Pol$VGxOh0;5p!+!?N68Wjuz0ns=KlL9RqxK!n}F<& z8S;qzF+amNFj_Ubz+W}HqRwC(v|osiK#=&8c#jFgH8^s=n?l85j%!V6;=7-Cuy0dc zhGDa}&hk-ZBYErc9MdxPInb^zZt&)O^0AaH)WGnpZ3<=GRS~f#DgiU6ie;5bKW^_c z^Y$2{REh{5s)0J7f#=8_pB-dDJJ4FvO5n3nU6Nb{QKYMBkgpxE2VjyBZ|pi~Tzhx# z+D?`Z1502iFt}7`}0bb|DD!vUMnL%tRspMwEisY*=@gj}YB! zwZkvVby`(x{=W<}Dln%O=aXr)LxM^= zj_)LhAeE;@aE+DqUfzM;@wG&w4Wh$A07S$-cONz#LR6TKbrQF8!rqG{sHM(}Ab*DW z^cvKN?nZ=lGQ6W^M8FF@xpI6QCYq%S*b#7l3W`Nw@h2va@aHgjjO}B&6`RAySF%g` zm0RVK!ZOuofX7JNy%wdhHg9I{YBqMgjwTkatY3Lo)X&p z*s$F?fG8{Wexd?{7mvK$W5x{6{Ur>uUMzSWg4}jd);irrAn~tq z`1&e*JbhC(0u_KeN^o4brEQ5O4K$$c>#QmQoHyX_Eq6a(SLy_L4&}{})Xt+Sj+4gk z-q&53+3Y{Wx%Lv20WJ@_I<7^WcXB_V&gby~*%>IH63{gLm^84wIWtf0pcbo0y!P4F zIy%Eo-#I2%N&Q#k?_)!Xf-nV?EuJg)LqD;c7IVlaZKC=6Dm$sO_o$x8BQKWMSLj5a zj52$4H=S&=OMC9(qQa{!8N&6qoQ5RH#yHaYzcm1b+lh%MP6{rP5oa`dhWrI3_l1C{ zfoVzO!LGfW$qw0|R@hh+v)2+F6q02{P%EDIXO?)6XyxVAZ1;d@j7M`FN}@-tM1gff z&IcYYJ7gwAfgAupbXE*B-TY^g6az~GKq!p|#-#s9o}#!^WmACLB%xjhH2=yv-~1Q>dBnE6S+VmEY%H3b6(y5adq@|C{DZf;WO}e1?DRv*e9bBX!u6#lpYgzSzJUK~_E9zxJ7> z9KbL4B}){+f6M05YV25_0`F%?|``1o{XM|FzG5P1!$=" + ] + }, + "execution_count": 11, + "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{array}{cc}\n", + "X = \\begin{bmatrix} x \\\\ y \\\\ \\theta \\\\ x_1 \\\\ y_1 \\\\ x_2 \\\\ y_2 \\\\ \\dots \\\\ x_n \\\\ y_n\\end{bmatrix}\n", + "&\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{array}" + ] + }, + { + "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{array}{cc}\n", + "X = \\begin{bmatrix} x \\\\ m \\end{bmatrix}\n", + "&\n", + "P = \\begin{bmatrix} \n", + "\\Sigma_{xx} & \\Sigma_{xm}\\\\\n", + "\\Sigma_{mx} & \\Sigma_{mm}\\\\\n", + "\\end{bmatrix}\n", + "\\end{array}" + ] + }, + { + "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": 15, + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\"\n", + "Extended Kalman Filter SLAM example\n", + "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\n", + "\n", + "# Simulation parameter\n", + "Qsim = np.diag([0.2, np.deg2rad(1.0)])**2\n", + "Rsim = np.diag([1.0, np.deg2rad(10.0)])**2\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": 18, + "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, z)\n", + " initP = np.eye(2)\n", + "\n", + " # Update\n", + " xEst, PEst = update(xEst, PEst, u, z, initP)\n", + " \n", + " xEst[2] = pi_2_pi(xEst[2])\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": 6, + "metadata": {}, + "outputs": [], + "source": [ + "def predict(xEst, PEst, u, z):\n", + " S = STATE_SIZE\n", + " xEst[0:S] = motion_model(xEst[0:S], u)\n", + " 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", + " return xEst, PEst, G, Fx" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "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: 3x3 pose estimation\n", + " :param u: 2x1 control input [v; w]\n", + " :returns: x' = Fx + Bu\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. " + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "def update(xEst, PEst, u, z, initP):\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) # Calcualte Kalman Gain\n", + " xEst = xEst + (K @ y)\n", + " PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst\n", + " \n", + " return xEst, PEst\n" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [], + "source": [ + "def calc_innovation(lm, xEst, PEst, z, LMid):\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", + " y = (z - zp).T\n", + " y[1] = pi_2_pi(y[1])\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", + "\n", + "def jacobH(q, delta, x, i):\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", + "\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 hmere is use" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "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", + " :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])):\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": 10, + "metadata": {}, + "outputs": [], + "source": [ + "def calc_n_LM(x):\n", + " \"\"\"\n", + " Calculates the number of landmarks currently tracked in the state\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", + " 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]])\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": 11, + "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", + " 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", + " :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" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "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", + "def pi_2_pi(angle):\n", + " return (angle + math.pi) % (2 * math.pi) - math.pi" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "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": 16, + "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", + "window.mpl = {};\n", + "\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('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", + "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 = $('
');\n", + " this._root_extra_style(this.root)\n", + " this.root.attr('style', 'display: inline-block');\n", + "\n", + " $(parent_element).append(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 (mpl.ratio != 1) {\n", + " fig.send_message(\"set_dpi_ratio\", {'dpi_ratio': mpl.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 = $(\n", + " '
');\n", + " var titletext = $(\n", + " '
');\n", + " titlebar.append(titletext)\n", + " this.root.append(titlebar);\n", + " this.header = titletext[0];\n", + "}\n", + "\n", + "\n", + "\n", + "mpl.figure.prototype._canvas_extra_style = function(canvas_div) {\n", + "\n", + "}\n", + "\n", + "\n", + "mpl.figure.prototype._root_extra_style = function(canvas_div) {\n", + "\n", + "}\n", + "\n", + "mpl.figure.prototype._init_canvas = function() {\n", + " var fig = this;\n", + "\n", + " var canvas_div = $('
');\n", + "\n", + " canvas_div.attr('style', 'position: relative; clear: both; outline: 0');\n", + "\n", + " function canvas_keyboard_event(event) {\n", + " return fig.key_event(event, event['data']);\n", + " }\n", + "\n", + " canvas_div.keydown('key_press', canvas_keyboard_event);\n", + " canvas_div.keyup('key_release', canvas_keyboard_event);\n", + " this.canvas_div = canvas_div\n", + " this._canvas_extra_style(canvas_div)\n", + " this.root.append(canvas_div);\n", + "\n", + " var canvas = $('');\n", + " canvas.addClass('mpl-canvas');\n", + " canvas.attr('style', \"left: 0; top: 0; z-index: 0; outline: 0\")\n", + "\n", + " this.canvas = canvas[0];\n", + " this.context = canvas[0].getContext(\"2d\");\n", + "\n", + " var backingStore = this.context.backingStorePixelRatio ||\n", + "\tthis.context.webkitBackingStorePixelRatio ||\n", + "\tthis.context.mozBackingStorePixelRatio ||\n", + "\tthis.context.msBackingStorePixelRatio ||\n", + "\tthis.context.oBackingStorePixelRatio ||\n", + "\tthis.context.backingStorePixelRatio || 1;\n", + "\n", + " mpl.ratio = (window.devicePixelRatio || 1) / backingStore;\n", + "\n", + " var rubberband = $('');\n", + " rubberband.attr('style', \"position: absolute; left: 0; top: 0; z-index: 1;\")\n", + "\n", + " var pass_mouse_events = true;\n", + "\n", + " canvas_div.resizable({\n", + " start: function(event, ui) {\n", + " pass_mouse_events = false;\n", + " },\n", + " resize: function(event, ui) {\n", + " fig.request_resize(ui.size.width, ui.size.height);\n", + " },\n", + " stop: function(event, ui) {\n", + " pass_mouse_events = true;\n", + " fig.request_resize(ui.size.width, ui.size.height);\n", + " },\n", + " });\n", + "\n", + " function mouse_event_fn(event) {\n", + " if (pass_mouse_events)\n", + " return fig.mouse_event(event, event['data']);\n", + " }\n", + "\n", + " rubberband.mousedown('button_press', mouse_event_fn);\n", + " rubberband.mouseup('button_release', mouse_event_fn);\n", + " // Throttle sequential mouse events to 1 every 20ms.\n", + " rubberband.mousemove('motion_notify', mouse_event_fn);\n", + "\n", + " rubberband.mouseenter('figure_enter', mouse_event_fn);\n", + " rubberband.mouseleave('figure_leave', mouse_event_fn);\n", + "\n", + " canvas_div.on(\"wheel\", function (event) {\n", + " event = event.originalEvent;\n", + " event['data'] = 'scroll'\n", + " if (event.deltaY < 0) {\n", + " event.step = 1;\n", + " } else {\n", + " event.step = -1;\n", + " }\n", + " mouse_event_fn(event);\n", + " });\n", + "\n", + " canvas_div.append(canvas);\n", + " canvas_div.append(rubberband);\n", + "\n", + " this.rubberband = rubberband;\n", + " this.rubberband_canvas = rubberband[0];\n", + " this.rubberband_context = rubberband[0].getContext(\"2d\");\n", + " this.rubberband_context.strokeStyle = \"#000000\";\n", + "\n", + " this._resize_canvas = function(width, height) {\n", + " // Keep the size of the canvas, canvas container, and rubber band\n", + " // canvas in synch.\n", + " canvas_div.css('width', width)\n", + " canvas_div.css('height', height)\n", + "\n", + " canvas.attr('width', width * mpl.ratio);\n", + " canvas.attr('height', height * mpl.ratio);\n", + " canvas.attr('style', 'width: ' + width + 'px; height: ' + height + 'px;');\n", + "\n", + " rubberband.attr('width', width);\n", + " rubberband.attr('height', height);\n", + " }\n", + "\n", + " // Set the figure to an initial 600x600px, this will subsequently be updated\n", + " // upon first draw.\n", + " this._resize_canvas(600, 600);\n", + "\n", + " // Disable right mouse context menu.\n", + " $(this.rubberband_canvas).bind(\"contextmenu\",function(e){\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 nav_element = $('
')\n", + " nav_element.attr('style', 'width: 100%');\n", + " this.root.append(nav_element);\n", + "\n", + " // Define a callback function for later on.\n", + " function toolbar_event(event) {\n", + " return fig.toolbar_button_onclick(event['data']);\n", + " }\n", + " function toolbar_mouse_event(event) {\n", + " return fig.toolbar_button_onmouseover(event['data']);\n", + " }\n", + "\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", + " // put a spacer in here.\n", + " continue;\n", + " }\n", + " var button = $('