From d6b3f63bc8a7f7024811168fc9838bf467413aab Mon Sep 17 00:00:00 2001 From: Peter Date: Fri, 7 Oct 2022 12:12:35 -0400 Subject: [PATCH 01/34] C++ implementation is > 2x faster C++ code makes converting axis + theta to rotation matrix 2x faster use batched rotation conversion FK in C++ allow the user to recompute the precomuted FK stuff needed if you add frames to the chain store joint limits --- .gitignore | 2 +- pytorch_kinematics/pk.cpp | 93 ++++++ src/pytorch_kinematics/chain.py | 281 +++++++++++++++++- src/pytorch_kinematics/frame.py | 18 +- .../transforms/rotation_conversions.py | 2 +- tests/test_ik_using_gradient_descent.py | 77 +++++ 6 files changed, 454 insertions(+), 19 deletions(-) create mode 100644 pytorch_kinematics/pk.cpp create mode 100644 tests/test_ik_using_gradient_descent.py diff --git a/.gitignore b/.gitignore index a55fa43..beab62e 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,5 @@ .idea +*.so *.egg-info __pycache__ temp* @@ -7,4 +8,3 @@ dist # These are cloned/generated when testing with mujoco tests/MUJOCO_LOG.TXT tests/mujoco_menagerie/ - diff --git a/pytorch_kinematics/pk.cpp b/pytorch_kinematics/pk.cpp new file mode 100644 index 0000000..077db2c --- /dev/null +++ b/pytorch_kinematics/pk.cpp @@ -0,0 +1,93 @@ +#include +#include +#include + +using namespace torch::indexing; + +torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, + torch::Tensor theta) { + /** + * cos is not that precise for float32, you may want to use float64 + * axis is [b, n, 3] + * theta is [b, n] + */ + auto b = axis.size(0); + auto n = axis.size(1); + auto m = + torch::eye(4).to(axis).unsqueeze(0).unsqueeze(0).repeat({b, n, 1, 1}); + + auto kx = axis.index({Ellipsis, 0}); + auto ky = axis.index({Ellipsis, 1}); + auto kz = axis.index({Ellipsis, 2}); + auto c = theta.cos(); + auto one_minus_c = 1 - c; + auto s = theta.sin(); + auto kxs = kx * s; + auto kys = ky * s; + auto kzs = kz * s; + auto kxky = kx * ky; + auto kxkz = kx * kz; + auto kykz = ky * kz; + m.index_put_({Ellipsis, 0, 0}, c + kx * kx * one_minus_c); + m.index_put_({Ellipsis, 0, 1}, kxky * one_minus_c - kzs); + m.index_put_({Ellipsis, 0, 2}, kxkz * one_minus_c + kys); + m.index_put_({Ellipsis, 1, 0}, kxky * one_minus_c + kzs); + m.index_put_({Ellipsis, 1, 1}, c + ky * ky * one_minus_c); + m.index_put_({Ellipsis, 1, 2}, kykz * one_minus_c - kxs); + m.index_put_({Ellipsis, 2, 0}, kxkz * one_minus_c - kys); + m.index_put_({Ellipsis, 2, 1}, kykz * one_minus_c + kxs); + m.index_put_({Ellipsis, 2, 2}, c + kz * kz * one_minus_c); + return m; +} + +std::vector +fk(torch::Tensor link_indices, torch::Tensor axes, torch::Tensor th, + std::vector parent_indices, std::vector is_fixed, + torch::Tensor joint_indices, + std::vector> joint_offsets, + std::vector> link_offsets) { + std::vector link_transforms; + + auto b = th.size(0); + auto const jnt_transform = axis_and_angle_to_matrix(axes, th); + + for (auto i{0}; i < link_indices.size(0); ++i) { + auto idx = link_indices.index({i}).item().to(); + auto link_transform = torch::eye(4).to(th).unsqueeze(0).repeat({b, 1, 1}); + std::vector tip_to_base; + + while (idx >= 0) { + auto const joint_offset_i = joint_offsets[idx]; + if (joint_offset_i) { + tip_to_base.emplace_back(*joint_offset_i); + link_transform = torch::matmul(*joint_offset_i, link_transform); + } + + if (!is_fixed[idx]) { // NOTE: assumes revolute joint + auto const jnt_idx = joint_indices[idx]; + auto const jnt_transform_i = jnt_transform.index({Slice(), jnt_idx}); + tip_to_base.emplace_back(jnt_transform_i); + link_transform = torch::matmul(jnt_transform_i, link_transform); + } + + auto const link_offset_i = link_offsets[idx]; + if (link_offset_i) { + tip_to_base.emplace_back(*link_offset_i); + link_transform = torch::matmul(*link_offset_i, link_transform); + } + + idx = parent_indices[idx]; + } + + // go through tip_to_base in reverse and build up the intermediate transforms + + link_transforms.emplace_back(link_transform); + } + return link_transforms; +} + +PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { + m.def("axis_and_angle_to_matrix", &axis_and_angle_to_matrix, + "axis_and_angle_to_matrix"); + m.def("fk", &fk, "fk"); +} diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index f9a04e7..03c8289 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -1,8 +1,12 @@ +from functools import lru_cache +from typing import Optional, Sequence + +import numpy as np import torch -import typing import pytorch_kinematics.transforms as tf from pytorch_kinematics.frame import Frame, Link -from . import jacobian +from pytorch_kinematics import jacobian +import zpk_cpp def ensure_2d_tensor(th, dtype, device): @@ -16,6 +20,12 @@ def ensure_2d_tensor(th, dtype, device): return th, N +def transform_direction(pose, v): + v_ = torch.cat([v, torch.zeros_like(v[..., 0:1])], dim=-1).unsqueeze(-1) + new_v = (pose @ v_)[..., :3, 0] + return new_v + + class Chain(object): """Robot model that may be constructed from different descriptions via their respective parsers. Fundamentally, a robot is modelled as a chain (not necessarily serial) of frames, with each frame @@ -26,19 +36,81 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.dtype = dtype self.device = device + self.identity = torch.eye(4, device=self.device, dtype=self.dtype).unsqueeze(0) + low, high = self.get_joint_limits() + self.low = torch.tensor(low, device=self.device, dtype=self.dtype) + self.high = torch.tensor(high, device=self.device, dtype=self.dtype) + self.sphere_indices = None + self.precompute_fk_info() + + def precompute_fk_info(self): + self.parent_indices = [] + self.joint_indices = [] + n = len(self.get_joint_parameter_names()) + self.axes = torch.zeros([n, 3], dtype=self.dtype, device=self.device) + self.is_fixed = [] + self.link_offsets = [] + self.joint_offsets = [] + queue = [] + queue.insert(-1, (self._root, -1, 0)) + idx = 0 + self.frame_to_idx = {} + self.joint_weights = torch.zeros([n], dtype=self.dtype, device=self.device) + while len(queue) > 0: + root, parent_idx, depth = queue.pop(0) + self.frame_to_idx[root.name.strip("\n")] = idx + self.parent_indices.append(parent_idx) + self.is_fixed.append(root.joint.joint_type == 'fixed') + + if root.link.offset is None: + self.link_offsets.append(None) + else: + self.link_offsets.append(root.link.offset.get_matrix()) + + if root.joint.offset is None: + self.joint_offsets.append(None) + else: + self.joint_offsets.append(root.joint.offset.get_matrix()) + + if self.is_fixed[-1]: + self.joint_indices.append(-1) + else: + jnt_idx = self.get_joint_parameter_names().index(root.joint.name) + self.axes[jnt_idx] = root.joint.axis + self.joint_indices.append(jnt_idx) + self.joint_weights[jnt_idx] = depth + + for child in root.children: + queue.append((child, idx, depth + 1)) + + idx += 1 + self.joint_indices = torch.tensor(self.joint_indices) + self.joint_weights = self.joint_weights / self.joint_weights.norm() + def to(self, dtype=None, device=None): if dtype is not None: self.dtype = dtype if device is not None: self.device = device self._root = self._root.to(dtype=self.dtype, device=self.device) + + self.identity = self.identity.to(device=self.device, dtype=self.dtype) + self.axes = self.axes.to(dtype=self.dtype, device=self.device) + self.link_offsets = [l if l is None else l.to(dtype=self.dtype, device=self.device) for l in self.link_offsets] + self.joint_offsets = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in + self.joint_offsets] + self.joint_weights = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in + self.joint_weights] + self.low = self.low.to(dtype=self.dtype, device=self.device) + self.high = self.high.to(dtype=self.dtype, device=self.device) + return self def __str__(self): return str(self._root) @staticmethod - def _find_frame_recursive(name, frame: Frame) -> typing.Optional[Frame]: + def _find_frame_recursive(name, frame: Frame) -> Optional[Frame]: for child in frame.children: if child.name == name: return child @@ -47,13 +119,13 @@ def _find_frame_recursive(name, frame: Frame) -> typing.Optional[Frame]: return ret return None - def find_frame(self, name) -> typing.Optional[Frame]: + def find_frame(self, name) -> Optional[Frame]: if self._root.name == name: return self._root return self._find_frame_recursive(name, self._root) @staticmethod - def _find_link_recursive(name, frame) -> typing.Optional[Link]: + def _find_link_recursive(name, frame) -> Optional[Link]: for child in frame.children: if child.link.name == name: return child.link @@ -62,13 +134,54 @@ def _find_link_recursive(name, frame) -> typing.Optional[Link]: return ret return None - def find_link(self, name) -> typing.Optional[Link]: + @staticmethod + def _get_joints(frame, exclude_fixed=True): + joints = [] + if exclude_fixed and frame.joint.joint_type != "fixed": + joints.append(frame.joint) + for child in frame.children: + joints.extend(Chain._get_joints(child)) + return joints + + def get_joints(self, exclude_fixed=True): + joints = self._get_joints(self._root, exclude_fixed=exclude_fixed) + return joints + + @staticmethod + def _find_joint_recursive(name, frame): + for child in frame.children: + if child.joint.name == name: + return child.joint + ret = Chain._find_joint_recursive(name, child) + if not ret is None: + return ret + return None + + def find_link(self, name) -> Optional[Link]: if self._root.link.name == name: return self._root.link return self._find_link_recursive(name, self._root) + def find_joint(self, name): + if self._root.joint.name == name: + return self._root.joint + return self._find_joint_recursive(name, self._root) + + @staticmethod + def _get_joint_parent_frame_names(frame, exclude_fixed=True): + joint_names = [] + if not (exclude_fixed and frame.joint.joint_type == "fixed"): + joint_names.append(frame.name) + for child in frame.children: + joint_names.extend(Chain._get_joint_parent_frame_names(child, exclude_fixed)) + return joint_names + + def get_joint_parent_frame_names(self, exclude_fixed=True): + names = self._get_joint_parent_frame_names(self._root, exclude_fixed) + return sorted(set(names), key=names.index) + @staticmethod - def _get_joint_parameter_names(frame: Frame, exclude_fixed=True) -> typing.Sequence[str]: + def _get_joint_parameter_names(frame: Frame, exclude_fixed=True) -> Sequence[str]: joint_names = [] if not (exclude_fixed and frame.joint.joint_type == "fixed"): joint_names.append(frame.joint.name) @@ -77,7 +190,7 @@ def _get_joint_parameter_names(frame: Frame, exclude_fixed=True) -> typing.Seque return joint_names @staticmethod - def _get_frame_names(frame: Frame, exclude_fixed=True) -> typing.Sequence[str]: + def _get_frame_names(frame: Frame, exclude_fixed=True) -> Sequence[str]: names = [] if not (exclude_fixed and frame.joint.joint_type == "fixed"): names.append(frame.name) @@ -98,6 +211,28 @@ def add_frame(self, frame, parent_name): if not frame is None: frame.add_child(frame) + @staticmethod + def _get_links(frame): + links = [frame.link] + for child in frame.children: + links.extend(Chain._get_links(child)) + return links + + def get_links(self): + links = self._get_links(self._root) + return links + + @staticmethod + def _get_link_names(frame): + link_names = [frame.link.name] + for child in frame.children: + link_names.extend(Chain._get_link_names(child)) + return link_names + + def get_link_names(self): + names = self._get_link_names(self._root) + return sorted(set(names), key=names.index) + @staticmethod def _forward_kinematics(root, th_dict, world=None): if world is None: @@ -121,7 +256,7 @@ def _forward_kinematics(root, th_dict, world=None): link_transforms.update(Chain._forward_kinematics(child, th_dict, trans)) return link_transforms - def forward_kinematics(self, th: torch.tensor, world: typing.Optional[tf.Transform3d] = None, end_only=True): + def forward_kinematics(self, th: torch.tensor, world: Optional[tf.Transform3d] = None, end_only=True): """ Return Transform3D wrappers around 4x4 homogenous transform matrices (called H) that map points in link frame to world frame (via left multiplication Hx). Specifically, @@ -137,7 +272,48 @@ def forward_kinematics(self, th: torch.tensor, world: typing.Optional[tf.Transfo from link name to Transform3D mapping that link to the world frame. """ if world is None: - world = tf.Transform3d() + world = tf.Transform3d(dtype=self.dtype, device=self.device) + + th_dict = self.ensure_dict_of_2d_tensors(th) + + if world.dtype != self.dtype or world.device != self.device: + world = world.to(dtype=self.dtype, device=self.device, copy=True) + return self._forward_kinematics(self._root, th_dict, world) + + @lru_cache + def get_link_indices(self, *tool_names): + return torch.tensor([self.frame_to_idx[n + '_frame'] for n in tool_names], dtype=torch.long, + device=self.device) + + def forward_kinematics_fast(self, th, link_indices): + """ + Instead of a tree, we can use a flat data structure with indexes to represent the parent + then instead of recursion we can just iterate in order and use parent pointers. This + reduces function call overhead and moves some of the indexing work to the constructor. + """ + if isinstance(th, np.ndarray): + th = torch.tensor(th, device=self.device, dtype=self.dtype) + + th = torch.atleast_2d(th) + + b, n = th.shape + + axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) + + tool_transforms = zpk_cpp.fk( + link_indices, + axes_expanded, + th, + self.parent_indices, + self.is_fixed, + self.joint_indices, + self.joint_offsets, + self.link_offsets + ) + + return tool_transforms + + def ensure_dict_of_2d_tensors(self, th): if not isinstance(th, dict): th, _ = ensure_2d_tensor(th, self.dtype, self.device) jn = self.get_joint_parameter_names() @@ -145,10 +321,86 @@ def forward_kinematics(self, th: torch.tensor, world: typing.Optional[tf.Transfo th_dict = dict((j, th[..., i]) for i, j in enumerate(jn)) else: th_dict = {k: ensure_2d_tensor(v, self.dtype, self.device)[0] for k, v in th.items()} + return th_dict - if world.dtype != self.dtype or world.device != self.device: - world = world.to(dtype=self.dtype, device=self.device, copy=True) - return self._forward_kinematics(self._root, th_dict, world) + def clamp(self, th): + th_dict = self.ensure_dict_of_2d_tensors(th) + + out_th_dict = {} + for joint_name, joint_position in th_dict.items(): + joint = self.find_joint(joint_name) + joint_position_clamped = joint.clamp(joint_position) + out_th_dict[joint_name] = joint_position_clamped + + return self.match_input_type(out_th_dict, th) + + @staticmethod + def match_input_type(th_dict, th): + if isinstance(th, dict): + return th_dict + else: + return torch.stack([v for v in th_dict.values()], dim=-1) + + def get_joint_limits(self): + low = [] + high = [] + for joint_name in self.get_joint_parameter_names(exclude_fixed=True): + joint = self.find_joint(joint_name) + low.append(joint.limits[0]) + high.append(joint.limits[1]) + + return low, high + + @staticmethod + def _get_joints_and_child_links(frame): + joint = frame.joint + + me_and_my_children = [frame.link] + for child in frame.children: + recursive_child_links = yield from Chain._get_joints_and_child_links(child) + me_and_my_children.extend(recursive_child_links) + + if joint is not None and joint.joint_type != 'fixed': + yield joint, me_and_my_children + + return me_and_my_children + + def get_joints_and_child_links(self): + yield from Chain._get_joints_and_child_links(self._root) + + def expected_torques(self, th): + gravity = torch.tensor([0, 0, -9.8], dtype=self.dtype, device=self.device) + poses_dict = self.forward_kinematics(th) + torques_dict = {} + for joint, child_links in self.get_joints_and_child_links(): + # NOTE: assumes joint has not offset from joint_link + joint_link = child_links[0] + # print(joint.name, [l.name for l in child_links]) + child_masses = [] + child_positions = [] + for link in child_links: + child_masses.append(link.mass) + child_positions.append(poses_dict[link.name].get_matrix()[:, :3, 3]) + child_masses = torch.tensor(child_masses, dtype=self.dtype, device=self.device) + child_positions = torch.stack(child_positions, dim=-1) + avg_position = (child_masses[None, None] * child_positions).sum(dim=-1) # add batch_dims + total_mass = torch.sum(child_masses) + joint_pose = poses_dict[joint_link.name].get_matrix() + joint_position = joint_pose[:, :3, 3] + axis_joint_frame = joint.axis[None] # add batch dims + axis_world_frame = transform_direction(joint_pose, axis_joint_frame) + # print(avg_position, total_mass, axis_world_frame, joint_position) + joint_to_avg_pos = avg_position - joint_position + # NOTE: A@B.T is the same as batched dot product + lever_vector = joint_to_avg_pos - axis_world_frame @ joint_to_avg_pos.T * axis_world_frame + force_vector = (total_mass * gravity)[None] + torque_world_frame = torch.cross(lever_vector, force_vector) + torque_joint_frame = transform_direction(torch.linalg.pinv(joint_pose), torque_world_frame) + # print(torque_joint_frame) + torques_dict[joint.name] = torque_joint_frame + + torques = [torques_dict[n] for n in self.get_joint_parameter_names(True)] + return torques class SerialChain(Chain): @@ -214,3 +466,6 @@ def jacobian(self, th, locations=None): if locations is not None: locations = tf.Transform3d(pos=locations) return jacobian.calc_jacobian(self, th, tool=locations) + + def clamp(self, th: torch.tensor): + return th diff --git a/src/pytorch_kinematics/frame.py b/src/pytorch_kinematics/frame.py index 77cc9e2..8a7bbf6 100644 --- a/src/pytorch_kinematics/frame.py +++ b/src/pytorch_kinematics/frame.py @@ -22,7 +22,8 @@ def __repr__(self): class Link(object): - def __init__(self, name=None, offset=None, visuals=()): + def __init__(self, name=None, offset=None, mass=0.0, visuals=()): + self.mass = mass if offset is None: self.offset = None else: @@ -45,7 +46,7 @@ class Joint(object): TYPES = ['fixed', 'revolute', 'prismatic'] def __init__(self, name=None, offset=None, joint_type='fixed', axis=(0.0, 0.0, 1.0), - dtype=torch.float32, device="cpu"): + dtype=torch.float32, device="cpu", limits=None): if offset is None: self.offset = None else: @@ -64,12 +65,20 @@ def __init__(self, name=None, offset=None, joint_type='fixed', axis=(0.0, 0.0, 1 # normalize axis to have norm 1 (needed for correct representation scaling with theta) self.axis = self.axis / self.axis.norm() + self.limits = limits + def to(self, *args, **kwargs): self.axis = self.axis.to(*args, **kwargs) if self.offset is not None: self.offset = self.offset.to(*args, **kwargs) return self + def clamp(self, joint_position): + if self.limits is None: + return joint_position + else: + return torch.clamp(joint_position, self.limits[0], self.limits[1]) + def __repr__(self): return "Joint(name='{0}', offset={1}, joint_type='{2}', axis={3})".format(self.name, self.offset, @@ -78,11 +87,12 @@ def __repr__(self): class Frame(object): - def __init__(self, name=None, link=None, joint=None, children=()): + def __init__(self, name=None, link=None, joint=None, children=None): self.name = 'None' if name is None else name self.link = link if link is not None else Link() self.joint = joint if joint is not None else Joint() - self.children = children + if children is None: + self.children = [] def __str__(self, level=0): ret = " \t" * level + self.name + "\n" diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 4c79f24..a935a29 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -454,7 +454,7 @@ def axis_and_angle_to_matrix_directly(axis, theta): c = torch.cos(theta) # NOTE: cos is not that precise for float32, you may want to use float64 one_minus_c = 1 - c s = torch.sin(theta) - kx, ky, kz = axis + kx, ky, kz = torch.unbind(axis, -1) r00 = c + kx * kx * one_minus_c r01 = kx * ky * one_minus_c - kz * s r02 = kx * kz * one_minus_c + ky * s diff --git a/tests/test_ik_using_gradient_descent.py b/tests/test_ik_using_gradient_descent.py new file mode 100644 index 0000000..8f2428f --- /dev/null +++ b/tests/test_ik_using_gradient_descent.py @@ -0,0 +1,77 @@ +import os + +import torch +from torch.distributions.uniform import Uniform + +import pytorch_kinematics as pk +from pytorch_kinematics import cfg + + +def ik(chain: pk.Chain, target_positions, n_organisms_per_problem=100, max_steps=1000, solved_threshold=1e-3, + verbose: int = 0): + n_ik_problems = target_positions.shape[0] + + population_size = n_ik_problems * n_organisms_per_problem + + target_positions_repeated = target_positions.repeat_interleave(n_organisms_per_problem, dim=0) + target_positions_repeated = target_positions_repeated.to(device=chain.device, dtype=chain.dtype) + + n_joints = len(chain.get_joint_parameter_names()) + th = torch.rand(population_size, n_joints, device=chain.device, dtype=chain.dtype, requires_grad=True) + opt = torch.optim.RMSprop(params=[th], lr=0.03) + for i in range(max_steps): + opt.zero_grad() + + ee_transform = chain.forward_kinematics(th).get_matrix() + + population_loss = (ee_transform[..., :3, 3] - target_positions_repeated).norm(dim=1) + + population_loss_matrix = population_loss.reshape(n_ik_problems, n_organisms_per_problem) + min_loss_per_ik_problem, min_loss_per_ik_problem_idx = population_loss_matrix.min(dim=1) + population_solved = population_loss < solved_threshold + solved = min_loss_per_ik_problem < solved_threshold + if verbose >= 1: + percent_solved = torch.count_nonzero(solved).detach().cpu().numpy() / n_ik_problems + print(f"{i=} {percent_solved:.1%}") + if torch.all(solved): + th_matrix = th.reshape(n_ik_problems, n_organisms_per_problem, -1) + batch_indices = torch.arange(n_ik_problems) + th_solutions = th_matrix[batch_indices, min_loss_per_ik_problem_idx] + return th_solutions + + loss_masked = population_loss * ~population_solved # if we've found a solution, set loss to zero so we don't make it worse + loss_masked = loss_masked.mean(dim=0) + + loss_masked.backward() + + opt.step() + + print("IK Failed!") + return None + + +def solve_random_position_ik(): + d = "cuda" if torch.cuda.is_available() else "cpu" + dtype = torch.float64 + n_ik_problems = 1000 + chain = pk.build_serial_chain_from_urdf(open(os.path.join(cfg.TEST_DIR, "kuka_iiwa.urdf")).read(), + "lbr_iiwa_link_7") + chain = chain.to(dtype=dtype, device=d) + + target_positions_distribution = Uniform(torch.tensor([0.4, 0.4, 0.7]), torch.tensor([0.45, 0.45, 0.75])) + target_positions = target_positions_distribution.sample([n_ik_problems]) + target_positions = target_positions.to(dtype=dtype, device=d) + + from time import perf_counter + t0 = perf_counter() + joint_positions = ik(chain, target_positions) + print(f"{perf_counter() - t0:.4}") + + +def main(): + for _ in range(3): + solve_random_position_ik() + + +if __name__ == '__main__': + main() From cce1d183fdd3a56a4bfc7325643315e8ce38b888 Mon Sep 17 00:00:00 2001 From: Peter Date: Wed, 25 Oct 2023 13:37:11 -0400 Subject: [PATCH 02/34] remove ik test --- tests/test_ik_using_gradient_descent.py | 77 ------------------------- 1 file changed, 77 deletions(-) delete mode 100644 tests/test_ik_using_gradient_descent.py diff --git a/tests/test_ik_using_gradient_descent.py b/tests/test_ik_using_gradient_descent.py deleted file mode 100644 index 8f2428f..0000000 --- a/tests/test_ik_using_gradient_descent.py +++ /dev/null @@ -1,77 +0,0 @@ -import os - -import torch -from torch.distributions.uniform import Uniform - -import pytorch_kinematics as pk -from pytorch_kinematics import cfg - - -def ik(chain: pk.Chain, target_positions, n_organisms_per_problem=100, max_steps=1000, solved_threshold=1e-3, - verbose: int = 0): - n_ik_problems = target_positions.shape[0] - - population_size = n_ik_problems * n_organisms_per_problem - - target_positions_repeated = target_positions.repeat_interleave(n_organisms_per_problem, dim=0) - target_positions_repeated = target_positions_repeated.to(device=chain.device, dtype=chain.dtype) - - n_joints = len(chain.get_joint_parameter_names()) - th = torch.rand(population_size, n_joints, device=chain.device, dtype=chain.dtype, requires_grad=True) - opt = torch.optim.RMSprop(params=[th], lr=0.03) - for i in range(max_steps): - opt.zero_grad() - - ee_transform = chain.forward_kinematics(th).get_matrix() - - population_loss = (ee_transform[..., :3, 3] - target_positions_repeated).norm(dim=1) - - population_loss_matrix = population_loss.reshape(n_ik_problems, n_organisms_per_problem) - min_loss_per_ik_problem, min_loss_per_ik_problem_idx = population_loss_matrix.min(dim=1) - population_solved = population_loss < solved_threshold - solved = min_loss_per_ik_problem < solved_threshold - if verbose >= 1: - percent_solved = torch.count_nonzero(solved).detach().cpu().numpy() / n_ik_problems - print(f"{i=} {percent_solved:.1%}") - if torch.all(solved): - th_matrix = th.reshape(n_ik_problems, n_organisms_per_problem, -1) - batch_indices = torch.arange(n_ik_problems) - th_solutions = th_matrix[batch_indices, min_loss_per_ik_problem_idx] - return th_solutions - - loss_masked = population_loss * ~population_solved # if we've found a solution, set loss to zero so we don't make it worse - loss_masked = loss_masked.mean(dim=0) - - loss_masked.backward() - - opt.step() - - print("IK Failed!") - return None - - -def solve_random_position_ik(): - d = "cuda" if torch.cuda.is_available() else "cpu" - dtype = torch.float64 - n_ik_problems = 1000 - chain = pk.build_serial_chain_from_urdf(open(os.path.join(cfg.TEST_DIR, "kuka_iiwa.urdf")).read(), - "lbr_iiwa_link_7") - chain = chain.to(dtype=dtype, device=d) - - target_positions_distribution = Uniform(torch.tensor([0.4, 0.4, 0.7]), torch.tensor([0.45, 0.45, 0.75])) - target_positions = target_positions_distribution.sample([n_ik_problems]) - target_positions = target_positions.to(dtype=dtype, device=d) - - from time import perf_counter - t0 = perf_counter() - joint_positions = ik(chain, target_positions) - print(f"{perf_counter() - t0:.4}") - - -def main(): - for _ in range(3): - solve_random_position_ik() - - -if __name__ == '__main__': - main() From bf05cba1bebc7a97984d533623e9ead6279ef5c7 Mon Sep 17 00:00:00 2001 From: Peter Date: Wed, 25 Oct 2023 15:09:22 -0400 Subject: [PATCH 03/34] testing performance of rotation conversion functions --- pyproject.toml | 52 ++++--------------- setup.py | 15 ++++++ src/pytorch_kinematics/chain.py | 13 +++-- src/pytorch_kinematics/frame.py | 4 +- src/pytorch_kinematics/transforms/__init__.py | 3 +- .../transforms/rotation_conversions.py | 21 ++++++-- {pytorch_kinematics => src/zpk_cpp}/pk.cpp | 3 +- tests/test_rotation_conversions.py | 46 ++++++++++++---- 8 files changed, 90 insertions(+), 67 deletions(-) create mode 100644 setup.py rename {pytorch_kinematics => src/zpk_cpp}/pk.cpp (96%) diff --git a/pyproject.toml b/pyproject.toml index a25c154..2613289 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -30,59 +30,29 @@ maintainers = [ ] # Classifiers help users find your project by categorizing it. -# # For a list of valid classifiers, see https://pypi.org/classifiers/ classifiers = [# Optional "Development Status :: 4 - Beta", - # Indicate who your project is intended for "Intended Audience :: Developers", - # Pick your license as you wish "License :: OSI Approved :: MIT License", - # Specify the Python versions you support here. In particular, ensure - # that you indicate you support Python 3. These classifiers are *not* - # checked by "pip install". See instead "python_requires" below. "Programming Language :: Python :: 3", "Programming Language :: Python :: 3 :: Only", ] -# This field lists other packages that your project depends on to run. -# Any package you put here will be installed by pip when your project is -# installed, so they must be valid existing projects. -# -# For an analysis of this field vs pip's requirements files see: -# https://packaging.python.org/discussions/install-requires-vs-requirements/ -dependencies = [# Optional - 'torch', - 'numpy', - 'transformations', +dependencies = [ 'absl-py', 'lxml', - 'pyyaml' + 'numpy', + 'pyyaml', + 'torch', + 'transformations', ] -# List additional groups of dependencies here (e.g. development -# dependencies). Users will be able to install these using the "extras" -# syntax, for example: -# -# $ pip install sampleproject[dev] -# -# Similar to `dependencies` above, these must be valid existing -# projects. -[project.optional-dependencies] # Optional +[project.optional-dependencies] test = ["pytest", "mujoco"] mujoco = ["mujoco"] -# List URLs that are relevant to your project -# -# This field corresponds to the "Project-URL" and "Home-Page" metadata fields: -# https://packaging.python.org/specifications/core-metadata/#project-url-multiple-use -# https://packaging.python.org/specifications/core-metadata/#home-page-optional -# -# Examples listed include a pattern for specifying where the package tracks -# issues, where the source is hosted, where to say thanks to the package -# maintainers, and where to support the project financially. The key is -# what's used to render the link text on PyPI. -[project.urls] # Optional +[project.urls] "Homepage" = "https://github.com/UM-ARM-Lab/pytorch_kinematics" "Bug Reports" = "https://github.com/UM-ARM-Lab/pytorch_kinematics/issues" "Source" = "https://github.com/UM-ARM-Lab/pytorch_kinematics" @@ -99,7 +69,7 @@ mujoco = ["mujoco"] # installed, specify them here. [build-system] -# These are the assumed default build requirements from pip: -# https://pip.pypa.io/en/stable/reference/pip/#pep-517-and-518-support -requires = ["setuptools>=43.0.0", "wheel"] -build-backend = "setuptools.build_meta" +# Including torch and ninja here are needed to build the native code. +# They will be installed as dependencies during the build, which can take a while the first time. +requires = ["setuptools>=60.0.0", "wheel", "torch", "ninja"] +build-backend= "setuptools.build_meta" diff --git a/setup.py b/setup.py new file mode 100644 index 0000000..cdb1835 --- /dev/null +++ b/setup.py @@ -0,0 +1,15 @@ +from setuptools import setup, find_packages +from torch.utils import cpp_extension + +# This is needed in order to build the C++ extension +import torch +print(f'>>>>> {torch.__version__} <<<<<') +ext = cpp_extension.CppExtension('zpk_cpp', ['src/zpk_cpp/pk.cpp'], extra_compile_args=['-std=c++17']) +setup_args = dict( + packages=find_packages(where="src"), + package_dir={"": "src"}, + ext_modules=[ext], + cmdclass={'build_ext': cpp_extension.BuildExtension}, +) + +setup(**setup_args) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 03c8289..894552d 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -37,11 +37,10 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.device = device self.identity = torch.eye(4, device=self.device, dtype=self.dtype).unsqueeze(0) - low, high = self.get_joint_limits() - self.low = torch.tensor(low, device=self.device, dtype=self.dtype) - self.high = torch.tensor(high, device=self.device, dtype=self.dtype) - self.sphere_indices = None - self.precompute_fk_info() + # low, high = self.get_joint_limits() + # self.low = torch.tensor(low, device=self.device, dtype=self.dtype) + # self.high = torch.tensor(high, device=self.device, dtype=self.dtype) + # self.precompute_fk_info() def precompute_fk_info(self): self.parent_indices = [] @@ -101,8 +100,8 @@ def to(self, dtype=None, device=None): self.joint_offsets] self.joint_weights = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in self.joint_weights] - self.low = self.low.to(dtype=self.dtype, device=self.device) - self.high = self.high.to(dtype=self.dtype, device=self.device) + # self.low = self.low.to(dtype=self.dtype, device=self.device) + # self.high = self.high.to(dtype=self.dtype, device=self.device) return self diff --git a/src/pytorch_kinematics/frame.py b/src/pytorch_kinematics/frame.py index 8a7bbf6..117ebce 100644 --- a/src/pytorch_kinematics/frame.py +++ b/src/pytorch_kinematics/frame.py @@ -1,7 +1,7 @@ import torch import pytorch_kinematics.transforms as tf -from pytorch_kinematics.transforms import axis_and_angle_to_matrix_directly +from pytorch_kinematics.transforms import axis_and_angle_to_matrix class Visual(object): @@ -116,7 +116,7 @@ def get_transform(self, theta): dtype = self.joint.axis.dtype d = self.joint.axis.device if self.joint.joint_type == 'revolute': - rot = axis_and_angle_to_matrix_directly(self.joint.axis, theta) + rot = axis_and_angle_to_matrix(self.joint.axis, theta) t = tf.Transform3d(rot=rot, dtype=dtype, device=d) elif self.joint.joint_type == 'prismatic': t = tf.Transform3d(pos=theta * self.joint.axis, dtype=dtype, device=d) diff --git a/src/pytorch_kinematics/transforms/__init__.py b/src/pytorch_kinematics/transforms/__init__.py index ea80b37..98cc434 100644 --- a/src/pytorch_kinematics/transforms/__init__.py +++ b/src/pytorch_kinematics/transforms/__init__.py @@ -1,8 +1,7 @@ # Copyright (c) Facebook, Inc. and its affiliates. All rights reserved. from .rotation_conversions import ( - axis_angle_to_matrix, - axis_and_angle_to_matrix_directly, + axis_and_angle_to_matrix, axis_angle_to_quaternion, euler_angles_to_matrix, matrix_to_euler_angles, diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index a935a29..66ea62c 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -2,6 +2,7 @@ import functools from typing import Optional +from warnings import warn import torch import torch.nn.functional as F @@ -449,7 +450,17 @@ def quaternion_apply(quaternion, point): return out[..., 1:] -def axis_and_angle_to_matrix_directly(axis, theta): +def axis_and_angle_to_matrix(axis, theta): + """ + Works with any number of batch dimensions. + + Args: + axis: [..., 3] + theta: [ ...] + + Returns: [..., 3, 3] + + """ # based on https://ai.stackexchange.com/questions/14041/, and checked against wikipedia c = torch.cos(theta) # NOTE: cos is not that precise for float32, you may want to use float64 one_minus_c = 1 - c @@ -464,9 +475,9 @@ def axis_and_angle_to_matrix_directly(axis, theta): r20 = kz * kx * one_minus_c - ky * s r21 = kz * ky * one_minus_c + kx * s r22 = c + kz * kz * one_minus_c - rot = torch.stack([torch.cat([r00, r01, r02], -1), - torch.cat([r10, r11, r12], -1), - torch.cat([r20, r21, r22], -1)], -2) + rot = torch.stack([torch.stack([r00, r01, r02], -1), + torch.stack([r10, r11, r12], -1), + torch.stack([r20, r21, r22], -1)], -2) return rot @@ -485,6 +496,8 @@ def axis_angle_to_matrix(axis_angle): Returns: Rotation matrices as tensor of shape (..., 3, 3). """ + warn('This is deprecated because it is slow. Use axis_and_angle_to_matrix or zpk_cpp.axis_and_angle_to_matrix', + DeprecationWarning, stacklevel=2) return quaternion_to_matrix(axis_angle_to_quaternion(axis_angle)) diff --git a/pytorch_kinematics/pk.cpp b/src/zpk_cpp/pk.cpp similarity index 96% rename from pytorch_kinematics/pk.cpp rename to src/zpk_cpp/pk.cpp index 077db2c..686cc56 100644 --- a/pytorch_kinematics/pk.cpp +++ b/src/zpk_cpp/pk.cpp @@ -10,6 +10,7 @@ torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, * cos is not that precise for float32, you may want to use float64 * axis is [b, n, 3] * theta is [b, n] + * Return is [b, n, 4, 4] */ auto b = axis.size(0); auto n = axis.size(1); @@ -88,6 +89,6 @@ fk(torch::Tensor link_indices, torch::Tensor axes, torch::Tensor th, PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { m.def("axis_and_angle_to_matrix", &axis_and_angle_to_matrix, - "axis_and_angle_to_matrix"); + "axis_and_angle_to_matrix", py::arg("axis"), py::arg("theta")); m.def("fk", &fk, "fk"); } diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index e551be3..266bfb1 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -2,23 +2,46 @@ import torch -from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix_directly, axis_angle_to_matrix, \ +from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix, axis_angle_to_matrix, \ pos_rot_to_matrix, matrix_to_pos_rot, random_rotations +import zpk_cpp def test_axis_angle_to_matrix_perf(): - number = 1_000 + number = 100 N = 1_000 - dt1 = timeit.timeit(lambda: axis_angle_to_matrix(torch.randn([N, 3])), number=number) - print(f'{dt1:.5f}') + axis_angle = torch.randn([N, 3], device='cuda', dtype=torch.float64) + axis_1d = torch.tensor([1., 0, 0], device='cuda', dtype=torch.float64) # in the FK code this is NOT batched! + theta = axis_angle.norm(dim=1, keepdim=False) - dt2 = timeit.timeit( - lambda: axis_and_angle_to_matrix_directly(axis=torch.tensor([1.0, 0, 0]), theta=torch.randn([N, 1])), - number=number) - print(f'{dt2:.5f}') + dt1 = timeit.timeit(lambda: axis_angle_to_matrix(axis_angle), number=number) + print(f'Old method: {dt1:.5f}') - assert dt1 > dt2 + dt2 = timeit.timeit(lambda: axis_and_angle_to_matrix(axis=axis_1d, theta=theta), number=number) + print(f'New method: {dt2:.5f}') + + +def test_axis_angle_to_matrix_perf_zpk(): + # Seems the C++ version is not faster than then python version for this case. + + # now test perf for a higher dim version, which has batches (B) of joints (N) + number = 100 + N = 10 + B = 10_000 + axis = torch.randn([B, N, 3], device='cuda', dtype=torch.float64) + axis = axis / axis.norm(dim=2, keepdim=True) + theta = torch.randn([B, N], device='cuda', dtype=torch.float64) + + dt1 = timeit.timeit(lambda: axis_and_angle_to_matrix(axis, theta), number=number) + print(f'Py: {dt1:.5f}') + + dt2 = timeit.timeit(lambda: zpk_cpp.axis_and_angle_to_matrix(axis, theta), number=number) + print(f'Cpp: {dt2:.5f}') + + a1 = axis_and_angle_to_matrix(axis, theta) + a2 = zpk_cpp.axis_and_angle_to_matrix(axis, theta) + torch.testing.assert_allclose(a1, a2[..., :3, :3]) def test_pos_rot_conversion(): @@ -33,4 +56,7 @@ def test_pos_rot_conversion(): assert torch.allclose(T, TT, atol=1e-6) -test_pos_rot_conversion() +if __name__ == '__main__': + test_axis_angle_to_matrix_perf_zpk() + test_axis_angle_to_matrix_perf() + test_pos_rot_conversion() From f304246707cb6dbcac8f34472e7f7b20ae6c74d8 Mon Sep 17 00:00:00 2001 From: Peter Date: Wed, 25 Oct 2023 15:21:01 -0400 Subject: [PATCH 04/34] updating/refactoring --- src/pytorch_kinematics/chain.py | 52 ++++++++++++++++++++------------- src/pytorch_kinematics/frame.py | 5 ++++ src/pytorch_kinematics/mjcf.py | 8 ++--- src/pytorch_kinematics/urdf.py | 3 +- 4 files changed, 43 insertions(+), 25 deletions(-) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 894552d..57da713 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -14,7 +14,7 @@ def ensure_2d_tensor(th, dtype, device): th = torch.tensor(th, dtype=dtype, device=device) if len(th.shape) <= 1: N = 1 - th = th.view(1, -1) + th = th.reshape(1, -1) else: N = th.shape[0] return th, N @@ -26,10 +26,12 @@ def transform_direction(pose, v): return new_v -class Chain(object): - """Robot model that may be constructed from different descriptions via their respective parsers. +class Chain: + """ + Robot model that may be constructed from different descriptions via their respective parsers. Fundamentally, a robot is modelled as a chain (not necessarily serial) of frames, with each frame - having a physical link and a number of child frames each connected via some joint.""" + having a physical link and a number of child frames each connected via some joint. + """ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self._root = root_frame @@ -37,12 +39,17 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.device = device self.identity = torch.eye(4, device=self.device, dtype=self.dtype).unsqueeze(0) - # low, high = self.get_joint_limits() - # self.low = torch.tensor(low, device=self.device, dtype=self.dtype) - # self.high = torch.tensor(high, device=self.device, dtype=self.dtype) - # self.precompute_fk_info() + + low, high = self.get_joint_limits() + self.low = torch.tensor(low, device=self.device, dtype=self.dtype) + self.high = torch.tensor(high, device=self.device, dtype=self.dtype) + + # FIXME: the init of this class is super confusing + self._precomputed = False def precompute_fk_info(self): + self._precomputed = True + self.parent_indices = [] self.joint_indices = [] n = len(self.get_joint_parameter_names()) @@ -100,8 +107,8 @@ def to(self, dtype=None, device=None): self.joint_offsets] self.joint_weights = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in self.joint_weights] - # self.low = self.low.to(dtype=self.dtype, device=self.device) - # self.high = self.high.to(dtype=self.dtype, device=self.device) + self.low = self.low.to(dtype=self.dtype, device=self.device) + self.high = self.high.to(dtype=self.dtype, device=self.device) return self @@ -146,6 +153,14 @@ def get_joints(self, exclude_fixed=True): joints = self._get_joints(self._root, exclude_fixed=exclude_fixed) return joints + def get_joint_parameter_names(self, exclude_fixed=True): + names = [] + for f in self.get_joints(exclude_fixed=exclude_fixed): + if exclude_fixed and f.joint.joint_type == 'fixed': + continue + names.append(f.joint.name) + return names + @staticmethod def _find_joint_recursive(name, frame): for child in frame.children: @@ -247,7 +262,7 @@ def _forward_kinematics(root, th_dict, world=None): else: trans = world - joint_trans = root.get_transform(th.view(N, 1)) + joint_trans = root.get_transform(th.reshape(N, 1)) trans = trans.compose(joint_trans) link_transforms[root.link.name] = trans @@ -290,6 +305,10 @@ def forward_kinematics_fast(self, th, link_indices): then instead of recursion we can just iterate in order and use parent pointers. This reduces function call overhead and moves some of the indexing work to the constructor. """ + if not self._precomputed: + print("Precomputing FK info...") + self.precompute_fk_info() + if isinstance(th, np.ndarray): th = torch.tensor(th, device=self.device, dtype=self.dtype) @@ -428,14 +447,6 @@ def _generate_serial_chain_recurse(root_frame, end_frame_name): return [child] + frames return None - def get_joint_parameter_names(self, exclude_fixed=True): - names = [] - for f in self._serial_frames: - if exclude_fixed and f.joint.joint_type == 'fixed': - continue - names.append(f.joint.name) - return names - def forward_kinematics(self, th, world=None, end_only=True): if world is None: world = tf.Transform3d() @@ -454,7 +465,8 @@ def forward_kinematics(self, th, world=None, end_only=True): if f.joint.joint_type == "fixed": # If fixed trans = trans.compose(f.get_transform(zeros)) else: - trans = trans.compose(f.get_transform(th[:, theta_idx].view(N, 1))) + # trans = trans.compose(f.get_transform(th[:, theta_idx].reshape(N, 1))) + trans = trans.compose(f.get_transform(th[:, theta_idx])) theta_idx += 1 link_transforms[f.link.name] = trans diff --git a/src/pytorch_kinematics/frame.py b/src/pytorch_kinematics/frame.py index 117ebce..e951530 100644 --- a/src/pytorch_kinematics/frame.py +++ b/src/pytorch_kinematics/frame.py @@ -65,6 +65,11 @@ def __init__(self, name=None, offset=None, joint_type='fixed', axis=(0.0, 0.0, 1 # normalize axis to have norm 1 (needed for correct representation scaling with theta) self.axis = self.axis / self.axis.norm() + if limits is None: + if joint_type != 'fixed': + raise RuntimeError("limits must be specified for joint {}".format(name)) + else: + self.limits = (0.0, 0.0) self.limits = limits def to(self, *args, **kwargs): diff --git a/src/pytorch_kinematics/mjcf.py b/src/pytorch_kinematics/mjcf.py index 6e703d9..b9ca761 100644 --- a/src/pytorch_kinematics/mjcf.py +++ b/src/pytorch_kinematics/mjcf.py @@ -39,12 +39,12 @@ def _build_chain_recurse(m, parent_frame, parent_body): for jntid in body.jntadr: joint = m.joint(jntid) child_joint = frame.Joint(joint.name, tf.Transform3d(pos=joint.pos), axis=joint.axis, - joint_type=JOINT_TYPE_MAP[joint.type[0]]) + joint_type=JOINT_TYPE_MAP[joint.type[0]], limits=(joint.range[0], joint.range[1])) else: child_joint = frame.Joint(body.name + "_fixed_joint") child_link = frame.Link(body.name, offset=tf.Transform3d(rot=body.quat, pos=body.pos)) child_frame = frame.Frame(name=body.name, link=child_link, joint=child_joint) - parent_frame.children = parent_frame.children + (child_frame,) + parent_frame.children = parent_frame.children + [child_frame,] _build_chain_recurse(m, child_frame, body) # iterate through all sites that are children of parent_body @@ -53,10 +53,10 @@ def _build_chain_recurse(m, parent_frame, parent_body): if site.bodyid == parent_body.id: site_link = frame.Link(site.name, offset=tf.Transform3d(rot=site.quat, pos=site.pos)) site_frame = frame.Frame(name=site.name, link=site_link) - parent_frame.children = parent_frame.children + (site_frame,) + parent_frame.children = parent_frame.children + [site_frame,] -def build_chain_from_mjcf(data, body: Union[None, str, int] = None): +def build_chain_from_mjcf(data, body: Union[None, str, int] = None, ee_links=None): """ Build a Chain object from MJCF data. diff --git a/src/pytorch_kinematics/urdf.py b/src/pytorch_kinematics/urdf.py index 1ff8700..039fbd8 100644 --- a/src/pytorch_kinematics/urdf.py +++ b/src/pytorch_kinematics/urdf.py @@ -47,9 +47,10 @@ def _build_chain_recurse(root_frame, lmap, joints): children = [] for j in joints: if j.parent == root_frame.link.name: + child_frame = frame.Frame(j.child + "_frame") child_frame.joint = frame.Joint(j.name, offset=_convert_transform(j.origin), - joint_type=JOINT_TYPE_MAP[j.type], axis=j.axis) + joint_type=JOINT_TYPE_MAP[j.type], axis=j.axis, limits=(j.limit.lower, j.limit.upper)) link = lmap[j.child] child_frame.link = frame.Link(link.name, offset=_convert_transform(link.origin), visuals=[_convert_visual(link.visual)]) From eaa4fca348e575b4d385551fd7534973104c1a09 Mon Sep 17 00:00:00 2001 From: Peter Date: Wed, 25 Oct 2023 15:49:36 -0400 Subject: [PATCH 05/34] perf test for kuka and val --- src/pytorch_kinematics/chain.py | 5 +- src/pytorch_kinematics/jacobian.py | 4 +- src/pytorch_kinematics/mjcf.py | 2 +- src/pytorch_kinematics/urdf.py | 2 +- tests/test_fk_perf.py | 63 +++++++ tests/val.xml | 288 +++++++++++++++++++++++++++++ 6 files changed, 357 insertions(+), 7 deletions(-) create mode 100644 tests/test_fk_perf.py create mode 100644 tests/val.xml diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 57da713..35af89b 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -295,8 +295,8 @@ def forward_kinematics(self, th: torch.tensor, world: Optional[tf.Transform3d] = return self._forward_kinematics(self._root, th_dict, world) @lru_cache - def get_link_indices(self, *tool_names): - return torch.tensor([self.frame_to_idx[n + '_frame'] for n in tool_names], dtype=torch.long, + def get_frame_indices(self, *frame_names): + return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long, device=self.device) def forward_kinematics_fast(self, th, link_indices): @@ -414,7 +414,6 @@ def expected_torques(self, th): force_vector = (total_mass * gravity)[None] torque_world_frame = torch.cross(lever_vector, force_vector) torque_joint_frame = transform_direction(torch.linalg.pinv(joint_pose), torque_world_frame) - # print(torque_joint_frame) torques_dict[joint.name] = torque_joint_frame torques = [torques_dict[n] for n in self.get_joint_parameter_names(True)] diff --git a/src/pytorch_kinematics/jacobian.py b/src/pytorch_kinematics/jacobian.py index 941c4c4..fe03c43 100644 --- a/src/pytorch_kinematics/jacobian.py +++ b/src/pytorch_kinematics/jacobian.py @@ -18,7 +18,7 @@ def calc_jacobian(serial_chain, th, tool=None): th = torch.tensor(th, dtype=serial_chain.dtype, device=serial_chain.device) if len(th.shape) <= 1: N = 1 - th = th.view(1, -1) + th = th.reshape(1, -1) else: N = th.shape[0] ndof = th.shape[1] @@ -47,7 +47,7 @@ def calc_jacobian(serial_chain, th, tool=None): elif f.joint.joint_type == "prismatic": cnt += 1 j_eef[:, :3, -cnt] = f.joint.axis.repeat(N, 1) @ cur_transform[:, :3, :3] - cur_frame_transform = f.get_transform(th[:, -cnt].view(N, 1)).get_matrix() + cur_frame_transform = f.get_transform(th[:, -cnt]).get_matrix() cur_transform = cur_frame_transform @ cur_transform # currently j_eef is Jacobian in end-effector frame, convert to base/world frame diff --git a/src/pytorch_kinematics/mjcf.py b/src/pytorch_kinematics/mjcf.py index b9ca761..50f86c5 100644 --- a/src/pytorch_kinematics/mjcf.py +++ b/src/pytorch_kinematics/mjcf.py @@ -56,7 +56,7 @@ def _build_chain_recurse(m, parent_frame, parent_body): parent_frame.children = parent_frame.children + [site_frame,] -def build_chain_from_mjcf(data, body: Union[None, str, int] = None, ee_links=None): +def build_chain_from_mjcf(data, body: Union[None, str, int] = None): """ Build a Chain object from MJCF data. diff --git a/src/pytorch_kinematics/urdf.py b/src/pytorch_kinematics/urdf.py index 039fbd8..a318871 100644 --- a/src/pytorch_kinematics/urdf.py +++ b/src/pytorch_kinematics/urdf.py @@ -105,7 +105,7 @@ def build_chain_from_urdf(data): if has_root[i]: root_link = lmap[joints[i].parent] break - root_frame = frame.Frame(root_link.name + "_frame") + root_frame = frame.Frame(root_link.name) root_frame.joint = frame.Joint() root_frame.link = frame.Link(root_link.name, _convert_transform(root_link.origin), [_convert_visual(root_link.visual)]) diff --git a/tests/test_fk_perf.py b/tests/test_fk_perf.py new file mode 100644 index 0000000..7166036 --- /dev/null +++ b/tests/test_fk_perf.py @@ -0,0 +1,63 @@ +import timeit +from time import perf_counter +import torch + +import pytorch_kinematics as pk +import numpy as np + +N = 10000 +number = 100 + + +def test_val_fk_perf(): + val = pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool') + val.precompute_fk_info() + val.get_frame_names() + val = val.to(dtype=torch.float32, device='cuda') + + th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') + print(len(val.get_joint_parameter_names())) + + def _val_old_fk(): + tg = val.forward_kinematics(th, end_only=True) + old_m = tg.get_matrix() + return old_m + + val_old_dt = timeit.timeit(_val_old_fk, number=number) + print(f'Val FK OLD dt: {val_old_dt / number:.4f}') + + link_indices = val.get_frame_indices('left_tool') + val_new_dt = timeit.timeit(lambda: val.forward_kinematics_fast(th, link_indices), number=number) + print(f'Val FK NEW dt: {val_new_dt / number:.4f}') + + assert val_old_dt > val_new_dt + + +def test_kuka_fk_perf(): + kuka = pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7') + kuka.precompute_fk_info() + kuka = kuka.to(dtype=torch.float32, device='cuda') + + th = torch.zeros(N, 7, dtype=torch.float32, device='cuda') + + def _kuka_old_fk(): + tg = kuka.forward_kinematics(th, end_only=True) + old_m = tg.get_matrix() + return old_m + + kuka_old_dt = timeit.timeit(_kuka_old_fk, number=number) + print(f'Kuka FK OLD dt: {kuka_old_dt / number:.4f}') + + link_indices = kuka.get_frame_indices('lbr_iiwa_link_7' + '_frame') + kuka_new_dt = timeit.timeit(lambda: kuka.forward_kinematics_fast(th, link_indices), number=number) + print(f'Kuka FK NEW dt: {kuka_new_dt / number:.4f}') + + assert kuka_old_dt > kuka_new_dt + + +if __name__ == '__main__': + np.set_printoptions(precision=3, suppress=True, linewidth=220) + torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) + + test_val_fk_perf() + test_kuka_fk_perf() diff --git a/tests/val.xml b/tests/val.xml new file mode 100644 index 0000000..f528950 --- /dev/null +++ b/tests/val.xml @@ -0,0 +1,288 @@ + + + From ae718a0260b1fb117e38f75aec55e67b5bc08614 Mon Sep 17 00:00:00 2001 From: Peter Date: Wed, 25 Oct 2023 17:14:51 -0400 Subject: [PATCH 06/34] fully replace old FK method with new one since I confirmed it is faster dealing with keeping the API the same --- src/pytorch_kinematics/chain.py | 197 ++++++++---------- src/pytorch_kinematics/frame.py | 5 - src/pytorch_kinematics/jacobian.py | 2 +- src/pytorch_kinematics/mjcf.py | 2 +- src/pytorch_kinematics/sdf.py | 14 +- .../transforms/rotation_conversions.py | 6 +- src/pytorch_kinematics/urdf.py | 19 +- tests/test_fk_perf.py | 2 - tests/test_kinematics.py | 85 ++++---- tests/test_rotation_conversions.py | 25 +-- 10 files changed, 159 insertions(+), 198 deletions(-) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 35af89b..35bc0d5 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -3,10 +3,11 @@ import numpy as np import torch + import pytorch_kinematics.transforms as tf -from pytorch_kinematics.frame import Frame, Link -from pytorch_kinematics import jacobian import zpk_cpp +from pytorch_kinematics import jacobian +from pytorch_kinematics.frame import Frame, Link def ensure_2d_tensor(th, dtype, device): @@ -44,16 +45,10 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.low = torch.tensor(low, device=self.device, dtype=self.dtype) self.high = torch.tensor(high, device=self.device, dtype=self.dtype) - # FIXME: the init of this class is super confusing - self._precomputed = False - - def precompute_fk_info(self): - self._precomputed = True - self.parent_indices = [] self.joint_indices = [] - n = len(self.get_joint_parameter_names()) - self.axes = torch.zeros([n, 3], dtype=self.dtype, device=self.device) + self.n_joints = len(self.get_joint_parameter_names()) + self.axes = torch.zeros([self.n_joints, 3], dtype=self.dtype, device=self.device) self.is_fixed = [] self.link_offsets = [] self.joint_offsets = [] @@ -61,10 +56,12 @@ def precompute_fk_info(self): queue.insert(-1, (self._root, -1, 0)) idx = 0 self.frame_to_idx = {} - self.joint_weights = torch.zeros([n], dtype=self.dtype, device=self.device) + self.idx_to_frame = {} while len(queue) > 0: root, parent_idx, depth = queue.pop(0) - self.frame_to_idx[root.name.strip("\n")] = idx + name_strip = root.name.strip("\n") + self.frame_to_idx[name_strip] = idx + self.idx_to_frame[idx] = name_strip self.parent_indices.append(parent_idx) self.is_fixed.append(root.joint.joint_type == 'fixed') @@ -84,14 +81,12 @@ def precompute_fk_info(self): jnt_idx = self.get_joint_parameter_names().index(root.joint.name) self.axes[jnt_idx] = root.joint.axis self.joint_indices.append(jnt_idx) - self.joint_weights[jnt_idx] = depth for child in root.children: queue.append((child, idx, depth + 1)) idx += 1 self.joint_indices = torch.tensor(self.joint_indices) - self.joint_weights = self.joint_weights / self.joint_weights.norm() def to(self, dtype=None, device=None): if dtype is not None: @@ -105,8 +100,6 @@ def to(self, dtype=None, device=None): self.link_offsets = [l if l is None else l.to(dtype=self.dtype, device=self.device) for l in self.link_offsets] self.joint_offsets = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in self.joint_offsets] - self.joint_weights = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in - self.joint_weights] self.low = self.low.to(dtype=self.dtype, device=self.device) self.high = self.high.to(dtype=self.dtype, device=self.device) @@ -220,11 +213,6 @@ def get_frame_names(self, exclude_fixed=True): names = self._get_frame_names(self._root, exclude_fixed) return sorted(set(names), key=names.index) - def add_frame(self, frame, parent_name): - frame = self.find_frame(parent_name) - if not frame is None: - frame.add_child(frame) - @staticmethod def _get_links(frame): links = [frame.link] @@ -247,70 +235,24 @@ def get_link_names(self): names = self._get_link_names(self._root) return sorted(set(names), key=names.index) - @staticmethod - def _forward_kinematics(root, th_dict, world=None): - if world is None: - world = tf.Transform3d() - link_transforms = {} - - N = next(iter(th_dict.values())).shape[0] - zeros = torch.zeros([N, 1], dtype=world.dtype, device=world.device) - th = th_dict.get(root.joint.name, zeros) - - if root.link.offset is not None: - trans = world.compose(root.link.offset) - else: - trans = world - - joint_trans = root.get_transform(th.reshape(N, 1)) - trans = trans.compose(joint_trans) - link_transforms[root.link.name] = trans - - for child in root.children: - link_transforms.update(Chain._forward_kinematics(child, th_dict, trans)) - return link_transforms - - def forward_kinematics(self, th: torch.tensor, world: Optional[tf.Transform3d] = None, end_only=True): - """ - Return Transform3D wrappers around 4x4 homogenous transform matrices (called H) - that map points in link frame to world frame (via left multiplication Hx). Specifically, - (world)H(link), so it expects points in link coordinates on the right and results in world - frame coordinates. - :param th: B x J joint values, where B is any number of batch dimensions (including 0) and - J is the number of joints - :param world: Transform3D representing the (world)B(base) transform; if omitted, the base frame - is assumed to lie at the world origin. - :param end_only: Whether only the end-effector (for serial chains) transform should be returned. - This parameter does nothing for non-serial chains, but are there for API consistency. - :return: If end_only, then a single Transform3D mapping end effector to world. Else, a dictionary - from link name to Transform3D mapping that link to the world frame. - """ - if world is None: - world = tf.Transform3d(dtype=self.dtype, device=self.device) - - th_dict = self.ensure_dict_of_2d_tensors(th) - - if world.dtype != self.dtype or world.device != self.device: - world = world.to(dtype=self.dtype, device=self.device, copy=True) - return self._forward_kinematics(self._root, th_dict, world) - @lru_cache def get_frame_indices(self, *frame_names): return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long, device=self.device) - def forward_kinematics_fast(self, th, link_indices): + def forward_kinematics(self, th, frame_indices: Optional = None): """ Instead of a tree, we can use a flat data structure with indexes to represent the parent then instead of recursion we can just iterate in order and use parent pointers. This reduces function call overhead and moves some of the indexing work to the constructor. + + use `get_frame_indices` to get the indices for the frames you want to compute the pose for. """ - if not self._precomputed: - print("Precomputing FK info...") - self.precompute_fk_info() + if frame_indices is None: + frame_indices = self.get_all_frame_indices() - if isinstance(th, np.ndarray): - th = torch.tensor(th, device=self.device, dtype=self.dtype) + # ensure th is a tensor or a dict + th = self.ensure_tensor(th) th = torch.atleast_2d(th) @@ -319,7 +261,7 @@ def forward_kinematics_fast(self, th, link_indices): axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) tool_transforms = zpk_cpp.fk( - link_indices, + frame_indices, axes_expanded, th, self.parent_indices, @@ -329,14 +271,35 @@ def forward_kinematics_fast(self, th, link_indices): self.link_offsets ) - return tool_transforms + tool_transforms_dict = {self.idx_to_frame[frame_idx.item()]: transform for frame_idx, transform in + zip(frame_indices, tool_transforms)} + + return tool_transforms_dict + + def ensure_tensor(self, th): + if isinstance(th, np.ndarray): + th = torch.tensor(th, device=self.device, dtype=self.dtype) + if isinstance(th, list): + th = torch.tensor(th, device=self.device, dtype=self.dtype) + if isinstance(th, dict): + # convert dict to a flat, complete, tensor of all joints values. Missing joints are filled with zeros. + th_dict = th + th = torch.zeros(self.n_joints, device=self.device, dtype=self.dtype) + joint_names = self.get_joint_parameter_names() + for joint_name, joint_position in th_dict.items(): + jnt_idx = joint_names.index(joint_name) + th[jnt_idx] = joint_position + return th + + def get_all_frame_indices(self): + frame_indices = self.get_frame_indices(*self.get_frame_names(exclude_fixed=False)) + return frame_indices def ensure_dict_of_2d_tensors(self, th): if not isinstance(th, dict): th, _ = ensure_2d_tensor(th, self.dtype, self.device) - jn = self.get_joint_parameter_names() - assert len(jn) == th.shape[-1] - th_dict = dict((j, th[..., i]) for i, j in enumerate(jn)) + assert self.n_joints == th.shape[-1] + th_dict = dict((j, th[..., i]) for i, j in enumerate(self.get_joint_parameter_names())) else: th_dict = {k: ensure_2d_tensor(v, self.dtype, self.device)[0] for k, v in th.items()} return th_dict @@ -364,8 +327,12 @@ def get_joint_limits(self): high = [] for joint_name in self.get_joint_parameter_names(exclude_fixed=True): joint = self.find_joint(joint_name) - low.append(joint.limits[0]) - high.append(joint.limits[1]) + if joint.limits is None: + low.append(-np.pi) + high.append(np.pi) + else: + low.append(joint.limits[0]) + high.append(joint.limits[1]) return low, high @@ -388,7 +355,8 @@ def get_joints_and_child_links(self): def expected_torques(self, th): gravity = torch.tensor([0, 0, -9.8], dtype=self.dtype, device=self.device) - poses_dict = self.forward_kinematics(th) + frame_indices = self.get_all_frame_indices() + poses_dict = self.forward_kinematics(th, frame_indices) torques_dict = {} for joint, child_links in self.get_joints_and_child_links(): # NOTE: assumes joint has not offset from joint_link @@ -421,14 +389,16 @@ def expected_torques(self, th): class SerialChain(Chain): - """A serial Chain specialization with no branches and clearly defined end effector. - Note that serial chains can be generated from subsets of a Chain.""" + """ + A serial Chain specialization with no branches and clearly defined end effector. + Serial chains can be generated from subsets of a Chain. + """ def __init__(self, chain, end_frame_name, root_frame_name="", **kwargs): if root_frame_name == "": - super(SerialChain, self).__init__(chain._root, **kwargs) + super().__init__(chain._root, **kwargs) else: - super(SerialChain, self).__init__(chain.find_frame(root_frame_name), **kwargs) + super().__init__(chain.find_frame(root_frame_name), **kwargs) if self._root is None: raise ValueError("Invalid root frame name %s." % root_frame_name) self._serial_frames = [self._root] + self._generate_serial_chain_recurse(self._root, end_frame_name) @@ -446,36 +416,35 @@ def _generate_serial_chain_recurse(root_frame, end_frame_name): return [child] + frames return None - def forward_kinematics(self, th, world=None, end_only=True): - if world is None: - world = tf.Transform3d() - if world.dtype != self.dtype or world.device != self.device: - world = world.to(dtype=self.dtype, device=self.device, copy=True) - th, N = ensure_2d_tensor(th, self.dtype, self.device) - zeros = torch.zeros([N, 1], dtype=world.dtype, device=world.device) - - theta_idx = 0 - link_transforms = {} - trans = tf.Transform3d(matrix=world.get_matrix().repeat(N, 1, 1)) - for f in self._serial_frames: - if f.link.offset is not None: - trans = trans.compose(f.link.offset) - - if f.joint.joint_type == "fixed": # If fixed - trans = trans.compose(f.get_transform(zeros)) - else: - # trans = trans.compose(f.get_transform(th[:, theta_idx].reshape(N, 1))) - trans = trans.compose(f.get_transform(th[:, theta_idx])) - theta_idx += 1 - - link_transforms[f.link.name] = trans - - return link_transforms[self._serial_frames[-1].link.name] if end_only else link_transforms - def jacobian(self, th, locations=None): if locations is not None: locations = tf.Transform3d(pos=locations) return jacobian.calc_jacobian(self, th, tool=locations) - def clamp(self, th: torch.tensor): - return th + def forward_kinematics(self, th, end_only: bool = True): + if end_only: + frame_indices = self.get_frame_indices(self._serial_frames[-1].name) + else: + # pass through default behavior for frame indices being None, which is currently + # to return all frames. + frame_indices = None + + if len(th) < self.n_joints: + # if it's not the same length as the number of joints, then we assume it's a list of joints from the root + # up until the end effector. + partial_th = th + nonfixed_serial_frames = list(filter(lambda f: f.joint.joint_type != 'fixed', self._serial_frames)) + if len(nonfixed_serial_frames) != len(partial_th): + raise ValueError(f'Expected {len(nonfixed_serial_frames)} joint values, got {len(partial_th)}.') + th = torch.zeros(self.n_joints, device=self.device, dtype=self.dtype) + for frame, partial_th_i in zip(nonfixed_serial_frames, partial_th): + k = self.frame_to_idx[frame.name] + jnt_idx = self.joint_indices[k] + if frame.joint.joint_type != 'fixed': + th[jnt_idx] = partial_th_i + + mat = super().forward_kinematics(th, frame_indices) + if end_only: + return mat[self._serial_frames[-1].name] + else: + return mat diff --git a/src/pytorch_kinematics/frame.py b/src/pytorch_kinematics/frame.py index e951530..117ebce 100644 --- a/src/pytorch_kinematics/frame.py +++ b/src/pytorch_kinematics/frame.py @@ -65,11 +65,6 @@ def __init__(self, name=None, offset=None, joint_type='fixed', axis=(0.0, 0.0, 1 # normalize axis to have norm 1 (needed for correct representation scaling with theta) self.axis = self.axis / self.axis.norm() - if limits is None: - if joint_type != 'fixed': - raise RuntimeError("limits must be specified for joint {}".format(name)) - else: - self.limits = (0.0, 0.0) self.limits = limits def to(self, *args, **kwargs): diff --git a/src/pytorch_kinematics/jacobian.py b/src/pytorch_kinematics/jacobian.py index fe03c43..abb21c7 100644 --- a/src/pytorch_kinematics/jacobian.py +++ b/src/pytorch_kinematics/jacobian.py @@ -47,7 +47,7 @@ def calc_jacobian(serial_chain, th, tool=None): elif f.joint.joint_type == "prismatic": cnt += 1 j_eef[:, :3, -cnt] = f.joint.axis.repeat(N, 1) @ cur_transform[:, :3, :3] - cur_frame_transform = f.get_transform(th[:, -cnt]).get_matrix() + cur_frame_transform = f.get_transform(th[:, -cnt].reshape(N, 1)).get_matrix() cur_transform = cur_frame_transform @ cur_transform # currently j_eef is Jacobian in end-effector frame, convert to base/world frame diff --git a/src/pytorch_kinematics/mjcf.py b/src/pytorch_kinematics/mjcf.py index 50f86c5..1e43d79 100644 --- a/src/pytorch_kinematics/mjcf.py +++ b/src/pytorch_kinematics/mjcf.py @@ -77,7 +77,7 @@ def build_chain_from_mjcf(data, body: Union[None, str, int] = None): root_body = m.body(0) else: root_body = m.body(body) - root_frame = frame.Frame(root_body.name + "_frame", + root_frame = frame.Frame(root_body.name, link=frame.Link(root_body.name, offset=tf.Transform3d(rot=root_body.quat, pos=root_body.pos)), joint=frame.Joint()) diff --git a/src/pytorch_kinematics/sdf.py b/src/pytorch_kinematics/sdf.py index 2b275e9..22be504 100644 --- a/src/pytorch_kinematics/sdf.py +++ b/src/pytorch_kinematics/sdf.py @@ -5,9 +5,9 @@ from . import chain import pytorch_kinematics.transforms as tf -JOINT_TYPE_MAP = {'revolute': 'revolute', +JOINT_TYPE_MAP = {'revolute': 'revolute', 'prismatic': 'prismatic', - 'fixed': 'fixed'} + 'fixed': 'fixed'} def _convert_transform(pose): @@ -46,13 +46,17 @@ def _build_chain_recurse(root_frame, lmap, joints): children = [] for j in joints: if j.parent == root_frame.link.name: - child_frame = frame.Frame(j.child + "_frame") + child_frame = frame.Frame(j.child) link_p = lmap[j.parent] link_c = lmap[j.child] t_p = _convert_transform(link_p.pose) t_c = _convert_transform(link_c.pose) + try: + limits = (j.axis.limit.lower, j.axis.limit.upper) + except AttributeError: + limits = None child_frame.joint = frame.Joint(j.name, offset=t_p.inverse().compose(t_c), - joint_type=JOINT_TYPE_MAP[j.type], axis=j.axis.xyz) + joint_type=JOINT_TYPE_MAP[j.type], axis=j.axis.xyz, limits=limits) child_frame.link = frame.Link(link_c.name, offset=tf.Transform3d(), visuals=_convert_visuals(link_c.visuals)) child_frame.children = _build_chain_recurse(child_frame, lmap, joints) @@ -90,7 +94,7 @@ def build_chain_from_sdf(data): if has_root[i]: root_link = lmap[joints[i].parent] break - root_frame = frame.Frame(root_link.name + "_frame") + root_frame = frame.Frame(root_link.name) root_frame.joint = frame.Joint(offset=_convert_transform(root_link.pose)) root_frame.link = frame.Link(root_link.name, tf.Transform3d(), _convert_visuals(root_link.visuals)) diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 66ea62c..01358ed 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -475,9 +475,9 @@ def axis_and_angle_to_matrix(axis, theta): r20 = kz * kx * one_minus_c - ky * s r21 = kz * ky * one_minus_c + kx * s r22 = c + kz * kz * one_minus_c - rot = torch.stack([torch.stack([r00, r01, r02], -1), - torch.stack([r10, r11, r12], -1), - torch.stack([r20, r21, r22], -1)], -2) + rot = torch.cat([torch.cat([r00, r01, r02], -1), + torch.cat([r10, r11, r12], -1), + torch.cat([r20, r21, r22], -1)], -2) return rot diff --git a/src/pytorch_kinematics/urdf.py b/src/pytorch_kinematics/urdf.py index a318871..cc56631 100644 --- a/src/pytorch_kinematics/urdf.py +++ b/src/pytorch_kinematics/urdf.py @@ -6,10 +6,10 @@ # has better RPY to quaternion transformation import transformations as tf2 -JOINT_TYPE_MAP = {'revolute': 'revolute', +JOINT_TYPE_MAP = {'revolute': 'revolute', 'continuous': 'revolute', - 'prismatic': 'prismatic', - 'fixed': 'fixed'} + 'prismatic': 'prismatic', + 'fixed': 'fixed'} def _convert_transform(origin): @@ -47,10 +47,13 @@ def _build_chain_recurse(root_frame, lmap, joints): children = [] for j in joints: if j.parent == root_frame.link.name: - - child_frame = frame.Frame(j.child + "_frame") + try: + limits = (j.limit.lower, j.limit.upper) + except AttributeError: + limits = None + child_frame = frame.Frame(j.child) child_frame.joint = frame.Joint(j.name, offset=_convert_transform(j.origin), - joint_type=JOINT_TYPE_MAP[j.type], axis=j.axis, limits=(j.limit.lower, j.limit.upper)) + joint_type=JOINT_TYPE_MAP[j.type], axis=j.axis, limits=limits) link = lmap[j.child] child_frame.link = frame.Link(link.name, offset=_convert_transform(link.origin), visuals=[_convert_visual(link.visual)]) @@ -132,5 +135,5 @@ def build_serial_chain_from_urdf(data, end_link_name, root_link_name=""): SerialChain object created from URDF. """ urdf_chain = build_chain_from_urdf(data) - return chain.SerialChain(urdf_chain, end_link_name + "_frame", - "" if root_link_name == "" else root_link_name + "_frame") + return chain.SerialChain(urdf_chain, end_link_name, + "" if root_link_name == "" else root_link_name) diff --git a/tests/test_fk_perf.py b/tests/test_fk_perf.py index 7166036..e6e90b9 100644 --- a/tests/test_fk_perf.py +++ b/tests/test_fk_perf.py @@ -11,7 +11,6 @@ def test_val_fk_perf(): val = pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool') - val.precompute_fk_info() val.get_frame_names() val = val.to(dtype=torch.float32, device='cuda') @@ -35,7 +34,6 @@ def _val_old_fk(): def test_kuka_fk_perf(): kuka = pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7') - kuka.precompute_fk_info() kuka = kuka.to(dtype=torch.float32, device='cuda') th = torch.zeros(N, 7, dtype=torch.float32, device='cuda') diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 9040c86..985fba5 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -1,5 +1,5 @@ -import os import math +import os import torch @@ -8,10 +8,18 @@ TEST_DIR = os.path.dirname(__file__) -def quat_pos_from_transform3d(tg): - m = tg.get_matrix() - pos = m[:, :3, 3] - rot = pk.matrix_to_quaternion(m[:, :3, :3]) +def quat_pos_from_mat(mat): + """ + Splits 4x4 matrices into position and quternion. Any number of batch dimensions is supported. + + Args: + mat: [..., 4, 4] + + Returns: + + """ + pos = mat[..., :3, 3] + rot = pk.matrix_to_quaternion(mat[..., :3, :3]) return pos, rot @@ -28,12 +36,12 @@ def test_fk_mjcf(): print(chain.get_joint_parameter_names()) th = {'hip_1': 1.0, 'ankle_1': 1} ret = chain.forward_kinematics(th) - tg = ret['aux_1'] - pos, rot = quat_pos_from_transform3d(tg) + m = ret['aux_1'] + pos, rot = quat_pos_from_mat(m) assert quaternion_equality(rot, torch.tensor([0.87758256, 0., 0., 0.47942554], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.2, 0.2, 0.75], dtype=torch.float64)) - tg = ret['front_left_foot'] - pos, rot = quat_pos_from_transform3d(tg) + m = ret['front_left_foot'] + pos, rot = quat_pos_from_mat(m) assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) print(ret) @@ -42,11 +50,19 @@ def test_fk_mjcf(): def test_fk_serial_mjcf(): chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_left_foot') chain = chain.to(dtype=torch.float64) - tg = chain.forward_kinematics([1.0, 1.0]) - pos, rot = quat_pos_from_transform3d(tg) + mat = chain.forward_kinematics([1.0, 1.0]) + pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) + chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_right_foot') + chain = chain.to(dtype=torch.float64) + mat = chain.forward_kinematics([1.0, 1.0]) + + chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'right_back_foot') + chain = chain.to(dtype=torch.float64) + mat = chain.forward_kinematics([1.0, 1.0]) + def test_fkik(): data = '' \ @@ -66,22 +82,21 @@ def test_fkik(): '' chain = pk.build_serial_chain_from_urdf(data, 'link3') th1 = torch.tensor([0.42553542, 0.17529176]) - tg = chain.forward_kinematics(th1) - pos, rot = quat_pos_from_transform3d(tg) + mat = chain.forward_kinematics(th1) + pos, rot = quat_pos_from_mat(mat) assert torch.allclose(pos, torch.tensor([[1.91081784, 0.41280851, 0.0000]])) assert quaternion_equality(rot, torch.tensor([[0.95521418, 0.0000, 0.0000, 0.2959153]])) N = 20 th_batch = torch.rand(N, 2) - tg_batch = chain.forward_kinematics(th_batch) - m = tg_batch.get_matrix() + mat_batch = chain.forward_kinematics(th_batch) for i in range(N): - tg = chain.forward_kinematics(th_batch[i]) - assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) + mat_i = chain.forward_kinematics(th_batch[i]) + assert torch.allclose(mat_i, mat_batch[i]) # check that gradients are passed through th2 = torch.tensor([0.42553542, 0.17529176], requires_grad=True) - tg = chain.forward_kinematics(th2) - pos, rot = quat_pos_from_transform3d(tg) + mat = chain.forward_kinematics(th2) + pos, rot = quat_pos_from_mat(mat) # note that since we are using existing operations we are not checking grad calculation correctness assert th2.grad is None pos.norm().backward() @@ -93,8 +108,8 @@ def test_urdf(): chain.to(dtype=torch.float64) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] ret = chain.forward_kinematics(th) - tg = ret['lbr_iiwa_link_7'] - pos, rot = quat_pos_from_transform3d(tg) + mat = ret['lbr_iiwa_link_7'] + pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64)) @@ -106,8 +121,8 @@ def test_urdf_serial(): print(chain.get_joint_parameter_names()) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] ret = chain.forward_kinematics(th, end_only=False) - tg = ret['lbr_iiwa_link_7'] - pos, rot = quat_pos_from_transform3d(tg) + mat = ret['lbr_iiwa_link_7'] + pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64)) @@ -128,10 +143,10 @@ def test_urdf_serial(): start = time.time() elapsed = 0 for i in range(N): - tg = chain.forward_kinematics(th_batch[i]) + mat = chain.forward_kinematics(th_batch[i]) elapsed += time.time() - start start = time.time() - assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) + assert torch.allclose(mat.get_matrix().view(4, 4), m[i]) print("elapsed {}s for N={} when serial".format(elapsed, N)) @@ -139,18 +154,18 @@ def test_urdf_serial(): def test_fk_simple_arm(): chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read()) chain = chain.to(dtype=torch.float64) - # print(chain) - # print(chain.get_joint_parameter_names()) ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) - tg = ret['arm_wrist_roll'] - pos, rot = quat_pos_from_transform3d(tg) + mat = ret['arm_wrist_roll'] + + pos, rot = quat_pos_from_mat(mat) + assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) N = 100 ret = chain.forward_kinematics({'arm_elbow_pan_joint': torch.rand(N, 1), 'arm_wrist_lift_joint': torch.rand(N, 1)}) - tg = ret['arm_wrist_roll'] - assert list(tg.get_matrix().shape) == [N, 4, 4] + mat = ret['arm_wrist_roll'] + assert list(mat.get_matrix().shape) == [N, 4, 4] def test_cuda(): @@ -166,8 +181,8 @@ def test_cuda(): chain = chain.to(dtype=dtype, device=d) ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) - tg = ret['arm_wrist_roll'] - pos, rot = quat_pos_from_transform3d(tg) + mat = ret['arm_wrist_roll'] + pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=dtype, device=d)) @@ -193,8 +208,8 @@ def test_cuda(): tg_batch = chain.forward_kinematics(th_batch) m = tg_batch.get_matrix() for i in range(N): - tg = chain.forward_kinematics(th_batch[i]) - assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) + mat = chain.forward_kinematics(th_batch[i]) + assert torch.allclose(mat.get_matrix().view(4, 4), m[i]) # FIXME: comment out because compound joints are no longer implemented diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 266bfb1..6b2fc7f 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -13,7 +13,7 @@ def test_axis_angle_to_matrix_perf(): axis_angle = torch.randn([N, 3], device='cuda', dtype=torch.float64) axis_1d = torch.tensor([1., 0, 0], device='cuda', dtype=torch.float64) # in the FK code this is NOT batched! - theta = axis_angle.norm(dim=1, keepdim=False) + theta = axis_angle.norm(dim=1, keepdim=True) dt1 = timeit.timeit(lambda: axis_angle_to_matrix(axis_angle), number=number) print(f'Old method: {dt1:.5f}') @@ -22,28 +22,6 @@ def test_axis_angle_to_matrix_perf(): print(f'New method: {dt2:.5f}') -def test_axis_angle_to_matrix_perf_zpk(): - # Seems the C++ version is not faster than then python version for this case. - - # now test perf for a higher dim version, which has batches (B) of joints (N) - number = 100 - N = 10 - B = 10_000 - axis = torch.randn([B, N, 3], device='cuda', dtype=torch.float64) - axis = axis / axis.norm(dim=2, keepdim=True) - theta = torch.randn([B, N], device='cuda', dtype=torch.float64) - - dt1 = timeit.timeit(lambda: axis_and_angle_to_matrix(axis, theta), number=number) - print(f'Py: {dt1:.5f}') - - dt2 = timeit.timeit(lambda: zpk_cpp.axis_and_angle_to_matrix(axis, theta), number=number) - print(f'Cpp: {dt2:.5f}') - - a1 = axis_and_angle_to_matrix(axis, theta) - a2 = zpk_cpp.axis_and_angle_to_matrix(axis, theta) - torch.testing.assert_allclose(a1, a2[..., :3, :3]) - - def test_pos_rot_conversion(): N = 1000 R = random_rotations(N) @@ -57,6 +35,5 @@ def test_pos_rot_conversion(): if __name__ == '__main__': - test_axis_angle_to_matrix_perf_zpk() test_axis_angle_to_matrix_perf() test_pos_rot_conversion() From ef5bdd81ea7abd2d9cf8a690183bba143a9acea7 Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 10:18:32 -0400 Subject: [PATCH 07/34] in the middle of fixing API --- src/pytorch_kinematics/chain.py | 2 +- .../transforms/rotation_conversions.py | 2 +- tests/test_fk_perf.py | 61 ------------------- tests/test_jacobian.py | 12 ++-- tests/test_kinematics.py | 28 ++++----- 5 files changed, 20 insertions(+), 85 deletions(-) delete mode 100644 tests/test_fk_perf.py diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 35bc0d5..96e88e3 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -271,7 +271,7 @@ def forward_kinematics(self, th, frame_indices: Optional = None): self.link_offsets ) - tool_transforms_dict = {self.idx_to_frame[frame_idx.item()]: transform for frame_idx, transform in + tool_transforms_dict = {self.idx_to_frame[frame_idx.item()]: tf.Transform3d(matrix=transform) for frame_idx, transform in zip(frame_indices, tool_transforms)} return tool_transforms_dict diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 01358ed..f0a4928 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -475,7 +475,7 @@ def axis_and_angle_to_matrix(axis, theta): r20 = kz * kx * one_minus_c - ky * s r21 = kz * ky * one_minus_c + kx * s r22 = c + kz * kz * one_minus_c - rot = torch.cat([torch.cat([r00, r01, r02], -1), + rot = torch.stack([torch.cat([r00, r01, r02], -1), torch.cat([r10, r11, r12], -1), torch.cat([r20, r21, r22], -1)], -2) return rot diff --git a/tests/test_fk_perf.py b/tests/test_fk_perf.py deleted file mode 100644 index e6e90b9..0000000 --- a/tests/test_fk_perf.py +++ /dev/null @@ -1,61 +0,0 @@ -import timeit -from time import perf_counter -import torch - -import pytorch_kinematics as pk -import numpy as np - -N = 10000 -number = 100 - - -def test_val_fk_perf(): - val = pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool') - val.get_frame_names() - val = val.to(dtype=torch.float32, device='cuda') - - th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') - print(len(val.get_joint_parameter_names())) - - def _val_old_fk(): - tg = val.forward_kinematics(th, end_only=True) - old_m = tg.get_matrix() - return old_m - - val_old_dt = timeit.timeit(_val_old_fk, number=number) - print(f'Val FK OLD dt: {val_old_dt / number:.4f}') - - link_indices = val.get_frame_indices('left_tool') - val_new_dt = timeit.timeit(lambda: val.forward_kinematics_fast(th, link_indices), number=number) - print(f'Val FK NEW dt: {val_new_dt / number:.4f}') - - assert val_old_dt > val_new_dt - - -def test_kuka_fk_perf(): - kuka = pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7') - kuka = kuka.to(dtype=torch.float32, device='cuda') - - th = torch.zeros(N, 7, dtype=torch.float32, device='cuda') - - def _kuka_old_fk(): - tg = kuka.forward_kinematics(th, end_only=True) - old_m = tg.get_matrix() - return old_m - - kuka_old_dt = timeit.timeit(_kuka_old_fk, number=number) - print(f'Kuka FK OLD dt: {kuka_old_dt / number:.4f}') - - link_indices = kuka.get_frame_indices('lbr_iiwa_link_7' + '_frame') - kuka_new_dt = timeit.timeit(lambda: kuka.forward_kinematics_fast(th, link_indices), number=number) - print(f'Kuka FK NEW dt: {kuka_new_dt / number:.4f}') - - assert kuka_old_dt > kuka_new_dt - - -if __name__ == '__main__': - np.set_printoptions(precision=3, suppress=True, linewidth=220) - torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) - - test_val_fk_perf() - test_kuka_fk_perf() diff --git a/tests/test_jacobian.py b/tests/test_jacobian.py index 2527ef7..0ea304f 100644 --- a/tests/test_jacobian.py +++ b/tests/test_jacobian.py @@ -119,23 +119,19 @@ def test_gradient(): def test_jacobian_prismatic(): chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "prismatic_robot.urdf")).read(), "link4") th = torch.zeros(3) - tg = chain.forward_kinematics(th) - m = tg.get_matrix() + m = chain.forward_kinematics(th).get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0, 0, 1.])) th = torch.tensor([0, 0.1, 0]) - tg = chain.forward_kinematics(th) - m = tg.get_matrix() + m = chain.forward_kinematics(th).get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0, -0.1, 1.])) th = torch.tensor([0.1, 0.1, 0]) - tg = chain.forward_kinematics(th) - m = tg.get_matrix() + m = chain.forward_kinematics(th).get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0, -0.1, 1.1])) th = torch.tensor([0.1, 0.1, 0.1]) - tg = chain.forward_kinematics(th) - m = tg.get_matrix() + m = chain.forward_kinematics(th).get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0.1, -0.1, 1.1])) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 985fba5..9ef8a68 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -35,7 +35,7 @@ def test_fk_mjcf(): print(chain) print(chain.get_joint_parameter_names()) th = {'hip_1': 1.0, 'ankle_1': 1} - ret = chain.forward_kinematics(th) + ret = chain.forward_kinematics(th).get_matrix() m = ret['aux_1'] pos, rot = quat_pos_from_mat(m) assert quaternion_equality(rot, torch.tensor([0.87758256, 0., 0., 0.47942554], dtype=torch.float64)) @@ -50,18 +50,18 @@ def test_fk_mjcf(): def test_fk_serial_mjcf(): chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_left_foot') chain = chain.to(dtype=torch.float64) - mat = chain.forward_kinematics([1.0, 1.0]) + mat = chain.forward_kinematics([1.0, 1.0]).get_matrix() pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_right_foot') chain = chain.to(dtype=torch.float64) - mat = chain.forward_kinematics([1.0, 1.0]) + mat = chain.forward_kinematics([1.0, 1.0]).get_matrix() chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'right_back_foot') chain = chain.to(dtype=torch.float64) - mat = chain.forward_kinematics([1.0, 1.0]) + mat = chain.forward_kinematics([1.0, 1.0]).get_matrix() def test_fkik(): @@ -82,20 +82,20 @@ def test_fkik(): '' chain = pk.build_serial_chain_from_urdf(data, 'link3') th1 = torch.tensor([0.42553542, 0.17529176]) - mat = chain.forward_kinematics(th1) + mat = chain.forward_kinematics(th1).get_matrix() pos, rot = quat_pos_from_mat(mat) assert torch.allclose(pos, torch.tensor([[1.91081784, 0.41280851, 0.0000]])) assert quaternion_equality(rot, torch.tensor([[0.95521418, 0.0000, 0.0000, 0.2959153]])) N = 20 th_batch = torch.rand(N, 2) - mat_batch = chain.forward_kinematics(th_batch) + mat_batch = chain.forward_kinematics(th_batch).get_matrix() for i in range(N): - mat_i = chain.forward_kinematics(th_batch[i]) + mat_i = chain.forward_kinematics(th_batch[i]).get_matrix() assert torch.allclose(mat_i, mat_batch[i]) # check that gradients are passed through th2 = torch.tensor([0.42553542, 0.17529176], requires_grad=True) - mat = chain.forward_kinematics(th2) + mat = chain.forward_kinematics(th2).get_matrix() pos, rot = quat_pos_from_mat(mat) # note that since we are using existing operations we are not checking grad calculation correctness assert th2.grad is None @@ -107,7 +107,7 @@ def test_urdf(): chain = pk.build_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read()) chain.to(dtype=torch.float64) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] - ret = chain.forward_kinematics(th) + ret = chain.forward_kinematics(th).get_matrix() mat = ret['lbr_iiwa_link_7'] pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) @@ -120,7 +120,7 @@ def test_urdf_serial(): print(chain) print(chain.get_joint_parameter_names()) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] - ret = chain.forward_kinematics(th, end_only=False) + ret = chain.forward_kinematics(th, end_only=False).get_matrix() mat = ret['lbr_iiwa_link_7'] pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) @@ -135,7 +135,7 @@ def test_urdf_serial(): import time start = time.time() - tg_batch = chain.forward_kinematics(th_batch) + tg_batch = chain.forward_kinematics(th_batch).get_matrix() m = tg_batch.get_matrix() elapsed = time.time() - start print("elapsed {}s for N={} when parallel".format(elapsed, N)) @@ -143,7 +143,7 @@ def test_urdf_serial(): start = time.time() elapsed = 0 for i in range(N): - mat = chain.forward_kinematics(th_batch[i]) + mat = chain.forward_kinematics(th_batch[i]).get_matrix() elapsed += time.time() - start start = time.time() assert torch.allclose(mat.get_matrix().view(4, 4), m[i]) @@ -155,7 +155,7 @@ def test_fk_simple_arm(): chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read()) chain = chain.to(dtype=torch.float64) ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) - mat = ret['arm_wrist_roll'] + mat = ret['arm_wrist_roll'].get_matrix() pos, rot = quat_pos_from_mat(mat) @@ -181,7 +181,7 @@ def test_cuda(): chain = chain.to(dtype=dtype, device=d) ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) - mat = ret['arm_wrist_roll'] + mat = ret['arm_wrist_roll'].get_matrix() pos, rot = quat_pos_from_mat(mat) assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=dtype, device=d)) From 881d37269678fbfbe48d4aa9f42608dba9ddde9a Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 14:59:17 -0400 Subject: [PATCH 08/34] fix discrepancy in FK between MJCF and URDF --- src/pytorch_kinematics/chain.py | 169 +++++++++++------- src/pytorch_kinematics/frame.py | 3 +- src/pytorch_kinematics/mjcf.py | 19 +- .../transforms/rotation_conversions.py | 28 ++- .../transforms/transform3d.py | 1 + src/zpk_cpp/pk.cpp | 9 +- tests/kuka_iiwa.xml | 52 ++++++ tests/link_0.stl | Bin 0 -> 151984 bytes tests/link_1.stl | Bin 0 -> 138034 bytes tests/link_2.stl | Bin 0 -> 72534 bytes tests/link_3.stl | Bin 0 -> 96984 bytes tests/link_4.stl | Bin 0 -> 77434 bytes tests/link_5.stl | Bin 0 -> 67984 bytes tests/link_6.stl | Bin 0 -> 57934 bytes tests/link_7.stl | Bin 0 -> 75684 bytes tests/test_jacobian.py | 14 +- tests/test_kinematics.py | 169 ++++++++++++------ 17 files changed, 323 insertions(+), 141 deletions(-) create mode 100644 tests/kuka_iiwa.xml create mode 100644 tests/link_0.stl create mode 100644 tests/link_1.stl create mode 100644 tests/link_2.stl create mode 100644 tests/link_3.stl create mode 100644 tests/link_4.stl create mode 100644 tests/link_5.stl create mode 100644 tests/link_6.stl create mode 100644 tests/link_7.stl diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 96e88e3..9b56aa0 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -10,6 +10,23 @@ from pytorch_kinematics.frame import Frame, Link +def get_th_size(th): + """ + + Args: + th: A dict, list, numpy array, or torch tensor of joints values. Possibly batched + + Returns: The number of joints in the input + + """ + if isinstance(th, torch.Tensor) or isinstance(th, np.ndarray): + return th.shape[-1] + elif isinstance(th, list) or isinstance(th, dict): + return len(th) + else: + raise NotImplementedError(f"Unsupported type {type(th)}") + + def ensure_2d_tensor(th, dtype, device): if not torch.is_tensor(th): th = torch.tensor(th, dtype=dtype, device=device) @@ -21,12 +38,6 @@ def ensure_2d_tensor(th, dtype, device): return th, N -def transform_direction(pose, v): - v_ = torch.cat([v, torch.zeros_like(v[..., 0:1])], dim=-1).unsqueeze(-1) - new_v = (pose @ v_)[..., :3, 0] - return new_v - - class Chain: """ Robot model that may be constructed from different descriptions via their respective parsers. @@ -45,7 +56,12 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.low = torch.tensor(low, device=self.device, dtype=self.dtype) self.high = torch.tensor(high, device=self.device, dtype=self.dtype) - self.parent_indices = [] + # As we traverse the kinematic tree, each frame is assigned an index. + # We use this index to build a flat representation of the tree. + # parent_indices and joint_indices all use this indexing scheme. + # The root frame will be index 0 and the first frame of the root frame's children will be index 1, + # then the child of that frame will be index 2, etc. In other words, it's a depth-first ordering. + self.parents_indices = [] # list of indices from 0 (root) to the given frame self.joint_indices = [] self.n_joints = len(self.get_joint_parameter_names()) self.axes = torch.zeros([self.n_joints, 3], dtype=self.dtype, device=self.device) @@ -53,7 +69,7 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.link_offsets = [] self.joint_offsets = [] queue = [] - queue.insert(-1, (self._root, -1, 0)) + queue.insert(-1, (self._root, -1, 0)) # the root has no parent so we use -1. idx = 0 self.frame_to_idx = {} self.idx_to_frame = {} @@ -62,7 +78,11 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): name_strip = root.name.strip("\n") self.frame_to_idx[name_strip] = idx self.idx_to_frame[idx] = name_strip - self.parent_indices.append(parent_idx) + if parent_idx == -1: + self.parents_indices.append([]) + else: + self.parents_indices.append(self.parents_indices[parent_idx] + [parent_idx]) + self.is_fixed.append(root.joint.joint_type == 'fixed') if root.link.offset is None: @@ -87,6 +107,7 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): idx += 1 self.joint_indices = torch.tensor(self.joint_indices) + self.parents_indices = [torch.tensor(p, dtype=torch.long, device=self.device) for p in self.parents_indices] def to(self, dtype=None, device=None): if dtype is not None: @@ -96,6 +117,7 @@ def to(self, dtype=None, device=None): self._root = self._root.to(dtype=self.dtype, device=self.device) self.identity = self.identity.to(device=self.device, dtype=self.dtype) + self.parents_indices = [p.to(dtype=torch.long, device=self.device) for p in self.parents_indices] self.axes = self.axes.to(dtype=self.dtype, device=self.device) self.link_offsets = [l if l is None else l.to(dtype=self.dtype, device=self.device) for l in self.link_offsets] self.joint_offsets = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in @@ -251,30 +273,59 @@ def forward_kinematics(self, th, frame_indices: Optional = None): if frame_indices is None: frame_indices = self.get_all_frame_indices() - # ensure th is a tensor or a dict th = self.ensure_tensor(th) - th = torch.atleast_2d(th) b, n = th.shape axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) - tool_transforms = zpk_cpp.fk( - frame_indices, - axes_expanded, - th, - self.parent_indices, - self.is_fixed, - self.joint_indices, - self.joint_offsets, - self.link_offsets - ) - - tool_transforms_dict = {self.idx_to_frame[frame_idx.item()]: tf.Transform3d(matrix=transform) for frame_idx, transform in - zip(frame_indices, tool_transforms)} - - return tool_transforms_dict + # frame_transforms = zpk_cpp.fk( + # frame_indices, + # axes_expanded, + # th, + # self.parent_indices, + # self.is_fixed, + # self.joint_indices, + # self.joint_offsets, + # self.link_offsets + # ) + + import rerun as rr + from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_angle_to_matrix + frame_transforms = {} + b = th.size(0) + # compute all joint transforms at once first + jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) + + for frame_idx in frame_indices: + frame_transform = torch.eye(4).to(th).unsqueeze(0).repeat(b, 1, 1) + + # iterate down the list and compose the transform + chain_indices = torch.cat((self.parents_indices[frame_idx], frame_idx[None])) + for chain_idx in chain_indices: + if chain_idx.item() in frame_transforms and False: # DEBUGGING + frame_transform = frame_transforms[chain_idx.item()] + else: + link_offset_i = self.link_offsets[chain_idx] + if link_offset_i is not None: + frame_transform = frame_transform @ link_offset_i + + joint_offset_i = self.joint_offsets[chain_idx] + if joint_offset_i is not None: + frame_transform = frame_transform @ joint_offset_i + + if not self.is_fixed[chain_idx]: + jnt_idx = self.joint_indices[chain_idx] + jnt_transform_i = jnt_transform[:, jnt_idx] + frame_transform = frame_transform @ jnt_transform_i + + frame_transforms[frame_idx.item()] = frame_transform + + frame_names_and_transform3ds = {self.idx_to_frame[frame_idx]: tf.Transform3d(matrix=transform) for + frame_idx, transform in frame_transforms.items()} + + return frame_names_and_transform3ds def ensure_tensor(self, th): if isinstance(th, np.ndarray): @@ -353,40 +404,6 @@ def _get_joints_and_child_links(frame): def get_joints_and_child_links(self): yield from Chain._get_joints_and_child_links(self._root) - def expected_torques(self, th): - gravity = torch.tensor([0, 0, -9.8], dtype=self.dtype, device=self.device) - frame_indices = self.get_all_frame_indices() - poses_dict = self.forward_kinematics(th, frame_indices) - torques_dict = {} - for joint, child_links in self.get_joints_and_child_links(): - # NOTE: assumes joint has not offset from joint_link - joint_link = child_links[0] - # print(joint.name, [l.name for l in child_links]) - child_masses = [] - child_positions = [] - for link in child_links: - child_masses.append(link.mass) - child_positions.append(poses_dict[link.name].get_matrix()[:, :3, 3]) - child_masses = torch.tensor(child_masses, dtype=self.dtype, device=self.device) - child_positions = torch.stack(child_positions, dim=-1) - avg_position = (child_masses[None, None] * child_positions).sum(dim=-1) # add batch_dims - total_mass = torch.sum(child_masses) - joint_pose = poses_dict[joint_link.name].get_matrix() - joint_position = joint_pose[:, :3, 3] - axis_joint_frame = joint.axis[None] # add batch dims - axis_world_frame = transform_direction(joint_pose, axis_joint_frame) - # print(avg_position, total_mass, axis_world_frame, joint_position) - joint_to_avg_pos = avg_position - joint_position - # NOTE: A@B.T is the same as batched dot product - lever_vector = joint_to_avg_pos - axis_world_frame @ joint_to_avg_pos.T * axis_world_frame - force_vector = (total_mass * gravity)[None] - torque_world_frame = torch.cross(lever_vector, force_vector) - torque_joint_frame = transform_direction(torch.linalg.pinv(joint_pose), torque_world_frame) - torques_dict[joint.name] = torque_joint_frame - - torques = [torques_dict[n] for n in self.get_joint_parameter_names(True)] - return torques - class SerialChain(Chain): """ @@ -429,9 +446,8 @@ def forward_kinematics(self, th, end_only: bool = True): # to return all frames. frame_indices = None - if len(th) < self.n_joints: - # if it's not the same length as the number of joints, then we assume it's a list of joints from the root - # up until the end effector. + if get_th_size(th) < self.n_joints: + # if th is only a partial list of joints, assume it's a list of joints for only the serial chain. partial_th = th nonfixed_serial_frames = list(filter(lambda f: f.joint.joint_type != 'fixed', self._serial_frames)) if len(nonfixed_serial_frames) != len(partial_th): @@ -444,7 +460,34 @@ def forward_kinematics(self, th, end_only: bool = True): th[jnt_idx] = partial_th_i mat = super().forward_kinematics(th, frame_indices) + if end_only: return mat[self._serial_frames[-1].name] else: return mat + + def forward_kinematics_slow(self, th, world=None, end_only=True): + if world is None: + world = tf.Transform3d() + if world.dtype != self.dtype or world.device != self.device: + world = world.to(dtype=self.dtype, device=self.device, copy=True) + th, N = ensure_2d_tensor(th, self.dtype, self.device) + zeros = torch.zeros([N, 1], dtype=world.dtype, device=world.device) + + theta_idx = 0 + link_transforms = {} + trans = tf.Transform3d(matrix=world.get_matrix().repeat(N, 1, 1)) + for f in self._serial_frames: + if f.link.offset is not None: + trans = trans.compose(f.link.offset) + + if f.joint.joint_type == "fixed": # If fixed + trans = trans.compose(f.get_transform(zeros)) + else: + joint_transform = f.get_transform(th[:, theta_idx].view(N, 1)) + trans = trans.compose(joint_transform) + theta_idx += 1 + + link_transforms[f.link.name] = trans + + return link_transforms[self._serial_frames[-1].link.name] if end_only else link_transforms diff --git a/src/pytorch_kinematics/frame.py b/src/pytorch_kinematics/frame.py index 117ebce..a078919 100644 --- a/src/pytorch_kinematics/frame.py +++ b/src/pytorch_kinematics/frame.py @@ -22,8 +22,7 @@ def __repr__(self): class Link(object): - def __init__(self, name=None, offset=None, mass=0.0, visuals=()): - self.mass = mass + def __init__(self, name=None, offset=None, visuals=()): if offset is None: self.offset = None else: diff --git a/src/pytorch_kinematics/mjcf.py b/src/pytorch_kinematics/mjcf.py index 1e43d79..2825e01 100644 --- a/src/pytorch_kinematics/mjcf.py +++ b/src/pytorch_kinematics/mjcf.py @@ -35,16 +35,17 @@ def _build_chain_recurse(m, parent_frame, parent_body): if n_joints > 1: raise ValueError("composite joints not supported (could implement this if needed)") if n_joints == 1: - # Find the joint for this body - for jntid in body.jntadr: - joint = m.joint(jntid) - child_joint = frame.Joint(joint.name, tf.Transform3d(pos=joint.pos), axis=joint.axis, - joint_type=JOINT_TYPE_MAP[joint.type[0]], limits=(joint.range[0], joint.range[1])) + # Find the joint for this body, again assuming there's only one joint per body. + joint = m.joint(body.jntadr[0]) + joint_offset = tf.Transform3d(pos=joint.pos) + child_joint = frame.Joint(joint.name, offset=joint_offset, axis=joint.axis, + joint_type=JOINT_TYPE_MAP[joint.type[0]], + limits=(joint.range[0], joint.range[1])) else: child_joint = frame.Joint(body.name + "_fixed_joint") child_link = frame.Link(body.name, offset=tf.Transform3d(rot=body.quat, pos=body.pos)) child_frame = frame.Frame(name=body.name, link=child_link, joint=child_joint) - parent_frame.children = parent_frame.children + [child_frame,] + parent_frame.children = parent_frame.children + [child_frame, ] _build_chain_recurse(m, child_frame, body) # iterate through all sites that are children of parent_body @@ -53,7 +54,7 @@ def _build_chain_recurse(m, parent_frame, parent_body): if site.bodyid == parent_body.id: site_link = frame.Link(site.name, offset=tf.Transform3d(rot=site.quat, pos=site.pos)) site_frame = frame.Frame(name=site.name, link=site_link) - parent_frame.children = parent_frame.children + [site_frame,] + parent_frame.children = parent_frame.children + [site_frame, ] def build_chain_from_mjcf(data, body: Union[None, str, int] = None): @@ -104,5 +105,5 @@ def build_serial_chain_from_mjcf(data, end_link_name, root_link_name=""): SerialChain object created from MJCF. """ mjcf_chain = build_chain_from_mjcf(data) - return chain.SerialChain(mjcf_chain, end_link_name, - "" if root_link_name == "" else root_link_name) + serial_chain = chain.SerialChain(mjcf_chain, end_link_name, "" if root_link_name == "" else root_link_name) + return serial_chain diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index f0a4928..2045694 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -450,7 +450,7 @@ def quaternion_apply(quaternion, point): return out[..., 1:] -def axis_and_angle_to_matrix(axis, theta): +def tensor_axis_and_angle_to_matrix(axis, theta): """ Works with any number of batch dimensions. @@ -458,9 +458,33 @@ def axis_and_angle_to_matrix(axis, theta): axis: [..., 3] theta: [ ...] - Returns: [..., 3, 3] + Returns: [..., 4, 4] """ + # based on https://ai.stackexchange.com/questions/14041/, and checked against wikipedia + c = torch.cos(theta) # NOTE: cos is not that precise for float32, you may want to use float64 + one_minus_c = 1 - c + s = torch.sin(theta) + kx, ky, kz = torch.unbind(axis, -1) + r00 = c + kx * kx * one_minus_c + r01 = kx * ky * one_minus_c - kz * s + r02 = kx * kz * one_minus_c + ky * s + r10 = ky * kx * one_minus_c + kz * s + r11 = c + ky * ky * one_minus_c + r12 = ky * kz * one_minus_c - kx * s + r20 = kz * kx * one_minus_c - ky * s + r21 = kz * ky * one_minus_c + kx * s + r22 = c + kz * kz * one_minus_c + rot = torch.stack([torch.stack([r00, r01, r02], -1), + torch.stack([r10, r11, r12], -1), + torch.stack([r20, r21, r22], -1)], -2) + batch_shape = axis.shape[:-1] + mat44 = torch.eye(4, device=axis.device, dtype=axis.dtype).repeat(*batch_shape, 1, 1) + mat44[..., :3, :3] = rot + return mat44 + + +def axis_and_angle_to_matrix(axis, theta): # based on https://ai.stackexchange.com/questions/14041/, and checked against wikipedia c = torch.cos(theta) # NOTE: cos is not that precise for float32, you may want to use float64 one_minus_c = 1 - c diff --git a/src/pytorch_kinematics/transforms/transform3d.py b/src/pytorch_kinematics/transforms/transform3d.py index 8032d50..e0f9020 100644 --- a/src/pytorch_kinematics/transforms/transform3d.py +++ b/src/pytorch_kinematics/transforms/transform3d.py @@ -167,6 +167,7 @@ def __init__( a quaternion of shape (4,) or of shape (minibatch, 4), where minibatch should match that of matrix if that is also passed in. The rotation overrides the rotation given in the matrix argument, if any. + Quaternions must be in wxyz order. pos: A tensor of shape (3,) or of shape (minibatch, 3) representing the position offsets of the transforms, where minibatch should match that of matrix if that is also passed in. The position overrides the position given in the diff --git a/src/zpk_cpp/pk.cpp b/src/zpk_cpp/pk.cpp index 686cc56..e63d5e9 100644 --- a/src/zpk_cpp/pk.cpp +++ b/src/zpk_cpp/pk.cpp @@ -50,38 +50,33 @@ fk(torch::Tensor link_indices, torch::Tensor axes, torch::Tensor th, std::vector link_transforms; auto b = th.size(0); + // NOTE: assumes revolute joint! auto const jnt_transform = axis_and_angle_to_matrix(axes, th); for (auto i{0}; i < link_indices.size(0); ++i) { auto idx = link_indices.index({i}).item().to(); auto link_transform = torch::eye(4).to(th).unsqueeze(0).repeat({b, 1, 1}); - std::vector tip_to_base; while (idx >= 0) { auto const joint_offset_i = joint_offsets[idx]; if (joint_offset_i) { - tip_to_base.emplace_back(*joint_offset_i); link_transform = torch::matmul(*joint_offset_i, link_transform); } - if (!is_fixed[idx]) { // NOTE: assumes revolute joint + if (!is_fixed[idx]) { auto const jnt_idx = joint_indices[idx]; auto const jnt_transform_i = jnt_transform.index({Slice(), jnt_idx}); - tip_to_base.emplace_back(jnt_transform_i); link_transform = torch::matmul(jnt_transform_i, link_transform); } auto const link_offset_i = link_offsets[idx]; if (link_offset_i) { - tip_to_base.emplace_back(*link_offset_i); link_transform = torch::matmul(*link_offset_i, link_transform); } idx = parent_indices[idx]; } - // go through tip_to_base in reverse and build up the intermediate transforms - link_transforms.emplace_back(link_transform); } return link_transforms; diff --git a/tests/kuka_iiwa.xml b/tests/kuka_iiwa.xml new file mode 100644 index 0000000..a4bae73 --- /dev/null +++ b/tests/kuka_iiwa.xml @@ -0,0 +1,52 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/tests/link_0.stl b/tests/link_0.stl new file mode 100644 index 0000000000000000000000000000000000000000..3895506d04b38e985d55a915e9ef69f71b5772be GIT binary patch literal 151984 zcmb4scUV=&_Vy;&5qrZDHCSUWD00rsfP#R41?;^m_8NP{-WBY>2KF!Y|NGx9FT*%o;2o*uRg~V_9?BNwTFfsTP9hn(n%iFvS;`;& zok(7NYHpwP^IX1c@^RoYI26vX zb&QC*HiPrDjl}13jNLGfZ0Sye=N9D&6T%smU<6K~VQlfPEw*mVC7v7&Wmtj{dOl*l zG!z-pHpiH_AciFu&n578)0djL#U)}Gc_#(ZCP@Xvl<`z6D~y=1crL%&V-6|(P~~IA zpC!b;U-OCAQK4)^_4WMb!ue+T412zVR~;TtBED&E@1Bsz>nG17vwv5JmE+#=62AqB zUOgMK#2;7lf<>pB-wHgsf)6U6V5Uk(vmXRZ?@{3i&%2!aRYj`X9&X*j5yS1HILbqZ05-@c62TvN?kooIt*&S zaQVc)Tf`&3%s0QQm(}|xkI1~?HN=I3Aq-0}V%Vcad}!_&W~(#|$KrUNe@kDHd^?jV;^9y#gDov{#rj;&6;BqsJ1Eu$n!+9Htm&Jp%oa5Z)%(RYg+2QP6hB28J z=k?}C(7Wlu3`;QLfg_P$%d(49ld8@=qk;w7_y_Tu6rv%pR{obec(X=ZNK%gGfY{=f zPW8b$rDCvY{2zCS#d7i%=f{5zD@opyB3{p0*xzaU1_ zXYdhMH}W$-IY-e`gI4mo+nl4Q|J4;H+AyBydCXULtSBDL4m10p>$_^as*z>!|6ya^ z$dWWu?mtO*Oe2P^V?>+lGx%Sb7IHPN7)ItNz3II!rFqkjVGK(!LXDNK6dK0nYBfah zbveZ|Kj$dwl3;`yE5GK$<5qpqB852~Ee$kBQI|yZ`3k{n&3xbzF^qb9!|09Og+%qm zcCD;1!Vy20dv)8+d4}pAAGX#IMIt_PHRGs}tbucph=LUK%MoyuLY#x=K`ySC`T^nfcJm>hOt|WctopqSVe{h9wxW@$MqNC^d;+ zSf|RWRe>3N^1b2W^^H)5B^ZIr&@lEr&n*i2mZdAIG}KBLBXGGH#@nX*Nb?cVqJ{|3 za*lJW#>!Ep=9_skjO5{q9S`>gQLo)$<_PDKV8qc$iM-;jncO*ZE(tF$#-6%Dl+S>_ zg|*Ti@8ExqiswHRQ~jgIwhZD`IzWv4Q@4S&)F^SM#bUF)8Aj&^pUK-SC8=MW-V$%Y zDB3M(otbvrDh=b)8$Yq>@IW5kGK^sfMqI0(%-ii<%a3+dsXAhBMvweGnyl>-%CH0@ z)M)oguC&T(XK*dCGiZu^`?f|J0&CszPv$!^mhj-h%EqFL;k5Y49z6f{aE2uqq38U$ zt(GX8Wdcd3ks1PP;c_#KE~Bc*M}wxN22QNW`WH{(7kaMbk6Jdd<2+&8Q0Gycr2qCk zyIap+8+W5pm-72D)3{GOvE%wTj82Ug(}m|g(DZFhv@vm0Y&@@!b0#mESjUcgmtmZ4 zHIR&0R$Cqqsid`Ck15Of-8?Bgn=QnSdjTNYR*|+vqa0(Nx${9(KJW~u&r!9GrI3qv zE3>ng>S$hg!z|0VeR2wkSV-*H8!(I!*%s3;yFbwEGn;50@(+oSkLSBc^Rt@Pjr;6su+zVRH2cMosvYrpIW1q+{o;<29e=9y-^zi9wU);b;{5YUDxxBeJ zQNMGNiM-H_jW+c=)HZH? z$%G9(X}gfeTp@6(T;ElHccsuU))p-({nAtUq}AyHOVn?SaHSAh`^;MMX82%{yM>o& zea~ODxW|pWT1pgp)mz4^N8Er^)f#P+i@xnl+wDp)%f}^ATCTL;3-%I=cSn*=%hv-U zsk5D6$$HST9c|8!PMWHH$uNcww#jq1I*WcI|1l-5a{o8NRU(G*;F?{o zit9-u^W8ELE(u0p+lJA8ZxuN^IF|^&yX8MQ$93b%lVPw273FW!|Asgx6H~ce`g;ZP zXlOwbop*38((J9X+{(5qL2P#mQNuV^zlwww4}CDViEv328Y7_o?W+C_BjQJBw_iTe zRR#8#-*rj;jrf|Xd#tu>7C(jl5&7jm2$z;Z8}Q$o3dO;OLfkCVkj8~M5iW_+!U$KZ zR9@du9%Ks;W9^{~Mj6t)vkSiaPv=tTUg(YDO=N3Fm0{*U-Q*GL9Vpduk z=5wqCJ}v=I)=ZU-I9r^F;~uw3^1={?B^Yt;*BPX|W24!6pnv#wq`b~+`+gFvJY@HG z+nrA!;Ln*hbVT#azG6-K_jI;reTF3%0lpmp51BYU8yi~$f5=j>{Ipigx5`U z@eD+UZ6RJ2n%mQsC6d?qcai8P%IiDX+=F&n5kT2k(}yGAA)BQLej5P~*-Vv=7|x5^ zAAW8n)}9SxSb`DQwqcZCRg8Wpc$|l24`w*+;3pFBUQHW%J{}&r$rrt^O|x}vsJvHq z4l&~Udy5Eouf*xS&X_)()C(IY_jsm zn$Bq@3V$BO)yRM)7y;fH86aJ;^SaBm>6rA)j>yDD8Ukx|YLHC&Wm!r{Wo6^excb6p z=|r+|Q5eG#jL>`SzJfMd!n-rS8W5o&uomv~hVk0)r0aGSql3>iWU;^o_R8gqovXB6 ztHwmGM$xF;+el#49G)+~O4W?mdJqp@=Ji5C+2zl>NU_w7W>j52J()BeyppT-$`d!M zeq*9xKA&@&zpGJB1a=5z_`4xjHmR}X|FF^Ew{rB^_$TDGBaC6|7_kfdthbpLT9Mb4 z+5>5aawYh*&7llSFaoC#7_aG7#Jrq2g}q`!h9wxG=Y#yvM|3{C$q^M0%CIEzL!ufP z%zWSyF^rAPo{}9qi-;xr8fj&P5fyT7Bf-2| z&mz^Lx0rQMt?7IcS!|bu*jM)*f8kR{#0?5#2_eggZHF^4+9_`wtyS zZ$fS5!Wfod1h#D$UnU(*eR!yY7l-r?L)_sOEHx03uwr&1S9_G zwwzoqIo--f+ESY+oar(t05J|OpM;C+)#zh>S1+qJUFMKItE!3n?;;qMU_`gk>&e3> zNqpTZHHyl1Yk6JPSF9M_h+zpv;4(A}U(ftv^Xi)P%SF9(F#?yHVT?VyhcsW-M1+(L z(Q=M+Tkzx(YG4R9Id=rj0R7CUOslUZU@n|Rh+;QjQDobe3Je6ViRo`6AnG4 zEpnxcMc?WOtOeQx{%s+S?mA4{UwbDWdQ7F*2G+vu%`n;kBOLNwVVRPBlE4y-fcy|h zrDbD3xky@fEGaz(PM{cpwQ&DeIj=984JaaC?3^f8XIt-1FP<4N8X~U+OS#XAQZjw> z1d1gXq1(7q>#-Q~_gUd##EEYzB)UrxkL}pDT8TR#st@}jj`x{Lu>>QqJ;UffridI& za)>3@r_k7Ko89${X9kQmj8Z{)<(J+)gl9~gzzD2`Q)?JY;!Db|ev?S>rHK@O7o+i5 z33F|aA~LyBAief-qQDZ2P&OcsRt>)T&X6sR{X~Z^o=PzSYvIw(FscteC-QH3MBAr~ z7g&N3stn=ZmJQ&p#Qh6-*s{TK8UkynnuSzahz_4UMSP9I>`l}(ifv#mecZh=rWK9J zoS%*B9w$_Lby>$V8Ahx1!NcUzNFTN&e45#=T-Gr{w{cHXbGLXa~`Dn?mf#sAe>Omq`L6uokurUPi^&^h4rNy1dF% ziX|9Cr@Rax0PTO+Kl5t<_%5Z{gSpqhZB8@i3ni>m&EHbhoSj zAaomENvA~SBkeeT*@dv(>T%(VPz_9_2MGT`?&q5N~ zm53NK$u;_z2&`rGVDs;WQJ~{%(PR2iakI=+iX|9!i9Yht(hM@E=~RkSVvRoL zcX2FY7^w^L$zs(yP*sCif)UELs!>%UhOz3zQ}Hf)I(_w>j=)-~tW>LUB32$dECSEG zqiP<+Hn0|EUJT>H?Z)DMiNY)<^CW>K7@_K1wSK3KGD9x%_iakDPD3Y9jKEr$nKGk0 z3iBXS^PtL|E4`R)!D#RR1}!Bp4>B|ln$|Hww^63jV+!*iRqaZB-&Km3JHfUMV^h`x z6y`yy=0PmM2yD+Va*Zg$Hn++_U*DSI8sW@T;c*3{4dVsP%Tl4|ZfYFo8sSU?*21ZU zodX$JSc#Km*@3{HMde=4YzeF0nuy64pV&&DdP{0Pm>e*)QYQO1S6&k_X-xpEVBPj* zBSu`IA5Q0z7=g8(cJQ>v{q!2xm#O;Qa|<>EOW3gMPugzBxM z|F}x7jh+f+b+>%5qq8VT4|=r{UsQ$2J9EhzW0~YUwLUZ zFak;>^=s+&zwadzCRCL7XFm{Ft4R8()KYtIk?LL7sM1A#!cR5pGr_*PFB^aT%t7&JVS%nD!)VI+Gf%^n*S9<@bR3wCbc+%HFauk+W zf)TjA8Aj-kitIzdd$h^c1AJc{JT!@&CP!o7=g8LYJug9eJ^_C^K|r} z-V{qPLQA1BbWTob+rOB$8uwJ-lwf;MhPIwP|Fr7E^LDa$*x!f!7W9{@kAT#2cTLF; z$8*{?XT3+(Mdczo;^^Pkf$^#ewU|j@2}WSs&}*L!hJ9r17{nl4_2+jncT5|lo(CS7 zRQnFec{FnT4&HnonX0Ml3x1XX?0=w`A7sK6RaZ3HXVejWzv5_YN}^ zfhnIyl@oYsXg{3dOUmc$Ae7I5B^Uu7AXgrmLOc1AaqrHEYXx-#)&gy={6;4teAQvt zzw%CuFJ=0PZtGYJ?+}C?DLWg}={|*}ing%?BOpIqd9zL%&HubW`o)x#*CtP(7=g9$ zj!jrUpZb+A0gud`Uc8qVqn&)oqor=X#BCiTbQ@6xAB)$X=Y;o7(@%7lB6wu(J;KM#qRE@{hqe%+dwF*IlCtDRRSFYF;^ z1et!K8-caJPjsi&Fp?UTlmqfjBDRQ0Dz0^Z7u&rF+*bj884k35aWH*(GLN>y}`IDqZ-uW#i>6Ctsqt z4E!yurRw}^{ITP_rx;eIF#Bte8P~dPU@eF_-FuP^Bj@5)bnA2)}5kZj%O5hrKq^pU5Xf?`pVaw7w%Jnof)4-hV(Gw zT6dj8H0d5C@cvXMUs8Q=Gx{#ZjBDKptc7hm`I0$9j?%3i%(&K_DvZD>G>lzyo&2tf zid0Hme6%(CaMd!@sPvURhp~`(M|TibT7G6ZI7_E(0CPIxXuC+~U@9TJVKg2y={l|vY=gq$xM(N;^a?G=d z1lq1SUb((&jXtIp-e+qV4QLTrw`d@3y4yKkxz-&qLfKF?s`6(T3r>F#OH+TMqaHfP zD;EN5sWHa2#%35d!=2-m#lyKJ7@Cj7;hioFS*3jz3Qg_7M zGye`8@{Z!-QqDTEf15|5Y}>yB)=jy~Cy&ny-!eUNQ_J$HEyTyk4f)1QZ6z7{k>iwL zg#M-KnRCh6H`0KMQ$BUD4WdT#TS=n>Z9^~L=MVC~SJ9n{KP(&a*gf%TZhpBm-1OVs z5{%GOm91-{czv*uwE5<6MJ)fZp{L5TQh9mv;|^Xh<&qh(Ks0J1R=p`;`}W8ap09VZ zigDekHH?vKO36GcUkX?W;8=nYIECQ#oy{iq9Z%y`b{tW0MgYXMrj1JvTGYF~{TUDG zwakvuhB4JIn~WWPhKwt5)y#(rfwfdwxl#);=kG;nyA%dz$R3mXiRp*_ck(I!Xl%4& z8+RMW9_rBd83)eE52A@~9mI=nvnl*fU{?!E$%@X5+)^wO%@ayy)1!tE7n>1}t> zOiy-y_7?GS`dfh|7=i7k~$$){RDzXQb(`^G-BR3kDB0DgU z+|58rU?8c*KstbdROwX=qyrd8ZZVLKV-N3gHv=iVj6F?@I~hnf0=PxDmc?sXsR9NP zc+r383u-cuZmoqk&!hqa$t?y_F<}-07)a6RemQ0_kZuV^SR9~*00vS31IZKviM4Ds=Q6)=zt7)WUGCIjjIF0g|(U?920Kq3S% zkPH||YB7**2}a-+1Kw|+`V1IIdUuk^K)Tx!M(FJ-_)@ei{JEZ3)y`xf-8~1lE4_aJ z11W)lwCBoZGLY_`gAu?$y4xG9<1`9p9}+hRW1z`pxcdY!6L#P-%oeWqkBXhVS!|=s zGPFW|#bvmA4o0xKf7%xBdCQ$##;i}9M5l_C_18XZ>alBD4ztv7bU<5u90sH#0{2@l2@R7Gi zlw&w0_^i}-zij7SFK_4PGwML99yk9}EPDS+%*#$0mS6-v5n~w5|I9C^_&pF!KUUBX zSZmYUoqT?oEnJ<)GsYG1lBrUB8gYK9nS{^sZ{lE`ANh!nnEwF zjb>Pa5&8+9ym9Bn!*VG!V?;|0fwe+gZRH`UGx-lkl?{(2heVaqf6$l7O&OM81U`=i zJA|f=6l=S@rE&9HXb7y;DsUbD<)5j1_GD#aS+-)LUa6d{#ptFCOE5w|CDg87ZAVIW zU*`K0)eu+vZ9--2NYKB<`}a3+tc z3_Iw|vWjo>oHqNCNO`uV3`;NqpV~BxX`2hPZfyt9%1KN^V6Cub(|GfMrToS;JCs$e zTou^W_StB=UiBE3V1#}GbXhhp_N+s7F(NurJDr(-!c6{qm94yVLLKvN0N2S-!wB?$ zOy4f|5@QRuH&5QXBp6}4JC(oax{gy~)gXg9u@@=VKto_HoLa;1X}p7Ej3_5R6!g>1 zDB>~d%MZ)=th&4TxLwLdui%RGblXqD(WJG8z*@E<3EV34ypLL`u^L z4S}`riAwMjtG%INlEWUwVC}3WM(Af>+f2Pm2NhW($m$rabTI;#n_)~E^&LOgsJ5JZ zv;xDq#UnM&6L{hMv&(I^tvqv^NH+6y3ir9Qfp;fH!KW1Sqaz(Mo zCQJFs0#kX}Gqvrwci~=O7|pI1qq{;q*o;e&8UkzKUSJp81R`?%HQ$(jsf#%sI*J&ViO2~CS>iOm@0?ssX=V_-)T{qhM{}oHec5Kd+ z#C3Mb(lXCPDYWYplwnj@yH#9!`5kQ#)bKy&qcGa_+b~+J*)B#@Sx17-glRU^cU@ZQ zxAOd)r=7O{c8PEBtw+Ktb@>m%rKM8n`fV87eIAQn_UGUY-Zn82E(!jwWzRgdXBcyu z{=!GDT+jVyclr+kQe|pcC1N4Qh&A?uyK4Za-_n&TQ-Z&1m77(%et-WdLi%~Lyr(KK zeEWg-(ak)#`YzI7E3xZm_3x*=6yC#fuqJcLGc3V~<|nrCAES4Y+UsjWKVP@YOO~(k zfHs(3RYPE{rXP0lVL7*u`?Hjn(Jv-9n>YLg**>L-cDKm3U)b?VX4;X^N5&U$NtUhseI^^CFH?6=N#p_zs4}m#(J_vz3VutTxqS@-v$J}AYKraCqcjA*5eC~<49it|p!W&^CtS2tVMP7(cph?KhIyVB7|5zGX@z_T z#qHLiaAM@E1S9ZGC=hL5-b6!wdMWZ3j?xfVOF#9Sb!%1n>c(49dt4h0fwj`gE#qm+ zrjiwH)jXKu5M*ulvNGzlAHx!iz^9CX5uV&iysME#re$iPokhmC(cGW6mB$~MNxJk^ zHcHV3{6dBD(%0}~_*?k4mc0ws@iDKak{h)Z!t08!=(6sOSmD)%VF^a)HvIlBCojba z`u_NLT0h5q`)QUGe%-c#yeg{VDCiq9ZhsuDkG&y3_Cxij__PpSH?hQM0* zEILG~QQt}BS8uH7XQs+^LkmXW8(j?J>V*9A)69v&YYx%wdcla1^^*(LJo+?TzLc*$zMCkY$S_KDnC}Sxxfmw_)N_*0B~I=V5pC<-h13<%iMK@;U-* z=_8!Iawa)GB(F%i6~U6u?dG>iEF*iK)VAaL!1WJj+`V3k3rqa@q*2it0&D5@5wZ4L zIrw6C5_89oVF^aynuU4r$#?Q>$({Vml{)far8GXTwLa4Cj2MEcy+a+T==FTc$QTqmSDs|zmxpeCJFpyKv&qM_ij~1;2E}v4j%br z-R5WbuodyVj<2T;BPJa^&BMif9@Dxa+-qPvbWB|SYbl?V+(mZnb&791F^^9>dOiT7 zckNH-pL5RR<=18hM3F7vWj%fIr!gX4Lbr!{OC4Rh3`%OcOQGs3HH zpq46(&~3bLlUtTOzSq&}M6iayDa3g)jBzuH$(6Ob(g&sdB$i-=URD=wSCt#)9};)! zHX(o3g6s%IB#u#9f0k@Sn~FmSn%>H^~oA6cg{@a zxu1>VuldvfoDz&yHcp5tyI0W(i(({}V1#aC#hT30tM6IbJG8FETG$?LJ7{el2N?wVJ`kW>NdK#khBo^4*b9{HI3AJpO%LKGT z(Gb4$!$yk{4jovGjjP{HbUVp31lD>RKZs8b*~ACtn*?olVUYst((qKC)GtzE2}TTj zF^G?uyxg+UqD5KOAh|GK63;XQ);ct001p_p+_EunLIF0V)h42BUd6tcLRkN|M+oP$nfh8C*BinemwQ#Csp=8v@;)0k@$H%4K#w}TE;9?g6)E;5 zhD$8L2;9?vZ{PD9ZTDdjKVGV{hQM0km1B88w&j)$&%3!;wa9Y3U9WJ7B^ZHwnqefQ zouhY7H6&LHcGeJBEA3f-K4R@$%SPPqUM#HXN5a~MODw?%+|yu(Y1lDZHhVQ1IiZt= zz*^;eM)8t8CR;Xc6oXq^>cmrECM1?%1nz0D_oLwk+Nt6!x@T1<4S}^fUY^YR)ELS8 zWq%L#;l1oQ?bh~JdU8d$#1f3aJq`8_PU%i}^h~B*T6NYCSSz*sJl=F(e=8rAc1)m0 z*%!F^G+bf{M&OlI46}@mR}-taXC;hI+G%7U2?0Faq~9 zm~oEoO8vO?9KG1IvxdN0LwhCi89Dp%E=N8=S*>|JiQ7E9*~Ki4B$i+V?rFdQEcwF6 z+E37tYdUKPtc7P(!>Ba5x46;c8#bG(iYYn~D+m>#>#!F5%z!!~ro{$$}X`4 zBk*dkVH}*(khaX_4LhCcY6z?atGoy99J|8fE`Nj?gjPteb*;^MT`DZG1S3j4KV0|y ztE>F-mT7?K{$e_x6`GTEhzQdVSnI<3L8&#yT;siZd;mn@K2gGlS7E!Wek-vABlMN= zsDLXXXktFr<$;dCS_{#h0CfXqX?bkdS{mS6RN`90T6o_9oRzuiC(S#TyX4gnSWB<- zMZL?h;NVR3=!~+mWoRz@$kF$>Ix~UyPvH6o4*AIwy8T5o-8?E(Ltri3deptnd&PFT zpSFG$C70#Bm0F$O;J*TuZ5Cq<`2;qvl;F=R|slIi1|td~F*bv4JXIy$1;(|<(HG7m)N+;t?D zV8r<9@npu56Wm@a2y8qVOw?$mq6vs3 zNb`GU%&`wVC-T)JTk^3h-Sw#`?7$Ax5LgRFZSvJ4i~Deh)Hsr#1^!}sWNryYfCosv zdX~#l3z1i!%9vgs{ub7P*@t}fEFqHMDxy%{E0$mcc(UZHhs;_P6Dp$cpKW@U?r&i& zm_^A~54pJ*EmTC|J=pY+-4cudkDPq<^f#8ANKu0pBOe^LKj4N4Nhi;1&;>>A30XyAfCmzE70b;q;KV)chhmhp#fDA}qlO zC?}#kf0w6UK>pMz!Hm2x0&77z5#@C_Z9pU;RYYM$UTz6SKz$SC`8#cF8Sg8LEV@Xn z$jgnuT2S9ac^yt0ORg7`UJy}??_)-gZV5&}yCur=ciQmDT1K{hoWxb+g};ThpxqMX zbvSJtY?w=?WhG+kW-}6YOE3cWX2Uptu%LulM=Tv2s3KuE0&C&k3^$TGD7{nX5Dj0| zS+-6{A#vk|@$L&g2H^e}IeQbCzP69$kqzDvL3fYL#AY{YB(Ve|aKAB(EE5)ywcFF_ z!X2G81lEE`f~dH`8L^P870H|>xtK$QODxe4S|2RH8uHj%=V)>8UNHjqM~EbdiW{6Z zTCDuURYZ}eb-2V5jKKW{cGi5ZAWFjt0#>uLhQM0S{U(!MFGrdY8SFiuHCx!qy`voR zfh8EB_rYoTXNe!{Z=grgJ81~4RjvO>GUBQ$V)43uPE2Zck}h}|Cb0w~aKC|b+YR>$ z@4@}3$B<4M0&77eK~&t}EUQT?zK9vg6X>dr;Sx(QLhpk`{x~HvT0A6mi+0u!SPLQv zqT&XpjlKE2WtA&wB)xOE#1f3a{RX)38t26$Z;`sHPG=2)wU##SOFD%lT9H?k-QIG# z&on+|W4Oc;jKKW{b|?JrgqXe15YIbw)(}_=&%1DP@}P%&bv0H@so6+k2}bCB@b`Up zY1V>2(_X>ha#p_+q*KELh$gbs!Sf(Q5=8m#&S+v>{iF2QhfJ(ii$IAb7=imE+`l_w z2_3s-IW-ox*ZTR(Urv%^5K$;UT1TY6xI!28NP{~d8ftSbMqt~pUR%sT=T*%v9K*WF z^Mg*25v%5q?}ucwffqwmNhnVSycnXq0H-H2acClq*x(Rj+O?Eef)SP1CKC^z(ZuP= zJos?ZJj>bcU8n>vhNzKEjjtvAPmrkh@#b$GG4oPRxTp9soGYp>u>>Q)iy_KSae6YV z@@8h&e!U`+v-oKUtc6nxcgl{ zFv6NeEgRs)NZ>_<#fz$W(EJwGvU;#(1H2dsyr@94^M4SQH(=QSUQ_}vD$wj~BCwV< z5?MBY7Zt#Z3X2z2{>Oh1mRDoh0A5r8FDfiv)Q!Me)`)7^0A5r8FADLw+gmav7-4y5 zmJQ%V1@NNM;zgCWWFoMZH8WT?z>5*en^9$jB^Y6OnU)RUMLF=I(&9yxpJ;vyYgsd# zWuu>5ZwFpfsMCiz@Hc{1(=-W@^jEzR7latw=68Jj3mU z{|AA4Gu%74emd>9s-WDm&g4av-)5;+j03!=1YVR{yr^3Oaflm%dz#6M3gAVF#f!QTSPQ%uqC60%4d6v3@S?=xMcopN zz&*|6MFsGp+~P&u2&@HO3{gId(*}4k5_nN=@uF@CM(BMIcu@hosIYiZHv($``$>Qo zwQK+{Du5Ri7BA|SV1(WWfft2c-m`?oi@Fh53)oKryeM(=q5^nPVez7F2}bCB5O`4m zyr{5vQ8xl>ffqxR&*CgA;6(-SqQc@u-4cwzJ%Ni15{%IMARlo=sQXKv)C`y4#SrDq zC{G4hPWL99n$CrsqW0shn46J{+`#G?j z1b9(m@uKb?Y#8T$Iw6Yxa)loJ5~6rfw*(`wZD0rc)?@1~G^Ag?HF;6@ElI$5+JP4( z7BA|)PslI^ZS`iyJ-U#{2_`S<)&f4s{^!Vh#NtH}0(emgyr`Hp*W^W02c_R67BA|) z%?S8Q_l-BOeqJ(N052*mUet}iTEKp$0xwG3yeRBQ@sSoU>Xu*x@R#nJdrV$b052*n zUet}iTEKq#120P4yr=+PR9d{KTY?e5U+xE9l(>0O0=%fScu_Y3YXOUA174K4c~J_y zsI+)dw*(`A@pRvd1YBRh6$-qlw0KcB0&C%0m4FMcQJQ5k00f zyza*izV{LPI+?tv8-cZe7e#emX<9j1_O7SMGQs3U9l(ncix+j@o&}7jyZ&MCN7<)h zRzkFRILPEh-3Y7&yr{b^n7k+jUQ}4Ts10~gV)3HxQownFd!66@O8Zrv3@eHzFX~2M zE!>VF624Z&jMZRuRPmw?;6;hWi#l94e*w$s&J)C(SN;|sCO0H^)|y(h z@uF@CMu^za-2X~4x%I8$MR#=jADwgXH2wH8RGvRJhG&|WWcoM|NpKY(sK`P`oUC@4 z*0FoTdTn)yB^Uvb1XrD2nVI8GZ4H67aB3m0{cDCe_nnul@;*c=4mVq= z;lwZdt$^LDlDOxik>u0F4guA_-^vR=clvg4LoB>4a`w|e@p|Ae`OSr`yj17@QJJcn{!blB)wL-2A z;>&}aH{KY=+}mZ?iE^{Kia)RfBRVx4%rDfOZ`t5~=3|w*KH}9EM`{SH_05W*JZ!q_ zZjn%6}|j?W|& zTZ<(aF?-T1o-*wR%SNq-D`|Jz7tv{Hq=vv+i}K9o5y>Mh8^N&ysa#W3s`|hZjA&YH z5#M@qpk{3?MdIs{i}~sJ`wEe^B6Ku>^ofm?*9ywSb`C_&ztXBiX~UBh($>qwSJEKHb%qE zk>}I-<9o-%jf>qh1lCG;xtgz>+ME3P;R}q3j}IT@Nk(>=cT<$a5{$s504wf){gHaa zeoiQU7bCFN?68Hr_ntnMhy1RpKZ$yoODY}?OE3c0reSm&e~lcgpDvc&>7*gB)~(Dl zc_xn`mW@fx!s(YQS)@mWaET=tfm3&2&@%4cNl*lr&;;v=68o~JhVr&E)XuU z1S9Y$q3+Cd&>p`WX$Y+K&y&7nI2WZiIyB^ZH6JHtrJ^c(Fy zWgncb>7*gB*5a(OeDutfmW>IAaxt|cu54flM&MB!ZV}|?>FGQt>|679)(}|h>Eph9 zNT1DC1gTEeln1u4*0^wqB^ZHcA6WnJJV8STdeM&ooizm3!u|uiW75EbHCr&0es~@( zu>>RVENU2ihujiyORN~QHA)^@oyPZs%r{2>+~+&{p5$w1#FJLZbD$5_TJwweA=N`x zJRK;p1S9m3q53c>UfozC!fv;fx5u9bPi7vOp8IhCM&nUJ?F2j`e9Jx;eJeH8ybKM2 zJPz>T;`_kcIIZpHVu#A(chh-+O!LT+9XV{+9`-n#w_nT(wTr$32T3f!2t8FZwrvt& zjwD*XhW~$F=W?Am!za;TY(HL`j64#>3cQ|2mE^}dHOY?neCF?4L;T2*p}EZ$wOlWC z8AfFLz5Ht$|4TctUzwrov(qpUIv4clhb$dR*&HZ@Lx-4slo_s zTfHo|R;1jn$nsRrFs-}3g|*Zvv9GC$BAdjDBlTIM<33t?6$0nO^|lwpoJIbypUK~X zHF@JOUrTdIFhc#lQY)BrtDwBuS}PBTm&t)_Oo3hhLAbQ^_tjvhh{*c9A?tfLN_$gJ zeRo8aE~LolVDn3^cjmOV4?)SqZ|c_y6eNVkKlOqjA*tgi_C>3(wLk#rHcEsHo2IgwxNlw`hA z=z2j=N7PukRMdL-5%};z5=&GHT?qBtWgF(fD%-`n`eCxxpS#Q&bZPzDp6fk7!>GKW zF1)naMpi1;z-$dJ2}W4;#8r!dk>R(qqMKg>Sgp=xwssc+Ypq8w3mQh)@Xg|Q|6sZB zTrm^jda=-|XRcbf%7^RiL-4O0Q^<4w7V=n1RTJToV1)V&y^E_+0z8?f`^DJ517+)a zd(CzQeZu`+mpwgIGkSXQb3e6`aF4Ktz*;y@P=nbjJ4)pLU8omtl>|lxuHGM1zg?$r zRX$v&b0GxH-IHvGJpj!|%y*4yW_lF@Mmw%XJ3Z%d6(ds98vDtRexEc6Mqt~pdnZS- z`29*=dEjC$bA-cX%W#Xi}%xJwT4em@&U8vlf+B$0S=PJgF+UOjk6EH z9j3v-1>}>O^%xtQDDLI>jki1)PcjW1X7ku^n%BKKpS1kGg6-+TU%5xKcyh5*HE8Ww zI~9>%b{At2E#C<&!HATYGyLGO1k(9TAwcwwy(kv-2&3rzhA*=4`Lt88C$h`)>N!Fv;DeWZHxPM!b22&|>&qhkA#^7-b5V#YspH7^4ru)hMU z;k>w9QT-yVz3Dr)^5>aETuUT@1tRVE4L|&<9h{@zH;BI)SewDgcy$kp`<1!}6PFWs zjh3j_Xz{CdaBiEHR~!H@k>9Sp$Tn|#3W@!^l*nMa9lsw3w;>)l%A585ULNb^ue~|B zZo*P>uKhGJd6N06uKT@9!>CbZ3EYqJ0p2ZcqP@IWn#PmQ6=ssiZFTwxxITPe^<+H$FG6GYt7X*(`BhyWb->A+Us0JKW!nW zd+y@?seX3+&KKM#Q=vaMg8v~mdPGaOYf!zRz!l47ty-GDt<^>IH=JJftWUz%4iFFe zL}&=C1*M^0cCZj$A9IO8_s5tv@OQC2yx$9M^8CYxdJUk$D?UPE2}VFl)oTovjh8+D z;gc&4B74U~YY41mtwCD|AKsq^!TYzce@S8qMnE3SnpGtNHx(v%il~CKNzlY-4S}`r zelPGW>t+|lk7nn0#zjjk!3ey23r^8_^rjxSCXy-ZA|#ezgi4|721B?RuX=8ApvO+f znyJwm0&C&@UcgiLolM(o@e`FM`^&lmQb_ldoo1OtPgp>5FEw|6`l%Xp-S!AOu&;#C zO^2(|E60h%5{yuF^YvE8eJ?+e8(q7@3)(?uD{)CM0`DCK?saEt@%!~^JRx70w(A8_ z;jRPt3aaxNu?NZVy}uK`dQCJ0*1|hrV9)j+O~mIpc|^185fV!<0!r513*f}ayxH8i z^$o-Z(Gs_CYc<>~H@&sz{xdsS)FT_c5EX5f71W%mg%NnSsXD7aiD$HkRrj!H2&|>2 z>c;7l_Rnw%d-LjOi6t0;^9NqW#!j@xi9bkM z5qi6_AC4m*P7k0(4l%8js1&;DAGbH~;fB2D)6RTDH}q#(OT-9OH}G$(*G9c;Ogok< zAy##)ry;P`$hZ@v-uML;VsN0pXp^awebjm?u>>P<8-qIsdIi&{y4g95bQ%I{;eAW0`FtWqZ;N+;*jY~b&{-;hS`ji1lc zydDAvFzadnJ6ZD>U+}B9W&>+sG;lImOR)Ik-KeYu9so)e*1{=-^9H{cXUF0ESll%t zaeC|AJ4MbHo6D2h`q=Q7;6|XM^;z1`cyT51v%nIJSi9*oIgmV;!znoM$eNXjhLhym z#Pc&L8UkzKJQ;>x$A4(ScO^uTaxq$}em;DGv|9Qj&vMYqhV6j|P^J~zx#uFCPKSu~ zV{emnRinwxrK@dY$NrD3yAeSiR<32MvE(9oeL0RS|0^6)m0rk~-S*leGOsNlaZ2!a zu|1eMN9JbX$J_AJ8ym>9CvOQq`Xu#qTrJy?Z(ovx;3UW6TRCifUcV-XRzFCEJ2k;Z z-R-&9w6-yhGDCtj1lBq=;|(d5{ew-R!O@TQX0}5cN$=QTxh(t@89i^0z0LYsHmnsL z_BZjUw#V+Y(KE=4!A)!=eTt62TC0~oA}tc=zE1H%0Tg=&ekxZN& z$Hj(*HeAwr=~hmv#?(zAdD~@`7=g9AZ2BKLmOYZ^?H>v@T0iq>~75Wr-yif!mm2 zgpUkisby|+wW^O1SPQpM!`O2_gl(U7!?rw|m#k6$9ceoBZ`;FtZERQzw=rnDuY*}i z%raujq$98vZlN$T0E083Tz$A(B&RGE_k?5}lb>8D)XIjna2tbL2Bf7oQNwPU8fy{ZXPUN0BS(T;k z`-4}xQbb}2M&RA15T7@1$?ma@RhOZa7% zSb`CF53FIRcYeaMUnF_fX)p5<|METnIyVksG{vD$2M}cJ6%>lH38@IP)O7I>?D^9QwS6cSt+fTmd zU7EXNoc|#3E=|bCFb4bQi_nr&+%b-cz*@>DQg&2o;YOh6+w3aNnLNtvk(m;_KN0VT zg!@GYPUicH#M0?KBV0b5iNIQxXKC3eb}x(aEJclIw`chu1m2|yt4ovTaF1Kx2<5%v zZ(%K5ZiZ2Ob8q@8VFJH6Ji_JmnKrEW!~BhR7{mGVqSeI6HBD*frFMyH3fG|WwZ4{B z(8(OI-|nP+h&akO zarwLdv4MA_L65rEU8M1z;0!V1yNsSvHym#!%mW{v!7g z9f7s{EV!W9Bb zFv5z$t$a*-(VxCg3nXiIIqTfjey|p9m9Xo6wWm0-f2J92V+ls!o$GLK6wI?H7I~Ah z!=oieU@g71!)?Iy2IM27NtAZpK-GuJml_N3_y{Z29e(F<{x{} z6Z}syurAdQSPS*xvafdC+iB9R zyYloO@$K~9*=RN^VYk5F!df^_a9%AjjK;>~yQ&M9Z$< z+8d_7B|lGYX8RPo!M?4^YqDl;s14f#4modGnkCU-f%%(B{4HE=*fzXS@p>T5RKt@E zdf7mF1_hGgp7)4~Sg_WSS(Mo7-BE8_Kv{KzR&omBgMO<*Gz8X~lPen;H1>%VO*AW0 zliqk=mBB5p5|;^1JI)h~aMumm?P*c=_I51|fwgoS5n~!qwOVqwqo>3YjCdcGgSPe2X z^kwndtn&MN0+%S(!u1dA;PX=KVYzek#kK;n`uNQD4zu2n=HK27z-^337g+L3%}=%!U*3}ZKb8DfyGj`uOdqf4$cD~w z2y6o*a0`W71e=tAlglO9$sF6YmoV|$ve-7f8-6N{X3p1~d0kJ?QiT!No;u^c+!5Mn zt>8z>OEt#6vtBI3@0#KlOJTh>Fp}&qRv31l1^gS4>U!}MUfMwK58kfznD=cuK`i-F zU1ACTE`CiE&SsqcLTruCk^Eb18UkzSuL*u49YyWd--=6BYe_7@2>kvi#Llb?ZCxNc zDRa=SA+Q#H$xxMzFFm}ej_CHt4ypS3#vw*1+h5-Rt-EWsXtik?&-=`oDwhN!@VkW2 zYrj0=wbu`$gC^8AQ{_TnE&av9KQbby=ab%i`gy7$u$C%y_xq#9@85pU4~FLyg+uC_ zrR$Pl1b&4RcGiS0aU}JdZLX_f2}a!V z&i)iiQzHYkmwPcnz2M?{y%M6kjSFat)H8hS-_zQHHyj}}If`g65MzXT ziN^J&ChW4v>uU(Ch2Iu-6n$ad$35j6%qEpy5Gyh`@-Xof9JMdKB*`Um+AsotNuAaI3~xcUgq!QiiuY@$@#C}4k}7{Kum$BF z&bJ3$B@;%4*+z|=$NPUdMb4cfP*&BxbP;j$U&GnE#u9%ErybjdxR%Tl@WMR%J-(v0 z>mGl1O8H^D&(D`F-zPHhln9Qk#s+tNEwBV5a0=lr*5?bwoC@BojlHJC2&|P79mH1$ z-60jTtGg!0_1YzBRH@4@4*wvq1S8t*4diue-y`aT2fSWacYv7OyfB;gqKd=_tTn5! z7q8*v@?_}hNg^)LxgJS2_EXq|8vvc2MWCqD_|)tm3a#B}QN^y>!XF zN@CyEPDxRmXZ0bhQM05#Q+B|p%ZU+xhQKt zuclUm_>95SZxeW%0Vm0ZdFnp0i0o@AAam33f3RSxBOzpwQdB~f>@NRcwNmYhOzI- zI(zJr>|(>UXf0KEA39DU>`5(sjH|V^jS(jA<4!w9;Ju@;5;yR){py6FG$Yz%)!YcI z1$jd`Uva0JNcJpG)k?L>xhp=$CkgbjN``y3SGG>)c5d=;?r&iP-tiAST)Uk1_s8>z zeolSOYf#YvB@s*`QE1`e;yA{%NMOmAJ|ZBk(B?n4M#`k>0@%|AW9f;0ryQmJ+IG+2GT z;z6&p&nEgd4Kh>Zl3;{tyNW+?_Nc?-I*5gn3)6e=Y>InzOE6+%##WxM&^`-MWPdZh zGH(yDfG`b#wNxKe45-saB@!prZei5_LS2cq@ED~d{w$hZ&N@W|3$c$e1^ zSWC}Gi}SY*b$<~?EB#6}8(0gMf?*tPamU#Xo z7S_^BcU9_Q$GBdN#jxvvYHh;(vMs(p^HJRe{Qis+yxxkruwN8b0R*f9P-_)HjR0n< zU=_f9+qBgxt+ML<-D7gM{&}u$Ny8G1!1fH|+wr;ik+=w&Iygi_U@e?lIQzQDlLG5Z z)E+OKL*S6zcT(f_2Ct=+$WDQE<`(O$#zZr{7y+y^x;6VoQf~pPGDNM);BR3qRqC!1 z0blfF4!G;}q(iN-UGk^FQ{Im-xt2{+zm2jQ$KNF zW|($gI7V3Wid7%mKh3m96$zl~#&=wbxSkbSp`5+8`ry1`R&Zl+akzV=HYFHgjjk4A z_~I?ij~ZA!3~`u^9lvR5o80#7y)+kNb=`QtwbeEYjPq0owY)VSk_d>*JF zu$DF3S*e<~xfNa1`v-C3O`vO5GbI?Im(`rIOu(KZxFIH3dlvxLfsRnG(Jqh9E8CT5 zptx`js{rOMB;eTHH_rk)?7l4)*3TPF5tnKNNk`^yWVNaD`Gll2J}%Se09?BGOTY-X ztx6PEvT9Qe%?3tbdxmjs$3Jj~myh&mY}anO#R%NH4CB~^?R-!`arq*MsZ{`XdV%HU zunNGfRRDMX45R1HxuR4M_zO2YwNzom{jGEP53^76TctxFj@sWTMZ}bEDl@7it5pE^ zx3Cs25x9qbN3sa{$yZiSEvy(}4xBz$oIXZid+H5^GGfZpPO?YOUqs%R^^S7>uldz+ zp|*CNb30(&fU9+bsHkro3k$sCKYFP6oWcD*l{$SA2mc>i=K&T~?*08i?1~K$Q7ov~ z5CuUIXOdvS&RP%^8@kvL8)8`-C<-blhz0C4J1Q!QGD)m!uh@I<*n54?9S43V`+xU& zd>)=X=QAg{H_5%pP0rWBS6kE1uPwd`I5y0RVuD2O(|6*ov+3JJewJPwW7)z~V}t4M z`L15to}wFr%ZWZ)U1jwa4iZ~1flI5?#UA{~{ohrVAy*nJ1onb;cn)6y%)4Ip&+-)g zg1zOk_@4q>FyWO}oIl_7ijNQY3rclqZA&q0eE^`0tmkNQsaEpPnWS1P^UYr*lrdVrV z0gUh!fSbPpHBVPB}|_*WfEaK7oHpr#m_(Sp+p~ExF%AZM{7| z25x=$m*51CS5^6HYBd=bzENA#&)1g4YR&kUK&$bU6pr`&WQkgE&KU@xq4u8mhO$e8yb zB7U8_(%P{WGH%B@-I7)vMXRf0$P?IKf-RWP?th+6y*Ar!LyB!HPRr+*zL?}&Fo8=5 z@6`8?8iF3i2*1NkCAMHft;fY;Pid7`I(aM0v_hY+0u5`(`T4M6ZP@@T^!(2Xy-TNm z>Al0vWoZ0WI1gZ9SorHR?^D7}k7K~vd;Tx!bmY((YCVU_f=^B<1ol#6l*p{jeh0;i zvzIDpEA;ulg)?*G5<)K4&x~5X4wNgpWoRq(`Q_dBv65lbjnCZjxsM)~R;PnZ*0kQ6 zKJv!ATf)O*onhRq5Bza&cReQXFM;;i@^JcdTNN2KyS}#Go*x631pgAeWqfs~eWE`I zKzb8(PDwXUFf&m>{}4z(T&+)LJ317p&Y9_zJ-P?D%!* zyco`^l?K(Rx)NtGkGGE{E2B^FY$v^5B?iqrN{dFgL9Wzi+INHe-@=4LjZk9jb(L56 zOIy>oy|$GG-D@N>AyX_SuoteMPG{LLlx`o_OgdLBtF6%IUlZ&VHlsM%x({^gmukC3 zzO3@3C4L(~C9jM^U@v^tHSNr^WYtSg=~4)?RO%O!Dw~e;m3BXy<8u=a?k*zL+Z^Lv z=WK$t@MC{D(z-p|;UN|0nU3!(8eWy?nxwp+<${oZpaQ)y*+@MW#&8+S+aQzN}>w)i}O0>0{ zMES}Fa#>J$rBs-}tp|4Rgj}K@b%z9;NMgZpyLe{P7#@?!44_uWlYAENwsB1i8-8!$ zpmEDLeqo?qx9|Eq`WKv~uh%z#VGAajMQ-NlU*>@JS`#2ruFV9^7oEJZt(`((uc8G~ z`OnW`<`^$ml%nZBPl&Vj0SsF(v9f6je_D2yImX_gxnymn(o!b3QwZ#J!)7@@UpOyD zowakbxyvp%f8{`XvSj87RP^+K?%Bog75>W(F{9!9<~^k-W~$&E^>Q z+)jyv>qqFvy&V(+d%f%u!$-{7#g`V-`p4-Cv&8(LX*8nvK!z=tu-m$TpZ&0dPhO(+ zkBLQVGuvI(GRpoE{kG?wjxqx2Pa3 z_ zCa~A?BC-6STe#^OYF{(L1?kGuROx=$kcx>k`q z?5b9e^x?lm+I@T3`kNKQ7EIv23AtXrHj*EGib$K57bzyN*Qb`@eEYA3{L0O)5aX(c zvve$WR#Xox#jphvxTirrfJ@!v$;J_|)^~$q0(;fhPvh;&FXu1awR&V1aF=a##f8n# zY7AR2f%~IQH*ji4I4e4oRNM54Vgh>|n>>RLJC({kr)n{x>^vmoDyC~rS7O+L3Ecld zQRk44{GPiRPM=+%n803I-xzf(o!>sHU8@p7F0%53BeZyo6~h)x;Qp`a*MdSt!3s>v zV~Ppv^{G`f-|7Y84i* zYR!cFe{=M+U%cg^CuZ?!4ukY`@)v%t^ekTAFB#sJ9PinPNq+yxOYn^XTQKpQz2Lt} z&E`LJsX)BnDS#Lur)3P{-?A=q=f%;y&{u!`s1bMh-yb9S(KQ?NV%8l#&LfK7XgmOj zKGBQCxo=}7%u)%qU_y=Y;P40`4~NQ)uWE5jU@u%kXo)Rq%K}ceGO$d7z*?VpwRXwA z!~FMzME=`xBa}+(Q9c!W%dR_GlGjI1^Lhz!y!e$A{gWn_xvqIMpL}|=9@kH&yS%o5 z9QdM>v<=n^Y{BZM_?NWZR25|W-_2!0pyjkf9G_ldEH|(#qaCoCGU;{fw%WlTy>&Ol-$~}@ zYi02MrSyi_nd|w5u3LHWeFR$Ko%+eb^V)ln-nte0-De}ee|#(dl;~!_v`RF){76`J zE-h#M<)jeUtH!^Z`QMi}^9y%1wPyc!C1m*hC!+gGXI8V!HvY|fBPRiF2JDsgIh`-6 zwSjkBtd(lX*AL>0Z;Gg%-dZ8B*SwP%-0ndNA4Ih0U@KZt22Y6+wHCWFY{A6!N*R25 z)f9g9il!Cso4rM}`cPK5h{0@L?|uBt+*RD}n41C9({($z#oYu>E^76d(7CE`7-BER z*BYu2*bBeO>U0r}{}Cf0+k*XzzZte*;z*TkywSZ_KBk2hBk0}s?1Int39>qn=_|(Z z60NuK_|Z)bTI-(gv4c~-7uA*YioMd4r7{ssz6ZmfGbY+pH}rt?Pb5U156bY3ZAY>yh`LD(3E zEttS>HLwG_xd(N2Si@m{s}R^r|8Nd}`*#wjM2oR%MdMhep8yam%$8M zFoEA>HLa9#u!<8)vIeUJ_A28wkNY%;(MBiN2m9Qfjbzw@2|P~#_3U-?$Q5WQWe%$Z z_UhC*fv+q-hiiJ`I^8ID9e>$1i~IS7GHk&Fp6|e#%=sI}myc@E3^`IEuvbs7B>wNW zIXpT-s|WnPQD>iItax)I!xl{7c^mY><)8VOjs57(=Ya}=z1sHN$i1`YneT^h=dZ?g zPUnqBc8z4%f(bnTgzpBK9mTERm1tPaK?;Gr)RAHSh5klR8|PO%f*H180*^7K-G-p! z9xFaB4p7D`?6t*yA3xG_1)n|96RuU6qs`f%_3vPJ+kIs=QRMtSzOVc;{&+`MWo7{< zS${aNnmg}`vNm0Px|K$pXNm*1VQ#_oOIj9vURoZnoXD+4 z{lZE>jDC|wEtmDCy=MI(z+%uW+WTD1MlTHAc2~^HG)A=8+8Os$`tbN|pCZkm+{ZV(PZ?D#@KZR*8WLt%P~;Aj3v{ByGREoR~Ur zTpnS%Ciq%)t5;a`xG>LHAX~duek*U$=-W#{-Jy>{U@z_J=9Lz{tKGarFF&uy{Z{r< z>Vb*#aIIFYxxde4Wo3x*Y|mM0F*@APr)7VIz+SjcuonKPgoOQeY;T+XH1~BhZ{R$O zESS*O@Tp!T59}XF1}*7knDK2Pk8d7Ms(5N|`ll-#f?eL1AU9__w$eR@?^(8s_}pNI zDIFH@gB-r5tZQO0zx9(p>kK7pZ4ludV}$GD{&}kgCJQFC^)cx8m_8&y@E9CS38BkUgp`PImU zJIGm+zqVwuV4~!<2oBE^bBy7m-#~`u)zne8%Ug{y5!lN-D>lc-@kth+m(QmQC*`k^ z{U1VGAA{$jImX=wiNfX9VLE7L&%8A<6QOu@kK+@E&mw=;ui$(a?>pi%?fSb%-s<3= z=*Vm2q~*LKooSBIdO;;n=PtuCJ@VHRO$7EbuY~;hC0)nT+ex1)Idn0}Ul;v9gtk5g zZ#m`|P0kIcIYvwN;!gg$sENQ{<`o@tjFoPG(=dxYbl8IY_1*tNXzOF}hGvctT=FPA zxBVpjI=w^Q`mTw3bj0L1rvNku! z41Xosbuq}2qi$2}9miY=H} z;Tgd{KTRhipJ~L@(>Ai-&BC%#d?|)4m{9xqp!F@~z@*D!z@Z$93G6i?Y6kCnGL?)A z(#DcHtMsyUi>1PEr4_>#OsM^Qvt3{5dAX2yU+n_L1opb)K8+u#x}2I_>jp+h}br>hwkD57XfRweZt#RT>$UV1r))i4s?Lc3NWaJKLC zhbFAx6MLpu(C?a8Bh7uVOHd`!)~7$5$jzacz+OK`rt-ZWGl+a*W?B z3|lavjwO1Fba(^r#I%)EOkl4{_tJS~G zJ8(OnT7NxR7v^qwRXBrR*QbyVmGp)#-_!Z{k{igA`P#~arEi$HF-*rMJ#NQ#1g7vy zMRt%?4VoCbAKk>KcS|Sk$?gV=+sQnqQ3lD}sI4>TZ(2z2pEoF+yjNo2-^Db%Wi&b{ zHXg6X1{Akv*kW~PJ#X!@m9*MO{u5)~f>fdV)^6Y3Zb58P%Wb?{={VA+Zd1dy^E>$M zDv4xguDfBZ-(G$+X*F5=tud79eT#*#x^kH8${owF1rwQFcJL`>l1aO7+FUKE$|`ZG zWDlCrB}gH#7rus|ZxC2gj6D-YT#JrW2s}FD(!!4TwY3D~n-sZChAQ>I#FK>^dF+9C zWMGgsyDJ({kz87z)co9nQ4Cu!fu9WUE?Q?7f7!st^rnvq?6oUCiBI`3hum=2Vyv5B zN7D9>Hf-xKnqdnj@G}wep06#Iy`gb{2^o{r_-S#ycYP%TFH&R_ZYkz;An&=9t!_bR^S z@m>;k;Sf$VaY9BlucO}n-=PYDy%xQg!<#-? zOJ*l(G5q2~j6c0j8T?8GGi<>Gej|s>s$cD>g--;z+gT;BS9SO%d=G}9Kdq#h_fbyv z>-e56p$uCvfoB#bZ4TlEyW%%A304T~rM8mPJCv7sRM?=kD{R38Zf|fNXY>-%rByhn zM~q_1;Ae^Z$9=rW zk_0loWIMRJ*`4aMwEeHCYhrPREtpWBI30UrQ75vN+GO}KToPPD{7cXhpMRm=qc?-j zNGpZFUTO@t63v;{j9M(MNH02Q+aBI_>;f`%G~rPP_T^b8gDJ%<^JS# zZin-xTk7exS$s1Y&L13Usn_P}F_|;?{$g4-l4766iO&tMiY`CeDFpT!Q|B$W(}(kK z0}BFit9_gp+M=WMHyji=2L9TE$StMR0>=&A9&(=Ms`LB`-d7ZVz^!QtmTcvBf{})2HhljG%n_k=yk+&MYf7mwflH`;=PV;~8y^>$DSea}_;=Mi7~082 zKn6b9Vm*=Af(d-xbh>ZHbfWJsUpe5>8-ecuzW*xmS?=biXP1{zXT2o0U;@X6Rp(<* zM9-#$$*JBx61P5W6=z}P=_c(vQZkpXfw}XrLfS698P(^2V$WRC`TRhMEw2Ku@!H=b z$$@bN|I^xkM9dLC{%+3?Y#5}(zy#J%fiEU-1`;y-kvA14De5Yiz;-y|`p>6taZOFsbXt~IkMgJ4@#7@6V4_j*Br@@8gz5gnYVC~a+_|bN zE{g0ileDC*T-yq*z5v*ry`vMsNyR9dg{-JzjDN}3bpq^`L4Ok5ft9HSg z{@-orHpf9c_}ED0>S8t0#Im>Z6*6_YyRXL@i$tW*(I-bJd86P2Pre#0R;h)(oO^qd z5~F^>q4H3rN8!HG*fW%X;x7O3<1^ernD3F3Jr|1EGt@qaz3_fm_~M=zNZ9HW;pZ|! z*(r+&b)TipmsK=s_H~l-D_G(dj`O{$tv&e2YWn^goUpbWC9wq)IMXrY7ag#ck|Om8 zypbsc_QE-AVUANVlX_KHsE02m3W2?Fo?Pus2IdxXT_7j$_qCE1bcs$Z(z?IFZErR8a}+g|C86_w~pkvUgY?^6F5c-@9NO%U2E7>AV*#Hx52^i(7Uvjd1xEOsIWu zScfD0!0Tw?*2^@)zX zOQKiYNAn_mM=1Rq6F9H8PB+4G6-~V(3`4h%R0!;aGulHw{hizB;Nj)Tij_l^EX_Et zGgdi=old3aQ#eOPU`g}`3;?E`ijrtc)fcPH>0UK14p zd*QbM?VeX4W6tj;8i6gCXkK(VftG20I#;hY-WWB1H`#8f64(pB0fHWj#WD^W>m;|y zMEUJv24CMRl=m`xY>w4EaSsOFrM9-lp@CW4(_4MkVgf6DLMG33RmqrRTlm%730gh! z#}Djz|K$iW z!gZ2aLGt^XM6!9)hrRtQ#wql#Yo?JE-u~FaQFad8$MC;L72{rYhD+bGw z&G^IDW0kiI?1kSSH64?M)H98=H z@!>fg#*6rJlN425JXgmwtQ6g9#{VfBCfbEgR0!;a)xlxq?wJL>BT9*yw}(pnj*DBk z%in97Jve-Ygk9F=IIX`0lQnY+(9lA|B)0sA$O3}r6C4QfUjpcSFZG?F$1@87rJ}W< zRM>(EC~daulxuwGV67#>d%J-5c4B^S&wppYUeHRiUHB~?Q>OsTQsH?{;CW8W&+~kX zHfqASXc{@S88M8DroZ7N>&lV5^u!GUPIM^!1NRAh${fxjJCzleWE?;CSEw?I;`JFk zKI(MV11-his6g@YcBpa(F@f*DY4jm5CQ|d5m|tEP;W&(mrn0LwhcS`Bm`KfIVt&mr z0b>`3G12_a0AnJDG11dJCgu~^3*RSGsSGeC8q8y2{{6s&HhY9I(R_7bOfDz#TI;@)fiVRp5X^S))lSng0=A~KL#dni-8k|5ASi$ zj7p^6uMma6Ug{m}lOc(5ytOeQ+caL~-w#Z{*u`OlGhba8;RuXy#5}^~6W9y4eAu@% z=7|Vt^_Xt^Szl`FqRU^05l~~)zux$Rw|o&!3ZAH~$E#m3y9-<(wv99}H@ElV=H54a zSD^^f>i8gqz`q1b= zH~Eu;QRLp_dir%!ZgKmfb4ftS!9cj&eJ7@*bz(~@FH#8Xg|#R(ExJT;!m1eS`n##b zzl*gR@d_J^KA#o|(BP#VOLmjkf(dmU&b3~A+VQv2M-MzA&yuKWT)3B3H-ab zg!sC_J^v7`Wtn1A2fh>7g0CC?CAhjvS_zABrP-x}OkxWr@HK>f-u51!^6nfxAJy!$Y`I}&?oG4iyf;Z487HL@ygAhYjXODV~JvU}) zmqpzkfh?$tgNewqU_$F3JLjU_Tg;bd_jTMif*KQnT z=u^pC_6we^s5N7va{a=h-H34hp;ES1s^Eq6!L)JmYl;o1kp55K8GD(px>-rN$jKm@ z*?fZh{o_vyhdXGpU?Re~uy8LufP4JX?qK7`3#i|-v9kU~>%4nzBCwYhBTxMpPORUL zBW25vmhHOy$ZJ<7U1Us{TMYlx5-VJ;PJQnVmF`XNDFpV?V*F2g`GIFq$j~%EJ~A}T z>mMeSV@zmo$X0%?-1=Qv*jsDu`J7zM?ICp?mMR4H(qiOkB*PlO_JQQ%VkRfA(V2GR z=2`wr=uCCL+&*3HJtt#lg9C`GV>;P^uplrjofHCl zX{E~3dWLya_FDS1-5D{~tCxw$vtR=65r=v0Q)k!>KbgV(Fk~%$&ljAUMYi=$)c>>K zDPOr^Hc9xBqQ|2))V%Ff5%DyH?TM_})&1P2AMxk(~->S#83O&5YKm{`;M7QbgT zmmD9v9@_5gSJfnBwT3*xiK5%<<9x`?#l$ISg&yay#QMdszI*nIx23mq{#%qpa;NMlB=f?`Z7B_zMWh>okaQs`?3)c^>)s2es z(yD?iwEcaNd1oKDs+dYVos#u9M<=cmXr*kbFBeK%R=H6Xg}`2+y2Jc~?Q-(G#d|)uCJlY^JH?gVFnp6vAF>& zENi)OVdqb`7VMf$bwzs_6Ih2C)&RC`prxH_um{P`N{r!l8_8FmPP#PHEAgNuT7898 ziI3EGsVf`*W($$+Hjol^yBmu1PbZV=ZX#1|dKhqNVFz8M?~pa3Jj)EPs>Hwqj;H11 zD8}M)jr79}50+^Qn$ZPPiFI~UB?gWSS?gx(rGxZ$M9R%B%w^^}l9E1;MBnr^{HU~% z)QFj9qL01YLat4UB@-%lhg}xh+1;V@GsKiWJs7rN!ZLR&SsEWp{+y!o{H|m7N`;Gn zkgf`Wy#iWoCnF0d5Yj-4;kTwTd)BU@_|e=;QMSeeR=I}!SLLg*BiD+MI!{_Kta**S zhUS1Sc1#lK9j5KYITBouf$}N+9ptMJ*h{@uK~A6OTGpG+{nk^tgP6cq9r6K8tRtt* zEg{rD~ZE1UqeL4NXXWbKsL@Y817!5OP&{8Oga|OY96w~R;GmniQ|tL z!xl`ut22-I`NWdeQmaRapf_T<^Ey$+rHevfuW|bqkUAY>$lX#}4ELi_Of?)8umAN^ zG`%r_^}XT!%GeoBPF9wEcM(N59D896ad;Y>xu8$E20iy0Wp#$H&Q}!2Ue|xGC9n&M z)Sar;!*yjvy7E~GSz2^a2<(Mhs7~ilZ9KeReTFlmeoEWL1a6hEFC(g|biTfnw(HV> zVI_8~(B9$A9CF}i-i|H(&9d_BHw&6r$VVZt7rwJF!o95_KQG>9tTKZs_Z$=WZo*fY z2HSXQ?K+^#>dvsjJ05Y~hb9s@aZ0okr?4k=LVaT6MLSQf4yG+jy(Tdg;{c3h*Z_CUfn_DCh?Nlu8 zwQ9Rs_^^O9E-k|+xu^v8!q-j90+mTtZTL-pfAwXB4y2FO`?~S&b>VnYu z9HtEhw`X$ZF5=oEhSYLmhQ>#Ckbk=@Am*$?1WrYmcf@=3o+}EKUPqV3nogzUTQH%W zrh>hM=2I#6r_B_nn(0_VmMQB{K7qZoCmo!MFvl4A&`LP{eUc^=FrBW+w_rj$O$B=* z%`wIVMDi={r9qX%bh;*=z+SKepTMaIa|{Mw+fQ0uql5LPtV8)0OlYU6U~i{6#+D0~ zG`yn~^Nur}63QpA7vvcsa4NzaLpzfi(dZOqhfGQNB_({qVCpJ=xQAGA!SM2{JJx*^-ZVf@(JvvwOcr` zV6KO&$fVmB4;B^onX(S$TQH%Wrh>ib<`^}vo}{5i)GSgjVbS_1ay>E(^PamMq~`4#foaGTcrj zucpo*Z+x_@L!fXZ-e1x)y@eIS7EGwUc4kOn0a=Gk%5Rv!UY~0$C!Ogu@+ZrUe7V}V zmUUpz-x;=GLhZFSE#2v~Xn*FtJBMNdd$rQVl3NC?>F1D}5ws&^nT|eWt}YHsKcyy=%{GzCa9Q!GzjtuiChJvE?rET}23n9Q?INh-sv8s&*lU>A zG!jr^Ir)=GXUuyyw(_6i)P6=ahAo)D{ZZ4Y?#Mzu4dj7IpC~4<*SSG6NRCV;?3Z?} zZg_bx|AAJbN@^vBEtt@r1X>&TGx`iV<-;r|Z5A(#OK0|6vE<8IvMqK1222DxkAG_!>1ywXVZU0*Xw##x8x?$I%+fDR=m3b6F4@U zgLHjL&tEMlPnPjeh)O>jk;~%<*d6K9zTjDjncOArHl23MqL(>PL;Qs>Icguxl^^%%dq#HGHk&_ocD5~ z-?E+mnX9d}Z6P}KEiauadNXXn#KR#8WLAY8JSJDGxy_ZD`kpUK%c<|WCrp=E zf++1=fK|UlSaF|4+Wefqe&}nk35g}f$@93)UA@8o?tF53B4i^m&Cl!E6p^pXyac6< z#td69@pR}s5;rZDr;X4kEQumkx0mtOw%QExo?kr)XL0D$ zU9JpUF!9Abl9UWh;O{cD7}m4AWR-r4Na)zg3W2?LZI2|H_Q8uDoq_le*FwThEaL*F z$_!gDabtcI*^#}LANpG>RmtnFvh2&j+`DaKhAo(gX%R`bKVHk-KWe7|Pfo2QXRQbj zTZVWk1opzM2X?EEC@I$%qQx}kt+Xplj18Gb{%*LD2VT_fd0qc|Vt(73;_92$3W2?F zi-G%5#e?}C*kHWp(vac4-6S!COuCrB%TF}?r=L$8UyrquKM5(~2`8%lHv(W{E1dEA zTxc<$R#>}MYgv7^%Y7dGQp}lQ3nrkSkesiv-0Q1$2M-M_$;kfw^g~;{LSQeS(wm5v zPmHOj!TG_17A(uF085B>X4ry>aVZX`prj)a`JFu}`!+^S5)LHG>hbCXKD2q z7UwJi|8-zTYEp&3Ubv^hw~6P=#gZ5YRw$*h(g!htdl$?g3$KH<9($R2rX|Du8TWHM zjzNAnd6jGbtU8ZogKEYSUFGe(?rJv!ZY3{{&LL$cY~txb?of}S4&RK&8!a_{e>0iw zy+4zzx{|t05mjgy#H+B^bh z5qVr))hjr5F40cJT+7vn0bNtcz(c+yD`o77?;FV*R(CgC@YqP`vblWlI(Ng? z_uGi;?pSk%rj9)-vaazV{Otu;DMHVsE9G_&k0U9(^CNcyZex%Wu=r!z)OL|!ilHaN z7EF{myMs6#O5k%ZYBje@D95@dc82#7y+U9w+{R#?A>?1W5tPPzCi^pN!Gu~5>sfap zbJ8h#vNur(?1ft;jBs-n(A+Xxs8?@)hAo)D*A31U#e~zo-X&SeLW4qJFWin{ZE5yz z@^Zx)I$%X_hAo&F(kY3IKR26CJEz^j(2Ii%eYTcmcJ*2)1op!1Sf}gd>CTIiY^ze|Mn}vxWoUyp%gg>Es}<;Nzip)u*h}pn;RU^gUA-iFt5X2O7EELhh$V*? zNAcqCw0giiN~DFHq-DceDg^ezPanuk5xz!fD})P+^=H_E3AMHF{ZT|_HXlOaS)~xz z3qMQX>Si4hjWSOX`=q`MTQH&aK}~1-($Js##(rv{5ZDVpOW+OJai8d#Iffsp4)a0u z^uh%0^RPO&|E_2ar-X)g@KXrvg~t^*8Rox6e1Ef7+{*0E@UsYe;ZX_BrIPNVgu`{w zCDuYcww%*iFkYuB{sI zKQphzkv4MM?i#Ys$7>W@Frm%5V8+D%%)A_ZkBCO`4dwO7(pmjo=VN3*n){62U5w?Av5^RkJ`+uM2wY)`s^uJl(5q>jB9Isrr*L|`2NG53B%vK zeZ$VMn)-%f3nsSMFDGR^r|sdbmA4Ltn0LAf3*X(lU%|Ykj8Q!d~Xty*WmUenr@Z#*O5l*_SA` zV4`}fNYdF5$v3^#Vl-)57IK%o7ndg4Y1xyswLa5tVK3Z5A-AEE3+#)!Cn8qoQf$G* zjV9q_m}M;AdsK^I>)n`})dXU`z7ARn@pX$-z# zO>}05a^}-ZJ?xbpg}uzPdviT{o%UjrUtXjS(r!>}!GyMIr{zQbvvPOQ$%ZwVRft*7 zDx+l=)7BGBzlFWDHF#Lb}*~Yeo}TIplv`)audx;Rey5 z@+^_PbO4+EY6po;{-Yj%`#gRdgiM8{4w=3vI=AYiyeDD;_hvYMeyg8&T0K*c{R0$2 z@lrO83 z6Go#x_QE|)ryHN?M}xW?5dD_)R|xE-j?{Z1H&HhAu_!pDz48{03Ea~l&qVTR8rnWt zytnVJ5ZDX%G|+~+H1T-_jUbuy7GvOra!RAwKWg8RNtH-njWWxO&d`E=#bguH^AU(eN3Y~nkJ;N4E z;5H3;giFkz@ZP}B)o^0r%My*tCq)|Ixkaly*=_WFYA_TjVN1(>oN0(Kt~P4_AI{x5 zHlg49I)i?cN?@-Y*QXkfS4}eg66~yT+)SEP86}EUZNRYC*zq>TLxIxps;Dhhi6>uH z(4F(H8hX8RQV3kC)b+=VTIO$ascJkCQ#LGzbvP$><3Lfv)2jyzol?Fb!{yafKE1xjWou=} zzXZEpUM;749d^=~81g;b8-<>_5`nlC*X(3MR^J07Bo&aIguKNYwLHl+mpElhO zwdUPBog_&a^;ospP7Hf3UtGZOuic^l4>9IU6c6^V%mz+%V%Q6pU5#X`9H z3Yoz{}QaK{kE4^19pqb z`<;{+nD7{tVK~*Ii^0{@60g0lA&UMzK`wkaj%$1EjxYSet9DIN6dkel9qhnfP)j)f zXeI6Le-T(y3+rI11Z08c2m1GyI>#V^EttTubvkViXFrR-Ws|g-0$VVls#>i$P(XIx z)?MDpEGVi^j^r(uo#R#;lNDV{tX>Gu!GAu9cK3SAC2uwvF@e3l4e;khGVk#9XHv9X ztc$LT2&(|O#H)(H7EEAGMaYtNHB}s~H$t8~UR8AeU7fe?_QI4;AA4b?N7FM3vh|LY zcHCL?d3DOTWXOAyDgpMw`jasKI9E};|29F!`kymm0(RbYsrcm8BGk9)&P1zx=W_ekuYjIh5^=*MIn85XextdcYxzo3v+_|=j zLSQdkTGPG^(s|xwX*1$9$E_MGvf*A}Qa`1`M~{(J-csS=n`GD&_>q&n>l6()RnN;O z!iNSQ86{hNh~t>RUIibPAU$`!;+1D;ds4sm4W?01!(`aPp#oblf%U_5I_HukN8!WH|6Ij&@zH{21q*YRT%efc&D+Kn! z%4v`fU~LhW+OeD5-fW7o)3+(4_SnmOz_=7W_DX8Ej9ln(gl~GU^$)uu1=+E#zEV3y zfGwE7+Fm+c=`|Lt(e)luTRFf4_QG0X@J1G8%}$@~AVWKiF<=6FMcQm7u#bs<@JNDE zeJPepkKJz}tI=5kTQH&OtA*eBN|*hvE}Oi*su0)&>mdjE+Xj)uiuSsD?iRX-X)9-#wIYu7MSj3N&cn0Uy z27hSETD2%FQwz=$n803Yj3C*KfmVY|TXC4LO*=`lwlCnPPj%8`FHFN*_)A~5=e&+R z$tfdTmt7)Zk(wqU|{*-J8FgdI8mL>m*IjtFALLfxoUw|*kA{Ri^T!kq^AKA^|+ zp#~p_*D!9FS3|4Emd~Tunva(B+)jUmz+SE`zmP5=@AS_y{eh_R3bMRS-E6ok{u0=d zQvC~Q{BIFM(L!nZW4WIRKa`t&GRzH#@9RR?3bz`@!S=BnTQD)W>ld=Q#?5TU46Rfd zPGeZV;3NFrGe3a|>@|Aj2lD9cE@Qba1A%yu9Lz|gnW7NnwS3tnmn`35&1dgwqsLx_ z=H`-*fz~`@cp4Bndk3>gB~nEpo0bZJy#}V;Cx?r5;$?%|0uj1&2<+eld;MjtR z8>#onbbBBEsn}W|ZvF1f?CxI`H`}xln802!yDpNM(P3Pqv;pGAmfmcc!z*F){iG3F zFi~>xMe^PvoEICVU8}Se-C4|HolNX(DKLS(a4&%8$6sApt-8PH&reN+e7B$6`L&Y7 z^h;J+`{sb-WPOV`67xnot8cy8pXDsOO52U|R0!-9=yZ&n6^qE1+W|oAJlKI{$dW8! z;z}cqfxSMpNhiO;caTB7S3o_sTxi9n&bdV^ADSz$SLuYKr2ou#!ae3RQHg)T99XpD zZ`#ZDioh03m`4ma@1y-U#>RpL_O8m#*SL{4mY6J^x5Sh0q1xFo$jGmh%29ryn=8OR zgQAg23`}evvxr3OJ4S9l`2saRdeer*7~8Wq`}!I1Z(*+iy%&=vD~^)22i8H&Uv@9d zvI}%)K7$3v7EGKfx{#CzJV^ovY5JV2UVf$8IvHqm@EQw3iDQeaB)JrM{>RzVGCq^}_eOX`T+G!wocK%{KaGG^;uPkQeX@5y zc5mW3fi0M@E1)wzEAxf?{Mr;^M2}v=y_!vBUrS~iuw_!qM#e6OK9j?cv>cZflzXku z8Qi8#W=&3Kb4*|_wH}#oO4AbUL)fkBjRYpJ7cMPmB8_;*ThU3ZP~Ybqmju&AkJ%c3 zo&QWeFVaT1Reip5eZ2|H?{Ecy3G6j#WwNoc=SOnBh^8)|JiaiERGjb32N7^1QAl9<$Ld*W$=Sv-N*)D+h_qk27CM4^zSBui2d^7aT z@X76f=y&G>DADw0Pg{25n803N*GBRq(dUTs^LQX`cPcG2-*jeAcUf?3nLKGB5B`0E zoIgSI3uD&u7X<`yi`1S5Syz6D2c^2Q!52IQwqRmT)i~}y>NrVR_!U~>my$O`LRK$! zx0_yIOGMTpUe9n0R@47!j(-WhZSN>49jNKf2~sIsd}Apep9m^rCA9sCNjZh(k%bP-CZ_4`imq6B z6?A@lhEpx`MNhYiiY9A%@FxDI>kK~U*j$2t2{OJ@2hq!RqBP#EO%J_Y$uBufuVjBklNA$csYcsmko0Pki~%=yTo$2OfikmiO^Pi~ zuP@{MohNeF#1jOoyMn5&S3K+w9s!yY{gfD(P;1`o%S>@@{uudwcwMFDn84Q%=4z)( z%J#k;2g>pVav)W0gM##d6*Xv>L--10>N_srTw?$w>lEgHr1{agQq7|R^~ zlD^p`WrJ;v6astU62h)x-%x3ByQR1m;h?C|-gBJ9f7q|#VSCmR91rx>B7)_{W>es+ zNpFR~UiiAfXB^)qa_ErSu7=fwdW%|!~B)H^IB?cz21~AO-43ngDn-ly< zMnmQ5VglcrKPSVURv#?OZU`b+>lLffsyVO^4^0s5i!Bx{27m@A(i6pcpjfd~ryE-B zmw2@Kvv_#gojqES&ilOD!ZUmuC|af}(RblNVHtW$*f(jfXqn;|_?KXx<=~4Vq5V;D zwnYc!d5-m2Rl+&wqcHqsA#*yYrNRVOTZNq*)8>lE^~(gzb(9!bDHPMNbGi3Vv7*E? z@xig7QgiQit9bR2MxNH$=|9S(mk!<$P2Lrju_YTQ1g`npaz=ji;wqk=QXih2A+6@X zZr_e_)}xQ~z=LewqcrR=z1!2!rx@p6e`9uTCvkD{Z9H3wC~HX~F7{8d4E zS-Ub^LmUIghWoKHi^6cI=-U#`ZSm!xW%ny{P^!d z|G8F^r^RbJbP}>aQ5+o;b%qP>FB5syAFbi)4qCrMq;GF3TW>F-lnQ&{`aw>oLJirw z`Hpa=VFAVOIJoRskr6U;5B@+QhpB9JVX<=0F^%g7YkhA8_pUKi`nhbP`&(r5A9vz- z?=mM0xE?CuT7NEm8`xJ?r?V6Sd*OIG-K!?c#M=wOpa@k;d6TJKDV6j26M3Nx8j z$iwcdsUVhhH{?G4fKxC9V zZFJrdEca|2su0)H!;F7T}rf)B-5ZDV}L->xfXpVUMVT4R96hr@Mx|zFmZOyxOE=>>j-@s>DwB~~*mZjUf z@8PRo8Tc$~EoV(l$LjLPuaLM7BBbvOFQ`Xg|83x!u8YXYV54e=gyxXmsAa-qf$@tk7b+j4R_1X>09n{i=-x? z(p;806nw~?mw51yPo>~m_3ATL{Ma~9ew{wTq@>!vepB8wqm1H(X}BM-lcSIalP*QK zm^4z8`@8TB!PW|`68?t2$)T+}$q)2oMW*EN9*OmM#c4LQVv#F+c=zf&VRi+IGxuoo zs1|TK^P2E~*N0&XCe-{s@o(z$ol`D|@8yOv?1keM8@-J;^s5J}=b9$#RgYEt$ila< z%d|hk7EDZQv6*kG@6HD=(DD?4lA!4M@~pTzeXv4cucQVm`SoK>`2K!cjAgN%#kI)S zqPytLuoqdeg!k;%mX|MVLseo+3mX}BQ!fYXPgB|zZj}>kqxkGegZR+5AiUO2ZMn) zs}R@=w>MbX?zo31)afmU?f#+=*sIFJOx|dO2cPyrE7g_hg~X4DA+n(BA&M=SP)CNI zy;_N$y?o`Hv%eJrdwG{x&mVMQyr$4%9AY!Xs{a16#P6FFTQGrpnod`*T%w2>*GfJa z3g`9FZ(%Rb3yFN`wvN2%crC{4q-@B~&`!E^{y?z>6Kbz@D{)<1TIDVS`;}yvz+UiW zkxv}llb1iO#n|wounbIfmqRZ-q1b{6wUzi(Y)-6C*Oq1c^hzJZy$iPmoo?ZzHT>MD< z_OX?F;6xRUj=ga2(&^ruiW8d$)RMD`xG`+O1itF94|!phI3H&(Q@%G+2<(NgI%p^y zWTM{5F2a8^D6%bB&vOF{@khB8>CLiR`F+c5W3RE5=%mC0d}*KS#&ZdFa0jijThc4# z8dKl+5LUkBQJzIC$ktUA71e32KmJdx`DsQD0gW|!dgg@xL*#k2e7S}1Jo~_qxlW7G zY-nrh^L_#SGG!#w@^}Sas!nQ0SD-liq81}hbPCuH*zR*Cdwk#VeBgFXE4OGmPF zdj;BTZ5mJLT!FMKT9MXzy^=4b?j&QRX%u}ko<#4SMh|}>uB2+J)AtS-`O^$*@n-g9hVK-< zgDHh~a`#f9#_xKKsMGK|KT@;5s5yFqa?dgS)F+MKVikA|ou*A5`}_>A_hyASZ8w%- z3x4{jPlI-n&=(;~;0tdM)AHx#>73(dAAZ_FHY@Kw#I8t$;C|zk7?@UxFz>P?$ESt} zsX9feIacV#rG@Y3VQkh=1`SgU1py_GsLU;>XZum&)@7QaRk1z8=UykFtgr?y>x z+n(~Q{cq}0M^7JJn8Z(Zh$o){j)J1#M80E1B57EC7s1NJaO(H!U>T`TrG@&AP&A7% zf%TGgx*{h#N~_ML*~x!h6r%2hX?)AZXmUB`3c;~K<#=FY8Pvsk?zDXx{I6H3#;l!YSZV4+;Jy zt+m&eR)sv-l%`Hf3{2qC!XEmu6(r=;XJI3ZB=>bRZ{R$Oz&8)W?>*jy^ES#_OVr>^U zRkW8ef#d0P4_{lrxg|fg@l`E_z+Skt+L_T3VnCyb%wdQ<&3cr=d+wS{N?4_me}Amx zrOHku9-gpCUD0>;N(~@u-i5N@gIyE?dtrs;KY4_C=Sj@csfa>guhdPD3m|bi>E1LN zX7m=u*+Sc$F#1>nMG+d83SUE=ZhPHD0@jb&kzeB!0(+@fck;72wAiq5tZQr`ilgIF zJ@~zqvj;OtZv8<}s@c{j>Gxv;Sd$Yz6k9NXb)TWNzjI-ApEqLBqiqyj%UT0=@pk*8 z$lmUb1S@aCEH$nsdmH7!!tVG}Y{7&YBhFvPe46)U`@>2os?(UjrG>Y?<8E@?wtCWf zgOj2auRk)6SA=tlt!;i8R)oazvh%aZ;o3W3Rjt|9lG689d)bTyDFpVyI`y#sYF;p8 zjaVZx%ULNp?i1#RaXZh=B%yo&`F=WrhppUBbRo`gb#;sT$|c)wizPccDFpVys`K!M z{G7=f+bYVCVO~1UNvoi8dVojwUn7~&7R_N~s%R;5+ z(6Vr?@YsjP#HjX@U>>!GR9w0S>QU5dvb<8dAf5WLD#eyg^Z((615-&M8AI?dX&L20 zrFB?24mrt{7?_w4HG}s(nM%e5X{XN$u9_e#cKpS?np9P;l|rB^4d1*97MA4DU(#dX zFk0jA5W@pZ4gqF@6%sMrft5Z=sySg>Hjf(08^ z1iPYQ!Pq-SMUB1p-ca7$u_o52u}6&>HTK@4#_!xG{JuTOAFjpnoc+$UJ9qBPnZ1dP zw9va6=IQ7@nl7@3SVZrS{p{rQ02^vD8^*9|cTB&Up(-zZLE`UXyv2SqKwGXSL>8j%|5vT0Y_jKp(8c)bsQ;UJ68jxkFJYOb_E&9=_2i^3RH)b>v z7y5nU#XiwFN7DtY!@v%<(C&8maoR%Gw^u`3$w8*v@ns=9*)o(6bKg%itt`FI&rWFw z^tzgA%Em>B`?Xm#Auiqf!gGCc7l9u$3;bPF1V(LP`bzzAEpOGLK50SR=7_)&BAOU` zHy$&G%*iPp^sJ^Szhk>47q-jaep$?V4YSx5i0RgBJhp~7<&#xwU95+WsOHhhypvE< z%%>a^^uiMAh{8XvwfP(>DBhL{5okdK>M&EzMCrTI;<)qpJ4(}##!-U5Wbp`ZB5uRX z;?a#DO%WP@7vs^*ut0Bf(8X@zir+S^2eH?_3`mm&FDA3E2QN`utqSkPTx!ONk*2*Z(KVjON6MIcZJc{4XFH~$JJ}z0v(Siu`dC)8r&JdD$3- zXyPfF62uF;CkX31$7r)t-l;U6{m`!+!xe}Ac79ZThrCi?peQt@14l%=q`mT4{i&?S z>Qc;KMErF_8|5RF#_${ExQ#NEb@B%t@Ror zaOF&+ecuE#E$uTu)Uk=c9ieSG=EzK|8nKAq3-K~7H&FhSKU+$B{iK7{Ba^wiz#0D0 zyN8BAFa3LPmv;%-w#yklwtp`%Klp-N7+#4@npl|QcczZW`RhWN{P;O%%{yrb^ul#QW4^-ril;qxW}SbajtQ2Q@?NjKVQ%x@ za;KCwS`0*BJX(|M|N8k%mUT(~38T^cHg zCq=U$LXXk?Y$IYF?k6JCrfa{8@tzdhBG<@JcH7H3yE|6?shL`;m6&*9F8@0?@=_wC4o5bGC zvSO4qvZ)JpU*R?26)!b;x~!bJ13ME`kazz&QH~$mlg(RLK&v0=_O&daT2`}(-37L2 z7DQk?%0jCCyIHbbIgvsPWB3$dypM+#%IJfQ*qcGtDS*H2Ch^bti}KZT3-rR8>xgmp z_n1^^Q6nXaqmsT@HawRv z+O-e?=W+=|pjT3z3sU9wV$bpyqMG-Dc+tupk1Tf6_|%b+NhcJt?act*MO?>`i@! zqkUbof_Fs`@9iVdf(UGNn%j2=nDKsIf*q-@ABpt0$ZK#TDBcSS;Zcr-%C#ofnGQt6WiOt$L8BIULsS!I~ga{j+y%3 zh>TV@jNj%KQ(b)gmH+Ft+Ie>R@BZ(c`~MYnrq4ZSe#%=#oWGt~dmC7KMHwnuIL})* zy?-*xHmsr|vt@DY>1X^F#=uiK+PO<9u56WRif1F2Y4yOdgz;!Uv3V(VfBhpSW^JQ7#8}9R~S1IewJ2b?;~=k zyGfMcJ;+r3Va zPGV4N`FzeemR|F8Z6~j6`Ba`SP1Jh-Gn&Qn%0O5x;^h=3f4yzBZm+A^tlJ!F%&ZEI zKBrc6{1$pye`kyyTJN4JrF^5fs#Uh3W9(*F{*B1U@Sr`*wuO~%zChuAdXBV8lA%~; z{rw}4XHV9Bvtf%+o+V`z&xoif;)dk?Pg`XmEObV@QGUtEGOEg(qLeMW%fw!@yfQ|g z_4o5~Kgb8oCelb8*L(x%F8Qi!ZcYA!$nZj?F1pijv6yl%T}R9qc!XKC%^0KZp4rXB z0#R)Fk&zj#&c17H4L|zXEO@51*tG78X8AWFqeTp3@AwkL)*B*rwa($_j||Jd5gDyu z7_URW-^U>~L53PdsG?-8EdO7rX-MXu%+m$C3*%g#Ky1a&ER#9W_5&l1(|>7Hb?Es> zR_U53UaWRws8NLoRJ$^aUpJN(>sND?l&KBByE>UvFjATKsBJc6o(_vlVJ9-Bu@PT7 z(pRc~`>JB_9)C6A=kgrA5M43vRCfBsZswWApt0Mnb1~9Avx&KGbu=FOp5c2~Xuhee zN?dl^3ix$t?wB%?(1oG3<3gG+$vypeS2yyn+nClUNB{YmqgIrW(g%Cj}?ivEU zkZ0d84vqW7`gIsCuC6V`JH1%S0;>&UD}G!egLM93Dc zH6D6IVEyPU_4Oh7@Sg;+dY`9Ob3|Yp(#mpRRuP`7r3l_vlb7zD%zkxEWXHCiVMRAD zV9kysu(Cb&GUTVHJj)dudH**tLYlob=6Xcv^;q-gbkc&LUDRW%n9QW&>;9Bm`+Ficb9tipXp+ z8aw`jnWNe27SmbR6_**Ji6=F-rpWuPs&#Wxk05Zn3%agVtPOcY

WDDnwvB!+2Ao8!^|f;fKZz*J9xB zA~U~X6t594&XyR%J2k1PA<(N#+%V=Fzl`<$xP;nj%#Oig_UJ?zpV&)d;BR_1k=^-q z4ZGcaB11IounZe6Zp_%kZYPx2bO8{d$DrH3!mUYF6-esuIA7r$h0Of4`%x!S6n6h$ zmW!yQarPr3LXBrlf8Ea3j`F2?G|1IW?0LD({QRtshCnY=7_c-zhloY3I+2o@msWE` zgxpMGPc{*|@@y+dcznwQaiT^MQh0RN5a@-iKv^%NgVlmmH&OC=GLMcsz%~y^VZ(Zu9)qwBDb% zJ=<$-ZpV129zvNlUZvFAnHRWM({h?J5F+##r+n_2r$+w7o9$_)AG-|Mq2ohCna9 zKaN+e$k(@NC?8&n6KFw%uAFsbQvuSmm>~!Ejn`DIQ0E5~u4twXoe;d-w~TGdr8t2W zM4+w^=_t}kAN9BCc`rsopqH+-b>Z)^wko96;C3TUpal`Ak7O8a&&`zXJxZ9zcIycA zLS-<@nb`cd?e^eQ_MzDjO#uuMsPjbi5I@^~Y2s-*AC1!x=!J@7hSBoSdRw02OKl0a z;{;j|fqGSjL0mQLNu^HaxeqZK0=;xiy#);(*vkHW+*WRXoIndAPBgBohuzL(1HjYZ?t+X+1GyIkAr-hXE%ZRbEsstw8BzWsoZ|{ z(@5*g>vM-^EPTj19=5TMKno)938vGfzarV9#W}deHjM~WXTsPNW2~Dwa$-qdHm;Xe zDny{Fong3_9&B4xww9bex4))$hX_=LA{D+-k>-Ug(^;MEJv9V+>8fubOS9N#2Sm#K zSKErY9p58LO{8|?tQnG#NYessz^UU_^)<&!73Kno&t z4W3rZ`tYY!XGr2U)cX8sjYaHy=>v>dFm2d3hG9=z#Ha1rW?o8cBhZ2fjBOY-GH>VS zdb~5&j|tNd=%tsc#vHC5?JKQPi?`uwVJeGVlPqsd+omydTVHn6D)Rf+UEC6Xb+d0( zwLMD(j%?hBzWQ=EOLLkk$G`hVZFM)Qg1GrDh}P9~cR?kyF)CI5lw-RMxr66#n8NjO2=Fvhp-FK{Bk@tFYt3>uHU$Xof`zyP?DuF$nv_SqI zu#ftqsEilY!WNqwI~U@JKrgHx>7{~yw$ z@MyYMbeZW0i?254`2h7Ui#JCLB5IAEOzOa6WzXE!*Ii;qKjE3HhC29*FaLOWJfrox zTorPQVF~e<=xaN>H*o^`sEU3yH3WL;F{ba&BO=~3QNqVdtH-1AvstDIBV>)Qrx=!y zPRTZ=v6BA7m0PBYyw}cUY;g228Qf|qLyq{(k!x7>p^0*I=E+nKpB6vJ$jn33$9r8k zS`dLO_J(0Su_69_Ro1+L9KA3eb6&_Eu1=6yhwh;m*T%2loey?bIo}V|5a@;dWZjkd z%!fxsslq$_wVERWTY+*v>Q_~1DPF4T#dg|!g>w`#{?om?&+p7ubW132<|-U5h)DWv zJG*soynHpz`nq#!y3Jhg)J+|&9j_tKOK+=21v;9ya}H6nhIn(dAmWdWo7j`vNpgFj z^>uf{!;S8-B&e^yme3IBh5h8lq@r80{s zyrZsgZncTyY>6c-`5=X5ZFfL6=+%hcAMH!N;a%Ezi7qWO3q+uo&gI=8@+2poU&jd+ zS`dMyHH^4i3#lHz^GPRK3PhlnUXLrsoW!sZ6U@eiZ2}dCP`gOiqO+JBgi|)h*|Ra^ z|Mf~xi%!>evN99wDcjBQZR(2OZClx}jvHm~J3cmyr^m1~8nZqA+dS`CNkgC)s^wYl z!JF(s&n4#O60rhHh3YCe7HE{r4rl%+XPCYt`e>sB5!nA0+k(l?hHhj@vl28mcJxAC zcf*MHGl(&3s(d%MpT_u(x-zIYLZ>p_!}+}P?PcJF1cB;I*j8hvq_SQ^m&m``S>NYg zgU3jx%$sCP!J(R30V))r1`}mEnUB(f8kLpTw++(}=%vS)T*9Ak3jAz4nnt*<+}t zZ-8nys0>BfpXKcK<;Av1kC{U>1bSh+(OR@YpgM9Pj~Z6(5XTiHt{JWMG_6hL_cis5 zKgug>S1oVmJOV9QuXGD*5m`xoviUK(6yMr%%(UGmNeEJ^0y= zrtR?if;Q`KTD?BYsVa7OVNTiZtudt&zvTbe(f^E^Z?k=zl8)FvqlkJqYp*$GR)9bY zBJ>z)S!Lx_A<=YR<}J{I2rMn-Uv0l)p2(d?-QN_Tl?vl|%&uvx+;U%fsmA^Ji?n!z z4xaQD$hwc5{kgqegL^$am5ykCu8H}wNJZt979h}q2t7vJkj>`2Qts;IX>WlRMCd&9 zE9%x{i(A!DSAPxAN~Oi~xt&((%hB{w)kr?bx6CZ6(&qRG)MG&PfUZ}D+H3S(m5yj$ z?nfS4q_hg-fdVavxUR(zl%<|j*INbO@D^x61hye%p8fKM-!Jyb{CY7^D;383P-?5) zwxUgXsg}LYChm-QYg%U%SP%3R8{5 zQaRcR5!ec}f8}3YOgPb!zbWmbl`8#r9d**xBeq=f5I%p+T~3bY_1z18jC=MpO~ zeE8G1eBJPXjFITDp#Fo7m^QPJ=s*59J|X&l{qY|J#wIn|&!_mpv?9Xj=PmGe(?_BM zjanCU_x0FZe(cB6;!x-6~8$L01G ziAn!^qW*)>OEs0dKk%g_}&X|?X8AdAozx(+sn_Ysx?gv zKJSX-iTdBW4-t9{r@@s~xEjTGKl|T1$`KtAdOb+_#LRMdfLeXoNt4_R zwJXpIwJssHzZnh4*$uH%>JkmfSLrB2556J!P!aCy=NP8&m$W*vUJlby!T+S z{z$YrFD#D@nah*aTQ>Fhc6(yu)xpR%PUp2PhlzO?bD2hS|6pWCM+E*7Xi*rjU8X~_7FUdZMCU0J&a8htaEo8 zaycU(GIC1Op3JKw=82^}1>MHBBd;&A_aa-cVf?&rs!9AiqQsLw?Z_RBUdTvnsrD37 z&8|cUqv2(S9KXn{+f7W9<1e0JBc|-2Y^sCp-BsC$M`q#Lg+!ag1+vIwQ(CvoTDdKf zUgPbuQoC9<ixw1TQ z)$a1u;?WNMURPCr?;E!7e29qkTj*e_tC_XF4H;tf7+sF|5^q~3(V^~XzLz+iepzIf zH+MwYkQEjgaIHHHe(H!=##46Y6^KADjBOY@a}`u~UC#1$Q_5?lLIjr3FjhCptcng@ zLnm=Ijjs<|RIf+bxQdF_CFZ#Mo&qh{H+res?+~iu_=nQ(X>P4lh`{=h_CUG%szLQ- z=8-Npw6;RT+%+k3V?|R|j*6j~{A%H5>hD$ah)3u+N6Xu$$uj%JH2G-Eew!X+RL_pe zdGRjkUNlvUfrvbdr^}$ssdCz##}s4p_SS0O`Q^ORfeji0y|6dw+~9c~MY?@rxoD^H zAtM6$erY83YpT4>Y-(2ZT*L@8L^@|*Do>9gWpQ93MIKOMJQ>=NxX8|!PHCAn1bXRw zmNWinty+y(ZtkzQl%IVwNj?bNCynHS3`>QrKsTf(MyPH5{^nCc-8HsQEIXp z66!IQ)a6!Af7Y|O}XT>SD}*&;G1vEU zAT%!LE*qr1eOuXa*)^u~IuoCz8U0U;qWfwbTM?NNvDNAP+n22@4!*{ zZRkSz&2vLA@^T^@rj_^Vs;YhQRd-+P;OK>Doyl|B)ygWYXf@*g7|YRu2vi@V)eBn3nEajjB+4nmQt1)RN>keH3WL$JCSZ}Juate z#rn_}MG{8~B6KCQH@%OOvRoS#5tP8O6_LXdTY=VacGJws+AC+T&RTyU0{JuPuH}f_ zYIcVvqzza`L!j4-U(U!%3uZgC_Gm77n`Um_(n|%;tHtq2MW*9ENx#WC{f5f%`>m(8 z&ydsRoPZd|sU=!8#H$nX`qWW!&`Jw&ZTulK#;3a~{Wgvxq7QgwzNBP@8+~MlSw9e> z)~qEmO-J5U*U{{a~JJm#^p6XE*Y*!p@O3Y5jZPRTY0@@4ekw7*MjnJoZ%3G zw<8QgJiKNr-h2dUHCEB?O&|hiS6ah;&27ev?4v9_Ui>ZevS!qbI~1h7oHNe!N{Lgm zSCx0<>1S9Fq0iLA{u*XdCabbov+=jkE4Jw)SzAQP-L2n6>5V7}bgl5Pq8<+weN z5d*#O)&-q3G?;E)XxNQ(Ew4ImC}iC8K*W`}`|`$>P&vEq?-V1r(KvJ3%x-GV+KUuqem(QP@IX5>}X%+H2?tf&&KrgFQ|9}4@t9Oj7HEWa_yWkZ=FN{%m!#R0tY8`n$ zk5#I~GZW;HzN6IDRWCIJde!^wSDChi$+dOA65`2$o052`h()lA#_Ni#jyhtbYX{lJ zB~f|)RE?tr5m;KvReQ9Z_%h;2V?D3NDLbOrc3E~(xSX2#D;qz0tqgtFRJuL4-cc{t z{cJ9*+)KrbDaz4;%&N%CYGqSpQLD?hQ6Gl5b9}2ILoEK1b))K~`RG72tzgS)F%W_A z=+>5WQC``asBF(FYB7*`7SWD8G8J65p&GNhfX0W52rR8(RPA0=?TBokR?}!l23_>R zH!3lInMIZIYM`?DxoGcNMCfm4kC~Uu_0Chm24@V0kI&9o2M?^N4lT)o53V9p6F>@C0sJ>2m%W#!} zY8BXSj?-{+xG(J#wJg99fnFGovOhO{GTV1+ukNlX&e4JheI$;{al!o1th>55u9SvA zFTEa@68D+$5BjLkz`PtSh`^_dRseNAn%#eEtNPgeIKIj7ZHezI(lMEvNuBG_N?q*` z&e4L1s6P+Ma<#|F5i_j!AnneZfm?||sn<{qfnNH!vd+}b{?$CIa&~bZAkZ6 zK2I}?E*PjtOGrbYmtQx#Y}LDwtarg0SMkf|n9a)#R4%^xI9d>)_s4*)L(CI3hAOX= zFANdrb*$6@`7S(6&T_M6>JwEbn{(X;tH7RFIa&~*&x!F%=wxZbAXVj8t|Nfg8<};# z>mu*l&_=~YHs#pQxW2;PG>i_h`^-6R-PG=YVH_=pz!f>|S(Y`;c~fK5rlN5g0=@K6 zvMQ6^TxfPvht_xFXh8&i0nmNtp^wc|PuiiJ81~?!ZiwIc^A4TkJU|7uHnucEr`hT;y3xUS%eJ!W<9m5 zcJCvd*O7{{?-?S{3s*Ii*LSC|X(=4Bp_R4Kjw2k`EA+vlJWBOwUhcK_)FMJJ)yuaHNiifr<@w!3n;FmxXC=DHx}kze`77$vs>0grg9vN| z$}lb0%RJ>XSlvwV*AVE1vn#RIjc#l{`+11!KEYp`MG=90L+W)E=9+Ge`qJvPsfIu= zd^YJlcy7Fzw6DLqmAQfT3?c%@n57G_#2gbFr=s_@*AVE1-&cl_GGnY+m=x3Ngtpec zybyuU3T4XvHrI4n*-wQ{<{ARM@H>%CelAv0r+oa>-J`LZ_CWZp@v`BfSlPN>L9TOo zhjw0LCNFtxT55mD7mV!Ir9UpP&c5ZWV-`zuw&T^*a*>-(m;T_L!jk2_oQ-8lry~4N z-~zeifRD`A(2eVev&~(-7!|b)xUV9$seQ3$JChUI_wOdXW_v8JkI|=}I-TThXqJ7z;HvU1ZSJIew>I z?`0d3G7^%Ka4i(J(@KlSF{%F^@qinq+^BIfN|CFgw0#Yzq?$}2sYFT?KmvV1k% z_{>ual&*q*CWhX4-A1`7!T`5@7fw&iF3fsY?EZ?Xh8(liE{4Fmsc$J2Q%t*9)V*C zN4s9CI+tqG`zemMsNgIj!Z*o?4+m^E@8VkD=>4(fYmi#!vy6XykY7Wf7mfv5>DO*T zrP{}dD}|#45z!x4$dg5LvkKQN-t!CgFtzFJZ9ZhqRSkh&IL7F$cCC#0ru2_IPoMr8 z#};xfAu?CRx084Vscni&`Y1Mx(s(x zhhG0=&UqOm(1HkjZfG~^$4m59vzhbjwbc;lg>$9F-|noM6t8GbI$c|vMG=8d8s*lS zm&_HlCtG~?8UnraS@gnuH%03oIqI?yXhDQNU%6GfW8O^lVe_xF(Gci`4C;=2Q58lv zAvS;D+T4x^eU!Z2`_$~wqdf2awzY;pFMV#GGv1YU?V@;6`Pu?4h`<@cFkIH$r0lsL zxLc+u4S`M@_cOEu7 z$q)Qd*)WZp3i$!`QV}~daqr|6d!F6V-jFz}VLZC2w7%-i+dY~8btr1gtwn+8$Vk&Q*x|F|rGf|eF zxR+&3F2=6rpDoY5NMo;(cG`S`r%CrNsqF83|Ilf;SLL>(qxhJUhP1|@jGW6uj|`Px zd#q$9PW?n*EMF&eQ-#G^?z+!KL!cLOBU}9KtyP!dH~EVbVH_=p@EA5yp8d3eH8Mt1 zj6M-Ds(wU1Ucq}k$MRx5nv6-2gO=IZ=V8659%DYos)H-T%}4zwX$bVv*`|vxYNi5+ zx$d58BaRkC=q$}2?+sA2pJ;Z@{YB%`MxO0g^(IQs=v}Nt=kin!OTVpp@^W*`<@{O< z%cpu|Qf73*ywHe_T1;b>~=i z>>Is5dKsOFfqw??oTG_`K(9RK$I6`9x3g~U)){@3PVtJqpIOwnh8hCBu!QtotD@8m zk5ukiWjaR-BJ_IH-5aSsuU*9ll}h8-YdA`RqElpzch!V1>@l_(OK%HB6N$@RUO&%nj`Nu#?TSX zJ?@!Jx6L()nM)v|p7=?!)HGJOm9Xio*-x8)G+llf!QH3T7swHf+|h_8exH~qRXV1+ z>D2g+R&%UJg(3@N{B+5B^tAZfFIM+ezi`{noEEt@wtEIfaYx5i=jk z#p@@q1s_)hqnCA#dr!u)KQfh~nW4+bY37i$0b*D6>O6fnf~A}*$(FUdDepK69)x2`|2$F(<8 z4y5n0zf5{Vi{Kk$Ia&~byxyeqGcvbY>|0xOnzvL#pck^6)5++X5~|{HAF=GrMh$^p z$g@s+mYb@pf)lHYwwq!!1bXecbwE0~t!A~VtfYF-UWRJ9u!bl^I@M@FM8ttDGMDR4 z)-hr!AxexXO(!ztNGs(iM=xZ=*AZv`_E61wRTTkZ8b=EvFx!-r{tmb)@4N0|M#NQ) zUih5ri2j`>nFVXbir`8;G=6IAO=O;?)~)%(+}^CcAcirH+~eqF?WDH|AIOsJR;E*< z2k%X%Y;DEqz|I-_?d-+$y&7}5j@VY_vYE8Is~C6RUqhfC3&y7Wk|FPj8@GeFdMX#M z8MQzrQ9RQJ*xGAYznrEu!A; zZ7kkg`kawX#g6^_Mbq6uK^A^cCMRp+23rkD$?!w$^u3Jk%OoduK z5P^C;bnbjApE`7=DUJ5Z8cQ?sFQ=bJI%3nlPdhi2*0`aV|IJw|6(at{xjfsE6(;(w z%A~awDh^@0(fRq%qLhczKz!Zi#L2^M@|77{^Scoc4OqNwlai@o0N+qmYn>;kWU+Vwyo2F%nifX%fi-4Tm|pR()Q;l zQ7+2`4Uv8dz;c9rWjZTx=^vOJ)pNACck*Y=f{64}4mK>z%H;UGcAPo4NjjSwp&r8hy(;&b%_-cZks6=RY)AWZrDhMchAE zMnj;Nbrx2zen-~a%gW_k(Q^*nx$8>o-!6_buM7(!uzuFPHN(;p5~MJ%)f^GnZq&LD zcbi*g_7>LJ-N0%4<=sDfv6UC*Fzf8*hiR=??BVbE6Z30!V9VE9Cs><0&ou{3>Mvxq zDvs=g3=1OCPnTG=^VTVHpJpq}t84p;u^M%7czmEy$N4<{jMnjH&}ZuIlkYm1xm})ma~JQLkscvY^X&AW)eIfnL@MrBp> zRWG_1Eu$gO3+FCU;hSqHmy=P%ZQ!ZRyNJ-|tFm!d%?I5&iDsW-9p~qpYL8>_(@Qen z=9JM|rWfn<(+>-KG?&>0JqZG+6PyexEe5w z*oZ7@zel8?FE4G?hX^Y_AfvRT=QZVy`8A}2I7bYX_*>|O>j&cfSa{!DP_BcBIysP| z1rd79-}Sp^zI@d|EX)?KA<#=-WxVYC2k8}c5{*`MaAXx{tXL3XWsYP#&9vSf`-t-T zItWtF))450qmu5#eLQV`F5F#At8dd*GKkQhbN3Iwn@3A_6?7|5L!cLqN-Gb*Zk8?* zD^86p#?gWZd^U;Ey3A?Q|8)-$_FEwhfnGQ&4WquX(Y&@fRxE!ProC$sp+Dz0za22^ z)afQZ=1tTP=!I`;iwR+|*|d9KvF{Dz_?>}YNYxld0WDiQ-HDVE7JqK7F2ag~M6GxZ@dF z3+eCk7poV@Eq{*`p93;yWI#A9h|u3ruK#?JXU>igIesnb$g;?IJ0rq6OMh{!4O>^* z%FE~`-X09g-)O^`T?R`Mb6QJ2%P6FeS;C^yMY76 zyNLQ40==+rXoscXT2n2H6*QA_v>-x%J~nT;YHt3}Q50X)U)yIu1kT!Y^JQo@RdhiM zG5Gfo4S`F-E*kVFWYL|hKN9Bb{Zuu7V$l6+Y-0IN?xmuoxQ3*o1G8YYzy!`z+C)iJI*HZ zHB4o}ho`WtMh<$;3wL`J{3ufoT2qhXXh8&WpwoVdQ&F~}HgQ?b>8&BqtJ&He%ukMI zLmv83j7l3Kc_-OZT(pQ70%8r#@!;tG7Inb@UmYv0uKZkOeGl}1e9nUUa*~Nyt`&i6!|6`cW{dNiq z4oqd0jqFsa4!h$;tLcT(EZ%dpAmX<3R5oMZ9@eLU)q@uXMvKAUrtt=mu{^AJ5>s8b zuo1Uov=|thV$A9)CiomMSH!GpAAFeTvCB05y zA08amc<(LVk5xR!n{HwN%dL$>>_O~V;x?@KkY~EnjQE3uhCnYIWAuESFimG)ny*@h zb7bJgvg6Zb7=FKW5>2P}=Dq)z&2j#~{>N6QoA-e|Mf|-8=6Y?WhCnZzB`7Upb7yfO z%Vu+X_EsD%h|qh`(oYyX;|AZy3h`W@hqCiSRxsP-B@8*~bvE`>PHjcWcK7(z0zMi7 zy)LDUVEGrUV;3(>qOtp?PQ197eFWc9Iwwa9B6QyK&q19<6}LTnMwZ$d0=@7lpbQ9? zeqwIOO|~Y7oA!Jl0(sVH7CjUvZa*r_nij99A0L`Id>1_1ie34aaU4I0 z!0|?`5tn{3o$fXg&zv`FBM}jwdZe+z&r{gsF;Vo6dOO=gEsm-tiaRaW5a@+m?v@ta zW3$@MubdcM1X`M&O=E|G7qV}E)wLm)yJ6g{cb61(%8MCyvI_J2F1%BvV6n)nkU$F}^cX`b@8U(XmKV;W3TgE~#QTbNwlLokmhbl})E}Lf_TmYH zbBQNSf;0qr>5T9BTRq{k{j!NsB`XT_3U%4U>Tle}GJULI(-C?4oa2#m-tgX8nATQ^ zK-PTf^Pe~IPl{n8KrdvogE)l#fFUC4*o>$f95(* ze#|uldg(E;WViDHJ9{$c5j_NQIU}M-!9{G~*EBXPcP*;Nw;AqYMbANI=YyUCSC+`@ ztRo7&zQeQJ>u5%~G}2%cs&<(9mR= zKPi>^!_%Id6nnV3nY^D@X-pF0i{@FXj+z&u>2zuCd)t!s?G@e3)nef9TC03|tIF>y z{e-(G&6lggm0Y}8L!cM(DiR;^wVWzAK12o9ZmTgaA_7^u>D%DlAaQnk72=`K!++d1 zo+T~YA^(c@*Lb#d?&x;|Ek(o)X7b~$Jmh0CqxX>v3fXRZF+GL7onn_09`~@lN}Ix1 zSgIV^*;-lpuIwh{;y9T#aUn+wBBtb;$_8xQBa<6jh&f|>i{H<$p=|U74S`-*T3TQ2 z?Im6Y4>IGbm*dELJ#OW2b~AdN%r$um)9Z1+OLMWV#(6X9OlOT@91(xIk7WR2^K5wQW&`U3sYuQ$!&p^{$lXa@rx`@CQA&%b})A-@S`*r7NLB!hqdl;?IlUo z7p1e{@Q9A8eb3(fYtJoA7E6*Hj>l;A!1~eKpk1nYWK&ml{7)B-Wk=3sy&n6Mvnprb zCdwMSXhDQN+FOn2FWf^1@NL9gk3EIs3fbQcV~6S>mUp|)?{E5`JrjsP_IJv;yBIE( z+47PC*n5WD%IJk?ntejTMZdx>>Xw;L<2}C}k-(g{%#$TX9{Lv>``E1AMc$jr{IcN{ zLq2t6WB=>)P?o*%a#`GYMfwwU>+V96*T}5#(4!YVH?$TV+e%bid*Adu6sA2m{U>RFpY+Vg=3IwQknT8t{zkhk4*mt#r3u?1}P zS}6mUHnm|q>lR%haVfI8kO_x0-gETA*mTZ0u$0L8<{mForhvebpckSo{t`}myHWg? z{yGA^u!N+8Rp}15_S&t}IONmD+G1>a2J_bw`TyErCK8(`_FBQ1g{*V|QzpC>Ha*6Q z+JPc;ofGA;6cuPegdSr}B~MXYZZQwmEUeWW5oMY!vDTt8+{gNw=rcc;$kVH}uXbg<9 z3m-MnN$n4F7uY`KkJ?!_|Hbm~wQ4r}C0dakeZ_AtK5vGsV_I8bJ@A+4JgU>5ywc0h z#P$}bA<#>Y(P#EE+rqoE%)5o+1#)X6OSg`&RI^Ae-E^H5r6JI3PHQ_OW?)JA>C{&H zuPiombgHQC=JOD^ZbxSBe<3{PnEq!z6JK~8Ee3ia+PZn4M|EjgMn%>9i=zeO>8tQ@ zw~8`4i&9D9`2~IhAOhpjP1ejCI6LS?EKN=t0==*|DLWx*2LE`^MSU3Pqm2^uLNwiw z-qhAyb}q`6<5X}4`?rHx)!Idyx95!GZ=Jn$``qrNwRJ=OQYpydL#For&RmX&zNK&f3L9Tw-@ZX)$#wNqu6$$P2O#3mMmx!Xh8(>dRsRw%F2Vk4B}tIf;0qr?TGs; z$hGda^cY*dPPILmH_(AV3nHTb47bf2vn3soe?(2X3FvNqs1hWc)(mBVUc;qT_8hyW zu-^YfIsQgwUCJC7+>Uqua8FtYv>@W}7utbN@^_$VpJBZ}DTdr<{%3+U1bXRgx)FsN z^SZNhnhPofX?>1}yqT7>JazJ?$H+su)NlS?EB}o^FYJFS@3k0Tm|5`gK0#tZuVyUz z({yIl{8hE8EdSmGj=zzmop#SRo@Kq~ws#=Vf{3U#*;vyuD;;RcNxh$4c3IKdtn@Ni zV|+(1>>JvFG_vq+&)YeA5G{yU@FCT9*KI?3jGkBLv2&rZ|3RRa-sd?(8t|KaOZ=zi zSf_)-2e2)^qtjy$o0YWg-6h=!7HC04`dDy`e9{1|}!LM(_Dfxz=q$qvY2is9IWX$$5^*B`|`5;N3wsl|MQ6U< z*#92{dg(PE{!1mZ&SY-p@dy&GPDSNEsY@ixaCYl&m-SrMFFnWc|CB9KWEML%FMnu8P0(~)^x+5ogx`!>&mZf4idrZ>qwt6vmNb@x&TR|OUpMU7pM1!%P$95j^oS> z9%K_}K?KgI#Dvi7iyZ#6rDLW>1bVf&{K8(rzB)a|@vO6?%gJ621X>V*b3T2mJ##h9 zd?omi3;%o09kspP+lSd7r8wFreN;OB-%^S-8Qm3j%)4ko#IEwKndh%l9cWS|Dd)r& z;wtqf%cN2w4oq*apK@O$5kQU#ahxn?-=QB#671bXSC{YV#^x#Xz3 zIm2E{(>FlG!H!*I*+vu7V}#rDo7JY)F|*_f(h%r{PnyN!^;q_Q*2d9;_|)>yKkaRv zuW|e?K97b$Y(uiwu2=^GEr?j~X{P9- zJEiYmeg8AA5aHwTS6b$MThn7iHvMFuvSrYJ5a@+tnle)6_A~1@TrNwl3)K1?`#JLL zN_i$z=JXiMsV*NjVh!uoIY^)d5vW!{XLo)2n*C4xE^p`b*AVCxpS(eq%(63mw3F5g z@px6`wxL0ye5qtPXnB2R&7A2mY}VfahkuaClY2Y<-!NuYDb7od$xo`fHh~sI;B04| zT85g-MKQkYOpt~^uZ5R;$aZhWrN=O?7cz~0q5SLlAb}P{;CyVcaz&c1@t;{QPrV*x z8!nRlca-^0ohZAl&k&QiAeqPCff>(-qqc|;C05H$DeoQsPq+K8F+Lz9ReIWkGz5C3 zx3uHEYZxbw{9vvK?5hn2zlNRs)RAL-8M8qktt+ICRQt54#SgS4Xly$j1{GP6MgI-ud+C85*%=A8# zh26K+v{o7at05xvdi>JAj4B;W-0i-p9B(z@Z700#NMGAs-PK@^TH@j7-WmeEbk6=L zmn!P~^)li_?oAvmh`>9ThVgW$FWuWNrHaJP;K)6WT<-3}C&}9L&q=2Z)?Kp66Dq5I z1cNc@{T_dE6Y~fBlrJl<<>4*9H7{6H+5nEJdPGbAfq{DY{?SJ*jr0& zD>GC>pqE~cEp>cJ1It5|zc)@}e8-m75wBvZDhEgP^?^KcTYDKhVS_B*V5P>6j`bsE zqu!;|DdzySDtx?#KrgJHb%Iq+ohuWpVxCmhxV+yMZ6;sOTP}|k`<3ZTo_v8FDel@RDGZmk|u!cY{Jx0@z zf{L}Qrb(1HkkmGS3FCsq2ai@LNVtH9L@@_6Ad zQLbg{RNXQUI9d>)vx_Z`DyiC@E2XkNIISVj3rk2h4%-B)$dnaku8Y~U6##NY;fj;? zMZ4Emr-q+4Pb@mY(Sit_L#WicipulOCDUnPVQnRYUf3d(<-NmKU0I%4-C1^vqXiMz z3N+gPj8YRj6R+mWUu%Ioc z_U1$eD;?2)QfIa6v9Ec4wwLQ{+Y9-Y@I6oO^Ksqi{qd_j zbY>ez3nDNceWl)RtlVSzGFCOKz_%qbG+}H~kEq^Vr461F?7DjuM++h_9%YMctD`>L z@#V>_3kZDcBV!iECJs|l^VoUMm7nW^hid)1~p?w5G-gWDQk8**&n>Wsdl zvINqsu!c8S;w;dD2wdUNs&6M#^Da)|jq*EdYac{l{pgHkaSPQbe=={|?K(#bBCt+| zK^ac!cAg7-_NpQR*>kXjxYni&x@X?1G|wUmp1Y^j9KDbu$I>OMq)MGGD7KV7uC33J z1xQDPoG7Nw&;G(c+$pH7!qE%kS-T&(RfD_*M1>`Jv{g8A6X6#CWwA~zt3Ko^DJ*U^ zv>*aYXc+d!f19V;lor<9jw^b+>5E?ghC$_5&PS_?)UfRwEr`H)q*z$LfGWGUiP-Zp zKks@YLZ&^P&#dMXpVf_rlW0yO<18a+EvkPeVow0-!e;Xw?ZSA#Cr5qaqX2wD)a zWnF9O8@rTQD-OfRdaMS;@Dcm#mC_LCb^o_v@>Ih)?0u(S2+_tRSS2hjBTBEU$kBp` z_bS?ex3cg|Bo zecM?@%!(Y$(Siu%MIsK<0!3AopxR>L;Jz9Hy|9GzHBro8^{!t*Brj>m(SiuQ9^v!- zRGXv{V#(8m+Dac+_sFV4`|U-&)ssP<;#}z&8Unp^ww`KN0@cB!;$qA{leM-&ejjWF z%9=c0T%F-Ikv3q076X45Tb=eY(tL<}*Ik50&(~rg0^?C`R4*^l_H}X5IA8@{AOzi^ukPe>+Y+&`0}QLpnXM-UKj)O2#K?Xhl0<^ymX=uScKC`@Kf4Qy>kci5(6jCb6lcQssE3GK;>q((9Kon3nfGs}wA%wmN5rr$ zw-=_*C4oDF#Hk}?#Fgc>Ia=_(0p3HP)9|S3qUq+EqGJ9$JhW0fw(Q3_j(NBCp0Vs+ zqseSwP0~l7Ihw6*F`ac?ahYa@)=_1t_qb@^vyz5DFN|&7y!R7TL#jJ+U(tdHtl#(6 z?GQ_P#a(j|@A(WiAZu?&sY>@wX1}`9ZKthgSlLfgS)=Sp?5vA*o4nsxKheS6n?_1r zj+T|3C$cqF$1xB0TMU1Rp4tLFVpX`G=sYw(KlbxT)+z4pM0=@9w44qBPuOm8qE-Z+*Uqhf5mew$C-L4`mt?j#`YHRgC1lEao z4T_f(6(aq`w|bMcJ8^ioOV^xSFsGV`e_Tn-`E>@z+hAA^Yz4~LYU3{w3zZUk-i+e- zTNpz}uO|V*%u`CxsR_p$0~il=G$|LSNM&)#r<^EAOoE8O z8!CvV_j%rmBBF3r;kka-!GuBOEP=!2Es6J+D(;(6_T#-)@+OKrg-K6%LmdV|tbnN46g1Xh8(tjxY?@ z-DL$S*NKqldo%=kVH?t%__4T1Xj)ypirLIj#T7G0Fsp;|8B)B(y5SW_3u~Z;K(9%K zx3XEAcF4B@E2yoUmwAXc(>zI|>M%zOA~2JO*3`7N$~CoyT6E|~jwQhoV%|IDY!|L4 zt~?{&%=`7UjCe%oYP6Z=mLR2Ae>J1x3@xJ(^MbSNNoA+Tcaq)#~9{ST3D){m%PVvv>*brO$}pVwvuAkFh4b}`4lam8uL@}m%eLyughItoeiC; z#XyAKRvpUL5N&A3md;wZ>xIpXmu>FY>%)9%%*-Y|$n`crDJcQ%EcQ zW}YIlZy;ql362&-V4bL~oWp2U>86%+?5!ct3tNQp!XE|-uav4PPakJqYxHE+d&XGV zGxtr_zg#lAqtP$b~i3>F2pPS`hJMV-oW@Jw;Axah>YnKh9r7y!28V z{GB*juzfzdj%A1Aen^jTqDB$HYSgCFhTeRPtj#j-U+w7IoO2_X&)qGKQHdGfbZ(H_ znbr(-)O!CJ9KAN~ZO{I>vfuHf;{67CqSDF}H-nF|-=4_Pg4yHvONQ~KQx!4tU3KNU zV~7?55&tfgm$>?}oZ?Hzaa7F48!Gxuiw2R!L}2Y&s_n#K8UnqrPQ=W8wX(>xzk;gK zU;#%9BCvkeiAgar_Esgeec*A9S*$C<=d<5hACnv3tPj@b-N|R&MToPnQofToS`dLV zIPLGAD??m;6j%{qs)2?8+6#Ds1Snyus^o+-EBy z@-g?9A*tj1?y}qOiqg2+*L{nv{@kIW#KXbd<(rrNl)CIdpqGDV=d|1J@399P@)1G~ zE@&UKW3YJFZ@h*;uLE!D*dyLNXI&5eNV$bKJfiq4)l0cZrH%OI5&Qb# zHX%CQy2u+Pe!qc+mbHl`)9%%H#y&RPXTx7Ij3!+T(c0HdG&;7QqnFWQ(Sd{P1v{Fu z^k0Yx?Jk&+sa!O>63<($$P_%z|2aG0yvcTONZsJ7;~uj!S+3f2P4B2R^-VT3RwN(x z=V(C$wzOgF@-D$f+7d+Db4@e^dY$f)V7s;clB3lrYjR~4Mc+9pqSHz(cL+}!@LYuU zuTsvLg+EqPUQM%VIYsD&c@D(==@e_md)HRhZY|~)U_L{wynoqG?^*9Sd!a9uD>+T) zNA(>D%r8Ln`{>#B_hYuEBWU)KUJDyK5SWF4=nd~5r3J3uk&ftGbvP?n>pKFoX%PKS z#n|9kt~=8a7yd}%Ynp^OVqm5V=E+2Qp0v3?-lSwWZ^)2gRG+tYtx zI^x)@Ormq{5)K6B4k0>3wq7X*a_~mdM-ELSW7vX5)rT*~Z2%POyL9Pn@v2frx3h)v-g5 zIdGVB*Zueo*8Aw`;O~et!CYM1Fr5@CvI@+5)AHdOZeW*--m-m1+^XOwuCzViKw!2Z zqIXqT!P+)+W8V?GTGRfR-+c!HGa3;cG$)01Im*)!Q~!1qUX8O0t5le0iRh|(r?65j zyQU*#i|n-T-dG1V#s5I0rwh&23 zB9=sUiK4bBp<61nDMbiMY(eF@_tFT06pf{dQj$`{QdBg>@63H}U*FIC{_@B9yz@xr z+0=UD35Yd*_bxrQPyA@JMLhH>)SbI`;m^BQ zlXlOM_U_P1OU(b)A{xEr%0HXm&fpu@GJGcRDUzQL?T=Rcaf?25%W)Nk5hQRGMLXM( z?Rnw;-bUtC7l}ZXyjmiUo=;ElGHxDg$}oZiuDfUze!L@p717B2J@7fl|6y>Ic|Ie+cR$Mt!a{$9rIm?AT5I0r z55{l%DGVb>$p0&!=(qXxntr@!sEb6P3ilc5_waAaU-;VipVM8X{X`_>eYj;UoT%2v z$IL7Imcj2O%zSZYSS{|heT4Bv?Mlm8SWIgl~Oxr-k28 zzNM&^Q8>U~dLKlhTGcF-4&_;YU8m{;dEki#^fuuo5vY=%+DF@mahIIhhR3Xi(o>5> z-Fcbns%2i*Trw|U5O12%&=Aic{w!4C97Ar#&nn;6_@(Yk&pAerz|$jiK8kj{f)gI- zHu|nb0#!Kk(FxE$d-8Q>YMRd=ek0>|IL;DO2QYjH&;GC;7rBcOBr2W1R=vXesg4RE zWuHHFPHM_M>2HMus&JMNF2IMpb6j1%u)s^&Z%0DjLq0#s##1JE@bkCYO9ZNLx1L;? zZ@hTanl^mSa&M{A6cY08d7mfs`T2MIa<8THCCB7kSbufU-?`>ay6k2&nAd>ko$SY{ zCxGP2AaUk_k6N6&$=tc8GhHv|e$_hqU1$+mS#Oey`A8#+Dd$@10OH z+i?|!>o$2sHhlGIHML2qne7-sqSSwwE#%ug>#s{Y+G@UkDtFCj$dEu)+m4TVUrpL? z5lM%O)dSCyX_oV17(rrUzj3zEV9m;s#F`0eeAU^!jC$!IfvWJymA!`!HY_6N=t(v7 z<3yf$AcA283Af~M+oeB`nR!e*+h4@0&L1W6oVy7UfvT%{)qFmEQe+XIzFVZ$tsT!F zHcn$0K|+3arv4A=fw$xNgSqJvfhyb;p*y7Ou>5C3;`t*sU)nE00^ikXebsY_mQyFp z9CKVpf+GN_6`&0m}8C+B=E0Jo^VF8_TQKzfvSMG#`d6P`>Zji^H=toYKl4L z7(oKZiL$+KqW0gIBY~=%(&qLN)F;PL$#FSkqkUmPk~!uWK?28#dK*5B)BYQCBv4iT z8&CUR_m5j+PPa7KI}J?W<0_Ugj36P8Al=8RRW^#Jlkw>ifhyeB61Q4Cwi`#{`CV<9 zw10&J?tW1(i*~>2gSHGXUcFk&a3=+KSmtFl(}oAFv%a18pH+;Y0b>pNmth16xh8e; z_WOFbKPDKoyCxB+s?*C&Q{K$h9N&Y9`YT=BCq(zUGK?UBb+**Wb85N%-OBMs)GB|8 zK$UmhHrl2(-)oLBk8*mU$Mzj%6g-V!7(qg=_?>>|PyO=uV~s(*6D0ywF=IPxe)c@g zQH!%vp&RU%k1#SOr!kBmA=f%z_PwPCe>>V(@+e&*P}O_3O?%w?N6q0bh28&0Z?|cr zapm7>3?oR$HQSzR%Jt(lf{ZSS???oy{s|tV)yTW1ZT@KkIdRSJhUiE71exo0+!w>0 zG!gX1vO&Lbvs6oD7bLXerMNqYs~A-PSBgU#~b3?00~r8Y|XG|Zr)=NKG7@m zh!@d@_%^@@62_Ci?U8TgSz|uhJ5CQMpJj+|10+yoyzz~F-H3dPsHl~$H~V&mA-)YT zg2at6Rkayi3~S809f{EwrbbgWd4fcs>Y%pKe(+GCMLb)xOt0T_njt)Tj3CirNNw%H zs8iOMpA4L-*K9V!==V>$M4+lkgPr!|F(nppe{Q<&wQ{=Q@mn~<2ofV+xoQ1|-PK;Z zD8{_(&18MBZ>(`Wv9&~?YTW%(_KYcywe};$NsIU+DeCde+6ML8W+%41W#1kCKoh&< z=Wmbn{&m{}%`bel?bfE^gExxqYyT=6X)j##7CE2N%W$z}GK@6J@yoxs_>ShZ`=Skh z67@*g@;ZCuI>osD#}er?kOl1t7mUi3axeY&C+|%H!NB5p)o|VA}60MJA`P``b z(0tNpzhw6*efpRHBW1!uhN`T;8~VI`xLj)xvC}3KS6}_APx;x^coFg^!w3@i1XG1+ zw_ntbHvs%LHsZNuI_W<4K`{no4gN%4k#a2mr15||6rkmEKyYzBYql1PROq>c!gexq3G?-k2C2D-o#bHT*l< z*3hS#`h%$DoY7zdbD1#G%o234(6u@`d#z{lE=@PH1S3eSsB+2HcJ6*_%Tc5nc)|h|RYY#irE!@l!Bv6$~fcJnr=CUo)*n7OEM4;+?v7dUPYpK@w@op+|oZJ;5tewyL46&suI@aZnVmb2DETyJ{Fg;+Hv_)dkNQS!2FEat66% zn{~0WL;_VSXXdKf$cuKz`$xygk=%9YL0zmYF@i*=>>cXT;O5qtkN2C#-Dhsn#mW*1 zRK?xjr(R6EZg;$Yq`8K3HTi%pR+bo%2;y~5D`C;`{ z^>Vx8{iAJR7|+h!rcnUo_6jcVx-AH3_^5^|BCIf)OOPl^<2_4O(uEx&N&MPV=HBvIGfKl^!fo zjSJcNjx1@}B941iRMq>kG=>o*uC6(!PI!`GjrpFWIJ(DluhyXXcy1@6<9f9Wd`sG2;qLfzKt zO1|eVK}7yG$-LQ7WC_**p!fgdl^yDnuAf-0evjf5?!2y46>|wjkmyotzxv_1pM4x- z-mD;*2Xt@7M3x|ds--pds-xatVRI0%xyj@%-B86`f)OO{{YnKA7ccub#ypI6AH`io zB1@1!mAJKe+PE)m4uW&L;t~#=$rW(cDo!rSpmS6;lp<13g^Wz8Bn77zEg$Ir+RQXiduC`g= zt~#>Bxjcd|tdq+`mS6-4-(L-N-i3dyF)t4c<7JZ$n^}ScszScor#8vzs5-Kw$>&q} z{DAFDWC=!)=u*2_9nrjo>KOB18ierjRD(?`O_vB%o$OSgo}KMw5s%Wsd0AL46WzHm zg2eDu_tdFVUDdO<#9qds>?ypk@(A1fZC8mv)%w)m)$iUNre4hy_X!szFK51E$8eD) zSm}bbF>=+5_^qFM&fp?TFoMLyjN0m{16!;y5AL{{ZdZxsVlF`fRh_>*Y_nJ0Wf27> z+gPT@G%m6PBS_R)R$o0@vC|s!loP9%`@R`m%q2*mYDj63E#mV77UAu_m1UfZ z-J7AmI6K?S5{w{$o(0{E3&j%q+nO66je_ zUAV889@sO%%n~F}bvk03-DA!{D@!JCe?xD`6U;2Z2omUW(9T3ePrbw*Yi0=&sCxN$ zuRZVT5i3h3vpV{xg|S@BB^W_M_CNAJ?XDM%h~Z*gf&{9PLJ!*yPWjo&l9E|<^v{mR z@cdU93?oR$)wrThm`^|~r>@o#fhy{}XJ5PWFEt@YWXbUwnqK_yhB}ky^jlWxKji+s}2>*8t{YZF(nI#xO zBA~RY7JYh;HRhdT&gvPTgqm4`1gh3Gc~=Vw-)a#%2Wh%n^C@PQU<8S+9bePFI-^-* zelqa1?)Kg!GfR*_)yKzrX%}wnv50YD`TB#RP%}#~g2dqOU9@XgPgrAqeQ>dUyxK&% zor~rY_*tk5n%Yludhd`$oN1M>hb@}S)y!~)5hQY}x7C~*-chgK6|0OO_tW~-yfD6# zdiEoMstc|YwF!fMQx7DF*(Wo9pHA~GRqwQA=)T~7JMPvi%DFX1^$yKKjcupGB?49G z2q_9xL(*MBVWw|@5hT!cpkChVj_BLZPcruzkU$kWTjU})+@q)3!p*%5j39yT3DvNy zJ*ww=hMD^%NT3QGI>#N-QL7w#G8jPuT_CE(S#w-3oI1ta_dxO)^I0PdQOSW3B(QRwy4+mbpu44c z8={f}2~?qvOJ~C`-`3tqckI?;g*tj{=sM8*`6f@D{B!g7zz7oPo{_8Hxh1Lf3)1syuhopDMBD^MMg0&~KwYUc(+~-_UNYR(l0Q0#)cb(CJKfPrYz@ zoH563isWD+AvHrXO_wC2IM`eA)sP6x^RO2eKhrwa z&!PFstD=vVd@R|>?%0=MBzNp;pQ4o&+S^0F^N~Lzzh$@lIyDoG{27VTXCQ(5$%^vn z>jU*j&)!Boy4MST7OG@#!sp6&YIZ_0bz<|8+zk8-d7rxGN(b0koO-U|^%0=w-NZ_c|IK>{5C>MDQiL)OAI$(*l{KoxpORNsDbEW213WX`)7 zK>|a#uGXqMcK;hs01^TYFa;wGAlY`Nz|!?VLQ zi9i+Z!z)VX{9EP?N8hKVOZ)9e$Y&JCG`Yw!zX&pd0;nGV?DnGy{RBnn5OSBDes8QX zJSIW%4UoVpWqNIy`dwh@c7HRk zFoFc0$D+=WZF0q(GG<;Ofhu&*sGt6cuDo5NCUjHfc7`V;@m3N%QAwwlgL;Wudkw$$ zKbOv0B7rAP=`$v@pc9R%p&jv)2vlJnQ;$ZsVD7o;bP?TI{3~yUr zt`DSp6!2s^s^qib;%Fo|9NT9Ppx%+n@Z}H@wxwDM~s^oLq0~<`>^R+9w zxVIQ1NT5R_`b>=Fd$JzrmviN+dsJaPJ^ioLU>@dk&Gd>ef&@BE)CH=;cz&zTU#8Q5 z1gfx}UepMO@a^yau8Y+xMvy?qOi@w?fv+gfyT|d$27&s5*!~PXA#?%IL!cfh17~uoN!3fJBPkN7 zLZ6CGL0p*0`#u?}i(LbZAc0;8jiB!gUQ&IwnO8`l3jH>k6K%8ja%F_+-C+a?^mOR< zx*gFxZ(*wG{2+lUbOC8yvL}ugbsA;n6-JOiZ%VwY#d4R1bIrU$0#)c{QtzGe1irfc zXfv-cf&_YOV)Yu&{j=tod4&Y3(3Pb#ytgNCw`K2}d4&-q@H8m-gMakpcIRPcULk=h zbeHKC@By>=lDRK!eO*Qo%jKNxX9lw-nNlI75dTi%~>4H zpMUfT%edH!q3?uF1NszHSyL9x4=)a9=SNMG2vngLMpYJWbVGOIV$)Z{2omVG(A=Ih zlb>5Ng^6krBv6G89rbjYJA-dMwZwFOFoFd7M)VB+8NGmOk zDs+CS_PlZ&?H|W8kyjW&0#BCH?jW6~7Vn!PuaH0$I@qGZv_E&vykWYQc!C_=MLbtV zBbXY@f9ZYK{5>#&1p0=w3cop)k1P4tbS;rU6`m_ol=M{-czC}*&GEnp66hOJkN7R4 z`TP$nnK*-m1gh{{8Ob&7ER>f(B)VmE;*x5``B3g~-!9z>gTVCN(&od-s53<*p zF}%ja3ie`2cZooi+`(*Pz|ZWqdnla<q8*k|H|Q4daeTn~rA|tKV?2c^VKSNMLsd+I60C zkj-=N&c*D51gh|4pjhd5VBJPKd`|4*fUY&3^D|G3u$C_p%-;heNT450U7Be={Lkk^ z0#$gj2jo{MpETw)lU(_RwZjboi$wDO1!4_4;-C5qm81Aak8w(Jq z!gGGK1Gz4UMGcAJVwVsjNXXu{`!p|h)gysFzoSY7s<2ZKox6)VqdlwMiPJZ`)DfuW zj#)mZ)>Npc9O9ZO0e-ZuWMc#V-^_|51 zj)bIw z-b=KTT3Scm1Of2DgZpUIbBZp$!&{vf)Giju9(*K@kg&G&tn_emss6t;|QND`!ithPw)P7(D z33Pku+{EAox}rpzPZScU!ukO5)UMJqave1+7(oJEYcW$V)VGDsGG_)PP=$34iZWvG zYJJ0%Xmh5<2omVN(_Y{HMY_kVICF+W0##VALANNSr0GpwjxlFyj39yCXsB}F#!!9F zoxbKwjRdN&?nF^i8s66jmiOVGpIpnZBRbXuV9#~xei2=vhu$5}`%bAM^;Sm$-F`)( zdq0d+TOjwZ)lec(gPtM?4bf_S3qg(8-uzZ6p_73;rxrVdru2 zzj~s7x^6W8ePpE6lNiF;h#b~9Vp3!O zm?0w~L&gSA80|Q8Y)s?-zyHqEkfgS~W}&_x97uz6DT?ozoB1_vH}tSL6NoF{AUHCWjsNLDUimrVOvg@@+UX-tTq2*Y{JrXFZ`@-0h05QS^}6#?*}2|QdPX`Dmo^0g z<9m&3m96VB&s|_kl6{#4DY@lHp6B?Z-cGEt9(v8X2rUX*T9V$3cOz5kIg$-K9Z+@o zLM5ZNV|N@e=XB-oydS+We3B%krf?^iGD)OVY`hSqg%;-xO@b!$A$0!tk&b$ z`6Ph>QE>D~QuVDH6{qEnB&XI5p@y*L5lMU6t9`!qq#M_9HYiw`R^dqAoxX{oWbgSD zt%}Ms`*&LnYPnN+Il_TN>#Wnj(E$4cjvh%eGR&jdL5^g=t@FajfDEWll1fHdk*6k3 zB%mNnfvs5TlKY>QE*c>8jU-tFS+eB=97*Bny?AZlJdIlR4H}IwG9LEZTKV_!T|4la zckcQa(@aNVP#7(g3cg+9*u8Jnnndn)Bo{5NQdlb3=dgs5)WF%E&2G)d)sQ5iB(p4) z%92z&(;17U+LNx!^tU^bz&$qv2CNf&3na&xH0{w?S#5bql3P)9q+z!5;Ad-r0Z|h=Mrj5nZ~rf29~-TN z_n3&z>NyCdg8F8;AC<$4+Wxmx1sPtn_|;9N=jYZ8KFfSqp_iZ4nabxvwj}u{_Ev7b ze65Vs5$gdN$@Y!4uM_|CMoW_KI0Mo%ay@Qt=g452jI>PG{2H~mvLvt-_`Ex<8Cl!6 zJ2vVi)&nvepJ+7&eOvsu9;O{#Ns~JP=*Iw&0a4253z|2lo>#uPl2p8bDb{bED9`GN z^?+qh?$Snnl76(Z6(p(1zb$*zs;RQ(g#+XLD)YKjN)~N6Eq}aoxpHKPZS`zO6UDP* z816jUfx&j)S+YcKn7!=(qvqXH&1u4f?YP#zY7QAKVp_>Fe&qkR=H7#K+2IJL=(TrX zu)O^*FO|3LPOB`TSgHq6jahX3A|>#)SaZmL^^>H)Z?BP4^NYBwli0ejB=EhFB%M|L z=;Kz-WI~=BgY#>*C%f89{NK0oC}E|Rq}EnC%8JkK#PFvhgX=3~9JjjWrLryCMDf|j z2S+K5u?xAb!^bXI^&twbiITMI%VOo^91qgjw<&`X$QVpIX;d96?nJ8Vhv%_M9bfD% z1qMWkYpu_<8%pP<9wcQ(Z3ZQfq0U6Aj@T&?T*vk9Rhj1~XY%#+F9k9n3a%28RMFLd z)xGFW-snA1pae41IZ@T|C`Pq1q7Kz(we&s6fv`M*0a5CVsxr=$_T`MQ`7M}L4QFC_ zFHK-T6kL6{C3Df9El>6!4Y%1TPy!jMm7(hJ+!Dlf1W#~fMMs=T+3?8}G9XH{OFEc2 zvAP;hQhFf{K?!82Pf~Rx-tgl(qKlnaW=|I~#ob<54Im1xC6eT{v@zRw#gjC>vk*fG zWW?v@RO+amrLKdI9$T^byIn}(`ojVPqQo_-=uZunQRG7Q>bw+IFUWxFl_a&X{h_Ee zKVtPoSe+rG&}nvMse<=-sXaL7j*`;Pg&aR`Lg2F?N?ZruI%yRH9}lv&wmE?k$Z&t< zUa7+*R<)_grZi>5cV{wWQwxCsQP6VY?^Ws$Wp;=Mk$c(^D1i*)YG*6o^I7BFxsHml z)s)AXE<`8LSztgEw7VoJW@9ilO7JAzlAH*XKt@#V^?Y@d^xUu7a8@O*D9g{4Sod=k z7!W1eSDiXl!$XZdNmQBxffC4=IzvZRbu_K-!FAZ3jlg%yoQeLf)&c{fM61uZZzjGt z%bjdC zO)a~7btHT(Nz%L>y5v|p7vi5-AxI!YwDfNV*CrYMd|b7;@qfOy{_0SzKK1w9``)}B z_46B%v2|QX;_=-A1EQe)$a`>7Gjh|wlN@cBB78MKhH7Q1I@ZbR%+R@O8{#w6g`|Yq z2n>jV-zAbXI@pQywDKg|j*b04Uo3y0t1{HzoffDwobfbQGWUWrx%e@G!e>Dgw0-$3 z+P^iqIMjo@o!Cr)639?%uIkWRq0ZELgY3w#ZO&w;*L;BiQKC)le$k5f#e0zXU$!ey z0vTVo@2J%Acw;!%@vV;uG4yvK2ZHYk42Tjfef`f>$(aBT5}f%#ffC3_k6uuz<4Q+$ z9h7`aaJ9BBReKp)@U z=uFx?c4kll8SvXslJrr3-1@TzDK)bb7!Xx-z_GF(8@H-HfU_BEaFy<^q~Lc`1|^Uo z)+1}wactP!ldM=!S71OCYz0Y5savQd9`8=(dq2i;FU;xOn1#qB=eK6%c-o_^S7m!jf?EEo=r3=xaqC!&V@=Bumr3|5v%!jCII3euKu} z--w>FU5AWXbmok+6ESU*If_`HE5L?V4r$w0--0qmz2Fi_@{7$vlgN7w^{9U6ZvP!< z?V=t0@4XFY(49Lb6YWx0EJ`HlnR71M9MM4I+{a4xbK8a9MfT^6VcYgAfeqb>={{3- zXJ}J8_0wLhdHHX2Y*0=5^~pkQ;jQoJb-W>cvge#uzfT2{Bpb(jaz>F4xfju#RK2xB zo_?mZefyVZkj`Z!uNsHFlCBn@ZExnwcWT}DD!wjr23|i~X}xC<`SGq0@2z4&k3Zk1 zEjPc1=yrYD%2T7gyYDKx?C(S^dRLe0H+jGr-m@Z<=R<c{ho=Rg^Y?DKEYhX*)33PbdeRBDB9f2)L&*zM0AHtVn&68>P!v4ARQ~z@L@Y+Ij za@|6D>|l=kEh`6^JYPsR=os=3|5LnFZ)>z+Ue$hJ!~ObX-jPXkTX;=0yPgJ}+B=(m zX}?{wSg${FpD><&9?(MbxZ5Jm@J%;k`-2TgEABCZk`_<g}%0Jf&I&uQOEWcw4{4B^7mgt9riiX{49o&RxYM{`dQHF9+WeR zeokfCYdWEshb0VA&IzehW8Q^Isn`C+u$$6@m8TVBxAV0WvzT0}j^FxCeX)|fga4l6 zR>Q#yUkKkx=j^C27fr*wbt}?)vYJQgVg2owlvmex&_-oRng^})H8n5npz~&BR=y{# zhvm|Yhrhk})7&K~+^;L^zC97^Bo-FtqM&X*UtJ1gp0~2`vm65jJ{Rf>MH^||&id%xv>n{ensVNQMHd^9dbxT^ z%E3AGNVUPd1^HKa?h@MhMkmyvM~0WaR|@Sobujv%vy?Nwy>?(h_pHbYA47owQEQ%$ zqaUhFMni|poOV`VK-BZq9qEoEX(;cvnTI4DiRw=qdk2xAd-s*CbLyO{?Uhj{Bv`KB;A~=f9;|^~ac=JJy_J{YFe$_*1(!*#FSc-ldh&wZZ2O zJ=^pFsc&r~hfDblKD_6D@44U={e7c8S@N=jz(7fD z#u)=!tmFRO+9c1zlbxvdT;@95-?jXPYPZ&-nbYUzk23v*j1wDIj!=*JRrp9uaXYId z<<};us~p*nu-5bmDas%JsVeq9(vdDKetpPzMRhDPN)86GE8mOpkE|6k9PQ?JbE$7y zp7vt1p4hp;o=P1~(Y?5i6?>+$ApdogY-&qw^mfrJ)3?aKJ9Wk@X6&X)@&Y;ISa%HB zyg%NIV2Lk0ac_sI0t2F;Zb`boU>ehpET}ZYN@VtP z`zUp19}^gS#iWV8U8v;(FM%ydTUsPAg9U?>$jgSxr&TNIu(aXy<>QtZGRjY^qk1(o z)X~zJ*Q2QFB*wk9O1Ph;(tPL&S~D?>K40Awn=D;ILl%vv%NLko_$2P%y*rgPJ9LRw ztSX`-f2C5L<^8!8V2Gn^Qt6QGW9Zr~1_E1>o|?>H<-bDYiu<9|_s>Eay0<$$vFQuC z+F=pRzBhti%aJgAk|e$Io6fRZuArrZ*9$rz1L~8crLU*6nSKO~E!9OI`YxiEq)=+K zri9xd|LAKsXb~O7-00@gyL_})q|aan+BT5ukuEYsK{nJUN&T-+WxsZ9KpD2Lg*hC~ z?V^s(_ouU>Kld~SkrNP!9TzzhNET!uY zmdYPqZ0GerlM-3oIqy-2ZQU`HK!&(R?H!lM3YrZ>Cx?x~%BXDGy!PFE(?vCq>9}m_ zztLMJv8D*>mZX~oQ7p8t4vMSaNSWuio5shV@p>@JMnkOk&|A;bJ=Im_TiI^9eo#Ga zE9=&L?rLon%r=eCAsaNKankZs8oSp6ovfLvv3Rza)*eMrufr~y^Cwo(hZCEiXZO80 zBWh#_+qJhkX?NEJLkVQSl|hoWO$=kZhD#*As-?hysQGyrG^Cd;a?RKC!Lx2*cl{O&-eExLn$-AKeK=^NEAW%!ywJ)POE5Pxgp9= z$^BP7CT$qZj`e?xj}OrZ3|J?qn~y}DAeQ3!8E-J(gb#bC(i)!|q1VmtYhb%UeSEEr z=)*Mh6J9uaE`}1wfcp5HXzarL4Vn|9P`*jjGP%hOrB7eaNmr;fGAi( zNlIwt!*-TG#y8nV?CZ6d`ib(@Hk`TLd^&?xMLLF!)zPlkjv1{j!#dA?V<>@E zAG8L!j;Ev8nSjICExW1EAJ7(oHVU5;n-6C%zy3foZW#%q9ojphef8&O5W8Jx95TFj zRbW6Ad{_9_#A?Kr7cxBTa-jl89JHLoQ6f(WW}5s{_-_5$!q|ljSSS7tE*QqnIo-k? z+!|u|EQo?*T9Pi~(QI~&O}LFisL)oheQIsrOz&J@tl4}(^{8$M7{{X7ENrmf6GI7P zz;@%i;mgM{U%R0=zUM%J0a5pRZsqHih30kPHLhc0$3$lG)&{@)(Go)mWWZU8uQ+EC z*~p{S@zt%ZG%a$pU;m#S!Tjoxs^+mPXGdFc*( zro|!*C6EDIo$pi!PGrU|wejBKkwVR3o#31=NgD=EV!e;&pzFmwgw+5t#Ck+`4`%WH zPjL6E`-J%l&O|Q1meKvgpJ@z-8uGU`!?qu*|L8nE_F)%>63Bq{oDJZ-GN|($I^^L{uhDPj@=_f<>&|*ldyj*w>JrF+ zDEOTyNl7gmv#SRTh_7r!QaeS_KGPhLZ4XBTXB_bh@@`pEW?x^I>?}7XPy!jE4(ly7 zSi=i-$+K)L;_|B({Wjc6Gk)_r1iw;Owuq!!zb0Of=4SDFbn~!aElUl_rd#z0lt6~4 zAXcJ8PlFd%C1@_6bTXRpn4+`@I_%y41f`cxs4Hvh&@0vWfJnbgG6TRw0_ z{hFDY)1Eci`w4$t_YFe{WWbhI<7E8Uyz=`vaQ_p50Z|`k&7(`1s~p#EJ=f8_tOr|K za1x(8`2<4=Waw*_(s#GldAUYKaYkaVZfsKDv-rY{5)37f0Y?n?8rbw^jdmQuzano7 z42XKTb0vNMK1p+?b}O!-eZ~G_AxlQWHyGr7wD6L`Xp&zU^JV0WjtP!uvV}| zAp`2;rP`*)3_7$VX$3lh{|fr7LS77~hIS!x^{(f6sooy5V70VO$$=@KFqA;X(b&Os z?DUh`$xn`Q#<}N>Sf_;=!lSD2lV%aLjl4__>Gcxz+!ai(1rL*-e|m({=k%i&Uk;ER zf8XMa!OuG|?wu#^LetUy%;`YH4 zLk2{NI@X=(!5Vp)610A{eEs-j+L2tBr(OCb=zvd>q#M=Sv$BOYq~~W1&Tx*UX0E$s zo5ZI=2}K=GXSQKYN46r9&de7W5cM;76m|N(K%VTO)_fjr$~x3-OQwy;#ZUqnu3bav zNUs*M*Y85k;L!-|%@Z>c9k_|=eTc5~);0g|Q>X{5pZXoujeTBKOZC#@!7rvzvmb@> z#8bs+mh}vJxW*HCqU(DEbxYEWAMKgjKubc5mkSJtf@49Fs+|a8ukve=VS^W-;oXvG zT)$Fz@44?nTfsJzq`E_fvL7B#aN)@l6f$~znoaNc|B??6)WKpsD!PWTx>u?ZhrB`= zG9XIqLA&X1m2|77q@YU@?^j>fV=0@gNVL5fffC4obG{@6yspQZA8kOq z!}SCPM2YW*!3`T$vaB9S?EM`>31o~M8%zH*t|MPeKg9dI-gReo=u#ar&H9eOfT-dF z@pNoyihO;<8P15UPuS1xCVby{oAA~`ROHVobk zl#<@M++Wh+LKHi<<{YkhBm}KLG>5)9YeJpVJ|V~uOXay}5Njqq#|<{s#E=0|uuhT` zvbH;Gcef17y89LAF^8V?skKMb3C&l@BaEu?Qe`yPFl*z6WR%@J#e4V&dV0ZXd5ndG zAu2F#0KNV-MLrYti`V?JcRyxhzYDKfdq#nNeCXeY`nXrNZ(mltHjVF;Jyk05Q|PZv znR4(;6AV$1&23ROg4xKUaOsYN!oC6AD>&o3kXkpaO5f)htMynJz<@uaW7fT)D~DYR3O9@Vyd&KX||#xd_% zv+$bZ&cYrGT-%ddE}#*2noxG=A!ocZ9>AXVJ&bqa!-9PU*Ymw;$+TeUTKQ$%5zbg% ze;BtJa&htGbPOes0rz+K&d;#1%zDdeoL#LIhGmB+u~g%4Okk<$Gx^@cIiXD;YF5Ys z8v53WTDDa^+jo+D*!^$6am#lXF>FydUqKs{$GtjqWcRM>62qty7@{B>_7mUpn%;*M zo-V~Tt43q^K0}n)ABDyvSjG`j|v%LK@!PNT0$P2cjC9El@pP zG~!rQKH3v9C$L6l3vhtZUV#Bo;tbdO)ex4q{UuKSJV#iO;d}*kbMN5G$!zzXNAzxT z6Xn^xrSwE{5H${~CwPIOZ<$*eDU(@pXf{2Y;UzF2%HA}cjxp^->n&@*>)|tRIt%UJ z7FCQ*7Cge3ETYXEJJ5Vu4MQ(3_t4**#%`>Bfuf&X6#To8A&!#nrc)U`ZjL*an+Sem zh=OB`_s96D?AFGrxI8UMU_cb~`|{oJ<%w+4DK8wo$^b(NWWe|FKOXwdqph)N=cWP! zqD24h*wT2Gkm-u+4(yGg1TsXs{rb3RtZ-Ws&4(H9gw}<<3EPeDs<%sI?@sr|2m1JG zVEaH69LJK>EIp3-zg&qOz7-(IfGGI>OVaq;5zM;ZDZH+Bf-qk}6nr0f49od&)_3-K zoH}-ez$u)cqcwN=M09k8brY_Oa5)J zcL<9yT7i>#XaxpDiC;xMuMS~r&n(7i+(QT@kRg6S9c+?y_>Cq5aJGTl+jWp1Hhw zfaJ{S3bk5DPu?)2vQAA5QRm&4($-~WwBn{IXZ-LO$40NS!S_=a3Ji!6S5DV6V=Ju; z{*@{)APTO#{2kOyWPfgNl{S(o!oIqTX;#C{^0^)LIb%xyiLCCx6_n4S3M@N(?vrI% zv{uMzd0gfGV4~p!w)XfZxvnNdU_jLD?<=WJ(`vLNxiQz_f5MA}X*T0p-KsF3xVh9e zz(L;D!A!8>x^JAP+IEM_bJS85o^HeHAKr(#-%?;e)Uw1$bXRY!Htf4#M@0j)u90jwR*)Lr)wWwpS7 zDA)>;wALkpJ$4Ahe6Lf15gV|CP&eO?sz_wVKTW0%O$G@Jh$5%9(gu1DRcAGJ5O8;9L{Yys$21LPe%ss+0hqFhz9+m*6Le@$j%TqR}4$2tN7qTt@WBwhLCL^XOAt> zgyI)hpL5GI#ln<;hN74SOpSpWlZRN2;W1_9vi9iWt>^Znd?lSO}W-!j= zjFf)Y<(HN%$$@o5i1Fg@-2dXb)Ze-zPivansh-q>u3c%Vrwti@yW{_1{6%GT*dV7n zPSZRq+rb&(F`X$2YDCto^(9auJ{Pu#b@(!>ThNH`FMELj+fA%TPQOIjp`Qi$)u9^^ zCI38EY~7xb)0IV|ZAn0wJBfO0NUuj9(EN1EM4zWLrRm?DH7AE`7g}19j=deIY@E}S zj7&p9e?T^DX-PVK^_b$d%$}?{-ju-SLXQrN#p4WqPUc++kH)=hDKH>v&WrZ+Psb(s zWlI#^y4##SD#zU2$lbE41p3<`3bG~XKwDYq`<9S-<%R^J%I9ln?VfwI#rw~r3#EP$Iredq$<0cx|5shnhW)SjBoih>F>xdUN%+p zxQ->&W0iE|MDj|V1O`Njt?Tg9Md|j=nJj(ThCm5q#N`&tN!6`1+Zr9@I@&j@p=>+p zKzy*LzB{wM9-+lCzL-$7tNlsMk{=Gd^AF|A1WVJ(K9M(BZr{iH^c8!`2) z<+(Ml1O`NjJxKMBQ4e!xqW$AW+NLj;mjpG`tm$_M!BW9GNm9#XJ7v+K?nL#h!Kl(_ zelKOC3_Y(d9SRVPBbB79hvq8WV@rOP=?M|0k&+$FdSS1<=5bDlHsw9&_)0lfBY+&w zIfdWXK(yIhec5H~O$5gk^rTDDfKj)V4F6Elq`_8!VfdyCHQ3TguGhc#UvaN78xJTy z%R)(Bor?kkM#sV!SV{7VU97~s4kLyAiZHA>L_s#+X_&Q3N#7Mn9xLxLM8TTF`tdc& z?x)gsU{6xTE)&DDLzGza(ZNRS0P99F#`F>x5Y^{sAhkOjBflE^q< z`jFsmh5`ek99DIw&ksk*#UI~s9T#^Pv7&oD`3bk07)l@mmR6ERrdu(OEB>TStCk2d zAWHviC@pA^EZ?$H6SG>10|3lw$+93 zLdEvw5VF%^G=`%Aw%cfLCwlgsx!ke&Q(mgETM66u%$9WMXF%a@57Z~>DEaNdX0PG1 z+rt!L&jX_1E)Z|sSuNOQtRZV&SPT16kOBK&k`|8EW4{)3B>n~mG2DrPDEL0|Z_au8 zY~2SBlC5_K!x;y%;VQw`sL~J0xrvxGUicD231o;mc$~9*+qEYde9W}c_G#_w*S>g0 zp%4-OYtDRmh}+8i7#`LmNkgaF%RWPWD%THn)&I*-ZHB+`<}jXKlD5C!BKNM1h>d+~ z0ws_kM%~|?+f%L|8%Exr)+JE8@dQ_ywQQ}ueN5fw`bRhaqBrfMUDbR5(RHmN)Z^cb zPTdT&F=;nA`%QikecKw5;@&L@oRQ(Y3ukaiYPVz^k7mSVkJM6_+aW`&2X%Nu?aTa$ zZQJ?;N+1Kye7pze?x4FD`;+oJ76JpJ;K>E<{fN0s`_Jz~4xX(poN0gz_ryoCi@B%P z>4aMIDdq!c+|@oL@}s`MfGF7NlB9c<%6_anDOzqWFdz!{EcZIs!tytxkt8Yq5;i@P zB&X%g(ds`hs_eDDeIWKt$%tR_Svrx7PMj<-(l@V=zl__UMZV7}*}v^ZX+1{Y=f9_# zKakgCP9ofY#lNZ~>96G93~mKzhZ+`h#yKZ5`K(?Hx39F7jK3xMcM1PKiAT^`&!YNP z(@FDjH{|}WH_B7GZPC66dxdW9caz`0Td7@I^c;!$+Vl*e5&T4B%u@Cs@4t)0)*TWm(R%Yo6PGg#LkVPvtx%L#O$q!q znH>Lcf%5Y(vfb1}+F;Fl1Y5y;#(nufo}!(9rG%G?W-8Q=O(SPRyfsh)8Dd*`>{MvG z##4#Iz0U|TAnL`^8?ux8Zml%#3D*&^$xOK&HkpLYIf9_Xx~d+{|9W3Lr_W3DII=pu z?D$AKck5fuD7*QCzNJ&hyf5MoQDGT@BC zPeJUlQ@mQ(kz?8J0t2Gp=#eDbJ_o4X^loJSwb~3yVBf$o#@{G@;(mNo5P5ECz@P*& z#PPOj=@KQWhdudtji3Di;|jJ9JhdlDk=HU6tCDKuO^~0!fG9XBc|60gwn}OEU=qBt zSooTNr}p3q$KNOeA7y#cNb+_~u5h;RQiD2lcKs5qqt`PeGAg=SC|OHJlam!W7)l@` zW^tKZ&3d=?sK+DzetccmPMJM%0Zn`Khy_M>C7wTGl@+TIJz0+ABk5)6akp-C z(B)8hvEC09_spAi_4bhWT=>E3!B3sB$4}dl_@YY+lz7GVpl7eNl`~jXd~S&+Jy&Qc zFSww_mwa7k!Mb_0BkN{vRp4_MOzchb7KO-;mQ^u)l6q>(f@S@7AUSof2s$7G>QnPf z{86UO?@xTpjF9anSNghRYkBMY*9d;&v>Do!?jAW%zSvitcM}a=+1-eGq^|iz1wI${ zO;pp-)Z#_5JhrwTw{~pCxw7I{x}?*{4*~Pxk6j4({E%LV*&M{W-ww_TkC21ISJZbREdG?GtesbhEE?lL8KWf1woRw_^e8R9$G zVap)pS7ZXI`<2gugKN`c9bagrkdK0;2j?;FRjYH9^7wfYZFg3fso@+9ZC@T=QfC|u zuM)w1GH(P1L_u4dpJTTVQl5VrOD6S=QlOOqt!2?p^j|kqnfEbP$4^0= z@1nTPjwE)knF1{fXqP~JyyoreDCLXClk0W~3Y0(wv{Cs^!=@?px#c9XPzu4&@`m37 z&|2o6qVD6V^l%*MT9ApM1TtW|Nz#|VJeoHsjx0&sATS^b_6_%b3^!E1ww*{yXZ05t z5GD4xRY)THakc}tI%%N5co-NbvpqVMu6^J{ukEVI-;dc&qgkHE5qvc2z7RVI*)Vog zl3ZtovO$lk5jXy^24fOotfCl`y5vM>*7TPd&z(RpWIz=3Kuc0qj1%kK#*z%yyCg(~ zL7z2@@#OoQy{NJ=H-OaiFT>Ek1HGKkM=D9_Xpb^6W929`8jQ^MaT~! zw}i;(d4nlonvO)fysD6y0?rcfN&H*Q?~zh^p)Gk^!E2bgZTGfynXXxOw%{*z@nS$^IakA8U_g{u^9HBCD1)Dzz#0C&LOq}kvF4pRJyR;~AI1-& z0vW6=)FCo%_PL-0`k0W4hi*a-LWbB@QHSm*$u)w=nPp6YqXDjDuxBNSpN>|LQ%7?A zqLJ{G3ZDzVkoaz2c}+Ib&W@xN{!yR>3Ht-;Q&)qk{6tl2?%&mAPy!jSXZbF2)*Geo z2SkRYR49-EQDQxgeQ3a*p3x_pzM8OPqe$9fiLLx`qXC9GU}^cjT5L-;Z|E<4rBN+` z0a2nY+D2>3j2!Cl@2D>dlt6}PC+?9Zv9@dP(1izjDljSt#wWs93huu;p1|IfETct7 z#t96Ff)O|Bd4ut6tVgb<|FAU*j2(g~7)!zP^*xMbqn}+wb!KlA7!U=co>V_|3~Sur zG*TnUp#(C-D2sXXqF7t~*7)62CNLmMjPl++dH_q9;E$hIyc433VB`_BGS$;geb`1z zCp_1y8iNwZfRRHyVykBl7V6R$R~)J-Fd#~_UiUd-R ziB;Eg9Y;4FO?42Tt6?QDAPSC9)vIR0;;ZK4eJ9#8IDcf!?MCg6p44t!SRE(5=}Mh* zJ+%SL)UTpE4}I2X@J1XQ*M&g|oIl``_`boxv)qz7jR)N7D$LZ7A!gXjd zTsTb4;&J$%PA$%`dS0C!`DQ?-46MhX1Tva+ol?nI7*mHcUbk$-b~RXy-<|Xj+6uNV z>>D17GqM?bo*RkHW4r_gL_vMrQ?%QWeSO&z?>Xempae3+$g`Wl4O#KzgE+r=6M+Fy zVm+$Jru+Ez1_lt2bN-@xOky<4!x7Dw>f$*mY{Q8>b3EAZKepFTV46N?iKn=@E;h=OmI zB-K39iADYDfaBw=1O`OGH<){br-ZWThaZuyQFR8(4pDHH;IUCjgIL~xER>L0u0RGv ziKjUp>qoN0$=N8!`H=!8kO5~qezJJWC?0dCkFI#17Z?x)MF zm*D$1nh6Yug8k29&zE~J>-Sf%=OQCvPJ}49qVg;^Q!wj1x(HjetRgTV3VKEO>E*4h zcx-JOlDTrB0(~#gizE7dN;)@YbKespJ?tnjAPRbSBx$m{AuIS1LgJUc*1+flh=Tqy zo_}}NL^d|56OMk^R`?!--+(ZpnV$vd5yz_aSJZmNRy^b1qMXHNCm#)TqCLe8KAs8PEgG*K_~PJd0oqQFEC>3G^C?e(L)-4k+cm z(WLju-1blc8PFfZ_i?hs*q8 zmXBBTOe09V{|Uig0>9Ou=Y{Ja_R8hm-N}h7wHWlOz`Yx|lcJ8RAgX_95^=lerNA8% zxDzMt_7%Ilm1o|aMpC=JmPN@wdv_}PpS^AS&*pSQqv=F`JY3kFhA8OW;Snh#+fiRT z7outDF2pmyNClW(kbiS(XVI8G4kSL#OJG10jCA9^*PAD39I_Bs5!(tk&DBHOX0zjx?#xJ&ls| zdEi=f;c~6Y-+%K?^2~URc}7C_coMg3p^$6RZ^2pZqoN(?+pLwE{Tm9j%7bmls>^Yn z#p7UD1)Y{VoY=m+D&(_-C~keo$I~{VZOh+shQ}~7#m0UBnOWtFz<{W21BS?6J65Bo zRyBADqwPOanh-~9SO$jAg{87sJVGvLl#PrVpX55CiyJA{+oH%1j}rm|qM$xC!$vQ~ z^J_1n?gT*X5ViKvUU`M#3N+xf+HOBhJ1c7JhfVQK<>}Mq@=Mp9m96Qy{<1vKZyVy7 z>)ef-kCiX4--&{o8t_u_Qz=T%8-vJk%X$iwK*r7RyRz^2Eoi~h4xHgLJc;l2O(0de zSHqA2QS<6%$O*G^&{>~BoH6oYn$o6fEYHc&0YeF7WXwA(AG()?Uc6Yt86Fk&6t{Lg zNl}wKLcTs&C#aievl?4US40gb>{S~DjyRa@Ph{|u+-TGq)YiOPMS-egU}Pk{kZ|9U?zt>ts#G@j{JJ)ir}d&^{NQlcLY;cx^opj^K<<*4E0M zLJP8XnxDXcC~-YM96^*OcdUqcv(CcF7s!BTXe4Qolur4bGNk`7F9O>H_Bkve-!VD- zoNB7s6QifxE&;6z8F0MuoXaK6lzO?gWacQ1zO=a?Iqs0$0oAe0_QZZBpX~-QWr*Ne#_*C>IBh zBzpW7B`ATJx#6tM-_6knl(^4BNQlE)3?+~uX8(2?lf~;1L40;^7Z?x)XCj{Wa4X5yE3Y2$Vp^gqFGTrkSZ|oOu)eehhjNp)?5XLXM`I z2@HsWb{D@N=LS(qy?prDC2PSVgA6$H@jc<0SCm*&Z!&dARRU`ZbGhGLVMdK#CZRti zR=iZfwvQE$VSUKbf-DUC8Rl}oa=?PxG)Y6bt*`QRFw(4C39r(TWYc0HM?6G5+3QMc z-<^r<4prqka{7H$3OBhC{kc^LED1!J&2^z$Tg9Mrdm3>@p6L(eV|iCXdmX~?xv*46 zAG*`}Z|9&Y_ipi0d6!pVhp%=ZI_$c@fGDVsTb8^1S)JL&#AWjY46~35IV^ ze|Qm#YGwihqF_F3btD?I_{SP@{8K)Lec*rJlLpRTh_1QjXe_@5(ccjh(FDUH-h)S% z)?*dpoXNqkn*sx(MhxjmXU`ppUIwb)a1Xojy~jm_lnx$<@p(ULwP8NW^GMXdl8F5= z-@7pjE^5c)`W6ceh;r-`Ld#ueqIMCxd8zIUuwxr?oJfz)YcZ5S2F$q1^Wt>3V;}0a zBAZ4W5Eu~EfBz_2&wBuRt32g8)Ls4O8Z#1Gcn^nfA3?tz>wyNfsDU6V-*gtujcAJw z-B#bI>#`49V(=U9J$eO03Cu4G^QWr0Ub?Xqw-P+f^1P5)6*6G%#{XnOD4d#)16;L2 zR!5l05$3$(cL_a?V1K@4;T4fN7)l^R%x9UY4CA>h(s6YBE`b42FvkHuV-h}^so8qV zex+k5fee^Ml;4$dYBbZ|H2}wMUnejiO3a;L`!bGs=C;O>I2A()WQbWdljsA*CfJPx z^47Ua48xq65Cuml&pXH?eGB|}c1p9~0t2F8{!IQonAwgQe3N+8%X$gY(#c1ZbzU5GDN#Q zA@iW}!OfP$p;iI|qC|^~z1piBd)0=7=rYk=cPJ1jfehFp z{F`{(T_wP%G0~4`Auu3HwEEQBfsGRE$dAH?1WF(Swg``izxP~;8tF=kdl?E0h=LZU zdg}Lqq7&bpyu5xzuoEE)ev9yv_cgC7SqDRjx!+!a0a4I$=JC{tr3%l9Oqv}S%x{VL z=k6moYeP#`&C6MpXOs&h{?FzKw!4u%Gyiba(h2TOFG5Gl~X6e+Z0#AlfpqD;m1G zB_CI;_D^N}f`%k)n3cdV11LD&)cd1;D@&L;3G`_qj4R0aRne6$o75aFj1A^G-mQPY zd(fPy=k?*UAPT+(>Up(?$~+5mvbVc~@P0ssPA6~5vpHy7#w_4ETnxV}Gnbi?^tm=d zUT27c8Jqbid8Wf|XBm_4uFVOQKnBby&3D{+&Yfo;Oh~+~jgV~`GGGb$j(b}Z7U^Zg zzt1fM21LPCo1cPcXv`|c)*~--O@$oTkO5nopK-5k%~Au+h@ES7fdNs_8jz%yKP>oO zYC~d=BmyOn0Y?n42an4z-DgAAx;zmqWQc+m4nIrw#*CE>Z%@*~_6k-wM8S7O&3IzU zvYot%Ug=7K0a2oTMNZdbBs74ZH<%%OO+W^GgZVd3mxoHDlmNb-7gA^^LKK`ac+RsA zM--#um<-)=O0X;;3i^O}X1u-X-DiD>b@^KgC6EFAL3~b3JFYCv8crfF2MC@b$Pi~Z z<}z2g8{tY!`r8udjesi-^kwn4_DK+rt##r($Zzijei4X*9yawXS$idKy9aTZY%ee% zO7wo@Wf>~)Saoegw~xihWM246ZX|0 zO7%?s-Pzz@EN^zvqCemHZ62Y*O-=A5BRt{A-*a0tC2)UL;+7N0;2lm71yAkq(}4Hf zm5QS^xR*0PU_cZ+8OU>_xCbg~hMSbr?g9g%;4M*=JG{!Oyzh8RYHlevW)b5xNYZpJPz1`6?TkO8A~xs|bczcTO3E9{}^F2wIb28^2J z=Zd~%D>EAp=Q#%!2`4S!=?XCpV8D-?ihV?XlGtmJ5cdjEFp5AuWm=$|t2L4|@4g+u z7zP*(0Z-lVvzF_$O6;X5QX1X{LkVQShzovi2DztP*fNyxQyl^WqQt0|VrVH7PVWbO;fKl(F8^Jn+ALci|hbu5!AVk5q z9DbJUMdjugeVwa#G|Q_CbPI*hA4HMkHCN^ zF-PNb^C@hS`%biDa6KVMBV@ocEqs^EVyc=Y4UOOblEP;}6wK<$y|pEYjL$s$Hji!; zN+1Jfq~&c@E1r$KKO2*N^EHqGQ7{iEw|6fGvU*pZ;lZts3VAtUCQq27lUuJl+?igI zF41rQPPjb+X73#=+-c$8$Bx;ou0`TLS0PXW888PrKRLPfi4tdJ&G+bA2sRwd`~__- zm2pDhaj9g@YqAVbWt)pw?>yqnsH=oUB$42TkK(S^QiD`)D|VpqWyg$$U@Op^Ll zWGdND8jvYD?F9xz!S6P1!%d#4s2RosHe%sR7&72@w0a}kC3@4KK8b4DP1w7GyNht& zkY{4sT!QyX{v@I3J$*XX3(;-Mkm7RB%k8Qy+LWKE?qIoZinK<@w`HPnfgQPzY{rri zm}i3~nG+nb>G>0ymw{W+ajBzb)2IoWR+c-_i_0DwzB8`*C!V2GCs)F=i{lr=jM$@J zaY&;eIb&{3{PNKl^sL87Ihh*ZG3NbH=Q>Cpovvnlx8Ie7*VP+JJm(+BKF=GW)I>pog> z#|>4KwUARY)$Aw1wj1%c>HSFb!>ibPMiXRVy;M8H<*HB*$mX|T9E-${9($4SDox3i zLzc+Bx^??={Z69iZ>`b8mx*5QBJz>hoU8018UO;oechBq5a(%wzQt|k)|h`Mki8EKCHmUm?8;-~`) z(7j#XO6Mlas7Cra0@;q7uD$kWKl1E45Hb6z z^2RO4c&XI;8MH7Fi$j0vjBZ)WQZE()J5E@hW_#Cx4to1%~yj=+%>p)(pJ=SPd)ja zZw<6PY8QHDI!|jpVv&a5m5Z#poowGN`ntMrz;}I!u?{)%xloyDl8)~Bc=59GxZX*# z(9(G$D}VDnB=pY>t2f&QkqOa{@c0F_MBUoR%t&RZaZx{$yI}qLr2+$@c#cl=&yBYY zjC)k>CcZmusz4nO^{&%)b%r?9Hqn#o`1+ENn|sjlR@7LB;?tbHmw)pLrEtS8U zUvG<>EZc;RC0NNB*$$i$*su#RPAI{Kd2qFT9cMOL3KYh>?( z{65HYYy3&_q*>Ul-DL$zMIZh+57m)GkQ;o zrq-hqTt~Ha!%29L&**$D3k6DE8SO@Y`k(Xa+pxJNXhbf`{`!^Q);!0JTYay4l1_Wg z@%_ka0t2F;Zf;*qic+Hh(W)_Z6gV3!X}1R*ta8V5SAneu)K_^62H`6s8hzr50ws_E z_3@GTDuFcijzepXkHhs2tVjI~UF4Nl{m{Uf>(KnyyX8IC!V#R6__=NS$t2`yHd;Oa z1c*}<1`&s?oPKYUxaK{hR|=ftKz^Di%^U4qiKVc)v?If zXgPz-GrOzFh&tp284v~aNz$4Z(}>ZF`E>NUY|3}?QB>l1T5o?{K?i)2dK=Va9wSpr z;aLQglaVWsWsfjgU1^G)<}XJ+i(}|meqX?ynoCiQqye;co4S1V>3?f7@!nQTafs4W zpae3YZb=$(Gl2w+@lyuetuN?kdvG*Hz(^A+D|LVxcjhcgi$SI)i3Rp095ZbWnSw$1;|YLKzLXbIxyVv+vx2tK#;To6X= zvc6!ujs5}yqVi%h(X%%7(O$1`&gk6KgEZHv%dqG*@m!qs5v) zG=txhD%uSEoHMzb%;Rt(pW^T>OVRE*r!+-xnhRD2v_5zQ_I_Vd_u?(AuAYzqQPp-X zKo8FZY4n#4;qONj&z!vL+Ec80Yd5;hK&NVWXjUAajUWoL)f)@j5f4j=?7sOCpGcXC z_>7Gfw0A)eCDtQ0*_rq(tVwvbG=Tw8uoWtAT_A}L#dwcz6QOlsi^7$GTSa-p$WxQc zxPM2Cp#(AxHrar7*Q<&S#&zQTar42Xg&1OM7K8$)u8H)HjF4k&?) zPd?eGTg-ON;V#MQ3Up`^as1N+UoWnW;Y&FprnY zb=pXB&~*pqzEObzQBXI(yJo^9(xgnaV7)l@mwi~~l%O#vVcDRCPHcQ7) z0{df^CtquABy{cB6RyL2Ss#AO-+N5gF2Ya(8E_`z8I;3=$iC_oI6>JUFd&NW>Z8B+ zSMysJF8Py|$@;{&Z>GAd|33+2z0B=$bhZR_lmYOBqrzed9LC*>Mq&; zzUbhW9^WNHfA53k`IchsNd6yP?z60+?s@%B0vT}Tw0oN-@nw8On zv^3Qt2d5hgHHUTL-a+)wJ-j0pnhv3fut`W zT00YwdKzi;`?CmoEO^xY4?=#J>JpwgLhxlk2Gqxof4uV`z4)ETXyR*u0a38DJR6Cg z9cehL7U}HEql!VzVM#=W&T2cdBC0z1eM4VhK$JKV^{;x6g5RI;pz&3N{(uazt#+mm zGOgkvzw!1r{(oFubzGH6+din+ttd7MCLkyZ2xn$cY(zmtbkP+%u@MxzK*hvvMNI6L zGtb!F-L>o5-GP4h!?&x~y#B?{`?}7|Gd*(`{uZM2K6kv^I3sdW%%CS6CCGTQJApZ7 zD{8y8#LTquVo0b6%cc11$U7PXQ8?brwfzrK_UjsomvLGfiOAT{YZgn++9GYxyuMUM zLtA?>Bw`LL5#J(aQ3 zP5iy4m{6YAwUq(iLUC0hJ?E%`BIYkYF~0g<{-jDfc7AIg+tN+f+4LzaWO0 z!z9U}f+%?;h8N4+i^VLSV#~GQ3d8bZ>-A%{@C~*v%8c@Vx}Cou%SquC=E+fl4806< zWoR&<7BLWZ+s! ze!|V#iK+Kj@^7mSY79i-nokxfy}F2#`Q!Qe$nDy0fDBwK$$~DdALRt7%G>swtF4K+ z4(hu>%@e`meR^SGc+O`ymT(3~oQq?lT(8?+ANWXp{?OV=#23jSC?mASK$Jcb=g)5> z?l#FMD4U=*60!erKGLrCysp?w=UvLFr_B#!;CLgCkpZ13(%V^15h@K_OTKm($CjRW zVvF6Aouf93>@rqGnqI|}Nx2xu(TB6k=kQq8E%1l!`sRP=%h!)LN6Bj*`S2V=2{QCA zAN#P2$k+TfUo-536&Z*cJ#!3m81&6HW4jqa`SklPWIcC<7oE9EqC{(5(8`(G*ZyMX z+IZfgSuIW5hhK|2J-V@6?4O|@Y@cnartL!w-`@Ar*vGm>Wnxz|=VZeHJw(x4i}-$H6QPst$nKcFFWwG9w7QveMOtgIr zc*dfBv}b4E&$LZ;{77N0fA3eMB~$e&GG#t7-+qdLzg6|0ZY(-!p6z39J097pJNs#! zVmt8BjL|r-bdU&U_TuN(g&G4<7jH+ilxFK~{JE(=A7vLV_C3GDJ$BF67>J6D9nVUN zOSVh}%~)ZtYKDu)*Hd|N)LEnD&r$5rx3#t}OLOx%=Mz}B9s6uYyA|Zf&hQ=(0WUxB zerJvuD8X8-n;*>+10g40bbl|BI)w7 z?kxDp%!ElVcH-RT_56@ievN^sTU8R+tlOv3GS4kajP`e3#D=<=#j@hB43r>a=Z7Tr zGRb-O_sM3gu*{2FiP=*|^Wo>-8Q7xuwfc96XW=4OSwH^p?N5z?sL<=vS-u?YZF|<4 z*_ziDiWKvkzhRC|pKA<6QS2@DJCA$ill_E!!C9Pif!ewKcExy>rA4pJSVX{{oUm3VP-au=b^EpaOeJfdTg0AoP+gtPh_=nSCF^M+fhVR zWT->Y;+R_k-@m>&LkX6FzeFdQ&K<Cil6(GNK|qI8>yieTWMJ9! zGO=Zd2%S=t(M{68(tEv1VkKSb$^zacxy~T#Hqrk~b{2iRs`eeoz_MvKC>1N1TT33% z?TN&%#oxsml7*>Lw8)(_kstoCRbwCuTb*`;%F!a$a~i+;)KQ`Y8Tu$0QlOvM9I~Dt z*)@rw1jiNbsB|J*)q^zE2YB(p_8cY1z>xHwzv zJiF6Br`G4Fcf?she!@w^&DcK7)p52JCCJeAoNVw=QDUJd_ww4N%_v0SUER#iHCPOv z7{oufaONmM2A)glO{V2wacZR(|E#<@N|2#zk@s8si;B71@iK2lXbeQ*UEMs94HS(I zxN^$z#8H9_ym`~xYx5Y<`p>(}{zZ4wx9`_o9~pS_wpgw^ju4%~M_KQA8k*i2=OgNI zDGNs1;ll3D80p{iyv9J3uHiiz6eAw*@{pf%$C>$^*?&2&DQ+$MFVi&6O|lkQ9V^;Z z4w3_yWY#_V zQJa5gb?wX1)`-rDlp&^yql0x#{sWp75`Krib3UW|RHa5vljDYzGf=mUwL&{7ia>KF zR*+|-Y@a34%sTzc&I%b=TYA6B*-^Cn5y&%VZL2X5rQ1fee$`HlywZ%fXfoMA2{QCA z57`kS-uEuTMa{el&k1)7Px2W;(k2XbAje>2ct zm|l(Kl`HTizGSY(?DT-^{^wq=V)%Yd?}>}@P!E<6vr_YG@6^aZt3a}c`{^WBFDxu} zw9TwB5QXpJrhgO@?!6pDiGypkcLsb(({GUW$sNU_p(l7dy8#?u3UCL|*Y=cwadgUe z=ffxFlDJai9);@)^|{AzK@qL3?`PO))*^_~_uB2rapHRFP?>LOS&e}xv;(2FWaUsn zvGk;KZ(q&61R45TvM|>WL4I+Dr#;sgh(aq8(iIJgrPJ$I`Q}2fW?zB~oXupD`gO1% zKVF%;&j@YS;{3o>g5LB$3>2Gg=8@k<&(j!)!Wm4q&Jpw?JnS617`(#3RSi+Nj**wp zsdmD(<4Ioh`c&;ci1#*qO?=ZKYYaqT*`^&?tT?^8tkJqw4Xv%Pee@NM zGIWc4VL=92zGw_YpVQ+zKS+n&|J{{fX_>kW{lroHxp#&>s7zC!$t2FXJy4|2@=;` zTybzEB1`TD!^FHyO14hPrmfV7!ZAknSG9YQwR$mD%J-;ND;y=bqgpJ3c61TDCtYK) zF;_JPqVU#7@1p9tbykUTl&zqi*znQQ+ST)j)hTW<-IvHGFPpSJ*s}D0Y_>~2uE7eP zs6-wLLSvw1H(Gp?FF>mmEL&SY(@RMBr@pqvd2oN{Wd}67aI_b6Fn>* z0&UFE_8e`*Ef&)T;7gnv`Q4QjC%iq`&(pcAZA;Vc=3kV(R#k>Bc6u z^lf?acdo73&|`1vjP?VUvw@{uMbt5?*1E{hdoZEXZFV`%M-*70_Xnb|XDt@rL=WDq z3m1!4IBR7fN^f1e;JUm(t;XVD@xof`BIES&T&(_x;d`5`Izc^Xp4THi!iDSFcbZQF zqR>x+qKm~ZLqqmGt^4kK9*}BDdV(IF_(HU9VQQ zOcpVDa((g{-ON#f4Aili5orG6ANsZwHOHoKEFJw#kZrNNd}a~X9l2N-c2}zvmWO&O zGZ%!nD0;oBnJHG&>S0avH_LNn+^v-hwh<4lSw;J;{jJv)xThuVy}~9$cd~wv6ZYgC zb0%Z$B3lYSm-8p-Z&$X@UoL7Qn)npU@UHn!f(+ferghP^+-YYHU1B&wX-zEk(!X89o?@5dajr{#GoJ5vu_lZim-geO znejS0(*pm{`h7()w@qA^{AQSC|MoE(74*WI>-(P>zD3w;SRS?;#hHj6!^(`05HD(e zGHl`QRy)ULY02eYvU6`jt<$`xrZwvFlxkwJ$Fj8Bj+CvrzM0wjm*jsLAqRcZ7S%8{ycF-151gJ; z6e`?I^L)9saGrH;^v}I!(6R( z+j#c3(wkP=ox%72rw9FK1~E6%NsW<rqTjyLi#X<3_<{n}l;dU-};AWH9#pIiO; ztd2QF^0X$}chqmc-&)psV{ezc9~icR`NC3)XFHQaL>+FbQ1Vaq`BwiH-P1;Oef>Xe z^<~*3W=4U^eOqWfhz#r-vby)`&7ME3E51A}mC=L$^^}gnQS#+*b6#;-4$_D>QTV%9 zL;NPnx-jw>`{px1JSr7$;OHxuBCXwL&ri!c{uQgcKhav&d0AR~;v*U*o9|ELKAr1} zw%hZl%d^i~OP3g(mTk*B*2Cwk^>+5jX(K~EvCmQ2*~@Jw(mwf{86@8&#IV z$?x{T?=vHRU18-H1dGGYc@;{qb+HY}a^PlW?!F^}JaS)Z-+?G>H?r}1+n#rLT$*AI z)Y94t8G3)@a!KG1i{>JIYJH7?sQZzxti^j&PP=*QGqu&1r;GV3-@|;*)wT*H$Ux6G ziqUwx6nDSTRX8M`;M%GWtF!K3+v0W(-uv%%f;0^p15voIQ1sRgyLht_-Nmuc7971| z@zi(Lp*&kTHLtB~s@dmP3tr%2SXYr{+25KUEuva=uEAJtcUw$1bG>@k<1v5sfcC*U z2}bcRRyLxRmu>dW&#X&`J9~eil|B_Gt`6 z-QH0*!-x0uG1I2#ncHdpZFG0B{^d%4EFEiw<&iJhh*SL5_qH@jrWz<2{W_W%f#;kaIk*7*aibhhxKnZ>mwjo)0m(M3E zwH1^*bCWS?ePgzINCVr_q#q1XdRsj_SJ2!$ge}cqVtuhzSX=UUrnqfhd40v2XLGb# zVR`Ax+pxFud)vMZG%dD1x%$z$rnbP;^gCCv2Ro^jwn3o zW7%djL>Do3UTu-a8BS1#*t5Y z&JRnt%pNKFIczb!W6Q8{qaUSBp7MpAS)G^N9RE++MUOZCvky`ZP_{WFPSi;0C~@y= zwfM4it>@0PdhRb+uf|)g9jmTQ`{Sb-LE!Yde0*H>p<>{r&JrcaxKjF~HE7f6G^aPu zh*8Z5Tn-%u!EK3T8lmSqp|~QY4<5D>7aQo@$yXJ zOV{)j9hOv**lURDy1W!ybJyOM6!wM~okm_~mlkvt3H*Y#t7&IL*b~Wv$GHo62*rp> zhquc`HS(~P&7Y@bd-aTAOY3cAS^%zpA1U@lEHiKiKopK1vhr@cotro9LG|lu`+2Uq z`Ph~o<))0xBip$?B+OeY~d4zJ%v#N|2$Ck}0kcJlS~&`Jhj*;^@Osi6fu9Wy1sblc*tLbETQuctw#kh?6YGWIUx~0V2NCi;yT-u1 z1lN3vWx%AoLWGwPvp40{7#d3Jk1_M?#K`T{MdqyE4eSqOU`x}jsNG~f?A$=%_2ibs znTqQNwzPS7p1`k;h!(kah0<;M_sW0_t=%lkKKCcTzP^GyLA4haMB!>jHbtJ1e1~HX z@#ew?je#gUk(2&>XLS+N><4d@JCnj48Cw_Q@Q{b}`LblEe}r$CT3MSP*n`-!WTn^V z7~jEKiXMB8X!{_xD6V|;a#v*qe>kDHsFW{ATNAOZu+_;<->aN;-XCW zu0FUbnYK}r*x1k^V)*AK9CsPqqwqbzv@bcxOnU>j5`o(L6*6!Zm|nm3{N%GZk+ypZ zLkTi)ZqmC?Ry&cUS|PFhMOkfSz&Vd=480BpRAjdKBSg0LjyC*SyyNQYu2adZly7pN zuk1Du<@19a$(49?VAWB~oAAh6hFwt(JLEjPzCCI>Cf+BhTd4n$u z^AN5j3TX^PVc*a>@!3aS_(MK%JP+l>hBX`+dJi6}oKuh`F25PjK-)iXAB_9dfKeu# zwC>Jk%o_V;g~jNBtN7h!Ok*Gl_b$^1%R^AUc)rWAn8KNg@wRZz)7j@pZGLT4X<=sW z#V9uz7YAPus6R$e<@4=d@Ows6g%V`w?+kaV9N?xMGTj`t*gF_+N8g?4gv=LazsVz8 z*3nJ?$iQ}^D1x=V@Hd@K@y+*ZX%T@i3J|s%&2zHw&ht()EURFEObJZw7i8(d+H6Fvx@K)ImFFC2Za)3piMGq+!vN1 z{mM>mW?DrCqR^t*eABNjDAy0qW8_z8v4iV5_CL+qqP0zH5q`ISagBi}y^MqnN#ybC zO8cOjK&>unNl_DPdRollNscu{y`9biCCJeAwF`3{=Z&fgQH8wLQLlz<)Z>x2Q|+@n zv3CP8YWrJF=Y=R;OZGL{UR;h265%IiYT7=$ZR_{*i6zOZKeQ@Ebtr4#Z5wac_<}(G zQEozn?y!i2@iz>#P{(^T?!l&Rf{Q2p9`RB&zi13ZVQ3%V6*BhPHNG3!kC7!Qeu2fpMJjW>8E-Au z{G$Jo1?$=IGKuv6^=33=DcM?!fm^d>=#)y%QS&8i z%)qR4-kq~Gkwp$}Pa572{6X7;{x$X{v+~Z5G8q4{b;j#c{h1kyHD%vf$^kl|W=f;A zEb-kgjiLWi?R9Ca(um%)!lh{pM1?geZ>0>;tYu9zYp5A(X~)_aF*X~W$lz677&5hckQw_|7C z>`P;@zSt=PCCIS9KgoK3$9jtR*2tS)KNhtn+p7-Zqiar$fhfIJHBaQB*N&g<#SwT-f8oORgv+{&u4MeZ#l4f?tUp1jP z+t&Z`Gh%sW#@klB*Me}d`OY^pcjm9s5k;BWtiQ8uhFp!}C&Sx|x%IDW3`BJ}GRxZT z+X_~@%3-QiUxyj|uLA9bc``!@G6HU0wr=)c%+Ad_PK?cSlX!vWUBs)^t273puoWm~ zP4iT~{b?uBY2BTSm{C4=D#O0ub{@aFn+WslsWA|xx9;gvO<3-V z6~w%IwS_s-?iQQES{AQHD;ce2*?O=;JN{t3Iz9J)+hH(kzPKsG@&X;VU+FBfFyg9OQMhFRWk%ZNdZ>hOfKPGZ!q06{U^ zt^eh(4DHs(y3eTxyEH6}<>sfY=AHLbSu?IdWgizhEtM3>_38_hAVZJ+IlsS!`)4UZ zvDF$0lpup*%36PCsq}C;&4OAv3fI>`8Us=K_gUwyX19M97qMZDH3p*4PRe4LaqK)R zHKvr<@^=G)HNlp~@+gN}jwQ_PQgPAJXl!P}{8e9MV0qNgv)ovD*OK&x)mXE+`yUka z$FqJ7_}xJbMPX6Ij9mX~1;9B-c?qq*vo)(H{rE(RlaeocHjRNOoGWy`%6ozPe(osR zoNLN)jN;hUBlh}VAIL13o6?(pk&NB>za1G@30%j_?58i;hw^{YE9ZM{cSaPh7-n>_ z9K4rnS5aWp1&x6y+~G{U0pnfXcNH}YAL1xM2Cf*CZ(>;;irNw-0zWO)7>L6Cks`z{ zh~Y8!dQ;4^8QRW?3|ukDhxgq$Zu&eQ-riPYAPU!GiV@!;g(7CR5zaTiNR(jT;BH5{ zi7T79nH4dRAJg_hWayDRZ+$<-*A@y9m5)7;C_#qa=d-(evtb?Ti0L&lvIGCx4b1i9 zzy8^@4qC_4~ZT~(%wjR~jQ-m15Jj1qtmVRHv0)8Ao4eZU6#l+9>75hraAY6~cOSC4 ze`E0X=`DpEdX}RE8Tkk2WQ`WhX2J1isEmi_4)F2IBSg&p4H^ScIOoYXWBqk*W^wJ4 zyxhzh`fI;K24y&6Rol#Fa#}K#;aK@T-&U=y*wJyM#z2%lu3Fe<7Sj)u7k?K$X?!2h zm0h%r&DaAm3N1y&WHWZhGvAxHC>E>zh-{+uC^}?+%VMAe85qx&2I$Q!8JcR-8_7GO z7K@%ag_ZqhrWH|otz?ySK6Y?Rak<3^je#iqCh`E?yOMn9>xuT2bBX?zbZh9?iLCZs zM~3}@{ZBErD5Ko+L@wOx7uOhw!ZAiVdTS`()YwCmkFKum&WOTsOnRK*Rk_#F3L?uR ztHwYS?sgRYdphZVc9Na)YOA&nA_Hd^#f{2&gjpI_5Z96eGzOw@Poy|r{^MAoqVD3> z6o2g`gA80H=>E~BxG0&ws!#=T8kEbFy|Nq1I(10!#}R{Lfou(KI*Rbtfg)r_Kc2l+ z7<)c`4BNA2julZj7R(5-XF27y5Tz&vRtdL~tV{oqtkHy$jB;Ks<@SX*LTrA#;U^0DD-Ni&P+IBwW>mX| zUwMl(HxcZRTUdO(nO~cptoTYNwqDd>Jr4|K&1Pj`SX+ug*Ct3*I#!TkZP(@)qYq=4 z-k&{=bz2z0s+4l0G6G)KqgZ-{NuxMQV<1Y8@aI^;OSGRyS@;U>(IWg&{y|nRe>av= zV4D`t^#3E{<@i`mY|eaCi;Rbi0V#j7y~}&B9xd-tt)@RME$s7E5TU#8XbePQE6~02 z4@ZjKR#t4Q_FZEjin33!-+9SWYdeTTpNoi2f1EL}*Kk~6-vjd#AY=OYO3dPy$QHjdqsrf!l1l_T`iX0!FKP@#VY^Y<@BdZ{Bmw@vFl7Gfeb|HW4Bh+J|3B^s@US{q|ZTEQ7KO#`<<)tS<`hqI#U&q z)G;IT;x7r#RLZGnWs7^UYwmSuZ%J}o$!DA_BW}BRo4Fc)F%U(0GuVHbCF$+;ashGf za(&_DIbO5zLJJYJfFVtFVis}j3`IBc-6GNU15s$hWJWx(6M6oM5XbE9YgS>1Lc1JV zcjtZNR}Z%n!_RGFSO%hWiV$e=xk92)W8MKNfts z#XB6?K>i5ls}GhE?FZJ@ZeGa1dm`Ci*%G+@u~K4)7t?N#$k6+v*+;9$Grzo8{Ja*& zH40Z$oM{x9duSEmT;5a6|7#k@6$erJ96bHLy!qNit6ZwaKoqV-q&G+@DPDxv5Vrz% zaFiee=O$$mC{a|{=6H(xLoaCzMB%)l^Of^MK5Axp5!$Gfwj1CqqTGk+15X2#w~_tM zgn2CV9S^-xLj3)ztk5LzyV$c7={Czl-f?*m@#wRw#y}MIEZHHinMhG1ON+XbtpZn0 zoZHx<pQ13J)GvN_eLE2<%%#;hZNA&`*l<>Q2IatGmWP6#8(}4YKwLe%zyih?(yq zP=XBfDZ!5@evJiEN5m{=)-?d5dqO zvug}Qp`OZOsdKi7h;Bx?e%CC}q6nf7mabj;8CXRu6Mm!(f51?JmY}*1*5opQBF7ge zk>Ykxq6BqQ=$B0IyAuLMOZSpA;=QyeP{`0VSRy<^>|3#hzk0UMK#ygN@1%RO-XGdo zjD666OXIl4Kot7Hnl@fTMW;epjmJ(726`-`7cP3|(n{?eC#D~EHs-n5Br*_%ISJ@R z_^%Vz#YaboC$p<-HWTLS$A6v#Xg@&_1YE3Sbst3UWBCOfXv2Ugw8p2L-fed9ERRm{$J1JAHg|~9_2={YT%a638~Ek8aE*Z|U4L$7a1GBJ z#kb`Xn)MFqxly}J{y5nyQoe}<{-s6@je#h%D4-X5S5J!297(p89-6HIGElo{#!vJX zp;xEyGN+t12BJ_0O?Mp13wUcfSvnQ-)+~h3t`n_==yfo5Ew|0@BW6$XVrW5y474Mq zFaIlokGd5hQU*TbXf=gCs(9|AH_N>)6mh6E#Tc~+WFSiSg18itpAY-cRCx9;AW(t~ z^tC0+vzNzNP;wK&au(GXh(f@PBFI%^naGbqeV<1X@jr#nzok(imM4UXh!ps}~>xB*( zcsHc`d9{MV`C5?JHO|WMT?|opVsl;_z7-bBuegYQe&4lt0Eog!G4u|Xl1)6#;v(Mf%&naO5QXOz zitqFKA&(zJ*&R=p*UmnO!ss`&4_3Ry&((D#`$RX5fhhe9H!tlYZ<|yCc0xu5W?-Nl$5vXD3@;)cJkP8#5QX_0C{p3$x*{;)2k)19 zl4BkV%=D+{w3z48MAUry4@FNRD>}%Vfeg%CKxGUI6*s@!;VzX7je#i4@+h=0>F#?&@8c>Ix;u80YGg_B8fXMr|oe%-8J3<11BF$~P$BQPnJ3U7-XSgX(m*{yA>#zh6E(a6QkI zwWPYW)mvjA>U~IrwN#l6|CX_S{7-Io-=Y$Db>)<2wbhUH&G;?5FEg#ZW2R-GkWH`7 zDOV^vMIN>MqPIc`GW0T@FU%`En_V&%<@HgB!txF~ZMM$M)coICeP3HvY<-ks94b{^ zp#&N0w;#4TOum~jA1xMoH5a|r7^A~-Z;gSdoJ$T^-}kiqTSni}HAJbG(`Bum)s^w_ zl=a!6hkoX)4GcSFZG6!wV{RjxGCP!UH~n6XcDKA0N|2$KQLnKl`PNotz88HIqOiQi z9gkb56U?7`fe>xYZlZ@i# z{6Gexux!$?Ec?ul4gSH`Jo8rgyU5<@I>@@XKuSh=bV9Cmhwti`Pi)EIrBH$lT3M~M z%KiK0UP~wNaIZ?j(%VbLT)pmZEqWwFVsy`Eoi=4(#_#HkO8M6Fgz?2iQbAvZ5@cZ6 zWC=K=953MQCR(TXC`4g-Eh3)!d0syC?{}of4`RJ+HN>;o)fGyRk)!3$y&bQg`u95? zeXA^cg;W!RTznKtX2p+B8{FbV#_!@UQ5?wG-Ho1=Dv4v#TUCgvVjKBwZ^mz(pH<4% z*HvaPkWE_sKU|CtnX8G|ywx=ZqOff87}>naI9j2kXxr0A;qPL36Iu_qIaOZq@0UNS zbHRwIQiybf)fGyRvHtNiTj`XU|9*K|rot*{#ChH_rn(yAy~oz>cC`#im%eLl|2TEe z_+6c0tCDV*vAo4IAB7TRVA-aoy0ofsbSWQZ^-+kz@_ffC+uHF3|NV~SAMR>pP;);2 zUNwahWZ=nw{O%H~s&`$#GIMQ52BHdtp0ag+T;|_-9^+n(A~}5Ww{!JTxYHvF*%X1M zQz_-#JG&Zr<&{z7;~;tN?J#N1ZNG?7GR3p6q&y?mYhx$MwwWU`{-10=+PJE7Q(qc6 zHa#^^k~%O^t{WL5dnT;2x>uMZuf41JFJoRsKQ%3fVYoUxGElPe+k6>#+(p)(KgC+J z-ZHuET;6{fb?equ+2dyzk)eMZC>gqXg*+7b!}h2}1MA)|tEAEFGM!PflHF^mkly9@Kx+U2F{9Ginj&_g%Aup}#uB?!5-Co)D#T~U`yICx4zlEu*$8xC- z;iGIv8%&nXwuZ_0;`XfZ*;%r4s<+&{_MH`b(~RX!J5ASW>PxbNte>-sZ0I;aUh6!? z+QYxA9CUGltTFB{D~=e8#j}}dCl@|S$QVCvI~&Oc8>UP1^oqZf z5noi1E=N{#zsj(6u|=`}=`Di~Q*E8>3`_5e8UsiY5SwL@OD_f|88}}Jb32ih6 zqHuOmMub~I%Bk*MV{&>I1N#|KI5+9d@=IMByB`gT!J{z{rH_(@OC8ky(;jM(*BGro zun+VeT)IAwI+?$yifs8-V;~AwB{K(4MYTK7Nkw#y)7C3w=p)fN-COl@%%{fA>#wa> zh|<3!dum(ND>%uh?c2n_RR;S5XBUM$>(xk&{L$TLQSqL}KoqV@6p{2;q#8E1uMt-u zKwGbnp^uVrk2}#y?Q0ZBVHyKbIL0Ur%ZuTPyg=o|k~6;Ye++~mDf zK{4ue2T4{G^K(#*Zq93aP=e z&el=3egTvD%3?vpKE5;Q!DNoVMDIS!N-57d-=*Ws`og7SV@dh6Y(r*E;>a!|JIEU? zZ`Cy2diFWm&nc-9(PRL|&$I%cx106OBVxYKa%_U8Gm> zTJm7y@%+n`269ViE4iatJjHeY&89inyp(FQ{-BZTdsX4@+gd)XJygCn#_*CA>&bih zM#`KY#%XNIT~n;2vVZ;2NGxAQY;_Nm%x#wJ7dx7}`?OB6dHs)Py& zyl?DSTTv?m8CV|0_u1^ED%Gg3iZykU$y>bT=bz{0;C(guboU?`TKJgkyUdfjN^d#) z%~=^a-G$of+A&upj#$;EJ^5|OSobniJ}q}x*1gL#Hu=O&D5v@s3{(^?UE*(5-V`P` z=G`aDW-857@A=5T-<^=1&zL#Ai$=MsnC4bhZ18xAC}d*|Nk2H=NzHE-s66i#H1@Bq zB@f&@DD!8^r2X#4Ax-3w?=~6eWO{&#a97pvzMq;>>4iiI)&$F@h@{giD@%EQ)%sN_ z!*@(ed1>)#nb1kHu{{Iji}@+kb~70M68RKNDXaFMsIAPr;fTT->Wr{|oYnYY0jl(= zLdJmPhVn*oJ$omHAHo2K1^nMA15!=Agd~i z8I9{xRu6Ty_Bx3YWMFxem+X536}r2$a{Ag(D+AehmY|ioX%jVmWijO(yw--bLX^Jl zme?1k;zy3K?b%w5<9P>nYKH+SveB~IHVQgJ-{IOZPED~Dll0EOYu24DtClDwXBC*s zb{1S9H|{!ZQw@f*9VHga;t3CJAFBRIjBd5#)I<0D{`Us?YK%tjXUeL6#pL7Q6pc+U zMI}cnit;au&a7a2)jCn0v4qQf3m>z{lau8=w=S|w{>SWmK%z{!(M?`hW5(ogzcE-% zp4!=vF?I$&GfQUbG+bueT9v<@J4be&(N#XWSD6=>K25ev94M0}6(L4i|7bPi@K}Sg zpGfl1k+BWx%i@##H3t3?>2W@cP?VEQPB=BjI(y^>X^fj>o3}5RXZv%5toLq|?YvVM zMeW`wDZ6~yY3F8CMj-F5UM#Uv+_R5Xlpv#e$xU=>%DU5|S94W_p@!7A9Vs7n4Z zMWO^5IL0VnQIUqqytQ0zVQ36QJ=ic%Qf6TJcHU?zbhf96;l6|#z2%l&y(7_sano{s_fJc5+%sM`A?C*S~gb`Yv)(PCr*~FYYmc}+isCd zvbyo+oyN#hc~(jLmG1mywqf!?n-#Kv#q`3S(YC3gnEk5J-)l4mq8HcHp z$MH>Urt;@4q$ppCLdrA{uP>;`ONod=DQO=)dEQ#43J{k^=eynJ$#ywkEJ zF$#D$QR5yuC^L5rG7yzz>NvU4eUbdxx-~J1_ zjB-fp?y}6)u6$_UM7b>>PHr3CofxZIwpD+5-!K+EnXE~W;dX6;ObVMJi+FZ083)^` z;}7o|dG1AVlprH&&{P?2KS|D=+J+cqzqVF!YrYzE!qgau(!Zn2g*NJxuSJDSDauiT zj92U8WuVVODQkvM8MnSSQS_eA*ZSV%r*ISSBUHUQeo&U(mS1BaYMxA#`+ZK^u5}qjW%zz>uB-!x8D(qRiL(XA z$>X)ENsq##c>7%mazd8e(s#lrejt9P^h~QLzf_GT#FzPpIKS-+M+Txg4ILwQ zOl%=X_8dlx9e%Bp-P{F+Z1$L=1Q~gJC(FdQO=RxJW*M7yHdg^fHW|w={-ZGv#a>O2 z_J=yl7w#q__)H76{_JIAMq7i2x{r}>mW-9o-THGx9XT{XeiQMs@Y5c|$Y+G8u%*w8 zTsO983`9MB94m7aohdCd`Vhl?Yq0t_Ad@#woM`ddqMPQm*k=jEF51 z#T*!jS~#$uJhXk9Oqb>yJa1{LHcY;0l#e~fQGyH{J!DD#y0K~<@y1y8;h@Gq6pjVj zomV$d?RMo-eNQgnt6h4@udkL%=bJsW5rboaqTDpEuU=FyrZVSfto1qerrsa6{`J(f zM^0+k+s%wJ&dALVcSz>~jX9$9-GF6lq#CJG>eTVl8UsOZU39RCFJAwJRW##z0g;*FR;>&O7D$Kl4(p)}HcFPj-2z+G8F_ zlpsUDd4=}zRfBGLs#0T^b|1t$;GFFp<lMx zrXImpPnj zb-Phn)nv3#LsoE(l4YTOlH#|^ze3vcmdC>6u8vB!bqXa$`+08aZl+pvZm?(!L}6`B z9epkJ@U4e(-*M84Ux+Ad5%Nl@@1c6Rdh@dv90k6;;F}DtT{O?za&>jYVX0PB(in)s zm5=TpNp)1tgk3zp%I%ai^f0{uE!Qj{HZ!>)UA_78*3(wfv7V-dr6n}6J@!SAylg} z{`FLgIrj~R#HSo3$iNkx?gmZktALSNRMd-I+DeV9Gp@&^|7cf-PWcWhIcgfed^SQ( zc(_Sk8rDTywe^*{%p0!CbSh2rBU)o1>TGIk|XS`i{}_YO8sf%Fqq3Ax8-^ zaMh->Ph+9TTULE}luu(I3fFwHbjn&!z1dKX?zTnQ5wGs@aEU!~$=LwY((TvIfU7oH zE;nkR@_9O`;t#Xhkbx+?Us){U!)vO-7vIXD5!JN!M4VkX@+qo{yN|l$THf%Aan~4# z!g)ilgByI+)f#6FGtUpc0^+DlAOEM^Rw+?dj~Py_n_~)7`JY@hcpiI!5@g`$p&V}R zR@HjV2V>jQcN`gricg4;nbHKGerM2wWezi9Bs95EJ)U1qMny{@b%UKqpG8BsWTD64M0I?Aqb1x1mEwLJ<^`nU=@ zR#Z)EQG<`X;-S5st=GyByGVsOQVyRoEvMLi9U=(}cEARyy zQTj;CRoYE$3F&2oY^|;_5T&owW2KwQHZIvn$yQ0=i#eijRMNQm%T>*;zsGp(@2oKp zg|mR{+mBaKq4i%G7lR9Gujh!uF-`BHE6OO3-8od|zw>GgL|sn`kWaTI%Mu05yV~Ij zZmQ_C?8<#QWe5TZGH@1{XX?_bo~5{IQt$^y2BOwZJtNm&rmEcge?H%^5W-z+F+?8dd7$W{whM=<{RK z9w%j=T%Bg_8jXRd{TuwH|IvLiy+BtgqvaxZwd0+;YM6BbM+q`;c2PWlBNRPwjh}j! zZH&%f|AbN|mZ@b%NoSU6l2 zn($I)FFVwVFaM}Rs9a~AJlO4-tz%jcm2vZ9h}zQPIzPWNp7GcXrd7p`{p2}>x&r(q zb9atY`(EWXV)I^LWE&@4Dy*^9tn`Pbn;1HEjr4T;Y3sPW6_v5A+AuZxZZRWjSqp{| z{9V0P?e-2)5s57g=NZl#15p=4lI8hKHRM7+Q~$AJ)eyD2dxTMGSq>XYkinm)$j+xq z$xTD*5o6`N!RmR-2}Z-L6*LB-^l_C!jBl&P8ut0RN|Yc2^*dylxv;59YjT4ZvO4m8 zZP&{kKZ@)cl(QqpmM#^uPEH-%*4BT0B-Lu6dslV*u{+;a_%lNZGO*p~B=ap!O^-V* zDaSfT2BNT^=(H3(h^&@p8ih{J(Y^!gu8-Zr4TsP>!wX3<-1)ATtK^!$w%9gBbk@q# z%Xrc+MzyeaCfo3O8Us=L*Q}Iv?6b*tC(SP}uVU5VTQv=O#o;JH296$jr%sJl?|1e# zwnP`v7>FA8VX5?c!sLdY=6kzrK3E+aJi=(!#b78w296$@QR@e&-CyP#omX$w7>HUO zy-=q9-AP`JGT+-<*bgKh%f-gwZ&?^hkb$FzG;vM(s%xXS87uD^R%9RwS0#F_9W^-P z^*nH0oYn`}H$OM0$oIG1ZI+U~s8(Wm2hz&aplEE78Us-{LP=wCsiE5N^%lR~sJ}LL zk@2ZbN`?-B^4CxqW$OyH=jttr#kx+@E+7hZ2y~;*)JB`D3@HuR#WC=xCIb?XDbm%`g() zFVu8*$QX2XfgH2mDwjodp<3B5>#Rb$ry3i|&CwW$LaiKmVV~$mmS>xdg~MYtoggx> z|1B1e+nrUr9|w(_rF&`&MB#X&C7smP`KNw1I zT;a)pEI9%r)!(n)7)wU2(#{OX!0|?zVq14pYyP-qP+Vk*=MNlxc*3F8Cn8S0TIncX z`+IS;zd*YTwCW&z)TN;+PcskOxgLR<-77M5+mH0pBNb&vl!xlww4z-`^_VHrTC~2j zOu3-hXpm)Q`4Q@3rCrjrltt?eWYiclMULmKP3tQ2y*<|mbuQgQp1rV!p#&L?8cmb# zTdK>w$%+{H4-Hf2EO%`Cj=s|vh(cQvdf)9nOtqWYPdYdLrZd1I1#Md>2E^$&Ww}|{ z`0*u~p(OLXnR3!}KiOjIBJGz*yR;`xk;jNZR!IK%9fAK$lFQ%rr9J+()*|M*J48_= zL359i*jC6GQ(~elT420<)z?BZD$;F;a?H}o_^{^>je#ir++O?5K=on3Ok@2zI^UF; zM0bO!(kV|-?QVc6%6Ud{UpG%_UjZSYzlu7;6-=&eJ5wK$}at*B%_Ayz(|QR`!#c#V?|e zO>=NkEZwxb8urOEwVGfJu{Y@^e73*ZRDPv#d@$E)h4#Y8Hlr_c~2A7 z<$V!lZF*j_VL=934$<4|q57)#-{d=y{!wEf3UA0{e^rdBFZn8~Co{8X+CF5Ug)A~CC#w}D$OsNflxzGt%OBfKo1)!i2de#V z7Z{Yu)uu53^(cfaYr^BDOO6M`==~^8{p@v7KAezS+dt3(A9o_MRm&Qu?z!hT!gBr8 zYy^>^&)Qtmwf8^@$oZ7C2C|r-}WJ$YPgG$cEwUfuSl^PlNeY8gf$Efo+2N*?f z4YT4(jVS%g!wwBrEBg&M-d(F~Lk6O7)uwTkXONQ3=a81HkwghH^mW(zAWAK-x6=sh zlq6Atj5Bw~$-z_R$j1duEpphRDAm5{P9uEyMvZ|eT=OlKd5yZMb6qbRORcHeZh#Ct zeNaS)s2*zhv{S}dwc&8={i0^$=`X$;2JB-yBh{Ch4#WLtdKP8^U8zu8M zAJb~tAYWnaeufOZA)6VFdaAlz_Zv4$ zd}sJuh{Ch48J)7HdiV8+F|@!ah7x4pEsSETFYc*aJDxNuR=uH(D@5rd(d>`s`{o;W zD{j|b2k})!Kgk@m>#ywYtT5sVZ`2rw(r1+K#$jqtuN+2}sx`F}88YzXM5plSo~rWe zo4jVq1I;oIEdkN~jxu3xYNP6v{~(itG6}SYLKNOb$=|s_E9DYg*+`GiqA?JKHUSjB zq+SHs$@m*%2fx>B`80-hOYO)0Q0bF88rv4X(inJS)$g3WqT8yGJr@}t%AetAnTII- z&e{1*Yo(rSHq7{g$Uqd@Vo_B2m95pIQb!HCgJ`yV$Utj4vQOL?p<KZebIrp7=NTGNpphkVJ3HO;O5D)5S-)f}!-`Wy23-l1wxqk?3IT#2F0 z6{2vpqgAv>OXagZubSODI1L$y!WVDz#jCw)R{En6+;O@@39i(*Gf-6b%xzV46ANh@ zR%r}Gp-nQqWz_GiHe9=F+zePPQGyKI;b`6M)JdtZzs=Uw7>L3%D(P4z_EJt84jJ<@ z3GFP3jQ=_Nbnm5B=R9I8E_~63zlA6~IgwRycw?hiC10`UwyzxAVjW98yn3fY>CU{u z+W+?+_gxvv#}qfn(~zQ4y*6!~zx(y$6!Sw|T<{MYwO|3ApUAqr;t*cDN=nAxvu^kP zA4aw2V|crMUgC3fB*WiA29`~yjN?NL%gq|Xyxke&)|q;PnmOJ5dB+JyY-V|jZ4LR6 zX35h0`|CCjs@3qGR%^X-KH_k<)<(ZG2^p~xdM)nGU%bAW@pn|~B;Mpfs-MaD^4_$- z?)Pq+JbAFX7@0_Q&owdQcg2R89N7m}e$M!Rzq8Yck-vF6wycAXcs;(6ff8ig-c~h( zv22y88NEHHCXEmu@w4<5f0YEKSKn#}9Z8l2J6BWjvnba4?y_$bQH*?m?7j}&z?7_+Z+;T8J1W}xy`o2s!b zmQrJ+ZOuq8@$!!`+Sg($V7pPDm*`-eZ{ST|p2NU)$Np&iifqEEpKc~pq*_hS-Gm=o zSWC2dJDH&b8Lz!IX0%oO&Dz9pebrTgV4XCX? zxi;p9y7`LgOD9;7fvBvu|Bn(=car&rOfgFsMT`*L(*q2w71l%_yYDuK7+zjpV*gt| zjuK>`rzX9AOlW6hd+jY&W_c>HZ{43J$)w_c?3xtg#BnUpyU!42^ljrW-n`FgG&}kK zv0c2gGVa_s&ivY4lcNgq;AIKsxZ3r8jU#=>t9G9J_D?@CphO;y3`Aks6h}CS8|jyP z1!>6)lpq6ZXtDe(o6aha_M=?x^$hPP-WfBhKtErOISw(WBF*zgTjb|uK7w)z8T(6I z$cU&=+_O9Xe(!q*JNxG8+T65QGLtvTz4>0E#;aIOf()F&7K?Y$nQYMtFEKA^IL9(X zzu6gOgiV~Om1kNmmo_6niHeIOG@shnURBN3_4dm$RqI)LLoRw!=3nF`a&3*(B*?&( zk8~5YBaO*3s*AZl^YhPZ*JX_Md&}Bs8XB}VrE~l3-8OSgeC!lvVBPVX^p(0n-yqhh zrk6-BF`6R-QO);E%xLxas3aOCVP1~>+6!;-rBwj~YlStzSzxi$jx5j9&-;nqxhoo& zH4<}9p7a=-(b6q8nHrPxJu>s-IsFCmsAHf688~7rmIkvv%IN<7f;?t9G7yF1jdC^e z(fnlf8sfx~xol8{4H@fT+`hKj?yT>eANr27bxH6N&9;uw_C9PMY&TPXUea)k@)y-& z+zp&}IJ>$`?wm0nZ)7&}bC!R4H?2@nCY}%O#Per4meKBG26}VMgxY=M#l7Zk*KBJ| zV)%+)@@A@^aJ%#e$1lWLgug^y5cA%!)erq>T!k1YK?dedB|EZvQKb8*F39SIp@t9d zA7LIUV}xd#ZJuO&tc>q2;Uf|o*d$7jfuo1!$BFvfoaeV)CP-XgQGbrVL_254iN?G> z)&GyJvyQ83iTeJr1F;pXD|R9%NXVHP6j2mW5evme#SRQmu@DpN?!p3$YoVOkV|RBe zcDL8ocWv&y&;8Bwy#JlgXRYs`80tUE2PH`8C!@y?jyJv>t|hvR31vv2 z7QUawGCp!5`7*ePE^RE@Q{ilY9v7xf|Aq7`Nf}8(ni<%(*yeRp>q#?sjuIqpR}9Oj-7ovSiLl&k$#YeK*I1gI26v ze0Hoi$~jrG0jsb;2*1*yhW=l4Ym6cYJY4mL={<4mjGk%RYH+diP-jDz{6|=({YW#T z7wl>EmcFW@}Am`WIS!ur2uM=i?(juudaufyeXT31Zutfyf&lk@)v6o@o7N^$?h{T zV{w>XS5QB59TwTlJwwpd4^&rg#+P7y26JH@)|+GPqSmM}Su%P_Sw~MQWBcI%zH^%*TFJUag>cQ>+(0dSbDePh8b_HI z-Nch$S8dn^{yjEljPt3YA%9hWquCz2YDRg{d$`UY#XASPi$hLZB@(Emw_x?D6L?#1 zcd;h^juq#RE5A0=|7PE{s%MBcmryp^?QuNH&Ru+*l}X|r5D9!jng{1LHUb`ciKjcp zS&=|3d|I+hoQo298ig3Ps!|qvIGsgAMasf|7UCn4rn4D?;^f4QrFg{lsmwPbM!Nhk z&j-D>jS%^(PDrZ|;?FydUB;$7PqA&e(1GPonaB1m$SjZMo5$8&T+C8jf7%j8525;V zxK&d8{!zdvEGU=B`aqV-lWlp6OylMLYQ!#G%prX|rt(X>y0GDCcWjINCsP^Irk5A3 zp4C<58lINXWdm5x>Wk&*mVT_?@5an!${cxd@{8ULvtf-7~bIS-hyso-= zzJiflygob9Vy*nRJ|QF9P(a@WGH2!qte~3@D_B^`n-1n!LN@`$?>~Li-18+2=LJEm zh}RxzY5P;tGIJIEOPhCiE7SL9r8_y}2+f&clzgVq0eMiyG`#IbD3 z9ueh4c?asN_FtYzlpulS(P_q((!%sI{mV94q864nT)MNYo)=`LUZ#KIN&70IZ-`Lc z&)Ug3{R3H2*fHt7%$+Y=;=zU&xgZy=^WsR;Y;d8p=y0on@}5yjdk-Y^GWLzFCI*#Y z>edYx8){*BQ#!O~-7fEwe|$G*wGFjPiHn0z8z-Zyi>YnvGt1@)GE=Pyy#9t3tm4lY z>0T|C?;F{Wd4z?_yyGVl@uX)d%F+~OyyJC+bNS9}R(Mg#0w!raab{Wo+uz1r`W-fV zB3ZjcxK~Y1F&f3-Dc#sgFN>{dy(!u*9{V(n)Qxiq-?ewS_pd($?o5%!JucZ^Ka>-} zzZ>v`^zs5FNZdF+mW^-qDed_5IC`oAiKPVHKj#O-b87@@>3ip+fu7=7rUtyWcRt$T z{kMxpV(iBR)@|{#w6H6#UGtptr4h& zwk$f$_}yNZH`YH)pQG8ukO&*LfyE8?wpqMPOVRd_Mk1j3ExsloTq96RU+L35VT#gx zhYxR&hvV3eS~s$!Fj_m`Jg6UAhyxnnWA z__>`-w{z2IizRsGP*Hxt7{jjrFO8rvm-$WaCkObK)oAj@Jvl_!?oBk*v$qoG3?#5@ z@|wIioN@xRF=p2MtPwc-AWf&pCEAEvf8$)y>k?S*UO{r_ zy~EbY_Vd}Q@LJO6-d-1ZjdO1h{L zk!>W-ETaeYV!c;Qkc*ZbwibFnj?MViM_NA}qcW@u8wxW9mN`fDOP;`PEgLGQhYn+* zhX%5*`=(2~?K9cydC|;a={R|`TLUU1@xE11jzdL0MG_@Q=rhiOKIO%=BEG7oQN%zA z&Tu$C(lq!~5m*W!5D|K4V{;r>K+qr@nAZR`ftv)TZ5dQOteQqPWh zVoK?@VtCH%s^pQ~5+z7{{56K1 zI2-6Qj=6GOS=>e4TRKZ4Q0q>nj;v9`J+k)!Gg?o`AP*6Az9!w)+bvOo1kR}Bi{oBL z#N~HZ*;YQ(2-F(!yAx}ix>Y`iH`lw{pVSuq*Id=fT3HR0Afc}rs$Z%jHh5K2ckkJ0 z1ZqvS^kfIVt&nF*9HsW4*rnpl>lzew(cVA_64-la^yy(0pO;lpcQWVF2-Lz}NmezA z*%oRotA-9*BC(~gZLs%Hn{TZvf@fAxbIzn_ZH@%ix*18Qo~Zk-oZ8YbT_aEn>(F9h z(E(!Itr99?)+>!bE&K}TG`xYos1jCMeJpD+P=W;3A=xY`zTK`5rBt-rPwk6BExoSR zx2!Ifov2Qp1G9PQ*j8-)h(F~?)q_X)GPbX7ntav04>xYNU=_CSl~c}kpk8wJf)}lp zDw1DOFO5L0wHrIK_g!|$NzK|3kvy4+A0H~IodxZ=Q@8%iAz-VtY;MU>D`ZQ1=DyO9 zJ#IE4;$AZ*+(uMWU-I~{S@j37!&!IA@W=HyYU%5%x9_Tpd?HeW~DVxaYZA(Mqt}uc{Ebz2oN`?mQq2Ed)c;TW10B5Ue+7YSgUEQ zLyP6(bU)#?y1a7O9c&#PAI%MM3(XC^uPL5)2>dUm7P%2EG;z&66J1sGw1dv z|=}bvh!2(bjjg*4Y8nsw@O@6Un5WpYk_uNrOS(EzJ980;VD*>Ac1=ZvP=~76c1u* zsWkx)Z8+i}jdO{ao1=zkyP-CDR2Aj;=J-zdb&;>yLuWCzoV(h#xUNQ^7Jk8WuEv~1 zh31~>vzo89AZp<#@%KK;-J^`^yzi0r-C=LXuZvDILVPJBVi9$(#S-m{LM^?wH>uN5 zgk5)3exHT*t)UiClWxVc+jjA? z`-XP>TFfN&(QTge*kaCuYxjl-<8kJUnG>HKwX&_A#MaM=m-cSqMBGbjE-tG~%5Pe{ zRwt-6(K41jpFK-vO)_u3gue?APM^OS(FOK#d|T9-Jv55ltu;w5X=C25dE@0TF4g#8 z1h&4W5vcX)Y9H1v|5WMN(cB3qPxBG^^FA;-4$LC3eo*UZqb@9^S+u;|!K^FFUm_aL zy+Uzo^JxTXp(TX&YGEN_QPrHPVHPi~cCoIo4(Se7=Eh=9k?hLdW0h7{_~uw6v~E8s zMCna`88g>B*4`Z71K*EsrFc{o)qP(ZPP~x7-hf*Ad(7!nQWR_Y(s=c>tVW;~+JneD zp<_oeyy^$T>q}V__bQI{gIbyQOknlO$I3AU&DByd86@bgr7`rLO(ReXdkme#4XZD1-@a|U?eLak zjiT0brvZ$zOvvw#M^hPZJ9E*e+7%;DYF2>+YGIEd>v?!pQQ7m5(XVD%fi;R+x>ar8 z(Ma*V&P?O*jBOHa#b^&`K4ls+qbb+y^anlF$in?a%Jv-@H%3r`#Dldn*(+OutPpCR zP5d|$CVtehsB9lBYXp|3m(i_uH*xUOQ^P&6t45#}mPaF8_in;H<{5c;|FEG1i5wjhSo`{O zrClY{W*M5)P0ZVJ$0)ox2glyG?86+EIqx_*SGM|JJ&~eQ3ZK9SM*gJ%Y+e^{prNy)=yWUns*I^f=Ty7~Y$GtJ^`=tumg7_0g5Yv4tZIGc)^B z=Z>t_46A&Q9>>uRtJ_{5z3(J$`W`hRBW7`YcKbuK*;W=QCqC`W53HNc)`xbMZMOEK zGU(2dNZoSKF!RwPfm--Z6gAsnkQl@^8Tp5_OZ#|dAz6Nh&?x}pZ6jB*CZ3JtwfBwr z%ccuh)aw}e&@gY4lb^mAvu%Pwo=y_A&<=<8If|dSKa#8;^Na~k*GMb_?P5riPhIQ~ zK|cD1-PLj$fm&EL-Ehk}P*CPjt1r0Lgp=*uus_}m18Ea+C0Afb;8KD&ERM)s-3+Q=ln zYUNy3)w_~xuzj#r3!^hFV=o4kmODzD_L9T?eaIg*fg%qlaFk%Z;rp4fqX!6&b5jie z#+@|+webC@j7)>Xi(#>59uti~ttw^Lu#VjvmMUJkN znQNV~q0J_(?_vw$*JYl0brD6j%`@`tH#ka=z}{oAY-`?Lyj(KfxZVGjMxYjckEUI; zwm6o98S%TE1)jy@>|A(642vyPK=z4^rS_N{S4a4zR58+9RnZ94YBFF9J9qht&3Ezy zB0S$W5Z{ma8WohIKnW5{W=vzXN7>2a$>!?Seozz9Jfb?S^b2YPYNe;fGxxYNwr5?& z65%whjd<$sYn1M65hy|8P3!q=?2>Hq$U1Yc_AD?=bQ@L8IQ#hnM*_71Qx-7a{fBLV z$IMt^S!#3__x4+jFS$;0lpt~a^>WtW)i2xrVrIOI`lWjb$`)d@?Wi;YwUP&{WNl~L zY_sc{u`Jf_8z7pTtZf_(T)|n7HQpU{U0XlkwR$StC&E@so9| zUasx73nAuCxRlp$VLzz4v8|dfM+p)(-;L~M(MLApa~mQY2S$s9X+@3h#mZ^~YPHFk z#6H*AXlv_at^kJo9x1-L7dBjOuVpAfB4_(#M)?hFhl@8QqVVRP;_Gw9b50t>F3;Xf z9uO662ktiGcp8eQq?EO%OgB;Th$m$fyh`2US9?g`_@f;Y>oxK+= zWQUK(*h<$h_vZsb+lx`#pV&92XGQCwUjXkF6BBF? z^P4;RHBNz|SdIzOu1s-(5+v}vp7LN(cHo~SR>^xy%V-2@wTc+a9J)-k?X78g4w!c) z=4>1Ql2C4TJvB-W&-WG0Z4}f#Tkx2lCZH2aP~2Y+3TM_^Y)@NY847 zeb1(~AQCvnSS&eCwiowuK9Xi^L;Nq)!X8Syi2~iJUu888^}NPWf&`8+xd^eJwLUln?4-!oDqMpiQd*W9uqfm+xrEf)6z6~+4HwT%3StlAn5Ju`6yNFG~5 zJ%y!gj4{TkqSklOqJzDX?CmXl#Hm8_48LNf1WJ(5Eky^5*Qb2+%Z-z5@@WKW;m(qF zsoVTTk$O7}F)F*Z=R^W6Q)XO)AYnH%&4_Z<_qC{nduqBfdbYLru=Sjg{%ohVcSd^| z+MFmdMS3R@>3hwX^sb+_qem^Y;*q_iayJo>4QPbJMc+oUBi@iOQ4XofJ8<*e4Ruzb6{x03*$(1+QO}A<6K<~cN z?dJvZtO;m7N)+vFZ|rv5D4QRMXB8v+%98W5bM#e1i#Od}S|1~x&bT6J1*;LLl~5s` zeY+ec->!Z`WgL$lCFWhYQz!e|q8xpwzq-t1iD}j3w@Rtn(^@RA@{bb3jndNpX9Wj!>#dIr{bJrDK2~LfaQax?uxoTtBT(yX&=Pk4 z4?FohTPGqMn^qTlZq!jve_hplw$YnzzeiW*Rx}~Q>zKTEa(Ih1{ajT1fO!%nNa#Ly z)9Q24VQ&?+J!FwapcZ=8QIvxE0V3V?57qo?Kh5V33G^v6&men=e9jllm^Id?au$2L z)?ZFuI+~%s;Qgd!Y~$oY^1z)#^hU!vTLyD zGkCeNGRc`?8K`w3K9N-_c*=I{ta)?9r`!k;8t!9+IqhdC*->%>d-Q&V?OlM)y4Gtw ziw>P*OI-1mh)x3|MUdm-jNXoAv>Q90t=;b|@456~*qU^@)N;7k9~*5<-V~=vkkH%w zUAO9DX1+S=_n+UjHpkXPpE9!V&hrxe4%eW_D&*q@-t|c6EjTVPNUW*opoY#_sI?%r z8v0*S?z4AoM7R7o6**yRo|#BsYnt&(Itb@7zm3lODrf|1-AhYgTc5U;Md}Qo-kwsn zhw1Ta90;#!LkSXC>tt2?HJI$wOUW);iD8YR7Pc%|itY~+rQVG;vKO4I5vZlN$D<9= zqEViDMnKRRh7u(7UgB4Bq=?;@+sG7@l_P;#`dFg!juKBcC(0|&9XU#nX!vwJ`&`P; z)~wBE>WP%yk-U(8+xjf_)CknVnoSQpj>o5)f}d>U#|ws*H4w!kM*&A=CTpubZ2j){^fewsE^+Sj*n!At3O(# zr6$Ov3$faWd?+e`1vpZq!ZsJQxx_r17%2*PSj{+hHk@T}Hqf7H&yV3^)s-P+Z+DR> zL1N*p$*gd$iLzCMc^}8S_h6x7mKmL@1Zo6o6|5P@d?!wq?}d3kD$HpR-I`oycz!CZ z5vYZANSVw!4JIq+O5qp_uPgAYUy>=@Pi=lpuj)44u(; z2@^RTEou;(Dp7(2dbiT;<;iWtpAU1Wv6&WV1ZwG{s9f4aB-|;g&egxBjfqI;eyNmkt@hH z{h3vVipwNQkkIRDZD0%0UgTGy=ca1}YUy5jUZt7}kM~7Y@?>YthaL&tqcNp^h&cZ< zpYrY8UGot}0$Y=I^s8HnSeZv{d$>UJvqUZIF&4|bgkUlAd0urtZzhgDo2Z38o@OMr z#v;3CK8htArFk2o?-=@WQwwIQE2?+TrOGc*nztePj-iJjohV)@EhfFrr)H=e0{zWV z3%$i?&za3xxK{E}FLTe-Zt&opQM}DV5%?bmQBQPGE4+W%a6f?eig3+H>yqGb;nL)> zVP7??6<2zAuLxKDG#m69AZ$an8+7lE;p!f>Myy}W4t4%zdlJ%+R!flyqr}m@snV}U zCXVYJTwndFmc$N41=(C1&LASF$S5&kxxMkO+bM<;BygWV8NdQ#=w`p4lsPS08Axx8 zNM;XQv>V4GGl3 zTA=yd$w^omXIGClJTtI#>@ip)bpAn6rry-PYFv(bW?=oGmh1I}tj@{m|MaV{a?QlS zqzguqah)^*weSn3@#;DgkHWVY6j#Fso6LF^9}y!RD!ozolBLO=Ae*3tuw!qtXCfX zOPoC7%FSCsuU}X+0=53E?&wo{%-_-2$jf5MA(k^akJ`1-L7@bR^(nKg7b27Xc`DC~ z3t0Fmd$qfSPM}ul)xp*eJ}Ljq29zPz_>!lDcoOcS9xbjXH>J*ElpV-3d)~@&_U1(y zzbCehu{l*)oza@KD@xvKymTocT0W?)P=dtyxut9as>y$d@D59jTz^&;)?gQf5+o+< z%_&paDrU9~`7?~0U{uQEETRjzY6NO|EkA4P7_gpE^d9=ozqw~s<#xU10ogrN_W>Ji zkDVeiN{`zyQKn|?oYDL6X=&|K-(6kK^;DL8q4z}W?bs_Vmg{FKsa=j!D4MRj_I=d$ zUn#er%bU>#_;pdXP2Wa5r{g&zOY;`$WApabQl(QedR*z)A}q1UiVOmK55>m}ZO)zh zWK*qL==}>HOLF*te+qd7}=i z5jrp9NwO@g#d0rOkkK>nX(@kHu%kLv=rW&R@1n+4SRieuTr+AEYZq(XV(EQn79Udn z?=tYeu#6skD>F7`aYotXC(~yNue<3xMUO11)fH+D=vkUMZ&~^ealh3RPPX0uL!cJc z8(CNmxYAlQhz%+4sr*`PGK zZ%^5m#b(sP|LRwl?;8P&3ySvJT(s{43H;Kix34Lqy47A|6o}FLm2<`U^4f>m8E=by z%wn1PEr)V@Ot(@}+|{+%DKace`wXo&hZorH-I$Uwo)`UVh&=ax)IW7~boXfcD%RFI^oyt_%TO&{lTbBIc(#G@h1CAKk4mZSIOpE9s))9b}UJvh;T8UsgL5#=imAnv+cTTd$ELSA64?HxC*TibxbfR)|Gl=tw#D*V z?CcWE4J^Rqg5Htx$r*nljyNi_0Ztj7oHW@ZAL?COp4t^u$9WP^MN@xPG9By%#fyF};5nPiMO;Tt{Qy#Xe2DR6h?faNQR9QDCc)M*^c8BkyY~%7V#C zj;g8kUF@&;6___!ohcLTAAHqC4~;-A{rmV{XRGl!-A#>pZ&9g_^V+(&?aSyt#rKtv z$+MPav^n+#Gd9&^W9xu#M#&=%S}#H3+^Y)mcDW@Pw8b)e-CW~vzmLX&i8_H=Ijyd; zd+@@4dgA3}bB*$Y|1W`B*el7lXU%gwM@xKr56_g8-{+_8V zmbM)`8Q#~ks4cT}0=4j+Xn+1`u0bb$Dod`Z2G&*kT(@m2r>gO2#qxdJLRS04 z-)lHrt95Yu>N9cJ=8XEm)gYa|&JJX&;`1uGUtjeh;c)efPoCj_({vZPO=EU$`u`!vMB-t`i-ucXFGUf8tqU@@$Y^uirRv|{_5-;^^wDQVu^jH&{DB01 z&8BB&K@s@;A*UQt+Q@J_dOVvsxfe4>2K*i=zw_GChI>q|jI~dW`D<)ldv3~j-WQQO zZO_90UU_4!(=CX4&c@n#In}bfdJ7_fZDX+uE5+tle+oz2wdNQL9$-;7IrTkPOuc~;Us79ccd$snq4ZoBBX^#!7{w69Bff6Jp zP4u^o7@YDC(P3bu?4FWWZFo^sp#+KaDi71b=4{UBm1br+cQI~W7Vg)hrnbAYMQ>u| z!&hdEQTl4h^v0$9JG{{{SB=1t6KOgznK<6+e>1PTe#SxRJ&xAGdH?QxdT&4fZQTD5 zy5v71D6o3k1p9yc?$$d#Hn$azjZz(2X!|JC!df6-oFD(y6-toM>uPv5FY#jUZJ!5u zYbvZ0+>`4wPSlFGyh&JAK{0sLu4+T9%L*iB)aZ}FJ=jIt-z!U;A1Rha^X#HiR*M)J z>!N)hNZ_|(Ms7LA=lPWomzuk(+UF~=ReKjPTGx6^dFjWt=b4r9MPb<%%bm;{d9+(8 zku9HxMxd4vkM$B5X&KR1i zzc~_E3zRwQi>L6PUR-wbs;RIq;i^V|^Dw7z+|%kT;zqeDY=edm&RL&TUQg|x-9v8= zij6Bvy>=A?J9%oW3|v`+w0~a5_441D9>`LZSi)xBlpR{tO`!w{bF{WEwk4yF(QWdk z)mfiv9^!|iPN3FFmn_!dz5iXwOmL|#C}W`!Q_oGSU2HY1H}i&DQBJEFF*cK@_Eg!@ zr&`l@CXuC}kq6d@d3Pz8m+tH;#`xFN>Iw<0H}V!aV=&sShM=UlIp6|W}fOdP=(E?C(&Am<<-mn-a7h6 zq8#Hokjl7L@I8C6H%6U4)kNa6<60}&t-LkPZ;KojY`(|cdr8LKw1Jc#kV{;vomIDO zzhc&9%&#@yyt9RVO_b$F4IsjrBNweI+o<-%yGxPOL?-r{DL7PitI7<_8i;iKo@&x*L8?sN zu%E^g=Y)c!9i%8LyH*C$_=I$q?07cS=4eY5a?jJ4HKro<#*^}HdUn2ly|+AY^PtS1 zIWyPGSUDv>WxNeiE{(hllpulS(OR^2UKJDGT#@gqk$lfnKKyV(hMy^^X_EtalF zGO3^E+fmG#HF8a8FQ9X{swAQ&+S(HUn~!w zkYX->{YCi=LsfwS1vvf}mhq@w1^Is01$p_Ud8ayJ`fth@+FHfE2pdxGK$6!NM!}$o-XM5$j<&&7&vZpW-8Zj_#8`3-r*Q)?(?kE2k>7 zAy8GQ7OzQ=(95{g{H?KUYy&l!U*N}wSCM(P?UkDg4B`t0Fj=V5Zuzvw0Ih8EPIY$W zecey}?7mx*Ac5ssEE~sUQOPM@s@jC7S{WOsaCs*sS>~uXTr1CFiJz5Ob&so{j%Cd! zuFvt6&$q9UB?^q8OlnXGd$p))Wl=s?J!wXoiQ77!qZZN@ z%l(+l>QTM-M$WDtB6k5-nLJ~XY~UNmOIGri_wtRAxj#+d_)j!{{V* z{*!CUkZpsce}hT<>y?IbTX1W+vzeIHc{=fm%po*<>|n_l4r4>@t?M z4-^|(xJj4E0dimT6zzZUpJ;?j$))bjpJyy+&`6Bl)L8npEF-sf&D7jL-BWof14{XeGBdwfpMqGpA0qxsBMf}O7|`=x)ijms6!%Xe)o3wL^D zi=I1`>qPJkJ2h>4GvlCWCQyO|J}pI7J(gXi4SFQY{A?{g5BHF6!4qsFiY4%h$w9K- zpJQzUeW!6On@$vSWK?)XAyPR+Z&IP z+6a^&p_gICZ-12ZSq@DL7AQeNzl*%Bxt;jBvZs-=L{ouU_=M=)YO&CHv*@%i-jL6l zn_n&a_p3!Mq-l@yA(x;VTSm6G4Kz<#q|u|*^iTZ8KUKC-{E|ijB}mZ7z#4A-dnBS0 z#oTXsFUuR_VJsJ45?t65&v@A^dIHDDXgZO&FuQm*?*e%)GjqK9pZ`Jv%cgrQ6|$12 zY$mlmpNkfOAIsCd^e(r4$v>9Oul)Nui^kE;?ER}{@?_p|9JP?9HFZiBvD4F0<$F*< zi}r>zdI(ZvysXdpzQl^E;0Z@@uxB+khP*(Fl^CJL&qUf{iL%QoO6;qqb|+`kybY1Y zh>|qpoPN%ouX-uBLz#s4t17JBp55}yz(_6bB+_I<&h&~8O{=TMMLyQFkmhqMv#*W! z$>Vj*s1f5Mvy1p$Om#bcRwGagV_Q-gyR!?29e&EGSSm*?j25dCF1M1-JvN6=c@-QMTMHtVPMYM8lrz(cTF_a(? zQ>HvyKliGfbC1z`jP99N>^mBw_LSLfMF~c?#eXvWMe~SD)mo`Os;mtO%&vhn`NN&a zBVJ@}sSbYHpymHSf_5zI-`x`B=iF#7>W*)rO09n?F_#Et57CLEce4oca8q`D@*7B? z7VW&)zxzasrFC9=;r+dNMg|v@V15+*CyS+BQX%nZViV=l&&f#0Q;U_XL@}w`_F)(i zA0y?Pp5(bHvQdcY8(26o0r^!8cJlOsA3+0shtE@=iKbe_ma*E^2+o&dC?h@@VXrIA%e$BV%>7oizRvsi!%e!GIHrscN3@cfL+GEX* z&%9Lrj_T8%8xkc*=(W4$=X35^yt68Os*r&MYPDZboCT{S8DFhGl~F9~Upz7)Oa;Al zGEjm9_87XUH}5_F=^Li9g<3TNwaCW7{#Cyk=I=IL;?t(}P;$f@ zi4r8R4k@ldo5S2~X@q+FuB3qkYDN2GW~;kwlcnYkq%!;)Uf@G3byw24nt>7|u-2)! zPddxjF9}ymjQSdZTED6kVPgs^c`C;tDx>hZhx|j`PKq*`87M(QZ;$Jf@=xIhcr=X9y4x&BBT#Eh&+pbniw{YE`y*7wxo`XVhi^U9%}LD+lpujEOW$Di zSNy7H2leTWzt-m1nmDhJjjT;pLAl~o=iFA)X374Yi;&RUoGkNn#`2f^P(McGa=+$t z;PYtPsY-KrXxwS9Mm5IRatF-e&vst-c~R=MZFNQSq~XDdBi0(f%NVVkM+uZ5VV=-T zZT;Go-oPXl8TDDU2@!_>tSF5@E%%^nK1W)Vms56T*LwK-1S4hZFriEEe<|bg z@ba?IC6hS6D+l`>k!VcWI_Uop|7vydYU8tAG?%e=ryj$DzsHuf>!BdsV4e-~l;%4h^?%`S7)XGfd6 zGV8IBUG7QjWq(b_6FL;*%IJJ{+TQQ4Myj~ll{rd~xF6=1mNn_Qj0`Y|0*QN+^&(%rItaOJ^`5ptNdflnX6I4%u_8lBca8xqKlB_&is7=o4G)l7+p;p<%P;2i=$`)7O9DR0- zJHs{>%5R+8I#Qqn2^`1Bv*zVj)@x4#GkTInpw|BWZLKSY+ROQ6XHgjm>4(@L-zdY3 zq>K_I^l|J#fj2C?=v>3~-e8SDt>U*@TXSZuBcJr2L1i@Dvx<#OOg4Td4-hCpLLcE$ zdfj1{R~|5`jO(ots8ui9BZ$5vcWk)I@7p$4N3ry{SZOX*`34CS_4WGq)2cL85izW;_q!RMXNBGeYXoY|IzP_(t=nQb>aFVxj8}6(Ts8#-aptVg!n>^CTJZT_b29~%nKw+*6l?TMXO(pK&|1nM%FIhkIM=9h7u7sW;9#Sr=>bq+Fqap37ivYgnM;_ zUCa`u9>)ISNT61u4-Kt*23(f6U-hOk%sj&DUAm}kHC}U+Ac1pmh6e;IT`a=PMW+#{ z)pcS6YwNCeq^pZLa}MdF*je6J-R^JWC_w_}U}}$NZ`sz$gO%xxgam4pAMI~#arvQ~ z_}h%wJGSBhR@!H%>Tqi!M+p-89BlXJ7xvi}rQWV@pb@Aw^G1E^j%QEh%*lWR!Zc?IJ@0wQznU&*cx-*qc=&)Tdq54ZlGRtt;23 z%XX=GIL-_>=F_RnXT_>_k0z^HQ;k5aS$1c9zMVfO>&Ka6dm&l@q)d-iS+a*2C_%!U z8UC9M=4`CTZ)a{qcKvR`+<#meRm4{E^epWZ08a<#9!vEIzP0jfS*d1}Mxa)fQM;{K z2X42$9$}8uwXKq6JH~j2TRpTH2WJDMEtW2Ae0i%@m!%nd8UG8la9*Lh>K4M!)~#yn ztTRj_P^--BRaV!_dE~u`=IZs;7-!zIS4(4(*D!$+Bye7#lhI|qd^g=I8aZ~5Mxd7I zZ~5ETTUu|K>)lJ$D)0v$i;euQ0|iQuz zTh)PymBfW&3$4Ezq{#&XVmOYEIF6Y)Co6H+)JE#Vx1t(>TJ@*Qx4wCBOh)D(Lhlj% zvM^6y(M$#A%P&xZ1dd7+*SWI`54jzxPQLigkwC3hHRoBcI$n~aUYRk;SCuNo^X>1b zSj$%&B}m{nW}b6WX0$au)Tf}M8i86noaS0%PTrE$YMLkR6P}jir_c6Q_Vaghlpukl zl6m)4@O#b!)sKy{Gy=6|x1VF(m*oLj4b1UsMaL?)(F&klRn#e`q5)KWpMzNF=>2t-fLHsO1V~=qXY>YmB`*cwJGmhJz7=iBpDK@ zB?fG=Uiki4Rty$Y28H0~g^Q0=uX4|1C_zFW;aul5<)NRVX;w?IB7s^{hiM}6M$^y&^NQ&yyWe`c zbF_LnteZCD=(CK)Qof@h-#87UGID+G%w2w`^MJvP1fCX)f%C}vOE@tqILR-AXzA{dG7qCb{qa_ zfi#Ac?8RZ-)tCf9=4gw`e z;0}Pk!FyqRy-Oz3GfX2;Yacsn4PH4z-rr_=q^v3D%@@qESFuZ)36vm#>v`(!Yg+No zH5}EJvJEr>wdUSFWu5V3mHgphM*08wS8cA2mQ&;Qa)A;gaE3E8nYHF^-#9BbH#dzy ztv_Q=SSKd@DeXPSQWm-krZaRaZ?KUs5AbYk1Hx>%=Vk zWq7n1<)7}B@I~_j)$K+F1WJ&=`H|udjvvNvHwsqy?6PSDY90Um(3+>sQCZ@~Kq{kl z#}T|h+fel-*DH<^B-q%))~a0;dQv$ z8YDFWwfYx1WZg37hHQ|LjW()n1pjP{P$kD~;V3}@=V1Ci+KuO1gZinS^`~eAYPs4U zv{o5$Pfp+5g5Dz``#?_nHPxx^g~pw`k}2dpEDK9oJ0 zHl#8_G7ser<%X)H6i1E{BydJGZ8BrH7&T12xW9`bfm%2}(usTIDBicm5Vf#URU_NC zL)L?-H|4+zb{uC09P{Zcb=?5oXk?@c@7!1;P^);;Mb=k)PRT6U&9Oawh2V8N4^_qP zw>40L1djRiMO8n@UIa&}y5qZQvjNTkSA#G6^t>vi-;<$KhG})a92Kpe?d@Qo1PODD z|8F+1`#p+f3mai(an%UaDm=HWwco5AGRK)>REG1;K=!ovNL3`frlCvz``>3fLw&j~ z-zm!#C{DzX28CH6hZvP8GZ`qUSFUZEsrAT?&h0c$@*Lxeu*$DuRG-SnBubFbedwFd z`QTGIY>c9O6A~rpn~&c3w2~=R$(9s1Mp>Kce)>q5weaulDq3aO&*icA8}gRUVd9V9 z*;wZ`g={`vGda$p`pj8*bTU62Fhy2=K0qT-t9RjoOq5(}b1q|AyjE^r!ehivd8pK2 zff6Ke-lf<(UlX}g$?QgVp8* zOiR(lDV*hAU>qzSt`VqJ`E6dds$mm3W4h^W*z>|79vi&TNFNa{P=W-`!Q`KqeFgtg z^N8_#O9zcWt&mfhSU<}!IdGS0BU|uiJkOfv8pS;i6DUCf=U}n{Ojy7Z27EGRJZzy6 zs5PRm9V<0`x*Xftw5rX>6VFRTXHg?#n+cR4fpaif)lz5k(?tuZz>$6$fm->_{j?sr zy^?&nO{?0@uvnfNQ9>t}2#p3!wxFoP$k&(K-BbYpa_4v4lpT)}9|ZSc5!ia{upPR7O&-IaWD5^daqTYhLkmAzTUr+;C)WR9n zVrf!vIe${Gt7^V;t45&Kmh8+M`g5Hx{TL+Fp#nwXW}S90_R85_k2F}_DHqx_8f);YUwj)^@#O6 zHuoU)`|3I?5~vm1I}7_*^RE0e&6S?&P3;Aoa*dj&OE#1sfjdje6E}Y=KPU!dM1n>F zwN|8LVJl|dmT8?TP#Gm_FXEppkt*tOltc*D@HH2e@$;{F z{QI$isvfUwpacnAuTVUhxl4G$g8nLB&W0L+TIIf;ux_eyT-v1`rPk`o;o#3O*&OiBT(z~qls3h5r4|%e&)KQ<rT^p%FngnVD-n+xdR+QmrQB|H8IZ~Be6|WJfg-=T{;;VP$U-LyP zF>0dr9!Qugj(@#j%*ex@Jo;#~y4n4LMxd5nyA(~1d~2iBvX@^aN|3;IqPiLz$nACx zQ%|o~*IE!gV6gX)2lk}aJh|>r^=g#RdI=Ic_bs=!+_*;;`C|z6l7#g7Jhb>wl{hR^ zBT!54?bpUd^0k43RjdrtdOH&M-O!22jP>0AXCHOY8mxU$=mCRYGucb3DDKB26mzMk zeYHsJPtMQcUYwUt;&al-@cZjQK6FlmiaSzKBTx&+7>gw^^a#H+w2ztDK^v)YM9tMV zFROp+mYmzqm&#buO7YThebkQ$N3_`hwQ%mD2sFh{@ZkOtDzT|Wo1>6;?3<4rY;av> zyKUx)8#*YB(}{*M+aCW5wQvrmtkWG2@$R3))%6cuwYe6F!a4G@(v2_4VvjR7Ts_O?>W|AXU5LH;q6oTz64C znQ80!w&p(MC*!EC;ZUo`t-_3r-XhD)F*C)Uo3@fiesxg^cPeTGYT+7{{6%{w@k2c; zt5YwkX=_m=Out00*cGx;WAkR%^ycfh!>?j0xnv!UKrLKr(`>*~_^e~^jLQd_Y3p{> zT3MnvJD+)oTs(g=l@UMdPwu$;yiuWf8;w9M+?P;f?wUvV%w>&@q_f>Mn>1M~M<7a73jD0^cX_golI8 z8|#{XB6=R;_(;|dia}=?Fh~VHuWz6P3G_lVPuwT+h@S&h^DQkk0=4vUx6I{bd}-T$ zitN1FxQhgisB|{*{UoQnda65FaZrLji8!KCFL{{GYj5bRdTzBEC_w_f5Y0P3H@IK7 zZffS?avFhJ`bgck#zVg7UKbVZnonCNB7q+GX7r>>yw{!{DtyyDiT{OKxDF`R?*+j@^~%#e)QD;mkniIHw=+NvFE1YhlM2N|3;t z9W-+uzRm+*b)~y9t{e%}!kNLm$8wMNbMLH#y+20@5_nsMGWRyRm{Ggs?@ZDN)WVs8 zqQl(0N_X+wtF?i%IZBYgn>H59$A%}l^NrSO|NFfffm%41kUg)$IkIJhC^HTnN|3-i zMrO7&#VL2V>3gmbsD-l+eNiC?dEZ=(6h+$PC_w^mSJ4{IwuifB_Ej6#=h3VNsD-l+ z#r>Fhm@nK}M_oRUPoM+|{hrrPX7E0PYp4=SoHPQpaK56EI^r;2A6-dZ+*3iI1PT4V z+U4h|JliWr6*9;}BTx%xIQpW-AK;y`<|iL7AI-LegnsWX=99t42K+XbEN!R}sD*Rl z-_c0&w|Zfi=YuFg0`C=CEaBsi@|wd>Q?#BCjX*7Zu06i*5?`=$FU93-soDCFz&nw& z=PY}Qd;eN)Ty7nv5vYYTHLb7e-s59$O*0nkY^T{QH3IIdQVzFAcRAeyFt*w{Y6RZ; z#JQbzUTIIrX8Bk)JKsgS$%^y2z5)pQ^?=(R%#{yxVP-2(t-`hY&Y!B4k|#f&v<33%9B)pO zeYgH`Bk0TnndH+;yYGy|-bq=dt^66=_nD?;JMOhGJd6ACZMnJ$jN^mxeP|_P`_}`C z{QBDWG|qfXlmS_yGy=7fa_+XBZo9*_FWU5UDm7lpRXyGKrNuqOp;zb9`W+r^%U*R3 z$9O_mw&`KI-*EWlZBUePfzONYK{Kih_~j&%@0+K{ekD&DZf!dn4m-LDlpxXiLrFO# zrnGFj)btn4ab^!?;G1J4ck8MVs5PKq78%y2iR@UwBz$h|H(HHYY4{B6C{TjLi8Uo; z+`PuJ`Caqe`N7z&bV|M7$P(3FBT$QMZ6nW9TRmPA;wUqOZavFhJ4F`X$Z}i&*rL%`F?J)Ch_NMV;yttZvHQ;7 z=Y9ATcE6c(=A3r~wQM{_>03#VKvl^{kHo#?>vG`-x=x*V1Xy3aNqjSaq#=mM=a7RRjB76jip~l$lYj z`5Ddsb(-#9jaK?L0gNDF`umhk+e0tDvT=9Y0Eq;uChxl_BHQ1Pr%D>}GuYXmE*u-J zDncm0RF%!TBsNUFDruGn6IZWDYMC9Q zat>D`j399_xtz59bymJ?rmN0DSqJIk5u?<_&AoM2BueMGP{sLhIX`%y9^b(`afBK-)jkdAh#IeV-}*EL8FAnsm-V zM!o!r_*OPGth&3NYIH=9;CV&qoJ%dcuaLsd#i)V4H}vGBgFuz(V8)YSde%Vkn@(Z` ziFI)`W-7B_WXJiR>Z7R8SouGYE;gFqGjpZMIM?jPiu7_Po!?`3>Cs!Rv7 zxqI%@&YTFf#`-Q{1PT1x@QvwiFGv)G*(<_GpbGuZ^r__&^4J^3cT`yo&od-=G7wzS z`fR;Jvwz~ec2Rf3!3+ufRI(3!yWgnj^00cDqA++Yje@ z;{ObnG*sc6h~0Y1UL$+$H8a-_--Gzx#kV$3(aG~vF?yKt`K*)SUx#u@~w(9?@g`*M#{?%W}&=_d;fS1u%Qh2uGv=yPn@+&eRG1ImG7%6*S};Cs6t0DeLv?u+BB$#>T#XxyWkau1nwU= zD;j%)HXZ7q;-g)xNT3Qmy?FOJ>N@fCnL2yDniV5Rpr;o<<9(tAu0Cqb*L?d4c!D8; zJ16_Z2zT{2QsX-|F$h%QevZFU56@HGz$)tO@{bJXFI3^4k$3tvizvC7t8x$YH3(Fh zu3RM>50Uq*=d^u755p@A3C=$qE?`_QS)ljR_sOTYx8eMS1nzy=*{I+g)v_KU+uC4* zKo#eo4o5KV-r-$Fm-qKju}go$D+~$Tk@H#V((5#@&oW9KIM5(a#ThF&f3013iJpBw zm$Ir1HhjF0z|2BB72c=Zn4z??ILshWW%_tkK7W&@?CPlB?}m>T5||-zN6IgcY0a7P zg;;|?6?Yg5=Tu5; znQRBb7p~9M#<+%)&z(S(6INMI@QBjc9#oA9I4p(_IV@jo zoxsG%ZGqHrP^dco_=TR}aS*5~T9YK6`ur^KPSX>IA%)R=w{y61sv+bPUL#Xq%ROORi(GMd?xK>IOAuo$% z#{M=;jAXaP12IXed-+Db7(oKFK8uAjRH_ic9T4o+g9NJ1&q@@nf4D1WG-}Gv2>ty_ znp!qd1>{VT7(oK_M14LuirP*|R_ee(gFsbCOp>T&y(8}}_2g&p3@?4tFhR9DRV*=r z1m=l+57uw7e3x*dYNXr=2~=?xvw&HdyxDxW(*)&r+gne*I3h@Je~~Edv*upsy>av) zDV}eT>}3$B;=T;w?58d$lS#gT8f(z+gM7eoS;2^^{J(UKvl}lnPPeB4jI){_bp|n zPNOAX#Pdvb6T%1*2TuPiwEvyYbvGt>VuZ3%^lzg>eEmfs)27#(+?HY(bTLj5U|JCzR(d@n*c{@@KzyH8+XxUcN zO)Qywf^X-WV7$S(o9fYVDf&jMkZLCk0#}Clb83l#PFLmK%t(I5uB|`IYi}hg6_V+X zE+?qMcRpv3GdIeT8L296Y8Qh*6?&OiEUgP&srsE%#a_bx7(oKx;1+{_OglosgmWdffFz0#)c`!js-ZUFkx* zboHy}#ts-k0^j-eJ{ftULxvi^wX#G4Rp@2HCvm(xPFv6akIZO^5hQSx(0-O%WN<*b zdUa&4L7>X?GAVW`Pgxmhs_BN?5+g|9JD>Y9*6fof!qZgvMR!61RXp!r;B-|<8&Z}$ z_NSJ*syHG@ykqMwN+Y!}J`a zBZ35Xn+oTwWp>~F{QXE#nW@7J0#)2QTHu_n>9Fg$%z2cocD5RGh+_mk(rzg=xH} zej_o0Yl%72QhRPC_NGo#y}3q=5hQSx;9dCeD>8IwIy=5EFbGt|ue@CFZL4qOSD(4@ zinHR5C%KlN#D0B?cpk?YK?2tmu8Y?BTb`Mau4;P*7zC=!8#wB}e2ZE%NLROxb~Eng zKmu>}V8{2su@t!~MUB1HN8&9Zcozt+T|DVsCzOUyPPMxsVgw0%o}S@tP1TE&)$X(Z zHdbf++u+VX-&yQMwZBeQ+1EZb_6$hi-=F6>Yj-8x#ae6&H3(GUo`}x}4>Y46xo3OM zr}mz0$36-P{2cR&^H)bY5}2sgoU+fWIS5qY-p*qAb4_D__&}$h=U6>n>*#+~eH*bw4%nBQv{0RoQuUMOF6$^1Vj-407{t4QR=Z z-fCKfnnpf|D$ETnmH`7@DKxLMN?l#giV-9NvpvMU3i&c)uJ+!^e^{SNX0%uHbD9|h zsxaT>y-$9Ly!lQGHD-A`Bdu_pz(iT4p01ZX{_%aLo~+d$?u0n^46+ z_fpNH(FTDktOxP;yoMWvwA@0q|F9W#A0%+ksApfTwBoY`RC$cu@x)PELKW7vIP;44 zrm8FBsd!<6QNKb0ce4CxUmr}9Uwy)-)rkgyDy+8gdVb57Zibbkod;8lIvf(XBj>KL zDl4d@P7i-~TbOpaadd@XtD#!b&0E+EciS_|_Bpw64vH5hSqgr~Q34(b`5))WIu8`x-bZ zjYweM3Hyt#Tt?4&X4B)@Q3io3tozyBLMivm2HJagxb`)0R2q@Mz7y@qkws@K9-&3Y zA`AjmSoh;u0MBLmw@Y2)!nCh}qtb{3_MLEld#yQiA>ui8Z)kTya1f}%x}Uzmekq@; zl~MD)3e>&^j!GjESgq&N@G^5KF`$MzT-4PdP=$3ri$#=MNF~!eRQF$ewXcDr(uf51 zw($EZb2??^G*c-nTN?zbuu{l-xY6@T-}C$E2a(aOYW*wc1fd zl|A^jL7)ojeiln1cOl8jvFc&#rrLABQ9Z+|8lLvD?_l>_a*MI4W7WGG1gfx>#r567 zZM1V=j9OO|qFv6QKF4sa;;IdJ)uCI}bYuRAFUG`v`BNw?46{?=tEUMv%Y`4~wPR%@ve4ZM;(K znvDdiFazLDr-XI(zj@QCe5VuKGl&G%vMd&_o&{8}+ol><2{*b$u*<^i{YWgcykP&( zBLD4sf(-9A>}W*iP<;x}MBaMT%HMZclocaLU~eRMa`^8T5%PshpP6nDrV3q%b;dRR zd3_rAdzw{yB$WCdBZ1X6u6}g-Nd$c{nwITOF$hzI?#ApB&efRVJuK?!_k#@rRp{!;-8-}TO5bG_)axe$tQbK8 z_rAQp3Ti7N0_!NBfq@2rDs=U1zd7Z@d|N0x-Kw|^?^`i~ z1m;xynVi^A^jjLNIuyNQ5U4^|PyU|sZK0P>hbZ5&m8}>-0&_z?seb%I{CO{2^;-Md zaN|am>7YI0<5n`~=vcLBzvTSI>3fYT%yG4MLR;CSf4sVD%Qgs9VcnOzEGEA#ZNL8G zhpeAb>U)fJKdjI3lu$N_DYk$7kdZJ|=z#g5M`u}Y_CKDPnke%I`i5mN$Bwgp(#p{cn)KiXPwGd$gPQ>-0qXyc!ay!l`fGkqtO1YHmtX z)0ed}TyBuSiXLZPNp+?6#mOFTF=~BS_rW=Fi=|u7dh&<6>8j?b1BS~D5?ImWE+n4s U@;;fNUTx@XRPL}QXI9nz56ifq4*&oF literal 0 HcmV?d00001 diff --git a/tests/link_2.stl b/tests/link_2.stl new file mode 100644 index 0000000000000000000000000000000000000000..303dedacc6b56a112fe79ce5944a98dbe0f288c8 GIT binary patch literal 72534 zcmb5XXINIb^FMqP6dQ^iuwg+dD!tw(i3nJ+uogf>Kt!-$S5)jE7R0jHv49mTc2Vvm z7F1a5yCURW#Agh6s ztUAX<#zglX*=yYJwoxPFtp5N0ZL6Rt(NPoey1WeJanY8)Ih&;Si%Zv6xzSv|2zk_?D|@)RXizlv=dn}TO{ zml4aN_8qDZF!s9?%02%J%?J%tbIZsQum=wvkbWf$E5|c z!k6~sORvYYbmMA$dHasI*0&`6-jgd;fAKr8ZK^tS4p+7R-?Fw-73J2PMQq75d(!l? zC4vaZHLAr$10wWgRh^>DOSz6Sh#lz~{zxBxGtVI7)AeJyV~-s7*1o&xpYtmGlA?sh zlwjkD_QWRt1cO|=ujCuhN%mGcKYqyYyV4FPQL0WW^01LW*#B+9Ap&wm*I!^jq~-l7 z5DDjIWBY;jQu@Vi021pA|IU{Is9R*R4Rwz-BfPZ5r1+#@UMC_ zUAT-TxZ9ITC=^4TM1Ct!wVMCD_BdCrx$nn!I4;DV6bNg9^?-VVT2Pec))(pAkM_jT zZU}?lf~A73sVK+(ddNOpvnSoo8xdHND!KKh|k4m1)}y}vFOfDJ7QDgC5AGh{F)gw>g%o7!_q2B-7B@YQN`9| z>4%#*CTg>xBoi#A>0znhmlUN(>?=Ak&z`8pRi#qFl0bQi66ZPteJ^aw8}#<%zrBGd ztD?aE_`7!*{x3ZBWiMR%rY*mg;mjcgB4D3al#j!g<5%g8dFQ^K5(07sTTWDmPucQY zMqbQKyy%%3pSQ<}LkdJdPb6%2Mmh4O@@sbLmWPCZT-}cDQael<{9A@ky(YwE>NYmx zup@^Qh=3!5qGSxRCg)}kVh^8sNC?RF<^Er4P(*&Nrb9(pT&*=pJUNlpZREuv1tNa` z7G6R7+f1FvLj5XqE6IsN3PivWPEkJiH6qU%&B5Kwy(I+X`dugWe=_ET)g%`zE@2^y zLkdL5UevG2Equ6v2^rheOF}@d-)-|-#uKkByyaLEa`%Q4hZKl_UR#VG)B~qiwI#vH zo)Q9b{kE~+GLC$ogVffpAq67j@jUok1}hrTkOXh`kPwh7=j;%@u=d|FtWut_FV(7&k4v05q(Fo` zM%`;=%-?zz1-(P8A2^SI4|0 z1myZXqW-qs;)~8a<4Q8>xzD+5tTj;nABf*GvSs^P^HHU<>DK3-65{_cQs@59cGJRJ z^ThOU=HJno|NgFl0ugZLq$saX*5?o6x3IkHUJ?RwJ-@v|ug&`YCnM6d3Lm@g88dI` z!XX7B3qVTLoPT+kr7_sN@>#+4-%K(nnMaiG(K*s z)3mP5%7b*R;m9EcBI+N$l&c{+?mQ(BO)SiD><>q>_?aVzb2Z2X(TdXG z`BF@edysNtnsCSk(Up6|>K%oQR$nxqRcYIKJfo#E>0n)#!?_{kf@nqgvi2(;X5&dB z=w}AGAbNetX1!JqU9VUnBRsGU(d?>%>m>$ftdI+$6(#6Z6Eb~~2YF$|lpkGU3^J1YZq>st2^pog@WF5=QgMqJfm{$R&nyRK zF2@Z|dyuzp8WTtfeRI}euc?(z>*1FaWw`wWRIP<4>D<LyrsX-Pn!SDw z&DFy%DN4tCXIWN(mssOeC2+33WMzf{F*-k457CNJW#3B1gPlo_>=qINazWXOGUKqq zElgZVY3+ZcwE>g?Wh+YYr$!u2@FsqPXG-f2=;t9?Q6fz(`FC>{66BI2As`oAmnh1U zw@y4L*o9m>!4do}T&2jP!74j*t~C3BcQ&j-_D2k)+hPJSy4DokFX}=YpZ3Ec-P@zg z#J2Ro;6QxsY(JzZBMU9Lk8U;YddikS3Pc1|u%kYo2!7KlN+7mPZ_e|s*yA=$34s)y zdwV+lz5}l0-4BgSx24LXw)n`8F#<8?T^Qfk=?U6+{UaXhFpBPf<%Qo{*FoiGPo}3D z*y5?pYM>6y!)ZxWTRc17OCaJV4(0oMtwI@}PT~%i66yMKZunR;u0jO-l9;!Dj^(9M z0XS?y9krSH9BQVv#S23wsMq$+r_F^HJU^AoO}w8>xqmCXqjEFh6YsYg#6OK0gX{m< zQj(EVFxP-c8|f~6N%Y!$N51y2@2I1-8-cZjT7Y^J>%L1qylY5B?7F#`gn(Rf%`46C z!IMlcpoAGU38X-TT=VqfV|Z@o1?XJFDybfgQxj=gpQhMhPLZTHQS%2n-gM8O_;rvm zf!~5Mp!Epbb#~)hdw<7T6a*q5*I$7%=qsUVXXUEU?&yJi_>S%KafHck2?4oa%PLBg zStlOR`#laG5H8gNB4FDn%EUH-yr{)fe7w#?1lt^P!S)w2+>GeUu?JcI195yCovYj1 zQ-^1oB-1y`pLnG`a=~|;XV8}O&Ge7Pdf+jZv#5wOoO9=U#+Z}bR@v;b_fVRVwE%TF zFi2f9G>+bIOhkNIB{lu8S+vWWQRwR1_M+y)cr*Q_Lowvpm5WUK?&%YIP|F8FI_>v> z8`)^>-*t4ENf!D|3wNWU(3)c8Y&YGNKAtg(9C)2+K$LN5i1J6X(eW|H|3WO?>BwH% z{$h{4f_a;?ru2E{b(GdPS$BG_F*R>>4|yyo?>+j@mUQLaeB?i{yeL(F{{Y_T%|#r& zJ%d%=mQMSAXowsKuJ^dwY87qNur-?X*F^Qw%SF`puO4Xo;bei(mmfrT;QE-njNuoY zQ;vQW-Z^?l3T^FY;$7X*7av|ekM4eFq5sFOGrpNPPw47b^k-VU;|4Z**poxbjc=)X z%`zhPCR6w&Me$pBo86pw1vhx^%1te5(A5_@WADP@v}9^?dPvB7JTHQp6+ShLqSNE1 z3K?G$s_`f9n_$(%i$gAm9$HJKU?Xwf-eJb#y!kRc+Re9*gmJif(e1}S{jII7L`ysj8i z_$9IaxYeGUAHIaw*4)e>SHD3Cbim+FxVFtB{q4uI4IX^%(M5U@lL;NnuN-m1H^cv? z`9AaL+>Y&W^r)q|(88C8CsY4eKm29O5P>i|-kpECa|2&m(vU$4M94D2ZpHEzU36L> zq|jSJ1e7iMpyPD@_>4Jq933dMm`DRZDtLOmLN&u8i5f37#s{~2RpFO}cB@Y3q1T71 zgDf8DA>vs3WQrmS(2~{e2%^PkP$Qaa5zfT!>GaCSRaD7phPrxpK|k7LQZesQJFNCZ z&o`~0hp*H_!y<+uMX6Rkfd`JrM?UYGa~9>9ni@{om#oBgcdQ& zw^MkyaR!?B^ozs=(LdVmq=|QK>q5gfiT+{#cMKo)unBrx(}8_5+eKRqM!9xR2#gk?>bFc<)|+(7LBm(9?KJ-M$*m)O6%> zw5C^Q_qTtIp!d9|BY}1oo?+1m(Q7-B=qPgz{Zfr-kGxLL%SI^=UmW^kzEdB)c^gWz z?B}5@~ySDHjqwz%L|PBrz=`k+l~qgnzFZO`bB zt6wDBg$Vd1MQM61jz^vL5j#xjEG~aKwaKZ3SGDz1A(vOqI2w7P5?*;CQFv;HoFV+k z_m0eG_8tZ)5CQ8aR*)AW`RrN4*>wL)5(09`HSe~?n=6NGnU#eNf9&csx1koqI5=hi7qJGms={kY2K+9plcKcF9?3TzI86InWiltY2Ia2XZIP=2b0!K<VD4ejhrVx7fck7|uYMmhnEDSs zk7~~xs+JD#LAzalj*fO6DC|n?Uh(3{Os4IOLJCCamqpXPmM_shR!-DByNd(gvtmCx zx!X!YK(3TcVKnKZF@8Rzo$x0gnzZM2zl5>T$dW@YC}a1Hadb{xAu4ILM#!k_8^qTS zu*E?ezOsL&PN!Q2twJuNj;VC#JbI(&d}Orul{%{ZOj@IK6RLUof?}S6%?_f|TP*-^g3+c5bi6|%DR2!oL zB6+zLxA9cs#^AT$jBK$!joy79h|=7ziFzzJ63RarUBY$SFO?9GORh)oTg1((Z^Y>N zS83J<#}6n^QCw#P@x;Jw*yeRAgA|B3{>NIH_Omg%TIGr;Rg_t*h*_S%_U3gZ1muDx zRFsl(6F7a^9;X_$XHX}nEEm%1ne&myspe>XvpICw)s5)0m9fy({u4v_>*s%}jyXpd zq)dH2i&p=Xi@rT8QDxgTP8h-qPnV+cIU6Mz5bd`yfgVu~Ad^W{)Whm>IJa6cJvS__ zm_Z6e$TB<|4d7FEA3}wuwVTPK~Nu(psZ>0KHvj2(n#RCf_I zPb}`kPkx%qIy=3V#t+!Hp?_4AhR$92_@agEL3~9HDG&kszoHmb?9UgSaAR4Mo-v4k zT(aMtYZ1@$ComLkF_6JFfV!G@aW0+qU^^PVvZ<&?$ChY%QXnGicbUvx zs#@ZCgRA22KQ_?b51y#;wQ3@1E(+$p0&!;|7xPf;Wz|qZz!@@}IV*~3g-K#`?up;_ zJAt4K$OW|^@&HB-=I7phMv+17q`4@Zf5N%1qTEeQ;LY}1VUOfA1ZxPnplq=c_ME~! zuUEj8E}fA|1rbmSigImYiQdo8mH&!$&4%lx(18Pmk!<>QXt}X zp}SuBqXAwPwiEY8(ebX%s|AJ=Gxm2+Wf3cAI@oemkKctzA(WPE=(xjtEmp@G15fVcqJrASXI~EBqdUBAR zzUCP_UTuV!``n+auQl{3ia$Cw7q*S|yMJ*BYHM{s%u9Co%+9S)qb1Ki)c!w+GA<4A zeautzCM;1P9>hP@d(^MRld1%Al#{Ek-{~R>8=9np^0aoct#l8axaW6N%&*e(j=J=* z;^t#J8d|W70ui!|8H=7B-B$3GCDa*Uu#y!&ZllHz4|r)@K?5$Mpb0*@kM4)`K5NdP zoSi4c9PV>Zx7^~$pS?mHJ4f z(hz0xVEx35tX+XVu*G|J$|^#tIYdC&Vr@{^f-a6dl>2zYR6{+sbYjSXU(xOTK1pwX zG6%h=^uSQ6uwKW|PydUeRBm21XzfT}n%jAb0Z~TzH)7HENyM5+Uz2(M(sOt2JqDR@IcKWyd%Cj}q z;|+*1jcVU5YXgWDnVH8F7FMnnIas$VztDP~USE)nMC3p>@yag!?MC}h&Z4{j($%PK zMRfY!JnZ5aE!7+%WEsCw&Dcf1U`$NMb68%;1<}Hbwx6pXwxR$ZbBQt3qxps$wseEFdU!~t{^<&<17Aj;4(LbXk1k6-zcG*pAX%zB~Et+Gvw z201#Y1&cAS^bOc%bZJ+RXu%p!D^sJ1Dd^fMxqoQdz0@ohiQWBw*{-RbF|GX7N@Rad z;jp$4q5Uo^tymSc>cQF-Sdxz2Fo!yUrGlkZl&Xspm}${3+$*QMgn(Q*s2m+>x)Zfn ztE~s)?Z(o_p__5E&#?cLs;nfku2zhw#a^3Y^0{&&KJ5Kcede7VD6fi#q$?TG;P9oR zw2~v~{fCESC0cFE`h@no_Km%$pF^_H?$w9gnG;)v&xQ??>H*6Rtw%(>9vz~`62Hlq9YBI`vjG~-5>PfRsr!dbL+513*>=U#4O{9~mH{+=f{iG2G zM$h5ct|)zj6PXrwz3_P~-*>bwUE_Qh9XxHNUX6C5J6h~RKaRIk>zr>(Cq2(aJxrWM zd%SkGWhNi;m=?8#qdxTKGUD+JN7ka-JeHdi#~}qGpllJdbpJ$cOTRG^6e`Jp^?+za zsr5FERoXT}T{d5?hvV($w1VYM)FGm^R3}AoVs&}s^J(nh`Su)+^e}25&l$uHugG(5 zz}mEE!{Is#BH))q3}BiiF9=LS{fBnsFgkE=cMy&Lv>n~co+ZTtME{6=#LjdtrX7z& zayS=pKHZT8PsS0<56s70)95H{}%EDLnmu5?_{b6afIQ0(p(qtAJdv%ah z4~T$u5}C{G8}mlBRS_>CQiKK836@q-4oq_tJG{3sI%XzCSRj{Nk7Zx|_@|}W*r|uH zBm+iU`RTZ$Ax1hh~wdp*0A4d=B; z^-Z7 zajmD^$_3kpuei>D2fyeKSH`{w3!U*dK&t*?dfS4Ne$vo`yR@RIyM4k-`; z>nCC|3Hz8!-V*%MWFUwB1ERNA_o5$%W}pe99EFT^b<$X|`ZwBEdz2&tqGb_ACqhm5c|S4U_5t5ztGBoVyu% zW_;oyBF~3N2*?FT29YW27o7Vw;~D#~Fv`$^Wh)46Br97R$YWIQ=u<4>m>UtZacL&g zU(DwNH>IQbWWG+W$N2I`S)*_ zt#yx(JT>%#P}7Ry`K^@c{w&0<8~iw=z!rq^6lI9DB`>XKPUh&0IjjftgEC@fxmLX9 zjAkS>rhvh{e~5rzQWP(%YWzztU(p_0Bwax*z#Te6&K*~7x|5#YS4uMAcV&cFrRsNH zjv}WPU1I-UbCj(`;69$BObWJP=vYsZvd~zX^+B|}+vjy_EZZ@=2N~7>t7IjR3tEh# z*d@(n+s=BBnrAFIq(DT+?27b3*Gx1kD?#iij(D++i9G|-;G~6wfLw3~Q=HoBd72&j z%ZJQp{!y}a$OSd6D4V*zXXhfkNMXMs1}P9BYxm>udOYu23$oVzB7+pTe+q3uwE3;t zyx^EINi?a=Aq65frKHk5jRMfYpUXwf9mFhY%gOE!3D<{+B3prL-o+m?9rU;RZi>TtXAl&)#bEsp67h!-Z- z_)%yuJ!JO8D{fa4+_YT>dRvNLX>-IW@2&X6sv=_(aB2SP%j0@@@w#UJLc|U~p%Z7; z__w-H9#LL@*wpnb&gWNk9 z5Cx-KVg23+L(R+TB-ecW^3(KtQcFH{P&*DO+IPzku(aZgNyZnN*S-yJ9qlF61CFmx zoBYscd@GN;RGTGAb$8!&I*YDh@ehVeF&XI3;n*eS3|qg`V;efLc5lW@qZ&lO)r+F6 zTyD?Wg?Z3BJ10vB$OXqlk?VY&G3$yCal+;RX{?357Wzj;3Hj8SFHSJUG1s0+87Xj& z7Vh1Oow$}^e72hne($r0K?>YOmh(%@n~&#RH{Mn6+s$GyDi3!7;C_ObCsqt+OG3<8 z-M!gXH0w8QT@&!N%tkLWL5@WUIX%oNss#&{9S*d5BmJdHyNL{zz+qpw%w zjf-AP5{QilO!%5J=b80t#BU6@rW`(I+-em0hmZ{<(>U;m52Hh>lmEnoE7pFzCmFiW=o#6J=Oa=~3W zF(Yf-l{Z&5v#)*2ak#?=vr{_F3!|%Bw8R}BUljf-)4wm*GDYIYl`u$w2stC=%S6mG zt#+`{Nwqjc!0esXOWV_!j&^vEaUEeL!&Z3l+@h82Nu5RsT=U>>2^eI5IheXiJq zeOekWAs`p@F3pu#`8;~_~z~k zYkW3M+OLHfFmevdr#mrxYD{f#U~k8%6nZrY-+8(vP`R_vEk*AeWr!bn3bV*Dp5{v&)VW0&+o33rnp0 zRllrV7)$Lok;BYYnEeY!2C>g6PK^d0T+IBgjp2|25ps_3mx(M&KO)%+gDP)X|T|)1sRuyx&-W--hoBNc_8R48rQN{;2 zvLPd_xU0Jlhu?)<@@z?XH?}^pg*XeTN(jg$&z5}Z^IhIBzjIoz;P zXFcSCkq|{Gx1t{lnp&Mto!3=DKrWaAEn)z^liBkF<#^|6e@NPeT7dNv8A7q4Y)SqS z)@W9o)aI}?$OYR; z%iq1vPF|_X#eS!RfLw3~Tg)=X-DGEuR^rztdP#fR5CM0sh3(!b&qewxKiSAxk^#R9 zb*L!r@9T+7r^oEeYI{k$5CKObu@hHZkxq>N%nr`{-wtn?Mq&SuwL8`~nJrq~kpDnf zvUX^@uuh`aKFeS`bd~v<>K!?(A>@*6_rSCa7Iyd>TYILvgn(Rdzh3O6)|uBgDL}tyi7j#EN3m*HU9fuYUSHjQ-i}Ad4J`0(b%>0$197gM)^}(Gj5ieP^ zmZeXw!ZyZ@ln{_hj-*Cy%44)oo@&iwB?RPxb}V*fni{jmE&=4=mdaAZ3+`>g=$E1_ z{SZv6#>UV^WsrZ8Abg#wQ~Q0lBo_WoLmDMGbV|&2JXs##<|K z825o^b6{4eIEiGbxJ4vA>}6*t{)Mj&NWd|#xUt{HjL z9d()125BdT=ngHfZ$`QLByaCR+$5?kffOhYeo6G&R@Ow*?z_)lF#Im$+Ep|GX(uOV ztg9$woUPqQoJB5=n+>l-++Ghv{f%_^!tFL_L|h~?d2Nk1o%Ta6^(UgIK`z*+znMVH zwdhDXcCo^z4_gwql^sy`a0mQkeTamBUs9CxKb%O_R8u_lqKi~>s4Ms-k$=^wJy|sV z9XeO9xrBgRvWz>~v82MO9@ulQC2FvK9y+6Mi(9`_)G^%`AnnxFzV}^qEq~5MG4>8P z@xf@Zk7KocFv&Dj8|# zRki!cM6A!;n^enLDo#|H$n^l4mfPd`q7I~I>I%GTVF`v5SX;S0TuM~3Y19w=;h!xM z0&>Zv8rLF-q#yqipG@A0Aq67Nm79fnSvDS`|?$d-G-L&C+qmXX{k{$5jiJIUYez7hlzBKI*`P zTy*!-Wy9~XY%y_$_v|dxx4J2h8Pc1(RjG{f58psjLmhQjO_!>FueyRv7pOY7H|Nx8 zi;Gdpao=1K-}P9DZ%mub7PTG1+rJ7xR~+@|udVyD**^7b&NdNmuP5T|W4})&<;EAOzrJ5WHl22&dM@qN?NctOyYB8lZ=Y_{ z{Ve^UwhYWhC7msD@0vvkUAcx%A-zUVKuvUYF+{9;wFNzJ3{;Obw?hyuyy(ZtBhkN#rDik0-aHkPG%f8Bw!l zAh{888-Lq!QbMGio{O}TlP9~()3Qu5+_M^fJf}`>d}-<(k`i^d_-4moej0ZyBWgjE+Zz zZ7bm#B8>!oNl`8x3L@Ke^H|+RB@9v^;%&LfD6;o^bboVi;jcti8!67(#=a+2o?iM|o){OZE%|cCgR>Xs6MXFG{(2t4nBWVh$dOMJw zot{r20&+dxl8oB^dWb%cX@bPfcpVdn{*QX}YTMe949L~I)@)S2^BvTUz7h54RCyd3 zva|uy@@1g)!BRol!o!7(CO!9+XSM66GS~)?OO_GVX((}-+<@7<-X$R*7u2DmEOE6a z!F4LLZhx!1Uu+Cozw0D=W|5$FsFr|QRM~~R8}C<#r4K|qM;}7YLE2gUA=Y+8aMP{D z-W*aOqVb7|h&X?&M z+(jo@39JXS7!mRE@FZRb=HkgSn(}e4W}w34W$1b4AvL083cAug6;<|FrFzDWM2ohi zqqM9QqEzCR9^$pv61xqsln}7&BM&Db)L|96cjl5n{7Q`=4T2`%!+#gDd+`fU?(_v{ zY1iybV5LkdK|(uy`0y>@~1FEQU8%Zxq#M5D6< zP;tj8>cXdU(SpxWDAmqa{c?XkYPWG5TC{M7C{@i@(PV7nbi8!nYN=EYuKkJneTYKA z4IWD+6u0&C>Op)za~$8}9)tRUrIKZQIpIfw&pp7Up2ZRZatW(JLq;c~Yn7&oQXM-J zMNF69z{f(Zn6F1Vn)bjB*?*p;!aBhciW9l*1`sWGFxYDxgA|B>@&pccg0zL#Ujt-=D;>hdB6DX<<;3qr;72 z`Z1ZLKX$-xXQd-pl3JVoL>6O)qYs4)EkuB2n)2#+xUsqJt9` zpj|yyp|dviBrY$z73k~d5VWy;D}mTMaU2=_cO*9I>C7Mka>3rLu-}N4aO4y+=~W&4;ijz~>I&9LuE*@!3FO7mMmXqIHiZbt1xqW&!G9(Y?Y5pM zvtX$`AQ#lSqL^$MMd}YdhuqGkOYH#>ux-TIrFo;sCSyB1X8uA+S5QAPV%))KQaGtK zZu(C?gA|B>o=>YsUqYPspp%xy93mhW981JG$k+Wz_Pt!R^g|AYmH}5U@`{B!P9ip^ zTygJ8H6;Y(>Q!kIy4>K6`l4MuVI^x{O(NGa+KV!c^F5 zkPF(F7WWxXs-&i3kr7C(3%8+iZU@!nz9}m7T{1%4tuAh@i^Us{rm66|5G^Bme4R`x znLFau@oS_tCq%$6i7bn}$z;babBqFiNeIXV^`5hXq zjFChv9;dpv6`;}$*@g&9S@y5Ehh@Q1wMRQ69v2cSA+%O2FOOpr;EFMc*}@_(XHW#_y!MA>;Paj&!S3w1@S z7pSn`f8$qWTpFS*mL(!AC>lLKoK4T+|D9?qJ2|)KOrC0<#?YR=uXTOquT`CQ=b%-G zUx<2y?j=avrH^W7B^dfg83J;_*qNd%ON~TgG{9eaM)MK%E!CQ%_oMs&>@l=+*?C17 zvFT`SwAFMeuK9NCe`;Qa(CSg91u-N0>W{WfHzJgU7)n*f^>2A)=M_c&(1oMCZ*>Tt z{J(tBGa38Q&&wMOr7GisXho@icM5vAKAdb__nyH>npTps9SrTauh(AGWy%PltJ>;H zv}S52GILpN{%=GXmn`E}Qd4o}4v`B{t^T8{GK41M|Mpl$Uvfv$v)xFyOHThmlyPZ@ zL;8K_^p<6!RP_%BqGi7JO+@G~4?vmUnvnYyI{pVy#-$<3bSNy* zWF<&1-=21Hrp zS1U=`cV*k%ymC3xKNu`x?l=BZ^Rn7%=rW5DzGOvhR2tTk)Q`($Fe@F_7HUC6qlS3l z_*K2djlHD|#&MyIP1u^N`aa%z$}zVX6+I zMb`ZpKU}RSoD{3qrFuYwEaT(w>!`x(x#C3CD5=*%&u}Swms()77kRj8XR7<;T}K`} z?qT20;SvIJ$^9emOFjImiWRxokVy4_2v|aK+uQo4VlQeX?z(X}ANS^Ob$EO>TJc0t zAp(|AWU-nJ#QI!&QvX(44!KUoyj1&TW}!tESvpz9%Vo}J@rwcE#;J3X?P@JpX6^ZpIXLWM^0Ti*QvMOu$lJz_k9kr6h4j&_pgK(^cUlKB|S0Ez+E7bf7Nal{%qfc^}ITgLkdL5^F;Hm zZN=TY$5Ed?ZX8C3VC1Ic{b027XBOJueu;(1CJUEO~!FA>ww?0U}Y%`jBW4w^@c6uAKcJn2Xvt5rvE*OXTRuGJ?v`I(3Dh(2d zfGw6}+pHxbuJ6g=w;)t{_GRR?La9@?p^m+6RJlD0il^hn6T@-r z!jT+OAVRiww?u2KbhN?TC0;^6F4@{=JO6_{8|}vVE4y+xTYogC=Vml-S)dBbK6;@y z>J^rOJU`frnlHOrf`cR5khJrr+;=BN{Ia-R%%Zvqdu{!j&C&2n8^mdH?IwiRX0Nb* zRdpiPAskZRcj1>rWFq1!E-YAw!)^sjrGf~k1u>I(KNC+|U_kTzNojV8LA}=) zphH$~m!TKUX6qnY%)-wbiM4YjLVMUqZ4TSRBs>^d7%xYjT|0|5x7lbyd@YLbu*zN> zazVS25zqG4CJ9~^mWU+CI|mMsag5(9Tm^#m%Z>=GBj#qpDY17yVKYsOCLO`z3LD^{d#rmShYJXpx1`A(O8PCqtF-U<3 zIlrWdMJ$=Pz9$NP--bO{-1v^{$a=LkDf+cq z@;=ax0B#^!vJtHC%9oO;ZggS(|-x#L15*8Ge`Lqzh|5xD5S_t;;hPbT_Qe%T92> zOfYRtRhA*9#ToP>GSQY#I^!kXS_jYbKIojH=Gs`|U)Hu%+~`p49g44D!?n2&q(B6e z_rLhA!|0|wDyW@=fL!90CN*zQa~$>7U&wgY=o#L1^FHgj*q>)@X@NSX+Tt;w6q~f%xir0N>nlkG)*>2Zt1hnE7(P>XPS#U&W0T2W>2OVRdm*FK!!E=(sy2J; zSyw_pE|@JO`uSvUVqsj5Z7Z;q@|GY%&Ja2mW>31lc4qf0cyLI8h`>Z!FUJ6C&2Sx688^NYml?!q2C zHdSRGZVus)0udFv%vaAwA>68dq9~QyfXVpd!rILL&{zopxnOpZ*tOjJ44W2lod3v4 zDizGEg7p*k!|kj=s)?J2OSig9HHQeOL$R6&YC-Hv6WFpF9vo^^^ab>DsyiNAqcfFd ztmyC+pEN_+Ne1jI z5H0p5j%&N32bp?5T*FKs}C=CA(G!$sppgvN{e6Pr3no&jnaW>zUm3!AniqRJY^ zH`s7Ufe6^LVzu4hj})cNVRO#bk`Ry!_IZ(K8Bmp+iW|o~tpX&wf-+#sikZyX1~_Ma zFzeH2yre6rAKBVnLl+?NvIFa=OqR0rAVSWe-<+O@Y+g8U?d{CQ$2O>q&Q`>BqxR|H z-3icx3rk$E-Ead`1Jic=(q1D}Jfjhww$qA2?+iVv*vCP4@B+n{^XjUEfLzcjwO4g* z@h@LHuDxpsr9&C8w2D&a(;{qQZp9;=t)(#va%omlwwo!UoRi(j{)u^P)WEt@b{ot# zgSH_0`AaJjZv24hD>ReZ93pntut$|gS>hKLe(FWG`m}n)vFHig^Uzj8KrXrFRS%xV zV>{I0hj+Sh$aUvfBUC!f7+)SSP7k#%=7}~I*yKYC@zxKKTJY_e*J{;Q<*;|~bUoZ- z63$dFFMi zxrBgRP;Xk)`5|I`>hNB6-K9N9xQi^;qsROqcztAjuH7;QDX`{nS61tTDfp1N1t-q! zr2SfmfSMNZlAHH&$B|X}t72DaPZ)B+b`lv|b!w0brGK;ZO7;>0a>+IC`l2`K{KST3 zd@09a&JAoEsC98};$r~OZsra;W6YtKftjGP?KbsUg0-`1m5@&AgRmY@3&O6t8RKVr zuQ2T7F%j z1acs|x{zclei5(09`y*AOd6tBvy$U}CxNc|jg$)2H#?+U#0vXLlN z0EeCv%7EjpwoBFvN4>1Z?ZdlqNP!4AzZU&tc~eZ>ezF@cf+Ymxg5$36C4PBm>h6l% zx@VBI{(uNg(`Bm+?d8QJR5;}yw%%)ign(Sy@3Pg4c0&z{9l2?4oa&aD=$^At1+7wO(dTPGuq%@h*&#|tjXwz`6zfm6Am+) zV5Sq?PY~_#(3Whrt&9DeiFqQ}QGh!QaCbl~(1+J1dmfgcu$J8<1muE|LPhb7`hfeK zYc|(=d~o-J=l-}BeZfv_}umj zc#j^Fjdx2K6`s>iSof8PiM3DS{qH-d8K?yabP&DQ-v`FYl{Cggiz~ z`NXhxK5BFWB#lwfQ^QeIi%hg8!=EKEa=NvYs9ulBxgG^H5o~#ouGc; zJKUmwe0obiDJ~=?MSgD^-oyrX; zn=5GAg%NuAC2_mh_bYgRLV2=k9F`D}OO|0iY6uP}wIUVr5r-ZJdTJog|`0X-4SB2g6cayC5SuOMvyw+DwWszBTQ{hGbO-o%YS zY}?mcnWk`X`q#*0G=M8G%X#p_&0 z7UPqo39s9#3 z1HGjF0TJDf?ovBU8vI*Eqv;Mryq1R7talUlr2gM78SGK8Z;F$8tLu?IPt)+&?}$Td zfId-1WW8)jv@!j79Z#vBLj;s9&UuwOaHEM;vFR!|$zQ>DWnjySmo^@{@KNUB=;35n z2?5_uglKJVdm(dK-;#TNapth4LVE1dCk)wc7(b#Lc+$CMD-6HIiK>yM=;A+4;>KxL zK4*A_YG=8_U=8MB19YXsvkhEw3yP>3Qb)DrFYkMDNP&oDQTvXHx9ESjN7Z3HvC;T8 z+|Km)QHIb?A@AA{WO5}Z0ag$7b2kEgtc#LrH^mpB(f9c zGk6LY-tY$BTNh)k>mjtbhBt|h@?_$6Qo~ESIWH!o`iCzWUViVm^ORb-N334E38U4Q zEyC|Fsqqh;m*P&k)f#}|o8AyDBXlcUY4aZP&7(Yn2*|a*WV7KNUR|$PA!FrjYqrP8 zgLF;sm1ICJ_&T(roO|bio8R%$V!X84gp-DE^$$9$gYP>-w4&_v@yB&`dytj6^;D7Z zWI!0b=%$D7<=%RgZ}|VnPYs1#8}%H+Y9~69hw&{Lq(FpxBWXDOOzRACBJT!IWb z7`~O!kWvryYWwN=A-i_J&)VyZO0d=+N}YglDErtll z1zT3^{H*8V1}IMw-=-;EvNFS<-O>5UdU)r+v^)pH|38Q3icu%XB^cN5;jw*5$`lQ6B}1|2DzX-c&CCk;w->-JGh8bhkf<1ZDE_sC-1MVPR0oXT#3WM zt}3(=c*6=rD@x%{@|(A%`BVKj%$y zbGk8zfLx7_o9Z-#7@>uSv(0aYKUZ`hu}k74T|xcGd#R3P2<^~(y+Q9e zX>(P08x5?VIC*b31Q)B~#`hbq5u`u_)PmTX@Yqc~2f351bz`KOL*EXypeRq=SEG;3 z90`4p%wTz;?}D}<&K1QCr2+XK$cv6=IRhcKrU!w+FoiCCNf@#*SvBJYPU46wL#NwO!Vr^7OxDyEq+ZCZ9Zh=C_LA~ zgNU0K5k$cIouH;gj&N3I^x+?O61{x}c3$#_s*S1ToaQ0;T_{gPIUQ%yI+i+O{lu3+ z`+;Z~@xkYUs(I1KNmDUIKud&Zu~u80fjU2PCnfjiVptM*vlXnLsE4={-hZh(5qD-{ zNP!5b1(69DKbp60H-Z+EP1xf>8qFAyky~Q>Ct`zF(R#_9)C&J3p*H7N(tWMX^=HFp z3hjP--9X%u-kB#1NJ8-+3H`@6jV78uSKqbvp|^K0rVl3I6$K(WA_} zVjg8?Blf&5pl|!e(c+dvsmn2clvsZ%ol<=`t#R1sUx-4pAa49@Co9Z6MOzPTKxrLM?`O)c0Lu~s%wSQ%#*0HWF7kPB?a|NnMupli9$E0 zZbj#NjHY&@DavlQR3M7Vcji_NldLl}K7i#450O7Q?5|{WkElgaB%$^<+hz}`l zyv5Qb*x0GLgn(SFoLy*f)CzQV)j5GUbJv=Gd6FqkFFQyG$aV0Z1HHoYP<^wb0-@4o z+B?0Z3o z@=P|ezXch*X#hRa^Q+!`#b0RMOC7CH)R?Y2cn2Lo-qa}Uo4#eQVo|EQsXA_S;<&h( z+m!6PtY8z;SD$0@wb~+;&K5Yw8zT{l>Cu|8pLASD0>Dai`SqY z7}47y~4!>3Vk^A?SHIEq(9dC(&fzuiJDKWK9JvyJ;qGDQ?XIP0@`9)1zM1nB#i)T z*UY4!ZrIcBrxpl=&8b1$Z1QrJR=Qne7A~SKAD+-x=$3*Y`qTRa8r-A?bw9sFAYz9M z;>#M(U?2Rbgn(Q&HnVAf`#OEgEt<89_c{5Vhuhf1K1UfW`_CD3=pP^YP`a}+lI!8Q zyFU+Gc8_fsIupa1LoT@xT!KRl_Y(%^?>op*RQW?8kMZ-mscyj#5|>IPOAu zT83#K-hAmh@#5`548IGxIy(%dp6hzhpW(|y&A;^z<122@X7+#Iz)&Z!B(g85day5l zerqS2mvS9Lt}_Ee>85!ev~B*O|F5evkIQL`{{NFCnM#I4Ns_V5b7$`z8KNRWnTLds zN~XvVBFdPMnGAK4c}mYY+dPlga9uK8TvM)j=K8JYeqXQO_p`r$ul0WRIp^8K+H0@9 z7E_7EjXKKq)lVDU(%y5FAc6Ck$uxC1mvb)^kw-7u8~EmEW#CsJ=WFdw(%-JU+mnkp^jNss!{lK&H*9j!2&AF0}=7n2osd&-#EjX4sih3{n9pSPAV**^{I zr-d9_r%IxFqZfU2r@E4<|3_xcT5?xsLH5rn#k#}U8QUZK%2|_7Dm%;Y=@}f~7N102 zaUz`CO1dc|Zm!9g zts(vkb*m$dw93w#sg0|5y32OAV$AiJgTR#x+rW3C#O)0`$tLTI8D5{96iWu*39TC1 zbNWZi_!Cpi2QTg6*gAe`+?UXsZyYIYw)*OKi=0&m)WR=9`;UWzW#fi6#;s{jlsCt@ z3!m`66JAMKdyR`e|0w?l5;!YSUYs|rWj!{-sMF6)vB=O0Q{Oz@FF=NE>1d?vwO0t# zQlILx940^2E5Ul&WNP?*u=lBZwUk?Z-8MRS*=lm z`zZV+S`8{h$QcFoj4P%A%FZh|c8xw`>Id`t*433=n8_58J4TMX?Q4Ypvx?*I;!3Ty zQMP$Mc`Gr^h(DdJq-<=)`Lk6O0=2MhlWFhC5z_DTdgHvqT;-{d zK>LC6mlTYYbz00eYzMAX2-L!Nq6{>H#>kaafBC}nERJu8TG)^2rbW|{az=nR)!aU$ z?9Y+FUP*V6H;<70_r21~wmPQ}sHKjN9~F8^$_2^$TNM$we?_ZLwG)%WgJjRCWB4`e zQVM}u>V9xvrjLAcA(pRqau+B;Lbbxp`F-W)`_uTw)O*Sf8+YDfY>Gaur9Vq+wVdWF zQ|Dpw)|o1NL*>gHpB=S6+0NIgzB==|v4w~;wox*2bP=w3?c*px0(}E?f;BiqPHC0F z*UlJb;FF-&0BQ2Q_8lxAtf8#1%N-a>kWkx*vX7AS+m+#WUaZt`mBBHu63^PlNQ#+Y zZb>;DB}m}xN_YEukERMSn^}AlT_I2lzX(;xYZ@V!RU&VY`+enGA%SZN?Y!m>kd*tA zrGNdP5U8c@Cfwc*ptZar_xturAy5ndS&DRUE-tOcy2ZKo6(z2QbF|2C#(|e=7p!g|`GT9R`(Po7Fd9?)3n7Bqq0<}W+Zqo<&+iFwo zDiHA_yPMqaxPXs{+^0MhRx-o($WHuosvMTPkj*|miM{ikt-qb|JG*!`fNgLlzuUs1 zeE-(3+L5+%bT;@bTe7M-wXyTgRJqwoWAV?ovUWda>Fl5b-`xDIh6Mf+8OZ&n%ah+{ zo5uylXh_VuKS!7CYw;Yr>IzM^==*6hBY(MhV4VO~z0zFWL95Rf_MV_2fxkp^;$ptYg9jHI2^O2;9mb`<>m#fJK<0kQ} zQ$7kYv>4Usd*a5c1kPg7tLbLjU-fz3&#^>Us$ljN!Sr>T3jAGcPbCJGaFMy+)^O); zt;O~I&GklYO7rUnQ(3x$m;Twh4FC0XF~jz#rp3P6^2m%7-mOMsg+MKAkM7a8sVfip zZsNHq^%OrG`rfc@it;YzB0DU};wS%Xp|pVnKB38!bgGx^w)iBgHEEX-@3u{ESFk3( zMRG-Usl_J!TdkJnf(^|X_E56)qoZYR%?aNtA|C-PTRo$cE&I^BuqVCVtrb=ejx%dgvOfkNOfnM^(hd&!a=Jh?~pA_B*ORnlbrWR*I6 zYIS?2CHL1~g;(HK4J}nLMjQyEJr3uEN4|2DAo104q~32rab9`zAR>Yn_moan$vmU` zTV)uoWml0)6Br zQ{w$j(skxkKD)HNLZBADA9)A6bfBs|U3g+lC4mwgclZr0_tjd<21BNb^J zk5oa@YJxN!h%{=9EzfauqE^tzES+u}oB!E+jz%r58#2JLs!?@YZH^Kousw>*{5eJT z-7R&hprsI~g?-xctr8^N#5OnbcH$^OLVfe_3sWsIsaj^urwj?y`dNRwKI_hHpS}Y( z(|cH~@O{&c7}tXSV)*9Dn1?eYviklSEY}WrZX~83XE-k*f%6#6S2KplHc7$8qgMXP zILEP#Glt1@^3PB?>&S10IfE;63Cv@h>nuG(o*3Rgnke%X&Qa=9nXI{7e9T7f zuIFo@1PPp7O{U4sOUj{xTFWaPI~X{>qP2u)dM4BTu1wapuP4VX9;tY7aBf%IXt%Jl z{Fql+e!Q2&P=W+LEyWtlkCyX>@)N>E%_15+txs)1A?v zcAL848C7AMs) z=`>tM{N9RB7-y$geMqP_+*8-#GP7C$|LW+Z5U7PVqsi3bO1#CB$~Mev$nkga2~~?M z&Yg&#s~N4%93@CpT`)^e>*>xL%)Luv(BVXajNO^1C6%^U2-HGrkWOEZ$IIC3kF`H5 zb>S#MqQli$`g*Ho{77|4ZTQz8D7O!b;m_ilDfT(q?YI(IZh*$fnQ_G^CUvDHQ`7&q z=ur#XqnM%vQL@#@cWlzpT#gbXa25S8m!9<6*?{kDR6zg9|E{U1g*4q!OzCU>o;X5! zeF`-&it)+hzCP=B?9i(nI;RB%6)_KS+@W9Sf1cjlcltg`2t15-M!gim@zxq`j#ZAH zz4?-cG(|w%Tf(ai>nAe{f(?u?eMz@_r`+DC^Y~jD(*JYocXPVG?0nMMKrN)b!u?pI z+G%=jqi6I~Lw)Y^CSmnuwUpBaN|3-?9%Ns2?#cd@v7nwEDWL{RkeL0>Ft1;drAt3c z?Sc5oTa1X`d}WySmw_`U(if(<=+!H))h92ojE~}Tml$i$^^;d_^fFL_gxW^Vg{Krj z*I71*?PlPNjP2nsk)0UB#rqT+`RAKu+`fGxJDM7)7Yi@S-YrXKceb|FoAWg7-LA!~ zk)ZRI$7RWeOX}Z7>{^kguQ}l$utrf@>y0e`da|}MuqSIWcQb3Xdf~x`Z`u+u_=&G5 zENy5TQ_Bd<_>Gyl&!wcY*QaK(GP7qBVaYh;a3Yo6I^Rk(={kmaz4^#``Ny+}-v+VR zK37WSD{UZw?NLry4^Po7E0_yCI0GP|);@Fg z8Yo<++w0qN4=Ds{;T%KtqdNByHS!XSDo?iZv0pZ`1%n=$E6&}kVH^0g^mTu0Ej&8r z8c*K+QV7)g;IxWO38Lp%=t46?i=iEar`>C#hxZzeb07ZCD$&rUi#QW^#aJ-=XUjrpbsJ(qj zixBa1yEM+0sHcoU9C!E?Xbk?=UhJ;Fkg|B(Fi?U7j`{!M`oy?eC-q8EKFZ91vjKhu zx|`8ukO-+UmTm-kD+IQuwn5bj#35ft`DcY09RFurMb$TFC2EP7H=c6Jj6{wSB=8%W zOyc-7!JhRte~g~ZaBj!d0BdTJZ%I!Olu1V$+_(Zq0=3i%l3u>kMB#*Rw(ZF(w$Vsp z?j8@=@wXbo6##$9lDQ>bI6ObdoEEj@NTAkT-$eHHk0LzTo6(4h51S-b2BtI1-8+;Z zp*~go)Hrdq^FB8Cc$z|>7FNZi8w!m_iDh$bsEX2Ig+Q%AY2#U8!-{-Swhuj(!{lM& zwL>Ahu=yHC2@+VVlTQ1N^$`QotMarV-xLD1u%av3S5bq6>&w5i-Q$-lYb}0V{D#yM z?{krJspKI`RzzG=QLD_6Ic%NpN_M^de0mS&)l|f^*rAoKTSK5#gj)F3X~(k1U-;!d zXElQC6auwyEus3(A@#-2Pvd$1{sxLAgVu|>ez;B-B6w6Ee)XrDLZFuVt;QGWEW#5; zQ6_T-ff6Ltr#c-FD%xxd;$_SK;z*zt{&OQ{OqssgGhbC~b! z*iE!4eP25;)P_@iHHHNK66J?`exAKNtn*#>Mv2$I!nKx>CHTGHa@bDWauh@8!gu|) zj@2&J*{9>LlH76bcIqXyr`N7_|NWw6QJzw7%%^9)9<3lt3+{_ctDFj`DHkR2iJw@Hnu;c((Ke zcWK;Le2@j^zh63Xw?Egg9NSWQ?+R9&s)Vr4SI?QB3@XOUP0J=CXHZe;Z+(d8$F>)E zf`Np3nxT1pFurE)w`4aKC_&=!dT0IX?Q&e4TtaQ^%RFxc&CTb({^%u8f&@OT#d}_y zP8u@#-L#Ghf#*2bHtnNAZ6xcqo~PVuE$|jys7+nH%}2risTIz4k95%My0zubCoShu z)*(lXx!YEd*SVX(8yu)b|A3hf@aO;jK9h(Ot}~4UryuzzeV!tSdNe6+q zAdtXcBAfclCVnbv8U2Hy3V~X|r@m;}bN%_fGYRw_7g|2xYfmra6UTK@2-LzF;wDp9 zzlS{ikIy{ifVV=R7T&s`-JM=i*z_C8ZF&a^+%>*GWyf6F)#Eec<}jRt$%ear!)TUe z68`1}N-x1ahCPO&ik}3NFJl>B89PY%&#`CVziBcZ`wGkU}+!(Q!qJ4|^6DUDK9p~MPq#H@ivUrP+LlpwG@crl? zy#I`HtFPp-LwXAQ*B1Ew)c*dv3NQU_sp4}mnGR&zir!)|cjy_Q5V!)U|9OCYLvFU& z!)J9FC2&5+m0@O!&Dyi0uKd*840`jR))RS3M>DVF5g|~51g=E1|Jc2rKbo1B(TUf))J5Pth^Opo-)(UFlQHUEBk~aT z7AQd?;;)Af3MeWl2HIL6td6ir98U8nAx0Pf2PqgOu zgC`MDr9=@?Zk8_}y|$-72@*Iq>2}S*a}<4DjNh0tT;M3eCsdy*vtY478S)uLJ1GQe zsbg?_#yF$i`#L{?YU>Sq`3yN{^ z(w4XJnXD3^g>x|7q6-`FUqyuUuj7=}0Dl+%S;`UrHj~ddXyTEkXoWy6oV6+YUic+$ zlj+DO7N?p;FzX|MeSyaLN|RV!@+|9N^ic@Z!g-!DQ;c^IY5o3Xv(IMmHBE*n>jx4z zA6ss?MGH%nnD9P3xbxFR%-Qst_U}Jy+3-3Utn8B%?e@6Y%(dqN_N>60CA42bqc*>W zyGYC4^j{4S^e3YK`%Z8pR@Y@CbMQS!#F=g$Vu861oyyGS?k_04Z2S`4=1YB6ZHOOR z8n#rQQ2Dv0dOseQcNGyII!Lbt@7UIwZCHcIRDGY%P=>ThM89ewN_VxFm155Fzum~l zoZUnJHsCmm@55Qy#nHOacqbdOb|gF7$4}=M*3nbF)O|$C&n-sa`3l0by2jdG@YL%y z_>(!G>d!XZ|7`Y%IL}-L`mj%Jt@PB-kBHbcwxw9G%0;g|rM{SXx&^DewYiValeetv z*;dTfGtk^SXf?P%t_bT2#cauu~fr;uX*`=4xcdL>bjPWEd$XRvaK z^BHQjtu>o1-xJ6lUbWn)>R7vpcvafSxA(3tjt^PJ3Wir;9szS${@S(7vB70+)ZqaP ze~EVVeOijGPgd#o1Kk8_Vc(rnE|VoKTkrF(i6+jadc^aF`6y3??}Sfi$+#FI z()~*EVQor^HU~ztCj-xGzh|FkySpc{_THtL&yW3V!$Rh>5JG$@Aqb_dox+PZwpw&y}J65SDo1X)KzSD zfUUk*uS!I_8*N2S(tV>8I-5IqH7IE%&l#Q*YLZDXfO>xX}Qz(0u zWv{lSPEX+({Moo$V-80N66(wl_PRgif4FGaoLt0Ff&_j;@{3*>AgVbZGKLS^st~Bv zvtkk(vdKz6R&g~w)m`^6@%Y>+W2Y&P-z_nim6}*zPr9&QnWI#~YDH&@$IICG-Clf{ z!L}*$S6zS6FLj?`)8d!%f1nnw z693&37G8b@My7vJfzOUwVM{gkB#-N_O_%AZ9%uCyF3s{-qodZ!sKuE<{kp+bdx>hF zD>JGtuMnt(U;4j0af0k0qrw+gfvXq32lfRzeO*skDeB+Wqx;nnxRRlk+J@CwA>^hr z>~pZEz;y{%IDA5?H*v0!2;Jn&M+G-h2-L#Whwfk<7L+-u7SEpPE>MC5&aM>M|3MSi zWjFq`ZFPk}Ep-+RnBpOl`lRtuK~0pE6SY)Jrr!HjA|>UM@$un%j{hxM9M~5qQnqRb zq1(JOd}1ysGXrWNP4;f8hj6>>PLY%AIodclqvBji@eB{^iyn`f$uP?8gam4#6-9S5 zrqvUDD>su9y9aWVAmQRG*xfy|^z5US%oKn0(!^WtP8k=5a+Dx}vn!oVtZO2=`g%xK zVueDW7FuU?^Ciqr^jK4x?p1H#C_w_}W6F}&x|gsYcU$XP~O*8fKo`RJK)kEt3!|{valc@Gpw_nW#Wf3&~ zXzC_Vf`m_WCX3r(Yo7DSayNtO$%v>8d>nPBKoUAHN3j{kw$MuO95QOvQt(R9;3 zjuIsB-~8`3pg2-Ez^D|Htq`cCzWIZR9fV6lBB#nH0_Q=rigDLRF%wRWsb=^h%6nc* zAy7-5Md{|GFhyJOQMJz~y&d*Fq3#WuoQM?xnFTEGk2T8w zfwKhCH1F>2A|gFkvE+(hIZBXF+vr<4Lj2}4&nVexFGpJhzbJlb+R;}SEGndypgW^a zIocwqg|m{$bR{xeycx8PIe9!$W*_WVXg^qL{f1M8yl-sF{d*iGNZ>c5dtRPBEcx{L z)jLI$uZ#aV_63tEb5Wp7Nx5mz-8&_h1xCkX{5Hjf$F`QUOB^-Q=U-C@)WR$bl*h}p zw=|uo-^!8)0`D~7eFMC4Of&WK!Lr(i(Uj@-tda!^ZvZ20GOeBJPni&^a=oFm#5VAE z@zw=-abg1~hQ1j;w6mN<2@-f)noiso2hg2{?Rq{u45b}pc3Zh&M?T$3 zDK1fhgc=u~;^rs6$OHUYl$}DL7TzDF2vgrqvi+?XUh;NX6e?$FC{xlY#pCUC6ayG$s>I?@T|u63V~YKp2_sf-IeNQ+DVUg zztkvJ*mI)gWHNdAmJzpFxXRVt-zo%Zp%rE6yLH8%@2gAUkjBwxg;C5ZLHVylt@^jA zBAczU;^4j(qs2@n`@fw) zyjVz?DTP1@61bvT)~ITN&Lxb!8ZfdQMA#c{F3hE*@hTM)WT>O+JBTSK~-W8n;(URDp4;; zsB?Q}jH__}=5M_5@l)O$-${LsE8i%W(-;q(YW*s0;O}DOh@~E6C9z|4s{Yy`Q1M@3 z><`iuhpf@9v+?sSYY5+v03uzgiY+| z;Pc{>;1g1&kTve2W!ntBe-u3xc*u z=bn#Gn~Kw=M|4ewT6ptezK!A2cw(+@l>Lvme1ok_n<^=59YZa=d!Q0i&N&In+(LFq zfZ`FxUGb1x?#%AQOCR4ZU+AfRM%aoeQ}>ehyq&-pAGDCrlTNF_*79O}kySiyL>t9h zi@si@O{N!zOaE7O+S;zOvJ*yM@9Tx7*x8+K?C!F6^i+}2R1@G=2VUvEN}v|L6IEoJ zS4u3JwBGD?Aw*P8_GI0s4mVq3_0hAfzWJNCE@Im7h5E(tjtYT32c&6_Q?;6CP@}X_ zp?zD$GlA`)mxAV!hHm24`FRw%+)D9&pw_Z^Ral!hU(6qz-_V;serGSX*oINH%}xR( zNML)Gd%`6xwx|)@L5OEx%ds+_YU)K>JyXsK@Rum#$-pYYd&FsDWtz7_pr;6ZHFUfG zQYp%$`^i{Tuby%?f$cRf=E^Ev?5w-VKj=M9R;wmLXZ$e29V#gVYN5x%WUB9OFRb#M zuR`=PS9{MkbeF8x9|l|ce` z`jjCy%T65s*iza!UguAHy0W@i$@-3Wly?Hoage4Y9#1QZ?{8YsJ;mP?0=*PSn@rQ% zT8lyPK{U=6@<`VTEU_?MKb=2|A%SgMa!uL`*Ug<}ty29J0(~b)(?9s$R;14lkrzLB zDra6uVB1u0;-Q-eEn81++_!?GWq}q4o_|pU-I7dW*2-9U$G4U;Cq7?w*4*UyRy}EN z6{g<#`L*DU5p`^kELy51n{c$6?q{`HFR`JLl9yE_?$#(K`v-){2i}Vn0<&`AeItrB z`1do#8uXV`hljN(?WW&tyFza;e*i-Q+op(=ttI56t=#yhsFeLDoC==UYN9jGPy$mlmMFn!&Gozu_ zw>Ffs_C=WfG3g2si>J8CR^J_DM0jz563nHBzht=!P)e>UUQ%}6P*us~iFCELE_z{? z7J8`d18QT`V^{e$ypT>B+yqK6TPU_?$tqt(`nJ4ac>8$?%wUBC{t`tec)7{(W1@^g zFD5X971DMOYU;(qa?B<2ENj$mb5;4ZQBAtH-B!u0inL0Q*Ia(Q^M`)&-|h;5T2w7v z9~##)zy9{`)JA4aCwa~M$b7nHpg;-cVpTJ%#!`LJ^%s9*mg?+n+m_d_@1LM`8}&`e zTZ^>GWSeLscdaPL9{e4u5U7Q1Q{BEIHZpK)30|paFA?HfS)UvIP|KM9L1_cqrk(KV z@>E^54nJL|vqE4NQp|u$rvQIj%TmijdGSx(1!`e?XQoxu%QS4l>bxkVZ)G>aQF_`% z^GOps3X~{WnUwsyX|1i~+4xlMu&Jw(Cl%?zr^@Tmw0IXv(c#Om-V}nBPkD6By--5yqJ5 znCy~24jN8NPw}7E!vsb#B8^W=IcsP%-3T%GwjP1Xdmy2<5&g%RTHw9)gq6@Nc$ve=LsYu;JiL;E<} zhHop{F8^jsS?xwKTOQFX+Ptv(OU*yI2&Yl|Y@dF^t~O^ACJU4x5jvqw{;95yv;fzl zMC6UKGeQfa`TgbN6#}(dEQm6%4fkc9&%e=Ag}>ac=lz(=EiqmwK|*~GxUYLG6qD!atG9jskXMAUhJuqzqR%X^Qq4^d~IS`^R8+a^JC8xcR#q_QFkoYO!v&* zd#1|8FD@wrYSp{vpT9UcTem4clD^f|TSfH>-$zONqXwND)G*&zzDnOY={Gj=+vrwD z25i*3`>keM9IN`gy17(uHNzl+?(gdT{tcI<10N~`Y8|{%!MrSKk?vL3Vp&q9O}(~b zZ%GmU0wqXnw6AD>d~>#bVe0Qh3{P2NepDDD2h=PrP=bV!*}>=Ki6p(?qlNIe6R-cA z+fG_Cw;+L9U3Zo@$M%WQ9|TxtpF1M$GUj|;ff6K~%C`4;UT3Uc|Ez^5`A4RH zWJW!yd;2H^YPqJhH?K|Xrnh-*>4|ivrUy)Om*YCL6DUEVc87{S4Lf$#W$Cv>#8lX= z=XEF}ch&B$5U90oV0rVuiH-GRw=H{4XWOE>Detq5+u?p_i2&X#!;_U(u(?3 zPI9hplli;h89ZDeQ0rrOIkQ_sd;QH86A{r{cj~2Lw;SckM+=l7q4wQv@f~&RNh!vS zwc`Xzkic<6bII)z`l0JP^r07~3LHhKm3Pd?$E0n_|Jm7=o~m0XSAA6Ao7QVjPg4lg z!nupaV99@U>-x>u8C$gt)WW%v;>haU*Qd^#B8v|x#`jm4Vy^#as~(&)LK$7^h_cLy zFS|{WIY~kxP-|K6WOKUxM!kPC%N_SUAsKptHc?V8Q;rfOa6DRa_W!OwejO{%uUnxI zsD-1M?wC9tU^p$BB#Sl*XSjnvZwt;b)UQ^yHAdUT%U=twCjwU=`h?3FQRfr_wY*DiH9Kpm`uuU0=r(O-EhEBZ zkYwu~ag-o|bBxI}Y*;j(?NM92;TW{dL=*e8LKWTA34nGdHMMOwTs|r1zkjfJTn<1!H%y z2!RqLaQs_pj6@le)@(9TJC9Td)Y?(%H?#HLW9D{8EVGZLf?3+uWk$QmXn_(WaK@my zy7}{(n;&{i-Dz zk~XN5p59BG!!UrUXS%bHtkUNJT7wfRzyWOG2M ziDN%jd*a-d%gJkZOW*J%Rv}Oednj42e=IP3XAWVN(#MHOLvETQPXubEY>RNzQhQ>x zHcO0=wTshDp|J{qTAAaoo9Bf6)Mn>d#(BoLF-F=zFFvaNIDrx*a0fuKwOXoizS&sb z^jwrepjOk!Yvy(j{MpeS@2L&H%fpP~SLgD69?=3NNZ<~Dd;s+*hgawpe*EJIg+Q%; zRvtDt-<8hZUHyyNxc;z=pu_pd{79~!qH5giL|{`+4_Sq zaAlw{Jua#j`&3EyeD<2*=u*eWaUqT8R;P@R*j@^OT2o(I>nB8^d41exdJl@JrFvfZ zMzeGM1xk>>m59#O1|KxuR7^Hzq=zd6YT?*4nGWw?Z`64+#RxbVsfhd{A<)Q95=sWyZ5n{Gv$UoKN{O za<3VlPY2WPu8TsT7Wzvmt7H5zV~ba~44X4a@p2-8s{}=CMf`3gQIzTS_2-TIj!|Y`PxjjEQxd$Y+ZxDt=KU za9yDj#hAayPwh(9lBYtTmg=*7*yMuY`_hSWzBW|+qDWxRCrjqTO=Hd9KaHR_z6zme z!ML%kYR8PJIm!B#CnFUPB=%RF=jrBTtINid!5g)p>=6oqTB>)D@?;qMdXHz6qgwGm zB7y4)oqvqFVbCcuXR9L=0=3XnNNdz}X}Gqm#Vt>T5+rb4A^%m*??$9Gov+**tPrS$ zok8d_xp2sM`PTu;(%e@eP)qd=(mAT(YMmWn zXZREhHj4Hdpb)5qql><-`H2zjXl=CoK1e0No>M*ala9XP88-dp%0tf>W<$htyk@Iy z*|E>-^t6-AVwbEcCX#)6$hRL#aFigSp7y0*f6gscT>9=Ps}QKAo+uXWb%}TV)Q>8r zr70()M+RQd=DTO;gPm71mDuibn*}Tl%+$7C@b+TS$?O7r=%-h8*HKg+I78gjM7JAqyI-#=- zfAqY)j9cI$P=ds{Z5_2scgN_VB`kipau=7g2S+v8-@mRxpcZ=AC?5cu&th0zS$w-D zP=W;d%S@(*u~%6boqJjOE=rI%ys5nQ+0{=UddXt%>cz>beBMh2`yJ)@AK+Q@@1}bi z-B#DV-7UV1=ZEj|kk}5g*{mlVB}k~J;Z@?VaqG3s<+w4W1rn(BCABEi8u!xwO}ImC z44UwoTcX=?e^wSKK>}j}EOz_fU~3x9<`EsU8VUq;#2obr+J45Nn&UR9H+aVv&8#c{(S^5{{95NGi0ce z1!{!0L~A`^F>|^6l%g;GH=h(md5E&h*v&c-Jw1ZwT5 zBZK%LeWLUlVarj1#6s(xS_t2)-|at~2ur2S8B52@HXphv1ZrUqrC7C#<9P2YW8`|L zM5XT{fxVJeob`RUoGj$)f2s;xm#~ki{pw`EL|(L4eJLk5PzcnrD%h^&zYfz&cCb{6 z)sFb`FO#auYHivm1Zt`4;Fh>iJnjeG^YRN2C_!R*e2(_osgpXP=&p327MxX=<99@)4&u#>FS~|?Ab3R6(1c{`6 z+1l~?^UWC@EGN8ItM}zT{&b35VWL8y7LG@g$+drX%E;A|S=EjgI66`5RKsmrt#U22 zfp(U2=LZvOQk7U6zB@!EP%GBmUh6XSZ>`ZX%Tq;7>%~u0YsfbY9WPLVguJ;$3vBs8 ztM zJyE)XT;|IJN|3-2Ono=wIL{wrD`%}10wqYGWnigBo6BP>-8Xy!LKFhEa6D4ps2N9j z592WTszU`zkU$%S;>iBo#NEFoQx(_Y3V~WUf=#9`^$*dVyS7HN!6O7pkU-0cqPzpv z@Ph-d>RTGbDg?;&fAw4g71YLZB9odAj>5 z_ER0~V=T5xlt2j*XqTEyM+dLrE(z}3YHYMZpcamK^2xkBK+*8sc!N$O1WJ%VTbq2A z^Vf2l7SsQ;GLS$moF&NPwO|hqJ-3uH0)-2dAc0oD$+WfGLdr#!&F@@|Pzcn*d4+s3 zc^mo1I|upEivtBpkigvw?NYBU=NBs;=WDZ60<~1Dudsm+yLf>rlRUNI7%hNy5ZWu2 zm?B-vT^KL-zv-$FsD-|P|FOvKTpdqU*{3O910+;SrdQZ3_M~#8w9LKe1Hj)!TboWA z0t48$GbZ`GppUZKM*9IHN64ReEr;zI`^=zft^y@U;5tve-7$-$^)rlLdqyb)YT-Kn zpZ9}Z9lgXDe<)5NPz$3|$m%<=l5LyN+lcd3W4w?+%Yba^R~^_tFHOdvl?h5z7;2$C zPxa{cR%7{hTQWUkn!vaf)I!UEY=)Uk%SrmhnmkWX2-L#(JBoDrmB5-0uFc2Po@a0^cz+Dv{dl56pccm8(HOivf$|3>^PWA&3zQ&%mI0kwW;ip?$CzwDDnKRotXU@zkq<6PwBZiF~Ha=p)u&8E3 z6PpE&i5M}gcWlUn(QPAR$29x@{kKqG5OyuAPxBl0B)gNwYm7HGm*qJ_QT4wH#ML_+ z$xCZQqo<_>;*^tivPWziHglj2f^DUm@x@}Tt1YFR*B^?u-zm}lJ{r|V45}=W)V~YD zfE^|{y>B`$Epecb0ueN@Op}{%LW>rJmR9dXH6xZX?>a^qP{zxET*tq;NKIZ8{y;psQk$0Vt05cT zb)-AqAD80u$~9^W;|A`QN=v$F>&_#p%yh|vf-Ic-wp3s8y*3<%Ft*VpR)JBZ6>8*Mn~N z)s;p+;B^HNr6nb7bO^$~qojW0D&=U@7GyuzkwT5mx<6MsnZHP@A6~njACD-@s}Y>s z(1Ahjw|{n^P@}MKJlYqFEqdGi=#Rg%YEj?%Ym|o{?YTaO@}Ncp z;ph%0lHbxxynEPz!m^w$mxy}`zk92#g|Y>qYq%RpSgNP^k9Op01rcoAit5PxS67t@ z&1mml0mS~mg+d#tqpTC`k7|rJ5MQrtCtrHm7d?D^T5LbRtsK4}3@x+rWV1G-z6Gt= z(3MzjdRz=C5CPX1L3pO$f-W-aL~N0dH${V%Ki zF9@CgXhC)@_NS@y9(k8VyPz7|LS=O<4L{rwJr45M%3wW+ddv@#{~f!_?=~l*T_?&$ zyC>vYk=qWnzS~#+_K$Y71H_%X79>Wmt13es?f+3A0`7^dRtBcTFFly{_#klz$i=sV zKCeyAy7X3CUJNM^0e4hEFxRO`^8X5>!_H?Pgb2t5btnj7Gi#Cg&V6auezP=?3+~7~ zBFUsKNoW&7lmFSp^#?>iEeJyDLNl^#eh;cY*j$7Zh=A6BAefvnC%b}zXtU3qy&(c} zK`pTPaeg>X@=BzJ%|B~S4ht8U$t5pOi%?$k z-M2)nn<|g$p^n|Ra~I(uJtxpdBfe@N1tR!bZLGBs2OJznJL_%K!1)2WU=3Nz@nba8 zVJbyO+e&BULmJPb+1k-QpSp=_MrLV$Ps~1~>9A|Iwzh&$Db>VY^HS)p+r>qY0uc@e z+{F5wv*g4bv8)|Ezw6!)h zQmC$Tq&K8M1TW)ejy(?dPo`NH2WcPzazVWb!sbmP4$4Skb8rOL=MVw=Ul8j29jHvI zm_oPt>K4b3OqM<@$&f#^))R+)>nXk3o+Po?vrcv_)J&O+BS>qkvG+Qou+fh7U zyxY4_ldWw>+lfiVy}!=Z{uYFp`fsJnN2bwFFJg)ycQgcOM2WmFFtB0r3pMl&xC;$*_xTZ$6RH4PXcE|~7^SX*+_3wi4dY}`%xVV<`rimMc z6o`PfuOQg;X-RjsSgO!47tW@JXdW>#wk|#UtXMHzCpm zy;RUJjt(j-YFZFcc47VTt6UfL2xqm4~z_U8k*IL3>9GNF?5WOFSAa={pfAe1+)Mbq6M<82pRx#$N( zKzV}Tc%wDl5TDKbHCIjsESHbTnB{*gXEdjU5Z?G z{j}Jpqp{pzW2_wfMYVVD>Q*W_dP8WP3H`kx0&>CH3c{yTb?J!Dz337@LuundGxkbP98Q$`*%UO_e7VL>Gh{9!lHp?K^YJ&2tk``(!f4p^seK4 z4WvNCYicIXP8jvWZdWY;SJx2c`p1lD(wd%^P-~k z3>-ttZ|u~-k&zp>Q>tv1Cacj1*#ClHxNo?!Rg*|me~|eZ(*22<=!XX>F%J^`@E|4T zL85;>$bMUADt2a*h&ryApYb0T^UoyaL82cXBtVqTSjxs#JUQ?-MY?lzgY@QV8v5Zu z{wI(5i4yZ5(Z3$#f>R5WX4@waP24%vgZz&IYsh>Mu_eziiDw^~-eG z$}r%{DEz5TB4KeK4dimYw@e)JARVEOEq_CVof(hk=T9cgE7A<>6Dtn9lY#E88X-ai zEJ+YHC1&6i#S_^%PO)b3^?Y%pXFAF~)r~{Ik_4fk|75(P&17w~mU)mO^B}eT5!Ydj z_$N-+{^k)O-LkR9ZX%1;9x8$qh=8&Mft+Z9J$EFNd6QQcLtR1r;iW^-?v=gG7fq3>RTZf)Lff4SCL)Mjnp% z%GK(2^Wz5}+GV45hwVg&W_BW55ts)_?9m}_NP!4mM)S*-$a>i{!cNIFu;o*a?eu|v5 zdW>SD25JAU-Ej!paR`fYsyhy1do5D;TDE^6w)Y`*?}KPTc(uMJDd-w*y${<$ih}{~O{}|7v7sxg&KaF$mVAhRz->B5}Y-{Pyt)?eEbjlGRE$ zcom1eVkeffPI6^It}ow$v|&>_ReYd7hHYY} z`tkR0KoIMX8xv(%D_Abnv>@ajZb5uEIa2+!b-3o-vs&qS!C|<~!+lbuk%Jge5saIq zEYkk{kBePctvovzknE0a>Hf3pIST9p*f-i!043$40}U9T$c;GI4yZSFcGujF2HbX_ z#odY!><`#$#Y0bMwb1l?D63WZPFu3!z5{KR*@zoIuuXhB$|P5saMyu$J(VFt8L-?F z_e!)f8e|S)GAuRkmEdRx)!tQLePONOh+#drBu9C)qZQfN%8g$BYnF6jVFte`oyCBDM}lLH(m2{XppEyU|A7w@K0jS2})7ro1_3jHH&t z_F1`U&o$a84)hHLA#QL6ejv7{`_5`xF0z)(YRh4~jI|uGmdpRPT znc0Z4+CJ9j_1UDdZ-(r@< zNAT%GrqtftUDfV?dWZcnbXF&%ICoTKGwqICY)Gbcs8HfNxlu@g@x=K0393E)qgF%L zw5HGGY<9NhMqvwKq+rkLbQ!(L`!TNKFPYMr5BK5TJ(zZZPN1$Jnyu|0%xJ}#jmkbV z4TU`g`vdAt5PGowczoryGWd=ghk#sA>w*wk+mbxKz70RoX;0xifb-)_k5TCQk_JC| z@awiZ#P8xIyg0+1LJCA2-0X`;`#^Q@s~Xu_@(920qQ;hfMH*q;k4H#tZsFz~ z>ku`H11S)}MhRl0H$jN?Xp8&NSqmu;0arUg zn10`e6s+&Ays6~RCg8aN)EnEK<6KC<_)l`$V^?*w|EE!iI4)+R;}vUvoMwF8){cBl zJ0Ufk=Sd+2BH#&xAh5E@{38h{(7=sDKrXlktC<6tc+qATT5FFj`8KVI#QZ{Um+JnU z?F(%!cB;?Ts;~_nbmpPP90GEcRvV)&DP?y6vt(Et5!Xy}Wty!^AO#|LYsu366OLHr zNmoZyVu*lTK_540Wt2n)F&VpT>k)Mw>Gt9xh7^c^R;D0`@lD7J7cWZs=5h$g^|9)> z6mq_r_liQT)#qb_?}d5LW!4S^+PhG1*ACP#R&{vLT=jAOOd5|&%Uoz_x*LapT)bCQ zCPm5>UY@jh$94o#AR^P@qDGbBcwUu}d)P&Zt>;P?Aszv_pzX`fg!8kM3;R9ji^nYp zq(H>Af4YdO4ExclkCPcGD^7P^=$d9090GFjzQOA^HqwG8SCu$z+%>v8Kkw zE;M7)G7bT`phYeSw)u9nud62w+U$uT1tJP3lxSuAW7D6>xX{IoB6jLi8I*w_0&?+| zesHIDR0!~-`|1VBkOC1Who98S$gdj8WP}v9rCy`hxH|8xKm_E1UWU34wxE`t9&}q~ z4(D@1#GE>NwKCdTjbt*i7u2Jj6FjK9=`jugx%5`f*CPISqI!^-?+j`5XcxNqz7w>I5b=xR8=Xp~9^0pLGAi~~! ziFRe!QFkJf;j?})QvCw!>aH9Da={n}^9^Poye!6zmh^X|kOC3VyBCC%#b-}lhSdlR`ZQYaNXLjblgxg4gtBKch5ZGj92*hbq~7Wln#Xyh}d^O zS1aQ|moZF6#v5ZY?|}lW};K z4XOFTg<7~|a|p=AM-6%_ZOF=39yGR}y#gr^VWpI4WlTAt`selkawGa?E_7h$#xg`e zE*KAB5y<^*$za)oo_n_eK?+3hJC2Q!BiX*+g}yKE%f(9|7u>G|VS&e6T%*r9B`3HO z^~h|1jwqIz+-=Qqla9~Cawv{KIskLqfP z4wUr~H~n1?XB_?_dUmcU8tEG0tldUvNm)}7>lrdc#Rdy8!*e1n@f@P;9C$-xd?Hhm z)WDQcSiJw?a?Q#-6YcMa%sh=@N?rE*mbD%^f6F$D zP11~Se1subMi@ynNtF(lo|o{hNYwjY543rv5sp4T3|&tSN9S%e#ouux`kbdh)i2a% z?MSFri&U9~(j~L^qSi;>i1zMDa%~5F^nHOH8r5~6T+Ln|t!~}~^?w^FC%?5|G8{fE zLtXQysyAP>br0&Ct>xM?Cc;4~$ zNJT8OvSoKv(fFQHM~=6hcJX?-KnHyKq*R34(1T|Ys^A{2dhMricn4- zTdzJQlhco1ppR_}W z$f4Q2iLxZ}CejF(1>Kh+7nIl1Wi$#}I|xOXJF#{|Jf6x<$fD%|a~6vu-V8-g|FT1h zqKDy#;YZ2iD^tnVEp6oY2m2$4n4CHSeKxQ`nr*KUM6(|JI)xbBnkG-G*&aVk9*54D zuNKcWEJhtSCL@+*D0yF$Ov1J(Fhi z?t;$FN8O`Y zzBJrbje1?}H-!wY(M&mA>lvCvXQQhl&J|B}*GG1X(~;v}FN>Qm>V`&Euru6CJtVhw zDq>`p1d>~GfU=^Z9flN$fbC;Bo9PqOD5vtuQ5ta3$7WlG=s1!PtMkoie2$1A1tQkZ?T$uz zYvd=kYC8_@BjjY)N=1mhhcmkOKp~Gs@o2yUH0G-tiqcF1qO;$*`2i7d zjZtrmOd;l7zsaG;8emu!s$OZ>LB_=q6Td!c<`BgM$ zd^{;@706CzMso4ggaiyOeUR!zsR;zyK%b#+yQtQ z?E)v0mnY1Whox>9QXt~cpa?_*zKU0SzGu1`ljKS4Jgn(aG7a}@@5*M*aB*>lF8=(= z7p>j5R{RodfVW4xA~P{vw0&2L?SthO-H7hghT5FI?1o)YnS4&Hm2Zx}UGhZc{a1<| z8=B&PM2U~H6JEy2B3oiRwFxb^xQU^K4Cgk~A+s!JcO<5y0kx<#UMUE5LsRF@ z6Jt%xaia=9bhK=%xaCz7Trt-JeS4KD7Vm4qv^!!~H!`sGSLKuQMg>wJVw`s%vJ@AI zjT>1rM6>L^ntQ81-8g3yrAJF1( zJn!g+PqyueLc%s{@=rKoSQ4{+O8b*bw5LL!yjCCra={uho8d(tlB%;z$)5W_ffR_~ z+hOy-kK9>NorVpf3ZzumcSEF4oH)w0>2Lk8`N1a0Tfm&1`T zzdpKJWsITaEC_)iQ%DMNSBl3T;B0D$;8(b-Zn5N{IFaoJ6S*}Ja`C%C=;|2K+;@Qz znwNr~HSLFLJMIxPy1(MQMu=wi)v__9XW&YOou6|E$YuPw7iwK_PdvOuT}9ss@#L$| z9EII|MUVm!uuaSYSe#7OG&5wU)yE`H=O}b)P&;JY$O=O)s6#c1lT0p$DDv2KIvDN% z(Eot)*cppoGMQ8UST-uWgdhbX`2M)7Ol9{ChRLa8M#)e*^qpaC1;O-V3UNw3pjo%D zNQM-M;61O0vyzF?g#O~4akUhPfLv|2#-S@Y9%#)BSEk(v<0)kL_S#B8|BrH;YT>B3 zO!E*AR?u7JQ7a76CVy~&k)BxP9)=I*Opal22vnG6FL=5y7^jMbCoc}(OCh+ zY|c|9@JNg@B5xK_&mc5gy5KfeGmwdnzPF3e5%Y+BY2jq~xK!mp#%u*rAOgx}D}z&a zQu3@^8Q9uVfu1{*R~ny&tWqzD_CZ}(txDX7l9Z3#l$A4kE06*aP&Qky?j@4+zOB%J zs!$FAx%eL3w=t1y%{^AM{d2eiDG&km#!mZ=B@zG8mU4I0ibFsy*#Cl{S&~Sq8+1_$ zURrY_5%xcvT`ZR~Xgn#twOkq5sxg8Th=8+M%~cyh;;&v*d}a*AkOJ);xW=%cbKCwT z_Qh2tWyex(ErAGVISInD`GZNn_Xm}6AJ%XP$i=U4*;XOMB=w?lJ?$`t6o}w`oFP4X z6T_w@%8DLGIRxZ_o*uhtF(HryM?Y5{cRt6(;UI$d?n)c=WR~S4rKj~C4gtBK$I5ah zoVt*Q5jwQ`qitMd0wSQF$ZXN>!DNbwKqt0Y#33LT^l{bbc^A@TjS)RED+5CcL_p8- zUm0hg8B%s%jYB{#-giz|)R|>vHl`7ezadD02;NJzIWnBYy>(UY)z(p9EDX+II5!2M zQTJpbuTa<>0|O2LxnT5*MF*pk*qXQw=}xs#AO#}e++A&H)8kUuayT^*siS!DF`1)ZVHkdt_-nz9CU*2^`yz+3drd~H)E}9La z+-d}}2|=q|X@v0>&MShR(7i#8&~dM)8gf^Mt%(C$)*-e@m_|O^h9Lzan&>x08{T_} zgYs%JL~83J_>gI5db9aQ4#D~dS&b^!M4YIBzb|_xw)kG+Re7?CwPR$fB3#2Lj6RGw z%(Vj|_y~Q-iaI21RS=ERSm7P^t$&&FHmJ4+S(aiQKuR%OV zxY5PK9&@^a=LXPw6@+TR^+<0=2O1N6kLy8*fc_PWE#2HF8s;E&R%B1Q-7*tT+;lI_ zto*|CE(k1lzPN~f*8Vm-sUsOaf5UzcT=-hF{}4d$bhG*&#O*E5ik3GNSU*Gb!7mwN z{f1*`Xr7EGIhShi^K{Lcx3#c(vau{QOf&jrO}ymbCr#~oEi^+)^ccEMO?~v$C!E&I z&>=j9l{+rkyI$KGn7z^?X5Zd?@W3T?B$kwvh!HNKbT~F9JmnWct<|p@Zdl#`Rhaak z=_HqP?AF$?D%*uDNp_S*#jF&sVq2qI^zE8&`;7402|L81;&YndP!s&-S`Tr$Ux8-Y&DuvInmR@Qp2QV~r)UbiO)-yda^irvj@_KJSath<&hCC9RN1di%+O>#S7k&bZxwaJ zM^Vkfv;Twm#l=qSTyiuWtX0I5C3{5Q2C?-0_&xuF_{GKSu>aZ-dOq9hJQgXM*hZUw zb-6>JrtugvR+b>>C<8S08kpgI_jYLxhc?xm8QXyUUA@hC*1ZEQsM~__lwSxH{YxW3 zA0&}keYDwj)Bi#IY>v;T6t^Uw=(!9R$ucm)#{a92R z=|%5}ROfazMQ!1)lUzZ_yPKBX6mX zc^RD_*y5Hg#Kh=U>covJeohF& zubIZYd67k&6~j)U+#LKJ@pE>uc*)gMD7l~wy*1y9LM}K{VQmHBnujG`d&Qb=%hqrR z$i=tgs#`mJHQ$A1Mmll`$i?RYEE?JvAO2?w4XJ1)!*Km?>rt;N9}WR?8~An% zUOoq>E*wVFPi(|+M}{^$Z?{(l??cu>cJ%Nd%w>x}&w}?Rh|4Zy`O=B97bH0ZrZ1bw?-XK>+ICBMFzI* zH;$&>wC5-gQTy6u@xhu`nl{_(usOKolQrpV@5|m1vXEg;5%d$_nFX8YTY^c4M#jv$ z(@~(;0AtpCoO)!rAK7%&l3I^9*G*nWGDnJVc+7<`|;ki2z$EGt9`N zk6r1`fP3=Bj`h%k;hv&dtSMJ3h-R-qH7LL{?c(U7&D9X>gO`uLi<3T>iR|@C%=gF1 z?i=s`5=ZZ>h?F4(BH-@BBHO}I9JOgEjeOZ(v7WAne3TmE)+voJei3vCJ3ohh2DI*Z|H{3fF3#Q?%ihggiJ^3efUA-kZ|{c7qc17^CxHnDhOAB0P0^r6;^bqMrW;QGPObHf`waYAtf zofmS6^Kl>-tf3%O)jNRiDubxq;FSvODcB!yEC@n)%U5{O#@=*#jdTT$1~~G0#PN9- zFpFW)&7M^f9J_Gj!;)Cs=jmtccr}bJsAtQ`fCwm05Rwauu=*~p_2T9f?n`hae(q2c z)#-dhv;B^GGP=wD5Z=484$U?6;t-Gv?pK1a_h~$i-(y1;o4awl8njEGY(ZFV^Az=5 z6iLHOPjePBw9X(}5H?P1gg^E1rS5|oQ)m@KE@(e6|Km*so3+*Gy-+U-vpiwlVVl^^ zu)J$Ha6-f74nhRXBW1VA=dDCYKauJW?Znw|aO6XagWb+Nmx*=8_n_??R->@) z(0YY^!?HyNFTm>SOhfdWatO%9YZpB{i$%NPba}TW+?ojO1UO>Y4Wq02WJ!)Mtz0H^ zD|NP~C2H8#UflS`0`p_Hqm=>K)XtgSih0Sca1c>8x+x00VJz-C-jt227puNtH5&E6 zt0skIK`y>OTHU*h-JW~XI#cvG1muER5QIcmW3uaDFrCz^1i>gE+-u<;%x)sxWcT6k zS+O~o%k64#C*$|1Zm;W-*IV8xqP`uKo;jfCvj;U(`&x6E#IQ}wSNm#4vYPBuoQgd- z1k6c=Bb2=_+NloFEZnNx>PEP+3laQCy#BTY$ryM~u{+n4!fXLpL%vqqt!&9(dp{{D zQFS>4d3bYG^MHvbXIHIaT1*d})JWBe3Coi?Ba&%zt}8}?)wz)fxp*0gDSl*4*(_z|L{o0G!yFb^ zTS3VGsKaLMW#!`$H}3WT)B?;fXKx6xm-kMx*DrfqA~Lkwp@j@rBKGcw(bXThf-1z`JH&E^1pC=6PdVDG(#>43GmbdYg6N;vwaf-ZmN{057 ztu|0=HaEbYCC8+})agUe>hyEED|^!J=#JVc&Eqgy=Z5ReOMfsOX9j(B%) z5}hNMB6uGI%HUi6{nI+^K64m-(`YG9(d#WTpFsX{BnB-HJ}fTXJ4yC?I2dK6%n+-; zOqAK1Ppnpp!WH~==Ri8G*+vX05HW7cK5<>xSb2E2=?rl#Z4J9K+JVNsZAspAmNbtx zcbA(PZ_?^#mCYd8X6>nk!-n3Nx`~J-C|Z`sff?u4mgw(K#hnt}`tM-F&SP4|_$*E<2X9 zT4lU(#D3eo=(!AQ#k|AdGGsgjTABywKhSNV! z?dK4X3yx5hrDtb_8{QmEmlqarV;3U$`KW&N#L32lJC?$yAxg~Q5 z$fabQ6s@Jhl^K`+4Nvmn2|v5FmGKluP79{<0o0-JC}`%x@@HIN&Lus8XY!M!vIzaKxI zzDOn<0&?*?XVIEa8;&@xcJs8fX}^=L|I z?Ir}?4fQoNK;q%4(yJY1C@;nwEo^pEdbCNs0qQi)gd|jJOhek#Ch*=3+Q@)l9wHe^}WE50uivESiVnZD^lR@NOvwi z&LJR|S+*7O-qA^RQ(~En$Z3s8%GS=b^B*jZ`?eL@)FM>Qx!}#+EQL2tSq_VT71q%U zr;}@b;O?cuyQpvmv-^Wq#$;x059)Q@6+;R{K-nx(w4xT7d^m`XNs8tWkc(d#_J%Yf zqeBRN(s?e16o}wk?!Ui2S-w=mzO%K5LqIO5H#SP5-(Z7J&FImHCIrqq*dMU}*&8Is zO7ODp&8TypEr)V93wkD7Q5pYxrg2z?`H|p7ju28Hw1muFN5^IOw z-#9qOhJ6>HF}M0a1e^uzEsHx_(DFrNXin_D|FObu^5lPkkGl=WGVJ z`#_6>#bj<2W5=dFsd?Ai7*ZgDUwyus@5Nc41K8WnIs_sh7hJnoc7lICe(T$gF8R=! zvl$>4>{&r*la`4$=-bkg^{yNOa`ARa@z`bTM6nf3XyeLReGmbARuG0Hrr`BUY^nQ9 zcMbu$;Lf0a$!sY07uZ)FoLX`DiI5BKKCD09ufo#OU@G_ez-9cwy$?p~S;mar-?*RH zi&m`N&SmLA1l&d0InHf&f(|*+=2jCB^v~h$4DU^`T1EK~gR3p+``fzQeh&9=cyEfu zeI|7vk^P&}lSQ5wQXm4}u43(2s3Dh+d{o?(w`=BY@ zT>yyS@8eW$j3<{8l9UkLmK*|d!K`w2L;6r0v3j#gF`LKVX@Cg+E?Ls^D3bT&tn%7r zqzKD`Tzr3oof%3*hf4}uw-7`?E||s6&LB7SA^DbHmE~i5arx~K0W;TGe&TvRGGLA= zeG->}Aq67%T+UN92(jr?pBlGW&mkZeeGP~130c~l z&Xm7kc-Ibc@$2s7(8lDlfjLd1Lr?8IHRBo>MFSzdTe0x1vytq(zH@~j^5 z@^46E?$zNe8Hj+pk04xjb|z$v37w?e!7vLRmJ96_^;Wz$S@yjy-M;?_hk#r#*PXrH z_QHesoNi3j`<##h5%7LB%f8#`NXl$&mF+@-aRxMW2=Jp87qyx_8<*epWLTe`WY4|@w~C|x(NL|No-l zU;M%7o_CEiYIYm@KAfzHYs%&a(jtE4K(V~wA9;kPt&Jo#-hOv*RIS?h z@yExK(Y&vk-m%7b!@4}_LXFv)xaDd_{Ggi~mCGS*nT6bnw6eY^wO`Okvi;)`T5;7x zez|C!=jrkPpnTUSQuCb|(i6X{%tGE=GKr$xP-WTo`Em`5zVgFmI_UUu6Pz<7Qq~=7 ziR>#|uv~*Ed0gLiXx2&fBrdG|aGKh6yV9?5y0W@?xcn^coml5ZODr`Hl4A-_iBY>P z@y#oJ;{HIU6INI6MqhwQ$DQ+K!R0rFKSZ zR;ec@r9%>F$;&{c#4{g7@0~5Tqh-bF`xTX^X31*;=1A(x1iNE1fh({f$ergl*v`V*&X%YxXeXBK^?d>W*v!LRtsYW1mHJn;#Xm4 zfRDPCXyT^Q`cZGh^<5XraP&d0R=cBQk8d53l-QUdl4qq*!>cWkj_q|00lE0Gd%Sfr zn}cR}^T3VVXz#RSx_n-0f^wU6!JiG-_YI#v5c@~>Wim=ilIgI_3baBwCeQZDl&ka? zh$VJCIWCB1=jX;#>CKoOD4|;%hseyIEzb&lk-xq(B60pE}QjX|pDJRLy>Y z2*?F%D+tX;cA+(qA$>e5n`;L|@GZam$eV7ftj)4NPvD#+S2?)AMt+k!1BF+(%Ci^N zmH&CQ2yIx?NnSXiRQkKcD%SG+vOX+IbW?fYRe+&>U`>+D`pMs?q)T6w)eK?LljY90 zvY=bv<>R$~ddSy(yydEAp$N+3Yh@SSgQhNgul#wufNKZj;$>vK987C|xTwS!ByzP% zUY;V~YOzZ?vB~GR9voH~Mc-U3Rg8PItH@${0E)c8PLQXF7%yi1=_IO`hJm zgS2C&AFGw?q%pK~(;DSjygP@0T(E}f>#gJI-|usj1s?S=q(B6}4^CeaPxmG*RKmRe zL=XYF;4aEC`*X%n^_!3}%d+t4GqLiG6RS0!lQttL1Gb56kNdsoqBMQ_VCHQMM;si9 z^#k2x)n=)jxRtehWr`<_p)Kg#;8_^XZ8*l@h+*d%L4(+vACf{{H>q#d{MQF?9P{I< zbjx6N(zi$H@o5W(fLt}2_mjI!?I`|Jc8%5Qk);RqnO1{#{QLsL`VJW6C4a2)FLoJ! z<+mAiZMq*VFn*`Fzq-b?93r4R7Ae~2!@i+lMC%yt!?1;LMnN4iOaD<<_8R+pWw3mJ zLqING#iFpjNo;R>^sFr+{P9MkN5(Pty*=|hW^u5P*9Xoq7A>QK!p_N0yO z*QER2-r{rx^>ZiKQ(oMojyU=CTUM*^&Qn-Sbfe6^A%dYL1MMJKTXx?dp*211)snuw zSc+j;i|)6S|5|oi0j3+c^?=4%?=eaNOyBK?UQun>yRlA=ch=8)$dzS1?XZi0IG(LI(9(BWC4o92B zHIB^k0yW`fEFar}cH7vP9`_%>At0BTWuSbe{c+JGN4+aEQ{RuCPHaN&9TwTQS$|O= zVp+DQoZ4}bSjbLMSq|jJel+-Msj}B?3m&y0Sk5a?6Wy&}BG_wiOslUOvs;takCmM2 zYdHkuvNH&j=f>xX8MD<#g90ejqgIXC+t~4i0(L&viE9~`T3rl&*>J>NAB6~qbQYHaQ-Jd+x|3++8)28 z9FF)RL(dcYn^Vfm|@E!u#i5e}+-#39FUd)t8m8U3uI?9`Y_ z<`#eY{9&4MVYCT_WkDGb%`$|h`qP*{JQTO*jX4D5g0h*%QfoAgJvExWp0rGXEnIP6 zlzhATJ8|LJb{IxQ*o#>+dsBRLu5y0(KIQQJIQe6vW#W-w5B%<9iq?0!@QmPTRa4|P zI=jW8b=0g$sm&OAtiyKpHS>cU0&+olY_^W?5Tu>v0Xx z2`AOtc5{tqc?PqU$*b#Ph=5#h?P6ZhyV10pN0zd>;dE}jf?RM_QnOx?X+ThIWmI)b z8P){Gtf1%3&V*l1p&9G#lv_7;iVy+0U=5kB@+Yx5*j>3gRTsmWKrR?TVC&Vj1RAy> zKw;mT;1H0DZwGq^k{;}Io4t)|%B{N)0WAY|M!z(f7DkuLd0|0Z!~@m}Mk&~ddt3^g z{<3|cHwwBt?Ccu`p^_4b5a<)Vb_@m_tA=-iEvW+L~5`HKdL)?>Vav zazRU$y)P<{ratTBDmLn610l&L+}1w;RZRUF*mpAQ!JIPm-j5+gY;P*ovFA5CLZ} zJO6l?r0!9u@7hKR!c zKgs=*?KFZgVR<|Gx!Hb}XFY4*n=6UZ=@Y7#`l-%H*)z+Ts`n>&%C8%aRZSDvYxZ}F z+j#%O5aOLW%1$AW<-Il{kW$@ei8NG^yecQ_V4d>AQs}6OUMJRnXNa=fL*(sq1KDXq zBW=cSVEtFcJN4h9S>szscOC0`=UP<95Upk#+A9Tpz3Js78&1aB4(}!NKkItev8_U9 zi$_VjwgyTc>>e>0PD-c}_^3T)`LzU6AOfE6ux}_ttW$Jfc+#D*jk%K_h=8X+?37D5En2)n7b@|Ci>)SJeg{fwax2+NJhGnPNCxu~fTTAhu=;9=jCpw~V$ zeAHDA0l6NSTFSW#9YlR!)n*tm{BK3Ik{3)Z#*j-kuOy%k+3X0_zT24rQxfOS7g?Z#-%Bgn=0Pmar!L z3074&qHnL+(VClIiqN8mT+p6pSue{EDe9|3^}Wtuo$jxsi{4u_DgAXZYzJSf%y&st z&U=ntH~JvMSp-ka_!-r2YdniaO;Ff-#oQ_iR|B~3vb#&K!e~|#U3MD2n)B7*P6pe@ z;&8EDsexZZ>c8L=f)t2=I%KcR=!x{Ny>|3r)Oij8xuD)yOlF`BWnTfKcPGu_`Wzx) zJU|fA-OcISY+` zGQc;lMoeo~oY?;xw@L`YisGe`&-xzBYx(!~z)vo9h5Pxs6kJzW6eqQwJiktV`q`}p z;VHimy-%4*FaL7V#M-GdihXCh*x^!tYSX7W;VHims=Qw}Un&!ZNTy{&**itg@b8FU zT!PT_o||TJt}0`RpP?)j$I#BU>}|uO=F)&?*&1I5!~a45La^79BnO|dG_r0Xhfr(s zlZ(HbV|l_u85|!$4gIcir`|gP?n#AD&TCdB8vM5I>elP6Jp8K{y<1b4z!eUz&Tys) zLc;?WWYee!c0>9xCj%mQjaV=HE?2A_L*rg=;1G}tp53#^w%0dNJ>R~P)DZLM{lD@6 zR4uUldd=GX#!S0O^B#F0Z#k7tb~>+qg$85@K(1de#jp(1id5;q&}sBoRhsxa;@7J) z@HL{%FV{=9ed4LXwmj}#Ewv^;GZkRZvYk_Zv-H9xk(Mp)@;^QJ6T!=t^G3@b|45=n zx4t7-7UbG7bEc$seUIkZI5iL8^5iE{-6xaizVJvztqFWR>F1kQ+p^1xYtNXgDVwFn zWGvaZvJ0<6C+GE|e8vWRD~fr6|Ghee^zGz~O;;87e}-!_IclxE>OE(*n&a{7WgEVv zaUUY&%EFS4Z;@$0pxUzsEOzBQ0`j~=e^p08$+*r!FyEn5Xs`_1(!Pl4}hvG)G= zS{HkRUbfmYobG;bRoim-KG@GUw)mE_SDNK!k%Q>IbN?tj<(CXz_P*w>#eR`~EJwHn zXUV87|G9SYYfOOcI{A6K0W7|&L*Sf%TyW&8*;I$+uNLDd`z{W*8o>VN=g0q%b>(qA zF5mxyNVbq{NvOz9ik4?)N=24r7bQ!jloS=A6)DoSU;DKa*?0QP46^V0zHeDCu6_TV zr|aH(=KJff&#QCZ&unLA&YU@O&g+wJIOLs_!=E)&yk0Oum6EdGP8(}Ej+5TmFF2MZ zy&eBZjM^g|9y*BXH#J$Yf~~}!K)8Q8k!<7bhi%*|+UR}&Rt1xJmAo-hkF^ciORO-1$^v+2li;BE&ylNSF)P z5Mp^JUgB$AtiTHCrN|XVe6GZd_Wk~Hb6B8zA-$n>#lv7**?*V2g1}sA%j2U`#jOTC zVdwlPB3qp{Hf^xX{oBv#6nj?TK7@G&F}D4!BILtYTLkvG!u_VUqwlFYV#9BJ<=v7W z6$Iu|%NQCHD+0q^>HZOe_;0TtY;Rjf&IPs5Jm zdzOD*3b`QOv{w+A3y&tmD((=@4|g(^H$HS#5GvPyYnPtsZ=R?&vy^-q-9di)amx7W z{&%-^3#}+_liH4_yJAH9m_R)Ojk2fWy;j{h6K)L`0~$uj%!~!fK8StQFdD2;_1B1T zfkUK2%2dUp4ePrqB6H$%o?jr9;Asbe5lbvuF)m`h!+#vGX}EZfFQla?U_Q!t{&+KS@0-Y?> z(?rkGl|UQwmDU+iiiV8OPO27OuDBJ%-Dxjh6ciFn!3gZ{r+Yx$fQ%#qrF}wMmFb;`EKw>*v}k9?EBN)*ey>-9;_~p9AWo5GN$?L2 zkT1$iSIWTO#eTM6neeY7pVaY@C3>U@>~)LFQ_EP~x&@qXz^1rrp;9aC@r!GyxBQ`C ze}u^A;osfxIOCe&8ba2$dhKK}zlY-G^SjD@6fQ#@!L!@?f(KoQ=(^*z!1rAEZVKNa z84Od0wUJdqw}=g%C6&7(d_Sb#N8PwMOWYO1WfpZ5k57Iu_B52!p4_&ecxAx5C}c(a zeYMCqJOnbVW+({Eb^YjjxGwRZ|O7ijKCC(IOOuvnA_*Ldv-M| zK+OKIT8zkymDdK_aooGOR=BosVyUuCytQ$Z&-Yp@`yl=<-V@;_=*Zsux8BxrX6^@Fp zm8;1+BN|Ce!3gZdtjA%wDc*#11`oGm0*@M=!B~30Q+C8<(ducC+|oErkt>W)rDWTo zqky<6te16Gqy)DX*H(YE^+R~ByCJ%^W3sWR%kS;n>0Z22J&Jo;MTGoWQx4$OMRmW<){!a_-Re&CkY}V>3Qh(F1z3(M~DHws< z1RC;32Wf9SF6`#oC}m(Dadj=Zwzi4>0z!=3WTqf67cS3WSmW4S_I+PN&TDX7;57=b zqADW4LoJAf+)}QZw^LvWMyTy5{AwoW%OoLx*6n(Yxg1Q5X9d>^BK<~wH>^BRr&VgRWaRXyiM<|h-PKnRqvMYW!_J}d)iEz+|G@3Q?St1G9bJp& z$6K4f6luqDjOPm68`O1@Nc_H;Arr=uP+Ul?9s>&{dE6Na;VoE!3-PPTB+=S+E zrZttB<4+1q!FPqK25@V5XNdc`LU?AJ6_|n%*uw*S)fx_zOU_moOWQtC5SR;V9}w+r z=uo+=ZE3M+d4ZyrUoq3bxN;2R9Amx3R%5qy?Xx7 zEG%Av{fEMhTmGN3Ch(n$N5LK4e=m6S-{m|eaMub+@P9kMwY-P_P|&N7{y)S&Tm!WU z`DF(s@Ww6m_)Zm*AM#4AljPk-_lf#a=f5(VKC>`({*lSw9_|2$p$@*_qn{`XCSM|$ zg5UqBU)nJ-Ni3Z-QhqAuPB9loFL&r_oHTMg5B?AZW!QFf7rHn3qJwD^Q!qm9kvc0MkCwT$_9_ls{6hsY8}9|eKAG951( zdyE;!z1%b?Bk6rGw@B+Qf7CWFvey1nx_-|+C$vBRYO|E!UWYrc=jZsUM;#>unP-@S z5p&Y28)rukSHwY?!G;I&6oyq*;myM0N?QE4H#<7n7`9_G3gSt z!+qB%F?+C^T+yi>!=>-}KGK*PP5ApOd8BLX7Ng_3&ivf$#ef*`Azc(&x0m&{Ra6j| zOKo{rje0_llwRkf8^hnlbx%qgZk(T9h8v&lhcZf^GZm{ELhOXj9t=}3LT$&Y`|E|n ziuO{^-h)fWwaT5g&-kc9An)Zj9m;4+bH$O^?x0ydqZom?u;fD=$f_4buCt%)>~@7> z3Pwb)`_nkqDv-yd>vOPl<~eb8NH0ms>{1Yz3(GOcRl!@4=F?5StGAS53P$YzZs2P? zhVZyWfl$VkqgD{(t}U!^y(oU8=x{Vfdg1}t5o>;>rt?2z11~@CzQ? zCO8#6swv_wI>~!Wnk)W3cy{6044#1J9*MZxa3AH7sI&vi7_K3Bd6x?pu*%7pl-3N- zHRzvzUrVbmq~kVS6HTYLfctX`hUeXomA8#!@7nS@12>Rbzn9`c$6a~7?|KwLKL56` zUJ38wVAf&;=EAc}*N{I8rvNI!`-Nf(M&P*u`{3tm;$XM~+}YT-m9fY(1#7 zg1}t3hPppoZD|>4EjyUKqnLsb_{|sC`u5q#87t~b+wYeZ1m>Dk){;ND?ZqRb^wpd5&c_EAj12>ezGX6@#)B5$Cb{On}M@Yv#(CgP7mQLALB(SwUbf+#~wS;tEpFf-!ISd5XstbK&;sF=e;#-RD}!N`b0(8}`z| z-eRDkSRdmLjyTA;DMi^l{`Hi@TzD41O_*~Zv1+faG^?#CdlcrveF%Q~DI7L}}1%8bdSb4!!eN9eiPKXW%OzS9 zx&N;P3IcQC^%4B9syWJ^pIgZ~A%7~bqVW!(uA+gVjpdk16{U^)d*zKHo*#HVf|vJ6 z2ic%pd3eoQoZ(lEm`nBeU2+OCZ8}=YONnL-Q!oP06|m6TRF_N7R+qt@N-GG=g*~gl zXS-bq`TTx;xu&2z!xW5A{jV1GvVnJfjb)y@tKtKRWfx06M8EiRC2twekVzBAXF~6ng8V#3UMY*Sjw{Bx-h4-U3*(kZ^naW1dzEl zE?R|(<#_uIvE)kw7wt&6Bfpc|i(C&d)8I|RQv;lxJ=u=6;Q~`I;?dx8{6+YPBL7#2 z7W%_lju>pu!p@Hon@KA^KD!qw-q@5hFnaT1U44kjNHcBC=I*>zHJ76QL(bv~m1N+? zmaPAscm?r#d2@d8&pzbQ>th;5gRSrPV(@~;mJ!pZO095Bj)b)10X@C-S~=@hgPPLC zx*1#Be~5y>TxuCzr`zj38O*-%Fo7u;p|+z*_4gvXo+rCCD^qm4ZOXs2izj;gioMs% z@SqVRNVWIJG~6Sg0hpJRn`0nmZ9BEEFar02!4P%(jd)*Tke&~lV=i3YC##png&UH{ zhlZxGM^&HsSX?m=Wd)(@j2MBr&W?Lv+|VkeXly{jHm(terj1~b5z}b*=N6-->%^jw zx>K;q_~yz)$T@pVtGnfvk(Nv&k^aX(N^%2THV(D%ShS&X8%*G*;8f-b~uPV zHHjCPYc^kHta@W2A%o1cOJ^q;&&|vvi+Xg}3FnVDN5vtZC}#Qfgb~*Sqt#kHja?&Z z+z((gf>H#gV1!!6!LKXDv{D`{vHJ@Jfw{08gNJFw3*yjBf9ArX6a?n-Tx7~0RE;a@ z1<2y+`as<6-if{4Fj!y;M&KC?k%h!c+UqI!MiGyE98LGrp;cPcm5KbV0 ze~?f0*J0n*zR@rO`t4sX99b7`s=dzAsJTNWd(v0K6pR?L@t)RaUJ5s#X9{u^(E2eg zSvgcf6b}V~xh~u+LpBZ`!Sz)F-k2nBqXjHRLjD4GkP;1~gzHj*5x6{vMsj!#?HUmz z-(4LlFc(OP22#R*Nr?th!vB^M)74Aq`x2gVcjhw%0VDV?7xXlNHIeIf0eHRae}>+S z=qib+S_bCo_lGGNV;jd?kJ8s&-%^jMLwZM9DLGVN3P!*P5?HmlzG{P|sAO@Lb;d(p zGK&zHf)N)Y9Er*LUi|O1-FUYuyVRqL9@SwlMqn=3C5V2;)prSqdU~@l(=&QjkLyE* z?Dr;5{CtY)i{ovnF}8-@uFERD@R8ekAJH%ZbIo7aoYcSDhyVCXAHmXZt1!!Of5`4= z)G!4j)G?oXy(D{ZBtXtO-IQPoMqqh^h(NWhSj*8(r9TN1gD15kqNTS!QqH)BxEBnD z9WRTqgHvr~a^4dKfw^!`8w}n0YE|Sr&Tb;B(ugSd4mwDQe zupljHR2J`0X+E@kLYF{#cH0lT~w<*cb2&Y)z0R7-+F5&_&#@+y;FWk$)+3SNyX)<^2)P$ z`Iv$cc4e#YiE5P1JFl{Vb{uW!M%_)u!QDZYvNGUk{J4E^{_uTIT9izYZLEj8V+ux$ z%HHSRcJq{?l?d#KsVU@4tyFopySs)d7@_My|KvIVKjhI(=@KnTo&;&n@b0HM&dTDw z(_*wHyPPx&-^qN;#u#n7bkdd$o&2liiHinPZ<{ePd0L@@z+8Bh02{#iFPa{sq1%pF zf%{7BAIMVVmCg0q=@EN3knKl@K#bo}3PPv-!-dO(7d#7}lBH9-$mTnq3zhO80f)S^`rsm&&GKIfsHw2_)PtGK=sbi`fX7*W;D?FN5Lc#a^ zRdI4}Nvb^SebpUPFhcLQ|Hd40R2ko#Nd>w3Q$b*^W~0XC_xwKP*Z#4k)Exfga*8~+ zGgDJ3|9uy?58|GG$m5HTq{xqr%P4(Vkr1em~WH3O^OaamTWSY+mWdtz-%L2S{KeJg>TplA0dGGe%_;BZs78;i|Pv#e{ z9n&TZ-((E6nfR+6Ww*|Q*go;nvgLz4kTc9U;bsOm8*Zm{ys*^x$|ZyU7T8%^7`w^% zvCc%U>vJ&Xt@A|B(j(-hXVn!7M#ML`YFzJ{#(O(-2SlIcd&Dc3UJ_#Mh=YNJ#*Plj zJh!KrHolk%Z~Zu-Xx^!1cxO))d!~EKuP>hqOu>j(KSPWMCTA7x5@7cko&vr&1LU`$ zXa#|}aQk3CH|r@r9~vxM+zJ(#D{g3#@xz=<{-J&;O+}2@w8t1yF+xUcixj%N{<9k3 zwdCMtul&j7vU$MaQqc0+?sK@W(O)J$c%~pQ7cSdixc;G{2*?eCSJFe2T44mPp~29g zWdvJc>&nR=UgCK7Y|^HBq?=Q7Q!-jkAy>jr=j-R4Ls~XD^k8|uUTZjin0yfTmJE;$ z4wND}yDT}p7$}kkY_nFa&Ye$`l)YN?lfI=^yI}-G!Q@jCB8zs;-rnVT)zvY)>$iE( z^4(XA;$Yioh{f_k!_tSP5|^h(zbpvf&+l`;TJHz5z0ITDUt#U@o;* zyFQea9)I?d7e?l2mrOkfH|;Q44Ud?UBT(@vdb$n#+e0&}UgdZdjKdW=!;-xerqAC?kz-L=V@FP@vk z!!22CKBi!Vy27=%yH)(G9RohR%ZwO-xmx&sF%G(w$TR9s2HBlkccbw77z5H?Unv7~ z;nfaKsVBLxY90-70X1di#0Ygwtn$9ONUD~^oYUIqx~Q>L)MTQcmp~Uaf-Xva>7vH_ zqq4}~x@e31a8c=aB0IUJt`Q?Zv;3C}+XmpKp=q|b_cVcdZ#$&e05Aeu5Oj-h2i`e7 zm0dCSHeQ>xFaLS&l%iSzTjum_F*UlzWm$ZZN@ZVI0gO63wP}h+E{Sv%M%MBIzw-QE;k4ot;H0G%+Q(4-JO;i>*ZX<|KA) z{aB@UF#@*_;``X$<286Po8I@V(pMOP`%SkxHxb`Gl32G6i*@bQ2>LGhrSBR+-zC5F zT_fnbzxt};l0gDq(dq3_5TIrL%Y|(xFwd`=aJ$>#%xYngzWZ;V;J(uL0NA_05~csW zx8KO;=MP~{m5TJ;e-S$EA1+)Tc<{Cu-wB%`tH9q!3bjP zk-qyc0&}VDh*?pLUOAM^;@ZtNcFyUlo!pT{WO@fJr~O)Y(09rHqn)%)bt`J6ZKe=C z4yeJvmTe)`uBEWXgQJX?q9978xr4q-_O;bDvRBVN$b(9$Y=+Y+1p&ID`+=|jU-IF! z4LKNB?Mr3(bz2$n*kS~hV}rqTz&zqv70P(sNGSudmi=23jMhD{+tH-lvCQkEG=es% zfi7A!*KnKOXH3`XuAfvS$B;`XBb8ci9L;!(`3eGa#kO6hLA2msvv$@AMh*7k*!;Vm zO095tVZCFt{&zCT-9N&iujbwLqzg-rW1dyb6$Ivr-5#Rtb<854TzUYaYeW;ezD5#r zcs9U@DR?w-o4`_ZWGxL_7t5}mIA(;^SpzM#sJ^%z&yE*rds`+GU6TdRWwx0%42og1 zGfQ$z!HCF77qu$(>A!5RiI3;e6OQrBu&di1{d_*~VFn@Iw%Y7#OSPdc8D!zn&f4~o zf0zBYzFV{ZtfTcpd?E&mnYP7&D$7SH!g0xR7bl0`Z%_YJGUO!R}ZgP8N zlTG3xDnU*DTP5HCJG1m;p}HNUeZ%}okp&0#;p6pX;V0ORrYDg8KdFl(6Z#)};=C1#W3i`Ix}Qz`cCbzc^BrmQRG0)3Z&zFV|AgJwxU-z9(RyK}C5q;sbaV6m`5U<#H> z{3Y;c%)F~-GJ{&}HDU@zsI{8g&Wttw(1&>xG;;;5kAR*?e(8w>^u(h512i=Pdg8DB zBlp;6+UjvIds&|9dg8wb%%#fJq9yO?+#FB#o6HorR=D4`Eoer{mh1cLuE=+;2^+EA zojEv-QV^I6^k4!y^{>@u_h&P<=UW>FUX21%FamT`5)&Hys~uoxV0(AiFn^D?y7u}n z1ta#X^(3ryhhH zIS=AfDn9AKeeDxlslQ#S)u*+<6pX+T%^}*tNn5!B@_C_7*d~H

4gX9(YWZUS@RxYsJ;gkz{IUA=|Kx#uk~7tTGQB63P~h4GldzpuX|Fa;yv ztix+}Tju_^Bz|fZA#;rLjpn0$1*TwxnnPiJqX>EHR)11$S2wY+_Y_{y)tNx0K1S2eRB$tTxU+ORVneUKe5@ca7tBo#^SnrR&~M@f zNL@Dxt1(!gga1-6Vqd9=+%{vY)}WbQ##BR3*}1ZyXF|e7!pSlGV*V#hpU;W) zR#I7gjtOhuex$%$7_E9IOh05RH?=RuAd|9!z+Bk3LDzRHva9J9EYSL`!21&32WN|} zq)JJ*U%T_e3ALHEiz$nn@~48pT*v(*$+bCpj86S8Z=D&K^q|j(J}+9(jSuq+di~(KxG!9(UWb7W1FcWuHbU2+W1c z1OF00g!CIus~3AB%J-Z^Ry)isDr5YkEHboMzoIg5c@U56VINl3E|(hGM<@u)g=-5r z6l_8vgMCYSYkFUSzl+N&`}-7<)%mmg-_mZiuq%5OYf4r`-cxL^c!$GZf;+FK;cU0p zW&%Dx3IcPfWfV-dXWPovW$$LBi{9RTGcx+~`Y)t%?2md+`u9#MfwIA7# zjaxNUU`p?@P00Qu14-BvSAxF;c{5}?)|k{`uG^0qF$IqSE)U|?=Ekt~LpIY(POsc? z|KJ`??UGJDcR8u;o9zj*)xT2!tD9}g`Xo2w_`9#x_a|npn~@Pm0!g0TNaDDz99i%* z7!WQs2eM@Lp6<_GX~YQ3h0BBdob@}i$2Ds(@Vw`^9k>kqC4(V1)r(EuV9Ts}W^v4g z(JOnlB_~7tz`D={YPGwzGYfHU#Wp+4T{05U6B#j7q>(0t8UX1 z*n{OcwCU$V8tz@pb=GGB$xmIc%}>+wn6xT8mN^~wqcc*zDhSM_%GH{lN$lN?YP4d7 z5P~Tf;nX~n(6L^cn~C1?+=66wY4L1gZ?;K6V6H7UGKp(Su6v_HIs)z=*@@>?Bs_Zt z!4!N?fy)MO^%)T?*0QDWvn)pvdS??oGmP2yAex;!ne6?Lp_%{HkJ`_fOzu|bsm)sx z0&jRPj7(;GYL}$XV@=&L*L{;oq{E)CTBQfQ=yB%^0$w*{XN6!uJgAb)CKPQntH1t zX>xTE>9{L{cC~IyCO;1#KCd$Y(V(RZTNRf_7geanFjsXuLZ0=VPIjzFqa|}2lCPU) zk#SWg0%GMH7dCOs0XkZkGt8A-vLR{xa0z+SeEk0)V%PeyijR-c9(S+MH-C7MY?sC4 ze!ysYcbNmZGC7Z!#HUjHC5ScI(4C##c8%s2H&M#K2wWc6GB$cJxW%H^$Tj7=xI7bA z2U76IPV$(Jfp&OUbYt)yfL4!POEb=Tl9mJ4k|7;pDdxgx@Ird-!S+U(vFCHPDv0Uh z8<2pRMlzs(f`W$kNl}bhJJ(?Iil@?fk@ZRWf+K{U8cH!@>qKWVWThbQ(?g+F5W$1J zb}zvoR~5w+jKH;pOqk>RSm>I{?Cyg-WaT$I$g6jnM9mLU(3X!0xp>}42)BDg-;R5F>|GW%UY zLte{yj*!K*IeSpSQ!Lm_$g8zMq{h1O1S4?SdOYL?%zm*uD>kyZg6P@HffS35B9qM` z6*RnQnA#BRF&bONiwVqy%Tsr?pHZz?!tPdV!_eCtQ!oPWk8p1=*NgSl>amP|7kH1v zt|aSyJMzcai3IPvDk7>xGMj48w9q%Dm6e(u9Z8gBJ4P4 zZIW5Y%8A6(?Iponc%4_*cJOjySsPkuPp+*eiD}{Fi&+EWzW%lH-L_|jkXv@`$nN+T zP)74vDeUU&cmi57acw-9ELs&x2AY(o7_A~6EKg=HdJZ9Hf7?hf1=k(d79_D*DvP`L zP=n}o8ZHBFmq^ch{$%Zha!Pq%5nhnYdgPxZ+nqY{h%;g2T2c@>eXBOb=;Sdq>-sCo;E5o#GTUXNvv zYm~xm1`jzGPqeP#B;a9tnszyfJQ?Omo|Wi8@s}W;%&D<#_UWed=)8Odfw|N&%GMpr z++({?J;ve4m=x0Fk`GxqvWHRzE*svfC5&SpsZR7^ZU>I_1Y9fpCD?1n^kqj2bqN;ceurZUM#SyzO%_h?P0s(^3W&G$2C}a~ zFRAVK4+;Wv-4$KPw49~n_wDsy1OqSkgB9*Ojk{7AVhR06!H9EPyh!!)%Sbs7Jp!h~ z>M$1Y>J|-HmB}%}t9U!I`0X|_>Ib3TpZbvW0V{~3)(#L^>%!Q$N_Q#5!7*YAM(pwL zLgL;ok|SU_?l2U((Kd207So7$8m_8_o(huA=kc{s1E| zSIW;JdR#ZssAo7Jj*WrL)AOu>lSJqHt~&e7z3i+Di536-5XIhEGn(Fy`{ zHOq@7&+m02jwZ2y@cHh}!Ui^Cw|1Baye8sx5U;4PaJ#2!i#muv|<5OIw%Oth4)}+xl1>exW7Cb&ub|N%%$$mrPp_6 zPiIzPn;Y-rSe7uCssT8)_GBBp;j9MHHZcNoVeJDf^uPJD0dbWWWb-g$1m;rp5SsPh}h$h%=Mf`MBGFo@nl4@EmsOu-0MhYNVsA8tjLz&+$a zMMK6~@guLUM2{qq6qW*I1pL*B89G*FXKVdbPN`U8@SHao-VJNVc34`mNs!9~Q!ql6 z5^I+bK#MN8^y~5LBn`UlmFVBk5?SbrH;Am70SBSeMn_5Z-Nn+ z3$H71x(g0rxv38*#EK`Ff)Q92^qk(|?0M`F+P}Uv#R$xW*A?*Ic@WAj6&|N|{QW4V zV1z1HiDg6CgeHP|jvuceFqeA9sT3H_;Jpm(&|`{%z+8Ckg7e3r5O&CCA#KC*D5hY9 zD!Y)imu3Gpk(xK%svt0zN7cb3v!FZ4zOA3tGW!o=n@2{_X%Ej+Ou>jB3;U1~12w{| z(g9(6qc3ylJBUu0_l9B$Moew$O`?zYBGs-=07O`g?rht$R&<7W8HN#?G7 zbj!>D#DFgC;QnzIeYmQua!SSLXnYDc7>1ekWp_qQp*K7Vl@l-K!ZidBx{19R_!`iH z37;vZU<9rq_(pm3U@!Yrp>jzXR>9bhl)U*?OZ_@t=>@eN;hvqC`<*kyb$fLMfw`96 z^COF@ta{L{OkZY8O4dwL zMicisya4?Y#GI?x(JcCxg1}t3eNZd#g`2u3iq894QPC6cWXF(Y*V9OzhaXjSIP=ko zY^Yxx&9A%79aAu(AayLUNa_L6BLbo2o9D){yWJPk3nR;Gm}}7O5YqAYS)};l4vH=T zkttFV*!N92H1lL}f)QBbP|FDW7|+aVPo>f2)(}j=h^n6xNQWx@i0O9SYS3g#JX>-q zl14RdO|3VjkwwdGi!>I@g~tgZn6(+ndN%4pubm#PATZafX`{)NPvyv>+yp2izkvBQ@&3E6TWn&Q5);pxQT+)VAqr8sEExGKY0@`Zb(+m6i? zQ!oN<6Up-a8QScqv49Az>dg*yx*`&0%~LF<4-SnlvW3RlCMaLhUpsYVPo`ZK?`Ov- z6pX-@TX^ASIhgGWtRq~u^ivR+OC68c*J12uguQ^*928S9LLKu7cg7Ui;0|3gRqWBY zNAZ{7X7u;b?9@AZ8ZoS`QU*rgUWdE8GYN2yW1wZdMk@%+g?k+$jL+=NI+?c+f!5oU zmg6x{?bLP-UD#1mB0BZHs#vx$7e+($v+IM{+o8E+!}n(j0(0T{2$?V+N3g_RU&scV zqZCsx0!xgpm&CD8i(P4rg|UkC;g;imgLsyfqgnLPVbr?cLxNXM%!MT%d?4+T*v}{n zI&|kef^A6n#zeK^c-I=oqKr;7?@TX(xenEdCEc&oBo4cGD^@Dd+jl0xT~Q_ashNvH z!3b;qr7_ zMk4cY4yNYu*WED%Bh*?!R6JI$!S8g{ys8}UmUvGrcX}XcwSPMKNS$GxN1G?GxpjY| zUY@^mOj+j;Oy;DFCtpig(spM9$UToN^3bmWAQmMjvhV8$(8K@-jwu+S)+&6+D7ckL zrL!zA8*$w+T19k?NMf_zR;P_GE>LV_mqIJzpB||oFcw1az` z$uQ;_sm<7q)91;)R&5jn=E65-@Q&q-8#{A8ms~m8SV3SetgnC$XKu%;4Du4uOKlnE z!nblN0!b`h4o;4caCITqx#XXGkJMHbiZn%y5nQ5$j62=Nr$#vTr)YpdiJ z{r;2cHp}oKlZ2_Iqa4&fh+qWf%AK0Zb#x1J{j`1TNi_BB-$sUo?B?E1do`Uh<6JkY z-5Nvm-&<}G+Q?=+sZ`9=&C%cu2)N31VPFamS!jz3xSrN0{V1H@OiSh{(( zvz%`Jg<}dvgfE&zdYmcl=Dw~YAR3;|c1&{D+tlQ>e#ZHHXeRGE-ADF0?kI3H zcAT5#>Mo0X9kHjn7a$&=UCs+MPwBVTMf^yuRn+f}C44B3t&YD0cIt_BN$kY7(r#`l z#R$x$mN8!(DN>m9`g?^e?Jm5V~b2(?z_Z>5stv#q4# z{s|P1xk=o+qA~CJAV(R0-Fn`iR!Vb}WT7RUYQC+g9nEZpDklqkVg(p#2FtS0A+W=_*HUi5O0JWa2aw|`CL zO9sREJM+or+wSsx$G!rWff2Yo$Z;sV$-T0zWX{M5bY$#PcYUVjn9WdTDxSdxL!*ff zV$T&#_RX^uexFtq$rX5KDcRm}TyMzWvOhu`@^zIjpYP)sfg^L{7~lHKmrQZO*-^UA z?4+!sYwWVQ?vYgK;Xq{#20KH)humJeNY6L6qSWH)MZLS=>2Sqk2TLgA$Zb-E8sl5Z zea8nWvWtCuupEQUGRu}eH-QM40ezJ3;_|SLqDLgnqOlVlrEk}7`FP#M@~ZkRdBFQF z*T}Z=(R)9E*Co6r>RzI{v@iOm=fPXK*MhI=;-N?Dp%{U=u=IfSJny5?bD)n5v1lh$ z%75Qoz5R!~zT>>=tLHI+cd~TgLN{5b)?tE24UguhuZN8K{xN@dFF?E*_y_Ty;wra~ za}#A})JJf}+23f!fXE{0sdZ`uARhf?LlgHCd1!krioc6x39qgO zgX35$VVJGSmyQjUl^P@PstxD!sz1n!ZY~l|^#Yf^KCf-jns{<+CdF$dScENogg!qO zc5kUrFaocSx~5-U6x4K*Vf}-s&7`VD@|tcomHN+YRW!l^DYZCbd7 zDHx$j`;y6F=r-!n;sWfeuhG~zzNeT8$cgDvA*oQNIlEMN6Iz%c@I;WY-VgOH{9 z$}<;;p5!aA28s78+za5jeA$Q07fy0!`eceJ7@_u6HQO**Y)>_jW2`~3-oE_JMBX-N zj~3ly7=5%Wi?2yosAV-748803wwcVi-I_(sH4~>yyg1BavSVsba^pr*e*I_yaV#;1 zEc)7*4~iK~_Px~e0t_0{RHklsWKFmB7k0k({J8%V;?ZTdf;c$amnXIhBn1`c17hKR zN7=G;6Sls_Fp=2MnTIc)K|;>oAsDS9?EGA%`(8Wtbk0ao%)*5iR$E18jVMP)wX)@= ziCc+@HTX%PFTuN_eU0SR%8smIn~6#p7=g=!*i?I+9){Uml9p2>vjjWc)6{J`>P)B{?~CbtF<%5T((zTxa;{nBzcDJ8+Ee3yG;Gzz^c~JZ%-NV#VULR}+Z+M%N#+{sa`iTPabxU8mP_ySp{yI&Tw(du@ z+jiXi%^C9PdnYJkNi|P7_;6j8kpG693u?eiZ$3&|Tn<+d_)DN=Bzelsb1m4V-cxC< zmo7YS>n4)Zb|jtDy8*ZG=A_QTc#6LS`6h0+k)dnqv6iK$Din-hzt!iT4jm#1eRV&X zK;|LCz0H{S=3UBnae3lq1AaJqJNa}+x6tnk^pKEeosK(xg<=XuY))v%4?bN<66)#q zwRdj$$rsIU&_iDjQcS^!z0!?uth9{0ou!wd#dVg}YmU-g=k6*9%;nov;}Hon$?C@X ziN$|P2TATPrXed$*zf~{KlL6@R*W7`>-K5H&Aw!lA(b!p8^f)Fy##C(FDEw_SQb>-T;#waI{azPc&dZK~VI zta|#&#Dg~kWG$dqL&o!SquXevDe=m>f=_)g=514C`u!sWqH}3q%-}uOi-%gjh(0uH z=@dS}&stmkCh&h&AJ28;WQ``xY27cr9A}ir=!&P3xcC0fWOBo9P^;X-<0PE!=(uU& z`Iv$cM;lD!*Xvl2V;9`s{sM!qfT4@Pp2tchgoH%f7N_)7-ErkJs^Qh+P% z9JF0Q3_KCV5AP2nU+cA0&=5t?a-4Kwjj6qH9XB~XgnxaSO1=zeMlk}H4L75^Aqrdk zZgQpX0*<*b`ung@p8qO<1bXP%f%_z5zn1T@tf(P?lr@`dgfwF)YI4V^- ztY|~Z`!_cp?jFi_=C>y~WlbqYtB4v+Ag0>;D#ZL?If4rql$YkT!h zDbkcIB#;lA*xQEliI=@d(358bb73^Z*!r0yPn{V{bS->!avZlaH-UHHd&uVX@!YZ2 z8Lhd~F6B!GgL(I4$P4gXyO(@Gp`bXBb>s*`KQm#NuN>600G{gaz*TSc(q8yyc)ID|VqoXGJ5! zTv%ct)}&o~slO?j*SVL1z+6~6gL}^J-ZEus4c5fUOJFSwb746K54xZZvVXKC`*grg zL0~Sdse%2fb!WM?(2^awxr1Z94Re*UVEm5UL+W?a--LEde==h-)+WvJuRkaeHd~6Yde19#s+dNNcUnrdcT{re^`P+-f#thxv+L- zFf5B4Bqz)}N6&gjD!M2}>>1ICyN{Sp7HrjhKMrmQmM2q>(%n{b6$IwO`W*Q6weJrz zY6s1Gvz1~BMqo`1&d#$3$hqH^({ZkQ6zvWp)Or5kU_ZI$kC}8^%bN-UbEz6xP-GvO z{be-e@oy=nV1znr#~tYlmcbCZ@WCr(K4S!)|FFUphDn<>PspWmmz6aUuY-7vF&NGn zg5}4AI`l=E*A%ZG_`7(0gq?F-uzX>9pYR9o6a?l{%XpYp2Qunj7h4iaF}#xD6;8Dj zxz=eSqk9w4Y=@Piy<)VA(B_%S?^gGOvn#}VK{hL_@2ZH3t!m2>3w*`F%MBT(U~&uG5aPS6M~_UNu!TeT=~8 z1b9Vva}?Oe##4A3PRwG*^3EfA5uf~i6z=8uoXZ2qvuz>tp~Xl}yb{Tw5nW+M<-{b& z9{E!##F-$Nf)RUHM)G1`vq;1<-7b1CJW&Q5A4vnMm~o82IrGXA_NBo)%p%@J|GXF7h_vgM8;#m?*!3ebszqJuE zX+m=m)2120b`gAH!PYj&0ZO~cCtEIv{x=UR2+V~oFJME?8ZDRRMbn^Z2MDeS?p?K3 zlP@L7pE(t&elv>CHMoYjN8pWOopG|_!E&@xV4>1i7=dj-uu?A^19`R@)5W;8!lQ%x>@6;2`2lu`!%u8MFD93~Hb`kg{HK8h(=PfREo$QzE!hL`txtzMQN4p{_N z(An!-Cj5XM1z|7Yj*foW2jf^^TUi zr|hQo3pT*J@c+Jrx$p_VV7S{oO5SW&KyB9jPA~-{5=b}hzi}-|+}0b)u&fg^wN`Wmyy(U~ibqh@si)e2w5NRehbCT+&!?Dz5vpZ^JaLs* z+uRZ%&IJkrb7Acq=J~pw(rNj2GIVxXhW9~Sp1QWjtoD~zQcBVz#VRQX%%!gFPwNko zUDnqZ1)-6ORRy;L_nV$&ELJ{PWd(2hey5m%ds-dAmZPI(^URZDB0~OFry4(P1*gc?I3pV?MzybwtT;D=WZ33!)IUrpb_R^V=N)*JQW&V;2h(z$iwXQK z%!SWXa5H+LDggcf_adP(H1@zJ6v5F-XBgT&moiCbb<$8;+Hs#u&3B=268?yJ;ML0~S`E_!xG5=8f_N#U)R z5mPWi9gkKO67|eOv`0x>jwu+Sw*2eMD99dp0Ax4Ai0y4yuCVk#LcfX#l=~+v$^;HFd9=--2nB(;)OO7Ah?WkO_t5np zH!ABD=ECC-w%21rWyzr9G{ZSpL0~Sty6O@5he`7m`{?BC*2*f15m@hn^Wd`>`5_4cV9_(*?dQPQC8HM>ic* z6h&@(U?+a*g(sW|GE*GkC96t}svAP?SCY|J_n3@c9ECqqNaM|!~!gYZBe(@8{%E~h0NPf5s zTsHW+%ubS%j#Z%nfi0C?21hEykr5#xP=~hiXcv3-(Jxc6*5aDr8p1w!x4j(nq&BT7z0Ja^+fU6R*SSs8Gf@G4<2xcZC+U(qz$vgs8K?=qMRw+U=Z^~TAj zQO@-3_nyjLi@ET=3w<>sMK;d-o!HLqMsT0t_>w9jq+g1JECSlcd)o-Uufbdx4Yy0B z3∨2Z%lRL&@%lGdg0agnZi{%gD1sEZKxd?**n{1nz0bF5kQ?#A2<=a+BT*CCVa- zxTi+OldTGAsh18c!T*PXz!8*jR6afPNl9&b@B6}`Z#Ra$La?`p9w*$h<1lSsN!_z% z=UZ!bs%k4XZ+ET|T?)r>$}=fT-X1$ntRLxdCI&7n135<8Kom3ZFRp9F@BKN9TrTcT za4)EHFrxh~aj(U2h}bij~x!Q64 zeeGpx8mY6rHo?81M_hbId(84;C0EQ8m=fKqGU-`!1W9VtfT(?ylvkRCq`ETxV73z5 z5F>CjBDe(ztj4VNbz;3*UFA5k5$3{Zxbxa*$!^r{$m|nah(<@vN%_g+$dDmJl!!_A zOK@+{)CykFc`(z76GZSkh!Ng*8fm*_hZ4sLM{9yOkdGlQr-jD8z0DLjx)es^Xd58y zODeH+6CY-llOr$%BP^}W$O<=3tk;{vn9na+p7rqWz*@D)5QRs}kk{EK$eg$K6r)wd zfQDAgwq9HI?R1cWz)`s{8Y~luHq7&l7u#3m6EB=nnOs9{0@UQ(Glc8D-^&{q*x> zQ9+mzp$$%6Tdmo9``U~Z{7KIyRUp^f>>}kKq$m;Ia8x#fp=zWxL<*_G^r&?hfuq*p z=yLj7%c?BWA&YJ+=gD?Xs6=WUjf2>HSxSsP98CaTjP$6&cDSu3Pkg(u;EI*V=%uH% z%xY7Wn1J}@6L^K4F2THN5U`#z7jy0w zltGH3W(7>&KGAOfaeJvnB1GuGtuDjK!BG@oL9iu`OF zL$O~M_V)rQA@*`@|JE!lD@3{N!-$DZ%JO-)E|7#rdX&w(P3y?->luT{a*BT%zIRj+ zO}xs%y+Kz-_8Ale=GtAdEbl(}3Q3=<$8>6DS6&_x(L=)^ahq;b=m*Gw4T_uxk z{Q)tdOkJ7r#EZe%K*I>kg>PlSrcWWW^%j3tZdOBH@l0htXURoUZEst}GY_L-H`rne zxuZPwH?|4_-zckPh_N=(*UX!(Y5qn*V1Gf3*8Q()OW($x>`}E&f;6_Lfd;^B_I zy_Ga?+Li@Q9wN5-T5zAYX=KH*48>nm_005et_}7?FZSxsW(opp7T5O$KW?;Pq1Y0disYXG=HU;5aKc<~m#UqjAu% zbdvFBchF=yJbWS^P6&n=yiEnBV8my?dq#K25;VQTBtTTZ`3-!X0~ox+5}1M!YCBeq zGL!fAcVBd2BdK zI+ek(u7-6u+#~Q_ZNO!bSb7M9Y_tjjbKxF=_Xf7Fg!$+IJ?g2_a@-EwK7--M#nRw^ z)e+)gPgi6YbE)lk&}ta}WacL_*Mut?GS-TH!fO~W=VoeGgzl|=t8M`I-aMDA>XyPV z1tT70Ip^1TQHA(4(-D<|E&0naGw7wo@vPdQGR8MPahTWvSg9U@^NbE^7Gvl)p zTglj3lc-Z#oBZMxmXT@QC)3Zu#r>!4HsaBB5+E*>tIFGi)@Smmhl0Rd7V};6D|9L# z#!ce^vAB{w&+&_3eO{cQk5WvH>jvE+W7u$7b9L){Auf~1@I-nhzoolp#k-J`MZZ^D z`==ehd1VAMo3cbfU@kX1=X@6MnC#Q^2sDttmIqxP%Xryl;`WS|#;{%w$wc4Q^qgJG z{AVSek`Cb>^hJ0}_rRbBq}9z9fXL{xitk!Gnt6;LtROJgno*^URV{9iw7qo!F~Ky> z2sf9k<%2YVDH!3qrkVT9IycFmf9i-GZhA`%$+LjB-OhlvCPjSjXu7&v@dU_QOu>v?&sc> z#NyT!>Dpss6a?lvwP}d)+$l=#toRMuajU}?e(tI_-O^(W!xW6blCNu)5BQ)bDc}Q{ zpdc_8o;To!T>dV%Z?=~XEHjKXJT=64eE(GPSG{bCxzzb_Zl|dTJAX~jFs~pm*UBk_ zjfU1sNd=Jw?XYXSp6Atg0U5dmF-*Y-Ji8$8(%M^`jw#K^!d?mjbK$uOQK0M}@(VG| zna#S^Y<_5{@nG2lq;s|L6mzL_u(@4%k>7x^Ht+2e1m?QiX^=6`^d$M~r5^n|`|4iq zTdEz~eX%yf6pW~q=$wCU%qbFDClwIKx>*RP*4>y}vGNK6b0q`}GIlC?iM(m1drd;L zI$rRpH?ufZieU;y;8jB3Ki>1r3kI>0OCM5 ze|9~8-`BP8$9kXZxu5&k;qeWPfhbg0R?!2Ws+FwO-oQ2P%-#z5a+FGHb|HL z0Wmb(mSg++af0ySR~(*sJdgZ0zvrb=2dtOz10ysBqVP1c&mg?ixv5oYQIkGYsns%@ z{3K6I{VYx5dBn5AcWrTJHHn&1K~Ga-APP?!_YaCL$}uIF4s-orT3(th;!dfEITWFN zmHL+$kVmRCd<^YaldUljgR#4s7fFbZV}6 zSJ`4@ac{}_XVK(!I#**LYW1w$1xEro&lxnG8H0aqZoeBFN48qadCJSBg|SbmhAawfttH&jp)%lR%0NFcOKXhFMcStwX%NW#4m9weq2Rap?#k2S~k{*7qtm#REouddX$Ux=e?z4g^ykmWb z98nZZn=c))y|^?}jQurTB1%`d@;7IxBF|Iu?D}CE15rcQ9^$bT66n76$0C`ZmcKNoTrG;WnXX*_HmP3g1{woV?euvo)hUgE zs5?y$*vd^jBLXT$@^36@IZeGB5=j2Vze%(p1Md~X$nCpA-9Hdaw@a633`Bi8^_kfGl=34@oY7G1{B`j4c>K-A8j`)$X^mWhnE)n_Fri(~pAPVm;W{jVsteMC+PcK({YVNf;)cQ@_3Uiit zU*WyN8;-vESS6p1BA>TEst^87x9xMACpN#BCQ#>5kJ*Pi`NCe9lSoIOS6A^hLT&YO z(#6j%pK0o>tLT&;YO1rHldM_vc4Qz5_j_~IWRlHZD~xweRG(%?3o>w1G{=y;>{eBB z8cFw)VHDr`xoz6m#@x3(OQJraj&b(2#~Sr#&~$0dGVLv&+1mUuPWZUbl!!v@V#e9k zs%hL$vcl9Lje#gsKK`!u=BU`2l_pdb%i5dmo})N-y70} z?(H-NqB=BrVC&l1Ci=9uI&yoq%26%5f5!Xn+zBnnKpo@zWBvx!e1#XeRjZ>h5QVD5 zp3Iw{mHU<`3S8b?Sl@2Fm6ycGlz!S-(ZBXh_4g>RIgwQCaM^|oM2%T}&-Q3?sc@NV zO@UgyV4ZsSO*CaYM%vMW3_L4_al3SndU7h9ro6kQF%X3(?ceW8#cm5F-b1Kn$33!5 zYjj*x5pEJu`iZK1wLtAl4)`S}6)G$iVZ+ zu~&!9D){**a_KowV;~AoGrv-c<|{YeIpI;TR>j0_uvNIeOgwhpA`qpYbH8RIlyB`Y z&cJTa7>L3%&ynrx;p$qgaGqD3qcISLiosPcZ3Zfy6iOY_Q#36>{rJXjh0UYoOfjX$ zAoj23R%@=FMvbG@pN1;5AOn3nj>CEOSF3!+ljHs78UsGh8;`zI4kE^ubPl_k6 zLNo@VP{+8Q;rXA|E0sI%M`^h`M4@(ZG%Dths@*q&C%%u=7>GjUGmJh5i`9{DHp)Tj zYr=dTqI89ud+?ZY{`d%Y5A@dV)rmw7z;5 zje#i4Bc=|V#Tg_a*g2I{dj?d=a$G^qjEm%3{VM4`I!W}s{PRHvU!%5452 zb?H~mp7QBl@z=mai6~t~lTweW)GIxx|C##|8HmD6BhPe7RjOuaKbp7xik5>!2Ksi~ z+t+xn>YwRPEwhR=2BOeYv*uHuQ@ja*4tMQe^%u}by{v}TJ)v>*dLHOtGm zs2V&NLErZE)EJ1ue57G?EcspCY!FIZJ1EhD4D`DUqjYqcN*zCn8YIsV$Uu~ygNz-0 zjH3plIU3bWpamItcX9V}da3F?G=zM=y<$TKqVVqGe@ERiHUC%u?fy7TyFc(|z)U0e zd8L;q?q;RDYm2lz4l+>Z*|YT9r`GQK#>zBk3`F5A!LNyTt5o315HkDD)v`;7(zSi} z$=QlK+^Ac=qr#jQsq9gKqOdZ8bvMK)%#4eXRt_C2AP|N6 z$oo=%_(yq^{UCRw^wk)MLUm>DHMm@%S6*G(c(f*m*Z!LVgQ|wQ!ga_e9134nb|a_1 z-q#q2LXF|r(&2iAYd>s4i_0!+^JEaE*E1xP(Pq{lL)WXfn=13XvoEOC zjts3%0#T?K97A?_q!MyQSm#5_>f`CsPgI>)r^2+~2hm~whZ+M>dR9Mw?<+N@)llBN z=&a2tLI!$(9MfOvSonPGKx)#PwKn*;nZUK5G|{Z3{(leoyB&=mG_hrSW9Cd3N^;sAXy|^{3+GJ z0e*D+(qU8H*ys#7uMebMOAnjDwd2LE<{1)ESYO6@gANB}Rzi+kc4(N!K-9=H&&(Qk()rb7<<(a0 z+Rt_8&SW$ebj<0nd3oU$QDx{<8C?6h*}Csi;WBKR%x+a)grsf~!56K(bJC$*vT4PJ z)Zl@K#z2(o$^GVo2})$tv1W2y_}@`E;a(Gp?cRjYf()#z~e=iG}>0T89vq^{cjoOcx!TQdhV z2BJ_USle4xqn4wKWn8lkgcfAzTc7iIr5Ej0$B^o`KwfPduQjSZ^p)<$C> z3U!6EmVefwaNlxtY<^ur3o@{l*D&MHsfF^5V_bpk#-EQuEE1wdWlu9PND^t$6fiYRO> zQDqRN?{{9i{5@(>)1Ufx{Z$|XQ6*jPn=c|Rh{Q5$X3aO}YE%6VJ*~a00xihET5f9s zjRQ5WHk4LqH&yE&k=yl1i>0lTHu6Q?l{HF(8Bv)bqq@wBzI3&L^obeZKcj52NK zBwEmOYB2s=vxn+QF>hTAq(-xMNVFgWeImnnP-T|9zcP$IEX&jwh~kQS z^Z4b<;){|%{*CmI4B0|N6K_FP#^7OQNY66f3Ex_F_Rco5f-j3{o4q9ZMEozmoG3H$ zqj<;jIE{g*4ZjRC7v4K7TtBsH2YXMRE6XhkqZT7G6k3oGk)LN;nbDx7mbb)N25G$} zd?J=<3`E_H`PTfy|9A1^Kt*Qks+}%(tPiCKm$eEl$Y}KQQqwabN7y@9)d~4G)1>S3 zFlt|Qp=wzn*j(Iaff&9gT_CEHZ;pA}?FVsVXgV`E6DPf+$5{I_6^PqV-ZiTkEP1-Gwe^(vdl)Crin`K zPP}3IKNR+VaRmfVnQHXiOj*Zi9AS0rmhCQP%vci6mF7r1n}*Te^D=M8+aR;d z@}|w{mN@o)7m4SF{~obBM4OiJ91)Jx7>L3eSi|5QjdDxVan#;3MQIi|k9cnQD|uTa zI^>R}Dv1j<2BNTP_TO4(ncxvc3o}*e|jbSX>u}2)OAH}ioO&SAHSjoc?uX9ea zctIrPwfb411sU}!dz$e-trpAwvbM6j*V`w!cbnc!R7YnsH!VY~@U$v~ ztbKa@!~dtww(m#SS&FylAj8EB*m}|&In}C&Ul!mk-H*AeWi^5bEy&RC+V#nw$jg-+ zuEr5skbyTfZ{eFKUg0o83o_6f;3)-Lykv`K zPIPL;K#hSY)D`X?n9`A>A6@Bb^ZJ_lpyJ@I%`f`&`m$+4f66O#(HMwACF1|P?~&w9 zf5cHji56s_60z^IuBW^|A%+sGPLZffh|=%#((qRDc62;B%y-uqh{|i{Xx4puOYE;_ z)$bO(H%bPikEf}Fo(r@fqo~3XbNK0NBE!?48Qg&+tquk5RL~fR3c6R`?0Dt2c-76S z-~H!h5JzzmXvMosZ?quedBbdTaG&d;OXlGtXFQ6elKgB<;gEsa#rcnNp>n{EXgYOmqUOn90U%9legsVdGs+WP}zK=>A6?{)J$S@qB@(P-;fLRCW)Y8U6#Hg1+T zMpc$w>qHV-kbw~-{*4*y=o_8G3p9={AAv>*fHK^%>0w^pwCu{_*fHC>%+>m@BQiz6Rgh?HU8(Fq#q>vEhZ%>yt35H{Ma91^>Gk zN8t@ewexv$QW)KQ;jJ+cg|9HKXBfL(I-d!mmLJbm_;x}R#;>iJPMc)=+>uoBYNf_N z6lxc564<%--+QoQ-4zNg$iT=8@8(F}A}c%_Nhz1IH3p(k?Rb*Ti=EPa<|qo|9X4n| z2EM{L)3ErobZj3;-DZESMb9y!qsL?xU&xnHhr{UT=bvc|M4{TThrHd!aR&Z-gub<- z1sNDs=PJGaTV>pZF;vHWi^f2d{vPC7XW`)})tBW)6Lw^xUy2?l$9-y*n)5ep6@Pe7 z))|NvN$Jhy?eZW2G z5feygK?eG${9TQ&BRYLik>;)%qA?JKZ))Bk*`b^`cD^kI)a^jnqlPGaA@iFvbdvYW z{a=u^9S9kS!cH{)u3n{hr|juV#`zkA7Gz*28oyG@LPSxqAKmHgLTEt-dbL(8qn5a^ zdnENacvI_;MHKeIT03$Zijt5x3V1PHV#gVx&=2MtCtI3H>k=usK_`uYDC{fa7v#rj zV${(j`op`DL<=&|4>pXFZeN+ML6fOnr5OSlh{8@Z&crR5@o#su6K}Ud3o_8F`MHrU+Qd&HW9NE1T9AQWEzd~V{)uQ%eIl!99fb@;VT^+( zX3cxzZLbhbC;M+z*yn>01bnyim$;y<8D2P+nlxXob?_ic_jh~rauxY)Cep^uwG~!& t<69j)POh4)Gt&I(;Uu!^!;yg~y)L|cz${@ga=a$nH4FH@=%X6O{{a?;kpTbz literal 0 HcmV?d00001 diff --git a/tests/link_4.stl b/tests/link_4.stl new file mode 100644 index 0000000000000000000000000000000000000000..eee21589d6ab1b7cdec6a04efc4e25cc6f73a0b3 GIT binary patch literal 77434 zcmb4sd0dXo7x$G4sT7JLvV<1VA}#kdGa(WpvSdwUNtQ^I3aLa{vhQp5JzJ`KX0q?w zW8e2RJobHg=ZeSgjQ9QL?XUaOIo~;R&di*dIdf*N&`xb@4(vay|Hz0@{UdAkO{f_( zG-6=?PQyb-4QbeK_|TgFzkjBs73I54EKYyDMV|JRHE>$TsCvZ7$NTI6|zI<5%P5Pv8Taq8qrRS|!`5O=DtQ>}Bo*pW7Y5(08P zNI9yuJiWj07vh^uEX#PkMgMoL{*tE`H7xj3E4`={(rP7Y@`oa1h&unO3Di$fM6L9q zR`_?V{%8&nqE>oQE8Q;{=515htQ1?);=2pi?4gyXQMy^*)qPuYsO0yMq_z6tuVYGn zD@xIni~3d}->@>L0f$@~hu|#Xl4VR7KTf|R-ii-D+JI{uf>ZxnMxl^V@>~0#Cg)eJ zUY!ZYPHWe&nd4j}>q3jdk`x6!bYY2Wp0la>G6HhRGQ68Dr2dwk7}wMn%{@-GxI9q2_XX2-Z?X;9^O01g}kaf8AFQbF@+kJ*6y$* zMKLS22^Uir5>q-gg4T@%S}ic-_|6YCJ|Ounr>K%oqX z(0a-5S_v6lSK0C^LtRMhjts4yB^0gRTAOHGn*Fq~sQuQgp(shGta+K!PUOeu98L2- z2v{yeE6VVc#>D@aGg;SZ3DRu;yDS~FkJej$%PUY6y01Rb8M%<1U5-%51<_hNXb4R= zMR5r?=bEivnBUUcx1?5DeYKwdn@el+lHXd1in4H_3E|6~Nv?hzgJlV>l5#bDplso( zH*KLNH5w4hFki0OMbmP4MZ*H|`_D+-@Woo+B)6#K|B6y)XCIb-&6(IP@ZgXF5t=+r z)~^w@X2Bk|^I0WQc+*EhK(5ErX6sv)o$*`7i>~jOg{d)l@UJ_E6o}CD)9mz1#*k18 zUhB(Iyn3#Wgn(T0<`nA7-mm{hh6CSQZ9cYc;lUvVBA}O0lvl4C@XzC%@%^V>5(08* z^9nXD^3!anDC?5Ec(Ar$H-7i}$Pj%p3!%|sPeiI1+xiaqT)enmI)c=x^kX(r; zR48J$vECd~AVRdBUTdpgi1kUv+_B4BwuZWMNP!5^dSH(7Og_f0W?1k#LwqCze$7eIx|r`rVIz%Q#gjj=HsP z%xy$(hm^k%e`W?nsk>+kN~+R;5ARtrqO?&|QkFpf;S%FU6(j1m3^Af`))i;|dqn-A zK!j+$KQo-71kTxmJ3p$#pWZGRQGXDSOSFZmS^k%;vP0kDJ7tY|r8gxb>JJ4XM9=@T zmJqXZdkYfz`Y1D8R5GIeARw1$3stlHFB!bE1L;;}K5G$JGNS%aAVTzfu!bx8w*g5R z>dY*kmyD=C2*@S+u`0$*!7mwNM3Ln45%l+n`a}5}@!z^sQN)NM=kvYL?-BI}p_Tg| zml!vy7*V=kGQ@}?VnpHJBkB(YB1AtfnWz4YC?ZA_*5#Fqs6PnECB}^^MwI$Xh8R)g ziggiw8dEZ&{!k!7^M_h1{z8ZmMbf*!#lJ_?9|}Zh{!p{_uUd%_g-tRo$lIur5%mWF zxio*Mwc;-sVnksvqDapfB_rw&1tLVx|Fe=+l$+NY;hWh`#3ij{MEyZPuHXImw~VW= zMxpG`#-wm|$%xX%LyaHF&V4SmK(o_6;&G)0(b#v6IDWSsI*~ex9(eDF z9bS}1g|CNEvuqpOIM@a$O14=NKN0DyTb)-IKUtMRr;qNb4%+U7j0`7J``|cTxk`uC zu!j@rpqWDpCqAwr5F6Gdam%rLklWtRXvcs^n&8(J4Y)ZTowzoD4!AN1?PtAE=PEHY zXpkwY9TO=K``(P@Zu64RXEPmM;W3ULd}g7(xELsLLD^!}cg>mK9H#PZ`PpbrC0F{? zxfdPhw@jUE(STY6bfGWjIUs+xK>G4z0PVMHx>y1DwD9IxI~(!)&kslxh{(R&oRVRL z&ULOJY8BPmn47h&#n)TjV^GGSnSr#uVN2>gwN$}YmwI$VPCxpq%`FeM<*(MYWL+y< zXM5bT=!B(<3)e0%Eb#d>ktV%9qz^q)s^CSxbh@hV68)xgE}~YODv#r0?N06c6ruDw zlj)wf-wW&Ju2!LSH=WL;)gQd~t>s@@Ad=RP<>_r-`7L&BDYXY|1874<33VRFt(%QP zLrfB+Hh^to+B}k$yD}Y}U)@P)elc_$&t7_5%^5laK?+1PPU}b4J>7}gHP;Z9tH$$M z_M`Ou&zP!^lD#^TS{~bu7HvmTNs3~8G?~9`dWLGd#UJ5u^!+;n?6LWtx;rb1j_z;) zb(&TK!IBi^XRT!Zxv>>{@nn{|KO}>`c$iBw-ud(A)!#xOsMS1bcoj-iJo|SH{Ah2t5v*b>*hnU(x&P-lTo5GwqjH9nbha z1a0{2OdH*5gde=`gDj0&(TmM&@h6{9fiR!v&C9+$h*nf>L?8tspln6yncIj5`*{oR z;3>&~=mry<=-0<4xZ$xBA;Wrx58vFh1s>khi9iZO@I}q(ot0&ApQD2XqEc@!zOdtn z62u0#CbZ_+t4Mb*8x=07N28`*Li#z2kc?=vq9OOa8jERJHv%aT0c9&n`mq46H|~g= z>Z%eb1ETvMX-Q8X*^Lg)oh@o*S)qfdl{?<@y&MVo7Df*YEJhnGA`#?*Xc0AV?#TJ_ zs@V9MjDTEn3tlj3#mQkioO0WiKng@ayD3WK>sDNU=Mjo7T}?tjF1ZDBLwfK^|IS9b z8wL^r_AA+o-gWEE&tANQitl~EuvU-@T0~La2J{l^9$S3@Scepn!PdQqKwsZ{c! z&~pYY??NXpb)xki7>Zhz-Q1Jcx&E2CPJ4qQ)()lXbQUztGFydQiG}^?ivgu+u5C?$ zSWq~CkH2(=?MwYEAs|;_;sok%ou?l%?}YG)bWANia6mntGovko-Whsrc{W(OrWQY+ zZ_Eut???#9wcchRO-A;#T2Lvm|7cp7@NIRC_{C7nAO#|ze%h?&$IT1HYmhd~NN$n7y?e+bVzXUSV$UnaE&v@S#|%31rN{Nvr7Oj}z+3bd#! z!}Z!|{=#wy3mtY8K?+2`{wDm@*J%E{+;(=ffg^@oumukpjH2F0^7T=6&Z5oV+K=R? z-lelsue~J%I}U z5pWh2o}pI~r(q*$dXlAtfLumk9i%9q7A5in&0Nvdx3w{xEyw5dqSYd2A=7fHf6Zz) zz9n({bz&tJ%_T~;0fT6s`F(V4vmcUYwbVvQ+`9TPYIitKqCfyA9kUMwDTEBComSAPrw&CLti#%d)@b;DA*j0#PMz1XuFT1kzU&5uYg|}E=z|rd!G*#6>=y$xX4EkZ zDG&i`t0>7^2k@dEE5w@mvV?$K&})l%uyZu`9l8Q-3*3hx1tOq+igNYzK>ptG28zu* zEg>M6JR5kaLwRsUA$oT`4?_w>Tv;4OU$0n*3NB9(*4-IDiihlIhI(wBi6I3dWb4w7 zqxq7sU^Ff_O+r8}*z*-7+$m9;qtp%#9vD&}LSFS%TQ-j8Pn$&D?kjpof$K!L%2br? z`i3Nai3hoqSOu@lKP^r*RGed2u_Su%Ukp*~^h%<5S|mqNj&-O*1_k(%Z{a;81mx0U zHCjnpBuA{<|EWZL&U=&bgY_6vAVP~6Xb3HmBM@hdNt2>S7B55s*uZ7-%xINRFa7r7Xe~CU}q~tLhL)fe5iT{1fF?ln&FXVDGcO z2?4o;?ff(unk^N@%hv*3N%16OoIMGoK!mnS)%4KfHHwnxYs+>fdXUw(8%hYs zrNvG(gk}vzxo_2rov-Ulrj4v4At0Bw|JQ1zSzokyFlAfpeTdtgiUd+1Lfijq2+fva zuD$+_Sw*^&MmLQJq(FqW|JQ1z*-ue2dR5@t@A{H5;d`|<{Zkg?YPa-A$^VzWc_L!r z?(H3TNUg?X{*I{_QXm3GqZOssEH}RMnJ0uo9TYb)_^>P=!cPzEUwA=;q?q1jR(a*Vmd9Cz}d_ge-j5Fy&3q*j{!6h(`2 ziU=psBApNcxwM#!R;%P$g#w{PIYoq%Xpv4xfe6u$!5Pbp2Og|iCm%9R?<650m(~uN z49$L8FG-;nS9p+7EgP4d0{ln$3-RYnN36)AQc+MBA2Re%LkS_u{lle=F0CZ3ABc7P z^nfw5myNwDcrv8ssoYfe0<) ztm&cIPf~lscw1drs8b0@8}8Ly?Cas9+rWg-^vu4m+^DOa|eB3KDphw{^WKw?5G}9 zT9{wp9C}inP=5=uo{^;sUp!6CbKZdF4u}D>cG3cTb_(Y%reK+b&R74&13f{;eN!tF#8yY#xZdU+<4j_8yHQkM%^E z_We-UgZXG)ZC|mhUjD(KZ!=Odmht)=YhW*fH)u2GOZcNHSYmB)H^K-L9~q6HYAB$$$5p);)^Kfsfa06@Iy};1|f)+ z5np>IlU9rVL5s^SmMjVpup~u^%^XLn%vwv6&)?M-HyMOHhg?8gZkwSUfrHRn-6_<{ z)*ZoiQj|Uk$wWjt*^SEvwD$Bkqz);CP41pkAp({p+M{+N**w{m8CRS`Yn~Z~?k2xS zoo4J(AzDVfdN-E%zw~0d*d!WxJOhpX>4j zHePtu*&T(|M@>QcVih}>G}Eu^o`tktIWnY~=C{#ghk@(Z0KNagT*D`Xtk6R6oQ48=n40csP?9JxK?Lk*re0 zeF*`%@{%Iai-<-z;jyLga3MSTlHKS6I@BtN!QL>|ZW1b;>VkLvTTU;x`TJY_$>M!) zP^(218SH%!0ZY=dcSaCIJ2J7am3ksXK%Eq2%)&@=;OtV?H7tku&hLw=O?ZLM6tz+} zTM#`=x7<#nRG z(URe-5m}$5o^kU+Kb&@>q8%O8l!R8u;KpV&s?KJCIQyjoxstMzCH8*6V5>okLQ9K% zRFl@k@x>_?`TB{3fLxb4`lG`9viPGf6XRp@KkZ1rV~yC%7iJtvZ{0i?jg6U)44Yq4 zVQs}K{82j+7<`%*FR+yKfQSV9K$OyS7FuC@Q0TF#*8p<x`RP-PijZw3(K#xq66;Yw*l z!S;u(DdLF@hLS!ao_I8NJA?Lt7KOc1WHc@rLq3}osymksm#n*_Nk4RFMKW4B!4<)h zgyu10h>yr>^sF*3Qt;eznzql)T+U5rOc-N3a3iKmNhHytM7 zu;V-E*qAZsT9^qsxciz4xnOGwFKRG`TzxwcH~4%=4-t^7`iVp_GkjEkEHn_dS`jgZ zJgl04_hyDsNP!60{)#e$b8lawcfKk1AJz;~phtB` z8jk8dt%?p0-KDkQx?~b(+zMrVe<L$8Sfl zz7PTR6FYj(zU2CaP~6`xgh7g3pGhdH>Kyg{euDyNLq!Se9ZpsaPQl+cj9`!g5wK+y zrEwE?QrzGa-nOR{zY>&;^1Ys_N5&fz#P#TlCLXPgv`iOh5k;w1t|Kv>?S$sWh_6t0Kc35mYKKhAVs6b*_op<@jKA# zD`#|WjTB_{Vk0sft3~e84^P6o!z=IuQ(ABsfr1Da*V0x?eaZSKN9lqQcNkoG!5JCO zs3HR*xjDJ9;}RtvHKnyE^rFxQD@wa_wMg3+JDB6R1{_)xu5o3}JIt;`ynMH@SLwb| z3qnL-%^IlIwsi>a@D-jRu}LxR+3FfIPH7<_AQ!ZPq6BOoNSaR`hpUZVBdrtRnhN@S zMH#WV2T3pPfGr;`vn1Hdt1atPA@UT*E7hO-v9Om^G7GhM7nR$OZd?qV(U= zo17@_!7PtllX?k6z+Hx-M3-)ZMqN|*^%~td^`7K4|Hm41ul5)n^)B7y%SAokp1yA-nRfgn(Rf?DhSvbX4DcJ?lnd_ykiAb@sg+Tv zWc*K_jOe!MKB|Anh_6fN%3-;1Ovs44ZW!4%7|z5hR;m@0cQ4mo9a?iK+7_@vjKK

D&qw$##Q(VVWnp#jkQu1Pund7{(`^#+KeiF8M$sHnV7YRwHf`L9 z&Tfy!WLa#99{<%BM$%zPV!i9v6E)9jOOD*GBt@N}9#B6KXSn$j9jX~ZMmdz>FdhxL z=3F1G_HHv76}l9Pn0}QTNoc3{Cp9}UnL~@hTFH8Nt*MRgxMu6C{7B$wEw`&?vzDRh zv-j(+J*YY-nZH~E8sL9+PII@=CCI6`A6B!b~s8Q#4x@ZUmiD2ZE|`N`e|IM0Je?X9xkWH zVJ%{Nd)`HMVZuK3ux%;|IgsZExi;mdscBA`=zes2(G%;(XJa1bLCp3#a7ckQ8T|gD z`laqfl=H|%AWWtOJUqM6T;z~3g;_m5k;wf@-1#ZXet|8F;ub@M8Fz~`9p6-;_9d4{u}*ykgFBi z^JW&x_a-W=$&-o$@>xxZ;jO&>-Q@xoaqH*Vhv7d=@K>b2zr4j}b8dx(_99ZNlnYPmtz8=UnU4q&d_HqD9W#ej{>f;w3!!qc1<+xGK6gGalXaH&CHYvK}KcR$$-3 zrHIM4)*Sk%gT-G|%V!hO+E(l@57%e(HoS6R9kJ4Ik;XYh$ev;D=L@*Mt%taoV#y%| zBH&qZNoEas{f{eoweArcRJ#HCp57b1r;~J$3+g8_&&Ydmhou&2c&)OeIYdBtBI4DV zaaBM>^+53d~zQfwt$C0_cBwqs2 z&{rzT!%21|u}2qtfDjHn4ji@6S1QVDI|mYz_7C1*S)0Rg0MV&8-B2tYiVTyyg=a9y zv=@0F)kvR*uNdrckPG%uk*ELYF;eE(@yWJ<((1KSr(|_w-{UCP(^wBzvWn6?Jp>0D z?q$7h4B*hBa9)CT6XSfTEvawz9Z#foQg4Sk!5WHFnSfYab4w>uy;$7f0c$n58h~pF zMVb976Dze5Iq735tui1&&K&sJya4wp*Osg8vRRS7>b8{-5Ush7a{Ri4iuq+)Rk z`#9E*FqROIOODV_3-%%U_GQWK!aEGw9dbdPMBhCXAaZdk5!*6pk{*x?o(_mTr(Jte z`lvZ^?BXdQAQ!ZPm{aDf9M0QtK9_f?J*Lzn{s$TsR=30w0&+pSDT>wB zfuxSI24B#pO6MPNy#u4FigN1AVA5miE}VPUNkTv_7(o)*pG{)O!LO@vdeT`6DG&jp zRN~Ihq+zI0c1_%e4lLQ@G@j^+&Al?k8TS7&dF1S!uFtojvllCiR|FCz1mwDsH(Ph> zcx}AMWRfW9?c_1&?UugmMy+@W0lBn&TLH7j+mECPM89L((Cc@{*^=Zzd`W1~o||W_ z@R9>@6mo^uHc=-O+Tn;MDFRU|>j-jfzJvwlkKm935m27+B_dW*C(s;=Gj5)d)l)6| zzypuIn;~Tj>>j#6U03Xc*PWOsWHhS37)QsM;eBtqb4Y=iPB8C4Q6BhC#;;!6i8b{| zNd`oJebPzIGpUaoztuF~?pP70AAZE1wCE%0aXGEA8Zf0Y{#I=ig%(kixzp|CJ_1G0TP%K%x{RfH43-d(OV(q~>7m%=+(}j?FGA`i5CQcQJ`pG3 z;sSFnPWL6vg9oltr&hAS8((*%&jG|(!48&6o`1;V4wPNR%Kj&O&_7TzvWIOGG)0*W+M)*2>Y1auL?`0;Rn8s zyuH6CUq5WCnjUY2L#jGc$OUy0>)k0mNdJF)+0(giq--jfK_zGJZ2s7e94qI-!snLf zFb4{9$$3k8n_G}ikK41aDK=7W6hy2FXoFIAHNx}GcnHnEU+^J2;{(`YQzr=lxr`n* zLFOIZa8uJDfzWREr*}V(-hOwG5RgmGjj}7QNOp&xLpF08OZit20kf=x7rj!A%x~$- zjur(-`BxBeIo%$)pKgTP^yn#S)g$*du640G9zVD(hrSQyV#zXGHg^zjq%2~=ejgdM z56q^zelQ5tzgZcZ=6%zP459S_WUrYJa*`Z2Zt1hD2g*illxW2lP$Z7 zTDi@$BXL0!+1zbdLO?Frx;<-FAbB=ZSn}4E98w@+dMyR*{#qBSAp?aBvC}5i9=2q; zysdN6-2z#7cheHZP7_2ozo|)G8TW5cvhsT)eB&A&;JD|Et2*?GkAR>@okKr{7 zDzn021ErqGD%@1V$GYG;QDZ3d!Q#}iLKFNp$`L<*7%9zBaQ1<7yQ2Kt>lNM+Z^U+| z^p<2mi$ZxKI@raKOvv+R{nI;hNP!60HewaN_Ft@$89?`qOwnHlXw8n-(8j4E_Rc=DCB}@@fH$N$oBbf#rtsH98#b> z*ft_V=!y~Pu=^~t*oQf!Km^oDtopoC(SZn+Pk!gZ;T}+%4LVOchm24sJ)DEZN~ZK} zw8>WGwW6H=Li}&0_Uee3uhwH=03()JZm6s zPdZ6+6r6EjNn$tgAq1a#=f$gexJWV}0?u6`2JqlAwk@#d(JuA)?9GPgb?Z`ir)g;l zxuDe*<=bVH(@sJ_F1c0#+pCbei(atYxOx%-a>2eJZqeN{AZG&>FayJO9F7CnGvFu? zE9CrF*y&ZGxbGY$As`nVX^LWJc^Ws$?jvsT^p(aSM97|D^MLKxb%!hWT;(9OhvoK5 zs>$KIXiHJH9=46Prk)^fS~TGzOIjLH5Fz&x;T3SVD&D+NeYuxF1RMoo75?%kKA&$b z?n2h$unpkpJIo1C6mNAY-qqNdU-5S3uw2Lm&(%fFcETs@Xi<&tvapvlhw>m=Sl7G= ze_HCq*DjWA1-YPX@uJ+v?s&_`hWufKyHqP!6IpZNb+Ea!16S`MX`DlZ94Wf!o`P3Y z{a3uP)kVrRfRQv9H4kyiT9x6AvFw|1*>S~&wgv|Af# z{{azj_7Uee_xj>K4{LJ!cPfWF6UYTUs>r``D2>m4sl^XeZzdrim%O`MA_{Z*T<{>uqal<~Vn4s%s|zIl7g62yNL zh=6DJVy;blg1WuQV)v6rO6MOi;whhI^k_B?ZwZW`x97!4=e3Yaj#FQ5JVU&8vJg2Q z9VsCo7mRW%iapN3N$L??v?@$G|A1UDk}jejR_5eI*8ozbRkn1)4fZ8?H%pxSI2n`J z=1oYoMpU}B1rhK*mN>PnWlJI}I}p$EM;W9*1dM))y@9P6sT)_3^nX{HLj>enl-LSI z_ic)_95(UdV(V&T#iUZ?__8t_QXoQ(r0RCXlYpHqMEvR#g*OJ^eFK=~FY+uaj3oyq z)n~Q~N-;=*IifIkRNMwMk0U8YE!b6?b`k<|!MtZh$vZugY})9|ysXlsjChEUvtH^9 zi6^n!@~Me`kd)sJ5ikcQ$qyI z%oT6F{Om*gE6-4sy2Vm8X7WaxA^!R&U6JB>dkutX6i87q86yxS}&6f;P;Jyv+^n~U%;iUP;{_hz#ri7H_&*x`_n2V6;VKu@?An_l23buD%?B?;pVzlbY2Dqv_AZ&ElQzNSqIL zaphgDrr>B3TLLK%QTU=6bxQEUX*5V69-i&U2VJ>{FFvy=^eM=syGD6o^Wm2YX3fi_ z+6}-OUta2lMQ4@#E}G?1D0*TUD{k)k29I&AKww#FhDQmPS$sDHWh;tbovLERmw|N# zt`Y*i;|0-T{zz@jLyhm_L4jTI4BN>xLEKAhvt^9*;z?=eRC-is-nod1bG7AaPrkBx zFMKm-CWdd8z_&$Y#G#>){KyS2Tz8SHBm=&^0!va9-xu}_DQ@kVy><-%lT0yL@tQvBWSBo|6VVgsXUh6iBnu@lGi!Uo$&`S;GTWXKS zLl#|@5ReO6K~dh%A-uTVGaS`=jr5)jM98+9TO)+0j=q3*HhhVo=CEyGj}hzL!vncE z6~#7r9V7(gf_4-8+DdELi)D5^cykjT8n!|IYKk#V4r@eBGH&T(ubAWUZT#ug(!=z- zMq1#?>AghsV_dEg-|bhK%sg6wqeaeifMqxe|970uXp}wOP_ci>yrhe5Pdm5qL;lx( zifqGmMcbGn5=zD_wBqv(slG?K$>>VtG+i6Ny6b)?&t6SG=;X9=%jz2(inS2Yd5{O1ni`*`rN`ctwK1Y zKm3=&c-t%$BB1PFFD|y<{D@9f=FsGM18G3WMbvqv0fO)Cz;}4W`z7^~Iq7;GId<78 zz1|7m{v7;e2*oEnQShLSNOClUg3-Ofm*Asyn>9q-KqqL?P~uipF7 z#CFv%q`((K<@ZI~CLS!fSHRY{bD&XX^h8*@d*b`x&7I_&RbzHo6#@N34 zywr-;G`)EvasS7ILM}LN6y@&n_WZrR6dGh-jEGN%e8iNo4h<9obSTL&WNqK_nbklw9CWjz+H7QR!{te&=>aL@y>5i&aU~) zkEGMXV&1hin5&1QHl*VO+AGHk-@1QNjN0gt!+4#1mFWu?O9;qit4pEJo;zT_Qa%E) zJ3NA)@G!!ON1_$EqeRC(cJWM9cJ0Njf8+)@~G9`Rok8)!uB1HV2}b4a;*xl zjpasN%Cqp8w-nY2qGj)66FZPUu&R!W=kAaYkPCV~MVS!Oif6m$u^u%Iq!yfG-JCWq zsDwYQ`Jpc#)rp>*XNJ3)%oDcK&OOAN`fOp@uMD<1%Ua&2lp~afru%)VvEE%l2J=e3gIT}Ts~PNlP=?&*Co9GA znK=X4wD}FCUIMw`EFrQJs*U7B;>R-6YaJM*Km^oJQ6fD0^Y{6S7+RLY+)H<%jo+O? zyN+b3kW1D)-Dfl(6;0TM2P#`$st@gbr2wVgE{)*q1JPoyb}f#Z-|xX%m98gQ7b0M7 zwcE=>I4U!RwH%(sVBMjuWEqBWL&Y2w!}6o2NHU;Ku(pcQadsu1-|`l_vY`PVJFFHR zkg*pXGy0}`gnjATQk#+U_cRr*)WpfCl_R(QdV+l{ZOSvsQ&d@UG^pLLf#`{@_+%JVr zuWLt-jhc);N8J#J@OCZv%xBZtp*rO`EEnn_*UIr(d-2v}0ITxDL_$EW4Mjn8QNU6Z z-0-lFVfiSCXS{Z0x&kW>DG)I@4b$Z{7Natz>jc7LOqhuC4Wi0*BMAYyWIeDls$2sx_XTVHBHV&vmS{kiBf%HFt5Ja4_7;2 z!eLpE3!;VhiRi`WRGWp%oH)TCWqA3n)YPmSikrD#g(ZnRnPGuEIX4o0ePzpGxsVI$ zBr;OAxbmgP8;IMJ84T`mdaVwj2aEmC*W;Il=-!#kqbpo?P1(x*cJza}#EK3POD zk;6n=o^eI>2OxEMcSN`Q^h8IKT~vrxlsVOEi#O;#VC`!daKGfgKZeFMH$x_!e&)-F z+|X|P`nIFE*_pMH=EJVFrRA1(MI+ZvQB7|4r%?|)(f7~VtEVm-Jo#&IQQ+xU)hdk56|wG#vmMb(65L*OzmYA%XmR#s!xA={bY*1muEqqW0Dc;YGgp+4}CEBn0GwGm*GG z@M$!Uo_~xUT^z-ZTnncQ3+JJ^Eovd?2cb@ia{16uu0=U-8_#Eu0ufLrky&%DJKxuP zEBoYrn8CV3E_wc_Y1c)}I0YuDvCLii)IKLEiNlQijI$}fF6$bK(Hi5QH>J0 zcxe-_xi>_T0TEC?@y1rI!8|*03qIN*l);)nFDm;IbYK{-v2Hy!t@VXM1mxPbV>C^? zVv4SIzb!^><0ehTn}a4KF?AcWclV=1x<{eCx!ok62z{j%*>1%h@^9c5Nz0kbjgho( z8w-?wC`pA}viFIdrt+W%>#_DCJ48UP+A(R=Yif;)GJ zhI@5!@^dAT+nLwI;|EShkPD(=`-}H|bYuD4?Dp6**+fD>E@%<));&t(n{6AgHsXsE zFscIApK`q9_K2}OuB{vE_wpKr6o`N;Sw)FIn8@`b9@1@d9!fD8=tW_CMnop!lDVT< zFDhdC6jC4pe&s`Cu{KZAUV^5?+?YWMM9AJJzvVdbC8#T^>9=+iA|Mxx0V&GK?#aAn z(-COl!i5x4AVMC4wltaBCEZ0{_Z1yPKrR?H5|PwSNqqAb8@%Gjv_eRM2-uopT~aQI zU+z{FTY64M5COShj}g9oW-y--Z;!n<-D0r6!afFjzBn0uIGERs+mG*z+DqXWgd+-i z3GoWl;&Ab9!fyOFU@3zh2d?L2M3S08H-Az2imfgsdHT(}Tt-0^)ASWOdg~+6Ma0?- z);~M(PvPUkM%c&)iI~iatv%@7gMNHW`-Tz%a*5OMJsF{;aZ~3O0#VqufZp}AY*#~!^;mZd5eT-kJ_f4kA=e>d0r6zCPL#@tx@Xn7sIjo5m zH~z1NGD3V?gojM~$UGj^;BW`we8ho{&|N?^_L&#T`>5t037fm40k_`e$+wzq)PH$- z37K{4C220l!s80hv9>*pxGn}u(R0Z4Zk;*Z9u^V+mSKQVup2JK|)mc3yg=LbtNpdJg>z144Nvjv4d(F;8uu0O`S*6e5A z?>k8d$OYwz)1^AjeCv>@sJoN$Vy9>ir+<~P9A#8BR(o5l z)vJ6xx_WA=KXnUdJ&qTM zN~uLutjN%a&51n2Yp%Zh@;T^8BfSoyEm}3xhwq(@N|j$J5HTmN(W9N3s+SKXONi!1 zOY~p*EJPnkk%ZRXddZ`y58u=1(qeW4wStHN6C?CpTIQhBcC&TMD%|8F>0ZS4u{2g?sliyY2sU3o(aSp8u+ez#uOghmMNd>IR;GrB!|Eq04d!TY% zX=0OT5ycrTAz-V?wX$unjUG^&k_Mlx`Fig<`W^Y1sC?nS;x&r@wSo4#?}{wcXJn3e zpF!k=(+eRXB!7_U|AqJ;m-yx>{`DfUc-Q%Zo;F!ulk`8M<4Zhi>wP?CpwnN+OYID0 z3oq8MlK9?>4_U|@Bn0GYeIZM~gik?-x`c@KIAwc|rX}1Hx#xX3>~YYd&~D<}nG<`k z&)vr3K4pe+eb0mXuC=q#mX#NDu#a)aefqeXStW0Dinmy|gs};OZ{U=6JvgMm-Um+_ z6=mhtYV1h8=NLWdCY?b-1hk0wzFKZ~mc1g3SbDx>P}@!07wSWNC!x0YHv7q%YyGxp zf{rXKtjAwWC@vf~DiejpDg_r>Wa^I@XOx_b!ji^E`JFX$*lDmP_f)D}aDax0e zxm0}dM!c3jg2TGQz65)W$n0;smWE8bjAK$FB?RP>HLt()I@5A-9-r?c%?8ky$e#Mu z#yKL}cQ3PW>%*b1tvakozxw+&G^u;2OS3 zbaX)*2?4p5RCT0PQZtY)bdd1Wxuxs!{b~hl{Rv43$OWTR;*LpFIlesA3J3QM;jr93 z24>V`$aLfwQBQ?vktb8#n|EG9amLAt{9u9)H5r+7`y1dk09mb10x0h-KxuD&|S?bltEZXoUzHAY|Aq64|GK^^F zo2kfQ*F)hGf9^2l$)7f3_xt`Fwi>hoEJ;yLtTg7z9ux9pMm9cHA!6YP@PnXG+{c`T*PP-#|!Ga2laVx3s5u!_E! zY)aD@X+;JRa4n&o(br(nrA?Wsc-aV+1-YPpin47^UH0?xBrM)_mgYgIIh-ZL>)#g$ zyV$S}S@+OSng`(wAkS(()u*%0<&l`xDoY5+1?{FN#}CxzkGF~&XeUoH*c)IZUG_fr z#jeYGpoRF}gb9ZT$R&@D*v~WQkkCea=L2tPcPD1GKl?U$=N0^_4-=p4QM290NY;fG zm3v8#W=!1ct4?~HZ7B72*b`yz5pin%N!$_kA-!h3k~D{0a=)Sr$FcNEIubXpGKVug zTmiuR2{A`qT*`La1d-=OpBY3zF1bBEKcmdTwHav?^oc4KQ<=qKipuD z0<$+@Yl?eC7wU*SnQG)=#6AYk3LqCeUPVf>JIZ9%-$%wQY_a{U#>F?vSd=U=1!#5V%9_{HNGSFFWKXws>Oo@dBZ(kR9~SOsV_p4T%40 z1!c&xw@f!-P5Y#?I}2ka8L^eT^h=^@W7{pMk`=_=@XGC((z*+~|2$UG10uxxxcX8- zj(Ajr_IAQ&iz#e=^aI*rPb`NN>k$R|*DD+2mJ25SW!+zKA2as;`WPuc5!M}+Bu*`} z6z2K#8xwb!w0-R#n`pl$b*g{|<`1DJKfLt~4Q%iR&oQD_|Gs=FYIL5xvK=5HAeU_Q z3dbGU@`yZ^a3o5y6+}QQh`)i1p0f+Oya6}5^ESxJ+s zG~lr{bfQ-Oi_poDyZ`AV#^8?1ETggscl{R1q1T6dPPi8lcgf0C5%cU5rn?=^Aq67f z?p5Ub6bxf^>TYL+Kl@7v$OYHIA{VFQIaW4f1nvKBfV4t}D>Ast5U+Ub^<}vsrd&5P zghPwM7L>DbD^#e!IzO$&W2~EUNP!4wH<6P%#+CKQuG~QHB_SZ!$J*WXD+e3lsySYw zJx)#B!^)g6<)QWcdE}@feVJ!g*z-_NDK8l23yX6#t9bUkuM>aKwXq}vmJ73uMJ`T_ zKCH~ECj4T&6F2L2Q(xuEeU!Ljt{x&_^i#wv>(3DHKh)-lr@T1K3x-@UQm80bQr^<8 zt9-eugDZ#SLe1qUu9m?XJ>Qon9CVQokPFHazRto=yyj4wPiTWUlnxQFhl&%$rhV9> zPo{izOt6H2T(F0VRmP%eET_c>RwgY}LO?FK3m0#mEn`eqZ-I#KhD-Z%*k9$iX#Q>s zKB|^48TE}yD;c;NfOESz+ZNw?iAnRo0a4*n1~!}x;P@AD(U~_y)Xs!GAKg##4A2|M z`P3VZU1baAZDLv9JM$)UuIW!bt&QKe9Zt(noUZTk)()3(il@ZumcGU7s`z7kgy_3k zCi&%~J=o@d`bh{V19~Fu`{#MgZDA&x|E;g&si6!gTkLCl8ghsE%b96*8%YMNiSgP> zbXq?L@&17J+JZRcV+JG7u&Ci79F_}57es4cqpiSCo$+JaZ?%y!$)SB@85XQ2zd1XQ z749Yy0&>ZjvQKi)vy>Pc9And7Y7Zy_=DLe-xV>G?n*VbFFQ3#*LO?EvAxrnD%3--MmlLA3uVCnS&la173~LT4 z5CL;M#kpF5FZYg|r|q951muGG!XjEL-jN|MS&zj_>hpWarErzJTGH(S zm>mso5(pU=mWyxW++bH;bdh=@oPA)g6dCb#X0T{3&T?wClV$^mfHRS}6F2M)+miK_ z^=aTMBfuRK*cZfmGRwcP$Dgh@^hRO zFR01QM>+Fn+e^{gO$_nC38vD`7kQ5IuChbim1)3-h}{H4KrT3U3BN1e4|=Fx65pdY zllm3RJc2z&tTJY`;MvbkvzaSCF-U<3Ip60yy2ZLpvf&eMh&c+}kAbI%&##-%6Baj+ zSPSb#-cpXjuclSto6gkbkOC3#JW`zSmMO~(g01+s({>U9a=~0)?NtA(cqPP+E48aj z2*?F(DE5PXru^VnD{kjyD_IvJj-l$bZqu^((x$RvoQH`Q3Q`mLvdT5qnUudG?-EM_OM& zgxnrS7kp)b^Q}ato&$%gJIE!sN4U7vuiXG`zQsvGKrT2Q#jdDvCtiPlY3!v^=_V4q zD*>~=wf8c5bK@6|%<%DZDK8u%sL0auf7G>cg+v=Tp@ zmx*1fHRmvX0b{x_wk+O_`sm0#lby(nxLhgw6Rz7}CaB0~h?vF1&0;dM%RMPl1Y>+9t_c55X4;$&SQ`Q5iny>CcOeE{InI4Ww)l$OZFZ z#Yy#DXYqpIzwFSA3K9ZxL9ea7HCcl%NiNHqRH?`z1tOpi7Wty4bvW%MsNxI2)GlB@n<-ac-UHayT zH#W!=wOXIlpDgX6!%u%y!LaU-3!+7w;dLMpH{z*zVKWT5Ao}UW326L#N8HikoRG1m zj1O71W+vVjVMfZ9ibUG|?8V1xqsPOWp$o4aah_=~x@FKC#lCaIADTBn;vDBiGg3b^ z9a~TNh9LrS?d>`MeHMs{w`vH)$?k|K9lQz+hOfl^nx-J_W^rch1$D@rIOHa{j(Zs+ zxmK~?TuEIXhMQK3kPwgy>LhNHpQ=W_`DNpO<~Wm8&AdwVSflTPwmoZrCZ{#RTZV*7 zI{kV(`rE6|_)rT|2>~^S`iU$H+a~13v|^mN=A@)K)E4TeCIx0wSi1z*LLibm+Kox4ZqB{e7igy|G zYWw&g)Y-$IuD_ovWW<|BlFeJLu&{rt5vo`vi8NTR!>R5ElH&@TD zRS<}~2giyNvUx~kRpC#a6VTyx6Vwko!=$fg!>?S65%nTTeEEGN8Z`5T^u=uW)xUy* zeklK5Uz9p&oRG0*aVL^m##8&oAu0VK47rzmj?z~2LrcClMb26KQ5VNqXm5=c$nbd% za(}i+AQDp>k>HF(JhNv*VwUZQ%HJ@+_ityQ{?qHC`0$J9-K53Huyz2dJLd;l+Gw;u z^l9WxLhp>hrn~DANP&oru3qREK8lujEf9$BgS^Nti*UTKtP3$a-WYupF9jT5GXg<* zup|-780tdk^6q%aaxV!HVC#&2&a%Q+!$(VKZJdi2PrhG3b8BG&$3$GN6S`BeChq+q z`mgaZE5%8?Pi=*p+vx}#6A%IAiMWre2XX9H3-{^dAt4|a)K9z5nMA4;Rbz#RnUTnM&kyu}y1MRw9@n@3O+rFeWENSW zj6!^$`@X}mWn~j35khuJcFNu(ag6M7?Ah}?cQ(f!naAeXWF0f!>v7)q_kQl*zu)Wn ze6M@o*K^(1D0#L3!@A*!rqw<Hii~>?V@3TU zu594gj>`UMSYkYT*>=A@V-#2R3eEYj7NWY@!R%N5rn$vo8td}Cf^OC7n|UdLUFZbXNZCAp7;{~c(|9wag4TRr1be;5)3E-D za?tf|Ox3gBnROdAF_D6Z%_DlT5#7ofBW6vYv!rujZ}G76Co?1Xj*0-TH*^bKzIuwDJ{~9z-ptK6j`I>oL4>;61M@c&SyY4m!mQE?0=fQcpYLuc zM6Ditm1hZoXB2X&XGwhDR-)8I#@DvZry%gOLp1qJP(`Z&ZOZV(w|SNG3K7^pifWAO zL3xU(-jUZA9?@nXdoskG51LYf;Z24&5!tVrbrSSh%MMS;DG-5Ns*G+|yNc;iPgux2 zn}R?tY#~_(J$eWayBq)9@h#7470jMh*}yVCO=rlZp6vl5PNa-lrZu@=kKZhr$V#uN zX#ck0q2}s3fxR0wSX=bMhvDub%U#paBCM0m7*ZlgK_J(tgt07iMDMi6V+!-Q%G+b&{>T+MvSP-GkNBf5(#FkHk%(n^79RCZs zaHMUvji+M8?&p5yuz&6|q#y$4-|9!4AnzJu*RfoReuZ4>4EAeYi+oE8$eeYAiF1JG zAdVaP8g%I(sFsOI-ykOT7SDFPB`6lTP9H@bD0O&otWdwEILNd8#p&PonRk=D zIO@3ALY!HO)ay1zSkY9DOLKA5KkzFI^%aV!+8Hmx##Av%O*9y47RaS)8Tn6)7Ek}` z$|%1GN6NBxJ=oFz7zal^dW#wXyhbJgKM?}TeU09Wy%h-cqiPWlbvqy<;pZl^4Q9~32a^bjHp0bft z;pnus{lEo|y~SG%?=Gs!9x+f%j$N&d$aYXcAQ!ffA}u!c5pGvkGK&1=NI?YNSL9!k zKT5c_+QO`wLWn>v?31PGM~bT3-mr-Cr#Vs(f%hZ%y#|lxQNHCwVv)K^g(Iw8l?O&~LUCJ7s{-&fjR5(B)1reBilVl97#-g0PMaE(A%Qx!(A}TuDb89|jr?EoI zz8<)<=|#P3pU?cS46W5gW@SY5YQiK^5TRCT`cO7Mu-cq^vW7$oA_6{7G{(F=rU#$5G~_Jz_r~}N zHD#?SepagvQhR^>SI&j|(@Nx<{!1&KSLOu$HtBygaF=-?uhRw2Uj5c|KGrB{Hbugq-+Y*drJu0+2_YhGx6 zezj2bXiQFamR;VxFumsbDKmI%ZWE)mW8+_XJI)P#ZBsq61^?ubP6hoH#2-~E7#mZ= zf6W1+DbsC{{$@_Mvck&YhCN4LP8>JVeW+gevd%%2y}qTycusctw9cK<>scdBp1Qi# z`+xUGsc~=2jRA4S=AI1jtEtK`;wnx z6!-IxeRgTBPixg#{lM68{3o)7Z*`Vlw{CFnf^`)ch*0Oeyzf`D&gTZ&nuSdzjt`Es zI=XD+Cg!}YvK;lWo;8CSt@d9#XXTGw_MvyD{hD*!n^sNlxq5+kf66K2uk1lY;0~tu zj~t`$-S&qx06J`X&VTRf`!l=6}JOZ*Z>{ffp) zv*zUARWeim!ngkBNIrLd)>!?Af(ZO#B`ar-rR48ZOjtQaaHenuaUI)i+4EGA-gSDL z-wM`IPB=W(aD`H~o@hV0Z;P9`zFG}s?IHr_iS$HQ5ANQ=S9-5g#|lRm$Bl9ovn!mk z*2&Iw{U!DgM-)fIW^13kjhFE#Ebk7fr;HUMR2j#9lod6GuQ07#rq<16?J8^BQ5VH| zqI@!2@>A~U!zN{>P!PzawrYEjkML>O-SnARQ=)|hWuR>GTbe-?^2~llSf}a=g3c0+ z&XR*x3-Q~KybW7_;4arvb)SYUB~lPU`-611|2us~Wc$jy&&$;2zi%p$GL34u7fCOy zS=JByC$emB@|Owuv)G5ZH6)&DxCd2V=Sk_6W&X}}`Mwf$6a;eNi9w#^AALlQf`!dz z4z(@Be|n4KrjAwWk5{~JzXhziQ!9yW$3D^8)#!A!|GT3SYE=?LrnTamw+2|NU89@+ z*LhVkbPDTNe1T@!lT^g8Yc)la!7kjTnV+@V|MOpnK-uK6<#w2tew&YUMZ2Q=puS_> zZq`cqw^bfzyyV)pv#5SeZRHfjvBL9_zKT9q5ZlU6=1H4sDgC(KES?>x_3T$34s0RS zB^#AZZ0Piyw>VZ;$zqO~%hgtehvcE0{) ziwJC?&9;B$-@I#aC-Jy=T_qbk=2=JCR(x%g?D?RqK@k_c-TofNz{hK~JWrOgF^zi} zd9+V<-!2PT742#Hbd_I&+h+I8mB%_R5D|+haFuwpRK%G$9U_S!pA$v@_PSP4ffPhw3+Xk(43q`p9~n`yteEh!mN7c&H070$EMH=IW1-Ky zwEE-EFqBO%af@5Yoad5_(Dnrt1ahHldTH`+Vf|K%>pn7rMvQ z6t;b6CBtK~&G&YLrWZZ`03Ie&3T&o(czjZWT zFS4?7>G%4`v^~;v@^8!I(jtskeR3E(ig~idox2$4e%OqmQ+lyu4#SN)Cl2WSN>(OB ziVNk~dXmSg1;Gbrj4;NoZ)Q(!6v)_o@hkQ9hf%piRA|{x#no9 zfi;rNS>Bu@*XZKW#)9z4B3Wq}kt zIn{IbZd#~p`1T=Nxbr2)|HT%btkn9~><#^EBaM|`zDOA|@EBWP?IK4CBJd`nx_#CA z$>7T8v;qY#@)+k<#%30!J&OE;AsTN~E6;X!`C0B|Ntb>otwMx)Cbnr9CSyjIXT!d{ z;YdLQ%BI)8HzBfVoA369#j+Fxa;axx$rrt3eS1A)>ZfNMDTq)tfCB^iNvk?VxdUT( z@in0a`2^^B=8aX>E3RX*K>7}nI~LT2$gP)%9=;NJyHG?Q7tTLLPDb~WqYK!K?q27W z9fi9HTJSrnfdy)?z(KgfZD%|j`N=}kRw%?f3#5P|EMbWz8lvTmu@_HS-$ z6$EnOI;PCSH>0I}UJI76W}|{YF7?Jq+B!^H71I_*E>aN4h2K>49(8xH+^&x`#i}73 zM-(*+JiBN|{S__iQ>?Jl*hB?^TsYDc$vSg@r0+Er(D$hF1&MbQw$QSR4v;@*USLnJ znjF9AkPGi!vZ}58O}cs3;oYtlS2O^;+ff^!v&13N9P`mv3@hVpV*C)+X`nCRUzJwK zazM6Z(ievtq-)uRTWgALqcS z=A@DSREu{#!wNU64xIb-zp0J|mHJ5Z9`)g+QF2TTu^}MNwCrQne_2)=j5xzcG_n-+ z%}RR~T}K@GV?0Oc*s7DcD*b9z&z{riHYgcVkXiW|PG)ayA_BRrmj+9=_4;G86~6qA zwK!QvB(5*Yu~pa-b*z4tb~T?isxIhEF_D4@9Ch;S=VgqdUbRGtBU4SRS3_g;t0mT$ zSr)bbkG#JtBLxvSh7>J(sRuKL`w2F3nu!Rt7BcpH z4xQ55hXx3WH{du^ID_}{wbvR@Rjc{mlW5N8P1wk`Ot*_A^O=d`gX{4a%BH-7MQ55PTh$Ww8}BuwAOgpY>L@0R zGutOu6NkdS8`yI^uW%HsNTkAi<>lJq<;aH&_aGwhpQr-ymEQc&27giJx(g?YX6-f0 zVvAnasy}s&b`y>Lk#@0aM>7*wBCbAK?Z5sheqI`#C3kO!u<22Cgv-tt>n!;X1raBA zeEju$`LbhZ?XIusVPwSA6=gj9f3?PHmDO(CAGmKQ7wfRbJa6l2qRsct=9(jp%tDN5 zFw(I4@_*=$`RcILXBxkFs+~bK!@B-qgsrMAx@`91NI`^UKeo`;Skkw1?lR`U=XFIJ zGK}K*;J6XzFNB38Ywf}y9+6N>O!x4z{^LIs^p3}WqUf5XmslnL+9LGsaE@bw2>d6y zIa9W??w&QokH`cQ+m54v<7QdU8}PH6s)-|0JDAwR_x2!W)!LdnK{IefXa)zBG^5W2 z2-bcpYqk8uuYN3l_cU$IiNVae2M4&g8u(8X72kX~AAYmCs6C~SA_Ea9&u07aWfIT7 zqK0_i=d0HI;-9}{ zrag>0NQfKmzJhW($wEba_=y5lSkI6S#)DJ7tWv0*ot+nG?6}R?`=6DWYwqU8VZSg7 z@xG=A524CE3nI8v@v5wOdCl;CIZ@$4G+7PuXd?C{RjRDKhHv~9$X59lG)|75#$J#1 zW|@AzMvVpY8U7Rb@9x&bvE6y3Ydb?h?6~jElEO8mMf3W}Z~S`m zN^HRROM2a92iW<4DzT(@PDZ_RTiN)_cGmLl3!Ud$Mg8bLyMZWJx3Z~ME+y_SDbH?h zJdif&%V~z=rjC{0->pPY&tArRkAmXJxO$A@yRw= zD1U;{Vr&_K|Ah#YO=IQEMHQA_@4)wpiVVk>UhHMdRa*P|=M{OR)1)>Q-M%ekg^HFE zUH4aI6+c&CS5F*a`Jb0%pQpXnPIf!Tu(kB^bJ8wu|Ln?o9Q0OXAOhuC-nex{j~2P8 zcDRosV?s|awlgh|rEET~$fJx|8MVcMGJgDhMim7yIZrvZ^n5J)CS>#ME$GkqTU^Qp$V7T(t)jr~$CMdT$-~7Q-*&m2T4|B?A`Cy1(k2f>QZ@|%0 z4t>hLx9`9@g*Igk*>YMXX)USBaqms+LP^2o_r1DM^XV!B_{IZF!GaQQ*yd zmKdPMG+>+${u5R0X*W>B7FcPf{s>ZhYkw=&pMCmM*OxYI$IxSwYDhP3FLL(GB|G=< z;OM!Gp2S}(1hLf>%Nyw<8c{!vd4`HD^_`fj%SXPUSUWa5Yl~LUZ4(RK{F}9-7@xQE zzg9`+rrtt}KBo_F_CP`4T6&q-nXUTN_+a}v*6Cx63KLX+&^R6Yk|PBXxC zp0Mfu*Ix<(xx9DPXL}MbhFx^ zREmiUW9=fA=yj$}V94e3sy$0zbWJZ-GJz1gjzx;ECs&#QR}(l&M>Mw9W~;con{d3J zY1+M-bDUco1r<^FV^5*CK572ld$!VZYzdynltXCfZ=&jzuKdj!cO}vSca$1$kg%q% z2&9O{&7tK4QV@ZAo~jT1)5P+zZz%%$7M51L3{nt*>y0ds{(VG;cI!swIJgeX!pEaGOAdm~k&C(gdL~Q3IljS|e zaSm{#)fs#o)>crqLi0`jmkI*8Q2Vg_0D=V7FfmJ1GdOB5*b%+)dTnqFz(IiS-*ww|% zzru=l{{Ith^Th#daq%*GT#H!cv?I^6ivvW$@d{?enC;4HM+DvyKU z%8i3JGVV>wz8fm?R=mny7%wI#&Gx=zZ!y6;lZ}~jnn#wyNMY&9`1MLoQXz2$(uVlz2RaUFespAdm}3fwE@D z4--CRRxr063pr8{fm)Q!=JYB??0FxrFWDcd#9(188OA}=Tk6_T;)2Ik-JU&8K_D0Q ziM&N>jS@qsa31`)V=tja)9LOkuF-*|smK_D0Ek7PX$j}nnl4VZuJ zL&~m21g;*6d`XKEG40Nk74S++7rrd%38bRIR1_uy+eXACCove2iz6LyWQY ze%HR9FK(1;8ex2z?L_;dkd{k2H|!*nwudpKAR_HbF5`~laKowfDzYtIueaG8F~~=D z^4rf5fm|Q+=QSv<#V8bJy$Lt-U12)huP*C{?Bhs5g!7v0#`qOOjL^DP)wd@zPMSWA z`%CNlAjkC+dea)?jdo+cYk_O->Tesx8N-_V)DTT)V#qa<NJFV*f%ac3hp^f9i4IkAI%-f0W&j55wo`A)4Od%MV+)=th|x{M(gqVcA- zGHkdDYkzG1FkaF65P>n{v=U3@6jpU3sxfP#w>okmn(RJXZt{;qYs$!|2MPkY&~u$U z0bMThYyPcem3r;Wl;i(s%L~OBGd_iD$c1Q|?c9e1?q8s>4EgcUe0Oe@<`J1-c&7B$ zFj@i8^p-k%3*Wb~lU(cFK|vrF%BEa;yW4S>$X+sQTabzWi}G-0=^pI7fi3u_552m# zGWTU_c3OeP`)v^##sa8_PA9VSz*?>3r$_fqq#y!ilTQ8ou6_8;Hk4QGks<>lI1p{K zIV|pKoPFC@o}yZf$b~J;KGa!1k#Cw+tB%&yx6Cf)%FkgkD!8?Ydl2JsR77Gx5!3rs zko;(SXd(p>D4VS3BiEV%4Z6szz?LSSSBOB_6h-&QG#^i`Cnx2;Zz30>G5&|%CaV50 zog*7a^5{@x;MuMsjuhW*KK?k6`Y}m4cTtAgD$ngT&A8fe@@NAehNl{G;fT;{M&9#= zRfCYC?-c}c#d_9E^LdtJeDrxw^U>|HW}LN;m8)mZU`Rm(&Zf=QtJ8SxnAce8yzNf~ zfn0b#TAl-&+2fD#l=o~pLkc2rg_5uH`O!S7*eKcN+Cb$@L@wMbj=W@OZAUUYU- zQRR!f(V(mk@BMrbOCI+@KU%IT|ImLt!?#-nk2gT=5&s(*98 z5U-e!%qF$lZBKdNz?T(W&t`^{)n2xA;B&{VBNh&pN8}Gemqea-_}c{O|vw zj348c)hoKU2ygbU#p~`S<7uOnRDEcO7~3|R{>iB@-@hZ7g-olWmoMYM+YDaER76(k z)<)ckjZ{M+S|9}xDBJp)sAL9q-N=)|2a0WCs$N^mBJcFIiVT!ZH56{mG{?dwK&qLZRWa+t<>I55Q0>P5|0k<*ubWIiF`vigYoNp%460t(STOJ& z3tF+9`5tpKS{8TY8S`e*=st_iDO2Yy<@b*^7f3;b<8}ul?ASAQJLgJ5L~kr5Po+%d z@t-vXQFXkx@$HE-_dPX%VRQslgYqmP_hh!_T{brqt#?#5!sANu*;!Ex5tZJ%8n3q( z<2M5)l8i5TO2~|*f0O-6UF{pcR5q&Jsm33D3}yIFgS>y}fJkS*Io{zCU#OY--Is&O3-@ z&sqq|7Gf`Y-H+Gxp23v2ZN(R-^_D68*u0;7z@7R6x%~5=)>^jl<3DpvV)#}_Uo7j7 z^XmoY@$gPrl{9d0S3Kya&QqR1}qq~3MUcXfn_+N;|7iD_KS(!^%mMFVd zJtY$xA~0u_Re8}xy!u^dCA+p4o-PGg;=M{d?#4(Z+Z&?EPJOzt*yHw%B|8Nv2+U@s z$~YIkUiY4`lso7VqUe=XqR^YQzqQ_iseA8GV}vDxlqb2j7NWaDkVj27BwXWd(P z^DarV7@~*F>!bG!sm0HhnMx~hPL~TtsanZgtJ+&21re%@%minXd{V{mIn5OWa-lDl zl?O7&%9zbN933fA16Szxdw6rJ)*!YJWmA>o1e=`pbuqU&()$|R2DmD5OfDy>3_J z@Sn)9@BH5sliHB)nb1R#f&Z(vs?g>y=Fq?;{MhWaqIdVV`j6LndCm*7m9thoMdLr- zF~gqz&POK-10#V*s+v1y46ELAQ#>eDVui2|sD&Mdw zRJlJ8v90HJ-F5tDR&mN2l5wj2D)ZW_b-civa0P)}c>9p{nzIna;>7d6b~Y9`K6tj{ zy<)SCGJl%iCr{yN^V=y1>hP_qqL5jyQ z`z=V}5nBf-2;@@l+ES+?*z<$SIr;G__c`hesNs;E`Z?p~ilw~g!a<5AgZfTP!=>80 z%kDhO&5A^_HHqXMMz7>&LIwz=AcCrpYwpi&{GO3Yh`h;bx&NOtx!2%63Ie(Ara#gi zy)Vw6U$D-rPm2v+KVc51I1qspL^yA}r9D5Nj~8iWwW`gvyyBYcWZraWGx7JiJnU|< zy!^=0X$*Bk%nwMp4Sy69g$j@3ky(KPDTu(#h@=7Z-NoG+t>zSEBd{g!pB~p9SN?}> zxxbpJt@3z#hf_5V-u*^rffPhwYbna~+$+9m{W4zuQLxevL|_ZaGEuaTxnjyh{-w)c zWwqlP!!y{*S<_di+l7B<5~tiBEe|`{M{lgeKOdQ`+&+|RBmNJwL;N6~t7oLZGXvMI zdM1XZj5d2d=*3IqjaJS?M5wK@>hLZ|bmE1lj#2JG3?BnO__vhDN^-&PWg*%OO>H~9l>%d^1 z{&JAAqY#08BE95XJDzqshBCwsQ4q+bo(yvI8*1Blo?;GHP6kBaHv_$rd2D4v5<|J? z^ij&`g9uz>6g{9P>z1zAsrE<(fn4edm*Vn_`|LT*Y=grT{R*`(bp}Pv3*6;6dmvA?e56jLI=87Iu zd4U39%05Q~?qISy@A=AaU5wyMZgx=CE}nL{Zz#U@hoeZZJ%ZOIO$I55P|w6GON)q^ zcRJEuZ>%7Y3r}$C+n}=e_G&us)UAd<|0MkGM{fx7P8gL(#>NM;#oyZrjMYxq;be5^ zH(lGf_6Fmci*YIVk#<{LrJdn(WvLZkB9mJ?aw4_7j|xgMu3Y;4ZBNY!Mn;Z`Bx6SvPtml> zT)x>}SFy0*_~5uvp6xsvE+iaD4mJ)GmtMVJ~8z>0$phGn2 zJ~5>Q)dpac6F{JE9U^>U3b5g0{IyDBtU2F)z*D@4PCO{`HWEld-$DE*@*}IBU!15g z!ywCnKrTdA-RsQGr|mfSYJw%>O^ByxGwqp?#2W~tpid(Hlg+ksxvS{lqnSQ?S_l#C z#@1D+ub(V`jv)g7iC)}id5Q0=hw12CPeGucC88-3sbfCjyls=2(m{w`{ax6o4^q## zpn9>QY|1rB`D%-Nn@*AUwGrMH^@Aqk?pxzXo|1+e8iPCTj^jV_c_SWe*$Hb zHR_m$s8c-M%-^Ak(keutJi4Q%dx|Ct{xKuM-4z+=y@6tNg>4g@j9)=JLQCe+7YD=rv6z_4h*JJZ~xM&2v#aYY?Hn-Q_NmTTECO z{3}-xQV@Z!fMmb2?=q`ijFN9ZC?@ zl-v^dPtt9l4JjpF59L%R6kW0-i@}zGm znN|9YIsLcN0yCQ+*Wwa+jKu-(^v{E>oHbiLa!G4#9Vt~-AO#U9&wA}EEgSYZWS-?! zMe5evhE;dY@5^x|TMNpjI-{#|$=lhUne9i_R1nC8vTe4iS8~f``SzJ>?s6pq4a&RG zEw}OKnkjmEb}PTnxlJC@@9139iVi~x=B&YNH1twEFSjh}m0;%Y+)N-BqU$_xHj1|@ zrl0?CiDX1QDkXP4X=L8MDFjk5s}BB?l}j%-`i zl93eZAp=UiHeNk#AdrIjeNZ0h)bl*0tX|AGHt;ubJuHtgy6#K+u7%f>JVl76FP6D^ zrJvs}BduIp1%X^Bn^wuE((=PxdKDScNMM#E)Rt8Z*&bb59%y`rC7Zt~8JZBSB7T<1 zD_PaTd}fX|3Ie%m<#sj}5A$aI3tRKiyhbT2yB}G+8VICdR5WIXvf26%%_j?O?!rr? zw-8eo7BE~Y_G57$jw|`7@SiBtZMui7wRtS}X{d=uX@!j&WqxOwHTE;iy@K+{-rljG z?BFtvr>||SAdm}X+iZD$=8+!7mT>oZjg>bql!sPTdf`1(iCufXguPnTU!d&`Uli51 zyGGY-!eioc%AwdwpbcqrnYUVg&s6r~t;z6})T+~P(>xKqntz+nS)jcYTN0D&py=l_%l~XkyHsZ*^IP*L z$ynJS$*AJKhtFI*NI@W%I=Urd{mcPDyZC{d{RK+LRw0^f;Xg~t9dZUwovkTzj_V5N zpW-@V7us{kTN_j5PceZHHdcU|qi0I5l=CY%q{6+TR3Ie(Ae(tJ|iz>*pTMr4b zqUb7fPtUpJH_=z%|6C!2W!~-7d=MgC`E6Dc9z!Pv-r<6M3a$?G*%a z;rvrnO7LSd^zj^CqJ3xO^g#sniN5Gh-JzLZHRtL)+te-8_9XmT~{TtRIbR zf0_|RcC)-r{RE!Qh){bze&0RQs`C?3te1j7E*u4l%_wrkeAulKcev9_IolC|eWDoN zA=AvKeHmZ;Gg{zkz}ZAJRTJzTXU=u~%8Gi8P!P!Vcyu>iU$|B~qCcS-thsE7nWNwW zR$%;4ffPjGC|EXt@#c%XJT3l@kqQF2&Xnt~@2fo3zQNs+G5yk=wB{X`@S`(^iTCw- z*&AkG#!Bet8SbtedP{rZGZgFfyS1*)Z;dx;sjCE>Czt2V&T_=Yotn7uqV#lsbrZ^K(E2;@@Nl_g_B zD;F6&yuCmQBIZc{w9}D~^g{bHNCsuzGt&0IGDEz2DhTAlePgqY$hOpo_;8ip(EBK> z9TD4^Uz*>sWqSEPtrISx=2xSzSZ6-HI!Hkv7w$)!?Q7~nBkBAc^JLp$0x5`C)+Q;S z-w$`)ZNp=d@oB_Lvs|S?RBtD6+1pqWyAxO}swvw}b_+&AP|bH~$UBm2v0H}@*59l3DjQ{C_y_03bU-DSg) zFZi23cIj8DwlVH>NnyBGaOG3XPhEdA;B!0q;z1692;{#0cxtxog)F=CvF|s1})4E#wAj%AB5kUE)%L}9+0#6LGCx*;12UMb%(eX7D1akS* zKduien47Xn9w8Z>UJf>oY%VLaKd&c{f(Se@=$o_IeAB0N0hv<$HwA%Qmu4K(;|AQ* zbN8{%lD6}Q(dg!unQvPPq#y!M46@LVO*E&L{76}WIw%O_!W+)=1e{_{J`!V6_B}Da zsnlCO*pjv<{f=_K;%=szNaIJDIl5OiUyK~4AdpMF&riQdG3UE=G)_hj6-Ysi>};n~ z`k@~K?8%evQO_L~6a;diJj%8(c#V1S zRxg=0f3;#4RaQRSb`*D)_jhxL>`pm&k0}UT;kb^is)!rS8|RwHSM76%T=PEZ`xg5f z#}BPlRy*zjvOxaWVEPxhYWAMkNgPkSp`Qq!qMx0c!EpZ78GP1anc3ke*#W%66a;di z9z?s=ccWQ#+iX)FjZhHCg=>Lg;!>8HH@18=UcHDGI8(@lGfPjbdrz6m^7Z|dp8@Ua zc$TP^ZPG){Jmn%~U5f5U3L28)a2d5Xhz4cQZpxv&4~N^0MxySe+4p=NNf3hF>-*%fBp{pDPID zLhCST$h*?53VgCl@kWZ(84bPran z&WON$L+?>#?wV1~$!6H^ofQOfp>>$vah~2WbGb)T^m2$|bw-40tqpE@+MJ#hVaA8` zQf$bGz`a7=>MKu}r9ujt>4hT|1ajd{qt`zDgXx&3vkYI=(ZDw-e9gk0X0t_<%rxs4 z=_&IjJ1Oy;$c6icD*bhRWDfKXlq}_=^2UO1H|lCXTjb%d2+-YQ^9y`eK`va=mNn|0 zNgh0gQ^DSfEgVNw?fIl?XUr96D;onA_frtarJn6SzZWnIiyUT`kFm;)gLf2ui_%^D zeTmUjGIQ<7Smi4f5vulj{d6<#Q7lFlZJM9wFXO9C>6mEbt^H9$KM>XTqwefd-1BRU z49fIW5XgmJlQbV81$m1nBV|*)HAe~}9G!D(=B+WtxPQXw=6sdA4bPi4RBkR7#gT%D z4qtxPCYi&H7Z1Y-vFxZPKRI%cB-^EeK(0aGowbA2`Wp4atnb0#ilKaZzkYK2{f!(c zh#*e_?bWhAMojnwLL@s40A$>=Yjpy#YI61v+0cCU%fip|_ zMK7IYMVrns-7XImxEhw-%C2RfnXG^Gy~Erdx6@K*e@QEN*s_b-=bdIwCmH3si%}5B zmDT!({dLGBd$)#`y~N55AGJI}zF6YPtF*kUJvD|H4<2zP<_llO>5FBs z;7CD)>H(3obr+|KY_h|scM1Zz61+}oEx+20zbbE_vAUjmfm6A7SuAIEffPijei?CR zkMSc@YsvbdZVCdqvI@S{qF)v>{$8|~WKfO?-gI$c+4;|!qUF(BT2|r*eeJd547pT~ z6sm#E9fNJMN+4Gd$fbJLoP2PR@1J(vyxTfRK_J(J`LDEsesOvS-z(Ir+s!WWN>l;t zh!!ToM<3Seh8<4(UhED-F4YU^RqRFnW_=FQ#QP`+EH9hcxeUT^PGa)wIh#*E(-0!*Y6GXXueecP;JjT9XoZ)zV=K0=fKq>)MT+ z$?Rp6WnppNd7T%%F^jMKqnkhqBJjnGtOiw{^UHTa<&k$^l|6wTBDjtzgIT%zobqML zPa`}9&Kk}+&JBG{RD8~@tV33vXB<(S57qyw=aQG)DK6F=R;G)BKrS3<>uviLpIR)@ z$fyw}aNLm#{nkiZilJlRh_9Ap@2wz^>uuUItwP7+TEa`qE*e+YSu|QOlI7XoULXY# z=zm8s?vowF^~?`!MOY^Vfm}HM^zsvyQ=Cfi=HB(%38WwbXOpahJ+q03w@G|UpEd&L z7P-)Gk#6T^%k?dv{@~TKMJv&n_%eo;dx}wgmPen9RH6s&Rd1_hep}4^)6Owm zZxzZ|ZiTYj}Hl~D_^L!TnxR@!voQP2UEU7Z7nS5^*KQ(fY@=Av9 z2G}RE!>x*AsXw;zv^|5Bo?~zEJ(}*puMXUG)CT^rz+mO28WA`OWD9T5l$SWNk#~7F zKtUiEMqpT8VW|{fvW^!D3s*)LM-*cy$R?9=l-vJW#RJ!e2&5na*MgO0^8sJ(x0+|< z>8K!(3*Xi0Rp!%t-g(19?manDIZLn~c#cs;g#EF6;m#R6#&4i(#aiPYMcC^XmM!DVI9lmRKBoJ=Ar-eWY{;xXct-n;}`CT$7<6^jiKrYlvDJ$2ZhJ0AVb(A4?fItc& zaE;Lm*3$YsU$T>V;QJ_n6kNNi_BwuGWlmXW49aFDkb;PjS=qD#k5+0m7Fqgkdbdzc z@iN+(aWMiZi0FD?v9@8*A6mMz^=_~)u`-|8<~R#-AFUve3)eK|{`Bg>Q(T;R@DO#i zBSPJ^e$^Y%w^~zPK6r$(KadMoKIPd??QSF-Uq`x0wDO9K=Q*D9)=R@mx&x!-_0&uy zYXoL@!0$H8XL}0|qFRdU9vA0GK?Hs?kWJrlJ|A&=kW6jSPC+0Sez)0dTc)S*fzSKN zh)teE;B~ zRg=wJ|MXH2$c5Uum7ifN-`3>55t?(5z!i>Ms14GWm**;8tko8M?#Uqv0=aM<(+h9A zG(KbtMGf4G5=cP=YJ;SU`mW*RlE?OB4ptDzg)85xUT5&RUGnoTANvWUAOf{PvgzO7 z&KF*3#;@e)uON_1y`7r|wPGi8#!IXE0!Hm%Y>xUxAO1EMySz9?2JfdjZtxb5Txb=c zue+9+^%f+KkhiuaDG21kmvPE2HZp-7n>U#9$!z9GK?GVw$iJl42D?YX0NEn$h=M>a z^+j=5%gi)=c(@E=k2z8hfp3NM(lBWn3k>Kkt7LxTNI`^p*IvA}Q;WacR%&-$1tO3O z-_j{o=It_eWkd_%NzqN3Tie=g-M@(fip0OV3NB&k%iNGU}KSt84Q&5Y7QsYqH0Arzq~QXxcX-#6|1zL(tBOqJ4oA%{9mv^6jXI}sP{B=K^^PDqt=FEELoGY-8UyJCd5m6(Zr34XM}hCvEMbgVv7UjBS-C0ddW z4GP0gCx1uLohlJBFRMr`3!)$F*dzCu?)w+W$fY2JqMa*KIQw0{x*&`0YQ z$-VTPEB`M^k2mPE3voMfzk0SptvHvKb5)iL+b2n_W<8`c3TqO(%WZ^~LxgYr9Bp;q z<$r6%TaI|k>ED+Bs|lRtkUsW)toiz9#qTqnk=4y0rIVk&eB^dpWI3k4@>%bcVAGNm z^t>L4GU?66oz2xk1hjn7+Oy{Ako5M0m`&C}8B*Z*c)v^s^&FR?q$RKB)_(e>0g3Gv z#1iW3AV`4-SVKt)3os^14S%*GQWrrAM8MH3N&6a`kgxhZ*qjDeH4p*0V4HZ$m%qec zMh;=a%M1>}THQK&M?O0vLs@mPhR{Aq$~pR#u4ocUetDfK{(~QCPpq7P`V`a<#`)or znu@Vk5__SYBCl2qeD9yQoIn%D%-5GYVy$I*ke-9q!xxYvug zb_ac3PfzzrB0;`|928SpWA-$;c;O`Ew!XgnXZKLqqIEucw4xesdE$l9_+xA;!OL_6E{L`} zuv`xE%S9(gV~+Uxv=@H-A(Wgrn2H~|C(3az^U&`PCuNLR$_t%xD|-#1C8=|_FnsIV zU~;X_~>&uA|sZVUn$hWa-qB-S=;5EjyY)eD^*tqVv2FK)Zr}goi3X6bgjJfR*s_f zV3qO(@|r)nito*7GI6~l|LmQiEPkOPR_}4c$uq~YYEP%iXM@A!yTkL9s>O@t?Yr8` ztCJ@y(&GdHElDk!C*u}PN3#LvrwbH_fb*jy`Ba~T53e1~B8(;-zn58`|BZ%)#@qAkgqj_8cLGQI!o+0-;XV{dVyhC0d$4@=Si-jj^MV(4{18? zn4&nC=pjiOAU{B7KSi;${xKMq3(+FtVLb=B^m#h_^?JDHvGc>UqwnV_5s|*~-NqBO zE>U@kenUNZugm`8W?QEybN={p?b=_fL8I_^_HI+M22vm*eC@>Itd~=iTYkD6@h2vV zCIqLk^PR41pp3Z{OSIZ~xysjR4uU+szao+Jd3+knb=@E!u76sg-PtZz+4R1*4AGL5 zdE1um|D4XMIXyi1qE(`H)4M!HwYX1iE45v`aw~sB*^*Rijtw2xXdGV$3)~?EBA`4; zdR-f9Yn5lP6u-pcFgd&U_^l~QQGBSJcWBnZE>;D~eFGzTYyM(S<5mSq&rXE59M$Zn zbc)SjTRP+xLoSGhI+UdI1(`~uCWCFgQ+yC2AeX4!>-8_v3zo60Ls(Stgc;wp(@&== zTYl%u&F1dV+Uw>hD}I&Af#+XqhZLtP&X14sS~a{{m#x0hn;9k#ES|Q%fns%Im|_s3 zFYh|oKyl9*rlf64klTA&DJ>@tuKd3wP1tG71`&TYXzJX9kOC1_6_(1l%b`lSm1>C* zFKe-*lY>~=SW9_dWCNw!l3~hCdAba_AX<_d{5VakrN=VcA;aY*r)w*-cO)o9`3Z7C z+*2*G8m}Zo>C5v&c4({g$Wg{!)aUJxm5bEtWi&%aw;hBC$OSbbNm+Nl(T^QMS)6{F z1|lFAtgR&7f3C}SG6UJuW>!M2AeY#VbmKR)S;!FflaDCK1!ai+QQz2*T&cAWC!Y3X ztnipz;iJP_CrNM@{`yn4yd-FO<^Lt=UD$8zdiDp-Npoh90ugXOukMz{;$K^ulU`Fi z)HBY%(^ghmsixfOL}j_KBuVPGc0JBn){NYW5@o=0VM&tIZuunisjDsdIYg9Ec6~wd zzl8>FqelKSRxnQ~CIqKEpHFUpeBa$89!QgqR+xsM~>8G`oGGIx3 zU&8WeY&T1y>Iza|xv(TjN-}*-`wgl>^47ZvGP1lkXeUk^UMU00<8w*5AxlZRg)=%k zF~|kWg(p4U@^xnH*^Q}q?Pw1H0l7i~PH9JPSf^2KL6UCdIk1XuCivGBX9g({A)eI| zPPbu)>YdUajr0@{kc-=!mfM^5e=?dG*)iKK9cWq|XVnt_Q6K`I+a!tGF5|XK|Jv?9 z1mxm&rJWeK{I3jdyOi55{cF4bC=el@Yr~d|rQCMeU)%k6KIgVn%x$-_Tu}zMUCM2j z{k7eHGGMvz#41T!cT7^a?XthN`%eb97!9}GN*PdIrR^eayX>#+{^Nq>iljzE_}kb*;#+&#vtF zx_R0|sgo+X;7nBCxvnyzVM68qCFyy*4NIw?UHovZMi_&zCa{L;yxRqv9L%Y^!}q?Ge~%|k#R0y}*x52q2CV@iU`djsZ)!%i-2evl<_B z@V$qXy3+pN91d*^t`d@DwZeo2S{=gPSDb~_03vF~1t}w9UH@8%iOotH@TVbDtpv_X zupO{{{9g3KSQK&GiCG4URst;}20tyXb8X7smfO5DCAYS3z{@{WYWLrWf_?C5QaVbn zcwaegBZJeL6S&$_S=h-yT|u-Y9oyNK+&K3I+2*xphXeBw+aFt5*8H>rG$6N! zyV}d*I8S|IO|0AAl$VSVWk3Y9F-a<1>qPD*A5fMocNJ_GB1B8H2{u%!+;=4U-fj$@ z&*7-e-P5Jm#G~MEfB5KpRc53*kd*oD8Kgi29RHH^=J-5%%d80*5UEke;J@7qoDCpa zk}O#b7Chqt{n0?QU1+Z%?Z+zBo_+Z{q83&)WMQMX(+jg?!P+4gT<0a}_qSHc{=7CU z&`%@GCD1aUy-CuX2A^^2m@hQ*x4STxz!gU+?S$+)b*-F!_^CD|W0)-L;b7m0W3cO;TG-XYfkY2&ua1v@dt8WczcEQJx61oFm-Oi! zjeAY8AvWt=1q9@R<6n{-b$`?Nz_-}wl)Er$;Yfu&%U7JI_vop#TBOmQc0!*+1nhsl z3twf!3Z_TWL+!;G4)!3N?IdaNJTt2K-IkxcD%SNIyWzYKTXXT-h+R<`5c?gjQHTub;Jz-4RR7en!5xxFwm!1)7?e@W7* zuElqgJlUg0FY%Q!Q{?r1s8YvH55e0Hcz?|;@!VM)(yAA0tv>@p3PgxEMaJ9o2tI1Y ztPNk{PR4;q9`2^}aMD9i9=uhTq_giEk==z3?A7Q90Rg$7KY{o8i#nv=DibD|e;0fc zP*+g4BxQ8IfR{Y%#TxgFqwv-VY7}}P_k|28+JR;3jS~6;Y8q;R&v12Xu?EdNNUW5A;hjG9_fl%?@Ih5=_0Y

CH^85D4TQonS2MMhfhGBi--8=L;NK(n3pR{n5H*s1t zOh7;`Q3gNT(_>c$kSmKP;VQx#s;k*R>Dk5Tm?|N#fPspCtFDazJwGWoW z@4|g+u&uFXWKmZ`feba`<*}hq2t0kl6yh1LOUP= zwn>s&wrokS6h@LOed8#sJM?BiF9-K#B;Qm@NB1OGp1u$ekPGe%BF? zq+-Ygy(A*y{PYnN9SS3Vy2Mae6Iesh^P{P@gc>&)M7+1gQb>Ua*iVwQ`TZ^$7nner zh0NAK3bYc@^V8r*0j;=`LK@9(E!ZoxW9UQTz6t9HdYOe2-&zwfq(B7Jg1Qb4KyO3* z$t9n{gPt#*X{u*Vshl(5dMA=h3k)Ic8;^!ABit3jEsHhHT#S0z(Q!%=b1x zYuYFMMI4Cvffts0ljga@F{D6*SSv%vOx)w+VDjuotk81UT4+6zbhTs}&UxldBF4QG z5ReOML6Rmn-HRiP`jUhReJP|s1oW};UEjp3xTIB2a{qadfPh?LJ5G;VjQczpMSQBa zJ_xM=S_zaVN#V~ZZn`p#Yj=|tQXm3)NhK+J$zA;PYj=L9AB&+c6>3_n)$uxuB1Y-!n`OLjKdD zSr9+v!EzxQ)=-izNO$CjlNqe%g?d^@fe7fKlceEs9gBkw$1wM)2^3ObYhg)}G%kD> zTAvop((3f4kOK7vebAERwrwgd`O%3PSUjU}cMs1A5Y6v*{W{?6h2iY1rl-&!5FyIg zd-@noI}yvm9<)Tzw+#{EIZ9sm6kl60gjFf(had$a;5mWc+{LBh(otb-3=PHbd~Q=kPFJ@2s<+xSUisHxKk|nwxKWe_B)L>y3^#pcJ=)BP30Gw zpuVQ^gj~>;M8x`|g-XfJ2`tLwfd+CxOB4}DFWFK9Ge5R+=W_}z1NzV5$(!45$9QUC z8O9Dzil&eP5u!JIvq>B+Y#+vCy;uPOxkTT#{ms#Ib$lqRHAh51t_`ItwZ7eR|LV%i z-H(!IX>3t(Lk;AD{&NwrH>)R2JCVltj>Z#GAOiaCC28-*XnM3Fl}*mi*FXg161AIE ztuvJ@)0z5i2~r>edi(h~>Odc*+4>l!J0V)=4>*EFkNd0%Ka}R1hO(vYh6o7A1^Y&l zs-+iE^dO$y$m>-Mz0=S~5Bq3H1-R(3Il!m=P290ih;`*If5 zHw$LIM}`a54iQl6e5c=b4)tB!kqx@~LO?(+@y5&k=WgotCWt*W4xx|&5%8q~pQ$(B zq3WB|ALoJv1muFRFC?kc4n20XqCX=?w+XKk;QIm*(R|Zq+W257TYD%$c%1;bpgc($ zNFYy=Pz>A z)w%zm0JitzcQ~YP5$2w;P$lcY4xy@OemZu4<~6@PR0F-!T}szh$#t%o2NL`%|-b%AV}&JmoQHiSYh zh#rxjq*OTQqY18R%ST;yVa?B6!soj_5fG3|yvx|!5VNu?)k$IIPzvv?AQwbSlIgPF zc<$%w#Aw5C3U}equLAe;lC+GiNB6sx91s%QIu+s7+>DG3466Ua8L63)1NP!+DSQ4LitGbYC=^nJv?4cNPLG*!YnJ6OS z&R-dt#I_{DHJk2l97`bra)}<3&{5{3#g~KBHYWx{3Pgyv&h1tilfe1+X*I*46jI=g zFf2)u?ou;$!ln(AM-QWL&4B(WILGiCug(%H`C-9IYrYg_ABcc6ktAKRb!A^t>N5L3 z;S_Q~d2ct5RQgQU|GO_qujk0VKDtjG{hkO2$OXM8lGI!i#Ol4>&0i-Bp^yR*aJG}A z{CppF;PMFCD&dKMfLw5{l%($yYBK*AJGQmyKw2YtoxJ1pOw_!1IL?R}TKW6vyCgil z`KHR>$(?#){tDr1G^((+V=o_!#KEqaORP=`4-dx7@cgc!ctEo*>D6GjzTw2McotGlWmZW&6izuw79cyAY zgTh)t#HNqdl{NJD7|mr^m$u}uMeNu;dw=RQcTQzH>P;Jg?=LQ{{O!>u8i#EwsrZTzD-DfsZu1|+`>m_+hLZz`@%c`8fJ>pAdL1*Fz93A~uG!rvAHzkaowC1g}i!zGhn2 z3wh|pc^ibrnG~87!;tgH-?VzK8fck-GKDY1bfQ`f35$&S31X3UZ z-XQTecd>PddD&rP=hc?LwGSfTdd1(D#7M;T#z$=xowfv0AOfyk{N3xY`zXI`2d$m- z3PUb8u)JZGAU*m3_k8nC$?*`X6H%nY#C;3^?W8!{f^Z|Sv2gnJT& z<-%31OXpzJXt6CCF-4W3Tlx#9dwj$0%|-|a$W>rE1}%-#K{^Xm#L$cSB*5Y#{xM;g zfPh?LJ1id^#pYj{5L>e(Dy*qstrco3K)$!7Ou> z8@v%!#9HEsrZ#BV+x1AZt}WmD#9U7y%PVwf%KYOBL_jX{Dy>lB&Q)mA9}A9%YMMx< zOwXYk*Z)*3XIrDP?rYJ-J`NaiK{UUo9)ZcRsjUbL>ZHuQ(p<49LyhZuetR*V+O3U%fLu^Ee}9$Om2^)xB1O}xQ&=u+IYdj6o~J!2 zi1lFilHHY>L(gb)mZu_hj|=y3UAL4}{{Mgb-C`>TvgEKcbE(&!LJCB{-Jm3e>Y0(C z!|rUuxOoBsa;f`ZRrU~m_Te{09>!$OMrT$rw~RsxM2P#{lKn4m`Uwwazw4KPfLx>R zbg7haE@%{&asK)-oN}NYv;WqBK?+2`{WV{4?kD0`qua6I8`c5>a=~3cf8{-=F+TIg zgI&=V5s)k2@YTVYD^gLb?&_(CM>%QhWjZsvDJ~3BAOfDLB;W7-aWz&AAoLS#?)(lc00-pN#9rEC9bWJr+envMI5RmIn|9rV{Wh&Zf zlE`J$I`D}e*xrtHPuF3P0ukbA;@w08ChhZJL3Pejh=5$}rWRMqP|t>vv~*P~R=e1l zmD(((kOC3#^upbP!8UB>3U_8d%~?P|uBji+RLW3KFRDY)g=ua(F;hDS1yUdao(=hX z>cMT<>!WUL#pE3bA|ThU+?l@D zMgal2%tx=Ql<~ilu$j9a_e(gley`qQNP!4=Hsm|x8xLr4xjPFBs74?Ha_x*8S}CIk zzklGii&oHkOP$!WJ>~>bAOfDexs3Q;w4$2_dvw-9KtL|_{fuh6bz7)66M=2cX%~)g zX1BYvBai|S@LofboN8=AGYvi2{bOwe1mtSb`hKx0!}p6SqrufoynUZD3twhUAO#}e z9S1+L#BITKpLnn*+ZqT6$Tcr2zjF2o!@gX`(I%g8;GA~+eo2Qw3PixW0ZICFU7x7^ z@$$h{3=xp4IAUj|49(qMTt@RUbE4z#%+&ZINP!4=o516po35HeAxdBeZ2V#O1|KauJy`5XnZ7I%6!q8^Qq{(WgMRM zwl@kdPerMVgLykH^_Yn5rc`5x8+9Q$ky-MA;PEIbDG#qGs4myMnu^W_=i?e@j>;Q6 z(ooZVxg4SUq6smy|3JTJYmiCE9u-@rp|tH|amAGeX!@=RsP3ywT(qGf`m`YxwcnY^ z5d~dqk$X$u(*@TW5y%ym{7nw6k%j{2X8#9q@-ah&Z`aeP{0P?6N>?r}N<}7HtntJR z=?C81WTNp;t?#EsGm!H(Yc6BzK7=L9&2)ERD1(%>hbGGF_Gh3vliFZd5Z1ofCyMy z9-CooL;}p$(2Yip3`&PuxVk})YdjS#NOn=%(WMg^NM_PeG4E;J`A(?AyHw;K?U&S*a5MuAap=Sm)-Lm9}al^=#BNz%#3 zp#%kF(1?=>6moSp_eX}cGSRl8!2cjJeD30{JE}7`Vk>AD)*adckLPTYqZ#_88f*5( zpL~A%z1X`X62IqFEr+!d$2s5Uk}5r1 zh{K3hc-H}f-q&4+-Ygu39qV>NQ*UiR%l3rfrMDf>pN`wn&!8|aqwd&!$bDxUGNwj* zayfLnXTOEZkn6rYeA5icCRJCU`}-#0J==JImdzIQ`RzoGF!=eMAs8R z#f=AVL_gc-;MNI}HojyT>M%5qBl^EpsAY;X>EYRk#I(AmweGwbnO>fNbvjj1(sWlL zO;Q#vGd`%@Tzw^)HX(;2j5e6Eg}zH=yegLpUNiCICOalt@hUa{U2ZVhAwWTG-C}UJOD*Jg0SskN zPT&YfT{9APs5ALde*uCgA*dgyH}2a$Vn`C-btZc2ys*v%Bjjnm2Q`d|7Bmgfd{w)C z7aRCSkcxzA0s?Y%&NfE9UhYFCn?rc5HkVaku3@s)W*$CRZh&@F*@<43Bx0i>ZIR-# z7G-u#7D}q@LEO1zG~ur-1O%)h)B>LqEvpfuNtk%-Da9qIA?p5gHR4t$$bhod2yxvrHcoX+;4$v2Fr+|)Xjd(UF2#i>dXhtHKMU=Eb%(X(?_Qg} zRJL0tljtjXxchSxtz}CsYBn<&&&|s%-qq#^dh%pAo|!#ciy|0$a4MG9Dk}e>5_D`R z;TbA$w^|dmB~y2xuhTMcy5E}OkF)lm@1YZflK2h1Nqg#(5>0k4J}e-hy!b$^*4le7 zGA8Od%HDiAozq|_ncrm*?s7p#`M7mEGQFCNA(yE`xwhBIA~gHyFpki5WAx0L2=c6R zrhtH4ZuiX;oq0Ra!;R|sV`s{I`SeQ-_itMWa|xVr;Jm`^<4h`b^#~GARyPOJ#I=(-*rgm;t1aI_YqCW*<2S=I%=jc?%=EqN3bL{d9V-@8k+I z92`;NI1jZsEqCsgNDM4C2(}CD74|>(_LX{R*Vj%~BNPPtfe2`o{5|#ACAjfznFJ;q zlQlor$cx{uK!4101^7ze7JahLh7P9}8;{M8L7h z&zwA?(bJs~q~D200s?ZuvBK}+X1&&C_Z&`seLE_QB8U)mb>9)w_>vLC{n7$qOh7Ji z)CSJaqRThOlPBA91q9@RV}-x?T}7!HY4Lco8-}(7xn?BkD%o*GXmp~wp38drZ0nT( zGSAyUK)_X0Tsgf>5Y{zpPhJLC6S(Tb-W2;IrRw71xTk}Nn#lu>PRJ!{cV3qwC1g(s z(X{@GAp&y25v=-z8#C8N9Z87KKnzC?)PmTKjqX2`Ki+MK`&Cy0_a9K6uVaw*@!%Dx z&&Ww!SC{VBq3D?}Df?nXAO#}CT6OL^lIAt^AhxK5fPh@$PG*nG6#B@+hwN{xPap*% z;5=42x6@0voXHKOPv8y-ay4GqK)L3)8oix0p0~p|@&esB(1+(YyoVtLBE%W)ic=Nt zsg{YFpA#Y=7o7RjC?OMaYl=M?wJVRpTY2b%e(2U2E!)=xZCKxn-?x7m=}e|3xRUdo z`YRiwJD|~~ebDPmvk>HhXdVl&z61G^(t_~#J7wy`7D#=4q&Id0DmtP;uV@4+n7R$Y zl6VHQ?X5_yazYw+|1I2X!<$>{kA~=n*24I`S{=EB|(&b8u>>{F~Y z-Z3|Ytkvr;AO@v3m!l&}(3frD|Jhku6pcfx_lzOS2geF)IGjZxnxE+J9aiQ>rINz6 z0r+D33B{WSoInP3LWNadoOc70*U*Rc5{Sc`I@o!(q8+6@f=1-^#c(!&vjl$|<=2EM z)R(x*iuTPs52dsHR`j}CcVSPx%g9XW^=vPC{8oJ@qiJ1(4KM0T>N?(&AqDQj;k=@r zot>CYprabcOS1;nQd)#72nSr(1>HLaOU1N$~T33AOhXEi~$uMY|sx& za=1}z+Otk`<=wDFsGggifPf|OolHX?{(`kJ$?3ONu{FZV-uV7#R;@*99$e+zv{>Zb zY#%E7Y^`LC8HrqCHgHQ+vz^XNN5uY`k1{6KTRFeKGcw=mgm%yGs2oq|hBAxe5cKf# z8{t@Mw$aFo@GP-fh=5$s=gA$TZCx2z=|mD6hbpjKSVM^BdG53hEF|8QBo5iDKng^N z?MO8+W

^kY*sge9Ur(+2aF-*>FTI>q)P4&@d!)w-s#rAZEQZ@U^n zE{NtWFL+GLZ-$bP{iZZ}$U$wxRoSR!R?U1+85%NI<}nB&njP4dWUnWgXfG?SOTM*2DKD zZ+)0;UPF?YcTa&7h=3Nuhu#Jg)t3q>P(Lv>PH5T3&FJ|%iI0!#>ju-} zd!xyZQb`!+aL>@qB0zg&(g~EbNqys`zSVAAC6(}70|aLV$o2cuG;Q3t<7nR(503D- z(T=9KPbd1glii8zgkr+Q^M+UuQnqK|!lA^SPu z+CeW4p}scF@Z6gQ+DXTEqbHiLTvt{j`)GGmPa%uu7f?vK_9a}irRrW(-uWvkTs}l| zp=>U?S8pCi=uXI^E50U?B5y|wXENAw*gi?(uOBM+SE)5VD_{GZ(|(-Ikl`L@4BMo$ z;Dq*Vm4j%~Xfxi9QC;TJIi5*G&9Dk75CPl7qcg+z(+vY-h~*=10Rg$h9yC6`hF%*m zjAsiSOd$m#pbq)X_O=#mOGHOfT=kK1V`n{OX7qk!Xe$ddC!E3go}tWuMdb&Q%=lpf z0&>9_oZsU3UQ%vtPbH5|b>V)_=N@}z6(CL15W#k#O>?jQ0v-0cUmt#7(objyv|Vwg z?w;O?xeoRuE27&8s{us7k;Y$B{c6aZmimx6IgKc6IV@LPKWbIA#YS&O5wDd=v^jH= zJ#3GleFvN3YjIKX-0!BX}WQc%VeKu7?-3MvW_Oo5M3~QH$ zB=dH6vc0IT0x1vy{oMTRc|QZ9ySg`tueDx4KrV5A71Pp=^xE!13=f+L9(TwEcW08c zFzFr+{vAQaPc2erKR+*z?#<9(UuO(!2+{m(5cL5&ScH&gGa6EefLuMgRYA_pcc8_K zOnA%d9&1WWmUxkfmv$6VAOgN9;D|b_@#%gEWaXvmxVsLMvtA!UV@HMvJ3y#)p7H(u z8ocIqA{h`q4M7CtS`)NYp5M9z?Qf%cuyh_#yktxq@&3YONP!5b1@4JkdH^q+6HjiL zwNW4fazTx7?anF3=f8&&uZb;bp|(_Bta}j6D>TE93u=V#mZrFnAdwydCDNsK{ zS2jcLY$bZEZ_L}_Hfaw2IDHi1Z=@8D%L(#@0msqexy~5Y5X$4RGLzTgLFY#h3+vwk z0&>CH^8Q#Jjx%Sckc$b;G2A=D8xN>;Ny>X~k6YbJBWFWSBZz=pJk~%y)an#!Keroi z$M(5V_+7(P;$s`2Mj`y8Km=@4rS}zkZ%rd=u40IQTu>uC>X&CBX|ZD@*}tWMFke9~ zvE^kKpW!nDL&!_J9(2UFQrYgqX0+I{3Wi*;pLiCioUNGWBPUgCy9#{{(QxkKZ`HV! z_slP$l7f5y+a6>p{cSJ zs~Jytt~&)%AOgM-=aI!c2a*p9A!$L2DMUan@$I1bcOT3%4-?BC8wCX9idbMRcj2du zgI@>nT7A!2h=%L*AjRi;E06*a@U5bHGhvQQpG6WLMSvj!a=~4c8qb-d9M}>?T#YR- zq(FrDTKyA$h4g4`I@#Rtw*nE63!W^v|HHl?jkQiCmfB4Uq(B6G>&~O%H|NutC8LP- zfcpXha=~*O_l(xuOwSkvk^UQ8F{D5Qe9J3I+Iz?8oZz0MUp-R+0lDD$ljj%JRM5!v z9Z7}1D~1$^fG1@2*5C$RyCjn6<>+8|0|9Rb;Y|qlJ6GJH;m%Q{^`mUTqX@ag9dhot z^YqW<7@j}6A%YZ$SlF;aJ1mDH*H`N6o%7cp(e0LzqzY#Pc&>rxU7k`c9dGY&++(JVl?)I+7gD_7D(|3(jMbw9#mX`j(nB%jhM{R}iuH`wQ8> z(PZ?lK_Qp1WYG=mRX2h>KHpM6KrT2ROH!j&x+MKoAHw%Q!rTrKa3$imwfBw4?iD?V z$FL8=+zz?K+gct$r{)SLu|>xfNP!6Pwsvv{iOkIlBAK&;gmnAY>}Yc9a-e{KT<~^B zy(wCwc)c9MeULH2y$?i)C*g$_vhwzL3itNq3JAyr&(Z2V^;fj!;3(3}J&(eX3b|na z^PT0j4p`SEiF63drH}#c;0+X2gogOBVdV}(WdpOt!;w-wn$#!LPSTYGc zI9ZrQAp+`wa{)O=)JX-1{^g-8I$W z+O;{I$X|Ht(`9Sx2?)pqYs)iD-4A8{+xJlZ#R3c|5CJvKv#J=!vjLM*=?R;I2qGXC z>?giY>=Z*LUtC6QXRauQF+VVZr{6g#wq-pI=*|A(a$K4ivYnzKa zTRcZoQre*0y-8^N>D%b#C|9&JU=;FBF6FlS^++<$6xtm>UTZ23{cec{wwZz0_+JQ~ zATQl%fy`W%pp&NzxeWdamuxty;8@GW3Zy`UI0l23#uN8#aX9$KLLqhuqD4gJ?LkDV zdy(g-sw>1tK`waDq-MVuN=9AIq3y;F!Xu4apsqV+p_6^}1TDb!ski5e#A#_`dTC#t z47CVr1+`vz<|KEE!+1WuIS7^oH7cIAPah8>^4;ycKXfsa0c!~5@mftzA(sCA6keuK zcPInOmZZ0DMvx8tYVxzxZv@MNGDJj;bFsuRX(zsQb9=GSYoPzdcGSMNmA~bjz#QAy zpuXd`6<57FMQJ_C4#E6RFrt#L2E%OWg1uwegy`u47eoi$nXV1(JV_ye4yq-x(e&Gj zG0aGAEFd5k%tpks^;}s+ch^c{`libeq(DU5st>guSGK1QS4JOqLoi#Dh)A(|OxG_P!s?wkC?Fsgl*iv1 zyf9|f`u1c$Lzf8ULV2zGI4YwK^i|5kta&@^hg-4$i;k?eUljoXxnO<{epa(?$5MGd z^16;;2vQ*8$vHoz(`t>f!BmxT`dJUAO=`fDrEw_0eu%Q5iMjI7-4Vf@93rAr>B43Q zo3Rlt5`q+nfU^0yHg^!SH><)v{pusgXxAi7**yP~cKK#|K^}i|*M1nw*m;cJ$}5v$ zxex(!fbd;LlSFo6|0bHHG)0iBdYf!zl+j+TcT-y=BDU-p&35T$(^oa?3KWRAb|+7{ zZxgBYyKBpJb@yI6YgeZRExEl{hGju6m`O>JULG9JZkugVKJBv;ayLN)isavc=)I&k zwWbG`vC%!9S=_P08{e#vThz`|46kO$xq~o*8IwdA@7z<^0`uwk!mV8b0%lKwXf>;f zJLC73r0vWWTKH}O=0$?<9C!@YD>K=z{sg8!Ww|gjz}bL*xkUEZKUvWorj9}W)m~Js za46fjUZ#)&5ioL^&xz*|e%f&eE4DHeVyew<7s_)2a+Ucz+9OyJf7j=>4R06i$r^!&6N%J91%qGd>Ib?NKWnTv_kS0V#BXWxx5{lw25yV z(6!-XQO6gbwGBMgnL2ZZ8@cxSIMsE#DeB*{H;D0w;hq2hg| zqafqM`~uXZ-Q?oW7i!@}25!96?!|MrelHA~c|( z9fncSL5)q3MZ`R0c(EPd!=;Qsq=V+5GA7xE!5ADE^K)i*eKg)87d2nmo+J3aoveuL zO!@arDJ&O8VFzT}@Hf4MsQ*dz#g<=#V3Pjf9lf6QQHVc>HH14^{tf9y=EU@I7doy2 zvr%3D$Z^|q(Y;t_3~K@-lq6~YkOZRhbSjRy-hjerYZ!A5Yse8OnOsTlhil}$S0Du< z`tIw6zAc-D22ASD+u<8HjPSSy?V#wBv`J$RWKuF4O?={wVf+t_9^!Xo{;nis-fvnq zw1Pstrv)3M4)qGq-XE@5%_8A5Vj3Fx(~-+)wXZE%y+4;8yJX8C7i>Ay2#*+PZcXfC z^yuj{S%@ow2-ur^_G#UUbZA&cd4#{9-5QU7$(eO0BbWM47|NEUG4|nv=f_oYC%zKm zqo#GRLc_ikAk!f-h8p3%?UAiWX-{2t`B5#Q9Z-hY^6snc$dV_`c=pyKg03Lf+!%eH z(Rvojc2zSW-12fGmlB$@;VDxE1muD?#`6w3hN^dPbW!qj3T+hj4YX->hU?1T0BoVQ z=Y9(^V9P~ay)R23emT>WUwLx{8PLXtcjbAQ#w|z9p3A%)B{P!Lmpig=tyO|uK?Jlh zzH;sxL!|uyo~Tc}5Pb#_Fy@QzEKB>55vy0yLz$$ebA+>TU63P?{R#$=$?s$&7`J4lw>4mc(@xo`u8uI5Qq0h9CtZ zpgc)B(r6NHyx&RvX0eb10`>t!tM9L>;VMOL%(J-{ZT%P<+X|v8(zIY zkPZ>BwvuGN;{)=o<;=EQ<_NY6?N!WDkmPkhiOBF^p7AZjj3*$M0jw>Lf+#J z&{0_!Qee5ThH7j^7OuGC%7!+bslY5AF#a6Q5f9tS{^E?@c0yju_e~94n%X8aYR`^RBtEu0>fCBA~THG|zfkE04dKaA7|FKecd` zfitJL;+$Oa9Px}+Z2xCl3T+h5k8s@ZJdp2O(cyQT*w5g23=z%dlxW=@(~#AgTrAF_ zCl(ef1+$zPT9_vw;P`-O9tC05kiK@%FvA*p7-|vDIIw5=jaRlAR=I&+RM-QBf=6>w~^pSC)0{3lj78Un!syA^_jV1W;n4wyT zfaj>lQ(e)|gte&LGMvwFx#PUp^b~XAy`vF=kwKpVx+tfOHlR)o2mB{izc8~eYx=S( z=`RmKFoq8zI+b^=^y5w28_H!otVdWxh6(BMj^};>asO#sJ1KjT)*#KFp+c0PI%@CJ z!p!O<_oRyuMdzJ(TU#}v5V>5*{!h+<@S}5Rzsy=B{HV7O+b2ZrSwdLW*UCSWTiQQk@pbM&7vN1__iF4 ztEpyH>3PANTwnJaUt3*QKtQhd*DTQ4(iLb{8#VIYGNmQiZfQ);7*z6HvdM z=|%F(T99c+Qe@cA@Ljl=38CMK9R5X}TBP`17t$efs$6SEAu8@V3B#CC7)#3ioMT$D zrsL}IY;520nh{n?L9dl4w{@BjeJDm8Uamfns2Tq5Cc7hOaj=GBt(F84f=0i7?gi*dMS>JbEDX0OsEp z!QEZD3kb*sH6lrSN=j+}!FRD`+inC}UpHV&(8eUmGrlg1SW}IRIoyo!`~%7a&t+)B zmP{dE28`O|J-EV}{X%!}ug?tx1muER=R1Hswb;V)OSs%h93M~~tS#Ry)$=FMf9sJ8 zvzlVqAFvN#^g2JQP3%azSn87U1G_Nn1IQ&>V${VOxLr_P;^o?wz&?PZ3u>CbNp%Up z%997URkuNcB|__qOM9#tK4B?(w@S@M^88>qDlh+q`S&0Qq(B7Bgu=5^t_-8i-blnD zDL{xU_65a^6{}FWo|^4V%~+>@xdEBE;sAye zh=6g>+;)fgv1h-(;M%&21O()Q^CORsx*5dE{r+I}v=*s`J-|Q33*T!FgWw>$`cW(&-*f?!4-J?WCIHI18V}cz~36! zc43Y77?Ia$^#lae0z~sy#a{93ME5Z``pQ$`B?o+?A=aw7NemmDIETLz_EF%g5U2$a zv9(hKEBg5q>wjy3Qpcq$dmBEH5ABITH=D;O7IjQeKQbDL-_3ZKnMfLTo`?;5mkY7l z(6^nFjZhZ@e`NG&Kle1OzR{8NJvLuO&`I({#9x!jZITBgc#{tEvhv86-t|c}r*sS*fq>wS!p<*XLEItKa}|?!z$G1%*TU2 zBK~fW4S&=_KtQhk_vg!tEgC9A+pXt_+;RT+XQ(NY?sO!O0uj5S%j8-uWTkd{RYp`< z0j?;j$@Z@EC6J5W8k6MR@>kur7pNfW!Ck;BUQfBsDg(f6VK}L1wcn)#sBY1m6 zKhDQkAO7|1b#!mA4%tLYl|n&TEG$YUUep~pMAjYk$oxDd)4r0 zrL*P zSacb8e|?dr8}}4sKm?S>a|k{9!ryZ4r0y;J2;^dgozT6g>e|!~8i*0H8lisL3yH;+<)Gg*nXT$7gjYCtOQzy zh>FQ0&>CHa?j|_Cd84) zZ2u_r650U~{+{*FZ|fJbo9lTlV=@1h>49&HXi=A*0s?Z0x~i=k%U85ncv=x3y$3rZ z_3m&)>|RtYaTK~a;FHY1DvC~(^hdUi7HEQ-`o7(|bO`x0>ppfEUV*MxbVqidI-t(c ziv%t>RwRinA4m#~b%-?APC!5|IMVpcFm)KQT)Y*}THP8$8E{<^Yqdx>p49G@fEW1Y zVMu`p*ghV|;vP*_wkSXbds_>c(&31Lvyvp~Zy!sX?609_8HN~AAOenHNorRomGnYU zJZ3FeKtL`xmt1u6^kU8CZP{GAj=Cd=cf=fYd)j6UDG-rSk&4D1i;)}rQRgdu14%~3 z1W@%`5Stg)L^~d}LDm<`k>^ZT)ScXyUFsi3o37cToz6{A+vX=Z;`ADC9&4~w$qO+j zkOC2(_jsczRq7-A3+l|^wT2M&9le?_6;dDqS|xuSeY7X>-*rTrt!E@4AeY#Vq|X85 z*pD0~dPgk+DG&i?ZAr377)rb{_GstDT*VLpxu6dDoqpF;;<2-d64y3T(5`i49$&)-uT(zMm%|I zv{?CZdYe!y*bZ1j9<}8+mh8jXcZpHZ2H-)Y(j2*?H3F8)qtPXN);mf&BP-Gwy@u7hyQ^Z2M2F(hl= zQ5?2JTn8Z+tS!&{)h&ux+MdC+dpQWTf(SVNxd+QImh71j#kPD6i{uQNV{mHM-x@1QO-C{Uj!CjyDmUFmu4AI0N!tpOQ3Uealf^(O; zBTFRBa$lmtQ%fEEfFH zHuiZZARyNPjV-71#wZ>3;w6Ga$<&`O}zxtDC95{ODC(^moUb64SS!|UJ>KJTitf)FNZ@+cqrp^pA*;%LpO4Yd6}x2fRx9K| z&#&-ylntGST?e;eyI0tgi;eB&{TIB@&S4VvTDgpKxFVnLpHSxIb#mmuL8x8h|5w&m zhgG?BZ*Rp0L`B3xMLcCP8+w`2a;r@N}mlZcQ0Nw$3^F-18Y6DTu(@l3v9p@x5hw$(LC- z_@-D-bH6h2EF!NoCkuFUVAc?J{(A{-`ZdqIqHr?X>f}JO8j-V`J5hGI2CJ_s6h!-SyEBSMe_vXE(3|1<%qJmZtL9)6MSY38o zF(YNk+>^LLkc2N zZuK;uYCYY&tz0f4Xy3zcXZ$T5c=uKi$c6JGy}k}k;NkbK3ZEI_8d4CU&Z0fG{K?bP zZi=v7K?(xr;7GTpX74s`EY<%B)yj4FM}F?YVG&%qorV-d;LeF|apJADvpsc@^^z+H zvFccWxVGPv-hN@40{v%$*?v&Z=PPgv>gAwqh>_bocE6tyZ-Ql($B6f zOPc*URb$7pK2WV%d@Rjx?=B*%ZR@Hb1;2~^MDMlTC-8i?l5$8`8wG(}xONd@;(k7= zmX&;7pp~+!Ap-k}{A;UJHDV5mKetrZaP7lBKp9frjPm~42fyXQ?rCvFx+qax6UqO> zw})1#ZZAQx^f*!wfom5x=g``Z=U2@MVs~RG3MKx|YJ8O=FZ+Qv;BkEik?5%fS5&=5!c<>1h==;gKOG# z7V93`NPEXX4JoKGs0&5}{yrlAR*snRI$R4YbkZ`d@@jKa=c|fdA=+fR@0IC$^e<-_ z(!@_Y?N;*0hFy%^`)2wbC-=WPhT3Dq5IW8(KCDSTCT0bJT(~DPndX1*%YSUGD!mJH zWw(R~Rj-0e*Vazdcqw+3U?$--8PMReLV;nk|Ah7|07wa-sf+o?xK7LyTK-IOwLW>DMF z|IkxjY^x2e(DjsYj$<38PB)Nst+kEzZ$``&Yf_U|OUlavcPDZ5$TT&! z);Ih;m8IM&!O`!MBE){GE!{_ZOL=O9N&$p=r*HksEZ`M@#NQ81! zHITOVohawadPP=#Lh#Z<)P(dIUo_**pgZvp5 z-RVMErwVFFK?F*H;u;(*qZwJPdIcO-&KxLdoX1QiBWq}nd=J_)yj5m6M5v?Ih{Aq+ z24#KADW;5CL|{J|d6)Y0Yw^Bv!WCzw2eBRMYEWq0A-3wepZqJ&Nm&gLfs&@TqHE90 zRX>_#Mqo_^fn2zD(Vb}dWqo_! zRL(u`rBQ5h3;Nn&gkaV0?#|p`S^BSHT0qC~W_)GE*H`=!ojI4p%C+q-^DpuD6$E+% z;yW%SApX=%{u6Gk>EgK=zq>vnPg7_0TcouSU2I*6Q8K%iHGlFxoSz?>qBouAZ0@u=jg{UwQLh|! z*z90VQzSySQImt^y&zkC)Pf?~vB@#I%}zUWy=JS~KbZ;oh2&_nrRqZ3`AyKHyVUU= z>ol9n*wZ~m27WS|o0Yo4k%9;;n{te#50-th-1I`vwkinZLW$5UdZwog`t+UGe3ik* zp6H^Nyjh!VYw!odH*?e&@-j_pD=Esjmey#a1vMPG5KZyO`t+3@zvptgc~;86_j(oK z8xSp{vX^r@eesFI`s;4YhG|`9vHIOZ^{A01_QrR;@+IynHf_f-8U=FUeE`kWbwMuCIUY z*^w0~ZM>K~P8lrI>M!B0!>=k93D|N4ZCbu=80F?%&JIpnWMn!0|Me}jt(m@(oQJAf z_A|ANgptq1(T!bY+{(Gi>Wu3-?osG9V}Eg3Ik*+Y!CtB$6fW2~(H-)iU+6x@Pev@t zRuH(e!1rvM%67ivA#)nOQ4q+5w=ML}d8M%=YjP3! z`WweP66C_W8Y2coq_inGP;BcjIK6l2HHLL(PZBRP-~O$>WA*_Bp>QdE zKKDa_+?QHeTQRwyGCpvw#j!$XwTc6zb(Qwa#dLyWKiBEX^|wJDtkAC`|LXI9nnuVK zj>&qLBQH5>10vL$q7nPLNoT(mdY?avX~^Z@ua0ih)S10lc$%q*h=;@FuN{HEXE@YE z)LpFYZwoqEslK(?P~xdlEBr1>o!%hl1j$16QiQgufQA%AV9!#ViE+2Zzz25HsaJjF zB#bLE-nP+h>E;{Z-1?P>=1f5#7v3$JOxgC=MA@mgMVl^d6$EnO`O2^a{4Rd<^^n;; zZ8fY3YCdWu&AYD)%PGEP<+_KJ6$El&4Na!8rK`z9y9-E<#$}cJL`0~vqMQJ-QrC^* z^!!)K_&{w(shdpyB*)4I$A|H`n^r5Dh${om!E_rnq@V2D$cit_yr3YE3-ygGGYhmb z#<*@Zx{|i|JHSC$m;i(^k=dH5y6{whu` z|4%00YZuOOHb5;=XND~oq9yaZ%D)_YtXLT0juqE=lWEqHL2~-7jeN`ITFMRp5xCc) z*QMG6WOJVx+;92}1%X`HPbSkZ=U#HhAREdk_?Ba9kxP-A>EN_j$+~*+%z6iuKF2a} zcV;r3e%Oh8InVnhdz4c89J!SKH<2%cJX5!v=%IOQ*i*=bf{Yr9ge|-&cl4-4cZ-x^s-fa^>q#Jw3@v zFS@4SL84<{ZFp`Y17;rq`*We85G92;{<;EXEz#7`gRYJyGiDU4|4y;I5ziipnL*gU$_ni}h{Akb<#dN! zczPkd+MOUfI{Wd@wM%e3DdO1>$0O}`@6t}D$}GO^+im4!id;Ca&@RKKwtThLNB+mL z498eV7;ovx_`l_Ez8z&dyPYDwaGtUbB3J3| zk-DYo0n3QPGpOYk`uWR^t5ynQjY4feuB}5N^m!>gEUeUGLYRxTk$#^OMT-iy3Ie%s z)h3&w`=0WC!eqJ^_0o`nh$K%xy~HXjOJ@2eDkD9umZVt4BG09Pf*hWeCFnN%yc$7?7O zLPd%}*F-}KA_D6a(eIqI*Yl1V_M%&x$7_q`P7qbgySL1RK1ddKrZyUFqyXRFGHEq zTFHaEhjFAJ;_Z~G%+)$XzZq<_!}sA2o-?rmKxhiLk(ZB zhHfX8DG203jUj)|vDGLCZzK8q_7aZ$j9l28 zMwFY@yvLSE`Rt!F9Q(jJ;xF^*y`%K)x#4X4fpflpZ%)#e78p#m`tWT%doyVuMU=BB z2;@?G(B)fzWz4DmGU?}Ojub>-Z<g+nq7(#jq2|-xr{!cGyt+SS zA)dpLf(VrQ@9f#)Lv96aA*a^YB^6{l+_ZP|oe@hnE?=vRbXI36jsh^ePmY3WXJ?U+;$$c6q!ajBa(~p>LFc0uTJp+l|JUqeRcD_#vA4b4dFU-i zZAh>6-7>sWoSr!#grWABOf|Z!6VZ_&@>Sktjub@T>`Hr|c}s;&n@D+#UaFCT2;6;; z4P^1F!p-tR+&JG_!@8e-G5hscrP!z6UI}6_?P6YM%W?)Dzc4g+(nC1ae{DkRQu& zXR?}nDe4ugtRWYk4Hic>(Y4oCM9rco>-`L9& zdv9|@AQzsH=-#JQc^R^QfhBd)9;aP-UE&r%2 z9h^3aYc~JUkb(%5G_8YvbgTCAE9-T8z4D@nH$`}2HJR*t`^(X*?+UtS;CMd6mSb(n zXLLjnIemYiq!}?FqNVt>_jq{lZ&iF2S*lQlLG7LQ)qOP5?#R>-C9EI<7CC^r3FME-NyTPXv%P|}o3sOfEf_&nlhd$Y0hPQV@YVHL|9<^im(Rypi+>tE=p(ao?uyWOBN{)FXRVk#TnZ%1#Cm zxT~S;Llp6}=GnKR7zP;;sDv4XxlQ zU-6OWiHD99$vwreJX$|8F0zAH&kK8Vtb#x;v~?#dq?6vfrrlXV(YZ9FAOht^yVroh zeBILHVogAlfWm(95L#G z7~$MsK_C~(jqdbam+`Y_gqV9aTtk_ltk478$as5%Z>zpv)ZG`VAdm|^3FwV}OEGQa zzI@^0=B-EjFDgGjuu>4ng(n%~lv+}& z`q4(Vcc`o(1rb<7x+$vno%bqGU3SWJP!Pz4v$n|;HR%-Z^QVj4wzGzY6hvU$2C_Ds zxQ~ApSwSEd&f1hU^i(*X-r8)${m_tt2z72h5!aAEnm|4|P3kHqNJQXSojk+h z%jri7mX&nVqTzgwGY-zKq*uR636~*H#h=?FlzA6*7d79=y*x^5zS&n$bUcptl;~fp zp4ATK4AK_0??$)I3pi2`fu}w?pHJ$i-D>78is$^PoCgts9>7L4s{k#r>ZrvT6@6Mvra@ioM8qGb zMNlPmWM~!tHUSa`Hlix^m79&ldS^+lAGV5am>aT&g91=)}PhQA$$~DBlTi^mb`rOE7K ziOPiVaeB?m2Y5@rJ%uIK9rX&!rgLq(42sDgBO7bem3E-^VVlVNtmP7(;MH7O4=yQ@ z3(K&2HPbvUEsb^aHe&o9Y&n$2A8a7EKKj!x;3yBtW?MtIsMxK9qW5y({-MI0)+}$*Gr-<9X5WQQ0 znE_>`jzJ?9fKQC8JYCdFsTJ0w{N79-_rMg^aicr6!}iD|w!@9~)HPxxQV=m|63w0<{FWRK3bMU5Q#gjC@8X3)FVhEBq2g zRy}Obs%{=7Df9Yo-F4WQ#;RR)`#-w-U!5k4_|MXuyMCfPbmyQM$HY9x#lOeL@kOrx z8Xtw~Ju=VVF;O-zH;dtXg@_T}OMRBn=(=m=N-ghS^R&6wfpPL3cUHcITsYg&8K-?a zKJe}^>9iqMne}lsz_LxI9d54NHE@jd-&0sA0}(g}lP%|~+Pq`zAj6tmiMD_d7SuAf z-?C-S-(txoHCvgH6H2c?T>H<_%<|Mh{gNrda|~-XsV}|60qRKSwP=2sai zOFmkvv;$WF^nxOb#`HGY!W>7rYDRAzGlSr|i*fbnWwiAxoK+I5@GHvTNYBC5<` z6Cc;$Z>QZiS8AIuUYPro&veBO}Nfe-q)=+d30K|e9+m~f^|ord0$o0B}Ab1P!^@+a2Zr7UEHcNK==d%=zl~cvgG3JImSA74Ctuu zNJwPOZMxE2l6|Iw^ho|DTJk&{xiI>-iZB=Qm30f6WXsB1M8S`g|8GVj^WEsjF|!AL ziAK~mKbhZlu`tbhDVha(>4(=OGWQi+LEx7tp5^t1(&KEVI2dg!5m9JIIsN3?MD}@S zV+CzQVyh@;zxqxYrwU1|2_i733Hi!236Y}~Os2>bYX#O9<)+pu^!fmb9Sc!Qer>jen;)|rAOz8YRxZ+#A>ZHjQ@{$0bD)$TZ)CwV9QgCXwy%&#K_Nb0e@A0 zDnECooj$f>ChLDcMv2&r@t4W=!(*(dd3rUc2+A5pmB#PZ7-F)-o%n+_?`M<|{;;~< zvE@?b(>~3s}&oNF_cwMjIy!(?toIel(cxJKtG}DvxN) zdq8=38wK-TKT|}SC*aQ|mYzoJks2M{-x6fuT|rZXjbcxjaZ}`bI7-9sB0?>rQyZP%Tbv?}%nh|+JaaO1xHTx4UVKd=n^lF2k`!Frx=%YEC_i&NTxa#PFr z728M~z2c&{!ESKO094kw5p!rflRel!>R;K1D8rGq^>RyL{j0Kub+h0w4^=FLnD#QJ6wqkojr?Y@AaU3%ajl9&6TEqNGIJe_kVltJeVk6Qk#~b&38d4CU zt{-Qzx{A>4mqbWXdj)~(AeK!xsjqGeIrf6s*1VC1^~HAJib}p2rmWxX_|m0|f7v`%W_;uLXa#{>xS~@0lHE+!PHKGkNktDuy4cUyH)IKT=81T^J&hvp2PE}`Tuve!>5e&JgI4Jn9FwcV~*u&m%Yi#MC3jwnQ6 zt_vfNNvvG+Gmu`ywhYI!imcH8b{mh7+pdgS7S0eIVdfZ84T{F0i`zK|MLImc`A^Vc$e%f@u z4*bw0mu>AdpMlWh^TAi{EHEoo2_5%1#CmnE%J{`MJy;2W0TvJkJWPI@Sc|8>ixVgxEJJPi5QkxM!}xsjkhkjuQV@aVnM`vXM#+K2 z#~j&JJ4r#{4GT)0Y}FhG$)!iiStv@gB3-lxSp_F=9++dV*B?fCs&6#n$G$u0e}vCt-QU-v{`e=ghHUY% zfLvA0S|VajGb{b)n{;-sL45^H?`nTXNXla(?$vrI?3cLeUgt7c1uI{U@~`u+0J~h)~NIWD_GtI8PNB6j=^u2INAtVG%!!VmetY#%zsq z2DTQzMEM6Z2g-GwW{NxRBb71`f#p#T4s1*3kAh?~;izZ{_8Mx8$@DJWU2fStO{Ch^ zl{kt}j}c7~fyhqZxT&4DwVHxJE*v+;>uZbO9=VlII!dG<0(F{JoTptZ=7+uHox$HZ zz9?brHuZHWXJtV_H)_8N*(u9 zdT{l)>z1tTlUeV;Ivo3-bl3WucpFhg+!@wWZn}Nk^6+#D8+h4ExeLeHj;x9YILlj~ zyya^D1_IH=x6OoT8kZ#2>3tLgzDHr%O2v-#u?D z>2*}3cy>^BWH`>%`Kof>RS{2bkW(gwNo*}5)RqTbDy_G+3L)#A@4sKe|7$g6SiNMH zN@MSL*Wf4xiYZ&Rj_w=Rk#g$UN~9nHZDx$ja?$$U9{%KAQ}zEK{%e0@Aj;iJWq&_3 zY;ioB4c1+UyUH)4`Ts%umkZ@a^KPpf;$3=~%mzAQx(-5sjpj@O~5_z38nI#|Mrsl%a8#F;73xtgoElv`8QY z5$ZS(sC~(@^l2~Iu6wS6KrYp8iR`b$o^iwFpMA{S!)3c=+PNt#rM?r#9S6?Zv~qUy z7D;hq<@}5X7NlUU)cLAr!y1qisDgw2Kl`Xlq>R6lUCmzyh59_42YdB68EK-@{8in7*-GIroGG>pcRDU4(ZI@vv6Re@yAEyd9 UOP?<-gAmGb7sz*IdkUBnfZiw3$c$MFl4~6*x>{E+xHt~ zACw#$KcHJm`0%9WaVg36|G)pTD=12wMR&eG^91gB_BZtKZauo_Nf26Q>WDrbokH`f z*c4~hIJVE@T^N1hXN5|iyjB%us}{-~cih5_#?)t!0uiRBL+G9-`_w$=`2x`+stbR= zD+ymnFJ?B+TKrRGR}Lup{spbQOK3C@V07g(U0D_-&i2NTW8_Yyc#^cz=cB!MC2{5 zhoY^*Y2kc3fzX=Rk{u5Zv)!j_^0h9J=;J*Hx+3+17LekGGA_2I2m95cG9qBB7df1k zuXRYT%|8|lMIT;%(bm~>4WcJZ&O%}LcWPGCrin2>?1)KJpPOp>t*RVSAc76fMi0AB z)jYC81>)NF?qsu3yw=ze#2HfS4jxSb$ne8 zI%EF1c!u@vVnw-{6Go=_-@>zNy0Gq-Mxaf1^3>8D167D9wTnj++^(tKm$#~l()d*{ z>9PJjPImj7LJCA=_y?dHe>tPXb`_DLw0+lwR4uuQYn^|CAeW=7C3?6a6j|POMl!-= zfCmXV+K8;$XCYA_;_qShXu;=DlzG8f$jD6gS_su(+Q^>>3@H$SjraTh`z0~v ziytgSJtlP|eo<9bnewZJ|B-Q}Z)@B#q#a4zM)Z~d>HilY`c$mT5PcFdJj{3DMk^YV zJSQTx3UWQnD=7O?JCm6L(QxlKJm*|f^0nrCrvH!rEx{qln>VMp?Em#PD9YwRKX6uP zQ*uR%Ly!VnD9i9aGmu@|)R9cznk9_~90RCzMJagogx&q!l{8Fomc|1jT5sF0>aE@I z#Zt7Y+2_No(_~lje&81sehYGm{*@v0)+x$2Uxj~c+Jvl5En)Dx&`NYo=rVMqqP+ae ziO(9}lq`QUS3*E8p^-9#ZU>4oU}GkW>(!hnPE9dv6>N#lsmsu9Oi?mS8xn_s&B)z| zK@^S$)U;@=rXz&y?o*WE4I7a$t(%g7ixc%${i2ATm;EjDqrxvK%2YfI)8Pf`>Qq_(VPxf2-neRsUPJe%(s-zZE5>!V0zOo(uFs#f}mJa_KWnpKU)8g=2;l z8-=gH(Yu>Uh@O_W4d2!rE|Zb+I#o>?ySD6aMe#H2Q&&0qFxQ0k9DeIw)={MHgkO}VaFU90-HM5{E>4}<=mxhjPgP|E)F>QHMfuuyG1`qhcw)t}R;l{9 z>(Ye`U)^f-zlDrqF*ap?D~d(zK|1epBfd0BMnEoIvwB~C_9Nr&adfot7go5ji8SVL z40QYYpKL|(-#CW-Xj_GQZ<7&_OO|0CmBZ#YT!JUvDYKGadWYJDdQ+71+CjEAuOcaU z)kGRWh=AjyD5l%@u%epP*xe&8B*?XvVbHoMsP@F(sJ?YMt$t}XieJzRE$er2Uo+Q9 zXpVWLSfe_B`@|A^Uo{l0ZAc&mBFcp<)Y@#%M20(^1wv?-EjI1RecCLfFhV*%(1xD2 z=}OmF+R^0vW7>_#0rW|mW?~Lrzubi{>$8D9F1HrL=rzkPht3~{wbsYXH1+q1)QWG= zb|qv9&HQ$6Ham8|FCV&Th9m=iH=uSmZE=O4ahIZ04GL$US48pw@8&VsD#!(6EfKxG ze9dmR4COnQrcl^+h&JSTP#W$}BX~{GkJoi8@-ck^_@m>0X^`vn>mYi%q&auGQ9R%zxjIR~tNN{_8#p^pe@mEU>DGZoYUG6g`8EPRqpzLY5f_lh~=0HUCsE?p0C=u8zpu+k0Avj;6734 zYHvNReCgopwy+6-2*@RCx3p~&KE+}N9uQ|DjUYt8aZ;2G6Wa35MJ-vm+X@Nnm`3+U ztx!XEWl8;j{Zo{@jve{C27at0=(RKlAv&qjB>E%ptf6|?77@2M%4o^&^>HVq7e3LI zdrzwm{#b)n8P(K%uKMp9?kmR(-*X!B+CO}Vi&-#(2*{OlYfssi5;ELXMLBe-E9A#}G-N9dXnamoG8bonF? z(z&f0hZKl_ahKRlIG4wTXFSQYfaVecatYaGk<-seKh?SuZoAosWL0pI5RglZgQmAi z*S@0MT~my|dbJ|fUFva2fe1MwGeOtz!S~*TyH}DBkV|N~Oopy~MX~ocCq;eT$f=2! z7^FZ1i~tp-WA{2_+7~a4~daS4@ zZ)bRtkgOJ@MZ4pA1o?{s5imwo6wl+XZ>ge8 zNN$4f`FN8-E-nO8AVT*oIzr43fe1J0f>N@|<_Cckh>-W92W`uvrjdR|U>vI}5Vt^M3Wz{NGP&7VXk# z+C@#RoOesBwLOgv`mLGz?t3kP_=cMEl%u)KsiFhF);ffCY!|B8&(ENhMj_g)*&eNE zRR(R*%AfW}McTbqLj>Y!nkO#~s>;fDZou~*>Oz+}bts-PJcB~CZ>2DL*r=oCd|yWt zSvKWu>Mq5T4%Xp!Bdq8s@*5hIYEA2PYEHWuCZW0G%hQ+Lt!UDgHK@?PjzH|G@5G`ay;0+UZnPK5I07|wIOANSd5!eXmbm7+e#W&T@FdjD)cG^(Jl=to?Q4!nJeDcdyTD{f>l zlHO1+syl}sGQda=Mt~xJwYEPWH_eo8Ny?StM2NWFZW7&Uh*l%ddWco6DeBDA1{`Du z&nIHIqpR#anfg>$wH&_oKfAkgyV~rw8!ML{ULqBWt~*#-U*hRa z_m!MbhfU3(Q{T3vN1Z>b#r=EJ=(Wx?|FeSfSLleT@0#+WzO!)nJO{q|b~nl|=c_R@ zgD6C=zu%tPG|E;h&D9Yx`#t%F366MQksXJWU74L}WZOFi>#PiFHlY*sXgN%+pbip< z&nvum#F2aWaEHfi|Csi4%*P{Y)6T(CtDrnZiF`)*`4o;#_q>x3kPEg}*wxbz-hq$9 z>sq{KP&(v-tyL5~d*g4YLgJ#YGpHZ?^Y!TZ8MTn>!nptFYRRD(o;rCp`{aK{vL9$y z&|(y2d2Bp4`Ou1O%LqWw5+_~HrtiE~`quJaqCvExwAeF>e;@EsyH+QZK?+0^R-Q=h z21gaQyl`81(U|?|{9V!|TF`sEgn(Rft8P~x$`53k;)1se7+k&f`;Vbh&5{fkw^gBV zwG-BUc(~ZBWuj_BbES0AVDay>|gZNF8`*ekEiKMG% z?m5&_H5O+#HkynGd6mj%TuZ=XC#A46ZkaSFbCFt5ZiTcu%l#i<3Y}N!dFLj`sOIp+HofXl>H%K53w&}#bnmxvPb`2sR7o5%dSy3df+w2T} z{#TJSYherFmlUO1SPSlc=p0^twhlMnSc^Uz)E=Ea;z{?pn$v%JdZ4SL+fmp;MLG4l zJ$F2(ITReov(; zt%>&iUTdGcIwvIc`u2)XBeHRAY`)f=$I@dVTy z^`hD1#vse1&kQi8hS9mOcH=($(bY|AZc344S1_8CW6@J5ZFrAUx9CC>1A#Fv%#r>l zFY4gR7nJ6!3BR?F5RePT*NU>#+>;w-7vj#}Oe6&4g3-C6kjP+O82^1=+>0s_0!H^R zzE+gEZO8D+pY8FXuahNRLH)qFDQYI_kLGqUez=pbmo#f30@|@S^LjOkN5wbBwP&xT zkOC3%&Z{pS$>VK0w-kV*o8twyUH+ zV|b+#g?M4H6^0aufHtk~SW>xJS6iGpd#>cKV9({9aBj!J{0tVy${yP!1muDm(a$FO z@`NjvIDOs&Nmmd7wIK37C5Y4E79z*%#32Rd9AsTBcJ0nD-YE86LvLfrM#1hEYD7dC z?=!e*J16|HqMf8Gs2|yOJEX_+Zg;csE35TV&tY%jIxkM*%0~(BGabkKUz0o>M95Y$ za$!ThAjFtAdRR`{dBJ@f+=Yn~_tj<`wP?frkY6!8af1kWrl%-%L!0rt=63vbT!^$E zglL$h627E|EuXNn6+hwe(f}zC0r#K6Gh7Jb5zC)4&-FDJ+@->u>44736b&fS&P=Q! zB7prbRnC`J;Ys&SAxMD;c_+NBX=iTTqJ*x@{lQ>t0CQH;#w5{zq^-r|s9xRH+cAaT zk99zv>$ggA3FLx13z3s?A0o6{9#3AjSwcWAxRX(ofEg-(9aEj0JjSGm48~e=d^P4s z5HBt$Pm+5UN(jg$$Gbi|6L=-B2{^L#T4^5z<6XEH6&ZRpna6p%;X=a(2?4oaY^Nxn z?sef#oi=FEvlS^KgPMkVQxvlULwLrauj<_CI~a`NAeSs7t?fW=J7Fd!PuEGi38+yR zIf)3_r$4_rZ!Y^(c{79K3^SY1dPEIm?qL4#5@sS2mk^K(woudoBqZ^(zcpv=m5mHi zAVS{PUcWq)7nkgzdoM4M5ReP*KgD>|9>%R_J8Q)Sze@@b6MTAQ#M8i;ArYwtVkD$JxR#M-IIjcEpcrqfcv14yFv^7cHbv>sc`U#Dqz=yeGhKzTI*gFv z&RbE;*No%eEDxhAuZAOtfL!n_T~S!ex_I@?=6uJPR{E)>uYMk+XU|~053I5gC)HJ> zao#XTe%{GPLO?G4v_?O}`I(2aAE@E6XDzt*c`yCc@)rdn^s^WJMCK>LrTbglbG>>tXvHDr|AF|of-cp!84)!sXz^%Y z3Gpwwj7yvgmer{KlrbRAg&a`3-~+W=b4Y;*xyCD3sYSXi+=3mi`A7)JrJsN4n*S-o zr-LzxJ@^*q8MP`qqyHZTB4ACKh{CrV#YZcck!}aPB?RQs&+&B4|CEuGu?Roh=182< zTa}&a|BnI@|EX?URvSOebs?1bNC?O!YRX)Nf~AH;}_!J@0M}t=jQs!^-md|u`XQ94`y#uHa~t* zAVRM+)OGi>J~8@-1)rb4h26SaHa~tLAeZi|^fCDh7nP~K&8Vm{I{1OnH8d4t!Un&6nbUZ zRn?(^=f5XEd-|2)-EUpRZH`Y2QXrzmt@~<}sXJY6n<`|~h&X|##t{Cr!aL?0Jx?uZ z)SkMHlfNq?J{Zj^^KLy}+HxoZqAzt%QUk&|QvGa7zbg}isc9%*P`;F1e`BtmvJ0nI zod#3L1<|7RW921O*&6dRHg+6xL3G~pBA@aD!fE1CUB=^^Q_)r5DBe5yK7$m9XpdVM z22bfmH?~U=2`Kvi9WlqRgrY8lTTZj#kn&efPpy4H zFm1OegTgN<%9|P4jI4CyZ|xfJ(QD^xw=Q>}pKA`LjT;=)E|oXXK1(tvL@P>h!Jq8= z7Q`(tDZKE>eeDcuMPHmvl@RbtdS&KicK^LC@1WU92zVw4<>@&~6Tah#BcIh%;gAc; zgC~vRq`F=)>+v$05An#9PA4lZyr=z{)P`;{bpKCn?QPQnYF9UbyN{d3j+HAej{VYy zhHa0KZX&@NSWyG%@DH}}4B|$-fUTro)U@h-=(*mFD4Y}Wy&~7dBJ6Uw8$V>9&mb2> z&wjdAom`_cZQvd$Mlk+j4ld_1h!3dSk3tGWxKv-ErdAqE9Ski5qEc1_>pM4;Z@yB> z;F!ZPkVkOt2P@K{sT-f~aGJq+2j{#zqb^o9A+PJU=6S>JGDv|4*guhP550x$vV-~l zmnS6z;l#fS3Ak@ux}4iQiz`gv^*t`pox`1dms0&>CGC3Z!Dtxyz=++|PqY}w6{kc7^#g4QYC()(V@rHi zWa*udp9U!qF}1miI%Y~LZBtpl+xK)q49c#N%&)%fCwWoG1+^e5YxwVmE4>r=(PmSn zIS3JQ?fJ}mt=N%$34D2aaGyJLu0)s}0J0uit}Uf7k{2Ikl?ir08N zl0gLIf|^#8y=|4U`t}2FMl+~)$R%ghPW+Y13U3ted;7&%x^Dn)60F+PSFQQyBxKUF zJ5rQMRl1NV-t(CE`Q5n1kVz;fX@$0M!fTR zpQpa@pUL1z!4Z^wV!(_|_~ZO&9$`9xLazq7ppA)B{qec@LgyGBdoY|r3PeD8;zpH8 zcQUO0Vs`S_G6e5eLcPKMiFw}7p1ihl;i7he!SAMA^hEPA{Aj6tO$xuHC==-tY}`{5 zS)3#SH5y}E37s{IL;rYrp>j$4RqM&4(36TCg?4)!FHb^h-awBX-3jD^=%E{`prH>U z(fT3H1>$W0B7Nsp=MFX%F_a#%dN{h!@0DgVezykuB%-C!Rzx|`&d~U|D=BK_fCjsV zqFR-m5xi^p*Ui?*?R;x=+tfnH_?qQS$fLSE`1y9^KOq)%I8=+~+_kv8`!Ka=S+)=8qKuwFqTEtqX*>%dqA}LlIGWNaFz!P=_K< z{jCid9c9Jle5goZOZvSXitg`Rr?$w>QRP;(EPlwk-8ClPKR6Ls#n!1)dAjf2O!V6v zS9Jg4-m;3{b&h^wJo1`eW0rrc!x3HE6G(vwpMIM)=e$|SJh{C<98Jq-?k$Z;!Ym{q zAlIlKE@d*R+I0~K`;Wa?o0v7YWJqsvH0qDym-h2ewPBG6azV84aEa5X|HSfSa*GfN z(P8@0vf5*%w3~z$l>^nn@Pd$w*pTc;7FIo?Hs81gB_I_Q$GNFX)~`X1L7kE8eF|gV z;gc4|#LvQktWPsW{>^8h>X)0KjelFANo&_2Bj0qZbh3+s5lg1p5GenE37f&N}tcwwG>=;a7Z=v2`pG2;&={dE= zp%DBsI)*?BM8G>{;&kbcOlqQS-TGxUTHaE%kii6w6uegi?;D9M z&gUDfa9~TdW%(EaxgZ+an4;W%P@CuH#j1`e?Fgj6Ghuk5EUND7UcqT?AJD*SeF*e@ zaNfa@6_NfYbF!jCe>LMl2WbQ$LLQIEai_6ubXT0$xt$~fepj}Vy$%JqTi1A8u2VM& z0lADX*Z8V=YRDfxDYkZt#Dz!h|~5=DcQz64U>_{(Gd{HY&H4|%072uUY! zY~h&8BeH2mIYw@;-0`;mC@d%+{x@q@;w- zZ5t(xIUHwbJ&H2^Q!W+xF*0XUD$}zZdY!hO=@1paWq)s`VH9N^)?&o}o9q8F4j%9kzLPzMi>LFdvmEH3>{iPd)Xhrefc~mnS=}m%`W@0^a_b)<){tC`beXsU~ zmUHnT;=VA072|rYM@Q@V9=TQDw^YL}RS|LGbugqr1ni%ouFvZotkF&@j$_CV=F5E+x{&!9%3ru8hRE>F*N z>J@a2SZP~d;*#Zy;i?ALD;Z(tI*hH4^d+^w2A5ff{w<*!srFpx?N?2@qO4yT!}KwK zJi9{KD+M}2A2m3du;O22Sd#1F`|lAs?0BQ>PS5`kkW0@e>i@6j6oq!nPr%pneMr8C zlXN%ZpY@?guc6<#EJW?|E&}N{6rxw%7dP+Iha}TIpM6NPykQvj5cVAEQ1s)k6DaJ1 zN-nr~Nq4ZI-r$#n_gT>pZ!q|f)uH%RwhwtK za!eNEaG7P?*mOXJ{m@5F@41jAMsRAhKkI)I5la9Vu5Kxi4?W zax6q$REHYUod(FIdm|mK+nacw!O8<)n~q3H$W00<5CP?t-8jT=2l|pd-*PCdje%%A z1Fg%@?@WnZ(HT=it@mN%>WO2j{!)NW(O(OIXc;kP%`+x4kmSVJMHJrJfN1&tM@-`r zTF%L?B-m=E0a74Bw)VKENlf>N2h_K=a%A z5OG2(tp;!ffN1^P`58N76Gq0oERUde;dns3DN6Fguc&jPFG)6wz|cma?aHm1=TM!U z*^J2f8}n*TG+_8f?3a`1(9iR6lr;thB$Vex~-XRcjj; z2bazH19iu0J5GC-{k?YA1x-GEIshlSc$0gl-cd+_ z2zyvM*W40@&WmDmnXlqzWkz0sAMaMV9PfU52=j_H&$h z`9)JTWm70J>laTIqXXL1%(kf1zdyYfze?*kFC5|MXtAn2YgP>#elR@FHi6fEZENTg zl7=h-qG`KbX=>$?0jP>uFM2b_NNspF2A%j2D-fOAy+nJzwI@SXne!~iEQ8P3uE=L$ z2Hlo4(2(F5iLBg`s9Vt*!+>(($fR(nKrHET3OjtMLxzlZ=6GazG||@yt9x;TTrDtVyR?&pd6ju)*}I%qGkQRR)8j`ZiyhgUIwC33pcQQSEXdi?`cyDyoJ zD#f%Fh?0UM*x@&0a=W^lgn(RdcIke`4|Bduu3*B78i)*_~LxaESx$yq$wxd@DBeKCeSVBM<5G`KVC|pP@e<)8L4G!k; zTQDMnvK6IgY#xhFHYU^l#vDd{5HV`gLhTIALD>s}MXN^MZ6Y$96S0!w#$i=q$e+fv zYlmUz%J^3Qsg6E3t17pyQl9Khtjl5D{MxZ5RNMqaUkft+bAu;-;9sH^&X3rg6z7n4 zS8DTm2cp;wLukab?b^Oo1dUvlK`Y;Spq*{vj@o-Ci&mYf+lBRb)0EizyYb3am9&y) zVd&V*3<+_%Yb)(TbQhG_NJqrmjmLG$xe&d+58CVG*Wv22MZt*2WzY&nQ`H&kgOKTH z{d6gBSX30~EVOI$!d(65NKcJSXgv6DM7 zKW@TjlrVMaKz|hSBVO_!aGVt7(u$fSe5f;dWq8Y=m-%XUOPzJ04f-^rCpC1biRh1p z=;?+Cq226b7x1bduH;%ENYNFNwW_h8T=NM0b47^{D29`o=~5>zhTTF1-2b}S5YI}tPU~kt3_T~ zd|{9R5wL|KB3oXFhnE`2s&Z8&Yln6PTPw!n>JEJGQ~*h-X(WvYL_k{*D^8WO811h? z;#PY|+Qsvj8ay%*JzLw2LMnHpa*I*FHrh!#|4koyS4kE-P;4in3p=(67#4dcxO#l2?4oQx>=wPRf5rrot^^G zYuZ|Ty=@Ub(5DZFZHE?a)p@zuO-03amyh&~JC@BlMd)d*^URG$!j#%XB*OveX#x8IqZ+6Yk%3IGCr56s!VV1@a32>3l(%Rm z`iq-U$OX~jYR)2ti$%ccRjl#GSY& zEFu(9vZdyS@tiu{BrBOee2$jaeh~5x zjQGzkwM)C1?A@*q5_w!64>)R2(<1xv!-&298Esoj|f&Q+OOkvay(TWm= z1~8xGmgIizrW{h>KKk{0PtCeTG@jwzGtQTu`abo3R8h6Z&h#P@CbZ66I{~9r9)X4r6a={h~ zEAb1_76f?_|BX#0T|qRIEp9u}JT}+i1@`#88;7F?zbntdb<1jUpP5T>Q`Ay=#gJJ(99 z1Cvb3FG(CyAOgx0IkNfvSqCF;ykUZf;lQ^b7hJnU-lx(uW`4X5$(xTQUjp?5 zTPxl}KJbRF=zkwCzS~#o2b2fLM!bde;Wiuf`*^(dc28+M;JlNyJG|7CXU>kmrwpNz zb|FIc)Z!GGPY5)}!;1nX1muD%gNQ|2)+gJvW%%M4FAn227)QfcOGHZpuHw(#x8Xfo z!a1bC_!`DqA{*7V9Ba0v1>SKuLy8$-oB;KvzXM6AM~^-@(mg{OK?wmeVIsHmPYc@j z=1$znQnnJf=a9$a)w*^ld*wB8Ya~vZgAf7tyJF>RH3%&zuqEH8w~-K#OP+(LvK!)% z6A{FvXE|v{54m7&K)mrgcqO*~_yu3j3zl|XaAyHEUFI3+#*>YBaS`FLA{JIk>X~i* zT=Hklwn>gTNleeh1v!EIM9b#r>ilP_o`>-a^g~~JZc_D1S&>x-w>h@#x`Pkdzrvo0E&NsY zt|)lfB(1-}j_B_?Lw^qQFtCM+65>^vZ0)!OyBuvJ-D810hgw&Ztec;)OV&R)A*qd| zU8qqRq1SM3)%3fTSc)=W&-IfZUFJ_+wNE+0Dor*b*FN}32*?E^4zV|w_lh+NzmHc3 zx6$t|{rVPs%}7QlDOsr6yheP?B-s+7^}z~rMQQzJ3O-iFnp?&bsrFp-DsLT*maiFDyIyk|f)GR-DXy1@ex z(DH?@jQ?f}hQFYJvwG-b{_AcAyo0Bo%IF#GpW_kUAu>@STAJ1{PiJl4`Aafl>$O9rZDwlvSqMZc$~3#X z;*Gm7dhJ3uuV&L39ba8ht2Hk}e+Tr}%{ehn;?(tjBX}^@M#OK5c-Nr4G|%UhgrKGG zu$nw9gBJGcipCZ>8h*ax6?$$Kig2|db?+@S1bM#r>rH?{V0fl^S>GOzkW$TA1R1{7OE)Ry*ANb1e(cZON8q= zv`SI;I(Iv((7ig(bt2L{hjUwA2b03ju%zY{c+o4OuTj5NNQi*ZP!t&G z^HOtu>2MxPHj}+5L_m)!UOlbmL-KB1VtGx!vT{j&Xyv}W+OsLibOCLKY z$Co@V*P4jmQDAlU*^x7}JvzE87bW%Dpu*~3xwf{wGMe;FbHIt|RdK}*!_ngfZ`JIE zI}ETg_j!}asIXxx^<-QpQSY-bES#LQiesIpZ@{pQ9oDydHqJ)hwZ>}7r5LfkbTe@v zEB-L$AJY{M+Yax|$X>KdJ2NsM+mk!Y$dM|^;awS6RW7RA{!oeCYfTyvyRg<7YFdA5(w20|HztACen>SFuznL( z4v81WtF$KjGYiGdUlRf;5HanEE82J=7mYHMM|$nKADNZ4L7a%c#}EOzqE7ju={{4D zyX76R@?>5QCQt9L#>R)wNC?OU?M=Ls`a2>|DpVlHx)fko4+Z7P2*o9cxE(MeZg&+4 zanrpkS{I#*b~{J^r;hB_!Z`AL>~g%{{5XO&6A+Q-9Elp(6rg{O#TdkU`n#e@o#16y zycWuu@(?s9bTaC~XGpalUNa(*xA@g5m#W8wwLf3kktB95N3!M`F-U<`7Erc0j}p~$ z@2=Ix$67e^`c_TQedocb=SMk14>R||5*K@t{pKC$&rU!R}Aruo(!a=~*P z88P%+YtqHxo~W*=B%P8$bnG_|l-Q^WDzet!9elLYjVyaviF`WzhCvEEAA<5k&0SqD za`ja$viS;UkPD*aQ_BQ}kd>lBy86iVEcj7#6gat5?K~ukLN16FJvZx2PRFeiF@q5w zwZkK5BW4U*B#bsP5`U*ksQRqeZV7jjh8;aI#W#~}qGW+n|m-3~o2p82Jz z==schUCGmGOuf443xf#A_3T4W^lb9{eNDRRl{LXNhmgxh7t@FbI~b%uL`BvQnPqxw zmdD!&M9`m!M2rdE(fkkgs@5=MZPr>fx2a8sM`xhrJ=PiO=9<&Ys?jKSc{|mqcL#xp z7~PWGZQTn;r#edgfa|%8Fx}pP=x@p%tM-{e3PiB52=sNtY&GXodm$s`c_Z??+gkkH z+JQp~M96#2B3~==`tRr1eVn*q14a;X!5yo3bKpfNsp-=MpS3BKS_MZFYF$wRXL*y7 zqRD9alm=4Ip{8LRr2k?e64CKt%$I**uph8hLlQco*AtGYk8bEyNd2um$kjS8aI)76 z1}P8$`zNYJZa9;2M%BsQqMMTK!rnqV7BgyaqJH;-(Yretv<&TJD*AF}k=Ep>8I`TX z;?xK-Nz}rfh)iKei?Yx-+_CuJqz4*Y;pBDDHo6~iGs$Ha19}ug3Pi~3;G?gjL~Y4o z&C)iAU7Vkd9>00uyZ-1(Nd}ZHYXs?h9&Mrl{GI=P8pD~Lrj#$nh z1tMT;#ooCng_I=zAu8`TNC?OUbttrZX$Wc1paFBcyF$_~L_kf8H@1$Xk+jb~y|k_AhSXs(w#NC?OU<>~MBjUf(OTVe4VYii}taj3TW zVRiiUxMCYh~%xs@s8f@pD49TH1c-&}@! ztS^!fkPG@4@w>0LN0F5AR=C;p3JkU#j+)$${D-L|LDUEDbx3270>>Y=P@FU@>`8j6 ze`3Frdn6ABeHZMX$OwN9Crcimz!xeXmHGh@@w>aDobU(g*}c}nCoT+YORC*Eg|B`7 z!C;&aW8VRdBF)i~BqJ)X&TTgb5i#C)vFigVW`GD;M%D7c#J%Nx92s>^LO?FqLg5*P zv?o_;mM3XNMG^vX$)4I~WfDp8wGs8ATci~S&U3i>h|2y0$zoaC zys}Ix`IHfg3oPfc=J&cFyWhJYo9HzfogULAYljvNza)M=!YYg$ z4qS|bd;Z08!hDfq&Q$b$^*>TAIFu*u$~eZ6z6+}2Q&{{O6hJ_(C3O)>*g6RPee|Kw z?wF{7q*{nSj`KXoAO#}iRz>CZC;qSFaNg}h5(0AF%?m;COWL8nPxbZV=z=IROuUCI zUNV;ukPFTgv3_{Okg(6w@!hDy3{oHh$`d=t#(jynt*83zT#rp0V$iD@!Dwx!hYI(# zvL%+bb0H!}rk4Fi4%m&tT`IgkDqeNG*owqiOi|ZVav^YM3c29^Q`8Q&uqNpxFQ|)| zfj|mGz`NE$SD{Yit5<+*8n+0_kY*IL3@A^$1l>1-gx~VQ zK7o}Oln%L|mk_7=ZO0O`ktXJyr0@2)I&< zyM2}Gky{6@v*oo#79G5p1ACtB}Y=dgoaZHSmTkowDfKy|Km5ncKpIoTlF(2sac%VKlt9Ac0H5pbNu z`|WcFk^84S*chL^5(09`{YacYNZ3_ZaVKXhgA|B>Iuz#yt|}4L*L3cd`qIfL%)`Jh zi5joW?&RBmk=m84w~`EqfEgVT0gMX-%gUWzhIB9!TufS`uz_?+0@^ zd;vpB+yzfMx#ko)VU;b~+{uwn>N1T!quv5x*(QK{9?wHhD>We3U4v-a@+I2aw6^G3 zvOC?dX0PVjC>Hf>?M_SEm}$E@^b!ci_O9H1{)FPZPTu55u_Nuj?UeSRVXA}}U+782 zjUgI+J6a&bdd?H)2eI=3SBlNokEih$zG;hXnn+QV%UWQ+iH2uivc5^O@4xxLV>{Iic=c^E{4$P!yI!rG9bYPUK{|ZI`zx((-p5R!E`ZtTBrG2KWzrQd- z9`C~F6F)0d`sB3=zohRC419iK1)^6x?HKP)r#$dQi}S4{#JLI`>9W3a3=`blgq3WJ zX~+vV9>@Bv+1MlpDt==|ZI;yyRmiVLn|JSqrg$|)2kx|_Uz&V27>9Qfh|8<&dBeRb zepW?98}Sa*G^V3ZxN#hUXc;lk-XOvp0vG}Dw#EUjGLen?f(~>6(>4I9z z)x$&W>F&UV)N%C-weuZ!dUj7f9ptP3lJd>rEz-oSOP7Q_Gv|Q-R;=0G` z)0~@mbnxJ-#Vu;P(cnkF(dHw*iW5aqOU=88`wY9SBN?PX#Mwo5^xc~Iw75?_A>+D3 z9lo@6OTKC9DQ4ExhPH{GOg%p4Ydg)`)qhW?CEM!I>dU5yR*ClpdD<2q8a{LcgYyo02{>=WyJ`b_@kDJ77PnI{v|VVg z%L|if;h6|E9cw~{2}T)I4VKK`rq zAo{gJ4f?g>3r5vb4DMhN(jg$_k2f2 ze|}_kU;KU5ToukvIBVs3e&%oSJ0{;k)qIZu7$P7Sl&9aE9HZ|G=)w?73@H#HYuA1B z7+y5_8-0{~6+r~#f_`36W<3w#O(w6$!A~Y*=mDTFf#W2y2Hkse{Y`@l6~9Ob$Th{T zHyygkR6EarU*Gxg*zUkssep2N8f z=cb6^nmLx$CLVb6MM6L>dDb3kQ;i=@d&O$+wBS%WoT;$2it>I=3%+(lUEX2-Aq-;! z7&A1y)PSD0nN5Ya5ZZmW19Sbou;QRx47p+oJn6tr;)ST=<&lg?`{v4b_iMoiY>dH> z0uj*LiTC=#efZe*P57%9FA$_a1k_vE`*3_uLKL093j!SGO z*zq5q9ohVRA|W8xy3>xdYQ;$U*fdu3eClR*e(QkB?6R8@NP&p@omf1A^_-dpv5T4*+JpF&hB&Cd#CCIQXnETAe{QGdZ)F$?JmY# z@44we=ji_9<`M#OK^qg1zHLw5i_~Dx$ChG9fe5(E5IKNdU3tRAc-Hq$c>)oT3)+~t zD-+R}KU-WKS32z@#aA$KvJO!EyA0&>APNZi3nvE~bzhuG(AmwFCkEf}3Cin^c?Pu<`u zenoPXgn(Qy8Wb8CD3+#?fOuoh0%1y5PMdJgSa+=3W9kk{E)N{^5bR zZc(z?MFc4j0rxxl8Ds<>>bHQElz%Km0B{9>D}$n(YY@!Gtp5jHJzZOh!r=^-R|Cfe zZMgM*Yuvu6gM@%wa4iuh)yKVf&I^vC;*Uvt1IPvAdGW6E=l)#pwdJ(y82S&mn}Avn zv1r8seDn7zsMD)k5(08TzasKiS%dhseht+Xg{Ls2Km;63k-xew-r~5NMYHA}ln{^$ z`W11)+jl76|Ev#NF)bBCZveTVRVqqqPOA9bf%z=rfrW&CT+mCDog(v;-gSBByxI(U z060_S*k@`S;`&{dO*XxxJOf0)IWM9<_KNk4J%zItoWt-%eE1%2o3;~*`;M7{9yjVO zVjuC_A55jKNQ;6O7*ZhOb-RI@MeHQh{z!yC%L_GfS=*fVO?4D+0%l|QU5Jon+?*H4&wj~5aWzbM^6gR7QKQ;^ zzkCg59br~P)J(Xw;!autPXb`{aHP9bRJxjp&BN3f|U z?=X0N3ell$2B8LboN0x>MhirSs~d57zL}jFXv_mr+)&2Fw)9}XTGDSCcn1fekF(p+ zT8<|KBC>Tw@_6@47WTOw&kwal0bi2o6tAZm{B;EQCH-B_I>fcU8($D~gx#6tjaDB> zrrZ1frp>%#gMzzf(_Hgu8vK%|1ngu>458xQ(x(vCxI!xw`YMkalskrr59_0;77M6( zimh6Ef;A#DXVJZDB1B9*Y)fPPoD;bg8OWg9t>t;s3;4P98&jzBJmRYV~BuUhszB|!z^cL zN1y01b&u8~h|$BU+Ntcx5(08TEeM~uG@ZN`XG9azreH{ch{wy)Q497+vtmrhSWAEQP#M3y}i`sdA*|I8?(bXSsgp`rfU zfCSD1IHTaa5x+Mv!|VT4b)8{Z<-qz=RK$*0)`B329oveCoRgr4y*F$KA}aO<>WaN% zFRNIv7j*54m6ODV4H3&)SbJM_)m7JmSk^md@AKUI=J&iW`8b)GBr}rP&I4F5ledID0-Yjp3Ss475i&6-_t!Chq{c59iI1fhhe~ zWky!uuU6Mk$6bHZ{MGMoea-RjW{8$vUsKR`+0m#5{OPtTYRa*{%|)uNne3P^hR5YJ z;}3Y56|N_Uzbk$=b}aqb?DKY!2&j6Pv?TqVKM%RJNLCGZ=l5dknb{wM#c%IAm~Pd) z&DXwt#f|zs%qubV%(rtQ#EQC2$ooA1w-W#9n3Co9dU2E>qs|_0bLOApMAAh&=hf$> z!E;YMD`zD+YYas7s#?$7A30V$xNYZzk58_~7Z?5_>o;=YC_%=YvR>x-$MM3WMgTGF zPCd^4KV;^mn+zF<3bFjmDb6#6EM`Z9lTP{ak_&%QP48V~C_zTyiC*S_k#z6jf)_D@ zXEWX-z63?q7HbSd;a8{ZYgP?DqX^}muMT4 z+y8Dm~1%HkbWaw*D z)5;xr^nro&=44L3C%KjB;}Iw}U8tq~D%1svEyeZZmr5;`Y0uLcG7uG1vbFhPPJiJV zT8RFS&$YYoRy~ttv6+_`N|1pwOPQb3UAXgb4;=AJQ=gwNiiWFOv(J95YET&nt<#tbFMz?mgYq(0sUU%RR|sU`%}&r5h{8Q8<CdTp8#M&^pC=gfmk$e{7H_ z!5yoeo_3=I%90-20VWg zA62+Rn0A^#29E7;6b&fN!^KS*y||!u#=&z9>KkQvOZxJFf6J-28A{?=22r|RJuTgw z-|}B$R-gZm#1kFv)p0f{EAw>_e@gX_J1!;(l;Al5=Z17Q=KyZ^#>r~!EKq`sNA3~k z?hoBXjkHjj!4*rxxZRs!(BPASC_#^kb3;8jT-(#`)m2Sv^|k>@kfHnC__-B%ZYo7S z@urnP$(g&J=H{;}#etrO3_R)CYi$^(R}mXLo%S!QeJR{*p1IKy0cB0}!RRZg?_gA4 z9(s1V@NRKiV<0NQJ<=o%5?=H3k>8Cf5ykUH=8-RkWHOW>L-(ScYYpUdpG+E6wrUIw zWki~(Wg82pVEg>>xNCnN+iH>Q@o^<{fCL%12Gh%=-UH}P(P3FIXElw1D4ZwCn7r%5 z?H5B&yXRymK?cqZMeg3#sr2761b%n4BAh4sx*vo2uubLFnvI*Z8AJx^0^MGY z=*8pbev*|=&J-v?t;AnTJLHV+eEg2t<}ZbEa-4HqWpMtfLWtgnd(a_H+IwqUy>LH= zyJb3U7ml#!oW1?<7sFE{o@;SDvh#m>^AiD^%=ZJHYYar;uXQ+{Y#GGE+k7$(rk&Op zh{Dq(WhIUc<*t*9ilnvs8A_0Wr%CE6A3lV4KCw+K-I~l$f(+DY%2dx8$-Bo_ls5}c z*BFS>PpN%>8_r*!>MvvO4rM4o2I@4uGFEaV?PQkFd}Nu(Kooi++s=pZ*s2HQw0s*( zO#-%}Ysrt`sywNap*|*rnW&?;)#{)Bk&sY zUhK_d=3CmY+TQ-0~GlcM|ZSwzj8phG_ zT}z#@^QsdcZnj|iTsm?*FORvE%lu_;s@-$Ke7>o`e=)MGorB1W9&OUg%xdSOUJS3K z4h_5+ICuC`F{b(<3*Ufkx-i^u@*XBO2hG9#Bq|TP=Q@**@_1M`WcHt{a zZoF-6^Y0^~4^*Xh(Aryh1BQvqm25_Nj}J2Wbwd?(@vg*LrIw4oS${m9Azqd`X<=rZ zx(L3`sr)ZDS8IB0mpkwyA zC&xO`ac>^8rI}yI6A5DJsY*2GS+PY_^!Fe&d&Vk_fherxvg`W3$qZIqb=~63*AL4t z8oih+TD%T1v5pAY6xpU7#;mZ~s%2^>LkTkUF}BywPu0;y)QNveYhz&56SAp>rNtZR zH`!S^ovf|ZM&U1f&kBiBKPHN)-$Us?f0-+n`u5W`>QZ263`Ak=7j-F^@=k5&ptT-!V?BRl~nTIr>ZS zyjDRclXu7^(%mPRxSnGih1T=2AKAiHiPC*iTaGI|GFrFDVOA?SP<+UarWxFDBNwL^ zR^^OPKaNo@WdGYczd54Y48gqZH*&XMbmqtY$VcxYdvTOt{0jdPy=gHbKW|x}j!K{L zgkb~<8TWGMGl!2$5aU-?rZLiYeP`iqnyA7jB->IVpIK~7qA1bc%|y1&n6ko^hjtBC z_uJ0b#y~c%iBz{V-a&7rbW+}j+OQI}a!?Zvv-kCOe>iE-|G}^0e^{AUJmn0>;@6) z9jKiLbjFmH1^JyO9o4q+u>vKylf|(qyJSsd>!V`T4t7)IdK_VVAGlleNLXc1#?MfP zw~O~bsv3WGJ8xv=+Af@WY@uJ3Qeg`FI(@Wyc`VFA2BPx(zS`K`Y^NAj=q53qhfHSP zKEqZ2FCEz6T#?4x(>ukPtlTD|{#kb1c$BtT$Xcan&O0^_qZf__QTNt$8Us=9RyQ&h zzuP8wDLW^exGt6jEDTdAcW*J2AY=5;n~X+5YsI-`4TxdCtkU{@ITgKt^WgJQ#<cpHybHO3Ys_TPU6G*x)_7wQmmS@XPX%*`;N}t9F}sw&Mb4!xS*8LC4}|7 zMm#Z6D)cs2Qq@_RwG%Z4qWtgHG2Xo`C$g5zB*u$n`;B7piQ+`Bi5w-!aDNheEbme; zQEI^~VyvTFtzY_W8DF-q_J81SA9t>pHPLUDSaEy^G3b_4V8`V-)PoK^GzOvuW>u@- zxZWZWRyT?moln&W82qf7+A=DTC!RVO=u$jU9Jt)ZL{xOz(UfV$678BiVm!~>X;d@Y zDaSBZKB?rPz{Go7L`q{n6WM<~Ka#TO?iP{V+>aP<&j*{A8%L|*<^@f!kiBqwN=oU6 zyF_AfS7Ok8B9m_zp{9yNje)2ymFfq!e!pAn{5LN#E*3d!gch2h5}F(}dv7}xc(CL? z(Za_v5Ji#Ol)#_%iM6kUOsilnS|6?Y&b^{B5QY0-hr{p95wptc`KH-v0>4~wmN6yI>XhZ)(>2{i zopv}H4DmGSHm)48q^ z(;BiS4>ck(L}MTdHO8(BziU<)*;rM(RF0$nKon|>!*TeEgI-G;sWuH+sChW_T{!>t z`#2ZOBiX;GC0mPW3`F7lQ&sVw&rIr{pq5V8eLJF1dno7C!;}3uSjBY8Lwy?7tTh%_ zPPV3p%rJ3o^!d2%QkjJuNVV4Qj?);3s++jqm{qE@I2>%x$J9s8?3&X&;n{CIM+q{} z$53CK(_hVDn;Oca-^TD)gU=a3vaz@nKfy$lKIacRzc8%_GiC2nqjUyn26`g8?bNU^ zi}tFnJWJKrW)N2foJ~5R-SlO*8nmPe>7pE07My>5&Kqv_U>iJpsQOW#7%~ur^H2SK zI{7ks?_RA~Dzw!SS5cfz@;*(gG3vFgUjFvs7_P5~!d08%SEXyRsHtO=!>5|WRUc8h zmK3AuPcxV%YhoUrpK?Ow0sV;w6ESEJ@9N|Yc2eGJ`2?(#D` zGACN4dP|Lgs6jVY8lM^`h^8K+EP9Ks*+(<*SQOoI%akZVhVFe9r+Twd-@=r`>2HmJ zsBiUG8F#~G(XGl?G{)^{2lFddLA6TrQ7A!%exm=eKalOE3J5o2tfuX#yQtHY?YkYo zuAf{d`?4V%SA9h3x?8>62$r&Zk(n}d44;$s&S-b8jb-JTpjj|K5e;@;`*}fmOkfkhrBnMUQ%JH0m{}b+m?AK`Lv+TI) zs(iodyhi62hIhZ^qC{I$+l8TZIUHXK$Fp;zg4D9UKWPj^p`}qgF>?)@@Ue}Wm6XMB z3`F6ckxoVXwllw8168fuOgkGO3N4K~IxOG8ev}(Vd9^Vn?(PwVyJgxZE=*zx<%g;# z+gv2>^bv)&>2S=Nx|0PYM=PUBKaGK?rxpJ)nuH{Z-*4ol)p_~;dG!9rKy~EPT!|87 zpl#CXoW7cQWb{@?%OB7fh&q@5g%L4&p-6sg-zE=iIgM=*z16`6XCz9Hfwt*zG#|T+ zT{#r0Ja;|O7>MdN^o8-&W3u?V=RJ*aCwej~dnQz=7gYZW5@eul+WFdPOvqC7t12pF zAZqN&hejEos}li_8J?;UrJsbusmsEho9)$hx69i392saU_6?pi7QG-`RoOa2V;~Cc#$KZ` zSe5C~>YC%8f#+I8p{>|E{fiV`iB_smqIMES6j~Z}b*ylct!VztERw&k7L!4bit!nT z2rQ51OmA7dOMCsKD#{CTT%Y=?9XtR(m^RjeHIDwzMkya-jdbt=mrZz;p8Z0*aCfhf$qI2;N43-I86 z4O!PWt+lF2WMI6Mb^zy!s547Ec+Ze|+I<78|Hr--6cKLJhb7gl&6aMB;W3S+;d8OB zk;84QmbEIAnAcd7S;Kg!o)y)~zysIenXzKMb2({YCHB4V7>*KT)W6-+TIb~)=!msXcaxhQ15v)q{HQ(TJ-ixobe7vT+sIR&vK5ew0Uc&6E)}>#Nn0LIg`=sS_eyQkwV}ga5 zKg#xbCCM@cBh;wqeOe9@8M{iJvO0#X7queSQN>p1+0)Y1wYQ2hW@!vWVHS|`YDLe< z7fUwFBlDYR9UU;2iWyUiUro2gkwR@flCCI@4kGfy1dniYJYpoJDp3-`~AWHww z?=GDsLl!qP6aI+hsIRE)sAKj`))lhSU-ymqBS&$RAOmw@cBE*IJezBw2t6C4F%X4X zNjG0QuaaGjN1}1R5gaAR(DQ0^x|9AL4rB<*Be zw#of2-fG^jwKN8zzJE@$D*drc%yhRa$vbs8D_@TCQ&eTjQGyK2u{s>Pybj6Y*BYt1 zlbtmNqFAqU)}+ie;-siUV?2mCBHwiHpmxr^%}|1jntms(md`ecb|cCXqfh-SGWWz# zx=*%)p#&M2gQi-}N+~j;eU!RgX1vBg)ZpM$>)XR5QTXzA!_ISFl_$2*o#z-gh7x38 zW}G~=?+F=RWsqujbBKuyL|vP4%ertkNpyUXL}Q$~wnJu`1C)Iy4lVWO`aM=?#&)sO z5pL*K8$b7uZ2!j~_4v&@ff8isV{8byL3f?|*%gf%15x-39S--foT}%*P~|i>zm}s% z6n+JVqi@;EGAJos#%*lFQTtGL^-T5NdnuCM9*{%+>ZWxgL56N0DG$!bQG+JQ`t!my z2BOfqC?9q4l??4s+l=`mLhC4pR*T)U?A74BydIZeQe;i*Gl2~BE40)1c`JFr+-z^_ zFpYsI>;gu00PSzdmPO04bu+04D0CM?M%11x>*j{iM*VC%^E3Rtle#^}WSwFGiDOrE-Gr0jpasY);9%29%h$mzqaC3zCWfqizLqFsAu$`zFwsQwE) zGzOw@U7*Vp_m_a^k=C_#q4d);*_T$W#OQ2Itw9WSimh(g~*k%^KWB;9qE zIYtiSC_x79KIna%ho{Bz{RP;$6>-}615XzEUX(gg2s=|2m}3G*2{NW76|u^{=x8lI zVrQ!Ds+wgfB?1c!oyaktjVL@bP^RJVXc51+xA;6(XCMmmk<=$O@vQJ{_)gI3%u#|2 zJY`U4BM)DZ&?G<>pEpipAWF}9Ift(hB|@gkDqCYYN|1qHnr^Z_PZmi9i>VQ1T64^8 z;+&(7IUM&o^ju?>z4Q&+fJ2PTZm(39Z_gq)FUPNj_^w#q%vmj zXP7fbHrhO8s_&i`E_=qQP7ku|8;AdwCr37VBJyxyZ^iW|iNG}601rPg)1EGkWVU+^`yMIl~zR|15tW~={CP~R-|ht+x~Y2j^|7~rQ&JQ z?q;=}`8>SNB34w_A}q+j*a=l~_>LF%Qywr%ifhpiteV641NCCft}1=3-^`_N$8oe& zv~xUP(VMKhyyWa%2aIn2#Aysfp*=brC7TtI6pd23Qaw28D{8y0yLRnh$e}*UG58uo zeMOY6yU#p}%WAVmt0Uz?G;K!|YNf+5;Aj(>fB#rz-(W`VLlmy3-gaEp!>maTkWWK8yj8hugb@I+zEt zkCg{&3`AjEi=t{>ugU{)S6S^2UK#^Y`mQha&Os~AHA1;xd@s=^Q1dZ&OOc}SA1%61 zrfMy}qcISLwn_df$3ts;$?>Y`$ZTys&`V(Uofw(UqEpq0>i&p)8Us=2m8dR!pR!i2 z{KbA%SJM(iVI2tdNST#k6|5Si4y?bcX(IYWtUI7SMV(Gqxz{&VRnj~)ZAU%UDzfgD#BTtDXm*j%n=JwR4}&13C=q9Pik1xMNuF z4qZFP^o<_Wt4623y&eDm{qJcZglwE2vE{YT;{>ZnnzJ)X>!NxXu4P;@9P?_bA@Sdb zpO*~1wufqdW#=oiKVC8*)S&QVmin$K{@OBvLJ1^Hk4I|$H*RL?G(y$JR_B(3uB($a z_(=rRny@oeD=~StnoIP3Wy4d?#cBu3_){q9Gp&}k1>G@f5mHI}T%ZWfB^sBi$X9Nw zKw8?!HXtn%k-@8&-Ks6*)yN1sa%_&egt};YS!VQ|dUu?=v0RyOEBBFQriHUn_Wtyu zovl`^zNL|P5@jTef6GL2#g!~|vWK>Cb_9hINI=^NZFp3aH#%;{D#Z9x*ji{0mV{8~ zK5v%%wz?AhIf5RTw?M7_GsIZ;Rb7s&kyG4^wTkmwr>-7Z$M`ow6>7$@TVWT-_J$D@ zwiea|mV{7j(+yho?e@f~byvv-B%nQna>|upV;sAXOG|3glvEEj@k6-Ldg}|1Gu%o= z8*3=r$mtl*4!ms3ny>SdY{0t1k`S8UyU{S=)r*XmOPf$wu18UW!8x<3*1Yg#gMW`g z%J?h6c`d*8b`UO9vJ3Ig?n>1Kmde6rxst=x+bVuhjj%q$WuoW9aEymMCy(MIDAa=X zWMXBiht_^%Plg)GEr+#&G(xae&<3pGs|-J-LcRPET-L&Zpc2fGvN3`}Ngp;x*}pf` z*jiW;Lc^^R$>rrSr1EV)3bmTLomNKM`y0nYCVDMjM-rW5*qL{JRLoaJtO;Yekbos2 zG>RsZl1=0AiANC>YB{=8!kHJ$jI>x~I4CM7Z=I*lm`GkMIzWyOjHFPqc(gh0uQ(WM z1xrH6GcAW4Of1GWo%WM#z#2k(2zkfuAkQlj4--eQ< z#mq@H>#h`P!5WH{h4mSqyZf}Beu*qDNO8cdaN503C|)vep_+2)k^#~(5&NtXz2a4X zSSf!vI8qx@@%IQdMrR~xzM|7cL zcmAUV30PZ%v?Gs51GfvB*PsZAfLf1tMd4=ET{HEk1VW3#y0SI1PP1Vtk@_srcTVFt z!&NKq4Bub5(STX@#$EKz-9~uLoCsqt!g8TKgf_i?NbXj@kB>S=QoKJBPk8>=ps!Te zTG&2>c9(2Nl7_Fwm(9CL?SKUA1%y&3pCOTZ`>~kna__=XljqfEUYmG%*szctT`816 z;!&sz?$INEwgj?BqZY!~xU%4KEEe0kAK>q=u8&kvioKhRLFMOW{C6JgpH&Uy6v8vi~LU;f|bqs<0 z+vw`7>&z4a38)4A2ZYiphVo*SMz9MF_h_%rg=&@Cu26p$8W#YyAdOJBkO1!X{sfCH z-&q@I>7!M(d7!$KUmF0Q?XV<-4%3=^miY>HaN}A6C6Ivj5Xy3K=L2W_V7H2u)}R)& z*JPQUc72C`o z744{hdke!c9=vzUR00X81$QEZq8E&1QNL^RBHK3;D1n6RWi(0%W{rFr@vFrbXlX6g z%vH;ywRz=R1wbuGBV=nfUhC96h#w!afhL%o0G~3DMyS&X2ipI_6;|x`G6E%#kZo){5kOBAohH1#eFSPj zd+=$8(7o6&I+6}%GpbMxN+7X$Oe9V_;i|gVZy;LkJ;Fdk2Yl7SimxV+fLib=iqQBK z;dE(iinhPpCJp_L!HqYz&zSu+F#u{oT6h^>BWS|9E%^BTIoj2nNL*{4tCG-tY5;uh z!ji-Z(J6?&=x3&cI&C0O0tsjjA;&HXU3Z|SI2)`dPz&0FPilnT*@e(b-zJlG2i9p& z0tx>lirXlvG9+q{=&SQP-01Ea+sM22D+rW8p9+?Q(5*i1bjN_Fq(bw3TG4J!I6KE2 z>njHmuq1@=0ZVEUjp)h4s|nPCwCq_9?qfkO?6aX>L$_*B0*T9K3SsL3Rj^6b)}kE; zUfw40hMF|huu02GKcn0n8;HY7_YHtvu}t*u{D9D>wzTovl>|y40c|7nJ2-=sToz2N zM-L9svv1ZSH>|7sH$InX$l)$qSED53TmJ>7mzci&Ui=HRCN9=Sk2AA7o z83>6oZQKnL;&T7pxIXa4RxRkt<|h>>fdsUT5PdO8b1;NbtJaew8`nlLBC6JI$!oFqV+1^tj)VIZL4Qd@*pR8tgt&gYO>k%LmrOR-( z#-%EauDX&`-0)QW(zBLP3!d&};*0rK)^o5z?bl{#kbqjy9zs=@e`j+~Inbpf?HqQklq}AINDfPZH8)6@d~+K-&mS8}myUnR=X^Zso!I);psf zj^7-x%-czQGjqCUMt7~q6V|!&t6tkO8+<*X_NeKk z9!=e%p0sXj)LOV@s^LJ(lX*me`KMWQp$F{LQx6U$kce+_R2|#qex_~@p{u7(XvvqJ zvF~j>IJ6FFSX(jMXWV0h`!8j?SIX^xglt2^eaOp44>gZqcd6w)yw57;F=H~$`Z=kA z1=Ey>R{m7un)K`#z_Jn^G-hxb< zS($GA=FVYR&z7YayxN~ImJ4euY;@a4qQdNHku7qqATer4kg}o0-n?41o-&a%P~VW3 zG4*%}%hSrKcz?Whx_{c%PdgM7Lb2vIaUXnMA=LTYG~pqar>9?6<4^(#s{)ghHHHTG z^@8|x5&c;95?6g-ceGJ#(A3=9d0p=?=k4kdd1Z8DnTlB4hMhkL%>SGBbZ^<8LUs27J?XJZFuj&y5k zv>_9U)|Azm;7Rq_UMs*?U3w~9e;Vw6?%Yr9^CQei$a{N*A)zezVi~FxBOGdJ59X^E z97F#fgnj9e>{dZrT5NA^4$FeX`eHj(OGCu zUe!2zgwJ4onsqpwP41;o{;FXy&AdWIV@)@L9{3DvS7xUvV!H`}3M;9U@&6edfqS z@8@AWz20p+IIT2?5=g+O9YW9g+3;)YS13tE>+nT=nrbs%`5N>!xO96{&1v$$484Xj z;c?ZKZ+g8}jhg4pp#%~??nG%pO%`S9B_ZTB)Pi3g_Dt(Nx*jk2E<*E)E28S<4tm>I z8;n9!y&ZCd<@lls+`q0ZOAf*uN+1z(w}Dnv8?EZA3nBXxq5QnV8J6w(nZXE4<7t7K z{k)^<(IKDHVC+PkSUy+hL1Qkl`ID?U)N0$Uh88mIrLkO@=(*6AyOzpfC5u(zPy&gi zEgZG<-$k_CmS;7p%E!7C-)=% zDx@7Q;jHPcg|QQaB7^U-hh@U~!k$MMlypftthtl3%W+s1Bw!>2pKn_AF0@7&5LwswH;jrPB>IXNl5NF!_;9H8axGI*Um7%hw#&r(I@?JL8$X^DWy_%i z5^C!lrT$Exyjsn;{fSIEU5oesRDeTC1O8LFaLQGyT&!F=jJ6=u;c#i1G|+|582pYw z2_#@tM4Yxmu8|{O_Oap5>T%zN6>$HGCA4Yxp6@@|vkERWxuBR=C-%ui1q(#)H0I2v zw}C?~u|9BC;!ES2mx+F-s?!JFFIni!q8v&fv43e0$r%yd5t2Ydq~xa{~^Ud7Z&{Nu91u@mrp3cs{IgI*e-| z6y)EA-Uv=6t}PETDA`;s48JchRuPfHbU8BdY(J&%&iy90uAgI267sVK?z8r#GNM+k#8s2J9tiTbLA(FBBwSRW!D72lEl7lJs{ zT3z(F(&s=`<5N^723@^KTu0l{&1EZcD1ij@)WlL+){ESWZAokXzQ>>Rd8$f8*#oHNP4uS-ZMcgDCkbu6Ocn&rlr=g$k#F$5M=;;;N_D^QM zX9;VF&|1^yT0(#={jg8rPyz|)4I)&jdqbw)tw+CGTT2Agg1()|_Ek?~SD*V+oBdXj z*9ZMM=ywUP&tSqUg*b?HSX%PPpcf|lS85@n??cBpx^Soky)&8k_0@zs|GYwM7nS1B zZ-d^MOpMJS{N7_T>Q-(qgAzzUPYt23hbnVN+ZJTt40jIwHt3x}FAAalQ=9NrUv}c| zCKep}RHchXY3k5RhX3g;o${^AzaE_{ZYY$Myd_9Lzf0u2zBb{Dt1r^x=2}Vw^r@gv zBr+!RUAS|V^V+Zxz8q>nUrQ#Us}tUzL7xhGQQ}yxx@jd-D>B_(eO zdPvY;LFmls#`w@g8@~2t5QpVL?@YEqN7f^2dOPrs_q;hQ7y4SVji`F(i2s+m{N3cw z3`(FM1U(#tszg5`*WO-YVKu1a$v}@|;!{iP_pO}nE$>69l<b0~oX^n*m?&KJ`nliuO*cBMF!h#eK{=UROig+38NJHjyy-5pA*HZ$Q+0tx6j zAtWMp^n2iJvZAdyhmzFuK{%_#W<@_oK`%;VWmZ2W%Z{`s?Ta?%Q0uN+Adc&O)OgyK ziF0-i6#d*u^qm??AOXEIaWivnSvt1SE3$TAF%Bi0mpJ0=9z}$A7Pe3J;jXoLN~V3g zN;<_U9BM&-P9|p6FsC9%Pa8Ze$Dsrg&{IRm_2?dPld2>Q$G#l;ZQI-)D;>vs8ofT* zhuhj~3%S_0B%KjiTZ+R$0!H)@3bson-rmvF_sum1%Yt4X^ajOvlo^H_t!zurwa;PD z^MZaG%8xP4f_35 z4YsIHEs20yFglEobq{+QvST5$p5@P>1QOydh;nJ~5E0we|2ux)iXQ%Qg|(SgOCq3_ z9CaS%`Gy4i`o(@;^5;+jiNw+Eloi=qMC_z+ZQ(OiJV~-{T604qZ;60fFxHPym&r+F z;8zFU`C@>S1%Sl4v7HTbmYvRP$EaRF09$eUA3Zz(qc z37F*&X9Lg0TJ``Bem=xs%6~v&L7StQP3vdn)#~lJcC4LNmFxFEU|CSBPtzzhaoLVM zV(zIFHguU2M}55{0&2ndK0^L=bC_jpG2U~DABPf1SlKO9%YK=fXJfL#lu!HinN=BF zOCq2a%+QE9_2W|f_?^Sd`L-X25=h)t)6};%-g!3Mr&i`~)-Ga2KGl*4s3m7*>YR4v z?=KrzhZX)DN+5CO^l7!@4JUnlhJNAwH2#$FD$qOL8yBm!!| ze2aJ*B+q9f;~nX|@qQdiAkn?R^~{E^j^^2L?^d53Xj_B6X;n)ipcc&5h?DTJ6m3oK zn)GOnpOnXegkf{}!1snTc{Zwbe4)Jc_oX@SYe@vuf;k;=KHp$Ly3co`vse0aD1pS* z(l$zqeq207^?4OtHIYRAaHSJkc}oP;l5<6AQ`5-yeWmD$r2!mDAYt7+SxH(oGp`-r zPrW8POw4HGSG6PpYRMU_e=b^3@0TZu-VP{%#JuB730rNGXT$4(BmL*wdh+0nmqb7< zIj=UUv>QD|@!2QVU|ziuf;2*n$KD~&GH&6tpr#zwm9GdPubr=W|@~;0$A}L|z2z*^^uoe=h}c{4keICbLgk&Ip|#C z@RV3Byxo0b>J`o5697JO)~?Hqc;*sO^9E{F6WWqnv%7PsCCWACwskF$iC6V}{r^rt zE!oC)6u?Z6o+H7XqB(rNie6Cly9Ro>(6)$|{H0cq5IthdrT_1>f?BXm@;ZmT2zxjG z4nnRC%d8B%A?7Ao`7!#>?F3x{3E1lh4Q~9_Ffh0aab4M6BA}M&E92dUTpQ65Ic(ki zmzr(^`i5?|8)(5>Myt9OT+Im0Zub9P=aA5Iw|ed+*T&y=2B-yh32|1Vk?f8CQB7|L ztkt$z@ah>Xz3$NV-)jX4 z*O9fgfA(GcKWYWFV4K977N*r%)b$EXUmvhmpXXH2Mmdzw^je90oAz~LLF3wK}hG#-cR<*0fdSg%!q z!~dvh#68c(-w3D$$41^6;BG16e8yWyx(&EX$OM!?LZ^Q1&wVrP?*!D!&zR}|_ICnm z$@|qFzc1Ro5_O2)S8#6^o|BsIISGHocq1v-#@`621^0Q;*CsVs%0Jd*cvg2Vp0Ao7 zt<%dAPiIZftLlHlv!P5t2_*FVSHAy%Q16n->_B2Fxw}|@a{hZ7g<7zE2>q=ckP!Zg zs^@O?8vdPtTCm^5eTLfy*u$i@q}`nu4$sTNThj7Gzr+xPdDLqa^G)coh}-wCJ%`%Qe;p#DF2hg%TS&x7z;E5^fk zH%jkO(N{|T_~#P6ef}o_wcvC2?>5A9P|1HO!kfhTKBw^8aK0}JGXnaX7XK1Z0tw*(;(z_b;H@W!$XK$VF)-xt+2V4O)Npac@)bdUdy z0d$|=nlxXX+q;l}TCjb8?_Egfx3~10r@1xyTVFvf*l!5k8MKJ(8n%{+o8BDuyPhA; z_i^Ez&Yg*F_L0X znXOW0A8^2Q+B#L-rc;J82jR_x-l#}kn0{bWF56KkfyDZSi`3Tb*5(nXEGIGX1salk z$(BMbXwSR%81-WLB%^JFZq|Fi#4S_Rv{^;*eTE5vGhf^>mX%8D2L8IRUx~_ez?0Uv z8GJik$Rn1fZdIfDG+@J5SENu2(yKln%P3Ouj?zQZ+p&bLC07z`$nukR5&^ZkJ$1-j ze(kWa7Z7@~Z5^pvqZJGJS%FS$F-m#9V7YSehyzxik5xRECK}6)oUu^p+G$;0tup61 zu^{&ttz`#$3bpo)Tdy?SHB)J;I$)V-6Y9>Y6uw9Fc0esii{4e9jvJBJyVceM{v&QrEFl(Ff#ae1qvmF>)lqa zPtVTKX;_kYE56ZwY-sS2JKcc{#Z@*2rQ28tDza9hO;IF-bzR_{yReDk}olf$L6@-CVL7ckSMpXy5VE#vw4J7 zZIui!QHo4@XHTIPv{$RYTc&6F1vPifFGmwrp=d2_=s|m0F!6y}wr5(#$u$))I<{L4 zEBz+@!MX}~dbdnfoUsi0-v~`=-oLme#EtP~!OtxuVFXoW+ zt9Fu&;X971(ZeD$ol<3c2&o5~v(-H+kuSw7&}NoN>b4Sz#ui!*PEotQUZv{ev3%S} zb$!BeRbP){Ppn*z*p*gTW~NO1({80&ZAYT2&nrla`-ye>Gl#gj>e@RMsaR`@SZhWb zBYvkS;(z1c%Qmi4PX3&k*Sl+6CXs%DH}SIu6)Dt$v_1>tN!vUKKZ{4UGl_VexjOqW?`CBXQQ40>;0^&4JLmG`0ODtz4su97@WVMdIrZ3aJZY zuNh!T2yI8zXtm?_wZXS!8~^OBiXT<^t@?ytGpy)P9q(WAG0(=0Po7kaH#tllIIIaQ zS0>`)iqkDK%}HVd2mWMJ3EVfSJl5+DwfwDqDoN#BHT~bk2s)GzZ-upCy^mJpuqIFo z()#_xPh{5ehUC~>2fkp)bEOxlVYC75L0X)Iy)Kga_eO{}cw_=<~2I~uK=N$Qjy%gm?B1k`H&B1Ex@YMe*hsMv#ij2ujI zCOL2@X*vcg$L=*Y)&$xXw_eK5QobA-PrA(%?RaLR_PN`{SXSNkodb`wX=)@OEqtd9 ztCYTPC$Mvy9rzo&lY!L(n;Hp7%S8C3Os!bG38d#e2kzO?K^-u)iLqR01JdFyXIoR! zA!)Y88rD zrFN@a*H~MTiEDh2MHL*(PCRnp?FTxhF!41y%o8J2tE4vij~X?WIwma?SS@V8!xIk@L{V7Q5RR_PoliED)hc_JwqGN zw)g_gPfu>8EW*Ms;bTfS)K0GJujn;_v`idWSDR0G>MSBT75P$=5G|?uB4cYIEfYTi zgSh8{k=mtuvJFU&xYtCRm1<=yNq=&N@U;aL{JF3LhmwT_MZWG%6@$KiKzrg0q1h=f zM~-1*zE`K>iEp^lte2wi;q^@)q&F-+PH|6jz~bLC#lPq6)W5zak(>*iS--Qc6lw`d zb(s;R=sUGc2pg)fLGo<;DNE1+!iJh>{8HpwX7j6>)DB3r2=Gxpy$mq6Pux$ukYau5)(5@J>7nKrtZ%PLKQ?_%U6C(Vxr|FujPO0E?TaLmK&c@a;;8Td?lVD zp7CV5t6r-=Er)#tZHu?);tJB{wbv8-wZ`%ILqILLR>w2GFwbJGaQG&pjX%8zYX$pI z|Kdq&8gXF`o-yD7u{%3bwI|&(r(z$eN= zuV4+uJ8`?3(%2&lm@@DtfdtgrxwefO{J>l}@WNZzIC7;L{ki21+t#Z%g%U`>eiM0v zo8{?lFFU^b=u-j-sO4VVN?o1MOer0vw?o|3CaLX1_|Hq%2$VoV?+wu_irym#727q8 z*qVj#TYF6@lt2Qm0uh-wSr2bG9LI-7+$NBKT6)ilUQu#;w~b=~@!hrtJR+zxg%U`} z^U7)WO18X3IDfzUHh~1xdUdg|;?SV2(yNNzj+h6J*egqSj*FU6D1n5$K7v}=^2+IU zJpSEN0tu+4_pIp0yxv`0wK~VEF0kpnY$%jK0=a=-Ou&8>uBrB?=F5oY&8oCC6Ev^=Fcu6vKFt!Qy|uX zwl_OVAOW@Xo)x{K=C(t7aEW!^97Okyzp2mNKN3iY`DV~pbne`J`6!-^`bg*#M{9lV z{*gce?!h95U1x$izE&%G?d=DB?*1X5mY8pu`ijn-yQ907AYYb;(T`P1=yUgv1QKxP z6L(TmR*{Xq;q*q(6MgRfA)r?KorTrME!wI(t@SZ~8hV#(?^~TZw6~;C0ttCf{Fq*z z_B&OcHn{zgKmuy%J*)2lxxJg1QGj|38Mw-Z@t&n9$Xy~RX4b@aLW zhk#mecSR_D_I$GR!5b#NcSm7dM1LDBzr&ztEH~fdq`O2@kn`b7qwl z$gRKplnAJG*JF0zmcDoMYW23$OJ-mCCVR2SlR^n3GCai_kpoY@l@Nfi->0}D>A8$6y=13zBa_{ z&uh8MLlfaIY!o*RYe+H67fshF#h)xOYC+qgcbiNV-+DFUvs(s9wSok+Cn6IoP59Q! zJIT%^UizN+C;plCXpPdU=0xKvg7H%E=KZR&-1kdeWy+2^Qmr5X?TORG^1^g`-#|91 zZZL%{TxuAheEBue*bcd`er&R$zDbYps_!+WzJdgd+=}V^xpcd>A@m=RZV_2ush3Q8WEcF#6U@wSM(Qj+s^88Hg z#-y4QMuEe+-c|m2F)2`gM!{IGcr&bT25anhg89YQlcLU$xN+o!GV&i!L+%bYKWT){0c1GI!5_%h%c5xb`1VRdh)tbgdP${2b@wGY^afWCsMD~;>C+Kj~S(? zzKg=LpcWiigkBxn%S@v0k}-SgN@EU*4@Yk+A-#5F=;JS*oEyye;SLH}<}DLY3y!~d z3xb<*$8X2g1MBKh7`wl>proO6`)jIItUrF!@@in`sp)F24XZcrS#Pghtdp;|L_jT= z9T4w%X?eT|NaXFic{ap1`?ai_p`0FmEfG*le?E%6J&)-A6OpKS&fM~d zyOf)NS}^M%_N(GqWLfMTR`YiqDgOZp@g&L=&nQ**oW!pcSd^jSOSEjtR&SXAT5>ky z;*EmT$|{ODqfiPZuw3y(%@EJpymoZCxR`7zjcBEini2uEU?xTXPSGUn`kd14;qM8Q zKtk^~;Th!FNT{8vwb>I+4^Mm|5l~BiJ_^4ik9aU@97{>Hpr=}4DUSoS;EX}YxyoBM zB(gJxSgxd6|&#kPih-tIe1ZI>V(IQ}vF%zCU+b#Mx<`o_lR!$UsArVlk zzhRH6zk8WW3{P?7kv&_n!|~NAv;nnXo(iGL>T|Z}RyH#kjHL_~Bf=^Ec{_EG z8b-lbR9%wP5}Wp`MYI$gXH}-sxB!3MG(udh426`L&lJw;dwpLq^ie?8a9j z5m4*iqDQJ5tCY7>m!V~8u|B`F_ZK}R0&2;bI6lgPo<7l*1eLBMW#S-Fxx*c`O-!-O z+%>DzIUt6f2Mqz6ehAOUNL(1rRF$-xfpv`qP8()s+_ z^4FOIKMXUr1D^B|S~+D0_M^q9=3$Vc29QYTUNo(--xPIzL%rn|5jAnA(;nhIUKfdw zwe&ZT$EvzFExcE|dfL~~<>`;{^{Bq%wNAdlG~}DTMCf$B7L1CB z?=!SDWy@dMQqKqOJ>=<`6dUddfi<1{-hsFgX7Ef$f#K8%w85@M|w#|EJV zyQbr$AtBu4kd;K}<>qUN6$Rq$KXFBDIjRh=y0V(SK7iz3Vp-(mw9Wxj6dbJY3{?hP z!oTZ1WwT2LN(9t`{U&}X-Y|^1RnJJ9YD1N+8i;?Lu{Rbz#RC zBeS0GuB>x6p$Umz5&^a3dos;eFJ{~`hy45$N}&W2;-s(Yk-XfeL0IvE{Mp8mE*T^^yAg_YDAE?L_jTg_eVqrcRwfMi&V(ar};=6%+3kNjIG!p-0s8 z*_b;MQ^&nyDIKn|RXw~U0&2mL72jA{k630OGp>JAA4(trM^ku97vE_1V`i~O=Q~m; zfdt%F#P>_KmLQYQd6FVq+R!fJ?y2KzbWm!y@W+Dq6ETO8bn*Ki$Hw9v&9c-p=Xy~1 z^n&}Yu>B{8fY1~>Up8UpL-k{?E);6PEPzZnl%2{dn?#ebE*&Y<+H-1urdReSB_rG) z4<0a4t$O{klH0r8)9bMt6@F-OE^!h8wO}qp_e%z8VS}rR??ASbS`J$aY4NT5;Kx{e zT~&*2+?qlOBxD=7XmjlKAW^I0){Da38Ab=?=ZD3-P58)^SQ7lX9fk2dNWhZBJEPXk zlxu5tkd^VV^l{urC1*rorCg9dh7mznlDH$h&WY`RKMK1ZjiE4N3JF+}hz`2W)%5pF zyi=M{@e47^`s@s)dUJmaW4f>;5qtIOM8X62D_$&CioG`Y(pLGs`?2zTxF42VJ}qP> zNo@2=OAG2K5l{>E0zx&@(#f^)9Y|tMIECfHSTC%t_|-RYPIE04z-F&(A+-Y%uuZ}* ziL@c*T(WW4uvj|a+c&lC%F4#`D?AUv^QZ2MUcfESH(_fU#7G3xf~R8f9hNs;S>pZ! z+WRi8Bm!!|wJF|rHlNR)?iq`>?vA1G+z%rYviExUJZ4)jCTVMWL{Yf5;fWrWBx3r> zwUjgCKH-NOTS^4fl5OD2^Ye}{rzd`&(|V)t6ch zTMPFXk=5^4j!ic?glD+QyALE_FNk-B$|Y;V4u+HVkJ?MmDA;mXLveF?Uq^D`S_rAI zqAi6INXYFNxa$e_e!LBrE6_sP+u?pL?}=*~tYx>ZZ&#k|>_nY!eEpLdfsuch5fF#I zw5Wi_>!)JWu!}@ME%93;io^1ZO#MkMPQuYiWcIKWH906wdPYHC1ZHSNHskOl;&#+W z?c1_7g%U`>?1{*EiCd9c?ZIkV#mi?c%|OsUpPsugS#%w{3l7kxEwg1Mn$sb_uPL4%Cae5IZ47%swqf(@E55T}FcZJ| zOV_ubp$x_sjM*MYL*G~2tcmTeWsBc}EN9w`LJ1^f8{BFt`CMZd(`UQrQG@XGRDJ$H zd+?kfzAX|KNA%yqY7^RqLJ1_G*Dt<|_so-R^0gqB)M&{D%rw9}g?Jmik+ZsgYB~1g zN)w5IT4EoS%mJGH@c(0A$Dk~ert2@Huq`rb$u-8Q<&NPDT zeYHxRG_DPW)?uw+Zp!$p(^y2-G($#=?!)~#Z9^@62mdz{_aLjBR(0?=?d$V6$p$1~ zNeGorU5p1-J*xIp|6>D`3+IBkIq>K_Ug9y4)j8KpYB{V4>^E`$YHc9feW*Nf-q)7G z*h0yL%hdaA4y)@s_+zZ4K;mlJE>NXfc8Yoi;mPz9rI*!j(3ne85n1f{gP)x9w_2g3ft||N+Mtl zAuVpoCVDdAW08YN-6>qp@XR5fSmK=DXy4zqWC>RNr1Kz*^~oMU&3X-);Z6j*yR5(T zyod3jn;L}b_gI?L1x90?0 zY<6quIS8Li@OdRN4U;CQPp^z7p10zq{R;L1>^JeI#g=8*YSegg{82l}1AuE#Zb!Ll zb?A*sI4foQnm85=gw*jI?rQ;yZW8^gG*j%|9^_`eEr;70Cvy38WD!!Dh4eLu&GZZZ`B# znMau+*1yyVRei+w*8hFJ!ZwNfqRMLKF{2=VnxjxCfdsTCh$$}QE+gFht0isRyP6X1 z{6W=kzQgCM_7V$Q*o=9 z0B}n8T|CK;OKCy&7sYh$u z%vGm1EH4pI3$9>slOx=lE-w?UwVdcmp#&1JP2yeT1%;@;{WjwLOri5?UseVM%~kZB z0iGIR4Fyrik4`3Y$>l>OB?4-}9uZ&bxmSV?U2H0Tlhu+go48Sle|A{;R!_D8ZHq4t zH@imOJCvej;wwpU23RXtl8E(n-L0igs7Y_lu13$aOvyYr^SAL$9e9q`$3pM<+!b{v zt(JDiwi5j?r%wL*FiQSQ=zW(Pbsjz{8hi8%rFNDTB|>%Nv$RkP)m+X#15UyhA#G@RhJi|F3}TI zpOv?jtL1#8h&k*L5$iMcVKr}+p=yM`)K@UdE%!oV@&i^m`~=A=P=~gsN7VW;8UnnA3x7BG>eyQT=aXU zE}-r5a@%8eRu;cua-6JfREk0gtQD-S{syQcuOEI^OTOwS`MWR986>PM+KO!jAudXef3{j3^;O{DMK50 z;hxo}WqvG^u9#6TEPnOf;Gely#B82^A5IhA)MeGyKT^ZG*Tx^#bjb9(cUu{>)Dy4X zeLC}6!>1B0&b7(Isn4h|=C-~wZhY7i`?jB**=*@=iGU@Etfiq9_3s+O`kq=sprm5otyPF)Sq=nIiKclaaqRS3g<5b7WWuw5 ze>%8ed9tW~5Q799O-Lg&Xm%^{n@iSAzbg#e0b34xUHq~`z(6WueOlvFdo@TvEoe`V zWelW!MQ;0GQh+qCAOYu?cq^sQFxq;X6{*_tp43;+9&Dd@Z@WW(D&D!nYx-##lt4nR z)wMQ7#BYW-r@y{BAl@QS3rqC?hWy#S>dTRc!BHQ<}WBz^-HU@2mG* zVnfe|G@!{99hq0%FG})TQ(WEdpmM*}D~`6D7zQFl4$V`uXiwAQ^1a{nHxxYbTh$^_We|@RQ#k2fAK>J zyZlM%l46D-jS#L`i_SaiK__>LlL&RlGsV@l5Z-jt6hm6vly$PArkHVgY zwD>Mgb|jtBr5J6Pkc45aU`=5A^bD36wKa>OLH^S>pq5;#7XzzMjRnxJC7($xhXgE1|K5@f zE#Ow4PPUz-!CFBrxgD=+1<;l8Rp^l~WukTCWYRU5|yKe;V zlWd`_ew(AH>VJr{oou+T5>CH9$GA+PZ)$B*GknSIk+SvnJ@v>!b9|K{ z{QY!}YUpi&6PN1Wb5BSr$!9EVLR-gYYLI|h^yoWvjiCtMGX0n!ULFYGe(^41)wU;V zV+v}u=`W?jtuM-^MuoNJRi7xk7n|VPk3Xtsr~gvA4>A+pQu{^j+`6t0eb%o&ff86N zSdut9r&QslPZX+Xr6e1WfVCA7`a-t6>*o-vN6=w?VLM>Ii5PNh2(NV6o|+u0L}1-v zP2f0*tmTN>9L;y9HLHHdP$Cha*AbfBp7NacPE`L*Y)HVm!;wYk;5rxXv)YI5uJKxf z5=g-I>AxP~$%_|sqv9QOX_i1Ox#i)3L;3IE5!$@>Em&IN+S+}^F5qV-Q#|T=X-)yQ znI31hDqXz1w3e%PXEr{nk9pSIzI;rml^Xtjn?#7Gnx;RI#rG8@T6~XecP!uDa2D?A zc7?fC^VAX=S2i5V*{bM7Y0J`qhk9&LplyUcR%yb;FVWx$txPzSKmytmzqDZ(!3`N} z@qsLF#x1DMMF^J9wG-);IB%*)+U#&~;apBC>n z_}zW4z>>t*DF-&^>6Lb4akG)wxq50fzd9HK>K4XzM%UIx4OX_zqNUu zllHF-@!RBF|0Of={d2=RD=*C!ZO)84@>$uw*H6>qJ}WBU`p*cut{l#P&p408JMsj! z7S<59Pk$S51V80FKsze(!m#d;fVL4DHgqV@*y})cx*-O87xt(;9^88<-&8sh2Y==o zB%l^-lkk?TM)0c3Z)n+l?`Tj033=`|7(A4}aPcDXaW^q+IkX4cgix7nLwS5$8$8rw zl{C(ffVPD%x@829zI8(L9&tk=pqAWMzGW)&?`<%j^v;77vMr#+O+i}0%Up3!dalmh zZmPL`-=_4)xvqwKSZJe9=xfmbyC;7V>dC9MiI9jbl!~-U!OMB+SM(D;~y8)B4@o)>u=ZB2WnWB z>))D~Hmj?lR?C}e!=U0~BtI*SwtiO6JT=qkv77&C`HO0lA66>yfj=;THG%eI8;=wh z9&Bge?Ux1;SQAJ<+Xx+wZ^-puof0=$8EiRht=w0G7u4ojQx~37?yLq0s0G_3;w2C5 zc#D7#Zr=HW1|^V?$2@gIV_vMMC13pD4Tdd;_F$XDE*kE~E8nZaJ9kRMPyz{PTV#H$ z9Qd>3x_pDh2Z?}Ma$o7caTwRnnLlk%gAJL6@XN9VjB|JRR#O}@;ko+t(>6uSTm1U$ zb#?n0eeO=FBi?_!=P5=pN+Pzdf1xClHPt3=+NwZW+qyG? zLHKJ@0j+$wuS!6+DYguHu2#Z@@ae^`6n$<*@6hM2PgVrIxwj0D3|npx^A_vUgu#}>*2;agDb9sXnO55vGl2xuf^9yAo-? z#@OY3$@4&o##~!Ao$X%vlRzzK59US0Y`+%9y@sA)HzsW-3pd_Y%dQ)*Zc^j(c36wx0b;NLWUeqJC*<1Zfp54(b=2JV07xLp| z(>H5%WP>kizccn2W-w%8*|Svkj?@vqaafo_2_&FxggS3_WbLZ;}DYW~NaSSG~UBc@Lp za~zdIpac>ylOm#Ykxq2XEI(c*-iuUeb6oMPw^p?{YLB57q=mOs-i_Y6UXqJniy=@8 z(sGXF=2b6xB=iQe6W`?MxblTkWOXkyq_84kG8lfUV-KjRTfVj8B2-Jc!%)N-%(u?*qr{h|D z-0T)Kff7i_852Xlv&6cG2aOE2lCn#X*z>r)!i&CDcCOX;cKtLYZluta*@daO zPYXkMLy^BbVvk`?M<(n>jwR6%0aSdYl0pe2OJ9VqS?cZhIn{|B`5r<)ip)%#-!+WUp|WM|Fr;N-P@fs% z7d;zOl>S+=0ckmp<72gtiIXOl9yOI}B-=$k|eqM+R4-$9kJeHXto$etunYp4y6~(sW?V{Ea_n>VAN+5C6|F;^ZZ7`JHr+*2$ z!qa%3y>J*=>bXZEpq89ndgI%b>)(OYzfb`skbu4fLdyN#yukb|c-8b3l9vGq*)J*i z;0A7yRFt*r=S*L@2Wl6O%@G;UH08=YSFOpIA@stdr)2}N-ivzAik`sYtLBR7ruoX1nYnEe-vh|r zMJ}V;N}P*5g_0HpHz_BwYT#9k(iB*dh|rhGW_~tv$;b|}4ZSx-uNwOY+ROU_&8|4{ zi{=ir-4Z99wQ`=Z-}RP?790OA(!vcNX}eLG9H#eGu^DHGmDL>5f084G5=i(Y`Qyh! z^>0YMQt7WtzEJKx<|veC6u75wb7{=K#|1=1oSY<3pUpHztdoK%@Y2_$9>@Wi*~ z4^SR<(QRb)b7Gw=uaTTjj`UQRE3P+xhP%JaRb zg~u+@5vOcO>YKYRx63OG@%yEV9LbPJyEpKaZSmt z@{B;qe~H)goc(j-i7(8Yh)?aYEPZxmIy!KL(qmO+?Ps?%MIUd`+nRB84PT;&m8RwP zRc8M}v`NR=nur!jgjkP%wDj+IwLIc!q=hGQ`?U5X)sI+?l5L1JsECzn)PnX98WUQ8 z?}%QknF%idYE|qzKxx$6Q`5&;CakmPlG^{QXTCO0w8YJ^s(3$M)7P_emm%tfQ?AC$Cp8SwrhvUmx=}duFgl|2T->+jiFHt|sbioPA2s_(lpVSE1zsStHtE9vP-p#%~U|6fX zL=Y6EDxl(HJ>8`D=2vxTcXy|oFs z{-S)Yjenno2#nUt{6}#=v9HV&V$Px%k2Vqi#=rly@#AZs+1M}lM7dK(yv={qe_9x` zRuPHk>xe>;C-tMdzMB82+#Z_G`d@_nNA3Gz(N_Ob@U=YG9YUYpwDiykt;o#1ZLVu?$bPRq>=712*0 zC_6|*sJpxDm-Z~}q2TPeEgNxnhvxY0m_EIVJHfq^x>q~cE`+UW-8l7edRd0MAH7XJ zGQ;t&)bg?JMBT9r>ybqh-&y1t)#a7_hl_K(cB}7IEnfw9f)tPNYt2& zCv_IT7W%*+bWB&GIEcoPwOA6)_T|#w6)9mwlvoCirW%NSe|`7uJAvMbE+`$2>{ z=EDchq-`#|Vp zomXlnwV@}h>?~qKrtyrg0SqOGXtK-SsJL*jJhR`l zk=S{GtdlvsZFc6r_$)T;Y$BAs0V0mK@GsaYN=y>dQ1^9Mte*PM;2BPsD)pQJS%LjCY}!7Nag7i>{;A-{ag9sq_wpO zi7sRL$ zIf5%redVJ&PBw1_QV^(xyGeP2eZWdyz4>?j!6eF1f`|!Y{?eb0@+Nf-m^S)t-*4@d znaQ{Bsih!L3-_NgiZfsrv5{VddD=8e5YcA+FZzRMKl1x#)5eMDYcz884zllaMFoLc zxMP*?$~%*Wh8&|OGQt^35bD@1_Hgq=Yeb+H#s*}p@54fR+B492pRcA8H9*9g7fZ}Y4$0hMephclexeoUlr?tv zmsJp`g)s*iL%!qAwtJ7DS1MO#C_%)Ur5m-!nZe}HQPalfr*`apz8$oIt&@rXEgVgG z57wPC@-~m+tYW7eiZ)P7jefZ9iefipz1pAWE$omrg6tl!MBCLWLBnW-`Q4hk$RFQs zd~7f){NatUEXzSbpw^<~s^q}haX(ia+wU24&f)j6Qm6_;2_n?UM4M6%X~LV`yw09b z1%X;6^ZAo(ZHT;C(0o@*et9WRTs+N7?C@nMK?FuZ`mOt&HLFZdD9KQ(!#30{#c!%1Q8fPk~dU% z*5{kXT%j}Xhbaiu!U&SA)lZl}lWM2a^#M@|0<|jd_9d^ruF-zXyL!{!@?@ACI{#G- zh7v@SsvJr_2d&rWdGqb|=|7Pk@Ns10Zv--wAOgP_Ia8M_!v$LI-Qup`}1!2x; z|7uk)QIX7kFjU?qX!avy$POBsaGd^r)l)&B7DmEk&+~PlVh*zOO#JA3tieRfrQf@nFn%W5i{RS%5q z{WXSKXb;C zL^PNfLgI(LvYHuSx&Judjuq^B+&pcHq88RlsEF;}J=rgH7ih09omE4NA6fa*$QbbSWNz&B-)Er>jQdLd)#3rnHgBS_V*Cb*5=5vrw$|*yPFJaI zxD7r@QGy6;t;Mq7qE%K2u+9kd4q2Flmz#}xZQ6*(nJ6gz#)Ultd6|HGc@JTZBbNB#l*K0Gq z<=%*)7CskOJ9!6BnPTk4$}#jzcr9hcL9~iU&lkW#DivlAN_{2{FVAU{T%5?Lfvc6; z6|8BISs5P2%nEFIGAR{xorq`PIc;wtTct`wt^aU}sKjCly{1Y1&rnwCoL0Yu6Y+Rd zRH?K<+wx1i{xuvivQ(rG?@NN)Vw|L9`rFfOUBi#KxxIR}iR$wK?)+?wzmcZ7)Ao!PcN?1GVrS zN~Y6B!cOFIWZhraSKclnunI=*YvoSfJZbtwp8Lw%?fvw$c91yyPd(1?MrCCc zpa&x>vnY-fBGguuYF>)fTTqqt>iLIa18Ze)Y@~<0*oU1g;?K6#TdmkY1bzz^%aE

FwKuy{3)~ef89+Y1+dsUS!7?dvfU1YVGgwKIGeYlY4%8^?K@8`3WsNjWOIoAOfEx zvjFl;r_eR|1n&Y$RC4k32Nc) zUY^!-aR#3`G@r>!WvGQ{v@NqskJ7D{TVdiCp9*Z~=h@ops}V-Z%LEOxWai#O?iGG! zmrj(Q!G&WfQMpAG1%X;Wcb4)#S<~x#mRUf|KX;Z72n+dl&zUPh1ZK=+^_hJdUt9Jx zk4~$mAW*ACogvy^w*JOHDW;8f={kQFKg)RdM*u?!A}~WI`3%o8b^Xv{qr&033Iet6 zznZ9>?orM-aKp4Q+O@rwcw}3R@bxViN)R!u(IU-^vfVsxBEFE7#I@WM`t@x!h7v?z zHq-QdE>R;jm2`8is~}KoVZcUha#w%jN2I9oayNGU_c}D+;mQmph*0yK8(WoPotiA- zQ6C)?1ZpkpzCxQfyt)zld8O<}<-me0c)q=u@+=QS2_o=|kzPivnY6xtO|iA6jTs~R zFXM{e7(U6YiVvl!d3{7=c#x7Ay?=SC-k@HD(duG?mil_2KEN7i{Md7vUed#kDSTO$ zr-DE&%#zCg`SFEhW2++Ep#@8&78OU>6FD_d6Fe^i0X6OI^4 z5E0g6qkigW;Lrcyo0^`YvD+w~yr6`FK&{>*SL(CcSNqwjqCSPh+uAuit93yIfm)c4 zmKC7Qzmx7~JVZwC5GC)7BZxU~S$%f25x>WSM2GsN7;52j(Vm_4(WH@_H}sP-DhGwmHkT>0L7Hpqhlgozpcv(zgCm;gH-(1zAL>)^J9`VJZAW#cg3-V0Bz*oE)^Jo5DPg84i zCqwcswFbS5Dm9U51)Pk}0q3ow!#$;|-330ZAl}+8)ilPJ&Sk)@4whDWSyQyU*i}k)zEsJjf zpCotN)I)?Gt<0iIu22xDrP}B;ERP5c31`czULZIgI0kCXs64sVtS@1kJ8V!#5NeU} zjmWcJMu&=OpYpQoV$TUa3wy32QV##a%~N7OhxstfzMTv6GDcaZYuOeDf*CW(x-U{w zOldWRUdVA^C_w~G@iF=auhAA)GyPrDBby`Y8CyS6hB-k*pl#C^wTMO&5~!W5vBgZK z7F5aD(qOQ5?T;b^pCoVXnf0DGo4J>!4+>UnAOh{lN{fa~#m>hz^yI-^^m5k_w;p`}1Ng z#kH_tYO^8IK=zKwfccmEquP*X2#dt=dk@qXV<}1yQEYyQ(Z&7s&$y4}R*W#2diMrT zwW0(OD&Hr4P$zL{lMne)EmP?Sw!PK!U}I(1EBl#;8TT3fy`OLhtU|)Z@1-a~glX^p z**lTd`^$mHbqaEbXl>1S~yM?OQ6>v@q4dX#+tIzl@UaQ zS^+vKevo)KE8QRmBNYT{;rN?(thW_Q7dXxiE$p9M&*MVHp-Cl$ z@BM`odx$+(tA4-BT7cG*DvAETEu$#G3Sf_}Agrw9=yg3SW`#ca5S1 z5%@-A#bGfIv94mc@b5ZZc~^+Qw=U-r=K|uw^biqwJcD2lvFG?L$oTHovSQfG(!zi1 zeWf4RLVP3A(~q6Q%@h6-HaRfd*HmvZO+VAg%UJi1J=wf!joxOOkI}KdxemIIOyL`2 zGWd#98pGWdBJfET%eT*Kc}&yK{L^ni4EKOnP7l)OcCKWUs#=8LlVs0V@8M&&ec;CO z0L2C((4LIFP8&w+7bqY$t&WuW+L4-!`xxWj*%6FVU^KyEX;ya-9Y60qKM`GzOsh0TtPZd$!_9ok)sRxL5}(eIHG-Y>bfJ=Kp-=o$@UH&>Q|N|7Fv&{7-_2 zr;pES@83BZ{Db*FpV6=eyY1s5!k#yzSmTN<%!zg)j;+q=Ng3w<{QmOS^aiOYx{cdU zQGy7yA6<^TrLVhbqU7Bz1SQyWtjL!C+TSc}*v^8Y>DCPt5vYazlQVTCH}c0`hp5wP5PlvHi=Hct}GMPtbSOnY=bV}Oir z8AC3yk(<>>zYOf4RJb9+&Qij7cC?39u#-6+b*>!dFT7Nglm8gj5RkQf!jXH0BvmHY%gGbJ$b{?oK?hU=q}#K zX&_r@AE#Z|Q_4tpaV7XKLbUYA@`useb=S%}CkL=n>+Wg)bj{X}Myd#WlEu>aZ4iE0|Z+&*KVgu(76_KoSYV&(9KKDg?r4|4YI1|Z}3g;!# zoHFMPkJkekYAx&NO=fg=&~Np1Avll8f35c(D(_x4p41=6<{b1Srv`kn>chnqE-q5wbTlQ(#7oA_~<~|Pp{2Tf(W%j zTCzTAz~yChf8Bu$=O~apUYld2f zZ{@4unC44%&2u5hl($%R4qv2w|N5FfKiEb=pq6UGCTy-TDc~Dz-?tUR=O#ai)7_0y zsO^)o`{$wEWk8uPmm#6kOgB$Z%ha zd)e*tYZ$*=`eLmy>Z|nOZe0!)B(54 zgvYv@bXV9ZI(l`a;c};k<{6!!AzDS0%rg0%-0%as)|V)Xg|dOzVV#hBi6 z*8tiAA2)hm@4=QVIxU&lWsCy{va|uS z?`W|lN*O+5Z)z)E=V%x&m1i_|9?7$h*I~W>$;&Xhj9Q46mBo|0a1q){Ry$o)BB^&X zy$mDfxwhcODh+L0EO{1J5&<)JQqxn89`RgnaMg?C`*oGJE5hEGR@R>MES8{2kMlpy zzPw$fOBP@FHIsIjSC*j!5!gcc?aoZ(fja|Pk9RH%C5XTlS}Xw<+Y5Py5Z&c)SBZsV zB|)1K_x1EX9%Oy$Gx?R2^KK#BM-HPsK0Z(osD=H@ykJV7((m%X;t$@ccyas)?5+@L)!MX+%@9w-RZLRN>&RQEkZ-_P}8 zzdiaykue@~Txj1$hmh7a5;SCdOAnx?4e^*5$fnIIuJB8cr;ja^C(yjlmKCN|<>~cr zC`u5a+OTVJo339{fTb;QXV@xax?l_C`B#5dqZj)(XU|7uQPe^DTSK zd{-uiZ1ni%YNNGa);-CKbZEIs>)Pj@#vMJ#9nWkH znOySLX_xwv2{@4^5C5Prwh*B*gw|#x)2Yt>%v#=!bvW!rs{Ha?D?KuIE+OBUJux{9 z$g-08s0UfpcX%eP@YIu`M9vKVA=FlV-|5ey9g^wp&9Z6)_;858{#h(8SI5)*E9%O# z?!PD;FJw@~PAyFm7vI(F4!xFd_f?0%@>cfdYq8h2HKWcGI<|BE3uo_ zQ**9;TSK&Yeqs&g9)E#)oP0=;fr$uwl6m?bWAe;?p0oW0?HN*+(9>_NCdcFR8bbEG z&9N4&^HxK4tDLE)5jLz$D!*d;LE*h30{Ox+>U{e<9lN7DudfF)w1Lmv+@zk|&&o5> zbNN>}QUA~mnQM&onE?zXh?pK)mwdE&m-;r%^nEVO3Swr=XVJBS3?+y_KCHa+-lIB` z=c?2BoAWZ1AUoD`MGbQ8=9kp^%}md-^TBZD_ri{KJ9%E=)}q$-QITZ0r$z7XX?m6| zmonzI_qD9;yQUye3tKA@wAozf4~Qd@QVW>a=~ z_-H;k<{CxoIY9x$tB9jxpUK9$DIxz%qvap-lO;U-pk>AMV)D%`gy5$ly zM5~CTD?8|lNtd~>4^X&+h*lB9r`hY%XZeWQ$*u}t6gi@kZM$omW=9(4KTV#!vuCQ- zAjne;N-ND!f(Xo>m~;Dmy19B$;oA3w(huZAs%*o#X&346yfx(ci4Q0~YsH)1THwNJ zhK%!RXxrrV3ED=hBH}^|DST1Ps~}o(Ak&}mIhCu4+w&h&hl{=S8|SJS1$w>GFjs_G zC%La}{Fwh1!sO}o=jfeQJ@hvVBMozPMzo4Z?3T&j``U|^4RR2q~j{T3g^VtHTSnI+JGoz(8dKue(f3EvCU8SiAGNP35uwLQ67II-I zK?K^CcW2u5Dx-gRc(FkbC_jA-5Qu99)D5L(8_ znsHy>aqF>$_GIR#%Qa(d{qEv!h06*8pNnY85kAyXWLK}lSFxKExdtnG1sGo5yY&uh zA8N=ukj%{Qv7*uG;qu!$Mo|mV((5y{K#{u!%Lsj_lORuS@YUT*D0~KFW~vC!EmcMM zDLX#8>NC?9{f~#}wlvc4%kHM9)=JQj6)3Ne?%^Rmi9LqN#zig$BJfGlTk;GP+2dYt z%dK}5IUY;;SdAV1d+J;EXK45&>4lF97f1eh%VzRnu2Hlc|R*kd#`E zT9N%uvL^ihBi@n`|H7Y+o$*Z&$-#|%`UJN6qgT`&szn60+my5_2 zLWEV`n4aH8#1{QdIu&ffI-hYdT2xr26|*`MjEky~)R~Q2^VyFNa%R_qwJx(x*Q&S} z<-a-+%(tjHmdzb{QjduSzgMV-k}(lWlC*?0XXDN(C!)UH>#ugn{a_ybUCKb^?cy6% z^9E)e*~;vVdf_tt6$EPSJ5!M~Z`5($^R?#N4Tx$_BVX>O6%O}QV){4+I5v`BvWZD% z!d^OTXD^0t6yLNu9$S;H^ZmVV8D5^<*{RzVjDkDM=oel)D%m%TUz;4rLv)7-;0M>M zUn2Gcze<^dto?xQ816#zJ?O}kukTX{Qme>HtzWkD|9pvNW&hh*&b0f>zDibR4j?cW zVzKNB+d?D0b)?zrdNb6*T!@P39K4a-<1eY*koL;gj^DBRc2BO{%VQt4q}N{bRI&j0 zRjOZNMW@eP-bhQ%_l#xuz2X~H5uYA2al!K}ZJGL9;XvBt)G<6Byie77uF~rMPK+5h zb5iH%Z{=L#--(FZ-w)8`_8%2qAM)%}#F4*z#o`9N_@D_sN~QrL|8g&C>@OX>e^x7# zU$XA5y@-|7HCG-4CO5Olt?1+|o&U=fw^+rqfX>zvO#X7z&38VytSzT z+5OF>`kJoG<#_aI9K|-qA0^#hmQrE>idI}bGQU*Yy_Txx2+p`umnGjxwf@=7gIPd= zh>XAnq(NYDYqKGy4V$#atlxvPy0^EJfU@>*5U*_9wCkRK&hA$9QOLGH+kD zxxzI-KT%zy{_LF1)1p7}*}nxVTmwWPV^6X_9~shZEH8~ddO!?8uQia3oZTL107} z(elI-|GBi)_yCde*q7n_icvL;U&@_u=cT-~U0Lx__hZPk#;BUQel+gXm2V$ZMD)5+ zPuZ&>T1Bj1634w}g^S?%Wf(@F5TUMWCMP^uw-?Ea%Q1{0p%$)*a?FLFSm0Khudd~% ztj<`Ep~g$1O8blRNh^5$W!}m@3S$n4{&Cx;CPCT{w&cUBo@ z0#JugbjmyQZNJN9f{zlnu1I0bQjiLk*L;uK3tvoWy=oWujBBUmt?%7f} zp4voFa;2b?KJH5mqt2>-lz6hV@n93r7Zl5UmnG5E*Dq5y<%uFO$1ZEgviKD4q=?i`|&m>M!VZ+5Zn79 zk)i|<0ksQStIqouv3cBD5?`nvJ60!^q686dQXI9O{RpX5;ElBL>!Gt`S6WXI*6xh* zc5w{wy~zaWt;d4E?a0b|^1z zExh%OVoUHVQN7pc*AI{m3!8}43Jwfgf@l>{eA@{l_SY7ocS;cjf&R7HkM+Y6`HB-% zbl>=fq686`b&!#}YMK1Ear$;q z&|r4Cz&{ivh(NCB?&Q{J~d!;iHeaE!Yx+(j|tidkJ; z+vWfKp8{@cMW-4 zb64K(>K4TVz*Qf!4w9v}JxG|fGLg=!m8=YAdsM%qs85>AUX>Ru_i>66L}1>?JT*I? z2x(M6?0E1|L7*1K9OTVF1xpI)xAVsO$@ND$M8RakqPzxA#ZEuGD|K0Q6Wk!1HDOgPV_sri>BW%BN{v|ulT#@@VYN@#*W>K5G#XSJzXNAOf>a z@_g#`Uh*98z5GixZ-)PE%p0ly^JjPcm^{Hla$kd${Ri#`a4#a)^GZ={$Khq<@TU9> zC5S+_keMY5XMcZl<>n0)C_w}=c`TMWzgwBS1)T2CS1Jh9LVl5qmtlC5S-2pBd|0LANHCXZatOR(9LC!&c|rz$}ZF ze>-v@|a@$_Q2%|0=2N}Lgpq?8wrnYFZDKw z&I~g#Jt7(yDGOb#gFEJC0SuW1*!Lp~;D3&apn>HKX6LIQWK946wc_d-G7C`cM;2i5 z946#hMf#MJK4wh+KM5kry{&KD=-eeWy{DN4$mka&()Dh7NLGk~KrPJa$O_PLM7Yh{ zphd4OZ894F%OW8{&HR{AT2^H+^_P{Pv}`kSVq6|gR-Rh%pQ>gWlDzA(&aEeDTR(17 zxSWW<|GdT0`cy48u5SiC_9ef8Oj1OkZF%zW`8q7E;xhVYw-p=_s1-dllC*5SIk&a) z1e)KQvucT)T0b4uQG!_@e3HoutI2*Dm?ZZgEBMMTmB`*@?{lApxgva$y!oB9VR4~L z=!(Q7#RekKo|(;P%|cRpNl&JlfpZ2T(6;18eX7cy6+BEMQ;t~?fm$lpxq+}_5#@@o zvUIJ&Lq;u}$7J2MtsV19u}I!_2!FiUo(!5)ikM@LoNcrxc}rz%*M3`na8tCy6Jo@K?x#MCi%hV_PKQ# zm-R^;5vYazlcyniIJ0tt3b3q*`V=LIz&^>d+aC6#lZM5yg>75v$l%95p>5gouF16G z=|~nBwVWdYwI13fYY{TZY`%4Q>gl!RbjZaxX89-W03uLJt!XH5dO96eCYp8lww9v= z5iQ0M?fCshKW$Y1w1zg_9>cEGv`Iw-YGFNvc{-qv2hF%KNl)l(ljtx0a%ZJMsud;8S-*^itad%0ix zrp!NUyoLzWQggzCFOJ~DqT-nU_`Rvt>euy}wqd!?!c|R0?9=zBk*^`0b)A8K7OaVucev$zmB?!&aQ5w({PLWQtn2zG4gIp0k(1 zqiA(j?urM&XCYce*fww$S*HrH_)!fN8`whmwf|RFCP&cQQ5=krr`J!J%pW(eY{<1O zcTU7=Fht9frdH<>9irXjey|Qj2_jS*`TXmNrInV@1sCHvvIWrIIOm4Osr5rN^Bu}O zj!TT(Nvxv&H%DlQKrNMPFl=T9uPo0zi#)PTsjtIUp*@Qw{Edsa_vkUbd|KWj3Dtn8 zh5JuAm-K2Qxzw%cd;e)VN)UmqmAmbNwM24(SelkOm!kiHeu>(Ttf~#g?sF~3s>DDY zdy8ll;W4qXsQ#%IS$kt5M^6UPi}SWHyzly2f6P9EU&V@xd#37L;{PFtKrQrxWNsp; zsVF(jl}E~%0iTO#Y@zgIcE*V#j;E|E#(pCBEVO|>ip&oVZ7R%jAWMyy!cl^VQTLk| zvlAWlAN}amq^{UFW;oy7BS}La2es54{e>%aMcD_F^m>iAQAD5?#sg%n<=HrKEYE#C z>H1xQ&qXx0R%ROhtR*g3?(p$-91UbHq78hKd2480$q8S~YkXVD5rJCq`Dz=J`Yid` z^L>#mM6-Sec#dtVjtJC3_Jz6gY9p?vwc{5S@6+?o3o+^qdyxAqWSb&KLq?-U)fOcy zuI69QE$4_pEwm@k7OC4-Y@Rrm+g)3$qXZHE)2bb%OinoWX*#WA;qW zyThl_L?GmD8 z#o<7E7FjG*Mmhs1N)Vyi2)JB?%`R*&%=3y+3+-V&mi!OCwq?$nii#z-Q1&u_hG}sHN83B{y!&R>jxW%XaOj7cbb1+|07k7sp<=V$>09 z{!A8YZI;@g5ieU)MhKxs5fK=_l)RDYnq8`i)~f+6Iw96KZqRLNxMIWgSa+3)W%4F}+u^ ztw0GPFm_^AL9}JN-{xqE)vX*6sD*4(Svi>+$KDT`tep;jLr@E&Ln?yABpJTEO%f1Us-1060C5XU1u8b6& zKB+gV(TkO)Q3h(EJ!BL}=D_(w#*5>zY|_Ck9CyE{g=m>Y4w%G0JG5cDzfRRr3(>ek ZHs_KI-ZZK?Tljf_lA}j0%mP|0{|Dc9uGRnm literal 0 HcmV?d00001 diff --git a/tests/test_jacobian.py b/tests/test_jacobian.py index 0ea304f..b1e3f69 100644 --- a/tests/test_jacobian.py +++ b/tests/test_jacobian.py @@ -70,7 +70,7 @@ def test_jacobian_at_different_loc_than_ee(): def test_jacobian_y_joint_axis(): chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "simple_y_arm.urdf")).read(), "eef") - th = torch.tensor([0]) + th = torch.tensor([0.]) J = chain.jacobian(th) J_c3 = torch.tensor([[[0.], [0.], [-0.3], [0.], [1.], [0.]]]) assert torch.allclose(J, J_c3, atol=1e-7) @@ -119,19 +119,23 @@ def test_gradient(): def test_jacobian_prismatic(): chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "prismatic_robot.urdf")).read(), "link4") th = torch.zeros(3) - m = chain.forward_kinematics(th).get_matrix() + tg = chain.forward_kinematics(th) + m = tg.get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0, 0, 1.])) th = torch.tensor([0, 0.1, 0]) - m = chain.forward_kinematics(th).get_matrix() + tg = chain.forward_kinematics(th) + m = tg.get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0, -0.1, 1.])) th = torch.tensor([0.1, 0.1, 0]) - m = chain.forward_kinematics(th).get_matrix() + tg = chain.forward_kinematics(th) + m = tg.get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0, -0.1, 1.1])) th = torch.tensor([0.1, 0.1, 0.1]) - m = chain.forward_kinematics(th).get_matrix() + tg = chain.forward_kinematics(th) + m = tg.get_matrix() pos = m[0, :3, 3] assert torch.allclose(pos, torch.tensor([0.1, -0.1, 1.1])) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 9ef8a68..655c8ce 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -1,6 +1,7 @@ -import math import os +import math +import numpy as np import torch import pytorch_kinematics as pk @@ -8,18 +9,19 @@ TEST_DIR = os.path.dirname(__file__) -def quat_pos_from_mat(mat): - """ - Splits 4x4 matrices into position and quternion. Any number of batch dimensions is supported. +def mat_to_rr_tf3d(frame_transform): + import rerun as rr + frame_transform = torch.squeeze(frame_transform).cpu().numpy() + pos = frame_transform[:3, 3] + rot = frame_transform[:3, :3] + rr_tf3d = rr.Transform3D(translation=pos, mat3x3=rot) + return rr_tf3d - Args: - mat: [..., 4, 4] - Returns: - - """ - pos = mat[..., :3, 3] - rot = pk.matrix_to_quaternion(mat[..., :3, :3]) +def quat_pos_from_transform3d(tg): + m = tg.get_matrix() + pos = m[:, :3, 3] + rot = pk.matrix_to_quaternion(m[:, :3, :3]) return pos, rot @@ -35,13 +37,13 @@ def test_fk_mjcf(): print(chain) print(chain.get_joint_parameter_names()) th = {'hip_1': 1.0, 'ankle_1': 1} - ret = chain.forward_kinematics(th).get_matrix() - m = ret['aux_1'] - pos, rot = quat_pos_from_mat(m) + ret = chain.forward_kinematics(th) + tg = ret['aux_1'] + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.87758256, 0., 0., 0.47942554], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.2, 0.2, 0.75], dtype=torch.float64)) - m = ret['front_left_foot'] - pos, rot = quat_pos_from_mat(m) + tg = ret['front_left_foot'] + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) print(ret) @@ -50,19 +52,11 @@ def test_fk_mjcf(): def test_fk_serial_mjcf(): chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_left_foot') chain = chain.to(dtype=torch.float64) - mat = chain.forward_kinematics([1.0, 1.0]).get_matrix() - pos, rot = quat_pos_from_mat(mat) + tg = chain.forward_kinematics([1.0, 1.0]) + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) - chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'front_right_foot') - chain = chain.to(dtype=torch.float64) - mat = chain.forward_kinematics([1.0, 1.0]).get_matrix() - - chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read(), 'right_back_foot') - chain = chain.to(dtype=torch.float64) - mat = chain.forward_kinematics([1.0, 1.0]).get_matrix() - def test_fkik(): data = '' \ @@ -82,21 +76,22 @@ def test_fkik(): '' chain = pk.build_serial_chain_from_urdf(data, 'link3') th1 = torch.tensor([0.42553542, 0.17529176]) - mat = chain.forward_kinematics(th1).get_matrix() - pos, rot = quat_pos_from_mat(mat) + tg = chain.forward_kinematics(th1) + pos, rot = quat_pos_from_transform3d(tg) assert torch.allclose(pos, torch.tensor([[1.91081784, 0.41280851, 0.0000]])) assert quaternion_equality(rot, torch.tensor([[0.95521418, 0.0000, 0.0000, 0.2959153]])) N = 20 th_batch = torch.rand(N, 2) - mat_batch = chain.forward_kinematics(th_batch).get_matrix() + tg_batch = chain.forward_kinematics(th_batch) + m = tg_batch.get_matrix() for i in range(N): - mat_i = chain.forward_kinematics(th_batch[i]).get_matrix() - assert torch.allclose(mat_i, mat_batch[i]) + tg = chain.forward_kinematics(th_batch[i]) + assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) # check that gradients are passed through th2 = torch.tensor([0.42553542, 0.17529176], requires_grad=True) - mat = chain.forward_kinematics(th2).get_matrix() - pos, rot = quat_pos_from_mat(mat) + tg = chain.forward_kinematics(th2) + pos, rot = quat_pos_from_transform3d(tg) # note that since we are using existing operations we are not checking grad calculation correctness assert th2.grad is None pos.norm().backward() @@ -107,9 +102,9 @@ def test_urdf(): chain = pk.build_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read()) chain.to(dtype=torch.float64) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] - ret = chain.forward_kinematics(th).get_matrix() - mat = ret['lbr_iiwa_link_7'] - pos, rot = quat_pos_from_mat(mat) + ret = chain.forward_kinematics(th) + tg = ret['lbr_iiwa_link_7'] + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64)) @@ -120,9 +115,9 @@ def test_urdf_serial(): print(chain) print(chain.get_joint_parameter_names()) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] - ret = chain.forward_kinematics(th, end_only=False).get_matrix() - mat = ret['lbr_iiwa_link_7'] - pos, rot = quat_pos_from_mat(mat) + ret = chain.forward_kinematics(th, end_only=False) + tg = ret['lbr_iiwa_link_7'] + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64)) @@ -135,7 +130,7 @@ def test_urdf_serial(): import time start = time.time() - tg_batch = chain.forward_kinematics(th_batch).get_matrix() + tg_batch = chain.forward_kinematics(th_batch) m = tg_batch.get_matrix() elapsed = time.time() - start print("elapsed {}s for N={} when parallel".format(elapsed, N)) @@ -143,10 +138,10 @@ def test_urdf_serial(): start = time.time() elapsed = 0 for i in range(N): - mat = chain.forward_kinematics(th_batch[i]).get_matrix() + tg = chain.forward_kinematics(th_batch[i]) elapsed += time.time() - start start = time.time() - assert torch.allclose(mat.get_matrix().view(4, 4), m[i]) + assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) print("elapsed {}s for N={} when serial".format(elapsed, N)) @@ -154,18 +149,18 @@ def test_urdf_serial(): def test_fk_simple_arm(): chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read()) chain = chain.to(dtype=torch.float64) + # print(chain) + # print(chain.get_joint_parameter_names()) ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) - mat = ret['arm_wrist_roll'].get_matrix() - - pos, rot = quat_pos_from_mat(mat) - + tg = ret['arm_wrist_roll'] + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) N = 100 ret = chain.forward_kinematics({'arm_elbow_pan_joint': torch.rand(N, 1), 'arm_wrist_lift_joint': torch.rand(N, 1)}) - mat = ret['arm_wrist_roll'] - assert list(mat.get_matrix().shape) == [N, 4, 4] + tg = ret['arm_wrist_roll'] + assert list(tg.get_matrix().shape) == [N, 4, 4] def test_cuda(): @@ -173,6 +168,7 @@ def test_cuda(): d = "cuda" dtype = torch.float64 chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read()) + # noinspection PyUnusedLocal chain = chain.to(dtype=dtype, device=d) # NOTE: do it twice because we previously had an issue with default arguments @@ -181,8 +177,8 @@ def test_cuda(): chain = chain.to(dtype=dtype, device=d) ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) - mat = ret['arm_wrist_roll'].get_matrix() - pos, rot = quat_pos_from_mat(mat) + tg = ret['arm_wrist_roll'] + pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=dtype, device=d)) @@ -208,8 +204,8 @@ def test_cuda(): tg_batch = chain.forward_kinematics(th_batch) m = tg_batch.get_matrix() for i in range(N): - mat = chain.forward_kinematics(th_batch[i]) - assert torch.allclose(mat.get_matrix().view(4, 4), m[i]) + tg = chain.forward_kinematics(th_batch[i]) + assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) # FIXME: comment out because compound joints are no longer implemented @@ -232,11 +228,78 @@ def test_mjcf_slide_joint_parsing(): if __name__ == "__main__": + torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) + import rerun as rr + + rr.init('') + rr.connect() + + chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read(), "lbr_iiwa_link_7") + chain_mjcf = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "kuka_iiwa.xml")).read(), + "lbr_iiwa_link_7") + + th = [0.0, ] * 7 + th[-1] = math.pi / 4 + ret = chain.forward_kinematics_slow(th, end_only=False) + for k, v in ret.items(): + m = torch.squeeze(v.get_matrix()) + pos = m[:3, 3] + rot = m[:3, :3] + rr.log(f'slow/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) + ret_urdf = chain.forward_kinematics(th, end_only=False) + ret_mjcf = chain_mjcf.forward_kinematics(th, end_only=False) + print(ret_mjcf['lbr_iiwa_link_7'].get_matrix()[0, :3, 3]) + print(ret['lbr_iiwa_link_7'].get_matrix()[0, :3, 3]) + + import numpy as np + + for j in range(6, 0, -1): + for i, theta in enumerate(np.linspace(0, math.pi, 100)): + rr.set_time_sequence('theta', i) + # th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] + # th = [0.0, np.sin(theta), 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] + th = [0.0, ] * 7 + th[j] = np.sin(theta) + ret = chain.forward_kinematics(th, end_only=False) + for k, v in ret.items(): + m = torch.squeeze(v.get_matrix()) + pos = m[:3, 3] + rot = m[:3, :3] + rr.log(f'fast/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) + + ret = chain_mjcf.forward_kinematics(th, end_only=False) + for k, v in ret.items(): + m = torch.squeeze(v.get_matrix()) + pos = m[:3, 3] + rot = m[:3, :3] + rr.log(f'fast_mjcf/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) + + ret = chain.forward_kinematics_slow(th, end_only=False) + for k, v in ret.items(): + m = torch.squeeze(v.get_matrix()) + pos = m[:3, 3] + rot = m[:3, :3] + rr.log(f'slow/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) + + ret = chain_mjcf.forward_kinematics_slow(th, end_only=False) + for k, v in ret.items(): + m = torch.squeeze(v.get_matrix()) + pos = m[:3, 3] + rot = m[:3, :3] + rr.log(f'slow_mjcf/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) + + tg = ret['lbr_iiwa_link_7'] + pos, rot = quat_pos_from_transform3d(tg) + rot + pos + torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64) # desired quat + torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64) # desired pos + + test_urdf_serial() test_fkik() test_fk_simple_arm() test_fk_mjcf() test_cuda() test_urdf() - test_urdf_serial() # test_fk_mjcf_humanoid() test_mjcf_slide_joint_parsing() From 0969c2bc4144db4b438df79b3eb0b736cdb020ff Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 15:30:45 -0400 Subject: [PATCH 09/34] bring back perf comparison test --- src/pytorch_kinematics/chain.py | 13 +++- .../transforms/rotation_conversions.py | 18 +++++ tests/kuka_iiwa.xml | 26 +++---- tests/test_fk_perf.py | 68 +++++++++++++++++++ tests/test_jacobian.py | 2 +- tests/test_kinematics.py | 67 ------------------ 6 files changed, 106 insertions(+), 88 deletions(-) create mode 100644 tests/test_fk_perf.py diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 9b56aa0..16124af 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -68,6 +68,7 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.is_fixed = [] self.link_offsets = [] self.joint_offsets = [] + self.joint_types = [] queue = [] queue.insert(-1, (self._root, -1, 0)) # the root has no parent so we use -1. idx = 0 @@ -102,6 +103,8 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.axes[jnt_idx] = root.joint.axis self.joint_indices.append(jnt_idx) + self.joint_types.append(root.joint.joint_type) + for child in root.children: queue.append((child, idx, depth + 1)) @@ -280,6 +283,7 @@ def forward_kinematics(self, th, frame_indices: Optional = None): axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) + # TODO: reimplement in CPP # frame_transforms = zpk_cpp.fk( # frame_indices, # axes_expanded, @@ -291,12 +295,17 @@ def forward_kinematics(self, th, frame_indices: Optional = None): # self.link_offsets # ) - import rerun as rr from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_angle_to_matrix + from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_d_to_pris_matrix frame_transforms = {} b = th.size(0) # compute all joint transforms at once first - jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) + # in order to handle multiple joint types without branching, we create all possible transforms + # for all joint types and then select the appropriate one for each joint. + rev_jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) + pris_jnt_transform = tensor_axis_and_d_to_pris_matrix(axes_expanded, th) + # jnt_transform = torch.where(self.joint_types, rev_jnt_transform, pris_jnt_transform) + jnt_transform = rev_jnt_transform for frame_idx in frame_indices: frame_transform = torch.eye(4).to(th).unsqueeze(0).repeat(b, 1, 1) diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 2045694..dcc0ad4 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -450,6 +450,24 @@ def quaternion_apply(quaternion, point): return out[..., 1:] +def tensor_axis_and_d_to_pris_matrix(axis, d): + """ + Works with any number of batch dimensions. + + Args: + axis: [..., 3] + d: [ ...] + + Returns: [..., 4, 4] + + """ + batch_axes = axis.shape[:-1] + mat44 = torch.eye(4).to(axis).repeat(*batch_axes, 1, 1) + pos = axis * d[..., None] + mat44[..., :3, 3] = pos + return mat44 + + def tensor_axis_and_angle_to_matrix(axis, theta): """ Works with any number of batch dimensions. diff --git a/tests/kuka_iiwa.xml b/tests/kuka_iiwa.xml index a4bae73..d76a4b3 100644 --- a/tests/kuka_iiwa.xml +++ b/tests/kuka_iiwa.xml @@ -1,46 +1,36 @@ - - - - - - - - - - - + - + - + - + - + - + - + - + diff --git a/tests/test_fk_perf.py b/tests/test_fk_perf.py new file mode 100644 index 0000000..4521c75 --- /dev/null +++ b/tests/test_fk_perf.py @@ -0,0 +1,68 @@ +import timeit +from time import perf_counter +import torch + +import pytorch_kinematics as pk +import numpy as np + +N = 10000 +number = 100 + + +def test_val_fk_perf(): + val = pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool') + val = val.to(dtype=torch.float32, device='cuda') + + th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') + print(len(val.get_joint_parameter_names())) + + def _val_old_fk(): + tg = val.forward_kinematics_slow(th, end_only=True) + m = tg.get_matrix() + return m + + def _val_new_fk(): + tg = val.forward_kinematics(th, end_only=True) + m = tg.get_matrix() + return m + + val_old_dt = timeit.timeit(_val_old_fk, number=number) + print(f'Val FK OLD dt: {val_old_dt / number:.4f}') + + val_new_dt = timeit.timeit(_val_new_fk, number=number) + print(f'Val FK NEW dt: {val_new_dt / number:.4f}') + + assert val_old_dt > val_new_dt + + +def test_kuka_fk_perf(): + kuka = pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7') + kuka = kuka.to(dtype=torch.float32, device='cuda') + + th = torch.zeros(N, 7, dtype=torch.float32, device='cuda') + + def _kuka_old_fk(): + tg = kuka.forward_kinematics_slow(th, end_only=True) + m = tg.get_matrix() + return m + + def _kuka_new_fk(): + tg = kuka.forward_kinematics(th, end_only=True) + m = tg.get_matrix() + return m + + kuka_old_dt = timeit.timeit(_kuka_old_fk, number=number) + print(f'Kuka FK OLD dt: {kuka_old_dt / number:.4f}') + + kuka_new_dt = timeit.timeit(_kuka_new_fk, number=number) + print(f'Kuka FK NEW dt: {kuka_new_dt / number:.4f}') + + assert kuka_old_dt > kuka_new_dt + + +if __name__ == '__main__': + np.set_printoptions(precision=3, suppress=True, linewidth=220) + torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) + + test_val_fk_perf() + test_kuka_fk_perf() diff --git a/tests/test_jacobian.py b/tests/test_jacobian.py index b1e3f69..599f26f 100644 --- a/tests/test_jacobian.py +++ b/tests/test_jacobian.py @@ -24,7 +24,7 @@ def test_correctness(): assert torch.allclose(J, J_expected, atol=1e-7) chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read()) - chain = pk.SerialChain(chain, "arm_wrist_roll_frame") + chain = pk.SerialChain(chain, "arm_wrist_roll") th = torch.tensor([0.8, 0.2, -0.5, -0.3]) J = chain.jacobian(th) torch.allclose(J, torch.tensor([[[0., -1.51017878, -0.46280904, 0.], diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 655c8ce..aefe056 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -228,73 +228,6 @@ def test_mjcf_slide_joint_parsing(): if __name__ == "__main__": - torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) - import rerun as rr - - rr.init('') - rr.connect() - - chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read(), "lbr_iiwa_link_7") - chain_mjcf = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "kuka_iiwa.xml")).read(), - "lbr_iiwa_link_7") - - th = [0.0, ] * 7 - th[-1] = math.pi / 4 - ret = chain.forward_kinematics_slow(th, end_only=False) - for k, v in ret.items(): - m = torch.squeeze(v.get_matrix()) - pos = m[:3, 3] - rot = m[:3, :3] - rr.log(f'slow/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) - ret_urdf = chain.forward_kinematics(th, end_only=False) - ret_mjcf = chain_mjcf.forward_kinematics(th, end_only=False) - print(ret_mjcf['lbr_iiwa_link_7'].get_matrix()[0, :3, 3]) - print(ret['lbr_iiwa_link_7'].get_matrix()[0, :3, 3]) - - import numpy as np - - for j in range(6, 0, -1): - for i, theta in enumerate(np.linspace(0, math.pi, 100)): - rr.set_time_sequence('theta', i) - # th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] - # th = [0.0, np.sin(theta), 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] - th = [0.0, ] * 7 - th[j] = np.sin(theta) - ret = chain.forward_kinematics(th, end_only=False) - for k, v in ret.items(): - m = torch.squeeze(v.get_matrix()) - pos = m[:3, 3] - rot = m[:3, :3] - rr.log(f'fast/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) - - ret = chain_mjcf.forward_kinematics(th, end_only=False) - for k, v in ret.items(): - m = torch.squeeze(v.get_matrix()) - pos = m[:3, 3] - rot = m[:3, :3] - rr.log(f'fast_mjcf/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) - - ret = chain.forward_kinematics_slow(th, end_only=False) - for k, v in ret.items(): - m = torch.squeeze(v.get_matrix()) - pos = m[:3, 3] - rot = m[:3, :3] - rr.log(f'slow/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) - - ret = chain_mjcf.forward_kinematics_slow(th, end_only=False) - for k, v in ret.items(): - m = torch.squeeze(v.get_matrix()) - pos = m[:3, 3] - rot = m[:3, :3] - rr.log(f'slow_mjcf/{k}', rr.Transform3D(translation=pos, mat3x3=rot)) - - tg = ret['lbr_iiwa_link_7'] - pos, rot = quat_pos_from_transform3d(tg) - rot - pos - torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64) # desired quat - torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64) # desired pos - test_urdf_serial() test_fkik() test_fk_simple_arm() From dbd2d027956431f83b4432d6cfacc6e90059986a Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 15:45:40 -0400 Subject: [PATCH 10/34] bring back perf comparison test --- src/pytorch_kinematics/chain.py | 30 ++++++++++++++++++------------ 1 file changed, 18 insertions(+), 12 deletions(-) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 16124af..964e502 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -7,7 +7,7 @@ import pytorch_kinematics.transforms as tf import zpk_cpp from pytorch_kinematics import jacobian -from pytorch_kinematics.frame import Frame, Link +from pytorch_kinematics.frame import Frame, Link, Joint def get_th_size(th): @@ -65,10 +65,9 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.joint_indices = [] self.n_joints = len(self.get_joint_parameter_names()) self.axes = torch.zeros([self.n_joints, 3], dtype=self.dtype, device=self.device) - self.is_fixed = [] self.link_offsets = [] self.joint_offsets = [] - self.joint_types = [] + self.joint_type_indices = [] queue = [] queue.insert(-1, (self._root, -1, 0)) # the root has no parent so we use -1. idx = 0 @@ -84,7 +83,7 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): else: self.parents_indices.append(self.parents_indices[parent_idx] + [parent_idx]) - self.is_fixed.append(root.joint.joint_type == 'fixed') + is_fixed = root.joint.joint_type == 'fixed' if root.link.offset is None: self.link_offsets.append(None) @@ -96,19 +95,22 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): else: self.joint_offsets.append(root.joint.offset.get_matrix()) - if self.is_fixed[-1]: + if is_fixed: self.joint_indices.append(-1) else: jnt_idx = self.get_joint_parameter_names().index(root.joint.name) self.axes[jnt_idx] = root.joint.axis self.joint_indices.append(jnt_idx) - self.joint_types.append(root.joint.joint_type) + # these are integers so that we can use them as indices into tensors + # FIXME: how do we know the order of these types in C++? + self.joint_type_indices.append(Joint.TYPES.index(root.joint.joint_type)) for child in root.children: queue.append((child, idx, depth + 1)) idx += 1 + self.joint_type_indices = torch.tensor(self.joint_type_indices) self.joint_indices = torch.tensor(self.joint_indices) self.parents_indices = [torch.tensor(p, dtype=torch.long, device=self.device) for p in self.parents_indices] @@ -121,6 +123,7 @@ def to(self, dtype=None, device=None): self.identity = self.identity.to(device=self.device, dtype=self.dtype) self.parents_indices = [p.to(dtype=torch.long, device=self.device) for p in self.parents_indices] + self.joint_type_indices = self.joint_type_indices.to(dtype=torch.long, device=self.device) self.axes = self.axes.to(dtype=self.dtype, device=self.device) self.link_offsets = [l if l is None else l.to(dtype=self.dtype, device=self.device) for l in self.link_offsets] self.joint_offsets = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in @@ -289,7 +292,6 @@ def forward_kinematics(self, th, frame_indices: Optional = None): # axes_expanded, # th, # self.parent_indices, - # self.is_fixed, # self.joint_indices, # self.joint_offsets, # self.link_offsets @@ -304,8 +306,6 @@ def forward_kinematics(self, th, frame_indices: Optional = None): # for all joint types and then select the appropriate one for each joint. rev_jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) pris_jnt_transform = tensor_axis_and_d_to_pris_matrix(axes_expanded, th) - # jnt_transform = torch.where(self.joint_types, rev_jnt_transform, pris_jnt_transform) - jnt_transform = rev_jnt_transform for frame_idx in frame_indices: frame_transform = torch.eye(4).to(th).unsqueeze(0).repeat(b, 1, 1) @@ -324,9 +324,15 @@ def forward_kinematics(self, th, frame_indices: Optional = None): if joint_offset_i is not None: frame_transform = frame_transform @ joint_offset_i - if not self.is_fixed[chain_idx]: - jnt_idx = self.joint_indices[chain_idx] - jnt_transform_i = jnt_transform[:, jnt_idx] + jnt_idx = self.joint_indices[chain_idx] + jnt_type = self.joint_type_indices[chain_idx] + if jnt_type == 0: + pass + elif jnt_type == 1: + jnt_transform_i = rev_jnt_transform[:, jnt_idx] + frame_transform = frame_transform @ jnt_transform_i + elif jnt_type == 2: + jnt_transform_i = pris_jnt_transform[:, jnt_idx] frame_transform = frame_transform @ jnt_transform_i frame_transforms[frame_idx.item()] = frame_transform From 0ac2a0a91213cd08914368867586ed926423047e Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 16:34:03 -0400 Subject: [PATCH 11/34] all tests pass! --- src/pytorch_kinematics/chain.py | 43 +++++++++++++++++++++++++++------ src/pytorch_kinematics/sdf.py | 6 +++++ tests/test_kinematics.py | 32 +++++++++++++++++++++--- 3 files changed, 69 insertions(+), 12 deletions(-) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 964e502..0198423 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -38,6 +38,16 @@ def ensure_2d_tensor(th, dtype, device): return th, N +def get_dict_elem_shape(th_dict): + elem = th_dict[list(th_dict.keys())[0]] + if isinstance(elem, np.ndarray): + return elem.shape + elif isinstance(elem, torch.Tensor): + return elem.shape + else: + return () + + class Chain: """ Robot model that may be constructed from different descriptions via their respective parsers. @@ -174,6 +184,7 @@ def get_joints(self, exclude_fixed=True): joints = self._get_joints(self._root, exclude_fixed=exclude_fixed) return joints + @lru_cache() def get_joint_parameter_names(self, exclude_fixed=True): names = [] for f in self.get_joints(exclude_fixed=exclude_fixed): @@ -270,11 +281,16 @@ def get_frame_indices(self, *frame_names): def forward_kinematics(self, th, frame_indices: Optional = None): """ - Instead of a tree, we can use a flat data structure with indexes to represent the parent - then instead of recursion we can just iterate in order and use parent pointers. This - reduces function call overhead and moves some of the indexing work to the constructor. + Compute forward kinematics. + + Args: + th: A dict, list, numpy array, or torch tensor of ALL joints values. Possibly batched. + the fastest thing to use is a torch tensor, all other types get converted to that. + If any joint values are missing, an exception will be thrown. + frame_indices: A list of frame indices to compute forward kinematics for. If None, all frames are computed. - use `get_frame_indices` to get the indices for the frames you want to compute the pose for. + Returns: + A dict of frame names and their corresponding Transform3d objects. """ if frame_indices is None: frame_indices = self.get_all_frame_indices() @@ -343,18 +359,28 @@ def forward_kinematics(self, th, frame_indices: Optional = None): return frame_names_and_transform3ds def ensure_tensor(self, th): + """ + Converts a number of possible types into a tensor. The order of the tensor is determined by the order + of self.get_joint_parameter_names(). + """ if isinstance(th, np.ndarray): th = torch.tensor(th, device=self.device, dtype=self.dtype) - if isinstance(th, list): + elif isinstance(th, list): th = torch.tensor(th, device=self.device, dtype=self.dtype) - if isinstance(th, dict): + elif isinstance(th, dict): # convert dict to a flat, complete, tensor of all joints values. Missing joints are filled with zeros. th_dict = th - th = torch.zeros(self.n_joints, device=self.device, dtype=self.dtype) + elem_shape = get_dict_elem_shape(th_dict) + th = torch.ones([*elem_shape, self.n_joints], device=self.device, dtype=self.dtype) * torch.nan joint_names = self.get_joint_parameter_names() for joint_name, joint_position in th_dict.items(): jnt_idx = joint_names.index(joint_name) - th[jnt_idx] = joint_position + th[..., jnt_idx] = joint_position + if torch.any(torch.isnan(th)): + msg = "Missing values for the following joints:\n" + for joint_name, th_i in zip(self.get_joint_parameter_names(), th): + msg += joint_name + "\n" + raise ValueError(msg) return th def get_all_frame_indices(self): @@ -454,6 +480,7 @@ def jacobian(self, th, locations=None): return jacobian.calc_jacobian(self, th, tool=locations) def forward_kinematics(self, th, end_only: bool = True): + """ Like the base class, except `th` only needs to contain the joints in the SerialChain, not all joints. """ if end_only: frame_indices = self.get_frame_indices(self._serial_frames[-1].name) else: diff --git a/src/pytorch_kinematics/sdf.py b/src/pytorch_kinematics/sdf.py index 22be504..32ac177 100644 --- a/src/pytorch_kinematics/sdf.py +++ b/src/pytorch_kinematics/sdf.py @@ -100,3 +100,9 @@ def build_chain_from_sdf(data): _convert_visuals(root_link.visuals)) root_frame.children = _build_chain_recurse(root_frame, lmap, joints) return chain.Chain(root_frame) + + +def build_serial_chain_from_sdf(data, end_link_name, root_link_name=""): + mjcf_chain = build_chain_from_sdf(data) + serial_chain = chain.SerialChain(mjcf_chain, end_link_name, "" if root_link_name == "" else root_link_name) + return serial_chain diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index aefe056..1614d37 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -36,7 +36,16 @@ def test_fk_mjcf(): chain = chain.to(dtype=torch.float64) print(chain) print(chain.get_joint_parameter_names()) - th = {'hip_1': 1.0, 'ankle_1': 1} + th = { + 'hip_1': 1.0, + 'ankle_1': 1, + 'hip_2': 0.0, + 'ankle_2': 0.0, + 'hip_3': 0.0, + 'ankle_3': 0.0, + 'hip_4': 0.0, + 'ankle_4': 0.0, + } ret = chain.forward_kinematics(th) tg = ret['aux_1'] pos, rot = quat_pos_from_transform3d(tg) @@ -151,14 +160,24 @@ def test_fk_simple_arm(): chain = chain.to(dtype=torch.float64) # print(chain) # print(chain.get_joint_parameter_names()) - ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) + ret = chain.forward_kinematics({ + 'arm_shoulder_pan_joint': 0., + 'arm_elbow_pan_joint': math.pi / 2.0, + 'arm_wrist_lift_joint': -0.5, + 'arm_wrist_roll_joint': 0., + }) tg = ret['arm_wrist_roll'] pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) N = 100 - ret = chain.forward_kinematics({'arm_elbow_pan_joint': torch.rand(N, 1), 'arm_wrist_lift_joint': torch.rand(N, 1)}) + ret = chain.forward_kinematics({ + 'arm_shoulder_pan_joint': torch.rand(N), + 'arm_elbow_pan_joint': torch.rand(N), + 'arm_wrist_lift_joint': torch.rand(N), + 'arm_wrist_roll_joint': torch.rand(N), + }) tg = ret['arm_wrist_roll'] assert list(tg.get_matrix().shape) == [N, 4, 4] @@ -176,7 +195,12 @@ def test_cuda(): chain = pk.build_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read()) chain = chain.to(dtype=dtype, device=d) - ret = chain.forward_kinematics({'arm_elbow_pan_joint': math.pi / 2.0, 'arm_wrist_lift_joint': -0.5}) + ret = chain.forward_kinematics({ + 'arm_shoulder_pan_joint': 0, + 'arm_elbow_pan_joint': math.pi / 2.0, + 'arm_wrist_lift_joint': -0.5, + 'arm_wrist_roll_joint': 0, + }) tg = ret['arm_wrist_roll'] pos, rot = quat_pos_from_transform3d(tg) assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d)) From 6ec0d34cf456bbdaeee28db4cf1ca87a9e509d59 Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 16:36:20 -0400 Subject: [PATCH 12/34] new test for sdf_serial_chain --- tests/test_kinematics.py | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 1614d37..a5c4af6 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -182,6 +182,15 @@ def test_fk_simple_arm(): assert list(tg.get_matrix().shape) == [N, 4, 4] +def test_sdf_serial_chain(): + chain = pk.build_serial_chain_from_sdf(open(os.path.join(TEST_DIR, "simple_arm.sdf")).read(), 'arm_wrist_roll') + chain = chain.to(dtype=torch.float64) + tg = chain.forward_kinematics([0., math.pi / 2.0, -0.5, 0.]) + pos, rot = quat_pos_from_transform3d(tg) + assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) + assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) + + def test_cuda(): if torch.cuda.is_available(): d = "cuda" @@ -197,9 +206,9 @@ def test_cuda(): ret = chain.forward_kinematics({ 'arm_shoulder_pan_joint': 0, - 'arm_elbow_pan_joint': math.pi / 2.0, - 'arm_wrist_lift_joint': -0.5, - 'arm_wrist_roll_joint': 0, + 'arm_elbow_pan_joint': math.pi / 2.0, + 'arm_wrist_lift_joint': -0.5, + 'arm_wrist_roll_joint': 0, }) tg = ret['arm_wrist_roll'] pos, rot = quat_pos_from_transform3d(tg) From 362646e312249ded20a80e41c5b508aed20222ef Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 16:48:50 -0400 Subject: [PATCH 13/34] new test for Val FK --- tests/test_kinematics.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index a5c4af6..f88eab7 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -260,7 +260,19 @@ def test_mjcf_slide_joint_parsing(): print(chain.get_frame_names()) +def test_fk_val(): + chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read()) + chain = chain.to(dtype=torch.float64) + ret = chain.forward_kinematics(torch.zeros([1000, chain.n_joints], dtype=torch.float64)) + tg = ret['drive45'] + pos, rot = quat_pos_from_transform3d(tg) + assert quaternion_equality(rot, torch.tensor([0.5, 0.5, -0.5, 0.5], dtype=torch.float64)) + assert torch.allclose(pos, torch.tensor([-0.225692, 0.259045, 0.262139], dtype=torch.float64)) + + if __name__ == "__main__": + test_fk_val() + test_sdf_serial_chain() test_urdf_serial() test_fkik() test_fk_simple_arm() From 13182611c809ad2f016f08be0851341c852b2f3c Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 26 Oct 2023 16:52:46 -0400 Subject: [PATCH 14/34] rtol hacking --- tests/test_kinematics.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index f88eab7..f906cda 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -25,9 +25,9 @@ def quat_pos_from_transform3d(tg): return pos, rot -def quaternion_equality(a, b): +def quaternion_equality(a, b, rtol=1e-5): # negative of a quaternion is the same rotation - return torch.allclose(a, b) or torch.allclose(a, -b) + return torch.allclose(a, b, rtol=rtol) or torch.allclose(a, -b, rtol=rtol) # test more complex robot and the MJCF parser @@ -266,7 +266,8 @@ def test_fk_val(): ret = chain.forward_kinematics(torch.zeros([1000, chain.n_joints], dtype=torch.float64)) tg = ret['drive45'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.5, 0.5, -0.5, 0.5], dtype=torch.float64)) + torch.set_printoptions(precision=6, sci_mode=False) + assert quaternion_equality(rot, torch.tensor([0.5, 0.5, -0.5, 0.5], dtype=torch.float64), rtol=1e-4) assert torch.allclose(pos, torch.tensor([-0.225692, 0.259045, 0.262139], dtype=torch.float64)) From 57b74fe00e2b2431ab29af6b8713609e219a57c3 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 11:33:17 -0400 Subject: [PATCH 15/34] finish translating to C++ and test for correctness with Val model --- .clang-format | 168 ++++++++++++++++++++++++++++++++ setup.py | 1 - src/pytorch_kinematics/chain.py | 87 +++++++++++------ src/zpk_cpp/pk.cpp | 100 +++++++++++-------- tests/test_fk_perf.py | 90 ++++++++++++++--- 5 files changed, 362 insertions(+), 84 deletions(-) create mode 100644 .clang-format diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..6b72b54 --- /dev/null +++ b/.clang-format @@ -0,0 +1,168 @@ +--- +Language: Cpp +# BasedOnStyle: Google +AccessModifierOffset: -1 +AlignAfterOpenBracket: Align +AlignConsecutiveMacros: false +AlignConsecutiveAssignments: false +AlignConsecutiveDeclarations: false +AlignEscapedNewlines: Left +AlignOperands: true +AlignTrailingComments: true +AllowAllArgumentsOnNextLine: true +AllowAllConstructorInitializersOnNextLine: true +AllowAllParametersOfDeclarationOnNextLine: true +AllowShortBlocksOnASingleLine: Never +AllowShortCaseLabelsOnASingleLine: false +AllowShortFunctionsOnASingleLine: All +AllowShortLambdasOnASingleLine: All +AllowShortIfStatementsOnASingleLine: WithoutElse +AllowShortLoopsOnASingleLine: true +AlwaysBreakAfterDefinitionReturnType: None +AlwaysBreakAfterReturnType: None +AlwaysBreakBeforeMultilineStrings: true +AlwaysBreakTemplateDeclarations: Yes +BinPackArguments: true +BinPackParameters: true +BraceWrapping: + AfterCaseLabel: false + AfterClass: false + AfterControlStatement: false + AfterEnum: false + AfterFunction: false + AfterNamespace: false + AfterObjCDeclaration: false + AfterStruct: false + AfterUnion: false + AfterExternBlock: false + BeforeCatch: false + BeforeElse: false + IndentBraces: false + SplitEmptyFunction: true + SplitEmptyRecord: true + SplitEmptyNamespace: true +BreakBeforeBinaryOperators: None +BreakBeforeBraces: Attach +BreakBeforeInheritanceComma: false +BreakInheritanceList: BeforeColon +BreakBeforeTernaryOperators: true +BreakConstructorInitializersBeforeComma: false +BreakConstructorInitializers: BeforeColon +BreakAfterJavaFieldAnnotations: false +BreakStringLiterals: true +ColumnLimit: 120 +CommentPragmas: '^ IWYU pragma:' +CompactNamespaces: false +ConstructorInitializerAllOnOneLineOrOnePerLine: true +ConstructorInitializerIndentWidth: 4 +ContinuationIndentWidth: 4 +Cpp11BracedListStyle: true +DeriveLineEnding: true +DerivePointerAlignment: true +DisableFormat: false +ExperimentalAutoDetectBinPacking: false +FixNamespaceComments: true +ForEachMacros: + - foreach + - Q_FOREACH + - BOOST_FOREACH +IncludeBlocks: Regroup +IncludeCategories: + - Regex: '^' + Priority: 2 + SortPriority: 0 + - Regex: '^<.*\.h>' + Priority: 1 + SortPriority: 0 + - Regex: '^<.*' + Priority: 2 + SortPriority: 0 + - Regex: '.*' + Priority: 3 + SortPriority: 0 +IncludeIsMainRegex: '([-_](test|unittest))?$' +IncludeIsMainSourceRegex: '' +IndentCaseLabels: true +IndentGotoLabels: true +IndentPPDirectives: None +IndentWidth: 2 +IndentWrappedFunctionNames: false +JavaScriptQuotes: Leave +JavaScriptWrapImports: true +KeepEmptyLinesAtTheStartOfBlocks: false +MacroBlockBegin: '' +MacroBlockEnd: '' +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCBinPackProtocolList: Never +ObjCBlockIndentWidth: 2 +ObjCSpaceAfterProperty: false +ObjCSpaceBeforeProtocolList: true +PenaltyBreakAssignment: 2 +PenaltyBreakBeforeFirstCallParameter: 1 +PenaltyBreakComment: 300 +PenaltyBreakFirstLessLess: 120 +PenaltyBreakString: 1000 +PenaltyBreakTemplateDeclaration: 10 +PenaltyExcessCharacter: 1000000 +PenaltyReturnTypeOnItsOwnLine: 200 +PointerAlignment: Left +RawStringFormats: + - Language: Cpp + Delimiters: + - cc + - CC + - cpp + - Cpp + - CPP + - 'c++' + - 'C++' + CanonicalDelimiter: '' + BasedOnStyle: google + - Language: TextProto + Delimiters: + - pb + - PB + - proto + - PROTO + EnclosingFunctions: + - EqualsProto + - EquivToProto + - PARSE_PARTIAL_TEXT_PROTO + - PARSE_TEST_PROTO + - PARSE_TEXT_PROTO + - ParseTextOrDie + - ParseTextProtoOrDie + CanonicalDelimiter: '' + BasedOnStyle: google +ReflowComments: true +SortIncludes: true +SortUsingDeclarations: true +SpaceAfterCStyleCast: false +SpaceAfterLogicalNot: false +SpaceAfterTemplateKeyword: true +SpaceBeforeAssignmentOperators: true +SpaceBeforeCpp11BracedList: false +SpaceBeforeCtorInitializerColon: true +SpaceBeforeInheritanceColon: true +SpaceBeforeParens: ControlStatements +SpaceBeforeRangeBasedForLoopColon: true +SpaceInEmptyBlock: false +SpaceInEmptyParentheses: false +SpacesBeforeTrailingComments: 2 +SpacesInAngles: false +SpacesInConditionalStatement: false +SpacesInContainerLiterals: true +SpacesInCStyleCastParentheses: false +SpacesInParentheses: false +SpacesInSquareBrackets: false +SpaceBeforeSquareBrackets: false +Standard: Auto +StatementMacros: + - Q_UNUSED + - QT_REQUIRE_VERSION +TabWidth: 8 +UseCRLF: false +UseTab: Never +... + diff --git a/setup.py b/setup.py index cdb1835..7aba117 100644 --- a/setup.py +++ b/setup.py @@ -3,7 +3,6 @@ # This is needed in order to build the C++ extension import torch -print(f'>>>>> {torch.__version__} <<<<<') ext = cpp_extension.CppExtension('zpk_cpp', ['src/zpk_cpp/pk.cpp'], extra_compile_args=['-std=c++17']) setup_args = dict( packages=find_packages(where="src"), diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 0198423..a221877 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -1,11 +1,12 @@ from functools import lru_cache +from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_angle_to_matrix +from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_d_to_pris_matrix from typing import Optional, Sequence import numpy as np import torch import pytorch_kinematics.transforms as tf -import zpk_cpp from pytorch_kinematics import jacobian from pytorch_kinematics.frame import Frame, Link, Joint @@ -68,7 +69,7 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): # As we traverse the kinematic tree, each frame is assigned an index. # We use this index to build a flat representation of the tree. - # parent_indices and joint_indices all use this indexing scheme. + # parents_indices and joint_indices all use this indexing scheme. # The root frame will be index 0 and the first frame of the root frame's children will be index 1, # then the child of that frame will be index 2, etc. In other words, it's a depth-first ordering. self.parents_indices = [] # list of indices from 0 (root) to the given frame @@ -89,9 +90,9 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): self.frame_to_idx[name_strip] = idx self.idx_to_frame[idx] = name_strip if parent_idx == -1: - self.parents_indices.append([]) + self.parents_indices.append([idx]) else: - self.parents_indices.append(self.parents_indices[parent_idx] + [parent_idx]) + self.parents_indices.append(self.parents_indices[parent_idx] + [idx]) is_fixed = root.joint.joint_type == 'fixed' @@ -134,6 +135,7 @@ def to(self, dtype=None, device=None): self.identity = self.identity.to(device=self.device, dtype=self.dtype) self.parents_indices = [p.to(dtype=torch.long, device=self.device) for p in self.parents_indices] self.joint_type_indices = self.joint_type_indices.to(dtype=torch.long, device=self.device) + self.joint_indices = self.joint_indices.to(dtype=torch.long, device=self.device) self.axes = self.axes.to(dtype=self.dtype, device=self.device) self.link_offsets = [l if l is None else l.to(dtype=self.dtype, device=self.device) for l in self.link_offsets] self.joint_offsets = [j if j is None else j.to(dtype=self.dtype, device=self.device) for j in @@ -298,25 +300,36 @@ def forward_kinematics(self, th, frame_indices: Optional = None): th = self.ensure_tensor(th) th = torch.atleast_2d(th) - b, n = th.shape + import zpk_cpp + frame_transforms = zpk_cpp.fk( + frame_indices, + self.axes, + th, + self.parents_indices, + self.joint_type_indices, + self.joint_indices, + self.joint_offsets, + self.link_offsets + ) + + frame_names_and_transform3ds = {self.idx_to_frame[frame_idx]: tf.Transform3d(matrix=transform) for + frame_idx, transform in frame_transforms.items()} + + return frame_names_and_transform3ds + + def forward_kinematics_py(self, th, frame_indices: Optional = None): + if frame_indices is None: + frame_indices = self.get_all_frame_indices() + + th = self.ensure_tensor(th) + th = torch.atleast_2d(th) + + b = th.shape[0] axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) - # TODO: reimplement in CPP - # frame_transforms = zpk_cpp.fk( - # frame_indices, - # axes_expanded, - # th, - # self.parent_indices, - # self.joint_indices, - # self.joint_offsets, - # self.link_offsets - # ) - - from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_angle_to_matrix - from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_d_to_pris_matrix frame_transforms = {} - b = th.size(0) + # compute all joint transforms at once first # in order to handle multiple joint types without branching, we create all possible transforms # for all joint types and then select the appropriate one for each joint. @@ -327,9 +340,8 @@ def forward_kinematics(self, th, frame_indices: Optional = None): frame_transform = torch.eye(4).to(th).unsqueeze(0).repeat(b, 1, 1) # iterate down the list and compose the transform - chain_indices = torch.cat((self.parents_indices[frame_idx], frame_idx[None])) - for chain_idx in chain_indices: - if chain_idx.item() in frame_transforms and False: # DEBUGGING + for chain_idx in self.parents_indices[frame_idx]: + if chain_idx.item() in frame_transforms: frame_transform = frame_transforms[chain_idx.item()] else: link_offset_i = self.link_offsets[chain_idx] @@ -481,13 +493,34 @@ def jacobian(self, th, locations=None): def forward_kinematics(self, th, end_only: bool = True): """ Like the base class, except `th` only needs to contain the joints in the SerialChain, not all joints. """ + frame_indices, th = self.convert_serial_inputs_to_chain_inputs(end_only, th) + + mat = super().forward_kinematics(th, frame_indices) + + if end_only: + return mat[self._serial_frames[-1].name] + else: + return mat + + def forward_kinematics_py(self, th, end_only: bool = True): + """ Like the base class, except `th` only needs to contain the joints in the SerialChain, not all joints. """ + frame_indices, th = self.convert_serial_inputs_to_chain_inputs(end_only, th) + + mat = super().forward_kinematics_py(th, frame_indices) + + if end_only: + return mat[self._serial_frames[-1].name] + else: + return mat + + + def convert_serial_inputs_to_chain_inputs(self, end_only, th): if end_only: frame_indices = self.get_frame_indices(self._serial_frames[-1].name) else: # pass through default behavior for frame indices being None, which is currently # to return all frames. frame_indices = None - if get_th_size(th) < self.n_joints: # if th is only a partial list of joints, assume it's a list of joints for only the serial chain. partial_th = th @@ -500,13 +533,7 @@ def forward_kinematics(self, th, end_only: bool = True): jnt_idx = self.joint_indices[k] if frame.joint.joint_type != 'fixed': th[jnt_idx] = partial_th_i - - mat = super().forward_kinematics(th, frame_indices) - - if end_only: - return mat[self._serial_frames[-1].name] - else: - return mat + return frame_indices, th def forward_kinematics_slow(self, th, world=None, end_only=True): if world is None: diff --git a/src/zpk_cpp/pk.cpp b/src/zpk_cpp/pk.cpp index e63d5e9..24c0182 100644 --- a/src/zpk_cpp/pk.cpp +++ b/src/zpk_cpp/pk.cpp @@ -1,11 +1,26 @@ -#include #include + +#include #include using namespace torch::indexing; -torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, - torch::Tensor theta) { +torch::Tensor axis_and_d_to_pris_matrix(torch::Tensor axis, torch::Tensor d) { + /** + * axis is [b, n, 3] + * d is [b, n] + * + * Output is [b, n, 4, 4] + */ + auto b = axis.size(0); + auto n = axis.size(1); + auto mat44 = torch::eye(4).to(axis).repeat({b, n, 1, 1}); + auto pos = axis * d.unsqueeze(-1); + mat44.index_put_({Ellipsis, Slice(0, 3), 3}, pos); + return mat44; +} + +torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, torch::Tensor theta) { /** * cos is not that precise for float32, you may want to use float64 * axis is [b, n, 3] @@ -14,8 +29,7 @@ torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, */ auto b = axis.size(0); auto n = axis.size(1); - auto m = - torch::eye(4).to(axis).unsqueeze(0).unsqueeze(0).repeat({b, n, 1, 1}); + auto m = torch::eye(4).to(axis).unsqueeze(0).unsqueeze(0).repeat({b, n, 1, 1}); auto kx = axis.index({Ellipsis, 0}); auto ky = axis.index({Ellipsis, 1}); @@ -41,49 +55,53 @@ torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, return m; } -std::vector -fk(torch::Tensor link_indices, torch::Tensor axes, torch::Tensor th, - std::vector parent_indices, std::vector is_fixed, - torch::Tensor joint_indices, - std::vector> joint_offsets, - std::vector> link_offsets) { - std::vector link_transforms; +std::map fk(torch::Tensor frame_indices, torch::Tensor axes, torch::Tensor th, + std::vector parents_indices, torch::Tensor joint_type_indices, + torch::Tensor joint_indices, std::vector> joint_offsets, + std::vector> link_offsets) { + std::map frame_transforms; - auto b = th.size(0); - // NOTE: assumes revolute joint! - auto const jnt_transform = axis_and_angle_to_matrix(axes, th); + auto const b = th.size(0); + auto const axes_expanded = axes.unsqueeze(0).repeat({b, 1, 1}); - for (auto i{0}; i < link_indices.size(0); ++i) { - auto idx = link_indices.index({i}).item().to(); - auto link_transform = torch::eye(4).to(th).unsqueeze(0).repeat({b, 1, 1}); + auto const rev_jnt_transform = axis_and_angle_to_matrix(axes_expanded, th); + auto const pris_jnt_transform = axis_and_d_to_pris_matrix(axes_expanded, th); - while (idx >= 0) { - auto const joint_offset_i = joint_offsets[idx]; - if (joint_offset_i) { - link_transform = torch::matmul(*joint_offset_i, link_transform); - } + for (int64_t i = 0; i < frame_indices.size(0); i++) { + auto const frame_idx = frame_indices[i].item(); + auto frame_transform = torch::eye(4).to(th).unsqueeze(0).expand({b, 4, 4}); - if (!is_fixed[idx]) { - auto const jnt_idx = joint_indices[idx]; - auto const jnt_transform_i = jnt_transform.index({Slice(), jnt_idx}); - link_transform = torch::matmul(jnt_transform_i, link_transform); - } + auto const parent_indices = parents_indices[frame_idx]; + for (int64_t j = 0; j < parent_indices.size(0); j++) { + auto const chain_idx_tensor = parent_indices[j]; + int64_t chain_idx_int = chain_idx_tensor.item(); + if (frame_transforms.find(chain_idx_int) != frame_transforms.end()) { + frame_transform = frame_transforms[chain_idx_int]; + } else { + auto const link_offset_i = link_offsets[chain_idx_int]; + if (link_offset_i) { + frame_transform = frame_transform.matmul(*link_offset_i); + } - auto const link_offset_i = link_offsets[idx]; - if (link_offset_i) { - link_transform = torch::matmul(*link_offset_i, link_transform); - } + auto const joint_offset_i = joint_offsets[chain_idx_int]; + if (joint_offset_i) { + frame_transform = frame_transform.matmul(*joint_offset_i); + } - idx = parent_indices[idx]; + auto const jnt_idx = joint_indices.index({chain_idx_tensor}).item(); + auto const jnt_type = joint_type_indices.index({chain_idx_tensor}).item(); + if (jnt_type == 1) { + auto const jnt_transform_i = rev_jnt_transform.index({Slice(), jnt_idx}); + frame_transform = frame_transform.matmul(jnt_transform_i); + } else if (jnt_type == 2) { + auto const jnt_transform_i = pris_jnt_transform.index({Slice(), jnt_idx}); + frame_transform = frame_transform.matmul(jnt_transform_i); + } + } } - - link_transforms.emplace_back(link_transform); + frame_transforms.emplace(frame_idx, frame_transform); } - return link_transforms; + return frame_transforms; } -PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { - m.def("axis_and_angle_to_matrix", &axis_and_angle_to_matrix, - "axis_and_angle_to_matrix", py::arg("axis"), py::arg("theta")); - m.def("fk", &fk, "fk"); -} +PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { m.def("fk", &fk, "fk"); } diff --git a/tests/test_fk_perf.py b/tests/test_fk_perf.py index 4521c75..78830ea 100644 --- a/tests/test_fk_perf.py +++ b/tests/test_fk_perf.py @@ -9,19 +9,41 @@ number = 100 +def test_val_fk_correctness(): + val = pk.build_chain_from_mjcf(open('val.xml').read()) + val = val.to(dtype=torch.float32, device='cuda') + + th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') + + frame_indices = val.get_frame_indices('left_tool', 'right_tool') + t_py = val.forward_kinematics_py(th, frame_indices) + t_cpp = val.forward_kinematics(th, frame_indices) + l_py = t_py['left_tool'].get_matrix() + l_cpp = t_cpp['left_tool'].get_matrix() + r_py = t_py['right_tool'].get_matrix() + r_cpp = t_cpp['right_tool'].get_matrix() + + assert torch.allclose(l_py, l_cpp) + assert torch.allclose(r_py, r_cpp) + + def test_val_fk_perf(): val = pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool') val = val.to(dtype=torch.float32, device='cuda') th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') - print(len(val.get_joint_parameter_names())) def _val_old_fk(): tg = val.forward_kinematics_slow(th, end_only=True) m = tg.get_matrix() return m - def _val_new_fk(): + def _val_new_py_fk(): + tg = val.forward_kinematics_py(th, end_only=True) + m = tg.get_matrix() + return m + + def _val_new_cpp_fk(): tg = val.forward_kinematics(th, end_only=True) m = tg.get_matrix() return m @@ -29,10 +51,13 @@ def _val_new_fk(): val_old_dt = timeit.timeit(_val_old_fk, number=number) print(f'Val FK OLD dt: {val_old_dt / number:.4f}') - val_new_dt = timeit.timeit(_val_new_fk, number=number) - print(f'Val FK NEW dt: {val_new_dt / number:.4f}') + val_new_py_dt = timeit.timeit(_val_new_py_fk, number=number) + print(f'Val FK NEW dt: {val_new_py_dt / number:.4f}') + + val_new_cpp_dt = timeit.timeit(_val_new_cpp_fk, number=number) + print(f'Val FK NEW C++ dt: {val_new_cpp_dt / number:.4f}') - assert val_old_dt > val_new_dt + assert val_old_dt > val_new_cpp_dt def test_kuka_fk_perf(): @@ -46,7 +71,12 @@ def _kuka_old_fk(): m = tg.get_matrix() return m - def _kuka_new_fk(): + def _kuka_new_py_fk(): + tg = kuka.forward_kinematics_py(th, end_only=True) + m = tg.get_matrix() + return m + + def _kuka_new_cpp_fk(): tg = kuka.forward_kinematics(th, end_only=True) m = tg.get_matrix() return m @@ -54,15 +84,51 @@ def _kuka_new_fk(): kuka_old_dt = timeit.timeit(_kuka_old_fk, number=number) print(f'Kuka FK OLD dt: {kuka_old_dt / number:.4f}') - kuka_new_dt = timeit.timeit(_kuka_new_fk, number=number) - print(f'Kuka FK NEW dt: {kuka_new_dt / number:.4f}') + kuka_new_py_dt = timeit.timeit(_kuka_new_py_fk, number=number) + print(f'Kuka FK NEW dt: {kuka_new_py_dt / number:.4f}') - assert kuka_old_dt > kuka_new_dt + kuka_new_cpp_dt = timeit.timeit(_kuka_new_cpp_fk, number=number) + print(f'Kuka FK NEW C++ dt: {kuka_new_cpp_dt / number:.4f}') + assert kuka_old_dt > kuka_new_cpp_dt -if __name__ == '__main__': + +def main(): + # do an in-depth analysis of multiple models, devices, data types, batch sizes, etc. np.set_printoptions(precision=3, suppress=True, linewidth=220) torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) - test_val_fk_perf() - test_kuka_fk_perf() + chains = [ + pk.build_chain_from_mjcf(open('val.xml').read()), + pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool'), + pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7'), + ] + names = ['val', 'val_serial', 'kuka_iiwa'] + + devices = ['cpu', 'cuda'] + dtypes = [torch.float32, torch.float64] + batch_sizes = [1, 10, 100, 1_000, 10_000, 100_000] + + # iterate over all combinations and store in a pandas dataframe + headers = ['chain', 'device', 'dtype', 'batch_size', 'time'] + data = [] + + for chain, name in zip(chains, names): + for device in devices: + for dtype in dtypes: + for batch_size in batch_sizes: + chain = chain.to(dtype=dtype, device=device) + th = torch.zeros(batch_size, chain.n_joints).to(dtype=dtype, device=device) + + dt = timeit.timeit(lambda: chain.forward_kinematics(th), number=number) + data.append([name, device, dtype, batch_size, dt / number]) + print(f"{name=} {device=} {dtype=} {batch_size=} {dt / number:.4f}") + + # pickle the data for visualization in jupyter notebook + import pickle + with open('fk_perf.pkl', 'wb') as f: + pickle.dump([headers, data], f) + + +if __name__ == '__main__': + main() From 61b74ea79dfc39912c2626603b03b237c2fd2371 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 11:52:01 -0400 Subject: [PATCH 16/34] jupyter notebook to explore performance data --- src/pytorch_kinematics/chain.py | 91 --------- .../viz_fk_perf-checkpoint.ipynb | 89 +++++++++ tests/test_fk_perf.py | 88 +-------- tests/viz_fk_perf.ipynb | 176 ++++++++++++++++++ 4 files changed, 266 insertions(+), 178 deletions(-) create mode 100644 tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb create mode 100644 tests/viz_fk_perf.ipynb diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index a221877..72d5969 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -317,59 +317,6 @@ def forward_kinematics(self, th, frame_indices: Optional = None): return frame_names_and_transform3ds - def forward_kinematics_py(self, th, frame_indices: Optional = None): - if frame_indices is None: - frame_indices = self.get_all_frame_indices() - - th = self.ensure_tensor(th) - th = torch.atleast_2d(th) - - b = th.shape[0] - - axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) - - frame_transforms = {} - - # compute all joint transforms at once first - # in order to handle multiple joint types without branching, we create all possible transforms - # for all joint types and then select the appropriate one for each joint. - rev_jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) - pris_jnt_transform = tensor_axis_and_d_to_pris_matrix(axes_expanded, th) - - for frame_idx in frame_indices: - frame_transform = torch.eye(4).to(th).unsqueeze(0).repeat(b, 1, 1) - - # iterate down the list and compose the transform - for chain_idx in self.parents_indices[frame_idx]: - if chain_idx.item() in frame_transforms: - frame_transform = frame_transforms[chain_idx.item()] - else: - link_offset_i = self.link_offsets[chain_idx] - if link_offset_i is not None: - frame_transform = frame_transform @ link_offset_i - - joint_offset_i = self.joint_offsets[chain_idx] - if joint_offset_i is not None: - frame_transform = frame_transform @ joint_offset_i - - jnt_idx = self.joint_indices[chain_idx] - jnt_type = self.joint_type_indices[chain_idx] - if jnt_type == 0: - pass - elif jnt_type == 1: - jnt_transform_i = rev_jnt_transform[:, jnt_idx] - frame_transform = frame_transform @ jnt_transform_i - elif jnt_type == 2: - jnt_transform_i = pris_jnt_transform[:, jnt_idx] - frame_transform = frame_transform @ jnt_transform_i - - frame_transforms[frame_idx.item()] = frame_transform - - frame_names_and_transform3ds = {self.idx_to_frame[frame_idx]: tf.Transform3d(matrix=transform) for - frame_idx, transform in frame_transforms.items()} - - return frame_names_and_transform3ds - def ensure_tensor(self, th): """ Converts a number of possible types into a tensor. The order of the tensor is determined by the order @@ -502,18 +449,6 @@ def forward_kinematics(self, th, end_only: bool = True): else: return mat - def forward_kinematics_py(self, th, end_only: bool = True): - """ Like the base class, except `th` only needs to contain the joints in the SerialChain, not all joints. """ - frame_indices, th = self.convert_serial_inputs_to_chain_inputs(end_only, th) - - mat = super().forward_kinematics_py(th, frame_indices) - - if end_only: - return mat[self._serial_frames[-1].name] - else: - return mat - - def convert_serial_inputs_to_chain_inputs(self, end_only, th): if end_only: frame_indices = self.get_frame_indices(self._serial_frames[-1].name) @@ -534,29 +469,3 @@ def convert_serial_inputs_to_chain_inputs(self, end_only, th): if frame.joint.joint_type != 'fixed': th[jnt_idx] = partial_th_i return frame_indices, th - - def forward_kinematics_slow(self, th, world=None, end_only=True): - if world is None: - world = tf.Transform3d() - if world.dtype != self.dtype or world.device != self.device: - world = world.to(dtype=self.dtype, device=self.device, copy=True) - th, N = ensure_2d_tensor(th, self.dtype, self.device) - zeros = torch.zeros([N, 1], dtype=world.dtype, device=world.device) - - theta_idx = 0 - link_transforms = {} - trans = tf.Transform3d(matrix=world.get_matrix().repeat(N, 1, 1)) - for f in self._serial_frames: - if f.link.offset is not None: - trans = trans.compose(f.link.offset) - - if f.joint.joint_type == "fixed": # If fixed - trans = trans.compose(f.get_transform(zeros)) - else: - joint_transform = f.get_transform(th[:, theta_idx].view(N, 1)) - trans = trans.compose(joint_transform) - theta_idx += 1 - - link_transforms[f.link.name] = trans - - return link_transforms[self._serial_frames[-1].link.name] if end_only else link_transforms diff --git a/tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb b/tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb new file mode 100644 index 0000000..92efc80 --- /dev/null +++ b/tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb @@ -0,0 +1,89 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "ExecuteTime": { + "end_time": "2023-10-30T15:37:54.975496787Z", + "start_time": "2023-10-30T15:37:54.933122254Z" + } + }, + "outputs": [ + { + "ename": "ModuleNotFoundError", + "evalue": "No module named 'torch'", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mModuleNotFoundError\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[0;31m# Load the data\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 2\u001b[0;31m \u001b[0;32mimport\u001b[0m \u001b[0mtorch\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 3\u001b[0m \u001b[0;32mimport\u001b[0m \u001b[0mpickle\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 4\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 5\u001b[0m \u001b[0;32mwith\u001b[0m \u001b[0mopen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'fk_perf.pkl'\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m'rb'\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;32mas\u001b[0m \u001b[0mf\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;31mModuleNotFoundError\u001b[0m: No module named 'torch'" + ] + } + ], + "source": [ + "# Load the data\n", + "import torch\n", + "import pickle\n", + "\n", + "with open('fk_perf.pkl', 'rb') as f:\n", + " headers, data = pickle.load(f)\n", + "\n", + "import pandas as pd\n", + "df = pd.DataFrame(data, columns=headers)\n", + "\n", + "df" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "'/usr/bin/python3'" + ] + }, + "execution_count": 2, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "import sys\n", + "sys.executable\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/tests/test_fk_perf.py b/tests/test_fk_perf.py index 78830ea..c6d0f67 100644 --- a/tests/test_fk_perf.py +++ b/tests/test_fk_perf.py @@ -5,93 +5,6 @@ import pytorch_kinematics as pk import numpy as np -N = 10000 -number = 100 - - -def test_val_fk_correctness(): - val = pk.build_chain_from_mjcf(open('val.xml').read()) - val = val.to(dtype=torch.float32, device='cuda') - - th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') - - frame_indices = val.get_frame_indices('left_tool', 'right_tool') - t_py = val.forward_kinematics_py(th, frame_indices) - t_cpp = val.forward_kinematics(th, frame_indices) - l_py = t_py['left_tool'].get_matrix() - l_cpp = t_cpp['left_tool'].get_matrix() - r_py = t_py['right_tool'].get_matrix() - r_cpp = t_cpp['right_tool'].get_matrix() - - assert torch.allclose(l_py, l_cpp) - assert torch.allclose(r_py, r_cpp) - - -def test_val_fk_perf(): - val = pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool') - val = val.to(dtype=torch.float32, device='cuda') - - th = torch.zeros(N, 20, dtype=torch.float32, device='cuda') - - def _val_old_fk(): - tg = val.forward_kinematics_slow(th, end_only=True) - m = tg.get_matrix() - return m - - def _val_new_py_fk(): - tg = val.forward_kinematics_py(th, end_only=True) - m = tg.get_matrix() - return m - - def _val_new_cpp_fk(): - tg = val.forward_kinematics(th, end_only=True) - m = tg.get_matrix() - return m - - val_old_dt = timeit.timeit(_val_old_fk, number=number) - print(f'Val FK OLD dt: {val_old_dt / number:.4f}') - - val_new_py_dt = timeit.timeit(_val_new_py_fk, number=number) - print(f'Val FK NEW dt: {val_new_py_dt / number:.4f}') - - val_new_cpp_dt = timeit.timeit(_val_new_cpp_fk, number=number) - print(f'Val FK NEW C++ dt: {val_new_cpp_dt / number:.4f}') - - assert val_old_dt > val_new_cpp_dt - - -def test_kuka_fk_perf(): - kuka = pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7') - kuka = kuka.to(dtype=torch.float32, device='cuda') - - th = torch.zeros(N, 7, dtype=torch.float32, device='cuda') - - def _kuka_old_fk(): - tg = kuka.forward_kinematics_slow(th, end_only=True) - m = tg.get_matrix() - return m - - def _kuka_new_py_fk(): - tg = kuka.forward_kinematics_py(th, end_only=True) - m = tg.get_matrix() - return m - - def _kuka_new_cpp_fk(): - tg = kuka.forward_kinematics(th, end_only=True) - m = tg.get_matrix() - return m - - kuka_old_dt = timeit.timeit(_kuka_old_fk, number=number) - print(f'Kuka FK OLD dt: {kuka_old_dt / number:.4f}') - - kuka_new_py_dt = timeit.timeit(_kuka_new_py_fk, number=number) - print(f'Kuka FK NEW dt: {kuka_new_py_dt / number:.4f}') - - kuka_new_cpp_dt = timeit.timeit(_kuka_new_cpp_fk, number=number) - print(f'Kuka FK NEW C++ dt: {kuka_new_cpp_dt / number:.4f}') - - assert kuka_old_dt > kuka_new_cpp_dt - def main(): # do an in-depth analysis of multiple models, devices, data types, batch sizes, etc. @@ -108,6 +21,7 @@ def main(): devices = ['cpu', 'cuda'] dtypes = [torch.float32, torch.float64] batch_sizes = [1, 10, 100, 1_000, 10_000, 100_000] + number = 100 # iterate over all combinations and store in a pandas dataframe headers = ['chain', 'device', 'dtype', 'batch_size', 'time'] diff --git a/tests/viz_fk_perf.ipynb b/tests/viz_fk_perf.ipynb new file mode 100644 index 0000000..c2084a2 --- /dev/null +++ b/tests/viz_fk_perf.ipynb @@ -0,0 +1,176 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "ExecuteTime": { + "end_time": "2023-10-30T15:47:08.127357460Z", + "start_time": "2023-10-30T15:47:06.399148890Z" + } + }, + "outputs": [ + { + "data": { + "text/plain": " chain device dtype batch_size time\n0 val cpu torch.float32 1 0.001706\n1 val cpu torch.float32 10 0.001854\n2 val cpu torch.float32 100 0.002467\n3 val cpu torch.float32 1000 0.006334\n4 val cpu torch.float32 10000 0.024186\n.. ... ... ... ... ...\n67 kuka_iiwa cuda torch.float64 10 0.001017\n68 kuka_iiwa cuda torch.float64 100 0.001018\n69 kuka_iiwa cuda torch.float64 1000 0.001307\n70 kuka_iiwa cuda torch.float64 10000 0.005168\n71 kuka_iiwa cuda torch.float64 100000 0.048497\n\n[72 rows x 5 columns]", + "text/html": "

\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
chaindevicedtypebatch_sizetime
0valcputorch.float3210.001706
1valcputorch.float32100.001854
2valcputorch.float321000.002467
3valcputorch.float3210000.006334
4valcputorch.float32100000.024186
..................
67kuka_iiwacudatorch.float64100.001017
68kuka_iiwacudatorch.float641000.001018
69kuka_iiwacudatorch.float6410000.001307
70kuka_iiwacudatorch.float64100000.005168
71kuka_iiwacudatorch.float641000000.048497
\n

72 rows × 5 columns

\n
" + }, + "execution_count": 1, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Load the data\n", + "import torch\n", + "import pickle\n", + "\n", + "with open('fk_perf.pkl', 'rb') as f:\n", + " headers, data = pickle.load(f)\n", + "\n", + "import pandas as pd\n", + "df = pd.DataFrame(data, columns=headers)\n", + "\n", + "df" + ], + "id": "e9f94ff7deaec3f4" + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": { + "ExecuteTime": { + "end_time": "2023-10-30T15:49:47.362570884Z", + "start_time": "2023-10-30T15:49:46.906641952Z" + } + }, + "outputs": [ + { + "data": { + "text/plain": "" + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "text/plain": "
", + "image/png": "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" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Plot batch_size on the X axis and time on the Y axis, with a line for each chain, averaged over device and dtype.\n", + "import seaborn as sns\n", + "import matplotlib.pyplot as plt\n", + "\n", + "# make the X axis log scale\n", + "plt.xscale('log')\n", + "plt.yscale('log')\n", + "sns.lineplot(data=df, x='batch_size', y='time', hue='chain', errorbar=None)" + ], + "id": "2c1117400bd43e44" + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": { + "ExecuteTime": { + "end_time": "2023-10-30T15:50:59.675330801Z", + "start_time": "2023-10-30T15:50:59.556414795Z" + } + }, + "outputs": [ + { + "data": { + "text/plain": "" + }, + "execution_count": 8, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "text/plain": "
", + "image/png": "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" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# bar plot of the average time for each chain, averaged over everything else\n", + "sns.barplot(data=df, x='chain', y='time', errorbar=None)" + ], + "id": "f4922335aa20094e" + }, + { + "cell_type": "code", + "execution_count": 9, + "outputs": [ + { + "data": { + "text/plain": "" + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "text/plain": "
", + "image/png": "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" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# compare 32 to 64 bit\n", + "sns.barplot(data=df, x='dtype', y='time', errorbar=None)" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2023-10-30T15:51:25.097006215Z", + "start_time": "2023-10-30T15:51:24.992095665Z" + } + }, + "id": "4dc8bbcd3dea2f27" + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false + }, + "id": "bb738671a34e6c60" + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} From c62eaf2e586330262d15157c62a3b4a27198a296 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 11:52:49 -0400 Subject: [PATCH 17/34] gitignore --- .gitignore | 1 + .../viz_fk_perf-checkpoint.ipynb | 89 ------------------- 2 files changed, 1 insertion(+), 89 deletions(-) delete mode 100644 tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb diff --git a/.gitignore b/.gitignore index beab62e..9e2fb0c 100644 --- a/.gitignore +++ b/.gitignore @@ -8,3 +8,4 @@ dist # These are cloned/generated when testing with mujoco tests/MUJOCO_LOG.TXT tests/mujoco_menagerie/ +.ipynb_checkpoints diff --git a/tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb b/tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb deleted file mode 100644 index 92efc80..0000000 --- a/tests/.ipynb_checkpoints/viz_fk_perf-checkpoint.ipynb +++ /dev/null @@ -1,89 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 1, - "metadata": { - "ExecuteTime": { - "end_time": "2023-10-30T15:37:54.975496787Z", - "start_time": "2023-10-30T15:37:54.933122254Z" - } - }, - "outputs": [ - { - "ename": "ModuleNotFoundError", - "evalue": "No module named 'torch'", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mModuleNotFoundError\u001b[0m Traceback (most recent call last)", - "\u001b[0;32m\u001b[0m in \u001b[0;36m\u001b[0;34m\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[0;31m# Load the data\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 2\u001b[0;31m \u001b[0;32mimport\u001b[0m \u001b[0mtorch\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 3\u001b[0m \u001b[0;32mimport\u001b[0m \u001b[0mpickle\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 4\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 5\u001b[0m \u001b[0;32mwith\u001b[0m \u001b[0mopen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'fk_perf.pkl'\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m'rb'\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;32mas\u001b[0m \u001b[0mf\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;31mModuleNotFoundError\u001b[0m: No module named 'torch'" - ] - } - ], - "source": [ - "# Load the data\n", - "import torch\n", - "import pickle\n", - "\n", - "with open('fk_perf.pkl', 'rb') as f:\n", - " headers, data = pickle.load(f)\n", - "\n", - "import pandas as pd\n", - "df = pd.DataFrame(data, columns=headers)\n", - "\n", - "df" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "'/usr/bin/python3'" - ] - }, - "execution_count": 2, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "import sys\n", - "sys.executable\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.8.10" - } - }, - "nbformat": 4, - "nbformat_minor": 5 -} From 028cf029986c4927320c4a5bf0a4886c43b32551 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 11:56:56 -0400 Subject: [PATCH 18/34] viz --- .gitignore | 1 + tests/viz_fk_perf.ipynb | 26 ++++++++++++++------------ 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/.gitignore b/.gitignore index 9e2fb0c..31df576 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ .idea *.so +*.pkl *.egg-info __pycache__ temp* diff --git a/tests/viz_fk_perf.ipynb b/tests/viz_fk_perf.ipynb index c2084a2..aebc37f 100644 --- a/tests/viz_fk_perf.ipynb +++ b/tests/viz_fk_perf.ipynb @@ -2,20 +2,20 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, + "execution_count": 12, "metadata": { "ExecuteTime": { - "end_time": "2023-10-30T15:47:08.127357460Z", - "start_time": "2023-10-30T15:47:06.399148890Z" + "end_time": "2023-10-30T15:54:53.172705657Z", + "start_time": "2023-10-30T15:54:53.163263254Z" } }, "outputs": [ { "data": { - "text/plain": " chain device dtype batch_size time\n0 val cpu torch.float32 1 0.001706\n1 val cpu torch.float32 10 0.001854\n2 val cpu torch.float32 100 0.002467\n3 val cpu torch.float32 1000 0.006334\n4 val cpu torch.float32 10000 0.024186\n.. ... ... ... ... ...\n67 kuka_iiwa cuda torch.float64 10 0.001017\n68 kuka_iiwa cuda torch.float64 100 0.001018\n69 kuka_iiwa cuda torch.float64 1000 0.001307\n70 kuka_iiwa cuda torch.float64 10000 0.005168\n71 kuka_iiwa cuda torch.float64 100000 0.048497\n\n[72 rows x 5 columns]", - "text/html": "
\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
chaindevicedtypebatch_sizetime
0valcputorch.float3210.001706
1valcputorch.float32100.001854
2valcputorch.float321000.002467
3valcputorch.float3210000.006334
4valcputorch.float32100000.024186
..................
67kuka_iiwacudatorch.float64100.001017
68kuka_iiwacudatorch.float641000.001018
69kuka_iiwacudatorch.float6410000.001307
70kuka_iiwacudatorch.float64100000.005168
71kuka_iiwacudatorch.float641000000.048497
\n

72 rows × 5 columns

\n
" + "text/plain": " chain device dtype batch_size time time/batch\n0 val cpu torch.float32 1 0.001706 1.705588e-03\n1 val cpu torch.float32 10 0.001854 1.854159e-04\n2 val cpu torch.float32 100 0.002467 2.466516e-05\n3 val cpu torch.float32 1000 0.006334 6.334178e-06\n4 val cpu torch.float32 10000 0.024186 2.418595e-06\n.. ... ... ... ... ... ...\n67 kuka_iiwa cuda torch.float64 10 0.001017 1.016614e-04\n68 kuka_iiwa cuda torch.float64 100 0.001018 1.017745e-05\n69 kuka_iiwa cuda torch.float64 1000 0.001307 1.307084e-06\n70 kuka_iiwa cuda torch.float64 10000 0.005168 5.168081e-07\n71 kuka_iiwa cuda torch.float64 100000 0.048497 4.849671e-07\n\n[72 rows x 6 columns]", + "text/html": "
\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
chaindevicedtypebatch_sizetimetime/batch
0valcputorch.float3210.0017061.705588e-03
1valcputorch.float32100.0018541.854159e-04
2valcputorch.float321000.0024672.466516e-05
3valcputorch.float3210000.0063346.334178e-06
4valcputorch.float32100000.0241862.418595e-06
.....................
67kuka_iiwacudatorch.float64100.0010171.016614e-04
68kuka_iiwacudatorch.float641000.0010181.017745e-05
69kuka_iiwacudatorch.float6410000.0013071.307084e-06
70kuka_iiwacudatorch.float64100000.0051685.168081e-07
71kuka_iiwacudatorch.float641000000.0484974.849671e-07
\n

72 rows × 6 columns

\n
" }, - "execution_count": 1, + "execution_count": 12, "metadata": {}, "output_type": "execute_result" } @@ -31,17 +31,20 @@ "import pandas as pd\n", "df = pd.DataFrame(data, columns=headers)\n", "\n", + "# add a column that is the time divided by the batch size\n", + "df['time/batch'] = df['time'] / df['batch_size']\n", + "\n", "df" ], "id": "e9f94ff7deaec3f4" }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 10, "metadata": { "ExecuteTime": { - "end_time": "2023-10-30T15:49:47.362570884Z", - "start_time": "2023-10-30T15:49:46.906641952Z" + "end_time": "2023-10-30T15:53:26.027815315Z", + "start_time": "2023-10-30T15:53:25.589229733Z" } }, "outputs": [ @@ -49,14 +52,14 @@ "data": { "text/plain": "" }, - "execution_count": 6, + "execution_count": 10, "metadata": {}, "output_type": "execute_result" }, { "data": { "text/plain": "
", - "image/png": "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" + "image/png": "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" }, "metadata": {}, "output_type": "display_data" @@ -69,7 +72,6 @@ "\n", "# make the X axis log scale\n", "plt.xscale('log')\n", - "plt.yscale('log')\n", "sns.lineplot(data=df, x='batch_size', y='time', hue='chain', errorbar=None)" ], "id": "2c1117400bd43e44" From 0859d542ee61ae8879f5f46204740f9510106de5 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 12:00:54 -0400 Subject: [PATCH 19/34] cleanup --- tests/{test_fk_perf.py => gen_fk_perf.py} | 2 +- tests/test_kinematics.py | 12 +----------- 2 files changed, 2 insertions(+), 12 deletions(-) rename tests/{test_fk_perf.py => gen_fk_perf.py} (94%) diff --git a/tests/test_fk_perf.py b/tests/gen_fk_perf.py similarity index 94% rename from tests/test_fk_perf.py rename to tests/gen_fk_perf.py index c6d0f67..c1e2d01 100644 --- a/tests/test_fk_perf.py +++ b/tests/gen_fk_perf.py @@ -1,3 +1,4 @@ +""" Generate performance data for multiple models, devices, data types, batch sizes, etc. """ import timeit from time import perf_counter import torch @@ -7,7 +8,6 @@ def main(): - # do an in-depth analysis of multiple models, devices, data types, batch sizes, etc. np.set_printoptions(precision=3, suppress=True, linewidth=220) torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index f906cda..86822f4 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -1,7 +1,6 @@ -import os import math +import os -import numpy as np import torch import pytorch_kinematics as pk @@ -9,15 +8,6 @@ TEST_DIR = os.path.dirname(__file__) -def mat_to_rr_tf3d(frame_transform): - import rerun as rr - frame_transform = torch.squeeze(frame_transform).cpu().numpy() - pos = frame_transform[:3, 3] - rot = frame_transform[:3, :3] - rr_tf3d = rr.Transform3D(translation=pos, mat3x3=rot) - return rr_tf3d - - def quat_pos_from_transform3d(tg): m = tg.get_matrix() pos = m[:, :3, 3] From e2909b641bc42237faef9e1503bf37291eac9dee Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 12:12:35 -0400 Subject: [PATCH 20/34] adjust serial vs parallel test --- tests/test_kinematics.py | 32 ++++++++++++++++++-------------- 1 file changed, 18 insertions(+), 14 deletions(-) diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 86822f4..c9a9199 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -1,4 +1,5 @@ import math +from timeit import timeit import os import torch @@ -127,21 +128,24 @@ def test_urdf_serial(): th_batch = torch.rand(N, len(chain.get_joint_parameter_names()), dtype=dtype, device=d) chain = chain.to(dtype=dtype, device=d) - import time - start = time.time() - tg_batch = chain.forward_kinematics(th_batch) - m = tg_batch.get_matrix() - elapsed = time.time() - start - print("elapsed {}s for N={} when parallel".format(elapsed, N)) + number = 10 - start = time.time() - elapsed = 0 - for i in range(N): - tg = chain.forward_kinematics(th_batch[i]) - elapsed += time.time() - start - start = time.time() - assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) - print("elapsed {}s for N={} when serial".format(elapsed, N)) + def _fk_parallel(): + tg_batch = chain.forward_kinematics(th_batch) + m = tg_batch.get_matrix() + + dt_parallel = timeit(_fk_parallel, number=number) / number + print("elapsed {}s for N={} when parallel".format(dt_parallel, N)) + + def _fk_serial(): + for i in range(N): + tg = chain.forward_kinematics(th_batch[i]) + m = tg.get_matrix() + + dt_serial = timeit(_fk_serial, number=number) / number + print("elapsed {}s for N={} when serial".format(dt_serial, N)) + + # assert torch.allclose(tg.get_matrix().view(4, 4), m[i]) # test robot with prismatic and fixed joints From 4385a64925258d6204a64b05e4b1fcd1532d40fc Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 30 Oct 2023 16:19:47 -0400 Subject: [PATCH 21/34] fix tests --- tests/test_menagerie.py | 2 +- tests/test_rotation_conversions.py | 5 ++-- tests/viz_fk_perf.ipynb | 46 ++++++++++++++++-------------- 3 files changed, 29 insertions(+), 24 deletions(-) diff --git a/tests/test_menagerie.py b/tests/test_menagerie.py index bab88d2..6d7ae4b 100644 --- a/tests/test_menagerie.py +++ b/tests/test_menagerie.py @@ -44,7 +44,7 @@ def test_menagerie(): print(f"\t {chain.get_frame_names()}") print(f"\t {chain.get_joint_parameter_names()}") th = np.zeros(len(chain.get_joint_parameter_names())) - fk_dict = chain.forward_kinematics(th, end_only=True) + fk_dict = chain.forward_kinematics(th) if __name__ == '__main__': diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 6b2fc7f..6cc7c90 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -11,8 +11,9 @@ def test_axis_angle_to_matrix_perf(): number = 100 N = 1_000 - axis_angle = torch.randn([N, 3], device='cuda', dtype=torch.float64) - axis_1d = torch.tensor([1., 0, 0], device='cuda', dtype=torch.float64) # in the FK code this is NOT batched! + device = 'cuda' if torch.cuda.is_available() else 'cpu' + axis_angle = torch.randn([N, 3], device=device, dtype=torch.float64) + axis_1d = torch.tensor([1., 0, 0], device=device, dtype=torch.float64) # in the FK code this is NOT batched! theta = axis_angle.norm(dim=1, keepdim=True) dt1 = timeit.timeit(lambda: axis_angle_to_matrix(axis_angle), number=number) diff --git a/tests/viz_fk_perf.ipynb b/tests/viz_fk_perf.ipynb index aebc37f..6114825 100644 --- a/tests/viz_fk_perf.ipynb +++ b/tests/viz_fk_perf.ipynb @@ -2,11 +2,11 @@ "cells": [ { "cell_type": "code", - "execution_count": 12, + "execution_count": 13, "metadata": { "ExecuteTime": { - "end_time": "2023-10-30T15:54:53.172705657Z", - "start_time": "2023-10-30T15:54:53.163263254Z" + "end_time": "2023-10-30T16:15:27.994729591Z", + "start_time": "2023-10-30T16:15:27.993707047Z" } }, "outputs": [ @@ -15,7 +15,7 @@ "text/plain": " chain device dtype batch_size time time/batch\n0 val cpu torch.float32 1 0.001706 1.705588e-03\n1 val cpu torch.float32 10 0.001854 1.854159e-04\n2 val cpu torch.float32 100 0.002467 2.466516e-05\n3 val cpu torch.float32 1000 0.006334 6.334178e-06\n4 val cpu torch.float32 10000 0.024186 2.418595e-06\n.. ... ... ... ... ... ...\n67 kuka_iiwa cuda torch.float64 10 0.001017 1.016614e-04\n68 kuka_iiwa cuda torch.float64 100 0.001018 1.017745e-05\n69 kuka_iiwa cuda torch.float64 1000 0.001307 1.307084e-06\n70 kuka_iiwa cuda torch.float64 10000 0.005168 5.168081e-07\n71 kuka_iiwa cuda torch.float64 100000 0.048497 4.849671e-07\n\n[72 rows x 6 columns]", "text/html": "
\n\n\n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n \n
chaindevicedtypebatch_sizetimetime/batch
0valcputorch.float3210.0017061.705588e-03
1valcputorch.float32100.0018541.854159e-04
2valcputorch.float321000.0024672.466516e-05
3valcputorch.float3210000.0063346.334178e-06
4valcputorch.float32100000.0241862.418595e-06
.....................
67kuka_iiwacudatorch.float64100.0010171.016614e-04
68kuka_iiwacudatorch.float641000.0010181.017745e-05
69kuka_iiwacudatorch.float6410000.0013071.307084e-06
70kuka_iiwacudatorch.float64100000.0051685.168081e-07
71kuka_iiwacudatorch.float641000000.0484974.849671e-07
\n

72 rows × 6 columns

\n
" }, - "execution_count": 12, + "execution_count": 13, "metadata": {}, "output_type": "execute_result" } @@ -40,11 +40,11 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 14, "metadata": { "ExecuteTime": { - "end_time": "2023-10-30T15:53:26.027815315Z", - "start_time": "2023-10-30T15:53:25.589229733Z" + "end_time": "2023-10-30T16:15:28.606199427Z", + "start_time": "2023-10-30T16:15:27.993916371Z" } }, "outputs": [ @@ -52,14 +52,14 @@ "data": { "text/plain": "" }, - "execution_count": 10, + "execution_count": 14, "metadata": {}, "output_type": "execute_result" }, { "data": { "text/plain": "
", - "image/png": "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" + "image/png": "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" }, "metadata": {}, "output_type": "display_data" @@ -78,11 +78,11 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 15, "metadata": { "ExecuteTime": { - "end_time": "2023-10-30T15:50:59.675330801Z", - "start_time": "2023-10-30T15:50:59.556414795Z" + "end_time": "2023-10-30T16:15:28.712570761Z", + "start_time": "2023-10-30T16:15:28.600077822Z" } }, "outputs": [ @@ -90,14 +90,14 @@ "data": { "text/plain": "" }, - "execution_count": 8, + "execution_count": 15, "metadata": {}, "output_type": "execute_result" }, { "data": { "text/plain": "
", - "image/png": "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" + "image/png": "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" }, "metadata": {}, "output_type": "display_data" @@ -111,20 +111,20 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 16, "outputs": [ { "data": { "text/plain": "" }, - "execution_count": 9, + "execution_count": 16, "metadata": {}, "output_type": "execute_result" }, { "data": { "text/plain": "
", - "image/png": "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" + "image/png": "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" }, "metadata": {}, "output_type": "display_data" @@ -137,19 +137,23 @@ "metadata": { "collapsed": false, "ExecuteTime": { - "end_time": "2023-10-30T15:51:25.097006215Z", - "start_time": "2023-10-30T15:51:24.992095665Z" + "end_time": "2023-10-30T16:15:28.833907900Z", + "start_time": "2023-10-30T16:15:28.739415909Z" } }, "id": "4dc8bbcd3dea2f27" }, { "cell_type": "code", - "execution_count": null, + "execution_count": 16, "outputs": [], "source": [], "metadata": { - "collapsed": false + "collapsed": false, + "ExecuteTime": { + "end_time": "2023-10-30T16:15:28.880353691Z", + "start_time": "2023-10-30T16:15:28.833655934Z" + } }, "id": "bb738671a34e6c60" } From 12460889b136b06d3680bee5626b0ff50f937f8a Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 2 Nov 2023 14:39:27 -0400 Subject: [PATCH 22/34] testing torch.compile --- pyproject.toml | 2 +- src/pytorch_kinematics/chain.py | 53 +++++++++++++++++++++++++++++++++ tests/gen_fk_perf.py | 23 ++++++++++---- tests/test_kinematics.py | 29 ++++++++++++++++-- 4 files changed, 98 insertions(+), 9 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 2613289..b65a7b6 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -71,5 +71,5 @@ mujoco = ["mujoco"] [build-system] # Including torch and ninja here are needed to build the native code. # They will be installed as dependencies during the build, which can take a while the first time. -requires = ["setuptools>=60.0.0", "wheel", "torch", "ninja"] +requires = ["setuptools>=60.0.0", "wheel", "torch==2.1.0", "ninja"] build-backend= "setuptools.build_meta" diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 72d5969..8f995b2 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -123,6 +123,7 @@ def __init__(self, root_frame, dtype=torch.float32, device="cpu"): idx += 1 self.joint_type_indices = torch.tensor(self.joint_type_indices) self.joint_indices = torch.tensor(self.joint_indices) + # We need to use a dict because torch.compile doesn't list lists of tensors self.parents_indices = [torch.tensor(p, dtype=torch.long, device=self.device) for p in self.parents_indices] def to(self, dtype=None, device=None): @@ -317,6 +318,58 @@ def forward_kinematics(self, th, frame_indices: Optional = None): return frame_names_and_transform3ds + def forward_kinematics_py(self, th, frame_indices: Optional = None): + if frame_indices is None: + frame_indices = self.get_all_frame_indices() + + th = self.ensure_tensor(th) + th = torch.atleast_2d(th) + + b = th.shape[0] + axes_expanded = self.axes.unsqueeze(0).repeat(b, 1, 1) + + # compute all joint transforms at once first + # in order to handle multiple joint types without branching, we create all possible transforms + # for all joint types and then select the appropriate one for each joint. + rev_jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) + pris_jnt_transform = tensor_axis_and_d_to_pris_matrix(axes_expanded, th) + + frame_transforms = {} + b = th.shape[0] + for frame_idx in frame_indices: + frame_transform = torch.eye(4).to(th).unsqueeze(0).repeat(b, 1, 1) + + # iterate down the list and compose the transform + for chain_idx in self.parents_indices[frame_idx.item()]: + if chain_idx.item() in frame_transforms: + frame_transform = frame_transforms[chain_idx.item()] + else: + link_offset_i = self.link_offsets[chain_idx] + if link_offset_i is not None: + frame_transform = frame_transform @ link_offset_i + + joint_offset_i = self.joint_offsets[chain_idx] + if joint_offset_i is not None: + frame_transform = frame_transform @ joint_offset_i + + jnt_idx = self.joint_indices[chain_idx] + jnt_type = self.joint_type_indices[chain_idx] + if jnt_type == 0: + pass + elif jnt_type == 1: + jnt_transform_i = rev_jnt_transform[:, jnt_idx] + frame_transform = frame_transform @ jnt_transform_i + elif jnt_type == 2: + jnt_transform_i = pris_jnt_transform[:, jnt_idx] + frame_transform = frame_transform @ jnt_transform_i + + frame_transforms[frame_idx.item()] = frame_transform + + frame_names_and_transform3ds = {self.idx_to_frame[frame_idx]: tf.Transform3d(matrix=transform) for + frame_idx, transform in frame_transforms.items()} + + return frame_names_and_transform3ds + def ensure_tensor(self, th): """ Converts a number of possible types into a tensor. The order of the tensor is determined by the order diff --git a/tests/gen_fk_perf.py b/tests/gen_fk_perf.py index c1e2d01..b509f68 100644 --- a/tests/gen_fk_perf.py +++ b/tests/gen_fk_perf.py @@ -24,19 +24,30 @@ def main(): number = 100 # iterate over all combinations and store in a pandas dataframe - headers = ['chain', 'device', 'dtype', 'batch_size', 'time'] + headers = ['method', 'chain', 'device', 'dtype', 'batch_size', 'time'] data = [] + def _fk_cpp(th): + return chain.forward_kinematics(th) + + @torch.compile(backend='eager') + def _fk_torch_compile(th): + return chain.forward_kinematics_py(th) + + method_names = ['fk_cpp', 'fk_torch_compile'] + methods = [_fk_cpp, _fk_torch_compile] + for chain, name in zip(chains, names): for device in devices: for dtype in dtypes: for batch_size in batch_sizes: - chain = chain.to(dtype=dtype, device=device) - th = torch.zeros(batch_size, chain.n_joints).to(dtype=dtype, device=device) + for method_name, method in zip(method_names, methods): + chain = chain.to(dtype=dtype, device=device) + th = torch.zeros(batch_size, chain.n_joints).to(dtype=dtype, device=device) - dt = timeit.timeit(lambda: chain.forward_kinematics(th), number=number) - data.append([name, device, dtype, batch_size, dt / number]) - print(f"{name=} {device=} {dtype=} {batch_size=} {dt / number:.4f}") + dt = timeit.timeit(lambda: method(th), number=number) + data.append([name, device, dtype, batch_size, dt / number]) + print(f"{method_name} {name=} {device=} {dtype=} {batch_size=} {dt / number:.4f}") # pickle the data for visualization in jupyter notebook import pickle diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index c9a9199..37dc6dd 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -255,9 +255,34 @@ def test_mjcf_slide_joint_parsing(): def test_fk_val(): + dtype = torch.float64 + d = "cuda" if torch.cuda.is_available() else "cpu" + chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read()) - chain = chain.to(dtype=torch.float64) - ret = chain.forward_kinematics(torch.zeros([1000, chain.n_joints], dtype=torch.float64)) + chain = chain.to(dtype=torch.float64, device=d) + + th = torch.rand(1000, chain.n_joints, dtype=dtype, device=d) + + def _fk_no_compile(): + return chain.forward_kinematics_py(th) + + @torch.compile(backend='inductor') + def _fk_compile(): + return chain.forward_kinematics_py(th) + + from timeit import timeit + + # warmup + _fk_no_compile() + _fk_compile() + + number = 10 + ms_no_compile = timeit(_fk_no_compile, number=number) / number * 1000 + print(f"elapsed {ms_no_compile:.1f}ms for no compile") + ms_compile = timeit(_fk_compile, number=number) / number * 1000 + print(f"elapsed {ms_compile:.1f}ms for compile") + + ret = chain.forward_kinematics_py(th) tg = ret['drive45'] pos, rot = quat_pos_from_transform3d(tg) torch.set_printoptions(precision=6, sci_mode=False) From 595247e0dee79b86bef821f2b9994360140f728e Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 2 Nov 2023 16:39:32 -0400 Subject: [PATCH 23/34] remove C++ for portability/compatibility --- pyproject.toml | 2 +- setup.py | 14 ---- src/pytorch_kinematics/chain.py | 37 ---------- src/zpk_cpp/pk.cpp | 107 ----------------------------- tests/test_kinematics.py | 29 +------- tests/test_rotation_conversions.py | 1 - 6 files changed, 3 insertions(+), 187 deletions(-) delete mode 100644 setup.py delete mode 100644 src/zpk_cpp/pk.cpp diff --git a/pyproject.toml b/pyproject.toml index b65a7b6..67c1e4c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -71,5 +71,5 @@ mujoco = ["mujoco"] [build-system] # Including torch and ninja here are needed to build the native code. # They will be installed as dependencies during the build, which can take a while the first time. -requires = ["setuptools>=60.0.0", "wheel", "torch==2.1.0", "ninja"] +requires = ["setuptools>=60.0.0", "wheel"] build-backend= "setuptools.build_meta" diff --git a/setup.py b/setup.py deleted file mode 100644 index 7aba117..0000000 --- a/setup.py +++ /dev/null @@ -1,14 +0,0 @@ -from setuptools import setup, find_packages -from torch.utils import cpp_extension - -# This is needed in order to build the C++ extension -import torch -ext = cpp_extension.CppExtension('zpk_cpp', ['src/zpk_cpp/pk.cpp'], extra_compile_args=['-std=c++17']) -setup_args = dict( - packages=find_packages(where="src"), - package_dir={"": "src"}, - ext_modules=[ext], - cmdclass={'build_ext': cpp_extension.BuildExtension}, -) - -setup(**setup_args) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 8f995b2..7debc55 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -281,44 +281,7 @@ def get_link_names(self): def get_frame_indices(self, *frame_names): return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long, device=self.device) - def forward_kinematics(self, th, frame_indices: Optional = None): - """ - Compute forward kinematics. - - Args: - th: A dict, list, numpy array, or torch tensor of ALL joints values. Possibly batched. - the fastest thing to use is a torch tensor, all other types get converted to that. - If any joint values are missing, an exception will be thrown. - frame_indices: A list of frame indices to compute forward kinematics for. If None, all frames are computed. - - Returns: - A dict of frame names and their corresponding Transform3d objects. - """ - if frame_indices is None: - frame_indices = self.get_all_frame_indices() - - th = self.ensure_tensor(th) - th = torch.atleast_2d(th) - - import zpk_cpp - frame_transforms = zpk_cpp.fk( - frame_indices, - self.axes, - th, - self.parents_indices, - self.joint_type_indices, - self.joint_indices, - self.joint_offsets, - self.link_offsets - ) - - frame_names_and_transform3ds = {self.idx_to_frame[frame_idx]: tf.Transform3d(matrix=transform) for - frame_idx, transform in frame_transforms.items()} - - return frame_names_and_transform3ds - - def forward_kinematics_py(self, th, frame_indices: Optional = None): if frame_indices is None: frame_indices = self.get_all_frame_indices() diff --git a/src/zpk_cpp/pk.cpp b/src/zpk_cpp/pk.cpp deleted file mode 100644 index 24c0182..0000000 --- a/src/zpk_cpp/pk.cpp +++ /dev/null @@ -1,107 +0,0 @@ -#include - -#include -#include - -using namespace torch::indexing; - -torch::Tensor axis_and_d_to_pris_matrix(torch::Tensor axis, torch::Tensor d) { - /** - * axis is [b, n, 3] - * d is [b, n] - * - * Output is [b, n, 4, 4] - */ - auto b = axis.size(0); - auto n = axis.size(1); - auto mat44 = torch::eye(4).to(axis).repeat({b, n, 1, 1}); - auto pos = axis * d.unsqueeze(-1); - mat44.index_put_({Ellipsis, Slice(0, 3), 3}, pos); - return mat44; -} - -torch::Tensor axis_and_angle_to_matrix(torch::Tensor axis, torch::Tensor theta) { - /** - * cos is not that precise for float32, you may want to use float64 - * axis is [b, n, 3] - * theta is [b, n] - * Return is [b, n, 4, 4] - */ - auto b = axis.size(0); - auto n = axis.size(1); - auto m = torch::eye(4).to(axis).unsqueeze(0).unsqueeze(0).repeat({b, n, 1, 1}); - - auto kx = axis.index({Ellipsis, 0}); - auto ky = axis.index({Ellipsis, 1}); - auto kz = axis.index({Ellipsis, 2}); - auto c = theta.cos(); - auto one_minus_c = 1 - c; - auto s = theta.sin(); - auto kxs = kx * s; - auto kys = ky * s; - auto kzs = kz * s; - auto kxky = kx * ky; - auto kxkz = kx * kz; - auto kykz = ky * kz; - m.index_put_({Ellipsis, 0, 0}, c + kx * kx * one_minus_c); - m.index_put_({Ellipsis, 0, 1}, kxky * one_minus_c - kzs); - m.index_put_({Ellipsis, 0, 2}, kxkz * one_minus_c + kys); - m.index_put_({Ellipsis, 1, 0}, kxky * one_minus_c + kzs); - m.index_put_({Ellipsis, 1, 1}, c + ky * ky * one_minus_c); - m.index_put_({Ellipsis, 1, 2}, kykz * one_minus_c - kxs); - m.index_put_({Ellipsis, 2, 0}, kxkz * one_minus_c - kys); - m.index_put_({Ellipsis, 2, 1}, kykz * one_minus_c + kxs); - m.index_put_({Ellipsis, 2, 2}, c + kz * kz * one_minus_c); - return m; -} - -std::map fk(torch::Tensor frame_indices, torch::Tensor axes, torch::Tensor th, - std::vector parents_indices, torch::Tensor joint_type_indices, - torch::Tensor joint_indices, std::vector> joint_offsets, - std::vector> link_offsets) { - std::map frame_transforms; - - auto const b = th.size(0); - auto const axes_expanded = axes.unsqueeze(0).repeat({b, 1, 1}); - - auto const rev_jnt_transform = axis_and_angle_to_matrix(axes_expanded, th); - auto const pris_jnt_transform = axis_and_d_to_pris_matrix(axes_expanded, th); - - for (int64_t i = 0; i < frame_indices.size(0); i++) { - auto const frame_idx = frame_indices[i].item(); - auto frame_transform = torch::eye(4).to(th).unsqueeze(0).expand({b, 4, 4}); - - auto const parent_indices = parents_indices[frame_idx]; - for (int64_t j = 0; j < parent_indices.size(0); j++) { - auto const chain_idx_tensor = parent_indices[j]; - int64_t chain_idx_int = chain_idx_tensor.item(); - if (frame_transforms.find(chain_idx_int) != frame_transforms.end()) { - frame_transform = frame_transforms[chain_idx_int]; - } else { - auto const link_offset_i = link_offsets[chain_idx_int]; - if (link_offset_i) { - frame_transform = frame_transform.matmul(*link_offset_i); - } - - auto const joint_offset_i = joint_offsets[chain_idx_int]; - if (joint_offset_i) { - frame_transform = frame_transform.matmul(*joint_offset_i); - } - - auto const jnt_idx = joint_indices.index({chain_idx_tensor}).item(); - auto const jnt_type = joint_type_indices.index({chain_idx_tensor}).item(); - if (jnt_type == 1) { - auto const jnt_transform_i = rev_jnt_transform.index({Slice(), jnt_idx}); - frame_transform = frame_transform.matmul(jnt_transform_i); - } else if (jnt_type == 2) { - auto const jnt_transform_i = pris_jnt_transform.index({Slice(), jnt_idx}); - frame_transform = frame_transform.matmul(jnt_transform_i); - } - } - } - frame_transforms.emplace(frame_idx, frame_transform); - } - return frame_transforms; -} - -PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { m.def("fk", &fk, "fk"); } diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 37dc6dd..c9a9199 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -255,34 +255,9 @@ def test_mjcf_slide_joint_parsing(): def test_fk_val(): - dtype = torch.float64 - d = "cuda" if torch.cuda.is_available() else "cpu" - chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read()) - chain = chain.to(dtype=torch.float64, device=d) - - th = torch.rand(1000, chain.n_joints, dtype=dtype, device=d) - - def _fk_no_compile(): - return chain.forward_kinematics_py(th) - - @torch.compile(backend='inductor') - def _fk_compile(): - return chain.forward_kinematics_py(th) - - from timeit import timeit - - # warmup - _fk_no_compile() - _fk_compile() - - number = 10 - ms_no_compile = timeit(_fk_no_compile, number=number) / number * 1000 - print(f"elapsed {ms_no_compile:.1f}ms for no compile") - ms_compile = timeit(_fk_compile, number=number) / number * 1000 - print(f"elapsed {ms_compile:.1f}ms for compile") - - ret = chain.forward_kinematics_py(th) + chain = chain.to(dtype=torch.float64) + ret = chain.forward_kinematics(torch.zeros([1000, chain.n_joints], dtype=torch.float64)) tg = ret['drive45'] pos, rot = quat_pos_from_transform3d(tg) torch.set_printoptions(precision=6, sci_mode=False) diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 6cc7c90..6fd3599 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -4,7 +4,6 @@ from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix, axis_angle_to_matrix, \ pos_rot_to_matrix, matrix_to_pos_rot, random_rotations -import zpk_cpp def test_axis_angle_to_matrix_perf(): From 5794eb54a99906eacef88765c9f431d9e4c4c089 Mon Sep 17 00:00:00 2001 From: Peter Mitrano Date: Fri, 3 Nov 2023 12:09:08 -0400 Subject: [PATCH 24/34] Update src/pytorch_kinematics/transforms/rotation_conversions.py Co-authored-by: Tom Power --- src/pytorch_kinematics/transforms/rotation_conversions.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index dcc0ad4..bf75f98 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -497,8 +497,8 @@ def tensor_axis_and_angle_to_matrix(axis, theta): torch.stack([r10, r11, r12], -1), torch.stack([r20, r21, r22], -1)], -2) batch_shape = axis.shape[:-1] - mat44 = torch.eye(4, device=axis.device, dtype=axis.dtype).repeat(*batch_shape, 1, 1) - mat44[..., :3, :3] = rot + mat44 = torch.cat((rot, torch.zeros(*batch_shape, 3, 1).to(axis)), -1) + mat44 = torch.cat((mat44, torch.tensor([0.0, 0.0, 0.0, 1.0]).expand(*batch_shape, 1, 4).to(axis)), -2) return mat44 From b21e7c816c1fec9c990f62934b54cca8955eae52 Mon Sep 17 00:00:00 2001 From: Peter Mitrano Date: Fri, 3 Nov 2023 12:09:15 -0400 Subject: [PATCH 25/34] Update src/pytorch_kinematics/transforms/rotation_conversions.py Co-authored-by: Tom Power --- src/pytorch_kinematics/transforms/rotation_conversions.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index bf75f98..3098ed1 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -462,9 +462,10 @@ def tensor_axis_and_d_to_pris_matrix(axis, d): """ batch_axes = axis.shape[:-1] - mat44 = torch.eye(4).to(axis).repeat(*batch_axes, 1, 1) - pos = axis * d[..., None] - mat44[..., :3, 3] = pos + mat33 = torch.eye(3).to(axis).expand(*batch_axes, 3, 3) + pos = axis * d.unsqueeze(-1) + mat44 = torch.cat((mat33, pos.unsqueeze(-1)), -1) + mat44 = torch.cat((mat44, torch.tensor([0.0, 0.0, 0.0, 1.0]).expand(*batch_axes, 1, 4).to(axis)), -2) return mat44 From 1951e74ac547a56184de6f8f59c6823a28f3ae67 Mon Sep 17 00:00:00 2001 From: Peter Date: Fri, 3 Nov 2023 12:09:02 -0400 Subject: [PATCH 26/34] fix timing test --- src/pytorch_kinematics/chain.py | 4 ++-- tests/test_kinematics.py | 7 +++++++ 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 7debc55..9ccc842 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -279,8 +279,8 @@ def get_link_names(self): @lru_cache def get_frame_indices(self, *frame_names): - return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long, - device=self.device) + return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long, device=self.device) + def forward_kinematics(self, th, frame_indices: Optional = None): if frame_indices is None: frame_indices = self.get_all_frame_indices() diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index c9a9199..427b556 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -115,6 +115,7 @@ def test_urdf_serial(): print(chain) print(chain.get_joint_parameter_names()) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] + ret = chain.forward_kinematics(th, end_only=False) tg = ret['lbr_iiwa_link_7'] pos, rot = quat_pos_from_transform3d(tg) @@ -126,8 +127,14 @@ def test_urdf_serial(): dtype = torch.float64 th_batch = torch.rand(N, len(chain.get_joint_parameter_names()), dtype=dtype, device=d) + chain = chain.to(dtype=dtype, device=d) + # NOTE: Warmstart since pytorch can be slow the first time you run it + # this has to be done after you move it to the GPU. Otherwise the timing isn't representative. + for _ in range(5): + ret = chain.forward_kinematics(th) + number = 10 def _fk_parallel(): From 81f2caff9753cfd33081fb4175472c9feffad0e3 Mon Sep 17 00:00:00 2001 From: Peter Date: Fri, 3 Nov 2023 12:20:20 -0400 Subject: [PATCH 27/34] address review comments --- src/pytorch_kinematics/transforms/__init__.py | 6 ++-- .../transforms/rotation_conversions.py | 2 ++ tests/gen_fk_perf.py | 33 +++++++------------ tests/test_kinematics.py | 20 +++-------- 4 files changed, 22 insertions(+), 39 deletions(-) diff --git a/src/pytorch_kinematics/transforms/__init__.py b/src/pytorch_kinematics/transforms/__init__.py index 98cc434..1015cb5 100644 --- a/src/pytorch_kinematics/transforms/__init__.py +++ b/src/pytorch_kinematics/transforms/__init__.py @@ -4,10 +4,10 @@ axis_and_angle_to_matrix, axis_angle_to_quaternion, euler_angles_to_matrix, + matrix_to_axis_angle, matrix_to_euler_angles, matrix_to_quaternion, matrix_to_rotation_6d, - matrix_to_axis_angle, quaternion_apply, quaternion_invert, quaternion_multiply, @@ -18,8 +18,10 @@ random_rotations, rotation_6d_to_matrix, standardize_quaternion, + tensor_axis_and_angle_to_matrix, + tensor_axis_and_d_to_pris_matrix, + wxyz_to_xyzw, xyzw_to_wxyz, - wxyz_to_xyzw ) from .so3 import ( so3_exp_map, diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 3098ed1..7e22db5 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -452,6 +452,7 @@ def quaternion_apply(quaternion, point): def tensor_axis_and_d_to_pris_matrix(axis, d): """ + Creates a 4x4 matrix that represents a translation along an axis of a distance d Works with any number of batch dimensions. Args: @@ -471,6 +472,7 @@ def tensor_axis_and_d_to_pris_matrix(axis, d): def tensor_axis_and_angle_to_matrix(axis, theta): """ + Creates a 4x4 matrix that represents a rotation around an axis by an angle theta. Works with any number of batch dimensions. Args: diff --git a/tests/gen_fk_perf.py b/tests/gen_fk_perf.py index b509f68..334abad 100644 --- a/tests/gen_fk_perf.py +++ b/tests/gen_fk_perf.py @@ -11,12 +11,11 @@ def main(): np.set_printoptions(precision=3, suppress=True, linewidth=220) torch.set_printoptions(precision=3, sci_mode=False, linewidth=220) - chains = [ - pk.build_chain_from_mjcf(open('val.xml').read()), - pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool'), - pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7'), - ] - names = ['val', 'val_serial', 'kuka_iiwa'] + chains = { + 'val': pk.build_chain_from_mjcf(open('val.xml').read()), + 'val_serial': pk.build_serial_chain_from_mjcf(open('val.xml').read(), end_link_name='left_tool'), + 'kuka_iiwa': pk.build_serial_chain_from_urdf(open('kuka_iiwa.urdf').read(), end_link_name='lbr_iiwa_link_7'), + } devices = ['cpu', 'cuda'] dtypes = [torch.float32, torch.float64] @@ -27,27 +26,19 @@ def main(): headers = ['method', 'chain', 'device', 'dtype', 'batch_size', 'time'] data = [] - def _fk_cpp(th): + def _fk(th): return chain.forward_kinematics(th) - @torch.compile(backend='eager') - def _fk_torch_compile(th): - return chain.forward_kinematics_py(th) - - method_names = ['fk_cpp', 'fk_torch_compile'] - methods = [_fk_cpp, _fk_torch_compile] - - for chain, name in zip(chains, names): + for name, chain in chains.items(): for device in devices: for dtype in dtypes: for batch_size in batch_sizes: - for method_name, method in zip(method_names, methods): - chain = chain.to(dtype=dtype, device=device) - th = torch.zeros(batch_size, chain.n_joints).to(dtype=dtype, device=device) + chain = chain.to(dtype=dtype, device=device) + th = torch.zeros(batch_size, chain.n_joints).to(dtype=dtype, device=device) - dt = timeit.timeit(lambda: method(th), number=number) - data.append([name, device, dtype, batch_size, dt / number]) - print(f"{method_name} {name=} {device=} {dtype=} {batch_size=} {dt / number:.4f}") + dt = timeit.timeit(lambda: _fk(th), number=number) + data.append([name, device, dtype, batch_size, dt / number]) + print(f"{name=} {device=} {dtype=} {batch_size=} {dt / number:.4f}") # pickle the data for visualization in jupyter notebook import pickle diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 427b556..d7444bb 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -27,16 +27,9 @@ def test_fk_mjcf(): chain = chain.to(dtype=torch.float64) print(chain) print(chain.get_joint_parameter_names()) - th = { - 'hip_1': 1.0, - 'ankle_1': 1, - 'hip_2': 0.0, - 'ankle_2': 0.0, - 'hip_3': 0.0, - 'ankle_3': 0.0, - 'hip_4': 0.0, - 'ankle_4': 0.0, - } + + th = {joint: 0.0 for joint in chain.get_joint_parameter_names()} + th.update({'hip_1': 1.0, 'ankle_1': 1}) ret = chain.forward_kinematics(th) tg = ret['aux_1'] pos, rot = quat_pos_from_transform3d(tg) @@ -173,12 +166,7 @@ def test_fk_simple_arm(): assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) N = 100 - ret = chain.forward_kinematics({ - 'arm_shoulder_pan_joint': torch.rand(N), - 'arm_elbow_pan_joint': torch.rand(N), - 'arm_wrist_lift_joint': torch.rand(N), - 'arm_wrist_roll_joint': torch.rand(N), - }) + ret = chain.forward_kinematics({k: torch.rand(N) for k in chain.get_joint_parameter_names()}) tg = ret['arm_wrist_roll'] assert list(tg.get_matrix().shape) == [N, 4, 4] From bc9c65d0ffeb5f1d4ec2d913b214afbb2f1cb004 Mon Sep 17 00:00:00 2001 From: Peter Date: Sun, 5 Nov 2023 12:30:43 -0500 Subject: [PATCH 28/34] de-duplicate axis_angle conversion functions Also remove dependency on transformations, since we only use one function from it, and it had compatibility issues. I couldn't get it to install on my laptop. --- pyproject.toml | 1 - src/pytorch_kinematics/chain.py | 12 +- src/pytorch_kinematics/transforms/__init__.py | 8 +- .../transforms/rotation_conversions.py | 122 ++++++++++++++---- src/pytorch_kinematics/urdf.py | 4 +- 5 files changed, 109 insertions(+), 38 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 67c1e4c..ef10050 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -45,7 +45,6 @@ dependencies = [ 'numpy', 'pyyaml', 'torch', - 'transformations', ] [project.optional-dependencies] diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index 9ccc842..ede7dd0 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -1,6 +1,6 @@ from functools import lru_cache -from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_angle_to_matrix -from pytorch_kinematics.transforms.rotation_conversions import tensor_axis_and_d_to_pris_matrix +from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix +from pytorch_kinematics.transforms.rotation_conversions import axis_and_d_to_pris_matrix from typing import Optional, Sequence import numpy as np @@ -294,8 +294,8 @@ def forward_kinematics(self, th, frame_indices: Optional = None): # compute all joint transforms at once first # in order to handle multiple joint types without branching, we create all possible transforms # for all joint types and then select the appropriate one for each joint. - rev_jnt_transform = tensor_axis_and_angle_to_matrix(axes_expanded, th) - pris_jnt_transform = tensor_axis_and_d_to_pris_matrix(axes_expanded, th) + rev_jnt_transform = axis_and_angle_to_matrix(axes_expanded, th) + pris_jnt_transform = axis_and_d_to_pris_matrix(axes_expanded, th) frame_transforms = {} b = th.shape[0] @@ -456,7 +456,7 @@ def jacobian(self, th, locations=None): def forward_kinematics(self, th, end_only: bool = True): """ Like the base class, except `th` only needs to contain the joints in the SerialChain, not all joints. """ - frame_indices, th = self.convert_serial_inputs_to_chain_inputs(end_only, th) + frame_indices, th = self.convert_serial_inputs_to_chain_inputs(th, end_only) mat = super().forward_kinematics(th, frame_indices) @@ -465,7 +465,7 @@ def forward_kinematics(self, th, end_only: bool = True): else: return mat - def convert_serial_inputs_to_chain_inputs(self, end_only, th): + def convert_serial_inputs_to_chain_inputs(self, th, end_only: bool): if end_only: frame_indices = self.get_frame_indices(self._serial_frames[-1].name) else: diff --git a/src/pytorch_kinematics/transforms/__init__.py b/src/pytorch_kinematics/transforms/__init__.py index 1015cb5..45cf710 100644 --- a/src/pytorch_kinematics/transforms/__init__.py +++ b/src/pytorch_kinematics/transforms/__init__.py @@ -1,7 +1,7 @@ # Copyright (c) Facebook, Inc. and its affiliates. All rights reserved. +from pytorch_kinematics.transforms.perturbation import sample_perturbations from .rotation_conversions import ( - axis_and_angle_to_matrix, axis_angle_to_quaternion, euler_angles_to_matrix, matrix_to_axis_angle, @@ -13,13 +13,14 @@ quaternion_multiply, quaternion_raw_multiply, quaternion_to_matrix, + quaternion_from_euler, random_quaternions, random_rotation, random_rotations, rotation_6d_to_matrix, standardize_quaternion, - tensor_axis_and_angle_to_matrix, - tensor_axis_and_d_to_pris_matrix, + axis_and_angle_to_matrix, + axis_and_d_to_pris_matrix, wxyz_to_xyzw, xyzw_to_wxyz, ) @@ -30,6 +31,5 @@ so3_rotation_angle, ) from .transform3d import Rotate, RotateAxisAngle, Scale, Transform3d, Translate -from pytorch_kinematics.transforms.perturbation import sample_perturbations __all__ = [k for k in globals().keys() if not k.startswith("_")] diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 7e22db5..5932965 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -1,9 +1,11 @@ # Copyright (c) Facebook, Inc. and its affiliates. All rights reserved. import functools +import math from typing import Optional from warnings import warn +import numpy import torch import torch.nn.functional as F @@ -450,7 +452,7 @@ def quaternion_apply(quaternion, point): return out[..., 1:] -def tensor_axis_and_d_to_pris_matrix(axis, d): +def axis_and_d_to_pris_matrix(axis, d): """ Creates a 4x4 matrix that represents a translation along an axis of a distance d Works with any number of batch dimensions. @@ -470,7 +472,7 @@ def tensor_axis_and_d_to_pris_matrix(axis, d): return mat44 -def tensor_axis_and_angle_to_matrix(axis, theta): +def axis_and_angle_to_matrix(axis, theta): """ Creates a 4x4 matrix that represents a rotation around an axis by an angle theta. Works with any number of batch dimensions. @@ -505,27 +507,6 @@ def tensor_axis_and_angle_to_matrix(axis, theta): return mat44 -def axis_and_angle_to_matrix(axis, theta): - # based on https://ai.stackexchange.com/questions/14041/, and checked against wikipedia - c = torch.cos(theta) # NOTE: cos is not that precise for float32, you may want to use float64 - one_minus_c = 1 - c - s = torch.sin(theta) - kx, ky, kz = torch.unbind(axis, -1) - r00 = c + kx * kx * one_minus_c - r01 = kx * ky * one_minus_c - kz * s - r02 = kx * kz * one_minus_c + ky * s - r10 = ky * kx * one_minus_c + kz * s - r11 = c + ky * ky * one_minus_c - r12 = ky * kz * one_minus_c - kx * s - r20 = kz * kx * one_minus_c - ky * s - r21 = kz * ky * one_minus_c + kx * s - r22 = c + kz * kz * one_minus_c - rot = torch.stack([torch.cat([r00, r01, r02], -1), - torch.cat([r10, r11, r12], -1), - torch.cat([r20, r21, r22], -1)], -2) - return rot - - def axis_angle_to_matrix(axis_angle): """ Convert rotations given as axis/angle to rotation matrices. @@ -541,7 +522,7 @@ def axis_angle_to_matrix(axis_angle): Returns: Rotation matrices as tensor of shape (..., 3, 3). """ - warn('This is deprecated because it is slow. Use axis_and_angle_to_matrix or zpk_cpp.axis_and_angle_to_matrix', + warn('This is deprecated because it is slow. Use axis_and_angle_to_matrix', DeprecationWarning, stacklevel=2) return quaternion_to_matrix(axis_angle_to_quaternion(axis_angle)) @@ -682,3 +663,96 @@ def pos_rot_to_matrix(pos, rot): m[..., :3, 3] = pos m[..., :3, :3] = rot return m + + +# axis sequences for Euler angles +_NEXT_AXIS = [1, 2, 0, 1] + +# map axes strings to/from tuples of inner axis, parity, repetition, frame +_AXES2TUPLE = { + 'sxyz': (0, 0, 0, 0), + 'sxyx': (0, 0, 1, 0), + 'sxzy': (0, 1, 0, 0), + 'sxzx': (0, 1, 1, 0), + 'syzx': (1, 0, 0, 0), + 'syzy': (1, 0, 1, 0), + 'syxz': (1, 1, 0, 0), + 'syxy': (1, 1, 1, 0), + 'szxy': (2, 0, 0, 0), + 'szxz': (2, 0, 1, 0), + 'szyx': (2, 1, 0, 0), + 'szyz': (2, 1, 1, 0), + 'rzyx': (0, 0, 0, 1), + 'rxyx': (0, 0, 1, 1), + 'ryzx': (0, 1, 0, 1), + 'rxzx': (0, 1, 1, 1), + 'rxzy': (1, 0, 0, 1), + 'ryzy': (1, 0, 1, 1), + 'rzxy': (1, 1, 0, 1), + 'ryxy': (1, 1, 1, 1), + 'ryxz': (2, 0, 0, 1), + 'rzxz': (2, 0, 1, 1), + 'rxyz': (2, 1, 0, 1), + 'rzyz': (2, 1, 1, 1), +} + +_TUPLE2AXES = {v: k for k, v in _AXES2TUPLE.items()} + + +def quaternion_from_euler(ai, aj, ak, axes='sxyz'): + """ + Return quaternion from Euler angles and axis sequence. + Taken from https://github.com/cgohlke/transformations/blob/master/transformations/transformations.py#L1238 + + ai, aj, ak : Euler's roll, pitch and yaw angles + axes : One of 24 axis sequences as string or encoded tuple + + >>> q = quaternion_from_euler(1, 2, 3, 'ryxz') + >>> numpy.allclose(q, [0.435953, 0.310622, -0.718287, 0.444435]) + True + + """ + try: + firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()] + except (AttributeError, KeyError): + _TUPLE2AXES[axes] # noqa: validation + firstaxis, parity, repetition, frame = axes + + i = firstaxis + 1 + j = _NEXT_AXIS[i + parity - 1] + 1 + k = _NEXT_AXIS[i - parity] + 1 + + if frame: + ai, ak = ak, ai + if parity: + aj = -aj + + ai /= 2.0 + aj /= 2.0 + ak /= 2.0 + ci = math.cos(ai) + si = math.sin(ai) + cj = math.cos(aj) + sj = math.sin(aj) + ck = math.cos(ak) + sk = math.sin(ak) + cc = ci * ck + cs = ci * sk + sc = si * ck + ss = si * sk + + q = numpy.empty((4,)) + if repetition: + q[0] = cj * (cc - ss) + q[i] = cj * (cs + sc) + q[j] = sj * (cc + ss) + q[k] = sj * (cs - sc) + else: + q[0] = cj * cc + sj * ss + q[i] = cj * sc - sj * cs + q[j] = cj * ss + sj * cc + q[k] = cj * cs - sj * sc + if parity: + q[j] *= -1.0 + + return q diff --git a/src/pytorch_kinematics/urdf.py b/src/pytorch_kinematics/urdf.py index cc56631..d810fa4 100644 --- a/src/pytorch_kinematics/urdf.py +++ b/src/pytorch_kinematics/urdf.py @@ -3,8 +3,6 @@ from . import chain import torch import pytorch_kinematics.transforms as tf -# has better RPY to quaternion transformation -import transformations as tf2 JOINT_TYPE_MAP = {'revolute': 'revolute', 'continuous': 'revolute', @@ -16,7 +14,7 @@ def _convert_transform(origin): if origin is None: return tf.Transform3d() else: - return tf.Transform3d(rot=torch.tensor(tf2.quaternion_from_euler(*origin.rpy, "sxyz"), dtype=torch.float32), + return tf.Transform3d(rot=torch.tensor(tf.quaternion_from_euler(*origin.rpy, "sxyz"), dtype=torch.float32), pos=origin.xyz) From 25cd7c4e618700d0e560921bb6ae98b1ca31ee25 Mon Sep 17 00:00:00 2001 From: Peter Date: Wed, 8 Nov 2023 17:39:55 -0500 Subject: [PATCH 29/34] fix handling of batched inputs for serial chains and add new test --- README.md | 2 +- src/pytorch_kinematics/chain.py | 86 ++++++++++++------- src/pytorch_kinematics/frame.py | 4 +- src/pytorch_kinematics/jacobian.py | 2 +- src/pytorch_kinematics/transforms/__init__.py | 2 +- .../transforms/rotation_conversions.py | 26 ++++-- tests/test_kinematics.py | 30 ++++++- tests/test_rotation_conversions.py | 4 +- 8 files changed, 110 insertions(+), 46 deletions(-) diff --git a/README.md b/README.md index 0c0c593..1f939b2 100644 --- a/README.md +++ b/README.md @@ -22,7 +22,7 @@ See `tests` for code samples; some are also shown here. If you use this package in your research, consider citing ``` @software{Zhong_PyTorch_Kinematics_2023, -author = {Zhong, Sheng and Power, Thomas and Gupta, Ashwin}, +author = {Zhong, Sheng and Power, Thomas and Gupta, Ashwin and Peter, Mitrano}, doi = {10.5281/zenodo.7700588}, month = {3}, title = {{PyTorch Kinematics}}, diff --git a/src/pytorch_kinematics/chain.py b/src/pytorch_kinematics/chain.py index ede7dd0..d837567 100644 --- a/src/pytorch_kinematics/chain.py +++ b/src/pytorch_kinematics/chain.py @@ -1,6 +1,4 @@ from functools import lru_cache -from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix -from pytorch_kinematics.transforms.rotation_conversions import axis_and_d_to_pris_matrix from typing import Optional, Sequence import numpy as np @@ -9,9 +7,10 @@ import pytorch_kinematics.transforms as tf from pytorch_kinematics import jacobian from pytorch_kinematics.frame import Frame, Link, Joint +from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix_44, axis_and_d_to_pris_matrix -def get_th_size(th): +def get_n_joints(th): """ Args: @@ -28,6 +27,19 @@ def get_th_size(th): raise NotImplementedError(f"Unsupported type {type(th)}") +def get_batch_size(th): + if isinstance(th, torch.Tensor) or isinstance(th, np.ndarray): + return th.shape[0] + elif isinstance(th, dict): + elem_shape = get_dict_elem_shape(th) + return elem_shape[0] + elif isinstance(th, list): + # Lists cannot be batched. We don't allow lists of lists. + return 1 + else: + raise NotImplementedError(f"Unsupported type {type(th)}") + + def ensure_2d_tensor(th, dtype, device): if not torch.is_tensor(th): th = torch.tensor(th, dtype=dtype, device=device) @@ -282,6 +294,18 @@ def get_frame_indices(self, *frame_names): return torch.tensor([self.frame_to_idx[n] for n in frame_names], dtype=torch.long, device=self.device) def forward_kinematics(self, th, frame_indices: Optional = None): + """ + Compute forward kinematics for the given joint values. + + Args: + th: A dict, list, numpy array, or torch tensor of joints values. Possibly batched. + frame_indices: A list of frame indices to compute transforms for. If None, all frames are computed. + Use `get_frame_indices` to convert from frame names to frame indices. + + Returns: + A dict of Transform3d objects for each frame. + + """ if frame_indices is None: frame_indices = self.get_all_frame_indices() @@ -294,7 +318,7 @@ def forward_kinematics(self, th, frame_indices: Optional = None): # compute all joint transforms at once first # in order to handle multiple joint types without branching, we create all possible transforms # for all joint types and then select the appropriate one for each joint. - rev_jnt_transform = axis_and_angle_to_matrix(axes_expanded, th) + rev_jnt_transform = axis_and_angle_to_matrix_44(axes_expanded, th) pris_jnt_transform = axis_and_d_to_pris_matrix(axes_expanded, th) frame_transforms = {} @@ -336,7 +360,7 @@ def forward_kinematics(self, th, frame_indices: Optional = None): def ensure_tensor(self, th): """ Converts a number of possible types into a tensor. The order of the tensor is determined by the order - of self.get_joint_parameter_names(). + of self.get_joint_parameter_names(). th must contain all joints in the entire chain. """ if isinstance(th, np.ndarray): th = torch.tensor(th, device=self.device, dtype=self.dtype) @@ -362,32 +386,17 @@ def get_all_frame_indices(self): frame_indices = self.get_frame_indices(*self.get_frame_names(exclude_fixed=False)) return frame_indices - def ensure_dict_of_2d_tensors(self, th): - if not isinstance(th, dict): - th, _ = ensure_2d_tensor(th, self.dtype, self.device) - assert self.n_joints == th.shape[-1] - th_dict = dict((j, th[..., i]) for i, j in enumerate(self.get_joint_parameter_names())) - else: - th_dict = {k: ensure_2d_tensor(v, self.dtype, self.device)[0] for k, v in th.items()} - return th_dict - def clamp(self, th): - th_dict = self.ensure_dict_of_2d_tensors(th) + """ - out_th_dict = {} - for joint_name, joint_position in th_dict.items(): - joint = self.find_joint(joint_name) - joint_position_clamped = joint.clamp(joint_position) - out_th_dict[joint_name] = joint_position_clamped + Args: + th: Joint configuration - return self.match_input_type(out_th_dict, th) + Returns: Always a tensor in the order of self.get_joint_parameter_names(), possibly batched. - @staticmethod - def match_input_type(th_dict, th): - if isinstance(th, dict): - return th_dict - else: - return torch.stack([v for v in th_dict.values()], dim=-1) + """ + th = self.ensure_tensor(th) + return torch.clamp(th, self.low, self.high) def get_joint_limits(self): low = [] @@ -466,22 +475,33 @@ def forward_kinematics(self, th, end_only: bool = True): return mat def convert_serial_inputs_to_chain_inputs(self, th, end_only: bool): + # th = self.ensure_tensor(th) + th_b = get_batch_size(th) + th_n_joints = get_n_joints(th) + if isinstance(th, list): + th = torch.tensor(th, device=self.device, dtype=self.dtype) + if end_only: frame_indices = self.get_frame_indices(self._serial_frames[-1].name) else: # pass through default behavior for frame indices being None, which is currently # to return all frames. frame_indices = None - if get_th_size(th) < self.n_joints: + if th_n_joints < self.n_joints: # if th is only a partial list of joints, assume it's a list of joints for only the serial chain. partial_th = th nonfixed_serial_frames = list(filter(lambda f: f.joint.joint_type != 'fixed', self._serial_frames)) - if len(nonfixed_serial_frames) != len(partial_th): - raise ValueError(f'Expected {len(nonfixed_serial_frames)} joint values, got {len(partial_th)}.') - th = torch.zeros(self.n_joints, device=self.device, dtype=self.dtype) - for frame, partial_th_i in zip(nonfixed_serial_frames, partial_th): + if th_n_joints != len(nonfixed_serial_frames): + raise ValueError(f'Expected {len(nonfixed_serial_frames)} joint values, got {th_n_joints}.') + th = torch.zeros([th_b, self.n_joints], device=self.device, dtype=self.dtype) + for i, frame in enumerate(nonfixed_serial_frames): + joint_name = frame.joint.name + if isinstance(partial_th, dict): + partial_th_i = partial_th[joint_name] + else: + partial_th_i = partial_th[..., i] k = self.frame_to_idx[frame.name] jnt_idx = self.joint_indices[k] if frame.joint.joint_type != 'fixed': - th[jnt_idx] = partial_th_i + th[..., jnt_idx] = partial_th_i return frame_indices, th diff --git a/src/pytorch_kinematics/frame.py b/src/pytorch_kinematics/frame.py index a078919..04b90c9 100644 --- a/src/pytorch_kinematics/frame.py +++ b/src/pytorch_kinematics/frame.py @@ -1,7 +1,7 @@ import torch import pytorch_kinematics.transforms as tf -from pytorch_kinematics.transforms import axis_and_angle_to_matrix +from pytorch_kinematics.transforms import axis_and_angle_to_matrix_33 class Visual(object): @@ -115,7 +115,7 @@ def get_transform(self, theta): dtype = self.joint.axis.dtype d = self.joint.axis.device if self.joint.joint_type == 'revolute': - rot = axis_and_angle_to_matrix(self.joint.axis, theta) + rot = axis_and_angle_to_matrix_33(self.joint.axis, theta) t = tf.Transform3d(rot=rot, dtype=dtype, device=d) elif self.joint.joint_type == 'prismatic': t = tf.Transform3d(pos=theta * self.joint.axis, dtype=dtype, device=d) diff --git a/src/pytorch_kinematics/jacobian.py b/src/pytorch_kinematics/jacobian.py index abb21c7..fe03c43 100644 --- a/src/pytorch_kinematics/jacobian.py +++ b/src/pytorch_kinematics/jacobian.py @@ -47,7 +47,7 @@ def calc_jacobian(serial_chain, th, tool=None): elif f.joint.joint_type == "prismatic": cnt += 1 j_eef[:, :3, -cnt] = f.joint.axis.repeat(N, 1) @ cur_transform[:, :3, :3] - cur_frame_transform = f.get_transform(th[:, -cnt].reshape(N, 1)).get_matrix() + cur_frame_transform = f.get_transform(th[:, -cnt]).get_matrix() cur_transform = cur_frame_transform @ cur_transform # currently j_eef is Jacobian in end-effector frame, convert to base/world frame diff --git a/src/pytorch_kinematics/transforms/__init__.py b/src/pytorch_kinematics/transforms/__init__.py index 45cf710..c7d5562 100644 --- a/src/pytorch_kinematics/transforms/__init__.py +++ b/src/pytorch_kinematics/transforms/__init__.py @@ -19,7 +19,7 @@ random_rotations, rotation_6d_to_matrix, standardize_quaternion, - axis_and_angle_to_matrix, + axis_and_angle_to_matrix_33, axis_and_d_to_pris_matrix, wxyz_to_xyzw, xyzw_to_wxyz, diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 5932965..ea69bb0 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -472,7 +472,7 @@ def axis_and_d_to_pris_matrix(axis, d): return mat44 -def axis_and_angle_to_matrix(axis, theta): +def axis_and_angle_to_matrix_44(axis, theta): """ Creates a 4x4 matrix that represents a rotation around an axis by an angle theta. Works with any number of batch dimensions. @@ -483,6 +483,25 @@ def axis_and_angle_to_matrix(axis, theta): Returns: [..., 4, 4] + """ + rot = axis_and_angle_to_matrix_33(axis, theta) + batch_shape = axis.shape[:-1] + mat44 = torch.cat((rot, torch.zeros(*batch_shape, 3, 1).to(axis)), -1) + mat44 = torch.cat((mat44, torch.tensor([0.0, 0.0, 0.0, 1.0]).expand(*batch_shape, 1, 4).to(axis)), -2) + return mat44 + + +def axis_and_angle_to_matrix_33(axis, theta): + """ + Creates a 3x3 matrix that represents a rotation around an axis by an angle theta. + Works with any number of batch dimensions. + + Argsaxis.sh: + axis: [..., 3] + theta: [ ...] + + Returns: [..., 3, 3] + """ # based on https://ai.stackexchange.com/questions/14041/, and checked against wikipedia c = torch.cos(theta) # NOTE: cos is not that precise for float32, you may want to use float64 @@ -501,10 +520,7 @@ def axis_and_angle_to_matrix(axis, theta): rot = torch.stack([torch.stack([r00, r01, r02], -1), torch.stack([r10, r11, r12], -1), torch.stack([r20, r21, r22], -1)], -2) - batch_shape = axis.shape[:-1] - mat44 = torch.cat((rot, torch.zeros(*batch_shape, 3, 1).to(axis)), -1) - mat44 = torch.cat((mat44, torch.tensor([0.0, 0.0, 0.0, 1.0]).expand(*batch_shape, 1, 4).to(axis)), -2) - return mat44 + return rot def axis_angle_to_matrix(axis_angle): diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index d7444bb..743f1b1 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -1,6 +1,6 @@ import math -from timeit import timeit import os +from timeit import timeit import torch @@ -260,7 +260,35 @@ def test_fk_val(): assert torch.allclose(pos, torch.tensor([-0.225692, 0.259045, 0.262139], dtype=torch.float64)) +def test_fk_partial_batched_dict(): + # Test that you can pass in dict of batched joint configs for a subset of the joints + chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read(), 'left_tool') + th = { + 'joint56': torch.zeros([1000], dtype=torch.float64), + 'joint57': torch.zeros([1000], dtype=torch.float64), + 'joint41': torch.zeros([1000], dtype=torch.float64), + 'joint42': torch.zeros([1000], dtype=torch.float64), + 'joint43': torch.zeros([1000], dtype=torch.float64), + 'joint44': torch.zeros([1000], dtype=torch.float64), + 'joint45': torch.zeros([1000], dtype=torch.float64), + 'joint46': torch.zeros([1000], dtype=torch.float64), + 'joint47': torch.zeros([1000], dtype=torch.float64), + } + chain = chain.to(dtype=torch.float64) + tg = chain.forward_kinematics(th) + + +def test_fk_partial_batched(): + # Test that you can pass in dict of batched joint configs for a subset of the joints + chain = pk.build_serial_chain_from_mjcf(open(os.path.join(TEST_DIR, "val.xml")).read(), 'left_tool') + th = torch.zeros([1000, 9], dtype=torch.float64) + chain = chain.to(dtype=torch.float64) + tg = chain.forward_kinematics(th) + + if __name__ == "__main__": + test_fk_partial_batched() + test_fk_partial_batched_dict() test_fk_val() test_sdf_serial_chain() test_urdf_serial() diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 6fd3599..388938e 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -2,7 +2,7 @@ import torch -from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix, axis_angle_to_matrix, \ +from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix_33, axis_angle_to_matrix, \ pos_rot_to_matrix, matrix_to_pos_rot, random_rotations @@ -18,7 +18,7 @@ def test_axis_angle_to_matrix_perf(): dt1 = timeit.timeit(lambda: axis_angle_to_matrix(axis_angle), number=number) print(f'Old method: {dt1:.5f}') - dt2 = timeit.timeit(lambda: axis_and_angle_to_matrix(axis=axis_1d, theta=theta), number=number) + dt2 = timeit.timeit(lambda: axis_and_angle_to_matrix_33(axis=axis_1d, theta=theta), number=number) print(f'New method: {dt2:.5f}') From 3ff7f3c0ad670386b5175ef05921e5f1b56b8dcf Mon Sep 17 00:00:00 2001 From: Peter Date: Thu, 16 Nov 2023 15:45:27 -0500 Subject: [PATCH 30/34] add test to address review --- .../transforms/rotation_conversions.py | 2 +- tests/test_rotation_conversions.py | 18 +++++++++++++++++- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index ea69bb0..1402fe5 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -538,7 +538,7 @@ def axis_angle_to_matrix(axis_angle): Returns: Rotation matrices as tensor of shape (..., 3, 3). """ - warn('This is deprecated because it is slow. Use axis_and_angle_to_matrix', + warn('This is deprecated because it is slow. Use axis_and_angle_to_matrix_33 instead.', DeprecationWarning, stacklevel=2) return quaternion_to_matrix(axis_angle_to_quaternion(axis_angle)) diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 388938e..635995a 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -1,9 +1,10 @@ import timeit +import numpy as np import torch from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix_33, axis_angle_to_matrix, \ - pos_rot_to_matrix, matrix_to_pos_rot, random_rotations + pos_rot_to_matrix, matrix_to_pos_rot, random_rotations, quaternion_from_euler def test_axis_angle_to_matrix_perf(): @@ -22,6 +23,21 @@ def test_axis_angle_to_matrix_perf(): print(f'New method: {dt2:.5f}') +def test_quaternion_from_euler(): + q = quaternion_from_euler(0, 0, 0) + np.testing.assert_allclose(q, np.array([1., 0, 0, 0])) + root2_over_2 = np.sqrt(2) / 2 + + q = quaternion_from_euler(0, 0, np.pi / 2) + np.testing.assert_allclose(q, np.array([root2_over_2, 0, 0, root2_over_2])) + + q = quaternion_from_euler(-np.pi / 2, 0, 0) + np.testing.assert_allclose(q, np.array([root2_over_2, -root2_over_2, 0, 0])) + + q = quaternion_from_euler(0, np.pi / 2, 0) + np.testing.assert_allclose(q, np.array([root2_over_2, 0, root2_over_2, 0])) + + def test_pos_rot_conversion(): N = 1000 R = random_rotations(N) From dd7a3fbf281387413518299824a84525d493e866 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 20 Nov 2023 17:01:50 -0500 Subject: [PATCH 31/34] change how we test for quaternion equality --- src/pytorch_kinematics/transforms/math.py | 10 +++++ .../transforms/rotation_conversions.py | 41 ++++++++----------- src/pytorch_kinematics/urdf.py | 4 +- tests/test_kinematics.py | 32 ++++++--------- tests/test_rotation_conversions.py | 26 ++++++++---- 5 files changed, 61 insertions(+), 52 deletions(-) diff --git a/src/pytorch_kinematics/transforms/math.py b/src/pytorch_kinematics/transforms/math.py index cf95520..cc10065 100644 --- a/src/pytorch_kinematics/transforms/math.py +++ b/src/pytorch_kinematics/transforms/math.py @@ -10,6 +10,16 @@ import torch +def quaternion_close(q1: torch.Tensor, q2: torch.Tensor, eps: float = 1e-4): + """ + Returns true if two quaternions are close to each other. Assumes the quaternions are normalized. + Based on: https://math.stackexchange.com/a/90098/516340 + + """ + dist = 1 - torch.square(torch.sum(q1*q2, dim=-1)) + return torch.all(dist < eps) + + def acos_linear_extrapolation( x: torch.Tensor, bound: Union[float, Tuple[float, float]] = 1.0 - 1e-4, diff --git a/src/pytorch_kinematics/transforms/rotation_conversions.py b/src/pytorch_kinematics/transforms/rotation_conversions.py index 1402fe5..61bd32c 100644 --- a/src/pytorch_kinematics/transforms/rotation_conversions.py +++ b/src/pytorch_kinematics/transforms/rotation_conversions.py @@ -1,11 +1,9 @@ # Copyright (c) Facebook, Inc. and its affiliates. All rights reserved. import functools -import math from typing import Optional from warnings import warn -import numpy import torch import torch.nn.functional as F @@ -715,7 +713,7 @@ def pos_rot_to_matrix(pos, rot): _TUPLE2AXES = {v: k for k, v in _AXES2TUPLE.items()} -def quaternion_from_euler(ai, aj, ak, axes='sxyz'): +def quaternion_from_euler(rpy, axes='sxyz'): """ Return quaternion from Euler angles and axis sequence. Taken from https://github.com/cgohlke/transformations/blob/master/transformations/transformations.py#L1238 @@ -723,10 +721,6 @@ def quaternion_from_euler(ai, aj, ak, axes='sxyz'): ai, aj, ak : Euler's roll, pitch and yaw angles axes : One of 24 axis sequences as string or encoded tuple - >>> q = quaternion_from_euler(1, 2, 3, 'ryxz') - >>> numpy.allclose(q, [0.435953, 0.310622, -0.718287, 0.444435]) - True - """ try: firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()] @@ -734,6 +728,7 @@ def quaternion_from_euler(ai, aj, ak, axes='sxyz'): _TUPLE2AXES[axes] # noqa: validation firstaxis, parity, repetition, frame = axes + ai, aj, ak = torch.unbind(rpy, -1) i = firstaxis + 1 j = _NEXT_AXIS[i + parity - 1] + 1 k = _NEXT_AXIS[i - parity] + 1 @@ -746,29 +741,29 @@ def quaternion_from_euler(ai, aj, ak, axes='sxyz'): ai /= 2.0 aj /= 2.0 ak /= 2.0 - ci = math.cos(ai) - si = math.sin(ai) - cj = math.cos(aj) - sj = math.sin(aj) - ck = math.cos(ak) - sk = math.sin(ak) + ci = torch.cos(ai) + si = torch.sin(ai) + cj = torch.cos(aj) + sj = torch.sin(aj) + ck = torch.cos(ak) + sk = torch.sin(ak) cc = ci * ck cs = ci * sk sc = si * ck ss = si * sk - q = numpy.empty((4,)) + q = torch.zeros([*rpy.shape[:-1], 4]).to(rpy) if repetition: - q[0] = cj * (cc - ss) - q[i] = cj * (cs + sc) - q[j] = sj * (cc + ss) - q[k] = sj * (cs - sc) + q[..., 0] = cj * (cc - ss) + q[..., i] = cj * (cs + sc) + q[..., j] = sj * (cc + ss) + q[..., k] = sj * (cs - sc) else: - q[0] = cj * cc + sj * ss - q[i] = cj * sc - sj * cs - q[j] = cj * ss + sj * cc - q[k] = cj * cs - sj * sc + q[..., 0] = cj * cc + sj * ss + q[..., i] = cj * sc - sj * cs + q[..., j] = cj * ss + sj * cc + q[..., k] = cj * cs - sj * sc if parity: - q[j] *= -1.0 + q[..., j] *= -1.0 return q diff --git a/src/pytorch_kinematics/urdf.py b/src/pytorch_kinematics/urdf.py index d810fa4..d33c262 100644 --- a/src/pytorch_kinematics/urdf.py +++ b/src/pytorch_kinematics/urdf.py @@ -14,8 +14,8 @@ def _convert_transform(origin): if origin is None: return tf.Transform3d() else: - return tf.Transform3d(rot=torch.tensor(tf.quaternion_from_euler(*origin.rpy, "sxyz"), dtype=torch.float32), - pos=origin.xyz) + rpy = torch.tensor(origin.rpy, dtype=torch.float32) + return tf.Transform3d(rot=tf.quaternion_from_euler(rpy, "sxyz"), pos=origin.xyz) def _convert_visual(visual): diff --git a/tests/test_kinematics.py b/tests/test_kinematics.py index 743f1b1..6e281b7 100644 --- a/tests/test_kinematics.py +++ b/tests/test_kinematics.py @@ -5,6 +5,7 @@ import torch import pytorch_kinematics as pk +from pytorch_kinematics.transforms.math import quaternion_close TEST_DIR = os.path.dirname(__file__) @@ -16,11 +17,6 @@ def quat_pos_from_transform3d(tg): return pos, rot -def quaternion_equality(a, b, rtol=1e-5): - # negative of a quaternion is the same rotation - return torch.allclose(a, b, rtol=rtol) or torch.allclose(a, -b, rtol=rtol) - - # test more complex robot and the MJCF parser def test_fk_mjcf(): chain = pk.build_chain_from_mjcf(open(os.path.join(TEST_DIR, "ant.xml")).read()) @@ -33,11 +29,11 @@ def test_fk_mjcf(): ret = chain.forward_kinematics(th) tg = ret['aux_1'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.87758256, 0., 0., 0.47942554], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([0.87758256, 0., 0., 0.47942554], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.2, 0.2, 0.75], dtype=torch.float64)) tg = ret['front_left_foot'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) print(ret) @@ -47,7 +43,7 @@ def test_fk_serial_mjcf(): chain = chain.to(dtype=torch.float64) tg = chain.forward_kinematics([1.0, 1.0]) pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([0.77015115, -0.4600326, 0.13497724, 0.42073549], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([0.13976626, 0.47635466, 0.75], dtype=torch.float64)) @@ -72,7 +68,7 @@ def test_fkik(): tg = chain.forward_kinematics(th1) pos, rot = quat_pos_from_transform3d(tg) assert torch.allclose(pos, torch.tensor([[1.91081784, 0.41280851, 0.0000]])) - assert quaternion_equality(rot, torch.tensor([[0.95521418, 0.0000, 0.0000, 0.2959153]])) + assert quaternion_close(rot, torch.tensor([[0.95521418, 0.0000, 0.0000, 0.2959153]])) N = 20 th_batch = torch.rand(N, 2) tg_batch = chain.forward_kinematics(th_batch) @@ -98,22 +94,20 @@ def test_urdf(): ret = chain.forward_kinematics(th) tg = ret['lbr_iiwa_link_7'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) - assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) + assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64), atol=1e-6) def test_urdf_serial(): chain = pk.build_serial_chain_from_urdf(open(os.path.join(TEST_DIR, "kuka_iiwa.urdf")).read(), "lbr_iiwa_link_7") chain.to(dtype=torch.float64) - print(chain) - print(chain.get_joint_parameter_names()) th = [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0] ret = chain.forward_kinematics(th, end_only=False) tg = ret['lbr_iiwa_link_7'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) - assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([7.07106781e-01, 0, -7.07106781e-01, 0], dtype=torch.float64)) + assert torch.allclose(pos, torch.tensor([-6.60827561e-01, 0, 3.74142136e-01], dtype=torch.float64), atol=1e-6) N = 1000 d = "cuda" if torch.cuda.is_available() else "cpu" @@ -162,7 +156,7 @@ def test_fk_simple_arm(): }) tg = ret['arm_wrist_roll'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) N = 100 @@ -176,7 +170,7 @@ def test_sdf_serial_chain(): chain = chain.to(dtype=torch.float64) tg = chain.forward_kinematics([0., math.pi / 2.0, -0.5, 0.]) pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) + assert quaternion_close(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=torch.float64)) @@ -201,7 +195,7 @@ def test_cuda(): }) tg = ret['arm_wrist_roll'] pos, rot = quat_pos_from_transform3d(tg) - assert quaternion_equality(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d)) + assert quaternion_close(rot, torch.tensor([0.70710678, 0., 0., 0.70710678], dtype=dtype, device=d)) assert torch.allclose(pos, torch.tensor([1.05, 0.55, 0.5], dtype=dtype, device=d)) data = '' \ @@ -256,7 +250,7 @@ def test_fk_val(): tg = ret['drive45'] pos, rot = quat_pos_from_transform3d(tg) torch.set_printoptions(precision=6, sci_mode=False) - assert quaternion_equality(rot, torch.tensor([0.5, 0.5, -0.5, 0.5], dtype=torch.float64), rtol=1e-4) + assert quaternion_close(rot, torch.tensor([0.5, 0.5, -0.5, 0.5], dtype=torch.float64)) assert torch.allclose(pos, torch.tensor([-0.225692, 0.259045, 0.262139], dtype=torch.float64)) diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 635995a..f1ffd78 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -3,6 +3,7 @@ import numpy as np import torch +from pytorch_kinematics.transforms.math import quaternion_close from pytorch_kinematics.transforms.rotation_conversions import axis_and_angle_to_matrix_33, axis_angle_to_matrix, \ pos_rot_to_matrix, matrix_to_pos_rot, random_rotations, quaternion_from_euler @@ -24,18 +25,27 @@ def test_axis_angle_to_matrix_perf(): def test_quaternion_from_euler(): - q = quaternion_from_euler(0, 0, 0) - np.testing.assert_allclose(q, np.array([1., 0, 0, 0])) + q = quaternion_from_euler(torch.tensor([0., 0, 0])) + assert quaternion_close(q, torch.tensor([1., 0, 0, 0])) root2_over_2 = np.sqrt(2) / 2 - q = quaternion_from_euler(0, 0, np.pi / 2) - np.testing.assert_allclose(q, np.array([root2_over_2, 0, 0, root2_over_2])) + q = quaternion_from_euler(torch.tensor([0, 0, np.pi / 2])) + assert quaternion_close(q, torch.tensor([root2_over_2, 0, 0, root2_over_2], dtype=q.dtype)) - q = quaternion_from_euler(-np.pi / 2, 0, 0) - np.testing.assert_allclose(q, np.array([root2_over_2, -root2_over_2, 0, 0])) + q = quaternion_from_euler(torch.tensor([-np.pi / 2, 0, 0])) + assert quaternion_close(q, torch.tensor([root2_over_2, -root2_over_2, 0, 0], dtype=q.dtype)) - q = quaternion_from_euler(0, np.pi / 2, 0) - np.testing.assert_allclose(q, np.array([root2_over_2, 0, root2_over_2, 0])) + q = quaternion_from_euler(torch.tensor([0, np.pi / 2, 0])) + assert quaternion_close(q, torch.tensor([root2_over_2, 0, root2_over_2, 0], dtype=q.dtype)) + + # Test batched + b = 32 + rpy = torch.tensor([0, np.pi / 2, 0]) + rpy_batch = torch.tile(rpy[None], (b, 1)) + q_batch = quaternion_from_euler(rpy_batch) + q_expected = torch.tensor([root2_over_2, 0, root2_over_2, 0], dtype=q.dtype) + q_expected_batch = torch.tile(q_expected[None], (b, 1)) + assert quaternion_close(q_batch, q_expected_batch) def test_pos_rot_conversion(): From c960f237085439785a65955f357e5c7b91501749 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 20 Nov 2023 17:14:01 -0500 Subject: [PATCH 32/34] make mujoco required --- pyproject.toml | 4 ++-- tests/test_rotation_conversions.py | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index ef10050..4f913be 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -42,14 +42,14 @@ classifiers = [# Optional dependencies = [ 'absl-py', 'lxml', + "mujoco", 'numpy', 'pyyaml', 'torch', ] [project.optional-dependencies] -test = ["pytest", "mujoco"] -mujoco = ["mujoco"] +test = ["pytest"] [project.urls] "Homepage" = "https://github.com/UM-ARM-Lab/pytorch_kinematics" diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index f1ffd78..56533a8 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -23,6 +23,7 @@ def test_axis_angle_to_matrix_perf(): dt2 = timeit.timeit(lambda: axis_and_angle_to_matrix_33(axis=axis_1d, theta=theta), number=number) print(f'New method: {dt2:.5f}') +def test_quaternion_close def test_quaternion_from_euler(): q = quaternion_from_euler(torch.tensor([0., 0, 0])) From 1042b0f87d2d1b6113d14d8a9514afe1942d814b Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 20 Nov 2023 17:14:31 -0500 Subject: [PATCH 33/34] update readme --- README.md | 2 -- 1 file changed, 2 deletions(-) diff --git a/README.md b/README.md index 1f939b2..255ff07 100644 --- a/README.md +++ b/README.md @@ -6,8 +6,6 @@ # Installation ```shell pip install pytorch-kinematics -# Alternatively, if you want to load from mujoco's XML format, use: -pip install pytorch-kinematics[mujoco] ``` For development, clone repository somewhere, then `pip3 install -e .` to install in editable mode. From f98e6fcb58de762091d57a56e712506d2f8ac575 Mon Sep 17 00:00:00 2001 From: Peter Date: Mon, 20 Nov 2023 17:19:28 -0500 Subject: [PATCH 34/34] fix test --- tests/test_rotation_conversions.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/tests/test_rotation_conversions.py b/tests/test_rotation_conversions.py index 56533a8..46cbb25 100644 --- a/tests/test_rotation_conversions.py +++ b/tests/test_rotation_conversions.py @@ -23,7 +23,13 @@ def test_axis_angle_to_matrix_perf(): dt2 = timeit.timeit(lambda: axis_and_angle_to_matrix_33(axis=axis_1d, theta=theta), number=number) print(f'New method: {dt2:.5f}') -def test_quaternion_close + +def test_quaternion_not_close(): + # ensure it returns false for quaternions that are far apart + q1 = torch.tensor([1., 0, 0, 0]) + q2 = torch.tensor([0., 1, 0, 0]) + assert not quaternion_close(q1, q2) + def test_quaternion_from_euler(): q = quaternion_from_euler(torch.tensor([0., 0, 0]))