From 9e4a8dcbaa28f56ade30fc62a7f488a8e8b74ce4 Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Wed, 20 Jul 2022 14:10:24 -0400 Subject: [PATCH 01/38] update pose graph data link (#256) --- examples/pose_graph/pose_graph_benchmark.py | 14 +++++++++++++- examples/pose_graph/pose_graph_cube.py | 14 +++++++++++++- 2 files changed, 26 insertions(+), 2 deletions(-) diff --git a/examples/pose_graph/pose_graph_benchmark.py b/examples/pose_graph/pose_graph_benchmark.py index 4d5e56be2..5cc629bf9 100644 --- a/examples/pose_graph/pose_graph_benchmark.py +++ b/examples/pose_graph/pose_graph_benchmark.py @@ -13,11 +13,23 @@ import theseus as th import theseus.utils.examples as theg +# To run this example, you will need the cube datasets available at +# https://dl.fbaipublicfiles.com/theseus/pose_graph_data.tar.gz +# +# The steps below should let you run the example. +# From the root project folder do: +# mkdir datasets +# cd datasets +# cp your/path/pose_graph_data.tar.gz . +# tar -xzvf pose_graph_data.tar.gz +# cd .. +# python examples/pose_graph_benchmark.py + # Logger log = logging.getLogger(__name__) -DATASET_DIR = pathlib.Path.cwd() / "datasets" +DATASET_DIR = pathlib.Path.cwd() / "datasets" / "pose_graph" @hydra.main(config_path="../configs/pose_graph", config_name="pose_graph_benchmark") diff --git a/examples/pose_graph/pose_graph_cube.py b/examples/pose_graph/pose_graph_cube.py index 047558fd2..ee03c7444 100644 --- a/examples/pose_graph/pose_graph_cube.py +++ b/examples/pose_graph/pose_graph_cube.py @@ -19,10 +19,22 @@ from theseus.optimizer.linear.linear_solver import LinearSolver from theseus.utils.examples.pose_graph.dataset import PoseGraphEdge +# To run this example, you will need the cube datasets available at +# https://dl.fbaipublicfiles.com/theseus/pose_graph_data.tar.gz +# +# The steps below should let you run the example. +# From the root project folder do: +# mkdir datasets +# cd datasets +# cp your/path/pose_graph_data.tar.gz . +# tar -xzvf pose_graph_data.tar.gz +# cd .. +# python examples/pose_graph_cube.py + # Logger log = logging.getLogger(__name__) -DATASET_DIR = pathlib.Path.cwd() / "datasets" / "cube" +DATASET_DIR = pathlib.Path.cwd() / "datasets" / "pose_graph" / "cube" dtype = torch.float64 From 991c371b069a5588c6536d59ace6397ae3c79c56 Mon Sep 17 00:00:00 2001 From: Daniel DeTone <4764838+ddetone@users.noreply.github.com> Date: Wed, 27 Jul 2022 09:42:57 -0700 Subject: [PATCH 02/38] [homography] Use kornia lib properly for perspective transform, reduce default training dataset size (#258) --- examples/homography_estimation.py | 8 +-- theseus/third_party/easyaug.py | 116 +----------------------------- 2 files changed, 6 insertions(+), 118 deletions(-) diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index 4ee3cf823..5cb2441d4 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -36,10 +36,10 @@ def prepare_data(): dataset_root = os.path.join(os.getcwd(), "data") chunks = [ "revisitop1m.1", - "revisitop1m.2", - "revisitop1m.3", - "revisitop1m.4", - "revisitop1m.5", + #"revisitop1m.2", # Uncomment for more data. + #"revisitop1m.3", + #"revisitop1m.4", + #"revisitop1m.5", ] dataset_paths = [] for chunk in chunks: diff --git a/theseus/third_party/easyaug.py b/theseus/third_party/easyaug.py index 664defd49..34f1fb719 100644 --- a/theseus/third_party/easyaug.py +++ b/theseus/third_party/easyaug.py @@ -4,6 +4,7 @@ import math import warnings +import kornia from typing import NamedTuple, Optional import torch @@ -81,113 +82,6 @@ def check_input(inp: torch.Tensor): return -# Note(dd): It was a pain to update kornia, so I took this from the kornia directly. -def get_perspective_transform(src, dst): - r"""Calculates a perspective transform from four pairs of the corresponding - points. - The function calculates the matrix of a perspective transform so that: - .. math :: - \begin{bmatrix} - t_{i}x_{i}^{'} \\ - t_{i}y_{i}^{'} \\ - t_{i} \\ - \end{bmatrix} - = - \textbf{map_matrix} \cdot - \begin{bmatrix} - x_{i} \\ - y_{i} \\ - 1 \\ - \end{bmatrix} - where - .. math :: - dst(i) = (x_{i}^{'},y_{i}^{'}), src(i) = (x_{i}, y_{i}), i = 0,1,2,3 - Args: - src (torch.Tensor): coordinates of quadrangle vertices in the source image - with shape :math:`(B, 4, 2)`. - dst (torch.Tensor): coordinates of the corresponding quadrangle vertices in - the destination image with shape :math:`(B, 4, 2)`. - Returns: - torch.Tensor: the perspective transformation with shape :math:`(B, 3, 3)`. - .. note:: - This function is often used in conjuntion with :func:`warp_perspective`. - """ - - # we build matrix A by using only 4 point correspondence. The linear - # system is solved with the least square method, so here - # we could even pass more correspondence - p = [] - for i in [0, 1, 2, 3]: - p.append(_build_perspective_param(src[:, i], dst[:, i], "x")) - p.append(_build_perspective_param(src[:, i], dst[:, i], "y")) - - # A is Bx8x8 - A = torch.stack(p, dim=1) - - # b is a Bx8x1 - b = torch.stack( - [ - dst[:, 0:1, 0], - dst[:, 0:1, 1], - dst[:, 1:2, 0], - dst[:, 1:2, 1], - dst[:, 2:3, 0], - dst[:, 2:3, 1], - dst[:, 3:4, 0], - dst[:, 3:4, 1], - ], - dim=1, - ) - - # solve the system Ax = b - X = torch.linalg.solve(A, b) - - # create variable to return - batch_size = src.shape[0] - M = torch.ones(batch_size, 9, device=src.device, dtype=src.dtype) - M[..., :8] = torch.squeeze(X, dim=-1) - - return M.view(-1, 3, 3) # Bx3x3 - - -def _build_perspective_param( - p: torch.Tensor, q: torch.Tensor, axis: str -) -> torch.Tensor: - ones = torch.ones_like(p)[..., 0:1] - zeros = torch.zeros_like(p)[..., 0:1] - if axis == "x": - return torch.cat( - [ - p[:, 0:1], - p[:, 1:2], - ones, - zeros, - zeros, - zeros, - -p[:, 0:1] * q[:, 0:1], - -p[:, 1:2] * q[:, 0:1], - ], - dim=1, - ) - - elif axis == "y": - return torch.cat( - [ - zeros, - zeros, - zeros, - p[:, 0:1], - p[:, 1:2], - ones, - -p[:, 0:1] * q[:, 1:2], - -p[:, 1:2] * q[:, 1:2], - ], - dim=1, - ) - else: - raise ValueError("Bad input axis, should be x or y") - - class GeoAugParam(NamedTuple): min: Optional[float] = 0.0 max: Optional[float] = 0.0 @@ -288,13 +182,7 @@ def _get_perspective_matrix( start *= corner_signs end *= corner_signs # Set up a linear system to solve for the homography. - # pmat = solve_homography(start, end) - # pmat = solve_homography_old(start, end) - # pmat = kornia.homography.find_homography_dlt(start, end) # Newer kornia version API. - # pmat = kornia.get_perspective_transform(start, end) - pmat = get_perspective_transform( - start, end - ) # Copied kornia functioned directly. + pmat = kornia.geometry.transform.get_perspective_transform(start, end) # Apply perspective transform first, then affine. matrix = pmat @ matrix # Normalize such that H[2,2] = 1. From dae3375d3f46cb47ae91b53be0707ebd3f426c12 Mon Sep 17 00:00:00 2001 From: Neil Pandya Date: Wed, 27 Jul 2022 19:59:29 -0400 Subject: [PATCH 03/38] Update 00_introduction.ipynb (#259) Found a forgotten a comma. Co-authored-by: Neil Pandya --- tutorials/00_introduction.ipynb | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/00_introduction.ipynb b/tutorials/00_introduction.ipynb index d35aa53c9..2753bd525 100644 --- a/tutorials/00_introduction.ipynb +++ b/tutorials/00_introduction.ipynb @@ -367,7 +367,7 @@ "\n", "# Step 3: Construct cost functions representing each error term\n", "# First term\n", - "cf1 = th.Difference(x, a, w1 name=\"term_1\")\n", + "cf1 = th.Difference(x, a, w1, name=\"term_1\")\n", "# Second term\n", "cf2 = th.Difference(y, b, w2, name=\"term_2\")\n", "\n", From eef28d94de58006886a0418673978aa6c78b0f73 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Thu, 28 Jul 2022 11:42:13 -0400 Subject: [PATCH 04/38] Changed SDF constructor to accept more convenient data types. (#260) * Changed SDF constructor to accept more convenient data types. * Fixed broken test and added missing copyright headers. --- examples/motion_planning_2d.py | 2 +- theseus/embodied/collision/collision.py | 18 +-- theseus/embodied/collision/eff_obj_contact.py | 16 +-- .../collision/signed_distance_field.py | 107 +++++++++++++----- theseus/embodied/collision/tests/__init__.py | 4 + .../collision/tests/test_collision_factor.py | 31 +++-- .../collision/tests/test_eff_obj_contact.py | 81 +++++++------ .../tests/test_signed_distance_field.py | 21 +--- theseus/embodied/collision/tests/utils.py | 40 +++++++ .../tactile_pose_estimation/pose_estimator.py | 2 +- tutorials/04_motion_planning.ipynb | 58 +++++++++- .../05_differentiable_motion_planning.ipynb | 31 ++++- 12 files changed, 291 insertions(+), 120 deletions(-) create mode 100644 theseus/embodied/collision/tests/__init__.py create mode 100644 theseus/embodied/collision/tests/utils.py diff --git a/examples/motion_planning_2d.py b/examples/motion_planning_2d.py index 9ff09ecf5..c781454df 100644 --- a/examples/motion_planning_2d.py +++ b/examples/motion_planning_2d.py @@ -40,7 +40,7 @@ def plot_and_save_trajectories( include_expert: bool = False, ): sdf = th.eb.SignedDistanceField2D( - th.Variable(batch["sdf_origin"]), + th.Point2(batch["sdf_origin"]), th.Variable(batch["cell_size"]), th.Variable(batch["sdf_data"]), ) diff --git a/theseus/embodied/collision/collision.py b/theseus/embodied/collision/collision.py index e7c36ef61..2e966c22c 100644 --- a/theseus/embodied/collision/collision.py +++ b/theseus/embodied/collision/collision.py @@ -18,20 +18,20 @@ class Collision2D(CostFunction): def __init__( self, pose: Point2, - sdf_origin: Variable, - sdf_data: Variable, - sdf_cell_size: Variable, + sdf_origin: Union[Point2, torch.Tensor], + sdf_data: Union[torch.Tensor, Variable], + sdf_cell_size: Union[float, torch.Tensor, Variable], cost_eps: Union[float, Variable, torch.Tensor], cost_weight: CostWeight, name: Optional[str] = None, ): if not isinstance(pose, Point2): - raise ValueError("Collision2D only accepts 2D poses as inputs.") + raise ValueError("Collision2D only accepts Point2 poses.") super().__init__(cost_weight, name=name) self.pose = pose - self.sdf_origin = sdf_origin - self.sdf_data = sdf_data - self.sdf_cell_size = sdf_cell_size + self.sdf_origin = SignedDistanceField2D.convert_origin(sdf_origin) + self.sdf_data = SignedDistanceField2D.convert_sdf_data(sdf_data) + self.sdf_cell_size = SignedDistanceField2D.convert_cell_size(sdf_cell_size) if not isinstance(cost_eps, Variable): if not isinstance(cost_eps, torch.Tensor): cost_eps = torch.tensor(cost_eps) @@ -42,7 +42,9 @@ def __init__( self.register_optim_vars(["pose"]) self.register_aux_vars(["sdf_origin", "sdf_data", "sdf_cell_size", "cost_eps"]) self.robot: KinematicsModel = IdentityModel() - self.sdf = SignedDistanceField2D(sdf_origin, sdf_cell_size, sdf_data) + self.sdf = SignedDistanceField2D( + self.sdf_origin, self.sdf_cell_size, self.sdf_data + ) def _compute_distances_and_jacobians( self, diff --git a/theseus/embodied/collision/eff_obj_contact.py b/theseus/embodied/collision/eff_obj_contact.py index fe77f7762..c164832b9 100644 --- a/theseus/embodied/collision/eff_obj_contact.py +++ b/theseus/embodied/collision/eff_obj_contact.py @@ -19,9 +19,9 @@ def __init__( self, obj: SE2, eff: SE2, - sdf_origin: Variable, - sdf_data: Variable, - sdf_cell_size: Variable, + sdf_origin: Union[Point2, torch.Tensor], + sdf_data: Union[torch.Tensor, Variable], + sdf_cell_size: Union[float, torch.Tensor, Variable], eff_radius: Union[float, Variable, torch.Tensor], cost_weight: CostWeight, name: Optional[str] = None, @@ -30,9 +30,9 @@ def __init__( super().__init__(cost_weight, name=name) self.obj = obj self.eff = eff - self.sdf_origin = sdf_origin - self.sdf_data = sdf_data - self.sdf_cell_size = sdf_cell_size + self.sdf_origin = SignedDistanceField2D.convert_origin(sdf_origin) + self.sdf_data = SignedDistanceField2D.convert_sdf_data(sdf_data) + self.sdf_cell_size = SignedDistanceField2D.convert_cell_size(sdf_cell_size) if not isinstance(eff_radius, Variable): if not isinstance(eff_radius, torch.Tensor): eff_radius = torch.tensor(eff_radius) @@ -47,7 +47,9 @@ def __init__( ["sdf_origin", "sdf_data", "sdf_cell_size", "eff_radius"] ) self.robot = IdentityModel() - self.sdf = SignedDistanceField2D(sdf_origin, sdf_cell_size, sdf_data) + self.sdf = SignedDistanceField2D( + self.sdf_origin, self.sdf_cell_size, self.sdf_data + ) self._use_huber = use_huber_loss if use_huber_loss: diff --git a/theseus/embodied/collision/signed_distance_field.py b/theseus/embodied/collision/signed_distance_field.py index afe0bc8a0..9eac66781 100644 --- a/theseus/embodied/collision/signed_distance_field.py +++ b/theseus/embodied/collision/signed_distance_field.py @@ -3,12 +3,13 @@ # This source code is licensed under the MIT license found in the # LICENSE file in the root directory of this source tree. -from typing import Optional, Tuple +from typing import Optional, Tuple, Union import torch from scipy import ndimage from theseus.core import Variable +from theseus.geometry import Point2 from theseus.utils import gather_from_rows_cols @@ -17,35 +18,45 @@ class SignedDistanceField2D: # sdf_data shape is: batch_size x field_height x field_width def __init__( self, - origin: Variable, - cell_size: Variable, - sdf_data: Optional[Variable] = None, - occupancy_map: Optional[Variable] = None, + origin: Union[Point2, torch.Tensor], + cell_size: Union[float, torch.Tensor, Variable], + sdf_data: Optional[Union[torch.Tensor, Variable]] = None, + occupancy_map: Optional[Union[torch.Tensor, Variable]] = None, ): if occupancy_map is not None: if sdf_data is not None: raise ValueError( - "Only one of arguments sdf_data and occupancy_map should be provided." + "Only one of sdf_data and occupancy_map should be provided." ) - sdf_data = self._compute_sdf_data_from_map(occupancy_map, cell_size) + sdf_data = self._compute_sdf_data_from_map( + occupancy_map, SignedDistanceField2D.convert_cell_size(cell_size).tensor + ) else: if sdf_data is None: raise ValueError( - "Either argument sdf_data or argument occupancy_map should be provided." + "Either sdf_data or argument occupancy_map should be provided." ) self.update_data(origin, sdf_data, cell_size) self._num_rows = sdf_data.shape[1] self._num_cols = sdf_data.shape[2] def _compute_sdf_data_from_map( - self, occupancy_map_batch: Variable, cell_size: Variable + self, + occupancy_map_batch: Union[Variable, torch.Tensor], + cell_size: torch.Tensor, ) -> Variable: + if isinstance(occupancy_map_batch, Variable): + occupancy_map_batch = occupancy_map_batch.tensor + if cell_size.shape[0] != occupancy_map_batch.shape[0]: + cell_size = cell_size.expand(occupancy_map_batch.shape[0], 1) + # Code from https://github.com/gtrll/gpmp2/ if occupancy_map_batch.ndim != 3: raise ValueError( - "Argument occupancy_map to SignedDistanceField2D must be a batch of matrices." + "Argument occupancy_map to SignedDistanceField2D must be " + "a batch of matrices." ) - num_maps = occupancy_map_batch.tensor.size(0) + num_maps = occupancy_map_batch.shape[0] all_sdf_data = [] for i in range(num_maps): @@ -58,7 +69,7 @@ def _compute_sdf_data_from_map( map_x, map_y = occupancy_map.size(0), occupancy_map.size(1) max_map_size = 2 * cell_size[i].item() * max(map_x, map_y) sdf_data = ( - torch.ones(occupancy_map.shape, dtype=cell_size.dtype) + torch.ones(occupancy_map.shape, dtype=occupancy_map.dtype) * max_map_size ) else: @@ -71,7 +82,9 @@ def _compute_sdf_data_from_map( sdf_data = map_dist - inv_map_dist # metric - sdf_data = torch.tensor(sdf_data, dtype=cell_size.dtype) * cell_size[i] + sdf_data = ( + torch.tensor(sdf_data, dtype=occupancy_map.dtype) * cell_size[i] + ) all_sdf_data.append(sdf_data) @@ -79,29 +92,65 @@ def _compute_sdf_data_from_map( return sdf_data_var - def update_data(self, origin: Variable, sdf_data: Variable, cell_size: Variable): - if sdf_data.ndim != 3: - raise ValueError( - "Argument sdf_data to SignedDistanceField2D must be a batch of matrices." - ) - if not (origin.ndim == 2 or (origin.ndim == 3 and origin.shape[2] == 1)): + @staticmethod + def convert_origin(origin: Union[torch.Tensor, Point2]) -> Point2: + if not isinstance(origin, Point2) and not isinstance(origin, torch.Tensor): raise ValueError( - "Argument origin to SignedDistanceField2D must be a batch of 2-D tensors." + "Argument origin to SignedDistanceField2D must be either " + "a tensor or a Point2 variable." ) + if not isinstance(origin, Point2): + try: + return Point2(tensor=origin) + except ValueError: + raise ValueError( + "Argument origin to SignedDistanceField2D must be a batch of " + "2D tensors." + ) + return origin + + @staticmethod + def convert_cell_size(cell_size: Union[float, torch.Tensor, Variable]) -> Variable: + if not isinstance(cell_size, Variable): + if not isinstance(cell_size, torch.Tensor): + if not isinstance(cell_size, float): + raise ValueError( + "Argument cell_size must be either a Variable, " + "tensor, or float." + ) + cell_size = torch.tensor(cell_size).view(-1, 1) + return Variable(cell_size) if not ( cell_size.ndim == 1 or (cell_size.ndim == 2 and cell_size.shape[1] == 1) ): + raise ValueError("Argument cell_size must be a batch of 0D or 1D tensors.") + return cell_size + + @staticmethod + def convert_sdf_data(sdf_data: Union[torch.Tensor, Variable]) -> Variable: + if not isinstance(sdf_data, Variable): + sdf_data = Variable(sdf_data) + if sdf_data.ndim != 3: raise ValueError( - "Argument cell_size must be a batch of 0-D or 1-D tensors." + "Argument sdf_data to SignedDistanceField2D must be a " + "batch of matrices." ) - if ( - origin.shape[0] != sdf_data.shape[0] - or origin.shape[0] != cell_size.shape[0] - ): - raise ValueError("Incompatible batch size between input arguments.") - self.origin = origin - self.sdf_data = sdf_data - self.cell_size = cell_size + return sdf_data + + def update_data( + self, + origin: Union[torch.Tensor, Point2], + sdf_data: Union[torch.Tensor, Variable], + cell_size: Union[float, torch.Tensor, Variable], + ): + # Update origin + self.origin = SignedDistanceField2D.convert_origin(origin) + + # Update cell size + self.cell_size = SignedDistanceField2D.convert_cell_size(cell_size) + + # Update sdf_data + self.sdf_data = SignedDistanceField2D.convert_sdf_data(sdf_data) def convert_points_to_cell( self, points: torch.Tensor diff --git a/theseus/embodied/collision/tests/__init__.py b/theseus/embodied/collision/tests/__init__.py new file mode 100644 index 000000000..7bec24cb1 --- /dev/null +++ b/theseus/embodied/collision/tests/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) Meta Platforms, Inc. and affiliates. +# +# This source code is licensed under the MIT license found in the +# LICENSE file in the root directory of this source tree. diff --git a/theseus/embodied/collision/tests/test_collision_factor.py b/theseus/embodied/collision/tests/test_collision_factor.py index 8678581fc..49e21708a 100644 --- a/theseus/embodied/collision/tests/test_collision_factor.py +++ b/theseus/embodied/collision/tests/test_collision_factor.py @@ -13,24 +13,23 @@ check_another_torch_tensor_is_copy, ) from theseus.utils import numeric_jacobian +from .utils import random_scalar, random_origin, random_sdf_data def test_collision2d_error_shapes(): - generator = torch.Generator() - generator.manual_seed(0) cost_weight = th.ScaleCostWeight(1.0) for batch_size in [1, 10, 100]: for field_widht in [1, 10, 100]: for field_height in [1, 10, 100]: pose = th.Point2(tensor=torch.randn(batch_size, 2).double()) - origin = torch.randn(batch_size, 2) - sdf_data = torch.randn(batch_size, field_widht, field_height) - cell_size = torch.randn(batch_size, 1) + origin = random_origin(batch_size) + sdf_data = random_sdf_data(batch_size, field_widht, field_height) + cell_size = random_scalar(batch_size) cost_function = th.eb.Collision2D( pose, - th.Variable(origin), - th.Variable(sdf_data), - th.Variable(cell_size), + origin, + sdf_data, + cell_size, th.Variable(torch.ones(1)), cost_weight, name="cost_function", @@ -46,15 +45,15 @@ def test_collision2d_copy(): batch_size = 20 cost_weight = th.ScaleCostWeight(1.0) pose = th.Point2(tensor=torch.randn(batch_size, 2).double()) - origin = torch.ones(batch_size, 2) - sdf_data = torch.ones(batch_size, 1, 1) - cell_size = torch.ones(batch_size, 1) + origin = random_origin(batch_size) + sdf_data = random_sdf_data(batch_size, 1, 1) + cell_size = random_scalar(batch_size) cost_function = th.eb.Collision2D( pose, - th.Variable(origin), - th.Variable(sdf_data), - th.Variable(cell_size), - th.Variable(torch.ones(1)), + origin, + sdf_data, + cell_size, + 1.0, cost_weight, name="name", ) @@ -84,7 +83,7 @@ def test_collision2d_jacobians(): for batch_size in [1, 10, 100, 1000]: cost_weight = th.ScaleCostWeight(torch.ones(1).squeeze().double()) pose = th.Point2(tensor=torch.randn(batch_size, 2, generator=rng).double()) - origin = th.Variable(torch.ones(batch_size, 2).double()) + origin = th.Point2(torch.ones(batch_size, 2).double()) sdf_data = th.Variable( torch.randn(batch_size, 10, 10, generator=rng).double() ) diff --git a/theseus/embodied/collision/tests/test_eff_obj_contact.py b/theseus/embodied/collision/tests/test_eff_obj_contact.py index f003d5879..b3b9f4b9b 100644 --- a/theseus/embodied/collision/tests/test_eff_obj_contact.py +++ b/theseus/embodied/collision/tests/test_eff_obj_contact.py @@ -8,6 +8,11 @@ import torch import theseus as th +from theseus.embodied.collision.tests.utils import ( + random_origin, + random_sdf_data, + random_scalar, +) from theseus.geometry.tests.test_se2 import create_random_se2 from theseus.utils import numeric_jacobian @@ -18,10 +23,10 @@ def test_eff_obj_interesect_jacobians(): for batch_size in [1, 10, 100]: obj = create_random_se2(batch_size, rng) eff = create_random_se2(batch_size, rng) - origin = th.Variable(torch.randn(batch_size, 2).double()) - sdf_data = th.Variable(torch.randn(batch_size, 10, 10).double()) - cell_size = th.Variable(torch.rand(batch_size, 1).double()) - eff_radius = th.Variable(torch.rand(batch_size, 1).double()) + origin = random_origin(batch_size) + sdf_data = random_sdf_data(batch_size, 10, 10) + cell_size = random_scalar(batch_size) + eff_radius = random_scalar(batch_size) cost_weight = th.ScaleCostWeight(1.0) cost_function = th.eb.EffectorObjectContactPlanar( obj, eff, origin, sdf_data, cell_size, eff_radius, cost_weight @@ -139,10 +144,10 @@ def test_eff_obj_interesect_errors(): cost_fn = th.eb.EffectorObjectContactPlanar( obj, eff, - th.Variable(origin.repeat(5, 1)), - th.Variable(sdf_data.repeat(5, 1, 1)), - th.Variable(cell_size.repeat(5, 1)), - th.Variable(eff_radius), + origin.repeat(5, 1), + sdf_data.repeat(5, 1, 1), + cell_size.repeat(5, 1), + eff_radius, cost_weight, ) @@ -154,37 +159,43 @@ def test_eff_obj_interesect_errors(): def test_eff_obj_variable_type(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 10, 100]: - obj = create_random_se2(batch_size, rng) - eff = create_random_se2(batch_size, rng) - origin = th.Variable(torch.randn(batch_size, 2).double()) - sdf_data = th.Variable(torch.randn(batch_size, 10, 10).double()) - cell_size = th.Variable(torch.rand(batch_size, 1).double()) - eff_radius = th.Variable(torch.rand(batch_size, 1).double()) - cost_weight = th.ScaleCostWeight(1.0) - cost_function = th.eb.EffectorObjectContactPlanar( - obj, eff, origin, sdf_data, cell_size, eff_radius, cost_weight - ) + for _ in range(10): + for batch_size in [1, 10, 100]: + obj = create_random_se2(batch_size, rng) + eff = create_random_se2(batch_size, rng) + origin = random_origin(batch_size) + sdf_data = random_sdf_data(batch_size, 10, 10) + cell_size = random_scalar(batch_size) + eff_radius = random_scalar(batch_size) + cost_weight = th.ScaleCostWeight(1.0) + cost_function = th.eb.EffectorObjectContactPlanar( + obj, eff, origin, sdf_data, cell_size, eff_radius, cost_weight + ) - assert isinstance(cost_function.eff_radius, th.Variable) - assert cost_function.eff_radius is eff_radius + assert isinstance(cost_function.eff_radius, th.Variable) + if isinstance(eff_radius, th.Variable): + assert cost_function.eff_radius is eff_radius + else: + assert np.allclose( + cost_function.eff_radius.tensor.cpu().numpy(), eff_radius + ) - eff_radius_t = torch.rand(batch_size, 1).double() + eff_radius_t = torch.rand(batch_size, 1).double() - cost_function = th.eb.EffectorObjectContactPlanar( - obj, eff, origin, sdf_data, cell_size, eff_radius_t, cost_weight - ) + cost_function = th.eb.EffectorObjectContactPlanar( + obj, eff, origin, sdf_data, cell_size, eff_radius_t, cost_weight + ) - assert isinstance(cost_function.eff_radius, th.Variable) - assert np.allclose(cost_function.eff_radius.tensor, eff_radius_t) - assert len(cost_function.eff_radius.shape) == 2 + assert isinstance(cost_function.eff_radius, th.Variable) + assert np.allclose(cost_function.eff_radius.tensor, eff_radius_t) + assert len(cost_function.eff_radius.shape) == 2 - eff_radius_f = torch.rand(1) + eff_radius_f = torch.rand(1) - cost_function = th.eb.EffectorObjectContactPlanar( - obj, eff, origin, sdf_data, cell_size, eff_radius_f, cost_weight - ) + cost_function = th.eb.EffectorObjectContactPlanar( + obj, eff, origin, sdf_data, cell_size, eff_radius_f, cost_weight + ) - assert isinstance(cost_function.eff_radius, th.Variable) - assert np.allclose(cost_function.eff_radius.tensor.item(), eff_radius_f) - assert len(cost_function.eff_radius.shape) == 2 + assert isinstance(cost_function.eff_radius, th.Variable) + assert np.allclose(cost_function.eff_radius.tensor.item(), eff_radius_f) + assert len(cost_function.eff_radius.shape) == 2 diff --git a/theseus/embodied/collision/tests/test_signed_distance_field.py b/theseus/embodied/collision/tests/test_signed_distance_field.py index 5900e99b5..ceb7ab059 100644 --- a/theseus/embodied/collision/tests/test_signed_distance_field.py +++ b/theseus/embodied/collision/tests/test_signed_distance_field.py @@ -8,6 +8,7 @@ import theseus as th from theseus.utils import numeric_jacobian +from .utils import random_sdf def test_sdf_2d_shapes(): @@ -17,13 +18,8 @@ def test_sdf_2d_shapes(): for field_width in [1, 10, 100]: for field_height in [1, 10, 100]: for num_points in [1, 10, 100]: - origin = th.Variable(tensor=torch.randn(batch_size, 2)) - sdf_data = th.Variable( - tensor=torch.randn(batch_size, field_width, field_height) - ) points = th.Variable(tensor=torch.randn(batch_size, 2, num_points)) - cell_size = th.Variable(tensor=torch.randn(batch_size, 1)) - sdf = th.eb.SignedDistanceField2D(origin, cell_size, sdf_data) + sdf = random_sdf(batch_size, field_width, field_height) dist, jac = sdf.signed_distance(points) assert dist.shape == (batch_size, num_points) assert jac.shape == (batch_size, num_points, 2) @@ -39,11 +35,7 @@ def test_signed_distance_2d(): [1.7321, 1.4142, 1.4142, 1.4142, 1.7321], ] ).view(1, 5, 5) - sdf = th.eb.SignedDistanceField2D( - th.Variable(-0.2 * torch.ones(1, 2)), - th.Variable(0.1 * torch.ones(1, 1)), - th.Variable(data), - ) + sdf = th.eb.SignedDistanceField2D(-0.2 * torch.ones(1, 2), 0.1, data) points = torch.tensor([[0, 0], [0.18, -0.17]]) rows, cols, _ = sdf.convert_points_to_cell(points) @@ -67,7 +59,7 @@ def test_sdf_2d_creation(): map2 = torch.zeros(5, 5) data_maps = th.Variable(torch.stack([map1, map2])) sdf_batch = th.eb.SignedDistanceField2D( - -0.2 * torch.ones(2, 2), 0.1 * torch.ones(2, 1), occupancy_map=data_maps + -0.2 * torch.ones(2, 2), 0.1, occupancy_map=data_maps ) # generate verification data for map1 import numpy as np @@ -94,10 +86,7 @@ def test_sdf_2d_creation(): def test_signed_distance_2d_jacobian(): for batch_size in [1, 10, 100]: - origin = th.Variable(torch.randn(batch_size, 2).double()) - sdf_data = th.Variable(torch.randn(batch_size, 10, 10).double()) - cell_size = th.Variable(torch.rand(batch_size, 1).double()) - sdf = th.eb.SignedDistanceField2D(origin, cell_size, sdf_data) + sdf = random_sdf(batch_size, 10, 10) for num_points in [1, 10]: points = torch.randn(batch_size, 2, num_points).double() _, jacobian = sdf.signed_distance(points) diff --git a/theseus/embodied/collision/tests/utils.py b/theseus/embodied/collision/tests/utils.py new file mode 100644 index 000000000..780cbf87c --- /dev/null +++ b/theseus/embodied/collision/tests/utils.py @@ -0,0 +1,40 @@ +# Copyright (c) Meta Platforms, Inc. and affiliates. +# +# This source code is licensed under the MIT license found in the +# LICENSE file in the root directory of this source tree. + +import torch +import theseus as th + + +def random_scalar(batch_size): + number = torch.rand(1).item() + # Test with all possible cell_size inputs + if number < 1.0 / 3: + return th.Variable(tensor=torch.randn(batch_size, 1)) + elif number < 2.0 / 3: + return torch.randn(batch_size, 1) + else: + return torch.randn(1).item() + + +def random_origin(batch_size): + origin_tensor = torch.randn(batch_size, 2) + if torch.rand(1).item() < 0.5: + return th.Point2(tensor=origin_tensor) + return origin_tensor + + +def random_sdf_data(batch_size, field_width, field_height): + sdf_data_tensor = torch.randn(batch_size, field_width, field_height) + if torch.rand(1).item() < 0.5: + return th.Variable(tensor=sdf_data_tensor) + return sdf_data_tensor + + +def random_sdf(batch_size, field_width, field_height): + return th.eb.SignedDistanceField2D( + random_origin(batch_size), + random_scalar(batch_size), + random_sdf_data(batch_size, field_width, field_height), + ) diff --git a/theseus/utils/examples/tactile_pose_estimation/pose_estimator.py b/theseus/utils/examples/tactile_pose_estimation/pose_estimator.py index 417a0fa1d..06873f8ee 100644 --- a/theseus/utils/examples/tactile_pose_estimation/pose_estimator.py +++ b/theseus/utils/examples/tactile_pose_estimation/pose_estimator.py @@ -63,7 +63,7 @@ def __init__( sdf_data = th.Variable(dataset.sdf_data_tensor, name="sdf_data") sdf_cell_size = th.Variable(dataset.sdf_cell_size, name="sdf_cell_size") - sdf_origin = th.Variable(dataset.sdf_origin, name="sdf_origin") + sdf_origin = th.Point2(dataset.sdf_origin, name="sdf_origin") eff_radius = th.Variable(torch.zeros(1, 1), name="eff_radius") # -------------------------------------------------------------------- # diff --git a/tutorials/04_motion_planning.ipynb b/tutorials/04_motion_planning.ipynb index dcc9f0805..0d8dd7eed 100644 --- a/tutorials/04_motion_planning.ipynb +++ b/tutorials/04_motion_planning.ipynb @@ -2,6 +2,7 @@ "cells": [ { "cell_type": "markdown", + "id": "a28f8efa", "metadata": {}, "source": [ "# Motion Planning Part 1: motion planning as nonlinear least squares optimization" @@ -9,6 +10,7 @@ }, { "cell_type": "markdown", + "id": "12f6539a", "metadata": {}, "source": [ "In this tutorial, we will learn how to implement the [GPMP2](https://journals.sagepub.com/doi/pdf/10.1177/0278364918790369) (Mukadam et al, 2018) motion planning algorithm, for a 2D robot in a planar environment.\n", @@ -22,6 +24,7 @@ { "cell_type": "code", "execution_count": 1, + "id": "79f641dc", "metadata": {}, "outputs": [], "source": [ @@ -52,6 +55,7 @@ }, { "cell_type": "markdown", + "id": "6694efe6", "metadata": {}, "source": [ "## 1. Loading and visualizing the trajectory data" @@ -59,6 +63,7 @@ }, { "cell_type": "markdown", + "id": "728c17aa", "metadata": {}, "source": [ "First, let's load some motion planning problems from a dataset of maps and trajectories generated using the code in [dgpmp2](https://github.com/mhmukadam/dgpmp2)." @@ -67,6 +72,7 @@ { "cell_type": "code", "execution_count": 2, + "id": "5e64eb2e", "metadata": {}, "outputs": [], "source": [ @@ -79,6 +85,7 @@ }, { "cell_type": "markdown", + "id": "4095fd09", "metadata": {}, "source": [ "The batch is a dictionary of strings to `torch.Tensor` containing the following keys:" @@ -87,6 +94,7 @@ { "cell_type": "code", "execution_count": 3, + "id": "e7e1f69b", "metadata": {}, "outputs": [ { @@ -109,6 +117,7 @@ }, { "cell_type": "markdown", + "id": "bc9faea7", "metadata": {}, "source": [ "Let's plot the maps and trajectories loaded. `th.eb.SignedDistanceField2D` is a signed distance field object, which includes a function to convert *x,y*-coordinates to map cells that we use here for plotting. For completeness, we show the expert trajectories loaded, although we won't use them in this example (we will do so in Part 2 of this tutorial)." @@ -117,13 +126,14 @@ { "cell_type": "code", "execution_count": 4, + "id": "28498013", "metadata": { "scrolled": false }, "outputs": [ { "data": { - "image/png": "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", + "image/png": "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\n", "text/plain": [ "
" ] @@ -133,7 +143,7 @@ }, { "data": { - "image/png": "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", + "image/png": "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\n", "text/plain": [ "
" ] @@ -144,7 +154,7 @@ ], "source": [ "sdf = th.eb.SignedDistanceField2D(\n", - " th.Variable(batch[\"sdf_origin\"]),\n", + " th.Point2(batch[\"sdf_origin\"]),\n", " th.Variable(batch[\"cell_size\"]),\n", " th.Variable(batch[\"sdf_data\"]),\n", ")\n", @@ -163,6 +173,7 @@ }, { "cell_type": "markdown", + "id": "cab578f8", "metadata": {}, "source": [ "The following are some constants that we will use throughout the example" @@ -171,6 +182,7 @@ { "cell_type": "code", "execution_count": 5, + "id": "cf626274", "metadata": {}, "outputs": [], "source": [ @@ -188,6 +200,7 @@ }, { "cell_type": "markdown", + "id": "debc9416", "metadata": {}, "source": [ "## 2. Modeling the problem" @@ -195,6 +208,7 @@ }, { "cell_type": "markdown", + "id": "8ab0db1c", "metadata": {}, "source": [ "### 2.1. Defining Variable objects" @@ -202,6 +216,7 @@ }, { "cell_type": "markdown", + "id": "30eba75d", "metadata": {}, "source": [ "Our goal in this example will be to use `Theseus` to produce plans for the maps loaded above. As mentioned in the introduction, we need a 2D pose and a 2D velocity for each point along the trajectory to be optimized. For this, we will create a set of `th.Point2` variables with individual names, and store them in two lists so that they can be later passed to the appropriate cost functions." @@ -210,6 +225,7 @@ { "cell_type": "code", "execution_count": 6, + "id": "495b6840", "metadata": {}, "outputs": [], "source": [ @@ -223,6 +239,7 @@ }, { "cell_type": "markdown", + "id": "ffe66510", "metadata": {}, "source": [ "In addition to the optimization variables, we will also need a set of *auxiliary* variables to wrap map-dependent quantities involved in cost function computation, but that are constant throughout the optimization. This includes start/goal target values, as well as parameters for collision and dynamics cost functions." @@ -231,6 +248,7 @@ { "cell_type": "code", "execution_count": 7, + "id": "5bea3236", "metadata": {}, "outputs": [], "source": [ @@ -250,6 +268,7 @@ }, { "cell_type": "markdown", + "id": "fff1446e", "metadata": {}, "source": [ "### 2.2. Cost weights" @@ -257,6 +276,7 @@ }, { "cell_type": "markdown", + "id": "21cf8dd2", "metadata": {}, "source": [ "Next we will create a series of cost weights to use for each of the cost functions involved in our optimization problem." @@ -265,6 +285,7 @@ { "cell_type": "code", "execution_count": 8, + "id": "1149ed5e", "metadata": {}, "outputs": [], "source": [ @@ -281,6 +302,7 @@ }, { "cell_type": "markdown", + "id": "3da7695c", "metadata": {}, "source": [ "### 2.3. Cost functions" @@ -288,6 +310,7 @@ }, { "cell_type": "markdown", + "id": "6d9e8067", "metadata": {}, "source": [ "In this section, we will now create a `Theseus` objective and add the GPMP2 cost functions for motion planning. First, we create the objective:" @@ -296,6 +319,7 @@ { "cell_type": "code", "execution_count": 9, + "id": "e3b30cc3", "metadata": {}, "outputs": [], "source": [ @@ -304,6 +328,7 @@ }, { "cell_type": "markdown", + "id": "120726d4", "metadata": {}, "source": [ "#### Boundary cost functions" @@ -311,6 +336,7 @@ }, { "cell_type": "markdown", + "id": "71e4cba9", "metadata": {}, "source": [ "Here we create cost functions for the boundary conditions, assign names to them, and add them to the `Objective`. For boundaries, we need four cost functions, and for each we use a cost function of type `th.Difference`. This cost function type takes as input an optimization variable, a cost weight, a target auxiliary variable, and a name. Its error function is the local difference between the optimization variable and the target.\n", @@ -323,6 +349,7 @@ { "cell_type": "code", "execution_count": 10, + "id": "627b38e0", "metadata": {}, "outputs": [], "source": [ @@ -356,6 +383,7 @@ }, { "cell_type": "markdown", + "id": "bfa02b0f", "metadata": {}, "source": [ "#### Collision cost functions" @@ -363,6 +391,7 @@ }, { "cell_type": "markdown", + "id": "fb8b31c8", "metadata": {}, "source": [ "For collision avoidance, we use a `th.eb.Collision2D` cost function type, which receives the following inputs:\n", @@ -379,6 +408,7 @@ { "cell_type": "code", "execution_count": 11, + "id": "fd5bc03e", "metadata": {}, "outputs": [], "source": [ @@ -398,6 +428,7 @@ }, { "cell_type": "markdown", + "id": "d65413f5", "metadata": {}, "source": [ "#### GP-dynamics cost functions" @@ -405,6 +436,7 @@ }, { "cell_type": "markdown", + "id": "242a2f8e", "metadata": {}, "source": [ "For ensuring smooth trajectories, we use a `th.eb.GPMotionModel` cost function, which receives the following inputs:\n", @@ -419,6 +451,7 @@ { "cell_type": "code", "execution_count": 12, + "id": "88de9eb4", "metadata": {}, "outputs": [], "source": [ @@ -440,6 +473,7 @@ }, { "cell_type": "markdown", + "id": "2657cc4b", "metadata": {}, "source": [ "## Creating the TheseusLayer for motion planning" @@ -447,6 +481,7 @@ }, { "cell_type": "markdown", + "id": "268594c8", "metadata": {}, "source": [ "For this example, we will use Levenberg-Marquardt as the non-linear optimizer, coupled with a dense linear solver based on Cholesky decomposition." @@ -455,6 +490,7 @@ { "cell_type": "code", "execution_count": 13, + "id": "27461337", "metadata": {}, "outputs": [], "source": [ @@ -470,6 +506,7 @@ }, { "cell_type": "markdown", + "id": "ee023057", "metadata": {}, "source": [ "## 3. Running the optimizer" @@ -477,6 +514,7 @@ }, { "cell_type": "markdown", + "id": "fd6989ef", "metadata": {}, "source": [ "Finally, we are ready to generate some optimal plans. We first initialize all auxiliary variables whose values are map dependent (e.g., start and goal positions, or SDF data). We also provide some sensible initial values for the optimization variables; in this example, we will initialize the optimizaton variables to be on a straight line from start to goal. The following helper function will be useful for this:" @@ -485,6 +523,7 @@ { "cell_type": "code", "execution_count": 14, + "id": "12db4db3", "metadata": {}, "outputs": [], "source": [ @@ -506,6 +545,7 @@ }, { "cell_type": "markdown", + "id": "88ac4456", "metadata": {}, "source": [ "Now, let's pass the motion planning data to our `TheseusLayer` and start create some trajectories; note that we can solve for both trajectories simultaneously by taking advantage of Theseus' batch support. For initializing variables, we create a dictionary mapping strings to `torch.Tensor`, where the keys are `th.Variable` names, and the values are the tensors that should be used for their initial values. " @@ -514,6 +554,7 @@ { "cell_type": "code", "execution_count": 15, + "id": "86b7c9fe", "metadata": { "scrolled": false }, @@ -600,6 +641,7 @@ }, { "cell_type": "markdown", + "id": "dc5b2307", "metadata": {}, "source": [ "## 4. Results" @@ -607,6 +649,7 @@ }, { "cell_type": "markdown", + "id": "2f5dd147", "metadata": {}, "source": [ "After the optimization is completed, we can query the optimization variables to obtain the final trajectory and visualize the result. The following function creates a trajectory tensor from the output dictionary of `TheseusLayer`." @@ -615,6 +658,7 @@ { "cell_type": "code", "execution_count": 16, + "id": "de6fabcd", "metadata": {}, "outputs": [], "source": [ @@ -628,6 +672,7 @@ }, { "cell_type": "markdown", + "id": "bb85ef5f", "metadata": {}, "source": [ "Let's now plot the final trajectories" @@ -636,11 +681,12 @@ { "cell_type": "code", "execution_count": 17, + "id": "98cbadf9", "metadata": {}, "outputs": [ { "data": { - "image/png": "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", + "image/png": "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\n", "text/plain": [ "
" ] @@ -650,7 +696,7 @@ }, { "data": { - "image/png": "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", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAZsAAAGQCAYAAAB4X807AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/YYfK9AAAACXBIWXMAAAsTAAALEwEAmpwYAAB82ElEQVR4nO2deZhcVZn/P7VXb+kl+0oCkQCdmBCaJToQCRBQSdhlCwMqBkTkJw64gbgNgwIzjjiIJk5QFBADCmELDCQsgooRAzFB2RKykYV0d3qt/f7+OPftc6q6EzqkK92dfj/PU09X3fXcW13ne9/lvCfgeZ6HoiiKohSRYG83QFEURdn/UbFRFEVRio6KjaIoilJ0VGwURVGUoqNioyiKohQdFRtFURSl6PSa2GzYsIGzzz6byspKBg0axJlnnsn69et7qzmKoihKEQn0xjibtrY2pk6dSiwW49///d8JBAJcf/31tLW18eqrr1JWVravm6QoiqIUkXBvnHThwoW8/fbb/POf/2TixIkAfPjDH+ZDH/oQP/vZz/jyl7/cG81SFEVRikSvWDYnnHACiUSCF154IW/5zJkzAXj22Wf3dZMURVGUItIrls3q1as57bTTOi2vra1l8eLF77v/kCFDGD9+fBFapiiKonxQ1q1bx3vvvdflul4Rm/r6eqqrqzstr6mpoaGh4X33Hz9+PCtWrChG0xRFUZQPSF1d3S7X9YrYfBAWLFjAggULANi+fXsvt0ZRFEXZE3ol9bm6urpLC2ZXFg/A/PnzWbFiBStWrGDo0KHFbqKiKIrSg/SK2NTW1rJ69epOy9esWcNhhx3WCy1SFEVRikmvuNHmzp3LNddcw9tvv82BBx4ImMDSCy+8wPe///3eaJKiKB+AdDrNxo0bSSQSvd0UZR8Sj8cZM2YMkUik2/v0Supza2srU6dOpaSkpGNQ5ze/+U2am5t59dVXKS8v3+3+dXV1miCgKH2AtWvXUlFRweDBgwkEAr3dHGUf4HkeO3bsoLm5mQkTJuSt213f3CtutLKyMpYtW8bBBx/MRRddxIUXXsiECRNYtmzZ+wqNoih9h0QioUIzwAgEAgwePHiPrdley0YbN24cDzzwQG+dXlGUHkKFZuDxQb5zrfqsKIqiFJ1+M85GUZS+z4hbR7C1dWuPHW942XC2XLOlx473sY99jFtvvXW3gw8ffPBBDj744I7M2BtuuIHjjjuOE088ca/OvXLlSjZv3swnPvGJPdpv8+bNXHXVVdx///17fM5f/OIXzJ49m1GjRu3xvj2NWjaKovQYPSk0xThed3jwwQdZs2ZNx+fvfve7ey00YMTmscce63JdJpPZ5X6jRo36QEIDRmw2b968R/tks9kPdK73Q8VGUZR+S2trK5/85CeZOnUqkydP5r777gPg6aef5vDDD2fKlCl85jOfIZlMdtrXTUa6//77ueSSS3jxxRdZsmQJ1157LdOmTeOtt97ikksu6ejsd3Xc8ePH861vfYvp06czZcoU/vGPf+SdK5VKccMNN3Dfffcxbdo07rvvPr797W9z0UUX8dGPfpSLLrqIdevWceyxxzJ9+nSmT5/Oiy++CJhhIZMnTwaMEFx77bUceeSRfPjDH+ZnP/tZxzl+8IMfMGXKFKZOncrXvvY17r//flasWMGFF17ItGnTaG9v3237v/rVrzJ9+nS+//3vM3369I7jvvHGG3mfPygqNoqi9FuWLl3KqFGjeOWVV/j73//OKaecQiKR4JJLLuG+++5j1apVZDIZ7rjjjm4d7yMf+Qhz587llltuYeXKlRx00EEd697vuEOGDOHll1/m85//PLfeemvecaPRKN/97nc599xzWblyJeeeey5gBrI/9dRT3HvvvQwbNoz/+7//4+WXX+a+++7jqquu6tS+//3f/6WyspK//OUv/OUvf2HhwoWsXbuWxx9/nIceeog///nPvPLKK3zlK1/h7LPPpq6ujrvvvpuVK1cSCAR22/7Bgwfz8ssvc91111FZWcnKlSsBuPPOO/n0pz/d7e9kV6jYKIrSb5kyZQr/93//x1e/+lWef/55Kisr+ec//8mECRM4+OCDAbj44ot57rnn9vpc73fcM888E4AjjjiCdevWdeuYc+fOpaSkBDADZD/3uc8xZcoUzjnnnDxXnvDkk09y1113MW3aNI4++mh27NjBG2+8wVNPPcWnP/1pSktLAVPUeE/bLwIIcOmll3LnnXeSzWa57777uOCCC7p1PbtDEwQURem3HHzwwbz88ss89thjXH/99ZxwwgldTl/SFW76bk9UQIjFYgCEQqHdxmBc3FmJf/jDHzJ8+HBeeeUVcrkc8Xi80/ae5/HjH/+Yk08+OW/5E088sRct79yWs846i+985zvMmjWLI444gsGDB+/18dWyURSl37J582ZKS0uZN28e1157LS+//DKTJk1i3bp1vPnmmwD86le/6piY0WX48OG89tpr5HI5fv/733csr6iooLm5udP23T3urtjVcYWdO3cycuRIgsEgv/rVr7oM1J988snccccdpNNpAF5//XVaW1s56aSTuPPOO2lrawNMUePCc+5J++PxOCeffDKf//zne8SFBio2iqL0IMPLhu/T461atYqjjjqKadOm8Z3vfIfrr7+eeDzOnXfeyTnnnMOUKVMIBoNcfvnlnfb9/ve/z6mnnspHPvIRRo4c2bH8vPPO45ZbbuHwww/nrbfe6lje3ePuiuOPP541a9Z0JAgUcsUVV/DLX/6SqVOn8o9//CPP0hAr7NJLL+Wwww5j+vTpTJ48mcsuu4xMJsMpp5zC3LlzqaurY9q0aR0xo0suuYTLL7+cadOm4XneHrX/wgsvJBgMMnv27G5f4+7oldpoe4vWRlOUvsFrr73GoYce2tvN2K/561//ype//GWeffbZfXreW2+9lZ07d/K9732vy/Vdffe765s1ZqMoitJHWbFiBRdccME+r4Z/xhln8NZbb7Fs2bIeO6aKjaIoSh+lrq6O119/fZ+f141h9RQas1EURVGKjoqNoiiKUnRUbBRFUZSio2KjKIqiFB0VG0VReo4RQKAHXyOK08xnnnmGU089FYAlS5bs82wvgJtuuomJEycyadKk960AcNVVV/X7WYw1G01RlJ6jp2cE2IPjeZ6H53kEg3v2DD137lzmzp27hw3bO9asWcNvfvMbVq9ezebNmznxxBN5/fXXCYVCnbZdsWIFDQ0N+7R9xUAtG0VR+i3r1q1j0qRJ/Ou//iuTJ09mw4YNfP7zn6euro7a2lq+9a1vdWy7dOlSDjnkEKZPn87vfve7juW/+MUvuPLKKwHyphMAOw3Bu+++y3HHHce0adOYPHkyzz///F61+6GHHuK8884jFosxYcIEJk6cyEsvvdRpO5lS4Oabb96r8/UF1LJRFKVf88Ybb/DLX/6SY445BoAbb7yRmpoastksJ5xwAq+++ioHH3wwn/vc51i2bBkTJ07Mq3DcHe655x5OPvlkrrvuOrLZbEcNMperr76a5cuXd1p+3nnn8bWvfS1v2aZNmzraCzBmzBg2bdrUad//+Z//Ye7cuXnldPorKjaKovRrDjjggLyO+7e//S0LFiwgk8nw7rvvsmbNGnK5HBMmTOBDH/oQAPPmzWPBggXdPseRRx7JZz7zGdLpNKeffjrTpk3rtM0Pf/jDvb4Wl82bN7N48WKeeeaZHj1ub6FuNEVR+jVuwcq1a9dy66238vTTT/Pqq6/yyU9+co+mDwiHw+RyOQByuRypVAqA4447jueee47Ro0dzySWXcNddd3Xa9+qrr2batGmdXl0lH4wePZoNGzZ0fN64cSOjR4/O2+Zvf/sbb775JhMnTmT8+PG0tbUxceLEbl9LX0MtG0VR9huampooKyujsrKSrVu38vjjj/Oxj32MQw45hHXr1vHWW29x0EEHce+993a5//jx4/nrX//Kpz71KZYsWdJRyv+dd95hzJgxfO5znyOZTPLyyy/zr//6r3n77ollM3fuXC644AK+/OUvs3nzZt544w2OOuqovG0++clPsmXLlo7P5eXlHdMD9EdUbBRF6TmG07MZaXs4Y8HUqVM5/PDDOeSQQxg7diwf/ehHATM9wIIFC/jkJz9JaWkpxx57bJdzy3zuc5/jtNNOY+rUqZxyyikdVtMzzzzDLbfcQiQSoby8vEvLZk+ora3lU5/6FIcddhjhcJjbb7+9IxPtE5/4BD//+c8ZNWrUXp2jr6FTDCiK8oHRKQYGLns6xYDGbBRFUZSio2KjKIqiFB0VG0VR9op+6IlX9pIP8p2r2CiK8oGJx+Ps2LFDBWcA4XkeO3bsIB6P79F+mo2mKMoHZsyYMWzcuJHt27f3dlOUfUg8HmfMmDF7tI+KjaIoH5hIJMKECRN6uxlKP0DdaIqiKErRUbFRFEVRio6KjaIoilJ0VGwURVGUoqNioyiKohQdFRtFURSl6KjYKIqiKEVHxUZRFEUpOio2iqIoStFRsVEURVGKjoqNoiiKUnRUbBRFUZSi06Nic//993PWWWdxwAEHUFJSwqRJk/j617/eaa7vhoYGLr30UoYMGUJZWRknnngiq1at6smmKIqiKH2IHhWbW2+9lVAoxH/8x3+wdOlSPv/5z3PHHXdw0kknkcvlADMXwpw5c1i6dCk//vGPeeCBB0in0xx//PFs3LixJ5ujKIqi9BF6dIqBhx9+mKFDh3Z8njlzJjU1NVx88cU888wzzJo1iyVLlvDCCy+wbNkyjj/+eABmzJjBhAkTuPnmm7ntttt6skmKoihKH6BHLRtXaIQjjzwSgE2bNgGwZMkSRo0a1SE0AJWVlcyZM4eHHnqoJ5ujKIqi9BGKniDw7LPPAnDooYcCsHr1aiZPntxpu9raWtavX09LS0uxm6QoiqLsY4oqNps2beKGG27gxBNPpK6uDoD6+nqqq6s7bVtTUwOY5IH9mhyQAhJA0n+v07crirKfU7RpoVtaWjjttNMIh8Pceeede328BQsWsGDBAoD+N995Ctjpv9qBjL88gJH7CFACVAHl6GTdiqLsdxSlW2tvb2fOnDm8/fbbPPvss4wZM6ZjXXV1dZfWS319fcf6rpg/fz7z588H6LCS+jwJYBNQjxGcEMayCTjbBDDfQjOwHSgFBgNDUNFRFGW/oce7s3Q6zdlnn82KFSv4v//7P6ZMmZK3vra2lieffLLTfmvWrGHcuHGUl5f3dJP2PTmMcLyNsWJEXJLki41YNln/bwBj+awH3gPGARXki5OiKEo/pEdjNrlcjgsvvJBly5bx4IMPcswxx3TaZu7cuWzatKkjcQCgqamJhx9+mLlz5/Zkc3qHDPBPYDVGXNIYC6cdY91k/FfWX5fyt5P1KYwgtQNvAFvRmI6iKP2eHrVsvvCFL7B48WKuu+46ysrK+NOf/tSxbsyYMYwZM4a5c+cyY8YM5s2bxy233EJ1dTU33XQTnufxla98pSebs+/JYERmK8YayfrLcv6rK8S6ifnbpjExnAjG7bbBP84o1MJRFKXf0qOWzeOPPw7AjTfeyIwZM/JeP//5z80Jg0EeeeQRTjrpJK644grOOOMMQqEQy5cvZ+zYsT3ZnH2Lh7Fo3sGIQ8J/iaWSwwiJvLJYofGANv8l2yWc7TZj3GqKoij9lIDnef3OSVNXV8eKFSt6uxn5bAb+jLEVxYoRywaMsBRaJjlnXczfN4uxaGL+uri/PAoc6n9WFEXpg+yub9Z8p56gHXgZIxSe89fDCIm40kTWAxhBkVcAY8mAFZM2TGZaAiM8OUziwIdQd5qiKP0OnWKgJ3gT2IEN+mcw7rN28sfVBLF3PI0RlGZ/G0mBbscITNBf7/nbev452ot+NYqiKD2Ois3ekgZWYSwUEQapCiBWSwaTcSZVAyQdWtxjOaAVIyTiShMBSmATBzLAln1zWYqiKD2Jis3esg4TvPcwQpLFpi63YqwTNyNNhKcVaMG6z6L+vq1Yd1sCK2Bpf1m9815RFKWfoDGbvUXmfMtghCGFjclIppnEawLOOkEsoQg2KaANU74mgBUWV8Rke0VRlH6Cis3e0IJJdY5jBABsRQCpFgA2oF+YICBjacTVlsGITAQjKmX+sjA2DhTCiFFZka5JURSlCKgbbW/YCDT578Xd1YYRmgB2cGbYfzmDNf+t5d/4XdPvyLZkjYiEsUkBaWyyQADrnpNMN00SUBSln6Fi80HJAm9hrZYExpIRayWHTQqQDLOU2e/V9Kv8V/K/uLj9YloCLbZcDRiRkaQAsMkGHtb6kXWKoij9BHWjfVB2YoL1YMQhRL77zC22CdYqScHtqdsBuDhyMZWhSlvaphUztkYEpxzrRkujjwaKovRbVGw+KFuwyQBgXV6S0rwLmrwm7s7dDcAX+ILZL4aN3chgziBGcCLY0jZi0cRQFEXpV6jYfBDSmHlqpAJAE0Yg3OKbkj0mBM22d3t300orM4MzOTR6qNmmDZuN5iYAZDAp0WLVSPq0JgcoitLPULH5IDRiXF5ixcg4GEl/FgvHdXv5CQQLvYUAzA/MN8IhVQVcqyWIccfFsGnO4oaTWT0VRVH6ESo2e4qHKboJRhSimEGdZVhXWFcE4GXvZf6W/Rs11HBm9kxjwUgBTklvBpNKLVMNSCUCP97DENSNNkDxPK/j1ZsEAoGOl6J0FxWbPSWJqVEGdtxMHBtXybJLF9qi4CIA5gXmEQ/FbdWBDFZ0pDRNCCMuUaxV0wIcXKwLU/o6LS0trFy5knXr1vWq4AwbNozp06czbNiwXmuD0v9QsdlTmjBBfZkKoAwjAu9h3FsyvbNbJcCDZCbJPZF7IACfznzautmkFloCI1ohjACVkj+2JuWvH170K1T6KA0NDTzwwAMsWbKEXG5Xs/EVnyOPPJKhQ4eq2Ch7hIrNniAuNA8bsJeMMQnod1VGJgCP8AgNgQamelOZlp1mt5VxOSI4UqZGYjXSp+wAZu/i+EqP43ke2WyWdDrd626rSCRCOBwmnU6zffv2Xrdsxo4dSzKZ7LXzK/0TFZs9IYWZEkBK0kh5Galh1oAN+gt+AsBd4bsAuNi7OL9CdBabhSYWjEwRLVZPEzAIqC3q1SkOnuexatUqXnjhBVpaWnqtHfF4nBkzZjB9+vRea4Oi9AQqNntCPcbF5cZqWjGiEcDEV3Zi4y8AWXgv8B6PRR4j6AU5P3O+dbV15UKTUjUBbFp0EjgO41pT9gm5XI5XXnmF22+/nS1bem9eh+rqakKhEFOnTu21NihKT6BisyfIVAJS0VliN5KOHMLc0SbsGBlgcXgxmUCGUzKnMCI5wgqTjNMRd1zcP64kBjRjth2NmRJa2Wd4nkcymaSpqYnGxsZea0cwGCSRSPS6K09R9hYtgNJdEpjOX7LE2jCCEMdOghb2P5djRKjN/L0ndA8AF2YvtOnRSWzdM3f2Tqkc0OJvNxyYgHGjKYqi9FNUbLrLTuzAzRzGpRVxPrf7f7MY0fErCmxo3cAfQn8g7sU5LX2aOZZkq6WxbjmxlMQqKgdG+H8nkp/dpiiK0s9QN1p3qceWi5Fgfgs2W6wMO1VAEmPpxOC3ud8CcGriVCp2VtipBmQ8XJL8wZ1lQLX/eZD/WTNMFUXp56jYdAdxm4lFIkH7GLbCs8RoUpj4jV+k87eZ34IH50bPNaP/ZW4aSXkW27IMm9lW5qwfiZanURSl36Ni0x2asVWdWzB3LYQRlyb/vcxXAx2Tp70TeoeX0i9RSimfiH3CiJMM1szSYf10VB6QApsSCyoBxrDrEjiKoij9BBWb7tCIsUBaMIIg49masHPYSB0zGXuTgfvb7gfg1MCplEZKjWjIRGhgrKIw1kICqMBsF/PfVxXvshRFUfYVKjbvRxojMjLiP4exdGQsjEx2lqRDZEiYZb8L/Q4ycHbkbGv1RP2XKzwydbRYO0F/2XC06KaiKPsFKjbvRzsmRhPCDOCU4D+YTLFWbAmZdoxQlMK7yXd5MfMiMWJ8PP5xc6dzGPECKyo5jBCV+e89bBr1kCJfm6Ioyj5Cxeb9aMQKjYz6j/nLJdW5GSs4CSADD2UfAmB2dDbl0XI7z43MvJnCuMmk0nPG/yxiUw5UFvviFEVR9g0qNrsjh3GhyZQBpZj6Z0nsqH9JWW7HClEGluxYAsDpnG4z1yTbzMOITcI/Zgm2MoFUg65Bvx1FUfYbtDvbHUk6LBVKMAkBMrCzFJuFFnXep6El0MLT6acJEODUylOtuEhatAz6FIER60bG34SBofvqIhVFUYqPis3uaMVYNTK6X1xfrdhxNVIsM0JH4P/JlidJkeIjkY8wLDzM7B/Hut1kKmj8Y5Zjx+bIQM7yfXKFiqIo+wQVm92xE2NptGHuVAm2HI2skzEwUjQzBI8mHwXg1NiptnqzpDbL7JzuIM527MDNICZWo/PWKIqyH6FisyvSGBGQeItMI9CIdYMlMG4wqfqcgFwqx2PJxwD4ZOyTtrxNKdaaEcFJ+/tKMU/8bQYX99IURVH2NSo2u0IqAnjY7DMZVyNTAIQxVo+IRgmsZCVbclsYHRzNlNAUKyztGFGRuIz8lZpqEgcqwbjqFEVR9iNUbHZFK9YqkakFRCRyGAGRqQVS/vYheLz1cQA+Uf4JAoMCduyMVBcIYcvSJPz9apx15dhxPIqiKPsJKjZd4WEEBowgiAXSjBEFmV2zMIMsBU82PwnAKcFT7NTOku4sc+E0Y6wcER3P3y6IqfisKIqyn6Hz2XSFpCnLOBgwrjIRiiAma8xNX45Bc1kzL2ZeJEiQWSWzjNXSiHGhZcgvbxMnvyZaBDutgKIoyn6GWjZdIbNoBjECIVaMPyFah0UjY2bazW7Lk8vJkGFGfAZV5VVmoaQ7i5hIiRqZibMS60KL+y9FUZT9DBWbrpBxNJLiLBaIX/eMVmwmGhiByMDTO54G4KTYSWZ/sRtlwKdYSmFMbEb2l3E3g+j30wm0tLSwYcMGmpqaerspnQiHw4waNYrhw4cTDKpRryj7EhWbQjyMmMhATin3L4M3cxghSWOLcPoxmWWJZQCcEDvBCo2IRylWsMqwc+OUYeM1VUW9sn3Chg0b+PnPf87KlSt7uymdqKio4Pzzz+f0008nFtNy2oqyL1GxKSSNLVMTxcZqUtiqzlFnXQLwYCtb+Xv675QESji6/Ghr2cTIzy6TuE8ZxoUmtdBK2C9caE1NTaxcuZJly5b1dlM6UVNTw0c/+lFyudz7b6woSo+ivoRCRFgk1TmHrfxc7f/N+NtG6Cg182zbswB8NPZRYl7MZqG1YWqqySDOEDY+E8GIlcRqVPoVRdlPUbEpROI1MpATjBUiUwSUY+6aX3STrFn+XOY5AD5W8TE7OZpYQSFs1egK/2+Tv6zMP181/T5eoyiKsiv0WboQmSjNnVkzjBGeNFZgJKMsaLZ/rtmIzXGR46zIuOKR9Y8dxxbm9BMLiGNTrBVFUfZDimrZnHLKKQQCAa6//vq85Q0NDVx66aUMGTKEsrIyTjzxRFatWlXMpnSPDNaNBkYEJFaTw1g9YISkFDPyvwzqc/WsSq8iFohxZPRIs12Lv68kFEgKdAZbhLMFm52m8WpFUfZjiiY29957L6+88kqn5Z7nMWfOHJYuXcqPf/xjHnjgAdLpNMcffzwbN24sVnO6hyQHgE1HbsKOsRmEFQ3ZJgYvBl8E4Kj4UcTDcTuWppmOMjaUYlxlEYwIZbGTpsWxadCKoij7IUURm4aGBq6++mr+67/+q9O6JUuW8MILL/CrX/2K888/n1NOOYUlS5aQy+W4+eabi9Gc7iNiU4YRiST5RTEj/ueAv84vXfNimxGbj5R/xIpSJaZ6cym2eoDgViYIYFKeNV6jKMp+TFHE5qtf/SqTJ0/m/PPP77RuyZIljBo1iuOPP75jWWVlJXPmzOGhhx4qRnO6j8RgJN1ZCm2GsYMypfRMBmO5NMIfm/4IwIzwDLPcc44pWW2N2MyzCuf4YvUoiqLsx/S42PzhD3/grrvu4vbbb+9y/erVq5k8eXKn5bW1taxfv56WlpaeblL38LCTpLVjrBMpuimFN1v97aIY66cKMhUZXkq9BMCMwAxTcaDR3zaFTXeu8P/KmJsUtnyNxmsURdnP6dFstFQqxWWXXcY111zDpEmTutymvr6e8ePHd1peU1MDGBdceXnnOZEXLFjAggULANi+fXvPNVrIYoRB6pSFMK6yJEYgKjGCk8RWDQjAmuwa2rw2JkQnMGzwMBvTcSdNk3hMGiNGVRiByfrH1QT0PkcgEKCsrIyRI0cSCPSej7O6upqKiopebYOi9AQ9KjY333wz7e3tXHfddT15WADmz5/P/PnzAairq+vx45PFuNHiWHdZ2F8uBTndwpv+tAAr2lcAcFTJUR3TQneISxbjaivBCopUH5DjlqPxmj5IMBjkiCOO4Mtf/jJtbW291o5YLMbUqVMJh3WUgtK/6bH/4PXr13PjjTfy85//nGQySTKZ7FiXTCZpbGykoqKC6upqGhoaOu1fX18PmCe5XqEdG19J+MtkTEwbNsNMqgf4tdH+0vAXAOoiddYqwt9WqqI0YzLRyrFZatXYgZ5KnyMQCDBp0iQ+9KEP9XZTCAaDatko/Z4eE5u3336bRCLBvHnzOq279dZbufXWW/nb3/5GbW0tTz75ZKdt1qxZw7hx47p0oe0T2jAWRxNGANqwVQM8oAHjPgtha5mVwIptxrKpi9TZAp4x7JQCImCSVIC/LIxNe1b6HIFAgEAg0KeqQ8diMcaNG8eHP/xhPM97/x2KxMSJEykt1ackZc/oMbGZNm0ay5cv77T8+OOPZ968eXz2s59l4sSJzJ07lzvvvJNnn32WmTNnAqZ448MPP8wFF1zQU83ZMzxMLMbDWhtpTKBfZuGsxlZ9jpjd0l6aV5OvAjC9ZroREYnXQL5LDYyQDcNWKKhEx9co3aampoZzzz2XY489tlfFpqamhgMOOKDXzq/0T3pMbKqqqvjYxz7W5boDDjigY93cuXOZMWMG8+bN45ZbbqG6upqbbroJz/P4yle+0lPN2TNy2HEzUhxTqghI+X8wGWWSNAD8M/NPUl6Kg6IHMSjkT7EpAiPxmqh/TJlsLYcRsAjWTaco3aC0tJSpU6cyderU3m6KuvWUPWafRx2DwSCPPPII11xzDVdccQWJRIIZM2awfPlyxo4du6+bY8hiBESsDAnqR/z3YCtAS/pyGl7ZaSokTI1ONeLU1e9Pqg+I16EZGO6fs5c8hkr/RTt5pb9SdLHpytyvqalh0aJFLFq0qNin7x4ypUASIwJyVyQ2U49xq8ly//f+StaIzYejH7ZWkVgyUu4G/7hB53hB/zwar1EUZYCgThwwbjPJOothBmwmMVZIG8YqkTpmYfuSeM3UiqlmmyBGuPwJ1QCbZCDWkpTCkQKciqIoAwDt7sBOHRDFJgnIWBqxPsLYeI4fd1mTXANAbbzWbOPGa5qwlk4cIzJps19HCRy9+4qiDBC0u/OwVZhLgR3Ykf3tGIHws8863GNZaE40syG9gWggyoTABLOdi1QZkBToANaiCWFL1SiKogwAVGxkoGYQO5+NCEEppqqA1ERzqjf/o/0fAEyKTiIcCFvLx81ewz9em7+uFGs5laCVAxRFGTDos3UOY5V4GEumCjvZWYL8igEhOtKYX8u+BsCh8UPN8oy/fzt2vhuJ17T7+5X7x4yixTcVRRlQqGUjUwJIqRkp+1+PFYUYxhJJ0OEuezPxJgAHxw7OzzzLYIpthrFTP1f4+yWwIiPVnxVFUQYAKjYyxiaKcXe1YQQjjrVQwLrVPCANb6aM2EwMTcyP1wT8fQP+PlFsXbU0xroJYuNAiqIoAwAVG6lZVoHJIGvHWDFRbCUBqY8m7rUcvJV6C4CDyg6y0zpLHTT32C1Y6yjqLytBy9QoijKgULGRGEortg6ajJGRGTqbMdaIBP8DjmUTnGirRIvrzBUSSakuxc7UqZloiqIMMFRskpjOfyd2oGUTdpbOMDAYWxMtC800U5+tJx6IMzw23FozMr5GUptjGLdZBiM0EexMn4qiKAOIgf187WFjNmFnWRrjPotiXWNxzFTRJbAhswGAsZGxBDIBOyg0V7CPxGtCGHdaKVqmRlGUAcnAtmxkKoAMZoR/PUYMpLqzWCMSs/ErB2zwfLGJjTX7yUyegYJjS7wmjBkkmsSKkKIoygBiYIuNBP2DWIsmirVkghi3mBTSxKzb0GLEZlxwnI31SGmakN0ODyNYw7Dxn8FocoCiKAOOgS027kRn7Rjro8X/nMJOOxDDpjeHYJO3CYDRsdE2DiPjaGQKgjAmXhPyjy1jdTIM9LuuKMoAZGB3e64bTSo6RzH10cTdJa4xEZQ0bE1uBWB4YHj+GBuJ1XjY0jUBbMabpEfvx5GyvjzfSl9um6Ls7wxssRE3Whhj5aQx1kwJHbNxdiDiE4WtAV9syoebmI0M4HSFSebGiWC2CWHEza02sB9SU1PDzJkzGTJkSG83pRPl5eVMmjSJUEj9mIqyrxnYYiPTQZdi3GY7/PcyAVobdhpnSYXOwLbENgCGZ4bbTDYpc4O/vUzGJtM/p7BCsx/3dWPGjOEzn/kMbW1tvd2UToRCIaqrqwmHB/a/vaL0BgP7VyfFNSV247rNZIBnE7aKgG/ZbMsasRkaHWoLdoobTuqrhYFqjEhJ7Ee22Y+Jx+OMGTOmt5vRp8nlcmSzWXK53Ptv3AuEQiFCoZC6HZUeZT/v+t4HGfPSgLE4KjAJAlmMgAT8ZWATBtLQkG0AoIYaG/cJYMfaSCUBqTrQBIz012lNtAFPY2MjL774Im+++WZvN6UT4XCYadOmUVdXRzyuA8KUnmNgi40IRRY79sXDTuHsxlb8igBezmNnbicAVWVV1iUmyQHicmvGuOQCmCy3FNbqUQY0O3bs4IEHHuDRRx/F87z332EfUlJSwuc+9zkmT56sYqP0KAO765NAfgUmPiPusmr/swT4ZUBnDhKZBCkvRTQQJR6I2+QAV5jC/nGbgKEYK6cFM1dODyYHeJ5He3s7iUSiz3VaANFolJKSEo2RFJDNZmlubmb79u293ZROlJSU0Nra2if/n5T+zcDuBbL+qxxTG00y0cAKUDM2tgPszPpWTbDKFuAEO52AWDcxjMi4Y3U8ejQ5IJlM8vzzz/P888+TTBamz/U+hx12GB//+McZMWJEbzdFUZReZmCLTQ7T+bdhZ+GU7DOZKE3Gy6TMLq3ZVgDKgmU26C9TS0s9tQqMCw3/uM3AGEy1gR6846lUipdeeomf/exntLS0vP8O+5hPfvKTHHXUUSo2iqIMcLFJYyyZrdiU50aMNVJYndmfTC3hmzMlwRLrQpMpA8RqkTE24vIuwwiam+3WU5eQTpNIJEgkEu+/8T4mlUr12YwrRVH2Lfvx8MJuEMBaN/jvnYKbnbYNQyJoOvVYKGbERCZak2oB4kJLY5MESjBiU1isU1EUZYAwcC0bGc3fhnF77cS4ztxYi1Rp9jAusiwkWo3YxL24cYtJHCaMrRAts3G6A0NLULFRFGXAMnDFRpCKzVLjTGy9KNY6ydAhKKmgCd5Eg1E7q2cWKzwy74240FKYQpxV2ArRA5hsNsu7777Lli1byGazvdaOeDzO6NGjGTx4sA5eVJR9wMAVG9eF1oKxPFIYgQlgLBIPM0ZGaqhl6BibE/ACdlvJNpM06XZszEcqD0jl5wFOIpHgqaee4v7776e9vb3X2jFy5EguueQSZs2apWKjKPsAFZs4JimgHCMWO7Di48xhI6Vq3KkGGETXlopMK9AODMe60wb3/GX0N7LZLG+//TbPPvtsr2bQHXjggXz84x/vtfMrykBj4IqNh42vSMqzzEdT4b8PYwVHxuQknc8t2JI0MnWAlK0RS6cdK2qZIl+ToihKH2Vgi00IIyqVwHsYN5q4uiKYGEs71l0GHW40L+BZ60hSnaWY5yDs4NA0xqoZ5R9PURRlADJwxQbyKzwXVueQzzJw049lRz0z+CaVS3UsMyuw2Whi/UjVAEl9jnZxHkVRlAHAwBUbEZg4poaZjJdpxbrLZC4aIQclvsnSTrsZQ+MW4HRJYARmmH+MVlRsFEUZsAzcQZ0iNlI0U6aElkw0N17j7FMaMnVo2nJtxm2Wxk6sJkIitdTKMaIj00L7xTwVRVEGGgPXsoH8AZhpbKZZDTZWI260hNm2JO1bNtl2W9bGPVYYIzJlzrJmYDQ2WUBRFGWAMXAtGzBusgQmoJ/FxlWCGBdZ3F/WQEc1gfJIOQDNuWabfQY2NhPDCIxUDshhhKcVI1yakaYoygBkYFs2blqzDM7M+suTGCEqwQiPn/pclakiQICduZ1kyRKKhcx+ErsRMkA9xkoqxYhNCSo2iqIMSAa2ZSMj/2W8TCXGEmnCCE0EO37GTxYIlYeoClXh4dEQbrAFON3Av+e/yjDi0o4dENp7FVoURVF6jYEtNlIXLYN1iUWcda6AyHiaVqgJ1gCwo2mHEaoWTFxmJ3YStjJsMc4mrGhl0Iw0RVEGHANbbMIYa6MUKyYpjIUjAf4kRkia/Pc5GBIZAsB7gfds9QCw2W1gEwwyWAtHstcURVEGGCo2kkEWw1glYWedO3lakI65bkaFRgGwKbHJxntKsSIV95c1YURHpheQKgOakaYoygBjYCcIyDw0OYwQlGMsmwg2QSCCLWHjx2LGloyFZtgQ2mDqqEmdNTdBQErXxDGWUQwjSAnyJ2xTFEUZAKjYBDFCk8JYJVFsnbTSgu39WmjjwuMAWN+83rrbRHAk9hPDiFfAP1YCI0ziWougKIoyYCiKG+2xxx7juOOOo7y8nEGDBlFXV8eyZcs61jc0NHDppZcyZMgQysrKOPHEE1m1alUxmrJ7JN1ZrBv8vzHsQE9JVU5j0pdbYGxgLAAbshuMaISdY0jRzhxmrI18LsdYOGGM+CiKogwgelxsfvazn3HaaadxxBFH8Pvf/57Fixdzzjnn0NbWBoDnecyZM4elS5fy4x//mAceeIB0Os3xxx/Pxo0be7o5u0emB5AqAlLPLIqxWMoxYtSIieekgAAcGDsQgDeTb9rKAzJ4swpjEUl5mgazT4cYSTUCRVGUAUSPutHWrVvHl770JW655Ra+9KUvdSw/+eSTO94vWbKEF154gWXLlnH88ccDMGPGDCZMmMDNN9/Mbbfd1pNN2j3i7mrECEULxqUmiQEyQ2cZRpj82M6k4CQAXk+9TrY0SygU6izbfjIBg/z3OzHilUHFRlGUAUePWjaLFi0iGAxy+eWX73KbJUuWMGrUqA6hAaisrGTOnDk89NBDPdmc90csDjDWSRRjlcj00C0Yyybi/I1DRVkFYyJjSHpJ1jWvM+6xRv/V7O/XZrcnghGxNOaOS5KAoijKAKFHxeYPf/gDhxxyCL/5zW846KCDCIfDTJw4kdtvv71jm9WrVzN58uRO+9bW1rJ+/fp9P1VwBFtORlKY4xhLRIL+QhYjFE1wSPQQAF5LvGaOIfPZZDHWSwgjWq3+PiI67VjhURRFGSD0qNhs3ryZN954g2uvvZavfe1rPPnkk5x00klceeWV/OhHPwKgvr6e6urqTvvW1JhR+Q0NDV0ee8GCBdTV1VFXV8f27dt7rtHiMpNxNB5GJKowwpPBCEM7xmrxpyM4LH4YAK8mX7XbZLHjbeL+sbOY8TZg06NTaJKAoigDih6N2eRyOZqbm/nFL37BmWeeCcCsWbNYt24dN910E1ddddUHPvb8+fOZP38+AHV1dT3SXsBYGx4mdiOuM4/8LLMmrAvMj+McET0CgBXtK4yoSCUB1xKSuE0Ndnrooc77ip67DEVRlL5Mj1o2gwcPBuCkk07KWz579my2bt3Ku+++S3V1dZfWS319PUCXVk9RCWHEIoO1ZMTCkfTlICbQ77yOHHokAH9p/4vZrh0jSo0YF1wzxoUWx6ZXi2stgBE1RVGUAUKPWja1tbX86U9/2uX6YDBIbW0tTz75ZKd1a9asYdy4cZSXl/dkk94fCfyLe6sMIzRtGAGB/AGY/oRok3KTqAhWsDG9kS2JLYyIjbATrUkqdBwTrxGBqfLPl3SWuyVxlAFBKBSisrKSYcOG9XZTOlFSUkJ5eTmBQOE854qyd/So2Jxxxhn87//+L0888QRnn312x/KlS5cyZswYRowYwdy5c7nzzjt59tlnmTlzJgBNTU08/PDDXHDBBT3ZnO4hlZ7LgG0YgZDqzK3Oexkn024+B4NB6krqWN66nD8l/8TpsdNt0L8EO8U02GmjExgxkknZkqjYDECGDBnCWWedxbRp03q7KZ0Ih8NMnTqVeDze201R9jN6VGw+8YlPcPzxx3PZZZfx3nvvceCBB7J48WKefPJJ7rzzTgDmzp3LjBkzmDdvHrfccgvV1dXcdNNNeJ7HV77ylZ5sTvcpxbjAYhhRcJMEpCpAK0YgoEN4jis5juWty1nWtIzTy083x3HjNp7zGuQva8YKTBMatxmAVFVVcdJJJ3HiiSf2dlO6JBgMmrFjitKD9KjYBAIBHnzwQb7+9a/zrW99i4aGBg455BDuvvvuDqslGAzyyCOPcM0113DFFVeQSCSYMWMGy5cvZ+zYsT3ZnO4Tx4hMHGOFNGBrnIWwhTMr/e39+Whm1cziO+99h2Xty8ydTPr7i9jIWBqZlC3on0MqPzf759Xf9YAiEAgQiWhxPGVg0eOFOAcNGsTtt9+eN7amkJqaGhYtWsSiRYt6+vQfDHeKAZkOIOe8WrFxHSEHx5QcQ0mghNWJ1Wxt38rw6HBjtUjlgbB/vBwmISCDyUwTAWvDuNbKin+JiqIovcnAns9GEIsjiLFOSjBurxxGgMTKETJAC0RTUY4tOxaAp9qfMttI8c44pjyNpE8H/OOK5RRxjq8oirKfo2IDtnJADJMAEMSmK0vqshTclHI0fqmbT5R/AoAHGx80QiJTC7jz5EjigBTolBlAM5i4jVSWVhRF2U9RsRHEspGYSgabCl2GDeTLgE/f0jm96nQAHm99nPZIe4fV0/FqwlgvWf+ziFmJf/w2jJtOURRlP0bFRohiM8kqMKLgFstMYas4y/QDZXBAxQEcUXIErblWnqp/ymwbwY7NCWHiNDJVdKt/rCas9fMeHUkHe0ogEOiTYyL6YpsURek9BvZMnS4hjIg0YuuagXWBJcgfEyPp0Qk4o+IM/tr+V+5vvZ85NXOs+0ymhXaz00r886QwghbBuOba6Twz6PsQDoepra3ljDPOIJHoe/MWHHHEEVRWVr7/hoqi7Peo2LiUYwQigbVwUsB2rIBImnIbHRlnn6r+FNdvu54HGh/gf4b+DxWxCiMqUp5GxtpkMWN3JEZThh3o+R4wlvxEhPchHo9zwgknMH36dHK5vjdnQVlZGUOGDOntZiiK0gdQsXGJYwL8GezgS0kekCQBCepn6Zjl80PBD3Fs6bE83/Y8ixOL+UzsM7bUjZDGiFkbVnii2NlCtwPD/fN3k2AwyODBgztq0imKovRVNGbjEsF09jLuRqYWCPkvSSIowcRhpDBnJXxm2GcAWLR9kbGCJG4jd7gK654LYqwaETUpZ7OtyNenKIrSS6jYFFKFSUuWVOiksy7tf45h56YBaIezY2dTHiznhfYXWJNeYwtyBjHuuDDWogErajIINIUZf1NoESmKouwHqButEBEZmda5AiMQKfLrmkFeYc7yWDnzqubx0/qf8sNtP2ThyIXmODINdBY75qbcPxbkZ62lgHeB8ey3jwGBQIDS0lKqq6uJRnuvCmllZWWvnl9RBhoqNoXINNFJjODIwM4gNv05jZ2GQGI3abi66mp+Vv8z7tp5F98b+T1GJEeYY0oFggDG7SZxmaS/rhXjShuCsW6qMG66/ZBoNMq//Mu/UFJSQirVe9OVVlVVUVtbqynairKPULEpJIApnNmKHeUfxghNKXa2TnditIBZfvCggzltx2k8uPNB/mfb//Dvo/7drBOXWglWaDx/X/kspXIAtmAsqv2wVmM0GuXoo4/miCOO6NV2BAIBwmH991eUfYX+2rpCss/cUf5iwYB1h7lTfviWzjVV1/Dgzgf5SeNPuGbENVR5VWZdKR3Za2Sx42pk8Kic08NUGtgMjGOPUqH7A1LxWKseK8rAYj+NDOwlYYx1k8aIQDnWfSZC4cq041L7yKCPcFzZcTRkG7hlyy1GQEqxddVaMWIi00RnMRZN0lkfxAwu7Tx7tqIoSr9ExWZXSGxFXFtVGNHxMAF/ER+phZY06wKZAD8Y+gMAflj/Q95Nv2uESNKhA5gkgzKM2AT9zyUYARJ3WgLYhGanKYqyX6BisyuiGMEJYzp8v8ozYazwuDGcMv9zBRwz/BhOrzyddq+d7239nhGZEHZitXJsLEeSBNIYgQlhRSkFrMeWzFEURemnqNjsiiDGlSYToGX8VxorHuIGK8dYQTKIMwH/Mfg/CBJkQcMCXm171ewXxg7mbMG4ytowoiLTTrdjK0VLIsIm8ouCKoqi9DNUbHZHGXbE/yBsVpkMzJTMXfcuJs3yQ8sP5YrBV5Aly/yN88nGs0acmrEla0TQRKgi2CoDYWx8aAcmQ00FR1GUfoqKze4IYsa+eJiOXqYWkAGYrdiqADlskB8gDTcOvZFRkVH8OfFnfrblZ8ZNJq64LDZ1Gv9zBJvp5tGRUk0EIzZ7MRWBoihKb6Ji836UANVYF5q4wiRmIynNEmORZRUwqGoQPx73YwC+vvXrbPQ2mmO6Y27EemnCiFGr/z6FnXytzd9nK8bKUcFRFKWfoWLzfkgatJSeEatDLBHJJJMBmqXY2E0GzgifwZyKOTTlmvjX9f9KNp21AiVp0G3+MeJYd5rrWpPkgjSwFhUcRVH6HSo23aEC0/mXYIQigxEIQQppuuMUc0ArBCIBFoxcwLDQMJa3LecHzT+wAzdz2OyzuHMsMN9M1j+XxGoC/rbvYqYkUMFRFKWfoGLTHYLAMKwbTSwdSRhox1o8MsmaM3XAiPgIfnnQLwG4YdMN/LH+j3ZMTRbjlpNU6HZ/WRNGkFzrR6pCt2FiONvQpAFFUfoFKjbdpQwTuxFRiWJEZxB2+ucgdtxNyFlfCqdUn8K/Dfk3smQ5d/O5bE1vNWJUjh3IuRMjJCH/mFIyJ+q/xL2W88+xAZMWLTN/Koqi9FFUbLpLEFOJuQybMSbLwSYGlGKsFKkI4Mx58x9D/oMZpTPYkN7AGe+cQaIsYda1YJIDIL8Ap9RjkxhRBuOuy2AFrQkjOu68O4qiKH0MFZs9IY4RHJmGIOW/slhRkcGfIWe/tNkuGojy+9G/Z2xkLH9s/yPz356P1+wHXiTF2Z1iRQRmJzYrTV5SR60ZqMdUGmjt4etVFEXpIVRs9pQa7BTRFRgLRiwdmckzhxWdFEYoMNsOrxnOkkOWUBos5Vf1v+I/6v/DrJPK0AFszCaJzXqTSgYR5+VaUc3AO5ixOBrHURSlj6Fis6eEgeHYDLQYNjYjAz6lCoCkL5dj6qlFgQBMi0/j7lF3EyDA9duu5yf1PzHbgBGYJmw8x3XFSTxIxK0NOxZHRO5d/6X11BRF6UOo2HwQyjHZaTKpGpg7KdMGlGIER4L5bkq0XzX69EGn89MRPwXgC+9+gbveu8tkmknRT6kKLfuIuDVjXWhp//iSQr0TKzjrMCKk6dGKovQBVGw+CAFMZppUEZBSNRK4F0sk67/cu5ygQ1Dmj57PLeNuAeDTb3+aB3Y8YEXLjd1IBYEkNlMthi19A1bogv66FGYCti1otpqiKL2Ois0HRdxpGWyWWggbuxFxcOM5Kf/vIDqyzq4ZdQ3fHPFNcuQ4d9O5/Hrnr+24mxzGTdaOTYEWIXNrqkm5myZMskCr/zeJEZv12JptiqIovYBOC703lAFDMW6rHMbSkUy0HMYikVH/QWzgviDj7DuV3yGXznHjjhu5aNNFNEWauGLoFdZVNgj7WCDVojMYKymJTbOOYSdnCzjvJaZT4bc31sP3QVEU5X1Qy2ZvqcZUhgYbQ5GJ1mQWTncGzlDB/q0Q8AL8+7h/5+axNwPwhXVf4KZ3bsLLerZemiDjbFqxQibTIEgmm8Rpmsm3sHZiMtYa0Yw1RVH2KSo2e0sQGIzJSBNhSWDnvQk428pnca0lMMLgl7+5dvS1/HTCTwkQ4BvbvsHlWy8nHUvbY6QxbjURMfn2gs7x2zGiImNwZLCnJAs0Y2I5a7H12RRFUYqMik1PEAFGYDruSox7rQRzdyVO40+q1pE5JlWe3awz4LKay7hvxH3EA3EWNC7glNdPoSHTYKyZRmxV6UJEXKR+m2vxSOVo/HOmMMLzDmbagkThwRRFUXoWFZueogQYgy3GGceOv5G/8irFCEGafLdaDmiCcwafw7OHPcvwyHCWNS3jmL8fw+s7Xrc12IQM5hts8d9L7bRCa0ometuKESRJJJA06bXARqylpSiK0sOo2PQkZRgLJ46d+tlNhS4UAVkn1aMTdFQmOKriKF6a/BIfLv0wrydep+6dOhanFucfQ6wlmaYgh035kArS4lILYNOmy7DFREWckpistfdQS0dRlB5HxaYnCWAsl+EY0ZDstHTBX7egpiQViLXjWC7jYuP4w8Q/cE7ZOTTnmvnUW5/iqnVXkcqljJCksNWmwRbnzGAsmBR2zE4YWy064GzTjhGYRv/9ekxhzy2opaMoSo+hYtPTBDDjbioxnbsM/qzAVhWI+e9LsWNuRAxct1oKKtoruG/Sfdw2/jYigQg/3vJjjl19LG81vmX2FUtHRCGNEZHCWI1sk8BOZdDsL5P6bnH/vSQirMdM0taOio6iKHuFik0xCGDcaYP8zymMdVGKFRqZn8atNuC+T/mfyyEQDfDFEV/k+cOeZ1x0HC+1vsTUDVNZ8N4CPM9XAakSkKDrTLUMdoCoVBkAI0biypP6as3+tinMfDkbMDGdVjR7TVGUD4SKTbEIYOqnDcN0/tKRJ8mP1eD/FZdaGvOtyKRqzrDboyuO5m8T/8anBn2K1lwrl629jDn/nMOW5Bbroos6x5aBnQlsBQEZYCrb5PxztmKsmBZ/u3ZsUdEERng2YKsRaKFPRVH2ABWbYhLCuNSGYERA5sIBG7uRmE0QY/lUYNOhs+QX40xDTaSG+ybdxz0T76EqVMWjjY8y+dXJ3LXjLryolz+vTgwjGmLtiBUjyPTVLf5yGb8jgiTWkp8lB9iBoesx01KLiCqKouwGFZtiE8JYN9WYzj2GEZPBmGkHqrDp0NLJg61EIJlqElMJmdf5Q87n71P/zuxBs9mR3cHFmy7mpH+exBvtb9hzi2tMyuO4YpPAiIxkpcmMoO5rO0ZckpgYj0ypIAVGmzDVpbdi068VRVG6oEfF5oUXXmD27NkMGzaMiooKpk+fzqJFi/K2SSQSXHvttYwcOZKSkhJmzJjBc88915PN6HuIS20IplNvxXTWYK2CQreaVBkQC6WC/DRqYHRoNEsPWsovxv2CweHBPN30NFNencK/r/93koGkEZTCKabBWjtu1WhBkgPanH0iGKFLYq0fEZcMttinDBJtd65PURSFHhSbV199lRNPPJF0Os3ChQv53e9+x5FHHslnP/tZ7rjjjo7tPvvZz7Jw4UK++93v8sgjjzBy5EhOPvlkVq5c2VNN6ZsEMNbMKIxwSJC+HWu5ZMgvcyPZanFsmRv5xvyYSSAe4OKhF/OPqf/g4iEXk/SSfHPzN6ldVcuDTQ/iiYJ5GNGQ4p1u7EZIYufEkUy2bMH6en+bBNDgH0Oy2YIYt9wGjOg0YmNUiqIMaAJeRzrT3vGNb3yDW2+9lfr6esrLyzuWz5gxA4A//vGPvPLKK0ybNo1Fixbx6U9/GoBMJkNtbS2TJk1iyZIl3TpXXV0dK1as6Ilm73s8jGWzCdOht/h/xS0lgyzFwnArRDdhpx6QFOpm8jLKltUv48qNV/Ja+2sAzBo0i/8e999MKZtitpfzSfXoUv/YCf/4NVhrJ4MRujDG0klixw/ht7HMb2MKW4FaBLMUawlVY4uKqvNWUfZLdtc399jPPpVKEYlEKCkpyVteWVlJLmd8RUuWLCESiXDuued2rA+Hw5x33nk88cQTJJNJ9nv8dGbG+Z+lGnQEKwKynTuGRuqrgeng49hsMie2M2vYLF457BVuG3cb1aFqljUtY9rfpzH/nfls3LnRCpPrVpMJ3WLk/0cEsHPl5JxzCiF/3U6MiCUwolSCEZo0Vjy3+C+xeFKoxaMoA4geE5tLLrkEgKuuuorNmzfT2NjIwoULefrpp7n66qsBWL16NRMmTKC0tDRv39raWlKpFG+++WZPNafvUwKMxcRxZNK1ENatlsMW8cxirIMK7ABQ6JxE4M9rE/EifHHUF3nz8Df54tAvEiDAwi0LmfjqRP5t47/xXvo9s38EOy+OWFCFbrU2f7sw+VMYZDEWmghR1D+/xHGkXe9i59N5DyNM2zH12DZjhCeBZrQpyn5Oj4nN5MmTeeaZZ3jooYcYPXo01dXVfOELX+CnP/0p5513HgD19fVUV1d32rempqZj/a5YsGABdXV11NXVsX379p5qdu8SwUxmNhLTmQ/Gpj5XYKoQyF9xSblIEkEWYy3FyOu0a4I13HbAbaw+ejWfqv4USS/Jf737X0z42wS+vfXbNKYb7XgasIICVmjc2UGFFPki4xLAuPakSkEO644rx4pqHCNWWzCC9A4mlbodO722oij7DT0mNm+88QZnnXUWtbW1PPzwwzz11FNcfvnlXH755dx99917ffz58+ezYsUKVqxYwdChQ3ugxX2EEEZkRmA6eEktjmBEx33id+ubFWaquXEWmRXUF6FJsUncN+E+Xp7yMh+v/DgtuRa+s/E7HPDHA/jG+m+wPbfdVo0GOy9OV9lqKWzcRyaFSxfs14iN1ciUBmIRSaXpRmzxURnn04RJLtiGsYKkvpsKj6L0e3pMbL7xjW8QiUR45JFHOPXUUznhhBO47bbb+NSnPsX/+3//j1wuR3V1NQ0NDZ32FYtGLJwBRwAz3mYcJvsshLEKwLrS0thxM2AsnUpsppogWW05bNabn912eNnhPHbQYzw35TlOqD6BpmwTN229iQP+dgBXb7iaTblN5hht2NiO+x+SwYiJW2ZHjp/GTtDmxp6EndgsNnHfhbEWW6tzjncxrrYtwNsYq2cHdppsFR9F6Xf0mNisWrWKqVOnEonkz+x11FFHsWPHDrZt20ZtbS1r166lra0tb5s1a9YQjUaZOHFiTzWnfxLHVIweia0mMBhrvVT7f8ux9c/cjldKz8j2bl00sUAicOzQY3lqylP8cdIfObXqVNpz7fz3tv9mwh8ncNHfL+Ll5pc711bLYUWo8L9GMudcS0gssqy/307sVAhh8isotGNTqiWBQoqSDvKPsd1/bcJOheDGtxRF6dP0mNiMGDGClStXkkql8pb/+c9/Jh6PU1NTw5w5c0in0yxevLhjfSaT4b777mP27NnEYrHCww48wpj041Hku7aC2AoCnrNM6qpJ4U6ZJbTQ2pHss1K77JjyY3h40sP87dC/cc7Qc8h6WX697dcc8Y8jOH7N8SxpXUJOenIpSxPu4titWJeatEvcfG5NNlcYgxiBacZOsSDuuIC/fT3GpSbVC+qdbRoxCQbb/W3q/e3EqlMUpU9R6JH/wFx55ZWcc845zJkzhyuuuIKSkhKWLFnCvffey9VXX000GuXwww/n3HPP5Utf+hLpdJoJEyZwxx13sHbt2h6J6+w3yNP9eOyMmpIVFsS6smTbKLb2mVudAKzrrVCEHGtn2pBp/Hbkb1nbspYfr/sxP9/xc55pfoZn/vEMB647kMtGXsanyz/N0PjQzlNSS2ynMGVaBDCIzbYTayWLsYSSmGw8V6Ta/WuRCgZpjEUnwppw3svkcG4tubB/72Ra7BidBVJRlH1Ojw3qBHj88cf5wQ9+wOrVq0kkEhx00EHMnz+fyy67jFDIpDy1t7dz3XXXcc8999DY2MjUqVP5wQ9+wMc+9rFun6dfD+rcUzxMx7sdO6iyEeuyaseO08F/LwIgtcoyGKFxccfOyIRtfvXnplwT/9vwv9y29TbWJdYBEA1EOaf6HC4fezkfrfkogUDAZqWVkz9dtbjOSrGZbpL0IKVu5NrKnLZLwU8ZsCrFQEVAMqZ9JDDxKjGEU1jXokwq59eQ6yhmWoatPycvRVF6lN31zT0qNvuKASU2QgYTJG/0P7diOk/poMVNlcRWHpB5c5rIL8LpYWIeMqGbIB01wCDIkmXpjqXc8c4dPLbzsY7SN4eVHcYlIy7hooqLGBEYYS0JQdxZg5xlMiZIrC4RQxmfI/PopDBC4qZUSwFQqc2Gfz0V/nupXi0iIpaVCEzW39cd0Brwz1uCtX66ikcpitJtVGz2J9owgiNuKKlHJlZKyF/nVgNoxVoIMoYljY3fCE3+8kHkp0E3w7rUOhY0LuB/t/4v29LbAAgR4uOVH+eSMZcwZ+gcosGo2b7BP4YrGDKXT9g5tvznlWFnDQ1gLRHZphFr3Yhgpp1tZDxPACNUct0JrMDIINkwJvNPBEmqabvjgWRGVXFbFk7NoChKl6jY7G9IzGMHdtqCndgBmFLHTDp1GcsirrdS8muqgenUG/x1rrWTwbq2SiHtpXlsx2PcufFOHm14lIzvq6sOV3P2sLO5oPoCjg0eS6gmlD8ltbj3qpxlMu4mjBECsc6yGNHwsNWlg/4y9x5IGrU73sdvZ8eEcElsirhcj0yFLfXcslgrSGJLYiVl/c9iAcn5xE2nKEoHKjb7K2lMAkEjtvONYot6imUhwXo3HVoSCSSukcN2sq4rSYSqpmB5M2xr38bd7Xdz55Y7WdW6qmPVqMgozh1+LuePOJ+6ijoT32nAdNiukImFBflWUBojEBKPijrLpAxOq79+cEG7ZApusWLEbTYIGwNq9Letws7jk8LGmKTGW8Dfz41/SSKGK1rihpN712NpN4rSv1Cx2d+RqQHEDRbHpguLa22nv23I2acVm2ZcinVHubODtvqf3QQDD2NVldnlf2/5O/e+ey/3bLmHdel1HZuOi43jzCFnclb8LD4y+iMEw44ySNq0TIEtiIuvFStCaX87qUAtsSU3wcDDjueReI7sK1afuNbEWnGTI0QQRXQkZVzmEhJLKeqfVwa0es7xJQVdkhzEQhJrSCxJdcsp+yEqNgMBiYm8h+kUY1ihCGE6QQmiS5WBNuyTu3TEEleRGIa8d5/WM5hOvYb8TjMNXqPHn8N/5t7t97J422LeTb3bsXpEdASnDz2d04eczseqP0YsFTOdvCsMYDtsN2DvxmgkAaJw7FAbVkxcl5skH0gsBuz4pAr/fG5KtVRxwL8fknEncbA0Nj09Tf4spoPIjwdFsYNtxRKSqbdFgMQNKJW+1T2n9FNUbAYSEudoxHSgzVgxEUvGrw7d8dnt0Jv9z0FM5y5pzK71kPDfd5VO7QT3c16OPzf9mQc2PMADOx9gXXJdx6ZloTJml8/m1CGn8okRn2BEbIQ9jgwSdcf4SlVrKRwqwpDDdPDu/D+uyw2//a0Yt5mbNSc120JYC0omgSvHxr4CdE5QaPXXV2CnURDXXQwrYFm/3RXONmnyKzNIiZ8SrNUl46cku87NlpNrV+tI6WOo2AxEcpgOsRVjhcQxnVQD+Z2jdNDy9L0Tm3osT+hSeFOKe0qn73bcYj2U0TlmsR28Go+VbSv53fbf8ch7j7CyZWXeJkdWHMnJg0/m5OqTOTpwNJFBkc6uNYmVFMZ3BmGFTiwPcblJooBklZU5+4pgDKHz1ApiZcg1ithF/f1cd5kcU9LQM/49lH1l3E8YO3OpTIAnApZw2lniHE9ER74LqSohk9q5lpFrCWoWndILqNgMZKQS83ZMpyfVCKTDltk/JcYg2VlujTOpWSbWThBjOckxxCXljoERkv7LHXMDbGjewKNbHuXhtod5uuFpkjk7cd6g0CBOqDmB2TWzOan6JA4sOZBAOmA76ALXXUe7XWGQqgJNzrVIlpu0q91/X+5s42ELilY555EkArlGV0gk5tSCTeeWrDiwSQkBbDUEaac71bdU6w5g40SuCA3CVgWX77LQQpKxVdJeiSdJYoNrHYkYBZzPcq046xSlm6jYKLYSQTP5yQOev0w6cUl1lg5L6ptJUFw6n53YOIPEXZLYOI+cU2IVhWXvnKf41mwrzzY8yxP1T/DEe0/wz8Q/8zYdGxvLrEGzmFU1i+OHHs/Y+Fh7fMkSc0vSSIKBFPoMO8sryR8IK+NspH0ya6mM2XFTw+uxCQTufZUBo26HncIWEZXYmYhlKbbcjqSkVxe0X8ZKRf31kqwg025LirY8AMSxlbfFCivFZuNJnEnGHMm04G5KeAabDCJZetImsaBEmILOe5z37v2iYJli8Qpe8h1JmSawySXyANEP7qOKjWKRRIIG7FgbicvEsOIj5WVEkKRmmdCGLYtT7h9HrAUZL5Ohc1YZ2GKZrpsKOjK+3uEdntz5JE/WP8nyxuXsSO/Iu4SDSg7iuKrjOHbQsfxL+b8wMT6RQMz5JUpGXoLOIjQIO0GbJD9IsD+LHa+UId/ikfiNVKJ27+cOrNXhLpfzu1MyiIsvgc2Sc8cHidtSLB4ZpCpWzk7/XCJ4sly+L3fMkZxbZkKV1HZx3UksK4itJiH/C1IaSdynck1B57PnnENcrJJMUoJ1F0rFBmmfa5GJQHvO30LhChS8l3MXVnso7IzfL65VuN4rWOaKMlgRKBQKuR8ZZ1na+SsuarFIxdoXN3Yj5iEhgb3n8rcE8zAxCBiGKdArDxF9EBUbpTPyQ9iJHc8iGVVSlUBcL5JSLB2A/Ggkm8vtSCW4L+ViwnTtcusq7iM/TIlFYJIMVjWuYlnDMpY3L+fZxmdpyjblXcqI6Aj+pfJf+Jeqf2FG5QymxaYRjUbzq2bL8cuda5P2iHtNOnmJ9ZRixUCsv8Lkgxbs2J5y51wZjCVUQ34MS9yakhbttk0EUjpgsTQkWUEGsUo6thuTEtehiFAOc98zmLFIYnFJFmKAfDERN6iInLyXenYi0FKpQpJHmrEJDxLrk1iY1L6LYcd6yf+YWzNPzinLRBhdq0keCsCKr7yCzjY58oVKhE5e8n2LuMk9ke/djY3J52TB9pLNWfh7kHNIWr7nrJPrSvr3S4YrSIaoJJGIhSy/AfkNyv9KCeZ/6kA6Z3H2AVRslN0jM2buxCYDBMjvlCWzTWI70qm4rpQcJvVagubSyRa63KRTluQE2VeeKt0ftrTPn4I642VY2bKS5xuf5/mG5/lD0x/Ynt6edzmxQIzpFdM5puIYjqk6hqMHHc24+DgCmYDpKF0rzU2BdgfCumnVUkpHqleLxZPCZuoVDjptwrq93Kw9uY81XVxjE/kxHbAdlWsFyr2K+ed3rRmJVUmb5ViDsJmKbuq2uEtb/XUyj5J03k1+G6rJj1O5rlURJrGwYgXb4tw/EVG5T+5feWWdZW6HLpmD7nYyLsztxdwpJtw4mCRqiMBKmFBcyFLTT65JHj7E1Sjbu+d3i762O20Ui1NES4YVyHew3fkOwtj5qQLO+6jzuXDQcBRTFX4UfSpVXsVG6R7yA9yJ/eHJU3gM+3Tr/vgktiA//DSdqyp3NQjTzXJzO/x28geWyo9VrAfBf2r0sh6vZ17n+Z3P8+LOF/nTzj/xWttrnS5tSGQIdeV1HDnoSOoq6qirrGNUbJR9+oxhLQe5F0F/uSu6YvFEMB2xWAHiogtiLUWJtUhSgrjp5LgiQtIBpTBJCW7n0Y4RgsHku07ku3DTsSV+JFaCHEe+E/mO3Hteju0kRTRjmO9Yau5JvEmSFiQRwrVcpOqCm2UnGZFyX93704K1hiLY8UwetqK3/H/JuWWZCKnU3xNLSly6YP9/xTKThArIFziw/5vSyYvIVGIfAsQ1KJaJmyko/9+l2NR29/9WYoBS8WMnNrNR/hcKXZJi/QXJFx8RGhGiYcBB9Jkq5io2yp4hLrZ2zA9JpgSQjldcXfLkWzga37UQwD7NV9M5y006uDLsD1fiDdIhVjrbCq7byV2ehcZMIy81vsQf2/7In3b+ib80/6VT3AdgeHQ408qmcXjF4Uwrnca0QdOYWDaRUCCU745xkwxEbIOYTq4wAy7stzXs7CsWj9t5F2bGtWE7FBEhSc4A6zaTeyf33U0s8DCxuDD5cSVJbpBEAkFcaiUF91CewKWWnn9fOywqsaTk/0SuRyzitLMerOhKB+1bqXlZjLK/3Etptyvy0oHLdiK40n65LxKDkpTyndj6eCJqMvA3iR03JgOFRYjEapX/s2bnvrY590uutclvi7jZ5P9DHqxasG5mcZ3JvXVjcFKpXMQF7Pcmrk8ZzxXAWMkH0ycEZ3d9s1ZxUjojT2wSh6jGutii2Ke7cswPRtxrblqwuGo8Z53rHpLPSUzHEHX2lSdNOYfrb3f/SvDbJQtV5VXMDsxm9vDZAHiexzst77CifQUrGlewonUFK5pXsDW1lSdST/BEwxMdu5cGS5lcPpnJJZOZUjmFybHJTBk0heHh4fnnER99IRIYdtdJ3MAdIySWAeTHrlLYTqgdK3hiKeFcc5D8uJSMD3JdkrIcbOaeew0SlHaR77emYHkj1vUG1pXURL7lFcSIm/x/yDKpx1fl7J+is+Um2XgipJ6znVgzEgNyEyMS2IC93It2TOctU4hLpp6HcWVFMf+fOYxQSwKFZFbKd5TAulRzGOF2Eykk2aMem2gRwJZPSmESSeR8knQjmX9t2MB/m398+R+T8VliWcnvQb77RmAjxq3WRxMHQMVGeT/EHRPHdAhSU60d21HJoEqxRiLYH5L8mGQ/6ajkKTVMvhXkPjG7T9xhZx9JtS7MRhKrocCHHQgEGB8fz/ia8ZxdfTZEjACtS6xjZeNKViZXmr+tK1mfXM9LTS/xUtNLsNUeY2hkKIeWHcqh8UM5tOpQDg0fyqEVhzImNMYUGhWSnc/faYyOIE/RrjC4qbAiTmIByD5Sn006VXGRiWhJyrc8qUumoQT4RaSkA5UCrtJ+iTtIMB/n2EnyJ7aT8kDSqYO1CNxt5bgB57hpbAp+O6aDlWXSmYuIiMvPPV8Q+8AhQX25DnG1SQcewAhBFbajdschyblkHJpYzmlMHLIa+3/p3qcY1moUa0TcZOJua8Y+LEjcz/3+pH6hfB9ZZ3nCP3ahFRjA/p/FMVOjV9L5AaEPoWKjdB8RB3EVtGOeBuVJz43vSGchP4goNkgqnUQF+fPYgP0xFbp8xOKRTkD+c91MJcnSKny6k6dfp7MPBAJMiE9gwpAJnFF2RofLoz5dz99b/s6qplWsSq7i701/Z1XrKrant7O9cTvP8RxssccpD5VzcOnBHBw/mIMHHczB4YM5uOJgDi49mMpwpd1Q3E2FJLpYniNfnOTpXmIy7r2Szs/NhnJjXCJ+bqZUHOvOkfsmHZlbmkhESDIPxWKVzlLGD4Wc44q7S6yPdmxhWBEC+b+QNsh1yP+HuOOCWHehiF4EYyHEybewJPMP8lOOZUyTuFtFFEWAJaNOXHtZ/1iSUCH3NUl+/Koe07nLcWW8FNjCt3IPWv1zVJHvlhXBdlPgRYjdZIZ2rNCKxeNaO/LdbSDf8uxjqNgoe464wEQwJL4jAd0ENmNNnhjF7eWRP37F7Yik4xyCdaUJbiZYoQiJ60qeEF3ErVLmfBYydKpIUBOp4biq4ziu4riOMUJe2GNDcgOvtb7Ga82v8VrqNV5reo3X2l/jvfR7vNz8Mi83v2zcMg6DI4M5KH4QB5UdxEGRgzio/CAOjB/IhJIJjAqOIuSF8mMVgohN4XLJfir81cqTsCvAafKtIPceyhO8LJfO3s0Ik3vlWi/4+0rA2z0G2PEjrjUq7XBL54h7STpc2VYsBFdMd5JfYkiuyR3TJO0TwRN3mlhUsp/8j0nMRs4tFg9YkRerXR5uJEYjriwRMEm+kNiaPPiIpSVJM/LAIL8dtyK7fNdh571YhuItSDvr49iHCUlbFwuvCfP76YOo2Ch7hxvfyWF+tJJUIALjZgWJOy1EvgCJGyWO/bGKy8cVDHeAJP7nVuy8MoIblJYCl4XuKrD+ehcZjCqXGAgwLj6OcbFxnFx1sjmebwm9l3qPN9rf4PXm13k98zqvN73O64nXeaPtDXakd7AjvYOXml/qdNvCgTDj4uMYHx3P+NLxjI+PZ2x8LOPC4xibG8tYbyzxSEEwRWIIhZabuNgKlxfGleS+inUpiAhJ8N/dXjpW18oC+x12XBD5RV8FEQd3DJKIyGBnmXSahdclLkVBHmRERCUl2i1ZJB22JAi4aeNiLYkVJBZnyvkrFolrmct6aWcc8z8u8RmxQETQ5H5QcEwROff/W9rhJkNIXEdS8OXa5B7Jg5KIjwj6NjrPPdVHULFReg7Jpopi00YltiPjOCQTR9KeI8BQ7LQI8iMpJT+rSzordzynuJYidB5VLecodLfIE7mMgZEAvIiP5+zvdnLQSYQAhkSHMCQ8hBmDZpj2+0kUnufxbupd3mp+i7dyb/HWzrd4O/U2b7W/xbrEOramtvJ2+9u83f62nWuogKGRoYyNj2V0bDSjw6MZXTqa0aHRjCodxejYaEbGRlLj1ZjxQ10hT9SFFFpNbgaZ2yOIq6swgUA6eNeqEWEqLEsk97qwXXKcsLPMfcoH68YTIZSO3nXtiQgIMphUrlsEK+J8lr+uMLluTvl/SGBLDsn/jWtxiyjIvZNju9UUpP6exBzFnesmjIjYi3WTLlgu1o20Q9oq4iX3UlzbEvvpY6jYKMXBtXgqsU/UkhVUTn7l5Aj5gz/xl8kIelkmP25Jt5UkBBl5754/QL5bRo4psSVXhMSCEkGRAOyuRMh1x0mMSY6FsYZGRUYxavAojo0dayw+JxOtLdXG+sB61jWsY11mHeva17EhuYEN7RtYn1rPpuQmEydKbzcuul0QCUQYER1hXjHzd3h0OMOCwxgWHsaw0mEMiw5jaHQoNeEawrlwZ/eXXEOhMImAlNGZdMFnGb1fOJBCOntXANzvT3og9+nfTZIQi1k6UzmGdLauRRDCZnW57XLFTtyQIhAy7kgGpbr/Q65lJQIk1otYJRIbEktdBqy6yRCuGMp+Ik5R59hiQXrOMUVoce6HGxOT/1G5RhFgFRtlwCLJBWVYf7aMeWjG/OBENCQJoQo74l06FAlMR7FjTySrR/zlsn01+R2atEMGIxaKkDxJy1OwK0JpZx+383DHkhR2tlmMUBZ2wDkojZVySPQQDuGQzqVz4pBty7LV28qGxAY2JTexuX0zm9Kb2JTYxKb0JjYnN7MltYXGTKMRqeQG67bZDdWhaoZEhhiLLDqEweHB1ERqqMnWUF1STU28hppwDVWRKqqCVVSlq6jKVRENOerUlTDlCv7Ke/lO3LR16eDFFSTbyffkOftB5yQGsHEPl67EUb4Tz/nsWhmCDDaVfeVcOfLPKwkPIlYS43ETMCSDUCwhsQwl+UWs9UIRlrI90k75P/Ow4iyC5m7vZi0GML+ZKvocKjbKvkeEJ46twixWj2QwSVxBLBlxu8UwJTpkECT+31JMZlwUO6pdRuzLj1CeqKvI/zFLm2RwXXdFKFewj2uVyTnFz18Yx5AsKQqW+316KBBiVHSUrXIgnaQ7wBRoT7SzNbOVd9PvsiWzhS3JLWxLb2Nb+za2pbexPbudbSnzvj5dT0O2gYZsA28k3mBPKAmWUBmupDJcSQUVDAoNYlBsEIPCg6gIVVBBBeXZcsqbyimPl1MeKqeMMkpTpZQGS837SCmlXinxdJySYAmxXIwAgc4xs0JrRDpUiUtA/vfp7ud24O54I1dw5LNYIUIK6651XWdyXrddbkePc2z5ruS9vz5DhvZAO21eG2200UorrYFWWrOttAZbaaGF5kwzzV4zTdkmmtqaaAw28pPYTyjJlliBpOB80ha5fjcpoo+hYqP0PkGsO0x+0CI+SUzA083QkvEKO7GdPBjhkkGk+NvIQDwZcR3HjjR3S+IEMSJUKAAS+6kiv2OKYeNMrjvO7ZTEEnJH08tTqoibi4z5KLSQZJR8F51ySayE8RGTZNBxH6STc0fgA9lclsbmRt7jPd7z3mN7ejv16XrqM/XUN9dTHzRitCO9g8ZMIzvTO2lMN9KYa6Q91057qp0tKSfvuxuW1O4IECAe9IUnECMWjBEjRixs/kYDUaLBqPkbiBIhQjgYJhKMECZMOBMmFA4RCoUIESLkhQilQoRaQgQCAYJekEA6QJAggUb/yxO3Vha8gIeHZ/56HrlEzrzIkU1myQayZBozZLNZMsEMmVyGdCpNpj1DOpsm7aVJ5VKkvTTJQJJkNknSS5JM+X9DSdpHtpMIJMgECrMfyC88CtZViP17Y/RGSijpbEm6wpkrWF74f9JHULFR+hZuWnU51n0iyQbN2AF9g7AWkHTsbi0ueToVoSl1ziEpsmATDGQAnht0BWsJFWZwZTCuOpeofwwpK4LTBulMyp1jSCcilsuuiiq6cQVBBE2C5UFnuWT+5TU5xODSwQz2BjMpOsmuyGEEtbzgGv1R+16VR1uujcZMI82ZZpoam2gKNtEUamJnZict2RZaki20JFpoCbWYp/RsM22ZNlpTrbTl/Cf5XCvt2Xbas+0kvAQpL2VELNee185efTJvef9NOrnvdoWTRh70gpRSSolXQkmghDLKKPPKKA+WUxYoo9wrpzxQTkW4ggqvgspgJdXRaioCFbs+NnTOTnQfvvoYKjZK30YGDUpxx6HYTlc6WSlWCTbDTQbvSUn2ZvLHJogFEie/8xcRkh+tDO5rIt89AyZ11/WzyzGgc4A2jikrIunbgsQuPGzJeEmPlRhOhHzrCOe9xKBSBevc4qiuCEmKsIskWhQKqp9IEAgEKAuVURYqs+m2peRnnkmBzGryLUZJgR+EjTe0mG2ywSyJeIJEMkGyJUkynCSRSpAsSZJIJkhn0qQDaVLZFGnSpDIpY2GQIZ1Lk0lkyIQzZINZsl6WbDZLNpElG88aayXnkUvlyHk5m0rsWzZe1iMQDBAgQCAQIOAFCCVCBEuDhAIhggnzNxwOE8oa6ylChHBbmHBZmEgmQjQbJZKLEAlEiIVixFIxoqko8WCceC5OrD1GfEeckkgJkVjE3hM3LiQFN+V/Ur43eUBy68QVioog91vceoXZg30EFRul/xHC/GDLsMFlycJJYC2iNmzCgRv7EeGqxCYgyHgf+eHLNvKjllHnrghBZxHyMCLkJjWAdbEVdgQyTUA5+VaNVNmWxAmwVp+bul34JCsZTeKqkwC2O66osJ4c/rHaCpbt6gm5K+vL7fAEiY0UDujEXEMoFjIiFi2zmYshzL2V71LSkiV5JOQcV6xauc9ZTNxO6qyJxSZC7mFjfzJYU86Rw7hlxVJtxSaFuPXucn775CHHtZ7lwUBEtdBS9eh879yEgIjzvvABRixf94HDvb/y2R0m0MdQsVH6N9IBS8JBBbYzFjeb1M4Sq0gGKgYwItKEHTRX6u/XSn7GknTY0hm6ItRKvgjJoEXpNMQdN4T8OmSCm3wgRPx2VZE/oFIGE8ogWbAj8UV0y53lIizyFC2ds3SGu3LfFcaW3MyoKJ2FqFBUcNrkXluoi/fusSXJwk07l2O5FoCkb7uhENkv4OxTmFLsnqdQCNyU5hD50zWIaEv2XID89jous47/SWmPG8Av7HEL71dX7yUbTzLO3O/NvRZZVzjWqY+gYqPsX8gPPIT5cYo7S+IlUn8qge2Ia7DpzbJ/OXYmxSjmyVrqU7lWi9vZuCJUhhGLAKazLcMKj1hSklk2lM6xghz5lpUgnX9lwbq4fz7XTSfut6yzDeSXBpIYkitY4o6RjLl28l1jUryzkDj5T+UiwIVCJvEudzvp0N24GliBEOET60YqQ7hiI25RVxwLO23J6IsVrBNrVtrfVUcubkg3nV7+1yQzzhUreZiRatduJQZXnOUagwXv3TRpOZefGt9xre61BTHfpYqNovQirgC5ddJkzE8amwEnMZsqfzu3KGIIOzZILCEZoFpotciTsggN2MoIUnurFJuwILWwZNzEIGyRSHewn8SKXEQsCjuaONY9FHC2lTEpblFTqQEmlo5bSsjNfpLOTqwjsRLLyZ8FVa69MMNPOllXLKUqgGtJigCJu1DO5Q6wlcQJEYRS8itvF7qeotjCliIqci9FGNxt3fZKyrq4UyW2JpUIpI0iiuIClTFl8j8IVrjkPrnuNxno6Qqg+zDglq2RbeU7HE7nB5Q+goqNMnARqyNC/tTNYuW4IpTCju2pwFgW0sG47hWpGVaGEYs0+ZOsuU+mUi4HbIHHdn8/KRBaSkdAnZz/WTLepLOXp+bh5NfzkmssHMAqgtFUcN3SEaexllMAKwRgrS13mbjuZGCkiE/Gv1etzjJx9QScZdIm6byFEmwFZrACmMSObZISQeK6kiKVbgIFzrlC5Hf6MeyUACIUklhRjnWlimjJNmKVyvcvri2xrHDWxzHfl3wPrrUGnQe0ishLe9P+9Yor1E0CcF2OZfTZeA2o2ChKZ6QzLYytFFpCKaxFI0/VFdhJvcQNInEWcbWJxdOMzWbLYuNN0gbInxisymlTmb+/BLgrsG4WtySLDJzdSX6QO4hxHxaOpHez9QSxeKRDlnaJOJU6y0uwiQ1iNbmVvUWYcs4yaVcV1sUIVlxdpJK4WAVihSWxbkw3CcJ1BUrhzkry64+Jiw7sbLTyACKWpVg3Ym1ItQGxEMXCkYQPsWqcqhB5ZWfEkpH3Iiri+hSLLuesd7+XoLOt3IMD6NM9eh9umqL0MXZlCUF+OXkRowQ2JiJPyWK9hLAds3Sq0jm1YQs4BrETd0n2kzzJSodVSn7KtVhhldgn4DKsi0gSGQIY60YEL40tPOm6tKSDdkfkg3Ufua47t7ONO8tElGX8kaQhy32TuFETNgAvgiiWi1gFhSIp2WSutSJ1zkTMUthK0WItigVThbWGXPGRyhQ7nfa1+H/FshILTwYmiytUhFbWDfWPI6It90DS1OW+StZkFOtSLXX+5pxzi+AEgDHkTwXeB1GxUZSeQH5JXVlD2YKXCJKk5EqatiQJSKBX3GRupeBmrBUlKb4tWJeeh+10xL3mxhLEspCOuQKTLiz7SceXc44pCQ5J7ORq0tkPw4iYtM8tSlooTIXun1LMLJjlWOGQig9iBbqiLJ1xCVYkwXb+bsxMziNtKMGMc4o5n5uwdfiCWGuokvzyOLJPGGtZVWOzHKXtcn9lLI18x3J8z79esV7d++FWiXAzBuNY95lbHUMs3gDGfTqSPo+KjaIUE7ejL0Q6dTfoLy954heLQNwtQ/x9ZaIy6YBTWLeZPPm2YTPiSvx9XXES910V1ropfMKW+JObGCBZb262nMRlJLEhix3jIq4nGdcENtg9hPzBp5LEIU/uYAeiSpxLkhEase43EVqxaCr940q8TGJaYkkGnGOBjfXIObJYF5qkrIvVImIkghXHut8kNR5sDEcsnBKMKDT62w7CCpQrjiXOMhH7YMFfiaeNAcax68oTfQgVG0XpLdyANXQea1NYMcAVIckGyxRsJ9aHiMZgf7lsK6IhAiY16cR9J7GlCuzgRRES6ehG+ucRy0vESVx7EqyXmIdUaZDjNvrtr8SKWit2rJMIkFhMnr8tWPeeuN7ACrGbTi6uMGm/nCuEseQiGHeciIqcQ1xuYMVIREOuVyytNmzGosSExMUpLjsZsxX2vwuJp7X5r4xzbdJmOZ/cbxFgeWiRJJWJWOu2H6Bioyh9lcIMMul8ukLiKe7ARcmqk0GuaWe5lMaR+I5YYIOd5VKDTjpa6Qzlbyt2llQZzNqK6bwl3iEZeQlsXEXSsF13osRypDOV88r8NNLxy/FlCgqpCtCCtRykUoTEN6qwlkkAI2Yi1uLOAxtsdwP0If+cKWzHvtNfPgKbqShiKqIu7rwE+YkEEs+RFPtGbFagJCHIvq5wS6WCUowlM5Y+W5ZmV6jYKMr+QOGIfqEwhiSIOLmIC08Eya1ALJ8l0y6MdellsGIigiWZe9LBu64f110ngzQlyUFEDqxQuNaaZNf5RUI7LDVX1MCObRKhFatDrElZLmNnRPxEZMqxrkpJY0/621T755DxVzKWSBIMJCnBrfwtlo7cP3F9VvjX24Ktoi1xKYnNSU3AUf4939V32sdRsVGUgUhX4rQnfn+JxbiDPcG6+LwutvMK1nvOPmLhxLAWi2SrScVusTjEbSYWkohG4XQPhQNfJa7jZtWJm0xSjCUtW2aTleNI3MmlcPySe0x3vAwF790xO7K9O+bGFa0Ynasd9FNUbBRF2XPcDtKlJwLVrsUlHbe8ArtY1tW+u1vmHrurv7varvDzrt4rnVCxURSlb9FVZ9/Vsr5CYWxN6ZL9wDhTFEVR+joqNoqiKErR6ZbYbNy4kS9+8YvMmDGD0tJSAoEA69at67RdIpHg2muvZeTIkZSUlDBjxgyee+65Ttvlcjluuukmxo8fTzweZ+rUqTzwwAN7fTGKoihK36RbYvPmm2/y29/+lurqao499thdbvfZz36WhQsX8t3vfpdHHnmEkSNHcvLJJ7Ny5cq87b75zW/y7W9/myuvvJLHH3+cY445hnPOOYfHHntsry5GURRF6aN43SCbzXa8X7hwoQd4a9euzdtm5cqVHuAtWrSoY1k6nfYOPvhgb86cOR3Ltm7d6kWjUe+GG27I23/WrFnelClTutMc74gjjujWdoqiKMq+Y3d9c7csm2Dw/TdbsmQJkUiEc889t2NZOBzmvPPO44knniCZTALwxBNPkEqlmDdvXt7+8+bNY9WqVaxdu7b7SqkoiqL0C3osQWD16tVMmDCB0tL8CShqa2tJpVK8+eabHdvFYjEmTpzYaTuANWvW9FSTFEVRlD5Cj4lNfX091dXVnZbX1NR0rJe/VVVVBAKB3W6nKIqi7D/0m0GdCxYsYMGCBQBs3769l1ujKIqi7Ak9ZtlUV1fT0NDQablYKmK5VFdX09jYiOd5u92ukPnz57NixQpWrFjB0KFDe6rZiqIoyj6gx8SmtraWtWvX0tbWlrd8zZo1RKPRjhhNbW0tyWSSt956q9N2AIcddlhPNUlRFEXpI/SY2MyZM4d0Os3ixYs7lmUyGe677z5mz55NLGZKpp5yyilEIhHuvvvuvP1//etfM3nyZCZMmNBTTVIURVH6CN2O2dx///0A/PWvfwXg8ccfZ+jQoQwdOpSZM2dy+OGHc+655/KlL32JdDrNhAkTuOOOO1i7dm2esAwbNowvf/nL3HTTTVRUVDB9+nTuu+8+li1bxpIlS3r48hRFUZQ+QXcH65Bf1LvjNXPmzI5t2travKuvvtobPny4F4vFvKOOOspbvnx5p2NlMhnve9/7njdu3DgvGo16U6ZM8RYvXtwjA4cURVGU3mF3fXPA87xdzfbQZ6mrq2PFihW93QxFURTFYXd9s1Z9VhRFUYqOio2iKIpSdFRsFEVRlKKjYqMoiqIUHRUbRVEUpeio2CiKoihFR8VGURRFKToqNoqiKErRUbFRFEVRio6KjaIoilJ0VGwURVGUoqNioyiKohQdFRtFURSl6KjYKIqiKEVHxUZRFEUpOio2iqIoStFRsVEURVGKjoqNoiiKUnRUbBRFUZSio2KjKIqiFB0VG0VRFKXoqNgoiqIoRUfFRlEURSk6KjaKoihK0VGxURRFUYqOio2iKIpSdFRsFEVRlKKjYqMoiqIUHRUbRVEUpeio2CiKoihFR8VGURRFKToqNoqiKErRUbFRFEVRio6KjaIoilJ0VGwURVGUoqNioyiKohQdFRtFURSl6KjYKIqiKEVHxUZRFEUpOio2iqIoStFRsVEURVGKjoqNoiiKUnRUbBRFUZSi0y2x2bhxI1/84heZMWMGpaWlBAIB1q1bl7fNihUrmD9/PocccgilpaWMGzeOCy+8kLVr13Y6Xi6X46abbmL8+PHE43GmTp3KAw880CMXpCiKovQ9uiU2b775Jr/97W+prq7m2GOP7XKb3/zmN6xevZqrrrqKxx9/nO9///u8/PLL1NXVsWHDhrxtv/nNb/Ltb3+bK6+8kscff5xjjjmGc845h8cee2zvr0hRFEXpe3jdIJvNdrxfuHChB3hr167N22bbtm2d9lu3bp0XCAS8b37zmx3Ltm7d6kWjUe+GG27I23bWrFnelClTutMc74gjjujWdoqiKMq+Y3d9c7csm2Dw/TcbOnRop2UHHHAAQ4cOZdOmTR3LnnjiCVKpFPPmzcvbdt68eaxatapLt5uiKIrSvylqgsBrr73Gtm3bOPTQQzuWrV69mlgsxsSJE/O2ra2tBWDNmjXFbJKiKIrSCxRNbDKZDJdffjlDhw7ls5/9bMfy+vp6qqqqCAQCedvX1NR0rFcURVH2L8LFOvCVV17Jiy++yKOPPkp1dfVeH2/BggUsWLAAgO3bt+/18RRFUZR9R1Esm6997WssWLCARYsWMXv27Lx11dXVNDY24nle3nKxaMTCKWT+/PmsWLGCFStWdBkfUhRFUfouPS42N954Iz/4wQ+47bbbuOiiizqtr62tJZlM8tZbb+Utl1jNYYcd1tNNUhRFUXqZHhWb2267jeuvv54bb7yRK6+8ssttTjnlFCKRCHfffXfe8l//+tdMnjyZCRMm9GSTFEVRlD5At2M2999/PwB//etfAXj88ccZOnQoQ4cOZebMmfzmN7/hS1/6EqeccgqzZs3iT3/6U8e+gwYN6rBYhg0bxpe//GVuuukmKioqmD59Ovfddx/Lli1jyZIlPXltiqIoSh+h22Jzzjnn5H2+4oorAJg5cybPPPMMS5cuxfM8li5dytKlS/O2lW2EG2+8kfLycn70ox+xZcsWJk2axG9/+1tOPfXUvbgURVEUpa8S8Aoj9f2Auro6VqxY0dvNUBRFURx21zdr1WdFURSl6KjYKIqiKEVHxUZRFEUpOio2iqIoStFRsVEURVGKjoqNoiiKUnRUbBRFUZSio2KjKIqiFB0VG0VRFKXoqNgoiqIoRUfFRlEURSk6KjaKoihK0VGxURRFUYqOio2iKIpSdPrlFANDhgyhrKyMoUOH9nZTisb27dv36+uD/f8a9fr6N3p9e866det47733ulzXL8UG9v85bfb364P9/xr1+vo3en09i7rRFEVRlKKjYqMoiqIUnX4rNvPnz+/tJhSV/f36YP+/Rr2+/o1eX8/Sb2M2iqIoSv+h31o2iqIoSv+hX4nNhg0bOPvss6msrGTQoEGceeaZrF+/vrebtcfcf//9nHXWWRxwwAGUlJQwadIkvv71r9Pc3Jy3XUNDA5deemlHqveJJ57IqlWreqnVe8cpp5xCIBDg+uuvz1ve36/xscce47jjjqO8vJxBgwZRV1fHsmXLOtb35+t74YUXmD17NsOGDaOiooLp06ezaNGivG0SiQTXXnstI0eOpKSkhBkzZvDcc8/1Uot3zcaNG/niF7/IjBkzKC0tJRAIsG7duk7bdfd6crkcN910E+PHjycejzN16lQeeOCBfXAlXdOd61uxYgXz58/nkEMOobS0lHHjxnHhhReydu3aTscryvV5/YTW1lZv4sSJXm1trff73//ee/DBB73Jkyd7Bx54oNfS0tLbzdsjjj76aO+cc87xfv3rX3vPPPOM98Mf/tCrrKz0jj76aC+bzXqe53m5XM776Ec/6o0ePdq75557vMcff9w77rjjvMGDB3sbNmzo5SvYM+655x5vxIgRHuBdd911Hcv7+zX+9Kc/9cLhsPelL33Je/LJJ72lS5d63//+972HH37Y87z+fX2vvPKKF4/HvY997GPegw8+6D355JPe/PnzPcD7yU9+0rHdBRdc4FVWVnoLFizwnnrqKe+MM87w4vG497e//a33Gt8Fy5cv94YNG+Z9/OMf92bPnu0B3tq1aztt193r+cY3vuFFo1Hvlltu8ZYtW+bNnz/fCwQC3qOPPrpvLqiA7lzfv/3bv3kf+chHvNtvv9175plnvLvvvts75JBDvJqaGm/9+vV52xbj+vqN2Pz3f/+3FwwGvTfeeKNj2dtvv+2FQiHvP//zP3uxZXvOtm3bOi375S9/6QHe008/7Xme5z344IMe4C1btqxjm8bGRq+6utr74he/uM/aurfU19d7w4cP9+65555OYtOfr3Ht2rVePB73fvjDH+5ym/58fV//+te9SCTiNTc35y0/5phjvGOOOcbzPM9buXKlB3iLFi3qWJ9Op72DDz7YmzNnzj5t7/shD3Ge53kLFy7ssjPu7vVs3brVi0aj3g033JC3/6xZs7wpU6YU5wLeh+5cX1f9zrp167xAIOB985vf7FhWrOvrN260JUuWcMwxxzBx4sSOZRMmTOCjH/0oDz30UC+2bM/patTukUceCcCmTZsAc72jRo3i+OOP79imsrKSOXPm9Kvr/epXv8rkyZM5//zzO63rz9e4aNEigsEgl19++S636c/Xl0qliEQilJSU5C2vrKwkl8sB5voikQjnnntux/pwOMx5553HE088QTKZ3Kdt3h3B4Pt3dd29nieeeIJUKsW8efPy9p83bx6rVq3q0i1VbLpzfV31OwcccABDhw7t6HegeNfXb8Rm9erVTJ48udPy2tpa1qxZ0wst6lmeffZZAA499FBg99e7fv16Wlpa9mn7Pgh/+MMfuOuuu7j99tu7XN+fr/EPf/gDhxxyCL/5zW846KCDCIfDTJw4Me9a+/P1XXLJJQBcddVVbN68mcbGRhYuXMjTTz/N1VdfDZjrmzBhAqWlpXn71tbWkkqlePPNN/d1s/eK7l7P6tWricVieQ++sh3Qr/qj1157jW3btnX0O1C86+s3YlNfX091dXWn5TU1NTQ0NPRCi3qOTZs2ccMNN3DiiSdSV1cH7P56gT5/zalUissuu4xrrrmGSZMmdblNf77GzZs388Ybb3Dttdfyta99jSeffJKTTjqJK6+8kh/96EdA/76+yZMn88wzz/DQQw8xevRoqqur+cIXvsBPf/pTzjvvPOD9r6++vn6ftnlv6e711NfXU1VVRSAQ2O12fZ1MJsPll1/O0KFD+exnP9uxvFjXF/7gTVV6gpaWFk477TTC4TB33nlnbzenx7j55ptpb2/nuuuu6+2mFIVcLkdzczO/+MUvOPPMMwGYNWsW69at46abbuKqq67q5RbuHW+88QZnnXUWtbW1/PSnP6WkpISHHnqIyy+/nHg8zoUXXtjbTVT2kiuvvJIXX3yRRx99tEuR7Wn6jdhUV1d3+SS4q6eR/kB7eztz5szh7bff5tlnn2XMmDEd63Z3vbK+r7J+/XpuvPFGfv7zn5NMJvN898lkksbGRioqKvr1NQ4ePJg33niDk046KW/57NmzWbp0Ke+++26/vr5vfOMbRCIRHnnkESKRCAAnnHACO3bs4P/9v//H+eefT3V1Ne+8806nfeX65Em4v9Dd66murqaxsRHP8/Ke/vvTdX/ta19jwYIF/PKXv2T27Nl564p1ff3GjVZbW8vq1as7LV+zZg2HHXZYL7Ro70in05x99tmsWLGCxx57jClTpuSt3931jhs3jvLy8n3V1D3m7bffJpFIMG/ePKqrqzteALfeeivV1dWsWrWqX1+j+K93RTAY7NfXt2rVKqZOndohNMJRRx3Fjh072LZtG7W1taxdu5a2tra8bdasWUM0Gu3k8+/rdPd6amtrSSaTvPXWW522A/p8f3TjjTfygx/8gNtuu42LLrqo0/qiXd8HzmPbx/zwhz/0QqGQ99Zbb3UsW7t2rRcOh71bb721F1u252SzWe+cc87x4vG499RTT3W5ze9//3sP8J555pmOZTt37vRqamq8K6+8cl819QPR0NDgLV++vNML8ObNm+ctX77ca25u7tfX+Mgjj3iAt3jx4rzls2fP9saMGeN5Xv/+DmfOnOlNmDDBSyaTecvPP/98Lx6Pe8lk0nv55Zc9wPvFL37RsT6dTnuHHHKId+qpp+7rJnebXaUGd/d6tm7d6kUiEe/b3/523v4nnHCCN3ny5KK2vTvs6vo8z/N+9KMfeYB344037nL/Yl1fvxGblpYW76CDDvImT57sPfjgg95DDz3kffjDH/YmTJjQaSxAX+fyyy/vGHPyxz/+Me8lg/2y2aw3Y8YMb8yYMd69997rLV261Js5c6ZXXV3daQBWf4GCcTb9+RpzuZx3/PHHezU1Nd4dd9zhPfHEE96ll17qAd6dd97peV7/vr7Fixd7gDd79mzvwQcf9J544gnvC1/4ggd4V199dcd25557rldVVeUtXLjQe+qpp7yzzjrLi8Vi3l//+tdebH3XLF682Fu8eHHH7+8nP/mJt3jx4ryHge5ez1e/+lUvFot5//mf/+ktX77cu/zyy71AINAxoLc3eL/ru/fee71AIOCdcsopnfqd1atX5x2rGNfXb8TG8zzvnXfe8c4880yvoqLCKy8v90477bQu1buvc8ABB3hAl69vfetbHdvt2LHD+/SnP+1VV1d7JSUl3qxZs7yVK1f2XsP3kkKx8bz+fY07d+70rrjiCm/YsGFeJBLxpkyZ4t1999152/Tn63vssce8mTNnekOGDPHKy8u9qVOnerfffruXyWQ6tmlra/Ouvvpqb/jw4V4sFvOOOuoob/ny5b3X6N2wq9/czJkzO7bp7vVkMhnve9/7njdu3DgvGo16U6ZM6WTl7mve7/ouvvjibt0DzyvO9WnVZ0VRFKXo9JsEAUVRFKX/omKjKIqiFB0VG0VRFKXoqNgoiqIoRUfFRlEURSk6KjaKoihK0VGxURRFUYqOio2iKIpSdFRsFEVRlKLz/wHkUVgLnbfD7QAAAABJRU5ErkJggg==\n", "text/plain": [ "
" ] @@ -663,7 +709,7 @@ "trajectory = get_trajectory(info.best_solution).cpu()\n", "\n", "sdf = th.eb.SignedDistanceField2D(\n", - " th.Variable(batch[\"sdf_origin\"]),\n", + " th.Point2(batch[\"sdf_origin\"]),\n", " th.Variable(batch[\"cell_size\"]),\n", " th.Variable(batch[\"sdf_data\"]),\n", ")\n", diff --git a/tutorials/05_differentiable_motion_planning.ipynb b/tutorials/05_differentiable_motion_planning.ipynb index e14d9f256..3eaef4ae6 100644 --- a/tutorials/05_differentiable_motion_planning.ipynb +++ b/tutorials/05_differentiable_motion_planning.ipynb @@ -2,6 +2,7 @@ "cells": [ { "cell_type": "markdown", + "id": "d2052376", "metadata": {}, "source": [ "# Motion Planning Part 2: differentiable motion planning" @@ -9,6 +10,7 @@ }, { "cell_type": "markdown", + "id": "37cde4fb", "metadata": {}, "source": [ "In this tutorial, we will build on the [first part](https://github.com/facebookresearch/theseus/blob/main/tutorials/04_motion_planning.ipynb) of the motion planning tutorial to illustrate how we can differentiate through a motion planner implemented using `Theseus`. In particular, we will show how to set up an imitation learning loop in `torch` to produce values to initialize the `TheseusLayer` so that it converges to a high quality trajectory faster. If you haven't already, we encourage you to review part 1 of the motion planning tutorial before proceeding with this one." @@ -17,6 +19,7 @@ { "cell_type": "code", "execution_count": 1, + "id": "e29b5088", "metadata": {}, "outputs": [], "source": [ @@ -49,6 +52,7 @@ }, { "cell_type": "markdown", + "id": "aae80147", "metadata": {}, "source": [ "## 1. Initial setup" @@ -56,6 +60,7 @@ }, { "cell_type": "markdown", + "id": "bb2c2929", "metadata": {}, "source": [ "As in part 1 of the motion planning tutorial, the first step is to load a few planning problems from the dataset, and set up some constant quantities to use throughout the experiment. During this example, we will use a batch of 2 problems obtained from the loader." @@ -64,6 +69,7 @@ { "cell_type": "code", "execution_count": 2, + "id": "75279a01", "metadata": {}, "outputs": [], "source": [ @@ -88,6 +94,7 @@ }, { "cell_type": "markdown", + "id": "5c1238b5", "metadata": {}, "source": [ "Next we create the motion planner. Class `theg.MotionPlanner` stores a `TheseusLayer` constructed by following the steps described in part 1, and also provides some useful utility functions to retrieve trajectories from the current variables of the optimizer. " @@ -96,6 +103,7 @@ { "cell_type": "code", "execution_count": 3, + "id": "05e29cbc", "metadata": {}, "outputs": [], "source": [ @@ -115,6 +123,7 @@ }, { "cell_type": "markdown", + "id": "f42f7ee6", "metadata": {}, "source": [ "Since we are working with a single batch of data, we can initialize the input dictionary for the motion planner with some tensors that will be throughout this example. As a reminder, the input dictionary associates `th.Variable` names in the `TheseusLayer` with tensor values for each of them." @@ -123,6 +132,7 @@ { "cell_type": "code", "execution_count": 4, + "id": "84d04f40", "metadata": {}, "outputs": [], "source": [ @@ -139,6 +149,7 @@ }, { "cell_type": "markdown", + "id": "6b4e8fb4", "metadata": {}, "source": [ "## 2. Imitation learning loop" @@ -146,6 +157,7 @@ }, { "cell_type": "markdown", + "id": "a6d5d240", "metadata": {}, "source": [ "### Overview" @@ -153,6 +165,7 @@ }, { "cell_type": "markdown", + "id": "6e7858a4", "metadata": {}, "source": [ "We consider the following imitation learning pipeline in this example (see Section 2.2):\n", @@ -167,6 +180,7 @@ }, { "cell_type": "markdown", + "id": "e193bdef", "metadata": {}, "source": [ "### 2.1. A basic initial trajectory model" @@ -174,6 +188,7 @@ }, { "cell_type": "markdown", + "id": "21597f90", "metadata": {}, "source": [ "The following cell creates a basic model for generating initial trajectories. This model takes as input a one hot representation of the map's ID and generates a trajectory between the map's start and goal positions. The output is a dictionary with keys mapping to variable names, and values mapping to initial values (tensors) for each of them that represent the resulting trajectory.\n", @@ -185,6 +200,7 @@ { "cell_type": "code", "execution_count": 5, + "id": "ec11a366", "metadata": {}, "outputs": [], "source": [ @@ -195,6 +211,7 @@ }, { "cell_type": "markdown", + "id": "890f327f", "metadata": {}, "source": [ "### 2.2. Learning loop" @@ -202,6 +219,7 @@ }, { "cell_type": "markdown", + "id": "baf41709", "metadata": {}, "source": [ "With the model in place, we can now put all of this together to differentiate through the motion planner, and find good initial trajectories for optimization on two maps. This loop essentially follows steps 1-4 from the overview subsection." @@ -210,6 +228,7 @@ { "cell_type": "code", "execution_count": 6, + "id": "1a2c32a2", "metadata": { "scrolled": true }, @@ -296,6 +315,7 @@ { "cell_type": "code", "execution_count": 7, + "id": "9c242230", "metadata": {}, "outputs": [ { @@ -319,6 +339,7 @@ }, { "cell_type": "markdown", + "id": "ba844fd9", "metadata": {}, "source": [ "## 3. Results" @@ -326,6 +347,7 @@ }, { "cell_type": "markdown", + "id": "3467b83d", "metadata": {}, "source": [ "Let's now visualize the trajectories produced using the learned initializations, running the optimizer for a few more iterations. The following functions will be useful to plot the trajectories from the variable value dictionaries." @@ -334,6 +356,7 @@ { "cell_type": "code", "execution_count": 8, + "id": "d4c9b5e2", "metadata": {}, "outputs": [], "source": [ @@ -349,7 +372,7 @@ " sol_traj = get_trajectory(solution_traj_dict).detach().clone().cpu()\n", "\n", " sdf = th.eb.SignedDistanceField2D(\n", - " th.Variable(batch[\"sdf_origin\"]),\n", + " th.Point2(batch[\"sdf_origin\"]),\n", " th.Variable(batch[\"cell_size\"]),\n", " th.Variable(batch[\"sdf_data\"]),\n", " )\n", @@ -371,6 +394,7 @@ }, { "cell_type": "markdown", + "id": "cdece815", "metadata": {}, "source": [ "### 3.1. Trajectories initialized from straight lines" @@ -378,6 +402,7 @@ }, { "cell_type": "markdown", + "id": "d8acbdc6", "metadata": {}, "source": [ "As reference, below we show the quality of trajectories obtained after 10 optimizer iterations when initialized from a straight line. As the plots show, the trajectories produced from a straight line are of bad quality; more than 10 iterations are neeed to produce good quality trajectories (in part 1, we used 50). " @@ -386,6 +411,7 @@ { "cell_type": "code", "execution_count": 9, + "id": "0de3204f", "metadata": {}, "outputs": [ { @@ -427,6 +453,7 @@ }, { "cell_type": "markdown", + "id": "f93335fb", "metadata": {}, "source": [ "### 3.2 Learned initial trajectories" @@ -434,6 +461,7 @@ }, { "cell_type": "markdown", + "id": "3a5e96a1", "metadata": {}, "source": [ "On the other hand, with learned initial trajectories the plots below show 10 iterations is enough to produce smooth trajectories that avoid all obstacles, illustrating the potential of differentiating through the trajectories planner.trj" @@ -442,6 +470,7 @@ { "cell_type": "code", "execution_count": 10, + "id": "b34967ba", "metadata": {}, "outputs": [ { From 81b9d040c8da775e0e25ffd46df8ad23f60aad5a Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Thu, 28 Jul 2022 11:42:23 -0400 Subject: [PATCH 05/38] Fixed small bugs in MotionPlanner class (#261) * Changed SDF constructor to accept more convenient data types. * Fixed broken test and added missing copyright headers. * Fixed bug in MotionPlanner utility class. --- .../motion_planning/motion_planner.py | 34 +++++++++++-------- 1 file changed, 19 insertions(+), 15 deletions(-) diff --git a/theseus/utils/examples/motion_planning/motion_planner.py b/theseus/utils/examples/motion_planning/motion_planner.py index 695958a0d..86c8a5a07 100644 --- a/theseus/utils/examples/motion_planning/motion_planner.py +++ b/theseus/utils/examples/motion_planning/motion_planner.py @@ -51,23 +51,25 @@ def __init__( # functions. # By giving them names, we can update for each batch (if needed), # via the motion planner's forward method. - sdf_origin = th.Point2(name="sdf_origin") - start_point = th.Point2(name="start") - goal_point = th.Point2(name="goal") - cell_size_tensor = th.Variable(torch.empty(1, 1), name="cell_size") - sdf_data_tensor = th.Variable( - torch.empty(1, map_size, map_size), name="sdf_data" + sdf_origin = th.Point2(name="sdf_origin", dtype=dtype) + start_point = th.Point2(name="start", dtype=dtype) + goal_point = th.Point2(name="goal", dtype=dtype) + cell_size = th.Variable(torch.empty(1, 1, dtype=dtype), name="cell_size") + sdf_data = th.Variable( + torch.empty(1, map_size, map_size, dtype=dtype), name="sdf_data" + ) + cost_eps = th.Variable( + torch.tensor(epsilon_dist, dtype=dtype).view(1, 1), name="cost_eps" ) - cost_eps = th.Variable(torch.tensor(epsilon_dist).view(1, 1), name="cost_eps") dt = th.Variable( - torch.tensor(total_time / num_time_steps).view(1, 1), name="dt" + torch.tensor(total_time / num_time_steps, dtype=dtype).view(1, 1), name="dt" ) # --------------------------------------------------------------------------- # # ------------------------------- Cost weights ------------------------------ # # --------------------------------------------------------------------------- # # For the GP cost functions, we create a single GPCost weight - gp_cost_weight = th.eb.GPCostWeight(torch.tensor(Qc_inv), dt) + gp_cost_weight = th.eb.GPCostWeight(torch.tensor(Qc_inv, dtype=dtype), dt) # Now we create cost weights for the collision-avoidance cost functions # Each of this is a scalar cost weight with a named auxiliary variable. @@ -77,7 +79,9 @@ def __init__( if use_single_collision_weight: collision_cost_weights.append( th.ScaleCostWeight( - th.Variable(torch.tensor(collision_weight), name="collision_w") + th.Variable( + torch.tensor(collision_weight, dtype=dtype), name="collision_w" + ) ) ) else: @@ -92,7 +96,7 @@ def __init__( # For hard-constraints (end points pos/vel) we use a single scalar weight # with high value - boundary_cost_weight = th.ScaleCostWeight(torch.tensor(100.0)) + boundary_cost_weight = th.ScaleCostWeight(torch.tensor(100.0, dtype=dtype)) # --------------------------------------------------------------------------- # # -------------------------- Optimization variables ------------------------- # @@ -120,7 +124,7 @@ def __init__( objective.add( th.Difference( velocities[0], - th.Point2(tensor=torch.zeros(1, 2)), + th.Point2(tensor=torch.zeros(1, 2, dtype=dtype)), boundary_cost_weight, name="vel_0", ) @@ -131,7 +135,7 @@ def __init__( objective.add( th.Difference( velocities[-1], - th.Point2(tensor=torch.zeros(1, 2)), + th.Point2(tensor=torch.zeros(1, 2, dtype=dtype)), boundary_cost_weight, name="vel_N", ) @@ -145,8 +149,8 @@ def __init__( th.eb.Collision2D( poses[i], sdf_origin, - sdf_data_tensor, - cell_size_tensor, + sdf_data, + cell_size, cost_eps, collision_cost_weights[0] if use_single_collision_weight From 8d1605fbeb16b88e83dde9808c37c0e6c39bdae4 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Fri, 29 Jul 2022 09:37:37 -0400 Subject: [PATCH 06/38] Added option to visualize SDF to trajectory visualization function (#263) * Changed generate_trajectory_figs to also plot SDF. * Tweaked figure style. --- .../utils/examples/motion_planning/misc.py | 29 +++++++++++++++---- 1 file changed, 23 insertions(+), 6 deletions(-) diff --git a/theseus/utils/examples/motion_planning/misc.py b/theseus/utils/examples/motion_planning/misc.py index 04025dae3..e7648f392 100644 --- a/theseus/utils/examples/motion_planning/misc.py +++ b/theseus/utils/examples/motion_planning/misc.py @@ -152,6 +152,8 @@ def generate_trajectory_figs( labels: Optional[List[str]] = None, fig_idx_robot: int = 1, figsize: Tuple[int, int] = (8, 8), + plot_sdf: bool = False, + invert_map: bool = False, ) -> List[plt.Figure]: # cell rows/cols for each batch of trajectories traj_rows = [] @@ -169,26 +171,41 @@ def generate_trajectory_figs( for map_idx in range(map_tensor.shape[0]): if map_idx >= max_num_figures: continue - fig, axs = plt.subplots(1, 1, figsize=figsize) + fig, axs = plt.subplots(1, 2 if plot_sdf else 1, figsize=figsize) + if plot_sdf: + fig.subplots_adjust(right=0.8) + cbar_ax = fig.add_axes([0.85, 0.15, 0.10, 0.7]) + cbar_ax.axis("off") + + path_ax = axs[0] if plot_sdf else axs map_data = map_tensor[map_idx].clone().cpu().numpy() + if invert_map: + map_data = 1 - map_data map_data = np.tile(map_data, (3, 1, 1)).transpose((1, 2, 0)) - axs.imshow(map_data) + path_ax.imshow(map_data) cell_size = sdf.cell_size.tensor patches = [] for t_idx, trajectory in enumerate(trajectories): row = traj_rows[t_idx][map_idx] col = traj_cols[t_idx][map_idx] line = _create_line_from_trajectory(col, row, color=colors[t_idx]) - axs.add_line(line) + path_ax.add_line(line) if t_idx == fig_idx_robot: # solution trajectory radius = robot_radius / cell_size[map_idx][0] patch_coll = _add_robot_to_trajectory(col, row, radius) - axs.add_collection(patch_coll) + path_ax.add_collection(patch_coll) patches.append(mpl.patches.Patch(color=colors[t_idx], label=labels[t_idx])) patches.append( mpl.patches.Patch(color="magenta", label=f"radius = {robot_radius}") ) - axs.legend(handles=patches, fontsize=10) - fig.tight_layout() + path_ax.legend(handles=patches, fontsize=10) + + if plot_sdf: + im = axs[1].imshow( + sdf.sdf_data.tensor[map_idx].cpu().numpy(), cmap="plasma_r" + ) + fig.colorbar(im, ax=cbar_ax) + else: + fig.tight_layout() figures.append(fig) return figures From 0672bf962973c25cb8794d3c834af55800a79aba Mon Sep 17 00:00:00 2001 From: Mustafa Mukadam Date: Wed, 3 Aug 2022 11:21:57 -0400 Subject: [PATCH 07/38] update readme (#264) --- CONTRIBUTING.md | 2 +- README.md | 39 ++++++++++++++++++++++++--------------- 2 files changed, 25 insertions(+), 16 deletions(-) diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 53d2a17b3..0e33a4381 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -44,7 +44,7 @@ pip install pre-commit && pre-commit install && pre-commit run --all-files ## Versioning We use [semantic versioning](https://semver.org/). For core Theseus team member, to prepare a release: -- Update version in [init](https://github.com/facebookresearch/theseus/__init__.py) file. +- Update version in [init](https://github.com/facebookresearch/theseus/blob/main/theseus/__init__.py) file. - Make sure all tests are passing. - Create a release tag with changelog summary using the github release interface. diff --git a/README.md b/README.md index a407f36d6..99da3a42f 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -![Theseus Logo](https://github.com/facebookresearch/theseus/blob/main/docs/source/img/theseus-color-horizontal.png) +![Theseus Logo](https://raw.githubusercontent.com/facebookresearch/theseus/main/docs/source/img/theseus-color-horizontal.png)

@@ -22,20 +22,20 @@

- A library for differentiable nonlinear optimization + A library for differentiable nonlinear optimization

- [Paper] - [Blog] - [Webpage] - [Tutorials] - [Docs] + Paper • + Blog • + Webpage • + Tutorials • + Docs

Theseus is an efficient application-agnostic library for building custom nonlinear optimization layers in PyTorch to support constructing various problems in robotics and vision as end-to-end differentiable architectures. -TheseusLayer +TheseusLayer Differentiable nonlinear optimization provides a general scheme to encode inductive priors, as the objective function can be partly parameterized by neural models and partly with expert domain-specific differentiable models. The ability to compute gradients end-to-end is retained by differentiating through the optimizer which allows neural models to train on the final task loss, while also taking advantage of priors captured by the optimizer. @@ -60,6 +60,7 @@ We support several features that improve computation times and memory consumptio - [Automatic vectorization](https://github.com/facebookresearch/theseus/blob/main/theseus/core/vectorizer.py) - [Backward modes](https://github.com/facebookresearch/theseus/blob/main/theseus/optimizer/nonlinear/nonlinear_optimizer.py): Implicit, Truncated, Direct Loss Minimization ([DLM](https://github.com/facebookresearch/theseus/blob/main/theseus/theseus_layer.py)), Sampling ([LEO](https://github.com/facebookresearch/theseus/blob/main/examples/state_estimation_2d.py)) + ## Getting Started ### Prerequisites @@ -126,13 +127,6 @@ for epoch in range(10): See [tutorials](https://github.com/facebookresearch/theseus/blob/main/tutorials/), and robotics and vision [examples](https://github.com/facebookresearch/theseus/tree/main/examples) to learn about the API and usage. -## Additional Information - -- Join the community on [Github Discussions](https://github.com/facebookresearch/theseus/discussions) for questions and sugesstions. -- Use [Github Issues](https://github.com/facebookresearch/theseus/issues/new/choose) for bugs and features. -- See [CONTRIBUTING](https://github.com/facebookresearch/theseus/blob/main/CONTRIBUTING.md) if interested in helping out. - - ## Citing Theseus If you use Theseus in your work, please cite the [paper](https://arxiv.org/abs/2207.09442) with the BibTeX below. @@ -150,3 +144,18 @@ If you use Theseus in your work, please cite the [paper](https://arxiv.org/abs/2 ## License Theseus is MIT licensed. See the [LICENSE](https://github.com/facebookresearch/theseus/blob/main/LICENSE) for details. + + +## Additional Information + +- Join the community on [Github Discussions](https://github.com/facebookresearch/theseus/discussions) for questions and sugesstions. +- Use [Github Issues](https://github.com/facebookresearch/theseus/issues/new/choose) for bugs and features. +- See [CONTRIBUTING](https://github.com/facebookresearch/theseus/blob/main/CONTRIBUTING.md) if interested in helping out. + +Theseus is made possible by the following contributors: + + + + + +Made with [contrib.rocks](https://contrib.rocks). From 59b28a9afd289f3dd8faa05222a7735d90fc21e0 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Thu, 4 Aug 2022 13:32:03 -0700 Subject: [PATCH 08/38] Using darker alpha for robot visualization in generate_trajectory_figs for motion planning example. --- theseus/utils/examples/motion_planning/misc.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/theseus/utils/examples/motion_planning/misc.py b/theseus/utils/examples/motion_planning/misc.py index e7648f392..39da4a7cc 100644 --- a/theseus/utils/examples/motion_planning/misc.py +++ b/theseus/utils/examples/motion_planning/misc.py @@ -192,7 +192,7 @@ def generate_trajectory_figs( path_ax.add_line(line) if t_idx == fig_idx_robot: # solution trajectory radius = robot_radius / cell_size[map_idx][0] - patch_coll = _add_robot_to_trajectory(col, row, radius) + patch_coll = _add_robot_to_trajectory(col, row, radius, alpha=0.25) path_ax.add_collection(patch_coll) patches.append(mpl.patches.Patch(color=colors[t_idx], label=labels[t_idx])) patches.append( From 93e183dea35a86e07156fc4b5d2a47c75f7006b8 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Thu, 11 Aug 2022 09:33:37 -0400 Subject: [PATCH 09/38] Added MotionPlanner.forward() method. (#267) --- theseus/__init__.py | 1 + .../examples/motion_planning/motion_planner.py | 17 +++++++++++++---- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/theseus/__init__.py b/theseus/__init__.py index f2073f0f6..7f21e31b2 100644 --- a/theseus/__init__.py +++ b/theseus/__init__.py @@ -58,6 +58,7 @@ ) from .optimizer import ( DenseLinearization, + OptimizerInfo, SparseLinearization, VariableOrdering, ManifoldGaussian, diff --git a/theseus/utils/examples/motion_planning/motion_planner.py b/theseus/utils/examples/motion_planning/motion_planner.py index 86c8a5a07..e9477c106 100644 --- a/theseus/utils/examples/motion_planning/motion_planner.py +++ b/theseus/utils/examples/motion_planning/motion_planner.py @@ -4,7 +4,7 @@ # LICENSE file in the root directory of this source tree. import copy -from typing import Dict, List, Optional, Tuple +from typing import Any, Dict, List, Optional, Tuple import torch @@ -106,14 +106,14 @@ def __init__( poses = [] velocities = [] for i in range(self.trajectory_len): - poses.append(th.Point2(name=f"pose_{i}", dtype=torch.double)) - velocities.append(th.Point2(name=f"vel_{i}", dtype=torch.double)) + poses.append(th.Point2(name=f"pose_{i}", dtype=dtype)) + velocities.append(th.Point2(name=f"vel_{i}", dtype=dtype)) # --------------------------------------------------------------------------- # # ------------------------------ Cost functions ----------------------------- # # --------------------------------------------------------------------------- # # Create a Theseus objective for adding the cost functions - objective = th.Objective(dtype=torch.double) + objective = th.Objective(dtype=self.dtype) # First create the cost functions for the end point positions and velocities # which are hard constraints, and can be implemented via Difference cost @@ -234,6 +234,15 @@ def __init__( # variables are not modified. For convenience, the output is a dictionary of # (str, tensor) mapping variable names to optimized variable data tensors. + def forward( + self, + input_tensors: Optional[Dict[str, torch.Tensor]] = None, + optimizer_kwargs: Optional[Dict[str, Any]] = None, + ) -> Tuple[Dict[str, torch.Tensor], th.OptimizerInfo]: + return self.layer.forward( + input_tensors=input_tensors, optimizer_kwargs=optimizer_kwargs + ) + def get_variable_values_from_straight_line( self, start: torch.Tensor, goal: torch.Tensor ) -> Dict[str, torch.Tensor]: From 64732c152913771ccfd06d29fe95e2644dba68c5 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Wed, 17 Aug 2022 00:08:09 -0400 Subject: [PATCH 10/38] Small bug fixes and tweaks to generate_trajectory_figs. (#271) --- .../utils/examples/motion_planning/misc.py | 10 +-- tutorials/04_motion_planning.ipynb | 63 +++---------------- .../05_differentiable_motion_planning.ipynb | 37 ++--------- 3 files changed, 19 insertions(+), 91 deletions(-) diff --git a/theseus/utils/examples/motion_planning/misc.py b/theseus/utils/examples/motion_planning/misc.py index 39da4a7cc..5c74e4a54 100644 --- a/theseus/utils/examples/motion_planning/misc.py +++ b/theseus/utils/examples/motion_planning/misc.py @@ -181,7 +181,8 @@ def generate_trajectory_figs( map_data = map_tensor[map_idx].clone().cpu().numpy() if invert_map: map_data = 1 - map_data - map_data = np.tile(map_data, (3, 1, 1)).transpose((1, 2, 0)) + if map_data.ndim == 2: + map_data = np.tile(map_data, (3, 1, 1)).transpose((1, 2, 0)) path_ax.imshow(map_data) cell_size = sdf.cell_size.tensor patches = [] @@ -191,12 +192,13 @@ def generate_trajectory_figs( line = _create_line_from_trajectory(col, row, color=colors[t_idx]) path_ax.add_line(line) if t_idx == fig_idx_robot: # solution trajectory - radius = robot_radius / cell_size[map_idx][0] - patch_coll = _add_robot_to_trajectory(col, row, radius, alpha=0.25) + cs_idx = map_idx if cell_size.shape[0] > 1 else 0 + radius = robot_radius / cell_size[cs_idx][0] + patch_coll = _add_robot_to_trajectory(col, row, radius, alpha=0.10) path_ax.add_collection(patch_coll) patches.append(mpl.patches.Patch(color=colors[t_idx], label=labels[t_idx])) patches.append( - mpl.patches.Patch(color="magenta", label=f"radius = {robot_radius}") + mpl.patches.Patch(color="magenta", label=f"robot (radius={robot_radius})") ) path_ax.legend(handles=patches, fontsize=10) diff --git a/tutorials/04_motion_planning.ipynb b/tutorials/04_motion_planning.ipynb index 0d8dd7eed..96059c559 100644 --- a/tutorials/04_motion_planning.ipynb +++ b/tutorials/04_motion_planning.ipynb @@ -2,7 +2,6 @@ "cells": [ { "cell_type": "markdown", - "id": "a28f8efa", "metadata": {}, "source": [ "# Motion Planning Part 1: motion planning as nonlinear least squares optimization" @@ -10,7 +9,6 @@ }, { "cell_type": "markdown", - "id": "12f6539a", "metadata": {}, "source": [ "In this tutorial, we will learn how to implement the [GPMP2](https://journals.sagepub.com/doi/pdf/10.1177/0278364918790369) (Mukadam et al, 2018) motion planning algorithm, for a 2D robot in a planar environment.\n", @@ -24,7 +22,6 @@ { "cell_type": "code", "execution_count": 1, - "id": "79f641dc", "metadata": {}, "outputs": [], "source": [ @@ -55,7 +52,6 @@ }, { "cell_type": "markdown", - "id": "6694efe6", "metadata": {}, "source": [ "## 1. Loading and visualizing the trajectory data" @@ -63,7 +59,6 @@ }, { "cell_type": "markdown", - "id": "728c17aa", "metadata": {}, "source": [ "First, let's load some motion planning problems from a dataset of maps and trajectories generated using the code in [dgpmp2](https://github.com/mhmukadam/dgpmp2)." @@ -72,7 +67,6 @@ { "cell_type": "code", "execution_count": 2, - "id": "5e64eb2e", "metadata": {}, "outputs": [], "source": [ @@ -85,7 +79,6 @@ }, { "cell_type": "markdown", - "id": "4095fd09", "metadata": {}, "source": [ "The batch is a dictionary of strings to `torch.Tensor` containing the following keys:" @@ -94,7 +87,6 @@ { "cell_type": "code", "execution_count": 3, - "id": "e7e1f69b", "metadata": {}, "outputs": [ { @@ -117,25 +109,23 @@ }, { "cell_type": "markdown", - "id": "bc9faea7", "metadata": {}, "source": [ - "Let's plot the maps and trajectories loaded. `th.eb.SignedDistanceField2D` is a signed distance field object, which includes a function to convert *x,y*-coordinates to map cells that we use here for plotting. For completeness, we show the expert trajectories loaded, although we won't use them in this example (we will do so in Part 2 of this tutorial)." + "Let's plot the maps and trajectories loaded. `th.eb.SignedDistanceField2D` is a signed distance field object, which includes a function to convert *x,y*-coordinates to map cells that we use here for plotting. For completeness, we show the expert trajectories loaded, although we won't use them in this example (we will do so in Part 2 of this tutorial). We also illustrate the signed distance field for each map." ] }, { "cell_type": "code", "execution_count": 4, - "id": "28498013", "metadata": { "scrolled": false }, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, "metadata": {}, @@ -143,9 +133,9 @@ }, { "data": { - "image/png": "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\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAApQAAAECCAYAAABAGEf/AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/YYfK9AAAACXBIWXMAAAsTAAALEwEAmpwYAAC3M0lEQVR4nO29eZwdRb3+/64+M5kkk22ysAZI2CGBAIZIVAiLAi4EQfyhgrsErqLX5XoRQeWKgNfL9au4XcEFvSBixAVRcIPgBUWIbJIIsiTsS0L2feZ0/f6oru6q6uqzzJxz5syknterc7qrqquq+5x0P/N8lhJSSklAQEBAQEBAQEBAPxEN9gQCAgICAgICAgKGNgKhDAgICAgICAgIGBACoQwICAgICAgICBgQAqEMCAgICAgICAgYEAKhDAgICAgICAgIGBACoQwICAgICAgICBgQBo1QPv3005x22mmMHz+ecePGceqpp/LUU08N1nQCAgLaDOEZERAQEDB0IAYjD+WmTZuYNWsWXV1dfOELX0AIwYUXXsimTZt48MEH6e7ubvWUAgIC2gjhGREQEBAwtNAxGINeddVVPPHEEzzyyCPsvffeABx88MHss88+fPvb3+bjH//4YEwrICCgTRCeEQEBAQFDC4OiUB533HFs2bKFO++80yqfN28eALfffnurpxQQENBGCM+IgICAgKGFQVEolyxZwsknn5wrnzFjBgsXLqx6/uTJk5k2bVoTZhYQEACwfPlyVq5cOWjjD/QZMTYay+SOSQAIJIisTqT/yKw43cmXuedn1QXlovhvdGGM42/gTKdCO6uNe33pjsxVCLdfzzVUnENB++0C6a3I3UVvG5krS86VTpF0+nTa22UCVwaS0vhSpPUrto/NcaV5DfaczP70WDJpo89ZFa9kQ7yegACNQSGUq1atoqenJ1c+ceJEVq9e7T3nyiuv5MorrwSgu7ubxYsXN3WOAQHbM2bPnj2o4w/0GdEVjeCiHS4kEhKRbKVSti+EtOqEkIhIIgRpXRTFAEZd8QYYbTJSadWbZVG+zPeZ37fng2ceUcnow52jca2qoMLY5riRfz79gRDusUluW24ws2ERKQ+p0iQsFmn7tMzYR6o20leffMo4K8vXCeJkjDiO7HaxyJdJiMt2mdnGrCvHUa592WwbZ2OWjWsol4VV9sV1n2vmNxEwBDEohLI/WLBgAQsWLAAG/2UXEBDQfjCfEdNHTEtJoRCSKMIiXppMatIYlSqRTA9p85LNPJGsRiKLCWV2XcJD7HxkUo1RA5EUWGXWGAY5rmU+/UaTyOpAYSl9cbYvUlKYtBMyaSvTdsIkeAhESSKkTIklqOuL4yi594K4nJWhelNfT6RSsEgpiKLYIomqLs6OVc/qd4gkLquyKIrT+vwfKIKoFKfktBTFxEl/USTQnnBCJNcIiEhALNOy7VmoDvBjUAhlT0+PV2UoUiUCAgK2Lwz0GSEwyKNDJksJyfSpktXIpL8+GdOnWppqIn4S55I2U/FMr8dR8UxiaxFJQJhkt0CRNOdhksiiuZjt0sNoYOSvYt8tJpYm4VMFihBmdYoYCiFVnciTSxkn99YllgnR08QyJYhAVEpIIzZpVPOIIAZFMR3iHwGxSxqx2+D8luLkVCGJnWt2r1/3FQlJWYr0/0cZkZYFBLgYFEI5Y8YMlixZkitfunQpBx544CDMKCAgoJ0w4GeEJokFymQjyaRXtXRIWhGhrIlEesiWTVgzVdLqy1Elc2S2FiJZjdz2Fx7Skx0PvPt6oUiVWeCQrIRgauIIGApdQvgSsVDG2OqdUOTNJHUamSKp1D+ZkDc9B00c9RjWvYpAloXx3SnTtx7H7EsYfQkhlfopBCRtdZlLFLWSqu+NiDBUyoAAG4OS2Hz+/PncddddPPHEE2nZ8uXLufPOO5k/f/5gTCkgIKCN0IhnhOszWYpiQ9FTZK4UxalpPIpiolKyRQVbWi+TLasTup9StX5ktpXs9iJSW1QqZ/vGViqVnflkvpS+uYqSutZ0jnor+a5FWvXCM6+izb2Oqpt1D4ytIxu71VvUEdtz8d2XKCbqKCf3Ntk832lWnv0uEKjvw/iu1G8xU5lz5VFs/fFi1YtkLGH2mf0RYbYr/kMJT5ntbxwZfzhFep4tVpADhgYGJW3Qxo0bmTVrFqNGjUqTFn/mM59h/fr1PPjgg4wZM6bi+bNnzw5BOQEBTcRg/x8b6DNiz649uGzqp6yXYuYvGeeUych6cdemSrqmY/eFnZZZx7YamVMCnc/CssioK5hrzryty9N52X3oObll+fnY93pApu8KSmW18oFCFpht7YhpOwjHCs4xg21i51jmy1M/yTjrU5fFcZQL1snaRxUDdXRwjR2oYwfdFLVXfpMiNcdnZbpNPkCnHEfIGL6w+vM82busId9FwPDAoJi8u7u7ufXWW/nYxz7GO9/5TqSUHHfccXzlK1+p+qIICAgY/hjoM0KQkakin8l8ub3ZBFSbtf3m7aLgHdcs7pJIlyzmPg0bUo5YDYBIFpm8EXnCqduY9YVzqhPW+Z6+BuqnWXFsjGhts9wX6S2EVadIn+FvKYwI71gkfpSmf2XmO0mUmcC172RaJwXKd1JmvpZC5gJ17D8uZOpPmRFRFXSjA3R87bWZO3XVtMzh+neeD9DRvpRGUqSAAGAQo7x33313brjhhsEaPiAgoM0xoGeEzzeyyGcy8hPJaqqkWZ+2t7bKRLIaiSwiW656WQuZdOdjlufVUT+B9KmmA4JLctK+B951zVMoZeNmtjqZEk0hEv9JTQz1eZFJSJN7qAlhZPpRZv6VOmiHNKLb71epfCeVT6WeQ+ZrSUL8jObC9LU0vxthkUe3vbAIMRDJtEy3N9VaM0BHRMGHMiCPIZM2KCAgIKB2FJPJasqkSwKrkclKqmRRmp+0TLd3SaSHvLkkzj4/I5OaEHvJZMGc1HGeSHrHducx4Ghvf7+5cZsAkzCl80gDcNJWaYS3juDWQTsqSEVk7TCIHxLKEToiPOWNUt3zOI68pDJTJHWanoTcGX0LnbIIg/wh7GOtZBrkMReoQz7qW5el5FFgnKtGCj6U7YWO0r5Iualqu9cdP5NbbrmlefNoWs8BAQEBgwRt8s58I1UADhjkMDLM2m4AQxJgYdbpfXDN4LoPm+C56l+OdDp+kOk+NpEqJJRFqYAqEMn8nGwSmRvLINfZfMxJDJxYpGN5iGmzCaWZyDyFkbQ8m0dSJGUu7ySGOTw1hWu1Msn1KIAoSlTQpMzML6nGVR+p+TuOIPKkFELfFzvyOyrFqY+k7keZvz3fK+RM31II7+8uigRxQmx1JHjTv5eA+iA3MW7Eh6s2W7my+ipjA0EglAEBAcMSlvLmErtKpuqo4AXsqHuV2uTVP7N/e36VfCmtMpNwOSbPAZFJkb+mfJAOVrk7t36jQjqiVpAWIaSlzAFI/f0YScsNI3I6Zzc9kARDsbTVykITuD5XVFYqZdmYLxhtM3LnyyuZXmck0xRDuTqRpSsSielcSpEql+oPM+VLqVXK1ofyBlSCAEYMTtIeC4FQBgQEDD9o86+xAo6dMijzl/QpkzmS6Zxnb34i6VMki9TIHKE01Mf0kjwk0zqnlCmlRUQyVVEje56qUHoJpEXsGpyP0urDVc9aBDc4xwrKSaXJLOCGlLgVK5auWpkG7cRKeRQJWdOkMlUlwatURiWQcbaijpmjMk1CroNyiIiIk1VvdKBO/o8VYfVh56a0/SvtP8wifTuCG2XbQCAoyUAoAwICApoCTaYqBeAUEUZwVcX+kcmMIGLVm/3rfT1ntVOdQGYFHqLgnZPZv61qZvcLqx5ISWTFOfQHRQRyEIiKKMlMhjSDcpx2MgIR61bFimUltRKZEbRKSmUWYS61cTtTI1P1UhNgOxG7bmv5iDoBOmlfuH6V2bnuqjiZmhn4ZLshaoNvJBDKgICAYQhFjuolk1510lE0IVMB61ElfUQVtFpIWuf7VAfFCp5JbiuSyUpEsgKJNFXMojn0C0UKbAsVSkgUSjP4REd/a6UuUSaFkMhEbRQx2NHdsjZSmfpQQhxjkcqUDCYqoRA6eEct0xi7pm9sEpjOP0ceM1O7G8mtzeEu3O/e9KX0+p4GDCoCoQwICAhoAvSLtmiLnEhvH5GMSgUBOzWokq55u2hZRlOJLCJvwqsQeq45GU/PW63AktQZ11JIJD3+ob6gnCIS2F80K8dlfZPIm7w1yUwJpnSivfU55SgllqYZ3DWBx2VUuzhKSaQO1NHmbx1II5M8kun64WiC6on8TsmjvhT9R4FLHpOlGT2/t5Q0isRv0khDZPpSauIaorzbCwJBZ/ChDAgICGgOKqmTGtVXtqnfxO2qknnV0jZrWy/4Gkmkl2xZfdsmbpMgWn6SBpmsNA9XQbXqBgqXSBtlrYIbXAMkJFIl8JaxyFL84Jip9f2MbTN4Tq3Ua2KLzFytlUH1HWCtzW2tJY6ZBkjk0wAZpu9c+6QPfSw9SpYv4tv3DUQRlMu13tWAVkF5TwSFMiAgIKDxEHiDcCx10kgNVKsymaYLqpNI6j5dRdIlb1kdaRu1U9ncnR0UmLjTdEfSaodJqE0SaYxfLcm5PZn+EcHB9qEEmTJJK0jHWClH6KUU00YyTf+jmiambx14U5LEZeNySnFeqSzFaXuQ6jhJ+0OUjJMQOK1eKvVdT6vY9B1FMXGyDE72W/SZw21F0434zkhm9ttsqXocUBNa7CXiRSCUAQEBwxaFyccrpA3ylZnJzb31BWQyI4TkzquHSNp5ICsreV5/SbOPAjLpCwhy0woVjTtgtbKa+trot6VnyUVTuTOVSEAn+0lTPhFnK93oNin5jGQWeOMG3eBXKpMCqzxVKF0fRyEt03dRGiAX1m/MIY92gneZme+9Ny/5HYelF9sGAuhoA5P34M8gICAgoMEQeBREQ4FMFUdv2qDYKo8idU5UipOXeez0l6mAPhVUlLIylWg9TglcVIoT/80k0CepFyW16XHTcmeLEpXV3DQJjIy+olIyF7Nvcyztz5nMSbexxjPLS9LeogFuJbd/Zyu4/n5vVcczvruS9N6LSLcz7m36vevfWJT8PtLfnMy+D+MPEIzfmvnHgPJ5zZRx2/fXVrnd/KPmb9r+Y8j4f1L0f8T5Y8eqC6yhLREhqm614je/+Q1HHXUUY8aMYdy4ccyePZtbb7216nlBoQwICBh+EP6XYUXF0dveUBCtl6oOfKHA/C0tpa9oOUQ9tk+tzKcDMi7Pp9i5SmI6VjZHrypp+IVafeSUTez+G6QautfbyL6L4fRvBL+oFW4S9S5Jbi5xAnMwo7httTLzrcTyq0xT/ZAplWn0t3GuVhBxFMQiNdK6f44fpvnp9qXrKvVtmtDtMaEOfhLQZIg6CWMlfPvb3+bcc8/l3HPP5TOf+QxxHHP//fezaVP1pR0DoQwICBiW8BJJTyRzRTLpKEimOlRxDEclIjd2ZSJZkUR6XvC+4/6QSZeMFpFId8yGBNEU9d0KlAxCZZi5wc096RBHIVHakCQuR5VJpWP+JpJpSiGbDKqRNAFVkeLJ96mDcXSdJzeljxyCTS7R11F2SKbpX+n04VvzO6B9IBpAKJcvX85HP/pR/uu//ouPfvSjafkJJ5xQ0/mBUAa0Br1AH7AJ2AhsBbYA2yD9c18CpaS9+X9Dp7DQ7XS9sUxZem4J6ARGA2ON/fAM3O7gI3qpWdFQGt08k5rw+QJwVHty5UKY6XoMQmis/a3mZJxrEiiHRLrk0SRZFuEqIF8umRTmtRQRSWNOqbrqzDFFkU/nQKDJa1T9+hoGkxzp50kkVYyO9mGMRcbsddCNEZQjktVodJofXaeDbVJCKoQdqBMlSShjQ71Mg3IM4qoJo5OAXJFU5Utpl8lcxLcmiq4a6VMytX+lm0JIk0z1/yA8UNsJyody4N/J9773PaIo4pxzzunX+YFQBtSGONkkadQhZRRRjFDEsC8p00RxK7AGRSLXJ+UafclnR9K2TEb6+rC9e0vGmBqm7ajT2e805tqdbDsAuwITgK6arzpgCMNSIA3V0Swz21qEzlUwHWXSG3zjCSyxg2lsMukqksIkVL4XfdLWusYC03BhSqBqZNJUJF3ze6E66Z1CXSgkkc02fRt/lOo0QUBi1k6InJGTUWCqjrZaaZnAdXJxafShl2HUgTxSJPddXbLEKCP5Do2VdXwJyxEFaYC0CmkRUNfkjZW6yNuHR6UsB4Wy/SAhquF7iavU33HHHey///78+Mc/5uKLL+bJJ59k2rRpfOxjH+NDH/pQ1f4DodzeIVGELkYRwM1JmVYS+5LyDaiHW2+ylclI2xYU6etN2upf7SYUedOks5SM1YlNGjegiN7mZOsB1iXtRqBI6dhkHAGMAlYnZTLZ70nG2Yz6VYukzzXACuAF4H5gErATsC8wHkJY2vCFpThGmZnZCrgxgyVM9dKJki5SJrXCWWTids3brj+mmmeeRLoE0sodmV5gMdlK+66gTGr1VJTiYkXSOsaaS7U51AUfWW22OglkC1MrZMqdyMr1ijhJfapYOmolsUDGUfpHhzTIIWCnCDLJph7PNH3HWZllyiZbRSft30l2bprPTeTTBWWJzn1KpV560Vzf2/W/DGgPqL8NqhPKF1esYPbs2enxggULWLBgQXr83HPP8dxzz/HJT36SSy+9lL322ouFCxdy7rnn0tfXx7/+679W7D8QyuGOMpmSuBlF5DagSJhWETeQKYa63QgyVbAP9YstkamMXcl5JG03J/syabceGIkilVuBMSiSqEmlJCOkXcBLqF/jCOBZFNnbCqxFEccVSX8RihxOQJFFkZS/TKZUjkzmvhKlTEbJPCLgmaR8KTAVOADYmczUHjAsIBxzn0X2MEiVV4X0qI9px7X7S2qCmp6XC+4xyJk7lu4bg0Qa88i90AuVSj+ZxFNuKZKpid5DJHUbz5gDIhrm9TU9KMeEsXa3VuW0T2UsEt/HpB6ZKpY+tRIpLaXSXFZRJsszImUuSEf7U5prdOtUQq6vo4apNlrJzpNrcBV5daUOySxQOM3+3bKw7GI7QtTkQzllyhQWL15cWB/HMevXr+fqq6/m1FNPBeDYY49l+fLlXHbZZXzkIx9J/tDxIxDK4QLto7iZzLy8FkW6+sj8F7eiSJsmkFop7EraShSZWwOJY4YiZxGKQHajyNczKLWvDDwPTEzG3pb024UirREwDkUSJyb9rwSmkCmgUTIvrXqWk7mWyRTSrcm5WiXdnFxjlMxxPcpX0hxrLPBcMue+pG5Ecl+6gUeAp1Cm8BnJZ1AshwcckleUSgWw23giurWp21YyKyuTkUO+dMohIEum7qigur2PSFpErR7/RZdMFiiWGNdtm7pt9TSnJDZQqfIGHTX7/6M2ZVvm7qSMxFSNTBVLbQovIpVpDkkUqZTS9oXMVqvBCtKR+jcmC4JeXJXSURJzzROVUi3/aJQbgT2+MvOPME1itflcQ6mWRTQ0YDBQqw9lb5X6SZMm8eijj/K6173OKj/++OO55ZZbeP7559lll10Kzw+EcqjBDG5Z52xaJdRKpFbdtGLYRabmjcAOcHmJjHA9gSKLI1BkcSzql2Kas7uAVUkfE1DEbUxS/kJyvkzmuzYZd31yfjdKcexIyl9Amaz7UCR0YnJOR9LfyqR+U9LnmOQaxpEpkeOT+s0oYqkDf7Yl7TtQRLMnmYMO1BFJ+cvANOCgpN+AIQ/X1O3bzCAcixSabUo+gpknk1muQVsZ9KqSDgkF0rnmAnEcElePWVjPM7IUR23yTvrTZNck2caKOr7AnKKI8wHB8E+15t9MlDBWxUnG1ONrk7YqTMigNnWreUopEGUj8KaEUhbLkfr7txSn0d+QrJRDlAbpYJJNQIhMpcxM3RhmcP2bIDVfW+3I+iI132ffay6BOZnZu1qCdF8fAe2DRqQNmjFjBnfddVfxGFWSkAZC2a6QZJHQ61BEaz2KxGniuBVFwmKyYJRVKJKmSWQHilyNQ5G7Z1E+hBJ4EUWwIhQx25j0241SI3tRRG1z0u+UpM+1KHOxJm0jUcRsc3LcnbQfkcxpRTLmRhTpG4Md3a19OLUfZ5xc96hkPluSsl6yaPDNKKIbJ/sTyPwnS8n4Y5I+Xkg+S8b5T6KI6xpgcnJ/e5O5HpZcX1Arhzx8Cp5wVTYy8llreiCvMtlPMmkpkqYaaaUZyhM4fy7KCvfAUSbTMUyi6prXozzptevz4/UbzSSrlYZNryExfesI5jj7/lOTsyZyRr7HlAD6lMoK62crOdKvLioFU9q+lHWYpnW5jxS6/ydc1dOt8wXiWL+VgLZAI76OU045he9+97v89re/5bTTTkvLb7nlFqZOncpOO+1U8fxAKNsBZRSR2ohS2zSBXEOmSGqzcIQicGtQ315EZtJ+DkWOysn+FDJiuj5pqwNaymRkcUPSdjNKqds1qV+LImWSLHJbz2Wzsa99I/VcxyfX0ontw9lLRhZJ+tPBOpuTdh3Jvu5vU9LPFrJI8E1Ju01Jf/p8fS91X9p0bpLYp1FEskRGaHUgkkQR0XuSazqQQCqHKJSyGONdDcdSKE11sMDM7QTx1KJMZimE4opEMmfWdkzxeZKVXZ91vVWUPHN1HtP8bSmTpnk7sudpEchmKIgOYW6tD6XhI2kE40hj7UGhTTOJGkkMIlE3RSnOK5VaUUxTA2Vleo1tU6VM7dKJL6UZoJMmODcDeUT14JwswMivLlYq0yZzHdiT/nFVkKMyYHAhgA458JfVG97wBo455hjOPvtsVq5cyZ577snChQv53e9+x/e///2q5wdC2WrotDobUGrYyygSs4FMndNBJOPIiJQOYBmF8vsbg/oVrSDza+xAkUCJInXrUWRJ+zeuQQWgbE3G1GZf7fuox+gli9zWkdc6CKcXpTyuIlNFtU+kJnBjyQJ4RpGSxHXldTze9TiP9D7Cw6Me5gXxApvEJjaP34yIBR0dHZRGlhAIou4oyaWWXGuk5iv1Q3CcREqp1pkYqZqJbsGYeAxT4insMnYX5m6by8x4JlFXpObVS6ZgbkyO9TwnoBTbcck9WJLU7UcglUMU5otUHUuLOFrllpLoMUdXPQcvAatKJg0i6fYLNpG0xq830lo4/eSIYxUyaRBJr4LYIDXRJc4pGk0wnbW89bhSR3RLHYyjG+jPTI2spFSm6YHKmuwZ/pSm2ukE6Kjnm09t1DE6Nplz1WutNGYkUyZuSiYxlJnrknn91XLKBLQ1GkHxhRD84he/4Pzzz+dzn/scq1evZv/99+faa6/lHe94R9XzA6FsJmIyhexFFPF6nkwx1ApejCJpW8kCTCagyGJvsr+RLEK6K2m7OqnbhvKB3BGlEK5AEUeRnKfT65TJIrs7UERqSzK2ViC1r2MZRQbXJ/0k5XFHzIaODaxdt5b1pfVsYAMbxAbWl9ezTqxjfdd61vStYXX3al4WL/Ni9CIvTHiBp6KnWNm9soE3twaMgh7Zw+u3vJ53bnknrx3xWjo2dCgyrK9PR6hr0/lYFHEeATyQfO7V2mkHNAamMgkFKqRBmnKmbk+7XDJyw0cz8000FMsayaSXSBpqZKVE52Z5Eax5R/a4KZnMBex4iGQ1JbERbzVznGah5PRvqHmJA6JSH3UwTtJGEKe+lTJRHrVSSULKBKTkzgrSccvcAB29ZKIT8W36SGrCWGRGV/3gNXVDkRqZBe6YCqWZIkhxZJFeh1rru7UqckAxGrn04rhx4/jGN77BN77xjbrPDYSyUYhRhGwNSnV8HkUidbCMzr8okrbaZKt9EHXexV4U0XkZRXp6kr5GohTFZ5KyUWRm5U7U/+2NSf8lMnOwJkxlFBHdZOwnPpO9Xb08u/lZnuEZnhvxHM9te47neZ6X5Eu8GL3ICrGCVX2rWDVyFWtZiyxLpYCSjDsx2e8gC2gZmb9Fo+Qo9oz3ZN++fdlf7s9ucje6+7oZWRqJjCXluExfZx8ylsQi+3NZxhJR0o7wpOkRRFkgIpUuQfZJ5EjJus3rWNG1gsejx/m/0v/xdMfT/GjUj/jRqB+xS7wL5249l3O6zqFna4+692bk+zYUgdYBTSOBB5Pr6yn85gPaFDkymCOTeZIJ1BTRbUZzW2Zut+90ze+4LiIprGOHRPaTzFkkMiWPKNN3BVXSTDNkzhForHKor6/FPpQkq8oQC0U003RBMlUsBZHa12ZlndanJJHlJPekzJRLImmbvvV1mWUuKdTqY/IHjZAuASQfMW5EaJvpgtJ0Qvp7NNIiibTMGNpDUL1lWnUNaDu0gyEtEMr+ohdFAl9GkbznUSqhNq1qYifIHr4bsXMvrkHlSVyBIoimP2IfSjXUq7psMc7bhCI/o8nI6kiyxN96H9U+3hLzLM/yeOfjPN77OMvkMpZ1LmO5WM6TPMlz8XPIjuThrckuyXhmfsbUAj2G8fF4xoqxjBVj6d7WzdjOsYyVYxm7ZSwTRk2gZ1sPPb097DRqJ3beuDO7yl3ZuWNnRK/ISLW+RzovpTa/a2JdIjO1TyBLHTQyuZcjjHO1/+UGMpO2hMfHPM51267jfyf8L/8s/ZNPT/w0l8hLOH/r+Xxi8ycYOXJkFsQkyVwO9D1fAfwNOJrwv2UIwYrs9pFGlxw6G057n8nZJHgmufMmKq9CJl3TdhGRtE3d5vXWRr5M8poqk5HTfwGZtMzRRaSvEQTTIPatgIw1kU0K9DMgJZWG2doglSkB1ERRZCmFhJR507cDZfaWOV9KK8Amue/pyjru+b6ySiZzz/kmOQ1m76EJ9SodfEoZXpG1QKLI33Mo/8WnUJHDa8kSO+lgGU3CdO7GPrKVYfSqMXr1l04UIZVJ/Usof8j1ZBHWK5N2o1CmWu3jt5EsYGaz2l9bXss/ev/BI6VHeFg8zCPyER6NH+Wx0mNsEVtsgqgJHErx21XuylQ5lV2jXdkl3oWdyzuz44gd2bF3R6aUpzBp9CQmbprI+PJ4SuNK6tpLyRxWJ/PW5nIdUb2aLBJbkqmqukwHy6xL7tWY5HonGPdnJFnaIe1jOiopm2Ccq/NTamW0DxgNe63fiwvjC7mg7wJ+J3/Hf0/8b34/4vdcOPFCvhd/jx+t/xGv7H2lurdbk3uiiWUJFeT0ODCdYPoeUsivgmMpkwZZqsnUne5na39HUUa00roalElhBOyoT8OUbsypyPwN1JeL0oQms5HMjaXM3o5Kme5jk0jXBN/oaO96fUT7A23mLqEUPKmLtVIoEsUP0nW7DaUyNX/rYJy0jZGnUWRm7pwvpVYatdqp1UmRpRDSwTmZqRsrUMdSsw2CmZq4zdtaREALgnJcBdQ1gwe0F9rhKwmEshJWAncBf0DlZlyLUq06UGRvLIok6qX+NqAIjVYPdQod7S+pyV9P0rYnaauJ0EYytWxtMoZOl9NNmuh73ch1LFm3hIfih1hSWsKSziUsjZfyXOm5TGkzH/ACdpA7sJfYi73kXuwV78X0aDrT4mnsEe3BrnJXOmVnZgbRaYj0SjnmUokiKdfXo4mixmgysqrTCXUafer+tH+nJqH6PurgIn0fYjIC2un03WFsgiy5+TajPAm4ERsEJ3ACJ7x0Ard23spHJn2EJR1LmDd2Hj/Y+ANO5/Q08Cc1gUOWSukelF/qaAKGCKqRSd9L0XyhZoXkyszFIjJFs3ZlErBVSVMlLFAtgYEnFneUVQxSnAuyccmkOQdNvs32jYI7VtMgs+AcwwQsIqFUy9R8TaZWSkOpdJVAIfNlukqrj1RREQtm6lM5fQRRR3vLsnFstC0ig5UUzIChgUb5UA4EgVD6sB64GbgTpRqCInQ6cGYjSn17CaWqjUERDW2qhUx11GlwOpJzxpElFtcrxXQm/XYmZQkpK/eWeazzMR7oe4AHyw/y4NgHebD0IE+Wn1TqnB4nIWojGcl+5f04IDqA/cR+7LdtP/bt2Jd92Idx0sjWPQqlDmpipknT6OTa9f66pM3YZO4dybWuIossX5+U6XW8J5P5b04k8x3VCqIOEJIowqzJt0j2p6DI9liyVEOTknumo73XkuXE7CJTFUck17Yh6VOvIR4n93mUKjt227Hc99J9fHjsh/n22G/z9jFvZ8raKRwrj82USokizuOMa14CHE7AUEBCwnRgDmQr1OiUPkXqpD7HTBEUJWl33AThlt+kqXi6yqShlppEzT3PInF6HCcQSF2Eh/jWc2+ijNyaZu40lZCjWALZcoxm6qBm+Ds2y0fTBz2Oyu6d7OtgHEOtJErW7c4UWbU0Y6I4J0E6WqXM/CWldxUd1YfMWJyhCLophNI7ICRZTkrjEmokmy5pzKmRWh2tQCIrkd6AwYMWrgcbgVC6WAX8BPgn6n/OWLIE43pNa62wbSXLFbkFRZDKZGbc0WSmYZ3DURMVrfJtA0bB1o1beajzIe4t3ct94j7um3gfD4oH2TRqk5qXQRy76OKA8gHMjGcys2smB246kBnMYI/uPShtKanxdFJx7auoTcZ6XJ3nsSuZuw4G0n6eeu7a7CyTz5FJfVdStyYpG0G23nacnLtDcj8Filw+j1Jly8n92QGlAneT5bbUqqZWKkclY/cY39EEMhVT56iMyfJqjk/O2ZJ8F7pfff9L0NnXybfWfIuejh6+OOqLvGfMe3hww4NMYIL6zkcn53eSKZ8PoczeOggpoG0hIL8Kjhl4kpLMjCQVqze2opiSRMtkjk1QXTN3nWTSSyRz6qQxx3qIl3D6TcgkxnFKai0VE2seOdO0M6cBoRWR3mAF4ah9DFXSUCs14ZZmKiGp/CkTNVAImS6hqAN0hPQHthDjVRe9+R195UlZJTLYX7O02Vclkjn4elhABkGpDb6RQChNrAd+hkp+rUmgNgHr70qTSq0sdiXnmUm6O4zzNGnbTJpfcmu0lb+X/87isYtZHC3mb6P+xkPdD9En9ALbGXaTuzFr2yxmdc7iYHEwB718EPvsuA8dvR2qT53nsUxGOjvICKJM5jc+GX8Nivzp1EOaMGqMTq5NE2NJ5s8pUCRrMpmiqFMVSWAXspREuybjdpMlU9+BTC3UK+dMMs7XLgCadOo/u7aRrT8uk/51u61kPqs6OImkfAxZJLwgW1Fng+pXjBJ8/uXPc+uUW7m7624u7L6Qr6/7euYz20dGREeo7477gGMJT9O2R4GJ21UlXXKFQSwFFhFUdU5/uswNsvGZuSuQycyvMlOnvERSK5cD8TF0g3CcABzLzO0jk6Y62QwlMe3fOW40NEmKpU0sjWjslFRKmQXeaP9HHSwjSNP+EElwA3B04I2Z1xJSwm6qlvp63TKfmbzIJxKjrfbHNOv7Y8q23D0Mv8qA9oB6VQ7+S6mhhPKnP/0p1113HYsXL+all15i991359RTT+XTn/40Y8eOBWD58uVMnz7de/7q1auZMGFCI6dUH/6KUtG0chiT+i2iuZ4mbppUdiTtN5Gtla2JZC/EMubh+GHuHnM3d3fezd2j7ubBzgfpFYltXCflloID+g7g0PhQDpWHcmjvoRzSdwiTeiYpNW88ipgJsofdSDITu1ZFxyblL6LIk/YtjMhM1mUUQdqBLIH5jmSBMJOS88cm7Z9PykooRVGTQL2ko87jqNVF/auaQObHuCOZD6lW/0aTkfBuspfTCDJztUj2tdqqCaWOpO9GkUfIksPrAKiSUa5N99qc3a3m3xl38t3N3+WQEYfwrY5vsaBvAQf3Hqz6GEsWXb86+Q6eQgVn7UpAP9DKZ4QQpIE5QBoEY5nBjTWrbfN3XlW0CaP6jIqCWwyi6JJJ00zuUyVNIpkjkSaZo58qlKm4unPWJDFJJWSRSe0qUDLm4JK/RsC8xqba8TKSqA8REsqRukYdWKkFBR084/pTJqbvVEkUUhFPIzjHIoPJPbXM1Ea0t3TaCYljDnfVyvyV6XyU2bFtFnd/N0Xk1CzzLcEY0D5ohaBfDQ0llJdffjm77747l156KVOnTuW+++7joosu4rbbbuPPf/6ztbD4+eefz/z5863z9QtlULABeIxs5RRtotYkRqtjmkhqn0DI0gNtgZdGvcRfR/+Vu0bfxV/H/5V7Rt3DutI6ayghBQdsO4BX8Apmb5nNK8qv4JDoEMbEY2xz8qZknFFkRHaUMe44FNEZTZaQWxPcMWQPwqlkK+7shCKOel+bpDuSPlwCuDE5X/tI7pLcmxLKj1H7JuqvtkRGXjXhnkAWnd2JInMTknnr5OImzL/iZdKf+RzVEdj6ga//nO8jSyK/HOXjqr8/TQw7yHxFY3UPZ8qZfHDdB/na+K/xkckf4bYNtyFGiCwt0QRjHuuBe5P7E/T9utGyZ4QwXpqmCml+GgqYq1im3ViqJTnCaJ6fEc+MHKb9mKTRPK8GMmklNa8hKKdm87d7rkNW03ukx42cemEQvka+zdJxGtyvdyxDC9QpgRLSaCqVQtqm75wKmUCIJGq77FRE0mvO9vo/esqKzktN03qulc5xCGKujxq4YgjUaV8MOx/KX/3qV0yZMiU9njdvHhMnTuTd7343ixYt4thjj03r9txzT4444ohGDj8wPEFGtDR5k9h5CU3TN1CmzENjH+LPY/7Mn8f/mb9M/AuPj3k81/Vu23ZjTt8c5qyfw+EczivEKxi3aVyWBFybz/XKNNoHErJgE1CkaBJZQu5uMlO7ToKuczHqJRbXogiRzm2pA2O6k+udkIydpB4C4xoFWaT5GLK8kJIsoTpkvozC2Nc+jjpyW5POEfY9bAr2BV6FItsPoiL1nyJTRvU9HY26jxvgP8b+Bz+SP+L20u3cwA2cFp+mAoH096+TnfegUkY9jUolFFAXWvWMEOAkGreDb4rM37mAGIck2jktcVIKZaQzC3hxkqL7zN+Giuklkk4gEDgkU6OfbxRLndRBOKXYJpNJgFK2ZKNRN4CxiyclW0Mo9R+qaXJzEoEgUSo1URMyZ/o2/zAgEspfUq99HTnBOTIrt6K9rVRBwlY53ftRxedS/5FhJjivhiKSGTC0IGD4+VCaLwqNww9XYbHPPvtsI4dqLCTwCBnp0kTS/AQ2R5u5e+zd/F/3/3HHuDv4y9i/sK7TVh9H941mzsY5vHLjKzli6xG8su+V7Lx1Z0XMtNm8G0XMtG+e9mcclxxr/0sdMT0yqXuB7Bszcz6OR6lyE8lIm1ZR90zajSAzd2uCNIUsSnoKimhqBdEkkNovUZNDnfcRmk8O+wudQ/JY4BDgOuBhMrO8NqXHwBTooYeL113MB8d/kH8b82+8ccMbGdUxKiP9Y8mCiUqoZRl3JKQRqhMtfUb0k0zmlMwCNTBn6hb5MdO2hrKZUyZ13y6ZNMv09bhEshEKoSaqvv/LOZ9Jh0xaEd/9n4J3TnpM/LEqjeg+VSVjmamVrlLpQyTtAB2j45xPZK1w/C8z/0e/P2Qt6K+/pBmUEzA0INrgZdx0o93tt98OwAEHHGCVn3/++Zxzzjl0d3czb948LrnkEg466KBmT8ePmCxAZXNSljqbw1qxljft8yb+Ovqv9Ea91ql7bN6DV615Fa9e8WrmvjSXg7cdTMe4jiwf4xiynI76UytkOkClh8yM3Z2024AyL68lMx/vQhbRPJksj+MWYLek3yRqPDWdb0vaarI4FkU8tSKqk5Dr1D7DEROBM4FrUf6gm1FE0QzoieGsvrP41phv8ffS3/nyiC9zQecFqm4rWVL6nqTPVaiE54P0kx1OaM4zIk8Ytb+kiOIc6RO6zix31Eldn5JH89g0RftUSNOv0lAm9XwqkkmTjIJF4nLm7X4SANesnqqTmjimyiu2L2WzAmcimWbraQbS2YokwESI5I9tkSqS6h2QqIypMknO5G0G56QvjuSPFyRpUnIzWCY7ufpcrXQ/Ig23qflaTSKqf8v1kMygWrY/mvhfpS40lVA+++yzfPazn+W1r30ts2fPBqCrq4uzzz6b448/nilTpvDwww9z6aWX8qpXvYq7774791LRuPLKK7nyyisBWLFiRWMnKo1P4WwRjOsdxxMjnqBP9DFr4yyOXH8kr3n5Nbxm/WvYde2u6pvUZujxZGYTyHwH9frZXWRm1LFkORt3JMtXqSO3N6GIaXdSVyILlFmf7AvjswtFlMYl85iQnN+R1Gl/w+0R44HXAr9G3TutUPaQBhh1jOjgK5u+wnFjj+OykZfx3jXvZZetu6j7uJEsSj5GuRT8E0XkJ7T4WoYRmvWMWL1tc5Y2qEZV0heEk8IgdcLZN9u4JNBdkUYYuS29Zu6idbXBjsbW4/lU0/5Am7MNFTU71nX6Gt1P2XAFMX07mpHkjYYEEGnENjq4Jklkno6v80+aRFIoEpqSyQQ1kS+hxkp9GN0+RH0KZy0EMTWpG8f1ICiV7Y9SG/i2CimbE/+/YcMGjj76aJ577jnuvvtupk6dWtj26aefZsaMGcyfP59rrrmmat+zZ89m8eLFjZtsDCwEnkWpfRtQBELnntwE93bey/RN0+nZ3JMpmqBIiXbAXo3ycRydbDowZhR2/kYdWNNJtsygTtqtzd/a5KzT1XST5YIcgSKRPSjyOIlM2dRrfwfk0Qf8DpWgvAOlMpbIEs0naZZO5VR+PuLnvGfre/h+5/dV3RbU/ZZkSddHAQcARzDsiHrD/4950MxnxIyeHfnJsW8jKsl+k0lXhYxKMenyiuayjiW95KIigzoJukkohVOGLnOVSUO1NBOOq0LbbK7amYS2X19DhtRXUirFVh+nfpW6zEMmTQLYSDRTekndmpQqKcpCkcpyolKWo2Q/KdPLLKZlkVIgyxFSt5UCGQtkX0ntl4Uie0kbqcviCKQgTvqI+0pJnS5XbXSZlCDjKGkviGNh7Kt2cV/yGWd96Dp9rkzOlVJQLpeQsXF+HKm6WO9n5TJW7WN9fiz4t2X/zWNbnmrSlxNQD6aIPTmZS6u2u/8Vlzf1ud4UhXLz5s2cdNJJPPHEE9x+++0VXxQAu+22G695zWu45557mjGd6oiAPVDmUEG2bJ/hi3hY32HZOtw6RZBWFHUgjz5Hk0NB5oMXoUif9o8cn9RvRfkv6vQ5fSgTtSafY1F+kBOS8nFkfo3DjMQ0HR3AHFRATZksT6f2ad0CrIcvdX2Jmzpv4uquqzmXc3nFqldk+UZ7yX4fo4BlwH6EZOd1otnPCAEpmXTTBdVMJM21th1TN2CXVTF158hkrcpkRGoad/0v1UUZamUjoE216bz1OGQqpUkmS7qt0a6BkKlC2th+0+jtvsSkjbDN2obpOhfVLWRWr4uiRCXU4oLjD+kiFwzjHjuqZTtAaGW1TgU1oDVoBzrQcELZ29vLaaedxuLFi/n9739fl1+kqCVvQbOwL3A/WSJvM7BFK1Q6jUyn0Ub7160lW4axhCJ++kGoVUW9r1ee6XDKx6GIyWSyIJku8ml1hhFWrlzJbbfdRhw35ukphOCoo45ip5128jeYBMxEfdfjUUE2muhvAybC3l1785H4I/w3/80ntn2C26LbECOFqu9CvTQ2kkWvLwXmkrk5BFRES54R2u9RK3l1qJKpv6TpF2mYt62k5qY52zSBC/s8b/S4qUwaxNBSJk2zttlPLjinia/4ArIqzXkkhE82SaGUDf6/JcBKXp5DhDJ/6y+tCkFs2LxqMF8HBPgw7Hwo4zjmjDPO4NZbb+Wmm26qOeXHU089xR133MGb3/zmRk6nPvQA01DkwIxm1sEznVjLHwJZlPY21HNnNIoY6nW99X5HUq9N0qNQxHEiKhfkFBS56XL63w7w8MMPc8YZZ9Db21u9cQ2Ioojf/OY3xYRSALOAJ7GXmVyXfJaATXDhugv5/uTvc/uI27lx5I2c3Hey+m7GkQU66YCeJ1AqZT6AOcBB654RiZnaDMDxkEmt/kUuebRUSVO1NMmghzyZ5NTow8w1aQa6FCVFpyRz6qaVtgd7XzT6bWL6UKbHZAQ39alEEb5mKYmoJQxlp/psBERi6hb1/g1brwrsUTIrNheeoJ2AgBogGIZLL37oQx9i4cKFXHDBBXR3d3PXXXeldVOnTmXq1Kl84hOfII5j5s6dy5QpU3jkkUe47LLLiKKICy64oJHTqQ8COAxlDu1FkUEzHyXGfmwcg1IpR6NWnhmHIh7aJ0+Txx1R5HEnFBnxJfRuY9x999185zvfaVh/XV1dnH/++Q3rry6MAQ5G5accj/pfoNfrTlZFmjB5Ap/r+Bz/Gv8r/17+d96w7Q10dnaq9cq3kQVw6aTvS4AjCSplFbTyGVHkL2n5OJqqpEkCMUzeLvEDo21GFE11UrexgmgcU7ewyKVj5q5EJtP2xjhJ/4MGAVL/Id7Ibt2/MwdKKtvMjBwQ0CgMPp1sMKG8+eabAbjkkku45JJLrLrPfe5zXHTRRcyYMYNvfetbXH311WzYsIFJkyZx7LHH8rnPfY799tuvkdOpHzugIoFvQQXYaB87TSK1f40gW2t6Leou7oQyUU9K9ndD+T5OQamfOsp6iOLxxx/nqquualh/Y8aM4eyzz25Yf3VjH5T/47NkKaNGoQKkRgMC/mXLv/D10tf5Z+mffLfzu5zTeU7m8zoKpXCuR/0WVgDPoHxxAwrRsmeEqUQ6ymRVMllBlcxFu5rHBnl0o60tImr5JrrkkkwFrEYm9bFvLk1GziqbqJVxAy0sIsZecSYyxo3qfH3GhpIbSGXAMEQ70IuGEsrly5dXbfO+972P973vfY0ctrGYDrwZ+ANq+T7t36iXNNyKUqjWogjFROBQ4HBgb5QSOY6wLF+7owv1va1AKcWdqO9TR28DnaKTS7mUt/JWLipdxJnbzmTMmDHq97AZ5Xs5OtnfgkojNJWgUlZAq54RgiQIp5oyqQN2rFV1kj6MFWry+SbJyGFkE02v76ShTpoR3cIgj2kAjksmfetqmwRTX3Cj0V/FM/IQzjoh3KULDcgOUf/1RgLRN4gKbkBAE9HMZAj1INAeH3YG3gY8h1q3+VFUiplelFo5ARWEMRs4EEUgA4kYetgJ5Tf7TzJ/sB1R3+Vq9fmW6C28Ur6Sv4q/8uXOL/PZbZ9VaaV0Dsv1qD8qRqLUzaBStglqVCYxzMsJrGAccM7VjRzztamEOql8THXSB1/uSEuZrEQm3WjvCuP0G/19U9WrImqkuSArN5M19i9i2RzCHRDQRmgHChIIZRE6UcRgdxSB2Ea25vZ42uPbCxgYOlABOi+g/lDYiDKxrUWpjp0gOgT/Kf+To+XRXB5fzgf5IJPFZOUeMRKVQkqSLX35COoPkiHkHztsUaBMRpFNLk1lMmfeNomkafI2iKQay09C06l4fCddddI0dVtmbk0mtXppEkmdUsgkfS00fRciEv2LzJbUFCwj6+pfKFIZEDBMIYDBTJKj0Q4qaXtDkPlG7ogiDYFMDh9MRP3hoNM/6cT0OniqE+b1zuNETmS9WM+l8lKlTOpUUhEqyGck6nfxLMqMHjC4qKBM1komRSnOk8lIlevocYx2VjAOZGOYCqiRs9IK2DGJpqFKFi6DmJjMrbyQpTgzjzdj6wdkJJAdNWz9VDNlVHkLCNheENWwtWIOAQHbLwQwA6U6j0EpjltRSuU6lOlbwqWxWoXgm9E3eXbLs0qRfBGlXD+XtNN5Rf+RlAcMKkxTtGnmrkomtaIpSP0sXfN2jkgafavBPWbsIuXQiOrO+jNIpTBInRWgQ0YkdRqfCLWSTTO2fiqfUtSwDeCPdNnh3wICthcIlJ5RbWs2AqEMCJiAivoGFWizA9lSl5OBiXDohEN5K29lK1u5ZEsSnbwTmf/saBSpXI8ymT/XwvkHeJGqjGYAjrDJZJTkexRRojomgTxRSRO82FYlo1j1WZKpv2RUitWyjHppRiMYyArGAWulHHcZRcvUnRznVq3R+5rgdTSJPFba+gEZFRO/hiiJCSmVJYK/ZMB2CVHD1mwEQhkQACq6vwelTkpU0I2O4o6A1fAf2/6DSEZcVbqKZROWKRN5Lyp4oBtFLLXK+QTK5zZgUCDA8Gs0fBsts7ZuXMFf0lUlnUAfK1+k4zfpn1RRnXOez9St25nrZqc+nU7bZm/9QDPN0jJJrq62xvQZEDCUEInqW9Pn0PwhAgKGAMYCB6BM1pNQZDBGKY4vAGU4oPsA3tH5Dvro49Ktl8JLKCWyD3gZtRY8ZBHfz7b2EgJMKLIXGebtSCuIhplbK5NWovJUhcyrklqRFDlF0mijVU9HDdXIpQry+U4awT+pqVv7TJrKZGrijpElieyUqVLXzK2/bw5ZgrhTEnfKoCQGBDQQQaEMCGgn7IEK0tmMUh93QSmUU1CR2+PgM6XPEMmIq3uvZlnfsizvqF4daSvKt1Ki0k0FlXJw4KTrMVMD5Va+cZTJiqpkURS4SSJLmZk8pzzW44dY6HOZkVE9X6kT0bVCnRyAShkQENB4CKAkqm/NRiCUAQEaXcC+ZInO1yebQAXZrIR9V+/LGfIM+kQfl3ZfqtRImdT3oI67yFIJrW79ZQQouEE4rpnaa+YuxTWRybStQSQ1iTQDe0zy5cs36SWc2tydlpEF3XhM41KQKZa1eucPZNNyRyCVAQFtg2DyDghoN+yJUhxHoyK/x6FI4jaUCXwKXDjhQiIiftD7A55a+5RKZr6JLLG5RJHSDlTEd4VVPwKaB8vcnJi502CbhPTlzNwWYVQELRdwU0QkNYm0TOKZgpmD+/R1H/imj6RZZqQKSpXJ5FN2SGX6bubWIa0x6/pOYoj6BFGfUP9PAgICBgyBrGlrNkJyhSGEcrnMyy+/TLncHIbS2dnJpEmTEO2QIXWwMAKlUt5Dtq53hCKMOwAC9u3bl9M5neu4jv/a9F98redrKihHkCVHf57Ml/IllMk8oOVwV73R+1kCcqygl9y63pBTM1NzunOOfWyPXzlYR/rVy1qgzdyooJSWrMEWq7FE3I/nRBPfaf2aT0DAcECLFMhqCIRyCOHll1/mDW94A88//3z1xv3AQQcdxM9//nNGjRrVlP6HDHYFHkcRQ4EKvOlN9nuB1fDpjk9z3Yjr+E7nd7hg9AXsJHZSic7HoJTNZKUd1qKCc3YiBCG0EgLL/CzM4zRIx/aHNJXJQtO4Jo16hRrD59JadtEMqsEmtP0ikGagjhv5DZZiGI+geaQyhmgb6v9GHWOIGEQTc7NWWvs7IGC4Q/lQDr7kHwjlEEK5XOaFF17gueeak+Rwp512QsrB/1EOOkai1mj/Pcovchzqf4qO5p4MM0fO5M0b3swvtv2Cr278KpdtuSyJuAVWoszjk1Gm8meAvZK+AloL30PWIHTCIoQO0fMok3gIo0Umi4ikVkRb4XfYxFVi0mUR6/jjqNnvuVqWagwIGO5oB8Ni8KEMCPBhB5SquBEVuR2hVMdRpGbw88R5AHxzyzdZy1pFPCOUUhmjlmBci1Iq/0nwGWshBKbyiB2YY/hN5sik6TNpKpZuwE3qN5nUG8se5v0tsy1NSt7PBOH1oOGpgvoBEUtEX21b//oH0VewBaIZsB0hXdmrwtZsBEIZEODDCGBvlFo5BUUG16NMfZuBlXDEqiM4WhzNOrGOb3V/SxHHGKVmTkZFe8fABpSyuaXVF7GdwyCTbnBOlkLING97AnnMwBvD1JxTJTVhjYxgnFKckUdzSUQzSrzZimWta2lX2PrlnBVLZYaW9W21kkCR9F/TFoe/5AKGN4SAUiSrbs1GIJQBAUXYA+UTWUYpkzuhkp6PSLapcN5YpVJesfkKtq3fptb/7kSRznUof8pRwCrgqVZfwPaN4qAaD0l0Ugy5Zu5ayKSV71KTSIc8pkqnViubbA+W2rdyAFu/zed1qJOpSlkH+ROxrGlTN6Kf1xAQMETQDmmDgg9lQEARRqCWZNxAFrXdh/KLHAsIOEGewExm8pB8iOs2Xse7x7w7a7MFRS63oNYLXwbsjiKYAc2FNvP4TN0eEphbRlEH4LhkMpKViWRCInPBOa30ofRAdgiVYqgOCEn/TNFxXS6WdSOYsgMC8hBN/uO0FgRCGVATJk2axBFHHNGw/kaPHs3o0aNZs2ZNw/psCnYFHkOZvTvJ1ujeqj7FWsEnOj/Be6P3cnnX5byr+10IhCKRU1DphNai/qclEeKBULYQBQ/ZnKnbUC5TZdLswySdUJ1MFhHJQXKc12SyVrWxbtIWA5HyXWw6ggk7ICCHdgjKCYQyoCYcd9xxzJs3r6F9dnZ2Ni1ivWHoRkVo/xllvp6A8o3sJY34fvuIt/Pp1Z/mofJD3Lr1Vo7rPU4F7uilGLtQEd4rUSrlTgRnkxYgv542OWXR5zeZmr+1Wdowc2dKpWJcwlhf21Q49fgpgawlH2WTISOQNT7x+5Pip1mBMCkJbrLyGRAwVKF9KAcbgVAG1IRSqUSp1M9QzwqYOnUq5513XsOStQsh2HPPPRvSV4pdUb6T68kivrWvZCd00cUHOz7IZ7Z9hq+s/QrHdRyn6nQgzhhUtHgXypfyRUKi81bC8Z0UrmpoNjWCcNIy02cycs73kMkckXRSCek5DSqKmFm909LpOBEqsXoTCKUASAJsGtZnf+ZZr89Ane1lvf0HBKSQRIP9TCEQyoBBxrRp07j44osHexqV0Y0igNtQ6uJ6FEEcSRr1ffams/lC1xe4qXQTj054lH1K+yjyOQqlaq5J2nahVs4Jic6bD5M8enwnVbkdiOMzdbsmcR1kU5FMGn6WaV9gr9E9WBAQd/hfPnUviajbxopUNhqapIreBncco+auP731xvW0aBWeQCoD+gNBe/hQtsPjLSCgvSGA/VEvnj7Un2G7oHJVjgI6YcrOUzij6wwAvrH5G4pMSpSpuwP1P20KagnHZ1FR4AFNRHUl0orU9qUIcoJ1tAk8p0wma3gLnRbIyklpb2ldLVsbvCBqQiygLNQfTA3eRCwQTehblIVaqlEm84+TTylsIilFnkx6SJ9029RJQF0imeuvDaDnGNa+aE+IqPrWbARCGRBQC7pRJLITFVgjUebsTUldBOeOPBeA72/5PhvWbFAvr1WopRtXoYjpSBTZfLLVF7CdwgyOcdTJfNvkw/KpzM6FPAG1/CVNVVI4W1RQXmkD20zeyNsSC+/Wb2hC1vBN9V003/5uul9N/AbE3TUZjJ3jSqc02hzuzD8ondsZBJSiuOrWbARCGRBQCyJUyh+BUibHoEiiRBHETXDo6kN5lXwV61jHtWOvVUSzKzlHt38eFazzHErtDGgKtIlbpwrKyv1JzC3fSdfUbZnElTppEUszYXmUlYlScmwpj0nbzri2TffRSEgKk4D3N1+jqNBnfzdiEuVTQG+DN91vrMeyy2zVklSplCZplHkl0assFiicum2ujxq+g0wt7B9xzCmiVfqpt31Aa6FM3tW3ZiMQyoCAWrELKjhnG0qpnATsiDJrl4Cx8KGxHwLgG1u/gYylUjG7URHiXSiFchOKXG5o9QVsp3CCcdJij++k2cZN/2Oaui2V0lEmRUSmSCambwQZOTSTmtejVg70NsS1b/1CLKAcNWaLRUpSMzWx8ZvQJm/XX9I1fbvX6aLADG4SL5mQULtRhfuZnuce10/uTHN1IIPDESoop9rWH5x44okIIbjwwgurtg2EMiCgVpRQKuVYVAR3H9mSjAIYBW/pegtTxBT+Xv47d626K1FZUEE5L6OUytEoUvoYYQWPZqLCA9TrwO7mmDTa+kzdaQCOSybTNbvjjEia63hH2Esx1ro14pYUrXvtbP2CFI0je2WREcty8zZFYEU2ZmxehzB8LB2SGQulLEqRKYymatgARc/tx9dvLX30x7xuEeE29OcMyCPNrVthqxfXXXcdDzzwQM3tA6EMCKgHk1Em67Eo0/e6ZIuBLdC1oYv3xu8F4Nulb6u2ZVRU+GZUkvMXUarlSwSVsslIzTy+SG43GCcpy/lOpv6MrmqJ5RspjHW6U1XSTHruBuV0yPq3fj6x+21y7g+06di3meQmqrCVjPvcSGhS5s6pLDKFVZNKU72Uibk7PXb6rOQ/6SOXvjJTKa2FBHr6MPuuR7lMj3Pm90AmhwKasZb36tWr+djHPsaXv/zlms8JhDIgoB6MQa3xvRllwu5G5amciIr4lrBgzAIAri9fz+rS6nQVEXZJzt+anL8JFeAT0FT4/jL3Rn5XIjAec7mvPCOY2GQyDczBJkz92fqBWte99q6D3R/4Amys+4R9TW6Eu76Pjdg0zOAZTbzM4Bx9LIWtSmrfSUOdTPvzKXmpemm0TY5NwiZlpnKa8CqCDYgCbwQ5DASzfdFohfK8885j5syZvP3tb6/5nJCHMiCgXuwGPEqWj3ICyoS9ERgDe0V78dptr+UPvX/gR+t+xIdKH1J+lmWUmbwrOWcF8BSKkDY+Z/x2jxxpdNRIa5lFw9ztBuP4fCe96mTqH0lGJnV5SiqzubTkHjQ/sLMY5YR8mPfACF5KuUmzZQ39fUupiF0kIJYZcXSJpKlMmqZurWBqYqgJoUFQU8IlMyXSR8J8aYaUwmg2EpYfpvS00X6Z+eCgyuOlZFbvu2OTJ49xIJNtDd8fyf3FHXfcwQ9/+MO6zN3Q4P/KixYtQgiR2yZMmGC1W716NR/4wAeYPHky3d3dvPa1r+Xvf/97I6cSENA8jAHGoYjhJFTgzfOoF9E2YDN8IP4AAN/p+44ii+tRauTzKGVyI0rRXI0K0NlO0PJnhEEeGw7dt0sSTWXSJZNajWuk8lYJsWzI1u/bFxmfhjuAFBgm7gaqkb4tcRWQRaqxe3GWquiYujWKFEOP4giOGmmQzkLC2Ujy5vhhDrRvN9goYPAhRHVzdymSrFixgtmzZ6fblVdemetr27ZtnH322fzbv/0b++23X13zaIpCecUVV3D44Ydng3Rkw0gpOemkk1i+fDlf+9rX6Onp4bLLLuOYY47h/vvvZ+rUqc2YUkBA4xAB+wGLUCbvEkp51P6S6+HN4s1MFBO5X97PvSPu5bCOw5SZeyLK/3Jlct5Oyf6U1l/GYKKlzwgf+XJN2NqfMudLKQ3iKLNgHNPkLQzykvpeOp9G+p+UTDUZjVyqsF9IyaRNsKVAkTxI1NwmzyMmDYaSsUAgEzcUrUYmczDvl+k3aSiUspyRQmn6W2IokppwGZ8mCglZBf/JXPtUVXRVxnxZvSjqN9eu7p4Dmola/mieMnkKixcvrtjmS1/6Eps3b+aCCy6oew5NIZQHHHAARxxxhLfuxhtv5M477+TWW2/lmGOOAWDu3LlMnz6dL33pS1xxxRXNmNKwwLhx4/jMZz7D+vXrm9L/jjvuSGdnZ1P6HnaYkmxrUQpjktxc+0R2TejizA1ncsWWK/j+pu8rQjkKRSYj1P+8icn5LwB7oQjpdoLBfEZYpiGRfxB7TUeVosJ9Zab6ZRKpyGzTn9lXgO62t/FdW4jJs4m4gAw5Zn6LTAuQHU26FyYismTmyRSt4SKZmed9SP0pSTuwfCFN8zhY7SAzS7tqZGbCts3a+hxVj0U0fWl/fP6UftUz36YRBDSgPdAIK8xTTz3FJZdcwne+8x22bt3K1q1b07qtW7eyZs0axo4dS6nk99FquQ/ljTfeyC677JK+KADGjx/PSSedxC9/+ctAKCugu7ubs88+e7CnUTOklPT29lIuN08q6erqIooGIbZsBIoQbkMRxTLKJ3Ib6Wo47xXv5Qqu4EfbfsTl8nK6RJcyj8fJ+TskbdegSOXurb+MdkRTnxHm+7IfD2ArVRBkOSfN6HHTzBtlbVMy2UxVLm4ymXTGwiBqFlxi4l6vvgctUihlJBWpjKQaVCYqpXm3hKTq3TNVRNd30iSazmeqSqZtKwxRi89lQbtCc3sVxdGXTL0WUhrQHhA0hlA+8cQTbNmyhTPPPDNXd/nll3P55Zdz3333ccghh3jPbwqhPOOMM1i5ciUTJkzghBNO4Itf/CK7767elkuWLGHmzJm5c2bMmMEPf/hDNmzYwJgxY5oxrYBBwPnnn8+iRYua0vfIkSP53ve+V7efR8MwHRVU040iiBtQ5BJgGxyy7RBmiVk8IB/gpq6beMvItyjiqUnnSyhT+TS2O0LZimeEuzJEVaf1giCeugJpTD9Ko9/Mf6+JqpxLzHxK4gCRLs+o+44Lbkule5XcU6k/O708qGFIc2tG5MmvJpH6s5paacI1b+tIboM4muqkdWpskMt0H5ucygIyaJrMZZ4kytg4r8qNLfLfdBOyByWzzSFkQ5ZWPOSQQ7jtttty5ccccwxnnnkm73//+9l7770Lz28ooRw/fjyf+MQnmDdvHuPGjeO+++7j0ksvZe7cudx3333ssMMOrFq1imnTpuXOnThxIqCc8X0viyuvvDJ1IF2xYkUjp91wbNq0iUceeYQ4bk6I5YQJE9hzzz0RrVhLaYB44oknuPfee5vS96hRo9i8eXNT+q4JPaiVcp5GqYzdKKKoUwKNg3dvezcf3/hxfrDtB7xFvEW9XCahAnq2olbcWYd62W1NyocxWvWMeHnz1lx9w1FEmsxyU500PwXIJtqHzOjuAa3R7YP5WIsUgUlHqKbyedRI2cR70Ywod1+EtmXeNn0npdFeZqQzbav7lJ5+rUEH/h0WrbCTW83HbBOSmg8ZiAYo/RMmTODoo4/21u2xxx6FdRoN/W986KGHcuihh6bH8+bN46ijjmLOnDlcccUVfOELX+h33wsWLGDBApXfb/bs2QOeazPx+OOP87rXvY5NmzY1pf83velNXH/99U3pO6AORMDOKL/JTagX7VoUQRyl6t/R8Q4+ySe5edvNrCyvZPLoyVmSc4lKGQRqFZ2XUCmJhjFa9Yw4ZCdFPs0UQU2HR+G0j7NP2QGyiT6zMoZoG3agSaOgX1wxqQlZIlVaHqKEMEn/EoUVIBucOkvogJtWwfSdjDM1EUdZdNXJTG20TeeuGT0lnWYAjuGHWRioo30xnTJr6gVluUsMBLMt0SiT90DRdB/Kww47jH333Zd77rkHgJ6eHlavXp1rt2rVqrR+qCOOYzZv3tw09cx0lA0YZOjo7G5UOqEnyKK+y7Djth15Ha/jFm5hYedC/qX0L+olvwGlTq5C/S+cDCxj2BNKH7bHZ4SG1H6WjYS5HrdITMtNgEBkpNIkGkImuR770Wkk1D0ZyLxiVLqjdoJj/rbUQYs0ZuQRhyjm+6wwXIEpu9YyV7WMpU1KQ07KNoNoLqGUNTrPtiyaQZtnZ8yYwZIlS3L1S5cuZffddw/+k3VCSkkcxw3fAmrEGNQKOH1kuSV3QRHNkUAXnNmtHJyv6btGkcc+1HreO5KZvLehSOaWFs+/jbBdPiOiNK6jYVsOAvVHTiM3AVKvSy6y62hIwnYxsG2ghLTRKPQ3LPKd9AbgeHwzsf0blcpojOcqmLp9rgyrr5rmDrQw/CugBpSiuOrWbDRdoVy8eDGPPPIIp512GgDz58/n+9//Prfffjvz5s0DYN26dfzqV7/iHe94R7OnM+ywZcsWPvGJT7Bs2bKG9XnKKaekpsOAKhAoAvkcKp9kL8qcvR6l0IyCN8s3M3rjaP7c92eeXPske4zaQxHK3qTNpKSfVUkf21kq1vCMANkx8JezV5lLyFWjA19EWaUnSqOn3TEHaGqXkeiX3CH62kyZLEAltdAMxvGvlJP5ZtbiF1nTmD4SW2v+zIBBh6D+pRWbgYYSyjPOOIPp06dz2GGHMWHCBO677z4uu+wydt11Vz7ykY8A6mUxd+5czjzzTP7rv/4rTVospeTf//3fGzmd7QLlcpk77rijoSsNHXDAAQ3ra7vAONT/pNGoQJ1nySK+t0B3XzcncRLXcz3Xx9fz7/G/K19LHfG9Byn55HGUX+UwfW6HZ0QFaGEpqu/Lr2XNbVlqrHInEndJyjSEQOYQ9ZMARwJRHvwXaz1wSaNdWUwQ0yapsonVNlMu80TTVS3t9nZd7DGBV0t9FNB6tAOhbKhxYObMmdx44428973v5YQTTuArX/kKp556Kn/961+ZPHmyGjCKuOmmm3jd617HBz/4QU455RRKpRK33XYbu+22HTqQBQx9jEapitpltguVAmgyyuwt4e1dbwfgOq5TZZ2o/307oUzgTyfHG41+hiHCM6Iy4k6hyF89Wx3qZt19e7ZWQnZAPKL61m5m7oGg7mAcPGTQo1z6o7rJlVnzqKEsoA0gICrFVbdmo6EK5fnnn8/5559ftd3EiRP53ve+x/e+971GDh8QMHjYCaVOrkP5QY4gSx/UDSeKExm3bRz3l+/n0Y2Pso/YR7UfmZw/hixKfA2KpA5DhGdEbaiVIPUrLU6dCqiFwQp2KZry4IsygwbTV9JXp6O7LQJZbXUeg7DaZVk/rmIZ0B4YdgplQMB2i3EocjgKtQLOelQaIAH0QtfWLk4WJwOwcPPCjDy+ADyPUiy7UabD5bQ23UlAW0FGSpmrtvX36S2j9lcmXcQd0rsN9rwGBY4J2wzGMdXJXMBORb/N+hXKwacvARrah7La1mwEQhkQ0AiMQJm9N6DUxVGoHJUTUESzDG8VbwVgYWmhUiRHov4HllCq5pMoUqlVzoDtG6K55E5GAtlRwzYQRTNgUFAUZGMTzKTcQzxtNdLx8wwKZftB0BaEsuVreQcEDFvsAoxHqZObUWRyG0qJHAHHjz6ecauU2fux3sfYu7y3UiZ7UKRSpw0qJ+cMU7N3QG2QenlCDxqy+k2NgS/tQB2KrrcZK+EMRxQRwEqJyn3nhPyT7YtSLflmm8wpg0IZENAojEEpjF0ohXIdypydqJBdcRdvKr0JgJ+v/rlaalGbvterNoxH+V0+QzB7BwAgS33p1gwGVdGs3iYQZf8W7K71oSiS2/WfrJy3UhBSFbcXBO2hUAZCGRDQKHSggnPWoszdo1AkU6/TvQ5O3XoqAD/r+FlWtw1YQaZmjkTlpAwLIgW0AEoJdczqbfRmEHH1LaDx8KmRwdTdphAgIll1azba6LEREDAMsBuKKK5BEcRJwESUaXsknDj5REYykrviu3iWZ9U5MYqIjkMRym3Jtr7Vkw/YbiGywJe2IpN9NW6BVDYUvryTcfChbGOEoJyAgOGHMShiqFfC2YBSH8vAKOgudXP8iOMBuGnNTal/JSJp00FGSF8kmPQCEHGUbm3F9pqJWCVPr2sr15bkPaBBCLe6rRBFcdWt6XNo+ggBAdsTOlCK5DrUCjidKGIpSZdknL95PgC/5JfKLN4HrAaeQpm5RXLe8yilMmD7RmqTNh7Xw/xlLmKJ6KtzC2QyYDtFu/hQtpHbdUDAMMF04FFUcE2MSifUh1Ije+FNY9+E2CT4o/wj67vWMzYaq6K7tbL5LCo4p5z00TUYFxEw2FCBJ9ufaVE0ehnHgIDhDhESmwcEDE+MQ6UCilCq5FaU6btX1e04ekeO6DiCbWzjDxv+oNRMAYxFmb9HoCK+V6OCcwK2O2y3gSixbMwWELBdIfhQBgQMT3SiFMZtqNyUvWTEcCuwCd7Up9IH/XrLr1V5nLR5LmkzNil7GqVuBmw3EHHtwSjDCUWpgfq7hbRbAdsTht1a3gEBLl7/+tez6667NqXvzs5OJk+e3JS+B4w9UGbvLtT/st1RxHIdsBneVHoTF5Qv4NelXxOPjYlEpEzcm1F/5j2HIpWbUObwMYNxEQGtRr9EhEa8JyREfS0wr8cAAkoyPRblfl53jbDU3CBeBgxDiDYxeQdCGdA0CCFYsGDBYE9jcNCDCs7ZSOYfuQ31Qp0IB3EQU1dP5Zn4Ge7bdh+vKL9CvewmowJ1NqII6CZU+qBAKLcLiL5BfCm0cugYBAJZkohemmsri1HX5iPeOv2N/mzECkRVUGn97GaO179zGziRgKaiHQhlMHkHBDQDZlLziWT+kB2ol2mf4PW8HoCbV92sSKNM2q1GqZUTyVbNGfxnRUATIeIGmHj7O3aROb2RFrIYkEIpkQbBE2Wh9svN20RZqKUbJYowxsmnS7R8xKtaG/e4TkJaC2Fzc0I2GyHH5FCEDGmDAgKGNXZGKY1jUARzR1TwzTrgRXj9VkUobxl5i6obgzKRr0X5Ua5MjlcT/CiHOwYxGKXpgT++flKCByIWTd0UgSQlk5aQo8t983NgrXsdV14Huwj9OSc9tx9EL5DD7QfK7F15azaCyTsgoFnYCRWcswb18uxGmbFHqvLjOI6OVR38pfwXVpdX0yN7FJGciDKRrydbtnEjMKH1lxDQZMTqb4zBgOiTrRk7Fup3HEsgQgiJRGblrUoTpMlkLKCcKJRaqUxVS1LVUZpKZhWu7hJFKd2+qveR77T+FWnsNbdra28dVyG8gaC2J4IP5TDG+PHjmT9/Plu3Nmcx5jlz5jSl34AGozvZtqFI4UsoE/YEVT0uHserolfxp/hP3PbCbZxaPlWplFtQ/zMF6vjl5NwJLZ5/QNMgYkVYmpX+J41y9tigRDwIC+7EQCQAmZi+1ctPtjASOyWTsoq522cOL2prHA/YN1KKAfksBrK3fSMQymGKPfbYgx/96EdNHUO0Qr8OGBhKKIXyBWAHFKksoUjlZvV5fOl4/jTiT/yu+3ecOvZUVV9GLbs4Kjm/Kzneh8GTs4YopBQIZPLZZMRJ9LLMiJMlS2n/wUh9Rs1cBSk2Pl3yGMvW5bFMg11A3QCRMDs1qZa+BLUSqefjUydNhU4Tz1gkCqPIFLykLkfiavHDhJxJPacU1tBvf9RL6ziuTIQDQR1KkIgWpAWqhuBD2QQIIZq+BQwBCFS6oJEolXEkypzdlWw7wPGT1Lrev41/q8ikRJnFxwJTkvMkyvwdlmGsC3WrPa65r96AjKI2sU1aRCxUMEoTA1GUuTU/vbrXx/asl103koAcypHaLycmZ70vm7yZ4+ljk0xq87ShXkrTt1KbrqVxjvkV+8zZUpVbATWalBqR5dKnhtZA5Mw+rGO3vkbU0l63iQeftwS4SEzeg53YPCiUQxxCCLq7uxkzpnF5Zbq6wlp/DcM4MrP3RhQx7CNNA3RY+TB66GF5vJwnnnmCPct7quUXJ6GIQSfqf+nq5Nzw1fQbMhaIUn0PVRkL9SAu1dlHLCDK2glpcI7khdwCzRRp5ns0xm4ppMgChtI/hmViAqelPpTq0yGTsUkwEzJpqJM+pGTRCtQR9qfZfiCpe0wlUeb9HGtxG8irkf2ejtVPQPsgmLwDBoxRo0ZxzTXXNNRfc+LEiQ3ra7uHViNLKJL4JOrNvhHYBKXNJY4ZcQw/6/gZfxz9R/bs3lORyDIquXkXStXcgjJ7t2ke9yEDaZBCKUBKpEPtqpJGrVjFIIVUFoMI9ZaOE5NupEmUSN0UBFK92LVdqNlJ/gSWeb2RfpMiiZxOo6hNVMr3WDaOW71Eoml+TwNysMikRSRjg8BpNdElm5rk+Uzg0jjPREJG9dcvjXYp4XPa1HON5njSnZMer1IXUhDLyn0AtCikK6AGCAKhDGgAoihir732GuxpBBShA9gVRQbXogihRKUE6gTGwHF9x/GzrT/jDx1/4KwRZ6nzYjIT+Qtk5u+ApkLKRJH0miELHtg5X8nk2FQpEwIqImkoSk1+IZckIhbISCbkr8H91/P+0iRHk1pNtlvpdKWvvwKZtCK7cchkEUG0xkiIYM59gjzh1HNx4CVvNZT1x+xdtY8WJHoPaARkS/JMVkMglAEBzcZklNl7PUqh2YBSLCeo6uO2HAdbYdHWRciNEtEnVP0uKM4xIjlvFUqpHNnqCxji0MEyJqSwEhJmQTuesoQgKvO3Ih1Cq38meRQJgTRVyr6knQ5I0YQVmmPqTQisNNRJYaqijUSaoFxkKXlMP0P9aZG35Fxt+m7lUiymT6TeLyc3RgpkWaT7xMmx4ztp+UGaqqLpL2mQR9ePEjJF0iqLEzXSUgbttmZ/ZiCNX4XMX34ReSwOyqneR0CbQIBog4iYQCgDApqNbtRLpgcV4b0VpU5uVNu+vfuy84ideV48zz9K/+DAcQcqErkVpWpqn8r1qJyWOw3CNQxBKAIIiCTKO1GghCZdCRHImbd9HCdNe+OWC2X2jgwiFcnMpBsZJuE0F2MTlbmyIrNKCdWqoGy876S+RyaZ9Jm/MdqZAS1auS23mKCYUdqmEmkF6hjE1zR1O/1Iiyj7SZkqJEcEwV+my2sJzKkVeQLaGDUzoL3QDibvNuC0AQHDHCNRKuU2lGI1FRWUswGIQHQLjomOAeC27ttU+xJKnRyZtH0u2V/T6skPP+TNjuQCKmScqU6W2S9VrLDIiWsq9Qd+kEU1l5u0GeOluSjjZowj8mTSVCctf0Oye1KOyCK+RWs3d+zke/ORyZyp2/jufQpj9p1nRNFr4k5/g7X+WnV7DwH0mM996mV/4J5Xi09lwOBBCBBRXHVrNoJCGRDQbEQoVfE5MkK4EUUyS0AMx2w4hh9t+xG3b7ydD234kEodJFHks1O1YSvKn3Jfwp+CdUBKofwHjXsmY6FMRIb/o/af1Lkr07qUKEmkUOep82ViMo0T8zeJkhVlYd06r6ggIwDNCkaJpB4oVUaFurDmjAce4myUpUTaIWWmKtnqPJSQ+bDq+Zn7EmRiBpeagMbZfmre1m0N4mil8pFGG9NM7tyL7HyDqBn9WSZzs42+hNhP8Gr1ubQIqE9FDeRxyKAdFMpAKAMCWoFxKJK4MyrSuzcp3whshqM4Ckpwu7gdKSVijFCm7m3AMyhzeScqMGcrKul5QGVIoe6lfh9LkREs4x0pY5EEYxskUiPxvzQjv7UvZdpOkw5t+o5RPptJv4Bh7sZvOm8EfOZ2Xd4smGQSbIJpmo7NoBcDoln3wjdVk0gac8r2ySuS5rU551i+k+b5vrGNtrKoXQXiVnOgjqdfK3rcII/96SvkoGxXtCbPZDUEQhkQ0AqMR/lSbkKRy06yyO9O2Efsw45yR14UL/JI9yPsP2L/VGxiVNJ+FSraeyOBUNYDKXRITFakyYIwgnFigYxIIqNRCl9kElGh1MZE2ZTlSK1OoYNepECWQZRQymUkjTQ5ND8QRaugscwUU13RjJdNSsZwlL7kU5vCtboXkwXB6C70/Yma+DJ0iZFDIsEgkqaZO7kOGQtkbJrJtV9lpsJK4zwreMYsc/qvli7ITYRuKYiOWds2defVR93W/Cy8XdJOVxTn+rfTCgW0BwKhDAjYXjCSLLCmD6U8loDdUMRlm+CoDUexkIXcsekO9t+0v1IiBSraOzGNsxlFLEM+yqpwg27SF2lBII7KR1mHSmmavmORRnmrwJ+EkKRpcrADUZrxPtYqqB7bHLOZKYospQ+vqdtKFu5Dq4JzUuKbfJhEuIBMmgE81qo4FlFMigyTdWGqILK2ZnR3oW+mMV+rqA61sEjhrOZzGczdQwNCQFTnog3NQPDECghoFSaiXgzjUb6UEqVYvgyshdfwGgD+T/yfeqF1AzuizOPPka7Wwgs014w5DGAqLF5B0PV/00TBDM5xVSLpJxvpueUo3WQ5STujA0CMuqYEyZhqoBX8Y4zZjCAXw88Qfb3pnAxSqff1vS0M8mnGPO37JMsJkUvnHiHLUXaczF2WI2QcOcpi8rspR3lTt9suzohaSkhrII/S/W1WVCPzSqdVF9skUSuf3sjy3DxqKwtoE9SydmqT0VBCefTRRxeuPX3iiScCsHz58sI2a9asaeR0AgLaC5NRQtE2lC/lKNSSitsACUf2HgnA//F/ysQ9AkUmy6hIb4m9fOMQROueEc5L2zBNpi99bCIAzgtaGsTAMGFKTdpkRkpyKWQSwpUSS03uXHLZiC0ljsIhtpqs0XgCm+s3SsmVHTEt7CjqlNQlJC7W97SJW/KdWaQxjjLS6JDitL35PcbZvE0yWYup2/WdLDRPG3W2eTtPAnUwjgtr9Z1cncgdu2WxMb7ZRkqR+k/qawloLwy7tby/+c1vsm7dOqvsL3/5Cx//+MeZP3++VX7++efnysaOHdvI6QQEtBfGo5KZP4v6U24riliW1f7BGw9mjBzDMrGM5+Pn2XnTzqoNRrtOlLq5GUU4hxgG4xmhljtUpmwRoyK1dRS2sNuJUt6XMl05J/G5JD1OzMuaHOgcl7FwTN0g08hu0fgExOVkTpEeLxkrVZ1Ec3wUTVXLSaNkBeGYBBODxOu2LYZl5gbMwBtfRLalTGrEGdnLKY6WOl58nVZ6IVPB9M3Z+IPH7KtIydSfRYpmf3wrc3Oqq3VAczEMg3IOPPDAXNlVV13FiBEjeNvb3maV77nnnhxxxBGNHD4goL0xArU29ziUmXsb6mW2CShDqaPEERzBH+Qf+Ev8F06NT1Vm7/FJuxXAHqjVclYm5UMMLX1GJC/O5HWZFcssyTkCzOAcWQZKyTKFQpHIlApGiUIVqfxAIvFZlEmaIBFJpFSmpfTZLkQmGyWFskzjCZ4AITXZtccDmu+jaBDGlEgapMxKyWMQqEGBE+1tzqWQSPoUx7JN8lK1NRaZqTzdJ0tHpJVRh4xKZz6mWmmN4yGKqt5PGNMxXbdhDwl1+3HbhoCcNoWgLZZebKoP5aZNm1i4cCEnnXQSEydObOZQAQHtjxIqSnsriljuQLZyDupz7ta5APy598/KrN2LigTfRLbSTpyUDQM0+xnhe0mb5a4vpVnmqk6psmURDpEP4DDIRbY0YVZnmb8btbkkzh2vmZuRKLwimXSVSR041MqtbM5T5MhboSrpkEkzMMfyX3SIsjfIpYIimPeNzJM73zmV0gXZpnJ/mTWmgbhgbOseBLQHIll9a/YUmtn5z3/+c9avX8+73/3uXN35559PR0cH48ePZ/78+fz9739v5lQCAtoDO5D5Rq5FqZU7oEzZZXgVrwLgrpF3wVgU8dyM8p3cmmwjUEE6zVgLusVo5jMil54lUYRyvpQFQRVpO+0zZypsMlGefIEc5cjx0UvUrNzWQB9Kx2dTNrL/Kpvrs+gGIKnyTJl0fVAHbYuj7DtM71+U+LwayqTjM5n6NOrzTcVS/zYMku36TrqR3YWpgpzAnux8+w8eq2+THOv/B7rvKgS2qK5aWcDgQzAMfShd/PCHP2SHHXbg9a9/fVrW1dXF2WefzfHHH8+UKVN4+OGHufTSS3nVq17F3XffzQEHHODt68orr+TKK68EYMWKFc2cdkBA8zAO9TKdBCxDqZYbUU+EMTCHOVCGv8m/0bu2l864U5m9e5LzNyZ9bECRy9Etv4KGolnPiJc3bUHnL09fgj5fSvCbvpMyEWP7U5KkD0rM3DJCESchlWldKL9KldIlSSkkhWqrzc4NfLCr1XpEmrIo86eUWY7HBo+ZwiQXOb/EIqIu8ooug0BUnPma6YByJm4wVs9x/kjx+FLapmT/HzZ55Ryj3qNqJnM1yWRF1dKjROq+ivwqdf5JNxG6lCogx7qmQCzbC0IStUCBrD4N2Zx4reeee47ddtuNf/3Xf+XLX/5yxbZPP/00M2bMYP78+VxzzTVV+549ezaLFy9u1FQDAlqHXuDXqKTmEUqlXIt6IfUCm2D/CfvzSMcj3LPxHmZ3zlakUweQ7Jy06wFORJnQm4BW/B9r5jNi1g6TuPn01xNFElGK1V/oUYyIlK+jSEhXFMWKDJaSv+KjxAdSqPMQGPvqHCEUU9Vts7LsfEB9v8m+8D3sG0HyzP71O16PNQjLGmISsxrIZEreWgnX3OtGRnv8JdM2qVptk8mc32TSJjZVy0TNjE0ze9JfbJjf46QfWdZkLrL6M8tkHBEn/pi6LE7HiYyybL5mu7hs7Bvt4jiibLaLMcrU/udXfp7lvctb+90FeHHwlMn8+pT5Vdudcu+DTX2uN02hvOaaa4jj2GvKcrHbbrvxmte8hnvuuadZ0wkIaA90otTJF1H+kBJFClehfCbHw5zSHB7hEe7pvofZzFbnbUUpletRZvBtSR9NIpStQNOfEVIgpVQBOJAF4oBabjtRKRXBiFMHIBEl/CFWCqMkMeNGEkGsEqCXYqVWCYGQEpkQS2RGKIWxxKMsi8Y7GGkCC0hrXF3fIqJmRjU7fpIWkcRQ+pyVZ1oGXwS2q1YWEMm0TpNJbY5OSJl5Xs4/MzWNU9XU7fpOmsplrizO1E3p9Ju7dF8fSXmcm5NR56wXrtsHtBnaIMq7aT6UP/jBD5g1axazZs2q+RzRqgdgQMBgogflB9mBetG+QJZrsgPmbJsDwN1b71ak8cWkXSfqBRejCOXLLZ95Q9GqZ0QuOTnYL2+zrUmC0n3bDOoG8Oj+TGXK8hfUZY0OMHGIixtson0Bm72Z0c3uPExV0tqc4JeWzdP83uP8d+r3lTSIpkPYLALm+ubq31NKxAxS55q6jd+f2a/9uzT68/x2TdjEEfsadJsC4unOxS4rbB4wmEgsJtW2ZqMpCuXixYtZunRpVTOWxlNPPcUdd9zBm9/85mZMJyCgvTAp+YxRauMYlFr5IlCGOSPmQBfc3XG3Wl2nK2m/OvncRbXj5eSzxJBDs58RUic2jyOIYkUcNBlNfCkFCQlIZURl2pZoRS1K/uqP80plOcpUSe2raKqVkJmezbdwI/0nTQVUCq95vUkeTRkcgmKVmebtpNzyT9RkvdzU2NDcPMEhSy7ZMhTDtNwkkj5F0YzyTsZLCV1ikrbIpqsoxpHR3qdEuiRR5AiyT3n0pRLy7bttY0+fsXlOTPb/JmDQIZANSRv005/+lOuuu47Fixfz0ksvsfvuu3Pqqafy6U9/uqYcwE0hlD/84Q/p6OjgjDPOyNV94hOfII5j5s6dy5QpU3jkkUe47LLLiKKICy64oBnTCQhoL4xHkcStqCTlY1C5JScAAmb1zaJTdvKP6B9sWLeBMRvHqJfzSNRSjGtRq+6sQ0WAj2n9JQwUTX9GJC99UZLJy9Nj+tYBOkKmL1jLzB0r87d+oevyNFAH1Moq2o8yCdhJg3GSABlpJhZPxmsEZNK/SqYuUcnosnKFFr30LYKWlbnpmkhN3obyaxK3VsFDIrN52URSl1cjk15l0iWllhpqj2fOw4SscH+KzN1F99JHPGPnGqudH9CmaMBXc/nll7P77rtz6aWXMnXqVO677z4uuugibrvtNv785z8TRZX/+Gs4oezt7eW6667jxBNPZIcddsjVz5gxg29961tcffXVbNiwgUmTJnHsscfyuc99jv3226/R0wkIaD90ovwhN6DI4Atk/xO3QFe5i4M6DuLe0r3c23kvR/Uepeo7UL6WHajAnD5U1PcQI5Qte0YkL0ZFJ0lIIVlZnOQdx4jmdsijpVRqBTPtUyudQHI+UgXxaGKRropjkLyGKDsJQdXXkZFYknGSMVog/lnryhvkxPVJtAiXYW5O65uMHBkySaQ5d5kdW1HcYPlSpmQyVmVWAI5BMK0gHNNvUtrtfaqjqU6mc6uXOBYQRdcc7+sjtpRRVV6UmzJgcNGIP1R/9atfMWVK5pg/b948Jk6cyLvf/W4WLVrEscceW/H8hhPKzs7Oiml93ve+9/G+972v0cMGBAwd6MCcZZAG5axHrYTTqZrM3jqbe0ffy71993JUfJQya+sX90gUkRwLPI9SLYcQWvWMSIlKpNMHScv0LYC4nJC+JEgnJkqWWrTN32mgTjnK1D+BlaZHJG/c1BQOtuLUQB9x/1h6XjLXrlnIBdS4JDIpy0ibQzAtha+pU608V/PY8plMqnxEMiWEedVSt3cjulUf5Imeo2z6yGasc5uaCmcF4pjLf2lcr3kv3HNjt610TOCpAt2gLyZg4BAFmSTqhEkmNQ4//HAAnn322arnNzUPZUBAQAF6gFEoxVEvwbgjiihuhsPkYQD8rftvyjReRpm6u5O2WqFc2fKZDy1oxdFj+gbjr/qkTMSAbusxf2vtL123W/WYKpwk9WlUs6kQysaoCICtgDpjmbTJNn83AY5SZboO2GqlUV9AJpsS7V2L6dZHJMGak6UQViGTGVHFUib1+emxqxj6fCI9EdZmZLfVp0eF9F13njz628YVXPJClHf7QTRp6cXbb78doDD/r4lAKAMCBgOTUERgNMoPsg9FLjuBLjisTxHKe+W9KlinhPK9HE1m5u5FqZpDNDCn2YhjQRRpJTIiKsUqSL4MUSnhOHGk3vylGIHIVMhIZnVCKt9EKdL8lbk1sxNfy/QYkj5sEinN+oHAVEC14qpVy0aNUS8cYpYjkUkbL5E0iVALyIqr0FnzdedqXEOOSEKWf9Ilew55jOM8mdT3IDZSD7mmbteE7iOQXnXS185UPD3nFgXj6P5io/+A9oGgtpVwVqxYwezZs9PjBQsWsGDBgsL2zz77LJ/97Gd57Wtfa51XhEAoAwIGA2NRCuVmVICORK2AswZYCwdxEKVxJR7ufJhNEzYxunO0avMSilTq1DEbGLKBOU2FZQUW6Yo5AlSgTCwyMzZYkd+mT6U6O1MkcyZw/IolSR/psWmOSkjKgNRKU5XUfptlYciToiVpQjQsddEkkmCrlZXIpKHkNXWuMj9XqIFIpnXZvNM2VcikpRw6ZDJHbn2KYyWyWMGsXZdyaZLIArFLNkcECxgoBDX9ETllypSaE5tv2LCBk08+mY6ODr7//e/XdE4glAEBg4ERKGK4BkUIe1FK40hVPnLbSA7oO4CHOh/i7+W/88oNr1Qq5pjkvA1J29VkwT0BBoTyWSvFpIbqxJ/STCWUJTFXaqQUUqmXUqgk5iapLIs0KEerlYpkosiF68MYkZ1czl7mohHBOTooJ1FQU9JqmNVlufnkzIRFWFzClZTlSJRBmGKdPqgFPNgmwB6ztjnfdJ75eddOJvOm8TR/p0z8I81+PTknvUnMvVuB+byCkglY6qS+D2ab2GkX0F4QUfU2tWLz5s2cdNJJPPHEE9x+++1MnTq1pvMCoQwIGAx0otIELUcRQ602bkURR2DWyFk81PkQD5Qf4JV9r1REsgPlN6nVzTHJ8U6tnX67Q2KYWiNVkqULAmKVRzIirzaqQB3b5C318op63e5IWsQSMEzhwlAMbXakzxv4BSZjGKZ2K1DHRTPUSp+a6CFl6XEBkfSl5GkFzO+hiESqumIiCUl0N4bpG6ygHJdcquCaPOnzkcliIliZIFZr667b7f4m7XbuvJI2Df9GAgaCRvlQ9vb2ctppp7F48WJ+//vfc9BBB9V8biCUAQGDhSkoYrkepU5qUzbAFpi1aRbXjrmWB7ofUArmNlQC9K7kvE3J5/PAzFZPfojAIJE6D7g+VmZwaSuVmG0qm8DBMIND8t2JTLVMxrd8KBsUJJMlWs/69wXlpGiBWplTKHWZ6ZtoEs4CMtkK9atwrmARSd+8vaqkrvME8XjN3kZfJjn1+U1mbatchy6r4DbgI45gq5M6VZAPmUpZOETAYEA0JuAvjmPOOOMMbr31Vm666SaOOOKIus4PhDIgYLAwGaVIjkSRys0oYimBTpjVOwuABzseVKZxQUYmV6N8LjejFMoQmGNDQhxHRFGcEsAYFb8SRXiVSrTZOIqTF7kK4hFRcqKrVkJaBqQmbv0yzkzbjUnpoTotHjclHzTm5VIPLALiCW5J26TEKW/+1vkcm71yjj1Xk+AVz9syfbtEUs/bNXHXoExqU7epAMZmkI8UScCOXWcG8cTpKjs2GY3N1XeMMcux6s8NBDLJpKViSjsYxyW7Ae2Axiyt+KEPfYiFCxdywQUX0N3dzV133ZXWTZ06tarpOxDKgIDBwhhUGqCVKKIYo1a/2QSU4WBxMOwKfx/xd2SfRHQlD/A1KDWzF2X6XolSL0e1+gLaHMZLX1Mt/VL0KpXofW1CzlSjIrUy69tWLdVopgrWmEsSppthon6agRLp2FK0bJGcbELJbpVE4WmZL7hF99EsspJT6CrPO6daOr6S7nlFZNJSal210jInOwqmx2/Snr+vvc8Pslj5LUoBZJHJOKQKamcIGmPyvvnmmwG45JJLuOSSS6y6z33uc1x00UUVzw+EMiBgsDAKFZxTQqUC2op6MoxQ+zv27sjk3sms7FzJ0x1Ps/vG3RUx6U7arEvOXYvyvwyE0kDyQjffgYn/o0xWkjFJJbGqi8sghDJbx7FKcq7b5dRKSBVLwFYtk7oUDRLdTPUz9ccU2fhWIE4rVUofGXQIVyXzt5Qil5anKdMsSG5uzruIRGbXYPhFJu0qEUmTPLsET8ZR3mdSK4s1+03m/SGL2vt8J31bke+kqktM5M35igL6A9GYdROWL18+oPMDoQwIGCyMQKUPeirZ30Ka2JwyiF7BQesP4raJt/HQlofYfdXuGQHVEd9bUObyNSifzACALCjHcQUQKFOfiGRm/i6LJA+l5juKmOlobymUiVurgZpY6mUbtR+jjrSWiXJo+k82kuhp/0mZ+k8KO9jHSNbecpgErYhIJu1MIqnqjJVkmhycU6j05UiwUW8qf8b8YjNpeQ1kMjVz10Qm3foCMllEDn05JgvyThYts2giTsdq7PcR0AC0ME1YEQKhDAgYLETAxGR/E8qErVc+SUzfM1bN4LaJt7GkewlveOENyrS9FuU/qdU1icpPuU+rL6CNYZq7pbTMz6Yymb4Yk2jwjFSaJuyszDJvR5o0ahOzzOWeNBXFbG79J0qmiTtTKDHIZTbLwcpDaZG1SkQSvKqkucxhw+fp9uklwE5bl0ha14FdV4MyWRSAkyeB/no9N1cV9de7ZVmdmf4n7ztpn2e1HYw/VAKqoLbE5s1GIJQBAYOJHciI5FbgZZTaGAMdMGPbDACWTFiignEESnHbBjyXfO4MPA68usVzb3OkL8Bysj53ojjmA3WklYdSJEE3OrmzkMoMTqTN5aTrfQNZWaSIZGp6MmWcBq2Ok6qfZv9ucI5z/S2BzxcRLLN2+unJ7wjk18tu8Px90c+WD6WrUhaQSH2eqUia8y4ikqbKWYsyaQXVuMpiHOEjk1mdXa4DcWozdRskMiYtM9XJlv62AqpDNC5t0EAQCGVAwGBiAookbkGplBuT405VPWOdIpRLxyxV0eAdZGbcMSglM0KRyz7C/2gD7ktPJNE4qWpIplQmhuxcsI6uAZmmF8rKSPtBnwdZ0nFDFdUK5oBQNnJP+sYvyHvZTHhT1DiEzNo3FElVbiqDpolcVEx/U9ccK9wCW02tjUjqNm6ao36TyQoqojmW21bP0dtPhfySLiqt2e1TNdNzBl8QCzARTN4BAds5xqEYwVay9D86gTlwQHwAAP/o/odSz3qViTPNWTkeFZDzKMr3cmxrp9++UKoPxl/tqVIZgRQi9Yu0lclEjTTKSMigFDLla1qxBGzVEjLlEhyC14DlEJ2AoHQcNzAoQauXyrMIS4X8joXLHKbkKX9eM+daWVWtTDKzVW6KiSRkCdBN5dFeBSdTJvX4Zp15XhznSWZaZ6YUkka/SXnZVT6TvuOkX1CqZFzOzk8DcUyVsgnfSUD/IGh9qjAfAqEMCBhMdKPUyA2oJ/SE5HOrqp7cO5nJ2yazcsRKnhn1DLvFu6n/tb1kATodwLPAKgKh1JCKTAkh8i8+c13uBIVqpVb9HP9KksAdIciplqZZ2qVC/V4O0VyNR9p+m0DxuuGthKMoViOSuo2rSLpLGDYDRdHetqpaTa3MFEndpkiVNPuuRCbdNn7fSFvVLVY6RW7+rmrsS2KuVdQixCGFUFuiEVHeA0UglAEBg4kushRA3UmZSPal2vbfsj93jLiDRyY8wm4v76bIZBeK/JRQ6YJWAE8Ae7T6AtoTOso7LpNGa5tqZTVSKSWJWpmVy0RhFCJL12PmFxfJE91M52O+rAekIEh7OUeZjGORS1CT8ZDWZqgXhWTPIJBpUQUiqetz+R01yWwieXEJpFlWKS9lJSKZ1RebuIvIZFEy8qzOTyJ952hF0Zx7UVS3L4l5ke9kiPBuQwiJKAUfyoCA7RsRihBuQ62co99vW0hfWPtt3o87xt3BI52P8Nqu1ypFU/tRjkAdjwb+ARzT0tm3NVKTZDlREZNVcbSpW0hZaALXqmRGLDW5sE3hLrmEPMFMMUDlsNC0bpBFEeVOswlng+FdDrBaUE5S7lMkdZu8f2JTpm8TSodAuvPO5p5XCK19D5EErHRBerzUxOwJwNHtcyvheIim7s80X/va+rZKgTguEY2NuoA2QzB5BwQEMBalOI5EqY8xVpLy/fr2A+Cf4/6plMwyikh2oEhlCehBpRMKUHAjUWMJURIm4yiHFdVKMMzgqsY0hWvV0so5qacgbWVQm8j7C19AkJ5rOoZHpGjpa8ZDxqx9R5FM60xi5ixh6PbVsKlWMXvnSXB2no9oVlIlrf4rkFGTBNrlfjLpOz87Ni5NZgE1rjppnR/b1236TqpzVH9xsmpUQJtAtDZNWBECoQwIGGzsTKY0RiiG0JtswN5b9wbgsc7HsnYxikh2ov4Xh//JDoRKxSIkURQjpSAiRiKIiFJSqesK1UpIVUkgDdwBW7UErDbZNJwgmX5dirS6SseNDAJrqpSDpFTkSJ9DoFQbD7k0FMn02CBQZttmzdVPfrHmnyOP+tMiwx7zdjJ/mxDa7VI10rO+tnkvckqmFLlzzBRB6drf0th3TN1xnO2bZT5Td6ZcNvTrCBgwZEgbFBAQAOxEtpxijCKSHaR5J/eK9mJMPIauUpcikTGZQtmJKutCRXwHpJDSMEljkgAj1Y5LVLRaKYWV1zFtb/hSmqql1cZI35O17T/SftM5k/pTpuTWmKuUIkdkmw4P4auUKFwf15PjsSHT9M3TLPP4fVYiktl1YLVNz3Gu1UcmLWXWGaPWxOUmQXTzTbrX6LYFcqZu3c40dauyRJ0MhLL9EBTKgIAAdkYtmyhQ5uwO1IutD+iFg7YexLpH1yllajTZajpardTR3rsOxuTbE1kkbJRkJs/W5lbrdWd+lSn5SwhoqlbqvoQRta2XYCyLnCKZKZekRCK3vnZ/riU3TrHfZjaP5vhMVoJLMlwCaZYVKZJunZlCp3ET9RR5Vvop+vQpktl11Eck9bnVlMlCAulLEVSwtKKUgnLZ0780TfTFpu5YipRMxlL0U24PaAZ0AOFgIxDKgIDBxi7AXsByFDnsQxFLoY4z02qyaWUSlK+lVikPbuGchwCkFOnylIL8+08mEeA6z6TJyqTMzODmEodpnbFWt+tPKXPkzkbdD/6UyMic36bqz17He9DVoyICadS5amTaxkvObMLXsGk6JLVIzfPOu4hIJm1NYmdeZ24rJIuKZIInYCchkubYZg7JQvJZsLxinPvMm7r1NZifAW2GEJQTEBBACZiHWu1mBMrkrRVKkwlps6Yg85/Upu+dgamtm/JQgHrxVSGVcVKSBOx4H8nm2tlFyp9DLlN4oq7rfSFba3R7xrHM6lK0jQ9ltWTh+rhonW+TTDZUofTNtQKJtObtIZLZXG3zdU55rYNMun37VE2XENrj+lMEgR3B7TN16zYmXHXSdPgIaA+EtEEBAQEKM4BpqLW8O7FM3par3giy/JOdZIE8ryBTLQOQiNTELQSIhGiJSGar3iRmcCBRI0FEBlEzAnO0KVzvE2XjaI5pErk04jseeJBMkWmdgnXD071WEksP4XPJo1Xm8Y80FUndJqf+DXSavn6KlMrYOfZ9mnMvUCTNa6uJSFYxcQNWsI2paBaRSbu9TSbLRn7Lcpy1UeZxOxBHr5ATBzbZXnAsLIOFQCgDAtoB3cCbgF+gllAUZKvhuO9AHdmtieeBwMxWTXSIQLrkQVJNrQTS9EJQoQ0kATE20StSL+UAVcOUM1ppjNLejTH85zUbPpLmI5FATo00601FUh83jFBWON+eX7686LNIkXTnbh0PgEy6/ZlkshZlUp1nzgWnv4J7YgTipKmHarvrAS1ESBsUEBCQYS/gJOAWVKLzkcknZOwgIss/KYF9UcnMR7R0pkMCmUJpbnm1EgCdPshSIpViqX0U3cTi6ae0j1V/9lzkADzm3fEsNdJKau6+UDIfy2ahiOj5zN1me4skOoqkWe+St0avTe7OXxbM1bwOl0SqsmLTttnWRySBnE+kIoOGGukmM6+iTMZxZPlMlp1VdopSBJXT5Ojqmspx3tRdlsnqOYMQ+BVQAUGhDAgIsLAvMAZ4ABWko/0lQb14o2SbDOwDHEQgkwWQsfD6MLpqJeCN9gaQZkS4dFfGyY7NwBgzsntAymSUzQdBbjxVac5V297tMVv64vcQssJ9j2lb1xcRyQErlZ75uGVWnYdE2m39JNlVJK0yR5U0+9OmaV8f/SWTlgIq/X6T5vn6umJpXqNt6g5kss0gQJQCoQwICHCxCyrIZjXwT+BFlPm7hEobtG/SpmuwJtj+SF/uJmm06rHUytQMLoX3L31FLG1zOGSmP4uEOvvQP2LpklIz2twir9IxqRuEqBUBOpXIWa7eIJG6ziVVUrq+iQ7JbMD8KtZ7iKU9X/u8IiJpHefa1GjiLiCTcdnuv2iN7lyddT8zU7eVk9Igm6Y6GRukMvhQtiGCQhkQEOCFACYCR0AaUikYjPSCQxapydtI/2OavzURs4glWIE7YJucTXO4gsiSilu5K+2H+4CUyhpM62ZwUNH5zUAhWTP5bZUcj6YamZYVJQo32jVj/v652u0rXUMltbWISAKWeVu3NQNwivwlqymTZde30gnCiaUTlFO2yWRKLsnIpCQ7DmgXyLZIbO41CLl45pln+PCHP8zcuXMZPXo0QgiWL1+ea7dlyxY++clPsvPOOzNq1Cjmzp3Ln/70p1y7OI657LLLmDZtGiNHjmTWrFnccMMNA76YgIBhCUG2JGOboh2fEdXUniKTYGqmTLaKCpJWfNy1m51NenIJNmSLsy19yzub2abRm3e8stOuyjXk7rNn+cK6vo9+3r/8XDOTtiZsVfupOF51VTL93TpEMP1NO8qnq0y6den/J+u+6jKbFMeGf6q5Go6pSkoSRbOu/4kBTYfA+mO5aGs2aiKUjz32GD/5yU/o6enhyCOPLGz3/ve/n6uuuorPf/7z3HTTTey8886ccMIJ3H///Va7z3zmM1x00UWce+653HzzzRxxxBG89a1v5Te/+c2ALiYgIGBw0I7PiHSN4jjKtnKyGeQgqxfZVs7ayjjb4nKJOI4oJ5/mVu6LiMvKHGnup1tflG5mn7Vu6TiesdX4JWveg7YVzNXct++pc5+c60rbStHQeZb77O+8XI6c/SpbwTXbm+c35WmX/g6d32c5rVP3RrcrJ6pldm9t0putcqPaajKpFctyLIw+7CCccnKu3tembk0mJbZqG9AmKMXVtyZDSFn9pxHHMVGkuOd3vvMdzjrrLJYtW8a0adPSNg888ACHHHII3/ve93jve98LQF9fHzNmzGC//fbjxhtvBOCll15it91241Of+hT/8R//kZ5/3HHHsWLFCh588MGqk549ezaLFy+u60IDAgJqR73/x9rtGbHfmF258pCzM5N2wV/rphkc8OzbPoy6XO0YEdY17NeLbNx8WdHYjRi3v5BSFB+bKptWxTx5Hs39SjkeGzlPt8y3n83Zriuauy9xeyVV0hvlbSqbjqpZNkzkfp9J0naaTKb5JWO7nZlvspyem4/qLifHcVJ2DZ/mBfn4wL6MgIZg9p5j+OvnD6ra7pVf6W0qd6pJodQvikq48cYb6ezs5PTTT0/LOjo6eNvb3sZvf/tbtm7dCsBvf/tbtm3bxplnnmmdf+aZZ/L3v/+dZcuW1TP/gICANkA7PiN8ayi7qpDUypGjWGb7tsKk26tzlXLmmrRzqpNHjaply5SwRJ2KSVWq3NiGilc0brO3zPybzS13b5zrcO+Teb5WJM3vUX0XjZmnVyH0/A7SOXgUb9/vJfVP1Aq35zdhfc9OG1M51JHcpmJZyWcyUxyjqmQyNu+rQSSLUgRpMqkjvgPaDJGsvjUZDQvKWbJkCdOnT2f06NFW+YwZM9i2bRuPPfYYM2bMYMmSJXR1dbH33nvn2gEsXbqU6dOnN2paAQEBbYJWPyPiOHICcux1tKUUmSIZky5h6EZOZ0E82flCGlHWOt+j8cC21tc2UVReAUV5L1WZ0S5JbTTYcHNFVlT8dJ2jRqb7ptLnUQMHPFenH19QTtG8XcXUnbvZzjd/U3WNteJYQZWMnb5qCcCxSKbE6IfUzO2L6HbJpPablMlnTCCVbQUhW2LSroaGEcpVq1bR09OTK584cWJarz8nTJiAcBL9uu1cXHnllVx55ZUArFixolHTDggIaBFa+YxY07vRJgtp+iAJCIswWihIM5SHOlf1Y5yb1gr/yhV1EKE09VCN7dPURoMIH9HLkUdzv4BIqs/KxGxA84yL51nLvF2yq/ssIp45QulGeTv91ksmY6cvV5l0yaSrTLpk0kwLZPpNaiIZyGQbIqQNqh0LFixgwYIFgPLvCggICDBhPiP27Z5qvcDd9EGQ5KEUhkqJZ81ubN9Jn39kVuaQ1Di/HGI9cMfHJJhDzYcSCvwo/Uqf/vSpet6++znHWuZeOL8CNbKWuZtEMCvrL5HEPk5SAwFeZdJdo9tND6T8JTNlspzcB00mg0LZnhhWSy/29PTw5JNP5sq1mqDVhZ6eHtasWYOU0lIg3HYBAQHDC61+RhSSDmtNbKVYuufZxDBr71M2zTK3XpnJ+/ugF9b4puppzlhKkV8dp0iBbRK899qnSOIjYjjHBUqfo+oNeH4F9fZ+vo2PSPrm7Zu7WeeuTNMoMmn2WaRMpvVGeiDI1Eh3P10ph6BQti0G39ulcYRyxowZ/PznP2fTpk2Wj9TSpUsZMWJE6g81Y8YMtm7dyuOPP275SC1duhSAAw88sFFTCggIaCO09Bkh7bW8pRRE5nrdyfKIpn8lZIqlSchM30Wfz6TrL+kSuf4Su2x80k/fko4ikn5T+iATStes7BJIu6yYRPrqG00qfXNyr8E3v6rX4El0XguRBCfJeQ1kUq+ekwXe5Mmkm7g8DdQhI5C+iG5wFcpAK9sKNftQ1uTP0280rPeTTjqJ3t5eFi5cmJb19fVx/fXXc/zxx9PVpdaJO/HEE+ns7OTaa6+1zr/mmmuYOXNmCMgJCBimaOUzQiJyOf0KI7mtaNws+tU9Lxfda0R9W2sqV4gmrjcK2T7fiPw152nlzBTp1srck74xs+uw5+3eo4qR1Z622X59mxXFnKsT3mvxfReVPnO/C6PcjNBW0dt2hLdJNtOo7rLafBHg+ris83dKUUgmVT95M7e5RrdEE8mMTOr6MrZCGUzebYihFOX905/+FIC//e1vANx8881MmTKFKVOmMG/ePA499FBOP/10PvrRj9Lb28v06dP51re+xbJly6wXww477MDHP/5xLrvsMsaOHcthhx3G9ddfz6233prmoQsICBh6aLdnRKo0GYE2pkKZg2XaNtfJrjxGau4uO+ZuT/R3PfP2rtPtjumY1G2ltK5hBwRfbkhXEfSZlX2Knj4uNiX7+686R08gTn/m6ptTpbn7/CTNdvk2lU3cZr9u8E2RMukLwIH8Gt0kn25EN5hkUgYy2W4QDK2gnLe+9a3W8Qc/+EEA5s2bx6JFiwD4/ve/zwUXXMCFF17ImjVrmDVrFrfccguHHXaYde4ll1zCmDFj+OpXv8oLL7zAfvvtx09+8hPe9KY3DfByAgICBgtt9YyQKjAh0onMjYAck1TmzNoFQTmmSVwjH5SD95i4f2bvwoTqtYxZY91AUdmMXOSXWMmfssD0bRCpIh/GRl1DtXn7CKT76ZJI3b6IbNZi3jbblctZH+U4M3WrT2Otbk9qIL3EorkKjk4PVHbIpDZsm2SyTFh6sS3RXGt2TahppZx2Q1gpJyCguRjq/8f2HrUb/2/vjwNkpNIkjZ4VctI6TxnkiZ2VA7KG1XHqJXY+wuojl/3puxWoh0RW/sz7JOr6RpPJivOugUhClksynbtHkXTbpXko3TXhyYiiNpurOXj8Iw1imZ7r8ZnMVsWxyaSO6DbJZIxp7pZpeRn4OZ9mpXyivhse0BTM3nc091yxd9V2h184oqnP9SGTNiggICCgdig/MyGUEiOETIklYAXkQI2EsiCdkCqzxy4yN9dD/LyE0kpq7pDKNkgbolEUkGPuVyKQ1nEBiWwJofSkKfIRSHf+tZm/TUJZ2bxdr4nbXJsbSJdUNFMDVVMmtRLpKpP6OKCdIIeWybvd0dvbyzPPPMOWLVsGeyoBLcbIkSOZOnUqnZ2dgz2VgHaBVEvWZaRRKDOdFF5iaZqLtEk816W0I8BNn0k3kbkmAz7/x1ogRH48d27uPH0R4K1E0bXV4o+oPp3jKkSyv2SycJ51kODYqTPN2m57V5G0CGacvzaTGAIVVclKZDKWgpjs3haRSddnUiuTJnl0jwefugTk0AYm72FDKJ955hnGjh3LtGnTcitsBAxfSCl5+eWXeeaZZ0KGgAALKSGI1YtQRIqo6Rgdi7AZKYFcP0sfwTTPBVKCqffTdkZyuHoURDcoqBKpTPv3lA0W3DkUm5HtsnqThZvnNGKelebqUyKL5qw/XUUyLde5RfuhSoJtBjcjuXWdmWtSz72ITNZq5jbJZPChbDMIhtfSi4ONLVu2BDK5HUIIwaRJk8JynAEWJE5QjpAWsZQiI3+Rm3fSMG37TOIadQfJ1Bmck/fdNOvyz7l28qPME0p/XS3+lN4yzzKHjZgn5NVH9xpq8aH0zd0lkWl5DURSj1+LKunzlzTJZFkrnzWYuTW5BJtMloNK2X5oA+ozbAgl+B+yAcMf4XsPyCN5MeOxBMUYOdlE5mPp6cU1iReZw2uFT1GsCs9KOf4VeNrj/0G1FEK1+CUWqpIFvon9Qew5r4gI15LgPK9g5n0kc+WOedslk9YcGkAmY2mkB8Jv5lZ1mTIJpkJJoJLtijbwoR5WhDIgICAAkhdlslKOTBTKqGJqIFu1BKz2prroi7p2yyuVVUMlNVQ4bM075iC+WHzm52Jzd2WlT+/XEuBS9zx9pLcGH0pz30cg07nF5MpcEmmWp33VaN7uD5HUJu5UZdT9Y5JFm0yaaqQmk32AFNJ7DwMGCQJk8KFsHna6fCde3Phiw/rbsXtHXvi3FxrWXyNw9dVXc/zxx7PLLrvUVVcJ//M//8Po0aN517veVdd5a9as4Uc/+lGaezAgYLARxxBFxgtdE0s8SmNqDpdopc9a8tuA5cNYITDHbVsrLN/OCknNi/ofjOCcIlJX5EtZE7GskUhWIza1+FgWzdM99pnDc0pl7K9zTddmuTQIqE+11GM3ikymhDa5liIy6SqTZpLzgHaCDD6UzUQjyWQz+hsoyuUyV199NTNnziwklEV15XKZUqnk7fecc87p13zWrFnDN7/5zboIZV9fHx0dw/YnGDCYSF+8iiBGhslaE0sz4jslcQZBFPocj3KpX/JFgTkaOtCnHphBQeanO57v2JznQHwL+wvfmLUqlEAdAS75tgOZo6+82JcyTyCL5qz7cRXJtLwCkSwyb4OpWjZHmSxj+0xqMhkDZSGD2bvdIGgLj5c2EEmHD6655hrmzJnDIYccwtlnn025XOaee+7h4IMPZsuWLWzcuJEZM2bw0EMPsWjRIo466ije+MY3st9++3HOOecQJ0+L3/3ud8ydO5fDDjuMt771rWzYsAGAadOmcd5553HYYYdx3XXXsXjxYs444wwOOeQQNm/enM7jpz/9aa7OPHfhwoVcddVVHH744cyaNYu3vOUtbNq0CYCLLrqIyy+/HIDHH3+cE088kVe84hUceeSRPPzwwwC8+OKLnHLKKcyaNYtZs2bx5z//mU996lM8/vjjHHLIIXzyk59ESsknP/lJZs6cyUEHHcT1118PwKJFizjyyCOZP38+Bx54IJ/97Gf5yle+ks79ggsu4Ktf/WrTv6uA4Q2Jve6zXhM5NTHq8mQ9ZLMsv1Z3ogIlgSBlY01l9/xGrOPtrhFesW0NZa3cqs0pt1/lWsvGps5Nvg/Peuv1rpVedvqPnbJK81bra5P+ptzfTtafsVa4OU6y/nY2nmpXjpPI61hY5aYqqaO4y1L5/8Zx0j4hk2WZBNzIbDWcslGuCaOPTOqgHB+ZLAuZksmwlncbIqphazKCPNQg/OMf/+D666/nzjvvpLOzkw9+8INce+21vOtd72L+/PlceOGFbN68mTPPPJOZM2eyaNEi7r77bpYuXcoee+zBiSeeyM9+9jOOPvpovvCFL/CHP/yB7u5u/vM//5Mvf/nLfPaznwVg0qRJ3HvvvQB85zvf4fLLL2f27NnWXE477TS+/vWv5+rMc19++WXOOussAC688EK++93v8uEPf9jqZ8GCBfzP//wP++yzD3/961/54Ac/yK233spHPvIR5s2bx89//nPK5TIbNmzgi1/8Ig899BD3338/ADfccAP3338/DzzwACtXruTwww/nqKOOAuDee+/loYceYvr06SxfvpxTTz2Vj370o8RxzI9//GPuvvvuxn9BAdsdYilyz1BXsUzLk8/CZ24aGIMRGJMlMNeBPSkSlSnqp9nZMmWblqwq+TL7Y2JvFGpR/nzBLeZ+sX+iX700lctGztM9juN8uU9hLTJr6zoz2Ca/NnexeVv3Wc3EDZkqCRnpc4NvipTJtD15ZdI9DpSyzRCCcoYP/vjHP/K3v/2Nww8/HIDNmzezww47APDZz36Www8/nJEjR3LFFVek58yZM4c999wTgLe//e3ccccdjBw5kqVLl/LqV78agG3btjF37tz0nNNPP73fczTPfeihh9L1lDds2MAJJ5xgtd2wYQN//vOfrfWZt27dCsCtt97KD3/4QwBKpRLjx49n9erV1vl33HEHb3/72ymVSuy4447MmzePe+65h3HjxjFnzpw0Z+S0adOYNGkS9913Hy+++CKHHnookyZN6vc1BgRA8kKMBVJkWQCshOZSEUshZOpnKYR6WbpBMZFzXBSgg8eHMq6wak4R3HGLxs7V+fpqwUumko9iJZJWRB7Vvt2360epz/OV9wcmYaw01yLy6GtjBtroch+JLKwz/CT1OJWIpDZlmyZu07wNWY5JVZb3lyxSJr1m78HnLwEaAmRp8L+QQCgbBCkl7373u7nssstydS+//DIbNmygt7eXLVu20N3dDeTT3QghkFLyute9juuuu847jj63PzDPfc973sMvfvELZs2axdVXX82iRYustnEcM2HChFRxbCTca/jABz7A1VdfzQsvvMD73ve+ho8XsB1Cmi9/9aCNEanfpIk4eSNrYumiknrpKoKmD6YxlTqJnZqHqXqaY+fGrKBKuj6drURFxc9L1pJjR8UsIpJuvY8U9meeblnxvN3554lknjTnfSSza8K6FlORhMq+kpCpkqa/JM6nqUK65UU+k2a7kDaojdGg/+pPP/00H/vYx/j973+PlJLXvva1fOUrX2H33Xevem7woWwQjjvuOH7605/y0ksvAbBq1SqefPJJAM4++2wuvvhizjjjDM4777z0nLvvvptly5YRxzHXX389r3nNazjiiCO48847eeyxxwDYuHEj//znP71jjh07lvXr19ddB7B+/Xp23nlnent7ufbaa3P148aNY/r06SxcuBBQhPmBBx5Ir/Vb3/oWoAJ81q5dmxvvyCOP5Prrr6dcLrNixQr+9Kc/MWfOHO9cTjnlFG655RbuueeenFIaENBflBMftcx/TqQ+aD6/R+1nqbdK/nyW710tW7mezfbbjGNR0dev5jm0eCu6X+Xku0i3st7U9fv8Ud1rTX0SDV/GZs1d+0KWzTnHIt+2nPlGav9Ifa7+LsvWFln9ZtdCWq5VSddXUvtIalKZ+ko6/pJl8luMpC+hheaKOOpYpqmBTJ/JTM1UZSGxeZtB0BAfyk2bNnHsscfy8MMP84Mf/ID//d//5dFHH+WYY45h48aNVc8ftgrljt07NjxtUCUceOCBfOELX+D4448njmM6Ozv5xje+we23305nZyfveMc7KJfLvOpVr+LWW28liiIOP/xwzj33XB577DGOOeYYTjnlFKIo4uqrr+btb397amL+whe+wL777psb8z3veQ/nnHMOo0aN4i9/+QujRo0qrHNx8cUX88pXvpIpU6bwyle+0iKDWjm99tpr+Zd/+Re+8IUv0Nvby9ve9jZmzZrFV7/6VRYsWMB3v/tdSqUS3/rWt5g7dy6vfvWrmTlzJq9//ev50pe+xF/+8hdmzZqFEIIvfelL7LTTTmlgj4kRI0ZwzDHHMGHChMLo84CAepAqV7GkjEBEOOmCZKIAkqqWrtKnlUvtc2nWm/t65ZH0XEPFioz2tcCNOE/LdH3kRnljzcGaxyDAr/Y5xxWShJv7rhJp1RUkCq8FlXwuc3OtolSa5myrXLrlVdTKKoqkPs9UJc0IbshM2bX6S5plpkk8BmSRmTs9DnSynSBpjMn7qquu4oknnuCRRx5h7733BuDggw9mn3324dvf/jYf//jHK54vpBx6nhCzZ89m8eLFVtk//vEPDjjggEGaUf1YtGgRl19+OTfddNNgT8XChz/8YQ477DDe+973tmzMOI7T6PN99tmnX30Mte+/3eH7PzaUsEfHdD41/iKEsH0nRWT7RGa+kOo811/Sl1zcDOip1Z+xHpKX89mssA+Dm8i8EmpNcu73S6yNSOpPl8jVPdcK5nlrXp7gnEpm8HqIpK6LMdtlRDLtD5tM6jrtL1krmSwnZ0pjXyctd8mkViazCHDJnfF/sFYuq3hfA1qDV8wcyV9/slvVdke8a3zF5/pxxx3Hli1buPPOO63yefPmAXD77bdX7H/YKpQB9eMzn/kMf/3rX7noootaNubSpUt505vexCmnnNJvMhkQ4EKilSvswBwpUwFRRJ5gnZQbiEKSGVuBMa7/Yj6C3EQtxFJ6CKXr9+kmZW+ndbw16veh9KiUVVacUWX+PmqFdwlGD3HMz9uZq7TPKVQrY0d19JDItA7bT7JSknJTZaxFlfT5S5a16m6YuGNhtklM4iEXZfuhAQ6MS5Ys4eSTT86Vz5gxI3V/q4RAKAcJRx99NEcfffRgT8PCxRdfzMUXX9zSMQ888ECeeOKJlo4ZsH1Av+AjBPqVHGOkEkoaxFFWZpu9s3NUPzWOG1d60SZ91dCZa1a3CGaFtu0AH7GrNVE49J9I1p1CqEp0d37e+XaxSxgrEEld7ovcztVhK5KqLE8mzUsYCJnUf8i4RNElk/2MfQpoMmr56a9YscJKJbhgwQIWLFiQHq9atYqenp7ceRMnTsxlcvEhEMqAgIBhBx3IASQr46jySGQPXlO1jDFXyMmUS9UuI5aZKdx+eldUED3wRST7VE8z8tyK7G6Aab1ZqBY17R4XrTRj7rspdfRnkS9jLSgin5X8KF3yaPZTiUC67XxmbXDJY6ZIAoVEshbztkskwVAhC0zcrjJZRhILafUV0CYQIGtgc1OmTGmqK1MglAEBAcMScSyS3JKKRUZCqmACKRSxlIqA6eAcn3IJ4Es1pM/VSAN80gY2Ka0FPpWxXLaJprmEJOQJpB2w07pXfiUi5yOPvrrC9DseIqnr3RyPZvuBXoNrwrbr6ieRkFcj0+swxiwyb6vzMzJpkkWonUy6qmQtZFI6ZDIE5bQh6k1460FPT49XiSxSLl0EQhkQEDD8INXLPYpESv5MYllOyqI0eZsd9Q1KuYSEdCaR4iZRdEmdSWTcCPBqSN8FUlRcK7xctvs3k8+5ZvT++BM2AtWShLvHtQS3FJHItMyjHFadZwEnqtvkHefritTItMxQJPVcfKZt3aZWVZKC8oGQSTN4R5PJQCfbDAJkA3woZ8yYwZIlS3LlS5cu5cADD6x6fiCUAQEBww4SveZxZqJO1T1BShyzABhVp0VJrVzqcyEjmLoPDeFJiF7vkou2OdssNwhjhUhvgHZJ2FFE6qoFt5htfEnC3fJKEdW1oF8m7zjfznct9ZDIbD9v2k7PxSljYEQSnMjuZN+N5I4hp0xKoC9olO2HBhDK+fPn82//9m888cQT6Sp+y5cv58477+SLX/xiK6bQptgJ9cd7o7adGjOtRYsW8aY3vamucy699NLCOiklxx57LOvWrWvInG688caafjj9wdatWzn99NPZe++9eeUrX8ny5csL25bLZQ499FDrXr3tbW/j0UcfbcrcAoYf9Es8jaSNSdPO6CTnWb1eF1q90BUZ1ZvqqxyLXHspkyTkMdZWLmdta9l0ovX8huVnV6m9mQh8sLai8XWSb/P7yLb8uWk7fU+Ncp3w2/zO9PdV+/1255Dc49iZd5JsPPvt5L+P9PchBTECM3+k+buRZCqkqUiapm3XT9Jn3nZJY0ztZJLk09y0KhkLk7AWk8lAJdsQAmSp+lYNZ511FtOmTePkk0/ml7/8JTfeeCMnn3wyu+22G2effXbV84evQtm4nOZ19yelREpJVEsoZw249NJL+fSnP+2t+81vfsOsWbMYN25cQ+Ywf/585s+f3++5VsJ3v/tdenp6eOyxx/jxj3/Meeedx/XXX+9t+9WvfpUDDjjAIsr/8i//wpe+9CWuuuqqpswvYPhAkvg16mOZqZCmagnKVJyJTJkvpKteQqZgmgE67nkp4vqUyqzPxLyejulXJvNzyObizrvZqCSOVgzIMdU9T2CNz1fRF1VdyeRd65KMvmsoUlJj8uU5v8m0D3LHphqp68wUQH7fSLPM9pPM+sgTScjSAVUzcZeTM/rSiG+lRoIO4lFpt7SCGdAekIAsWDq2HnR3d3PrrbfysY99jHe+851IKTnuuOP4yle+wpgxY6qeP3wVyhZj+fLl7LfffrzrXe9i5syZPP3003zyk59k5syZHHTQQRZxWrduHW984xvZb7/9OOecc4iTJ951113HQQcdxMyZM9MlGj/1qU+xefNmDjnkEM4444zcuNdee22aN8o3h3/5l39h9uzZzJgxg8997nPpebfccgv7778/hx12GD/72c/S8quvvppzzz0XUKvt/PSnP03r9A/q+eef56ijjuKQQw5h5syZ/N///V9N9+iXv/wl7373uwE47bTT+OMf/4jPTPfMM8/w61//mg984ANW+ZFHHskf/vAH+vr6ahovYDuGqzw56yCbypJeus9VBX1qoFaR8ipmpnq66pSpbFbb0v4MtdNbX0UR1PNp1VarYplTKk1l11EnzSULpdT3Md/OVjn195ltPiXS9z1VUjFN9dH6LRmqZTof8kpkJTXSJJOu2uiP3s4H3VRSJXNqJH4yaZrOcfpM90U2h4A2QwOWXgTYfffdueGGG1i3bh3r16/nF7/4BdOmTavp3OGrUA4CHn30UX7wgx9wxBFHcMMNN3D//ffzwAMPsHLlSg4//HCOOuooQK3hvXTpUvbYYw9OPPFEfvazn/GqV72K8847j7/97W/09PRw/PHH84tf/IIvfvGLfP3rX+f+++/3jnnnnXfy7W9/2zsHgEsuuYSJEydSLpc57rjjePDBB9l3330566yzuPXWW9l77705/fTT67rOH/3oR5xwwglccMEFlMtlNm3aBMDpp5/OI488kmv/8Y9/nHe96108++yz7Labyubf0dHB+PHjefnll5k8ebLV/qMf/Shf+tKXcmuRR1HE3nvvzQMPPMArXvGKuuYcsP2hLAVC6gAakIlkl1MtkzZZwEumXKrjvD8lkAb3aAgh8SWD0xHl1VA4ToHvJmAFCvlQry9nf1At96Ob67GaL6Vdb5d5fSeNoJiBRHqbqqOvD1/QDRQrkbrMp0aq8Sorkua+z08SKCSSadt6orgpNnG7ZLJG0TegVRAVHwMtQyCUDcQee+yRErk77riDt7/97ZRKJXbccUfmzZvHPffcw7hx45gzZ07q8Pr2t7+dO+64g87OTo4++mimTJkCwBlnnMGf/vQn3vzmN1ccc9WqVYwdO9Y7B4Cf/OQnXHnllfT19fH888+zdOlS4jhm+vTp6co0Z555JldeeWXN13n44Yfzvve9j97eXt785jdzyCGHABSar+vBTTfdxA477MArXvEKFi1alKvfYYcdeO655wKhDKgIiVqKTvHFhKQZ5FIIVOS2bp+8wasRzKyddNbPJvdE12SuXAO5McmoSUBtkmmPEQmJLLs9OemMaO1bpigoxiWdvkAc1c4u8xFErUSa5e4a2JXnWF+djzxac/WW1UYidV3xfm1EUpX5I7hBBd6kbfpJJrXpW5vGg0bZXpAdg88oA6FsILq7u2tq5yZFdo/rQUdHB3Ecp76S5hyWLVvG5Zdfzj333ENPTw/vec972LJlS919A8RxzLZt2wA46qij+NOf/sSvf/1r3vOe96QKZDWFctddd+Xpp59m6tSp9PX1sXbtWiZNmmS1vfPOO7nxxhv5zW9+w5YtW1i3bh1nnnkm11xzDQBbtmxh1KhR9d2kgO0SsVTkLF0xR2R+lZHzOoydSG4zr6Ruq3JC6jPsJRZ1aiITFhGsBiksApr2JUXqt+mOkct9afSl0RYKZU7pyxPIfHnedxKoSiRdf8Z64F2C0aqvXC7xEGN9THUimbZL96VzbNeZqiQYpNFRJTHaDEyZzPoKdLLN0CYKZfChbBKOPPJIrr/+esrlMitWrOBPf/oTc+bMAZTJe9myZcRxzPXXX89rXvMa5syZw+23387KlSspl8tcd9116YLsnZ2d9Pb2esfZb7/9CpcuXLduHd3d3YwfP54XX3yRm2++GYD999+f5cuX8/jjjwPKd9OHadOm8be//Q1Q0d96Dk8++SQ77rgjZ511Fh/4wAe49957AaVQ3n///bntXe96F6ACfn7wgx8A8NOf/pRjjz02R6Yvu+wynnnmGZYvX86Pf/xjjj322JRMAvzzn/9k5syZlW59QAASQVnqjdzWGyd12scx8b3ri83z7Dbu1tsnLF+9vj4VFexufX1qq+aH2FeOjP4jY8vGtNsI+srV+2z2Vjy22irN33edZp/ZfUzus3n/48j6nuLYqHe/wyqb+j3Yv5E+6/fi/oZ8/SRtpVpXu888Tsqqb5K+ZPPVZVt23EeS+kdIykJa5Wl7o071Hat9qzw2zo3Tc/qI6UvIZ5mYPuKEaAZS2VZokA/lQDB8FcodaWyk9471NT/llFP4y1/+wqxZsxBC8KUvfYmddtqJhx9+mMMPP5xzzz2Xxx57jGOOOYZTTjmFKIr44he/yDHHHIOUkje+8Y1psM2CBQs4+OCDOeyww7j22mutcd74xjeyaNEi9t5779wcZs2axaGHHsr+++/Pbrvtxqtf/WoARo4cyZVXXskb3/hGRo8ezZFHHpnzVwSVQuDkk09m1qxZnHjiian6uWjRIv7rv/6Lzs5OxowZww9/+MOa7sn73/9+3vnOd7L33nszceJEfvzjHwPw3HPP8YEPfIDf/OY3Fc9/8cUXGTVqFDvt1KAcTgHDGhKtUmrzo3oBppHa0tw3VD1HfSmbEdzSrs+ZV2WxKpiZ0IvnnC21WDyG+16wFM02gjfi2uMz6batlOuxKFG4bpMqeDXejqJm7vk+9dE9P1XwPEpk0bGpOObLbLN3JfN21j7vK2mO3V9/SZnuJ1sbqGEBGaSAuGPwnwFCtks23Dowe/bs3HqU//jHPzjggAMGaUaDh+eff553vetd/P73vx/sqTQd/+///T/GjRvH+9///lzd9vr9Nwu+/2NDCTuJvXgXl1pLKup3YJq8HGnsZ/CXZY9JkxD6yKFLSCvBPT9bP9wocxikjzy2MkVQLSh6q1QjjuAnne7a12Y7k0TWTyiLfD7ddkadWS7z5ZUIpH0sq5JMH4lM2zl+kj4iWY95G7L0QkqFVEhTCREnuSrVecv7/ost8VMEDD4OPWwkt9+xe9V2xx41rqnP9ZpE0GeeeYYPf/jDzJ07l9GjRyOEyCWlXrx4MQsWLGD//fdn9OjR7L777pxxxhksW7Ys19+0adMQQuS2X/ziF424pu0KO++8M2edddaAEpsPFUyYMCFNOxTQXmjHZ4T2WytLHUiQqZZxzmyp2kmS9oZ5U5X508n4kl5bZlgqb7qdm75Gm26lzEzqWUqczBRcKUVQLelyGrVVSiNkztdM6+NL2ZNes2NONlP0+NLz6O/JTM1juz34NysNlPOdSzJzsyZrZeOazd9V2WgfVzxWZKyPzD9SOm30cof6XGmSQUhN0a4iWdbtEj/JcjqOTMatrEqWhZ5bnPZdTszbLpkMPpRtBgEyklW3ZqMmk/djjz3GT37yE17xildw5JFH8rvf/S7X5sc//jFLlizhIx/5CDNmzODZZ5/l4osvZvbs2dx///1puhiNE044gYsuusgq22+//fp/Jdsx/r//7/8b7Cm0BO9973sHewoBBWi3Z4RJCERSEOljQ7XMAnZss7gqs9uYZWnAjTsotprpU+p8aqKOxk6jzLViJG1zu9t/ZTP64MqW1SKm3TauKdvcryVZuDoWllJZDUXpb9y5u+18imWlsiI1Uh+bZm1d5yqPMDBV0hyrPybu2CkLic3bCRIiT8qHFqMmQnnUUUfx4ovKIfE73/mO92Vx3nnnpSlvNF796lczffp0rrrqKj7/+c9bdZMnT7bS2zQCUsoBRUwHDE0MQa+NYYd2fEbox6vrlSgMwpGtnkPaOu/FqMzjoFQpc0EKb5B1NSJndOy21GRRGs8xt03Rz72dHn1Fc/StMOMe15LjsVJ6HteXsRIKCWWFdj7iaM3NaFE5olt66opJpK6PnfZm5Lbu1yWS5bTf6kQSSANvIFs1R5cFhbL9sOOUYzjuVSurtnNzPjcaNRHKWpbvc18UoHIiTpkyhWeffbb+mdWJkSNH8vLLLzNp0qRAKrcjSCl5+eWXGTly5GBPZbtGuz0jzJd0qkYax+m+JjGmz6JubymTZlCG/TJ1VzzT+S9rhXl+SqakQS6lTRatICETsj7/zWahKA9kvYnCVbldViuRLCKKvjFc+M6tRiJVubTqfUqk2a5IjUzLnGAbvW8dO2mAwDgWMje/SmTSvoasf7cMT98Bg4tbbrllsKcANDnK+x//+AcvvfSSN1jiV7/6FaNHj6ZcLnPooYfyqU99qmoS70qYOnUqzzzzDCtWrBjAjAOGIkaOHMnUqVMHexoB/UDznhEyVWXSxOZpDemxzJrn6w1eZJMhYVEmV7XMWtX2yjXPN7uxlE4PSfVFk8dFZLMFqKQI5kzdVh3eOjuaOiOQOaImnWOqk8LCeVY5z6c+5tvYZT4CqY79aqQu89YbimRWlymSkPeT1GNXM2+DkbzcY+LOzN+ZyTwgwETTCGVfXx/nnHMOU6ZMyUXlnnTSSRx++OFMnz6dF198ka9//euccsop/O///i9nnnmmt78rr7wyXc3FRxo7OzuZPn164y8kICCgKWjmM2Iz6zP/yeTVF2lSkrRPfSqNY7D9Ls124ERfG2P7VUkjFVEVkufz3fT1afajk7Tn0EZvet9UKkZQOwqkXZYc6/MqEEm3bb/m6Sn1m7h9ZbKwXT1E0ixzfST1ONX8JCEjipV8JQEjzVBlMqn+WGujH1pAW6DutEHf+c53OOuss1i2bFnFBcPPOeccvvvd7/LrX/+a448/vmKf5XKZI444ghdeeIGnn3666hyGekqTgIB2x0D+j7XDM2KK2JNTuBSw0wbp/chRLU1yWKkMX10BWaw1j7AvZZEqz5PMovlY4w6ix09Rup6cT2KOVFbO81iJRLrHviCZtO8aSFClABy33qde+tVKO+UP2CTS10Y6JK8eIukeayIJ0JfWVw+8Ue2TtEEiS3weI1nTewV98TMEBGg0JXf6pz71Ka688kq+973vVX1RAJRKJd761rfyzDPP8PzzzzdjSgEBAW2EZj8jJDqNip26RW/ZaiTmyiO1bdItk/lNesoKt8K+KqW8qaP/NtjcNE35lD613I96vp9sxRlzc38HtWz5c2TBVlzfp/sRMl3Rxkz1Y7XRZFHgrHyjV7jJVrnR5m29uo1WJc3VbvQ63DpdkbniTR8xfSLpy+hDbypdkMyRybIIYTkBeTTc5H3JJZfwn//5n3zta1/jne98Z93nh4CagIDhjVY9I7RCA35zt3lsmsVd1SvCrzph1Luo1dQakaluQvjHFOQVvchzD/TMa03q3Sz0J1k45FVIq8zXzjjO9mWuzDuXCnW1KJtFKqRbVkmN9Lajsmlbt61k3vapkvo8V5X0XWORidskk30EOhmQR0MJ5RVXXMGFF17IJZdcwrnnnlvzeX19fVx//fXsvvvuNS2rt3z58jQ6NKAxWLFiRbifDcZQvqduUvJGoVXPCCat44/dnxqy979dMZR/0+2KVt/TRi3rvHz5lgb0EjCcUDOh/OlPfwrA3/72NwBuvvlmpkyZwpQpU5g3bx4//vGP+ehHP8qJJ57Isccey1133ZWeO27cOA488EAArrvuOn75y1/yhje8gd12240XX3yRb3zjG9x7771cd911Nc1l5cqVwY+ywQj3s/HY3u5peEYMf4R72niEexowXFAzoXzrW99qHX/wgx8EYN68eSxatIhbbrkFKSW33HJLLieSbgMwffp0XnrpJT75yU+yatUquru7mT17NrfccgsnnHDCAC8nICBgsBCeEQEBAQHbL+qO8m4XhL/qGotwPxuPcE8HF+H+Nx7hnjYe4Z4GDBc0Jcq7FViwYMFgT2FYIdzPxiPc08FFuP+NR7injUe4pwHDBUNWoQwICAgICAgICGgPDFmFMiAgICAgICAgoD0QCGVAQEBAQEBAQMCAMGQI5dNPP81pp53G+PHjGTduHKeeeipPPfXUYE9ryGDRokUIIXLbhAkTrHarV6/mAx/4AJMnT6a7u5vXvva1/P3vfx+cSbcRnnnmGT784Q8zd+5cRo8ejRDCm6txy5YtfPKTn2TnnXdm1KhRzJ07lz/96U+5dnEcc9lllzFt2jRGjhzJrFmzuOGGG1pwJcMb4TnRf4RnxMAQnhEB2zuGBKHctGkTxx57LA8//DA/+MEP+N///V8effRRjjnmGDZu3DjY0xtSuOKKK/jLX/6Sbn/4wx/SOiklJ510Erfccgtf+9rXuOGGG+jt7eWYY47hmWe27zVbH3vsMX7yk5/Q09PDkUceWdju/e9/P1dddRWf//znuemmm9h555054YQTuP/++612n/nMZ7jooos499xzufnmmzniiCN461vfym9+85smX8nwRXhONAbhGdE/hGdEwHYPOQTwla98RUZRJB999NG07IknnpClUkn+93//9yDObOjgtttuk4D8/e9/X9jmF7/4hQTkrbfempatWbNG9vT0yA9/+MOtmGbbolwup/tXXXWVBOSyZcusNvfff78E5Pe+9720rLe3V+67777ypJNOSstefPFFOWLECPnZz37WOv/YY4+VBx10UHMuYDtAeE4MDOEZMTCEZ0TA9o4hoVDeeOONHHHEEey9995p2fTp03n1q1/NL3/5y0Gc2fDCjTfeyC677MIxxxyTlo0fP56TTjppu7/PUVT9v8qNN95IZ2cnp59+elrW0dHB2972Nn7729+ydetWAH7729+ybds2zjzzTOv8M888k7///e8sW7assZPfThCeE81HeEYUIzwjArZ3DAlCuWTJEmbOnJkrnzFjBkuXLh2EGQ1dnHHGGZRKJSZNmsQ73vEOy7+s0n1+6qmn2LBhQyunOuSwZMkSpk+fzujRo63yGTNmsG3bNh577LG0XVdXl0V8dDsg/Kb7ifCcaAzCM6J5CM+IgOGMmpdeHEysWrWKnp6eXPnEiRNZvXr1IMxo6GH8+PF84hOfYN68eYwbN4777ruPSy+9lLlz53Lfffexww47sGrVKqZNm5Y7d+LEiYByxh8zZkyLZz50UOl3quv154QJExBCVGwXUB/Cc2JgCM+I5iM8IwKGM4YEoQwYOA499FAOPfTQ9HjevHkcddRRzJkzhyuuuIIvfOELgzi7gICAwUZ4RgQEBAwEQ8Lk3dPT41UYiv7aC6gNhx12GPvuuy/33HMPUPk+6/qAYlS7f1pd6OnpYc2aNUhnkSq3XUB9CM+JxiM8IxqL8IwIGM4YEoRyxowZLFmyJFe+dOlSDjzwwEGY0fCCNqtUus+77757MGVVwYwZM1i2bBmbNm2yypcuXcqIESNSf6gZM2awdetWHn/88Vw7IPym+4nwnGgewjOiMQjPiIDhjCFBKOfPn89dd93FE088kZYtX76cO++8k/nz5w/izIY2Fi9ezCOPPMKcOXMAdZ+fffZZbr/99rTNunXr+NWvfhXucw046aST6O3tZeHChWlZX18f119/PccffzxdXV0AnHjiiXR2dnLttdda519zzTXMnDmT6dOnt3TewwXhOdF4hGdEYxGeEQHDGoOdt6gWbNiwQe61115y5syZ8he/+IX85S9/KQ8++GA5ffp0uX79+sGe3pDAO97xDnnBBRfIG264Qf7xj3+Ul19+uZw0aZLcbbfd5IoVK6SUKo/a3Llz5dSpU+V1110nb7nlFjlv3jzZ09Mjn3rqqUG+gsHHwoUL5cKFC+U555wjAfnNb35TLly4UC5atChtc/rpp8sJEybIq666Sv7hD3+Qb3nLW2RXV5f829/+ZvV13nnnya6uLvnf//3f8rbbbpPnnHOOFELIX/3qV62+rGGD8JwYGMIzYuAIz4iA7RlDglBKKeWTTz4pTz31VDl27Fg5ZswYefLJJ+eSxgYU49JLL5UHHXSQHDdunOzo6JBTp06VZ511lnzuueesdi+//LJ873vfK3t6euSoUaPkscceK++///5BmnV7AfBu8+bNS9ts2rRJfuxjH5M77rij7OrqknPmzJG33XZbrq++vj558cUXy913312OGDFCHnTQQXLhwoWtu5hhivCc6D/CM2LgCM+IgO0ZQkrH6zcgICAgICAgICCgDgwJH8qAgICAgICAgID2RSCUAQEBAQEBAQEBA0IglAEBAQEBAQEBAQNCIJQBAQEBAQEBAQEDQiCUAQEBAQEBAQEBA0IglAEBAQEBAQEBAQNCIJQBAQEBAQEBAQEDQiCUAQEBAQEBAQEBA8L/D5belrTWMoQuAAAAAElFTkSuQmCC\n", "text/plain": [ - "
" + "
" ] }, "metadata": {}, @@ -165,7 +155,8 @@ " robot_radius=0.4, \n", " labels=[\"expert trajectory\"], \n", " fig_idx_robot=0,\n", - " figsize=(4, 4)\n", + " figsize=(10, 4),\n", + " plot_sdf=True,\n", ")\n", "figs[0].show()\n", "figs[1].show()" @@ -173,7 +164,6 @@ }, { "cell_type": "markdown", - "id": "cab578f8", "metadata": {}, "source": [ "The following are some constants that we will use throughout the example" @@ -182,7 +172,6 @@ { "cell_type": "code", "execution_count": 5, - "id": "cf626274", "metadata": {}, "outputs": [], "source": [ @@ -200,7 +189,6 @@ }, { "cell_type": "markdown", - "id": "debc9416", "metadata": {}, "source": [ "## 2. Modeling the problem" @@ -208,7 +196,6 @@ }, { "cell_type": "markdown", - "id": "8ab0db1c", "metadata": {}, "source": [ "### 2.1. Defining Variable objects" @@ -216,7 +203,6 @@ }, { "cell_type": "markdown", - "id": "30eba75d", "metadata": {}, "source": [ "Our goal in this example will be to use `Theseus` to produce plans for the maps loaded above. As mentioned in the introduction, we need a 2D pose and a 2D velocity for each point along the trajectory to be optimized. For this, we will create a set of `th.Point2` variables with individual names, and store them in two lists so that they can be later passed to the appropriate cost functions." @@ -225,7 +211,6 @@ { "cell_type": "code", "execution_count": 6, - "id": "495b6840", "metadata": {}, "outputs": [], "source": [ @@ -239,7 +224,6 @@ }, { "cell_type": "markdown", - "id": "ffe66510", "metadata": {}, "source": [ "In addition to the optimization variables, we will also need a set of *auxiliary* variables to wrap map-dependent quantities involved in cost function computation, but that are constant throughout the optimization. This includes start/goal target values, as well as parameters for collision and dynamics cost functions." @@ -248,7 +232,6 @@ { "cell_type": "code", "execution_count": 7, - "id": "5bea3236", "metadata": {}, "outputs": [], "source": [ @@ -268,7 +251,6 @@ }, { "cell_type": "markdown", - "id": "fff1446e", "metadata": {}, "source": [ "### 2.2. Cost weights" @@ -276,7 +258,6 @@ }, { "cell_type": "markdown", - "id": "21cf8dd2", "metadata": {}, "source": [ "Next we will create a series of cost weights to use for each of the cost functions involved in our optimization problem." @@ -285,7 +266,6 @@ { "cell_type": "code", "execution_count": 8, - "id": "1149ed5e", "metadata": {}, "outputs": [], "source": [ @@ -302,7 +282,6 @@ }, { "cell_type": "markdown", - "id": "3da7695c", "metadata": {}, "source": [ "### 2.3. Cost functions" @@ -310,7 +289,6 @@ }, { "cell_type": "markdown", - "id": "6d9e8067", "metadata": {}, "source": [ "In this section, we will now create a `Theseus` objective and add the GPMP2 cost functions for motion planning. First, we create the objective:" @@ -319,7 +297,6 @@ { "cell_type": "code", "execution_count": 9, - "id": "e3b30cc3", "metadata": {}, "outputs": [], "source": [ @@ -328,7 +305,6 @@ }, { "cell_type": "markdown", - "id": "120726d4", "metadata": {}, "source": [ "#### Boundary cost functions" @@ -336,7 +312,6 @@ }, { "cell_type": "markdown", - "id": "71e4cba9", "metadata": {}, "source": [ "Here we create cost functions for the boundary conditions, assign names to them, and add them to the `Objective`. For boundaries, we need four cost functions, and for each we use a cost function of type `th.Difference`. This cost function type takes as input an optimization variable, a cost weight, a target auxiliary variable, and a name. Its error function is the local difference between the optimization variable and the target.\n", @@ -349,7 +324,6 @@ { "cell_type": "code", "execution_count": 10, - "id": "627b38e0", "metadata": {}, "outputs": [], "source": [ @@ -383,7 +357,6 @@ }, { "cell_type": "markdown", - "id": "bfa02b0f", "metadata": {}, "source": [ "#### Collision cost functions" @@ -391,7 +364,6 @@ }, { "cell_type": "markdown", - "id": "fb8b31c8", "metadata": {}, "source": [ "For collision avoidance, we use a `th.eb.Collision2D` cost function type, which receives the following inputs:\n", @@ -408,7 +380,6 @@ { "cell_type": "code", "execution_count": 11, - "id": "fd5bc03e", "metadata": {}, "outputs": [], "source": [ @@ -428,7 +399,6 @@ }, { "cell_type": "markdown", - "id": "d65413f5", "metadata": {}, "source": [ "#### GP-dynamics cost functions" @@ -436,7 +406,6 @@ }, { "cell_type": "markdown", - "id": "242a2f8e", "metadata": {}, "source": [ "For ensuring smooth trajectories, we use a `th.eb.GPMotionModel` cost function, which receives the following inputs:\n", @@ -451,7 +420,6 @@ { "cell_type": "code", "execution_count": 12, - "id": "88de9eb4", "metadata": {}, "outputs": [], "source": [ @@ -473,7 +441,6 @@ }, { "cell_type": "markdown", - "id": "2657cc4b", "metadata": {}, "source": [ "## Creating the TheseusLayer for motion planning" @@ -481,7 +448,6 @@ }, { "cell_type": "markdown", - "id": "268594c8", "metadata": {}, "source": [ "For this example, we will use Levenberg-Marquardt as the non-linear optimizer, coupled with a dense linear solver based on Cholesky decomposition." @@ -490,7 +456,6 @@ { "cell_type": "code", "execution_count": 13, - "id": "27461337", "metadata": {}, "outputs": [], "source": [ @@ -506,7 +471,6 @@ }, { "cell_type": "markdown", - "id": "ee023057", "metadata": {}, "source": [ "## 3. Running the optimizer" @@ -514,7 +478,6 @@ }, { "cell_type": "markdown", - "id": "fd6989ef", "metadata": {}, "source": [ "Finally, we are ready to generate some optimal plans. We first initialize all auxiliary variables whose values are map dependent (e.g., start and goal positions, or SDF data). We also provide some sensible initial values for the optimization variables; in this example, we will initialize the optimizaton variables to be on a straight line from start to goal. The following helper function will be useful for this:" @@ -523,7 +486,6 @@ { "cell_type": "code", "execution_count": 14, - "id": "12db4db3", "metadata": {}, "outputs": [], "source": [ @@ -545,7 +507,6 @@ }, { "cell_type": "markdown", - "id": "88ac4456", "metadata": {}, "source": [ "Now, let's pass the motion planning data to our `TheseusLayer` and start create some trajectories; note that we can solve for both trajectories simultaneously by taking advantage of Theseus' batch support. For initializing variables, we create a dictionary mapping strings to `torch.Tensor`, where the keys are `th.Variable` names, and the values are the tensors that should be used for their initial values. " @@ -554,7 +515,6 @@ { "cell_type": "code", "execution_count": 15, - "id": "86b7c9fe", "metadata": { "scrolled": false }, @@ -641,7 +601,6 @@ }, { "cell_type": "markdown", - "id": "dc5b2307", "metadata": {}, "source": [ "## 4. Results" @@ -649,7 +608,6 @@ }, { "cell_type": "markdown", - "id": "2f5dd147", "metadata": {}, "source": [ "After the optimization is completed, we can query the optimization variables to obtain the final trajectory and visualize the result. The following function creates a trajectory tensor from the output dictionary of `TheseusLayer`." @@ -658,7 +616,6 @@ { "cell_type": "code", "execution_count": 16, - "id": "de6fabcd", "metadata": {}, "outputs": [], "source": [ @@ -672,7 +629,6 @@ }, { "cell_type": "markdown", - "id": "bb85ef5f", "metadata": {}, "source": [ "Let's now plot the final trajectories" @@ -681,12 +637,11 @@ { "cell_type": "code", "execution_count": 17, - "id": "98cbadf9", "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -696,7 +651,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] diff --git a/tutorials/05_differentiable_motion_planning.ipynb b/tutorials/05_differentiable_motion_planning.ipynb index 3eaef4ae6..38da61568 100644 --- a/tutorials/05_differentiable_motion_planning.ipynb +++ b/tutorials/05_differentiable_motion_planning.ipynb @@ -2,7 +2,6 @@ "cells": [ { "cell_type": "markdown", - "id": "d2052376", "metadata": {}, "source": [ "# Motion Planning Part 2: differentiable motion planning" @@ -10,7 +9,6 @@ }, { "cell_type": "markdown", - "id": "37cde4fb", "metadata": {}, "source": [ "In this tutorial, we will build on the [first part](https://github.com/facebookresearch/theseus/blob/main/tutorials/04_motion_planning.ipynb) of the motion planning tutorial to illustrate how we can differentiate through a motion planner implemented using `Theseus`. In particular, we will show how to set up an imitation learning loop in `torch` to produce values to initialize the `TheseusLayer` so that it converges to a high quality trajectory faster. If you haven't already, we encourage you to review part 1 of the motion planning tutorial before proceeding with this one." @@ -19,7 +17,6 @@ { "cell_type": "code", "execution_count": 1, - "id": "e29b5088", "metadata": {}, "outputs": [], "source": [ @@ -52,7 +49,6 @@ }, { "cell_type": "markdown", - "id": "aae80147", "metadata": {}, "source": [ "## 1. Initial setup" @@ -60,7 +56,6 @@ }, { "cell_type": "markdown", - "id": "bb2c2929", "metadata": {}, "source": [ "As in part 1 of the motion planning tutorial, the first step is to load a few planning problems from the dataset, and set up some constant quantities to use throughout the experiment. During this example, we will use a batch of 2 problems obtained from the loader." @@ -69,7 +64,6 @@ { "cell_type": "code", "execution_count": 2, - "id": "75279a01", "metadata": {}, "outputs": [], "source": [ @@ -94,7 +88,6 @@ }, { "cell_type": "markdown", - "id": "5c1238b5", "metadata": {}, "source": [ "Next we create the motion planner. Class `theg.MotionPlanner` stores a `TheseusLayer` constructed by following the steps described in part 1, and also provides some useful utility functions to retrieve trajectories from the current variables of the optimizer. " @@ -103,7 +96,6 @@ { "cell_type": "code", "execution_count": 3, - "id": "05e29cbc", "metadata": {}, "outputs": [], "source": [ @@ -123,7 +115,6 @@ }, { "cell_type": "markdown", - "id": "f42f7ee6", "metadata": {}, "source": [ "Since we are working with a single batch of data, we can initialize the input dictionary for the motion planner with some tensors that will be throughout this example. As a reminder, the input dictionary associates `th.Variable` names in the `TheseusLayer` with tensor values for each of them." @@ -132,7 +123,6 @@ { "cell_type": "code", "execution_count": 4, - "id": "84d04f40", "metadata": {}, "outputs": [], "source": [ @@ -149,7 +139,6 @@ }, { "cell_type": "markdown", - "id": "6b4e8fb4", "metadata": {}, "source": [ "## 2. Imitation learning loop" @@ -157,7 +146,6 @@ }, { "cell_type": "markdown", - "id": "a6d5d240", "metadata": {}, "source": [ "### Overview" @@ -165,7 +153,6 @@ }, { "cell_type": "markdown", - "id": "6e7858a4", "metadata": {}, "source": [ "We consider the following imitation learning pipeline in this example (see Section 2.2):\n", @@ -180,7 +167,6 @@ }, { "cell_type": "markdown", - "id": "e193bdef", "metadata": {}, "source": [ "### 2.1. A basic initial trajectory model" @@ -188,7 +174,6 @@ }, { "cell_type": "markdown", - "id": "21597f90", "metadata": {}, "source": [ "The following cell creates a basic model for generating initial trajectories. This model takes as input a one hot representation of the map's ID and generates a trajectory between the map's start and goal positions. The output is a dictionary with keys mapping to variable names, and values mapping to initial values (tensors) for each of them that represent the resulting trajectory.\n", @@ -200,7 +185,6 @@ { "cell_type": "code", "execution_count": 5, - "id": "ec11a366", "metadata": {}, "outputs": [], "source": [ @@ -211,7 +195,6 @@ }, { "cell_type": "markdown", - "id": "890f327f", "metadata": {}, "source": [ "### 2.2. Learning loop" @@ -219,7 +202,6 @@ }, { "cell_type": "markdown", - "id": "baf41709", "metadata": {}, "source": [ "With the model in place, we can now put all of this together to differentiate through the motion planner, and find good initial trajectories for optimization on two maps. This loop essentially follows steps 1-4 from the overview subsection." @@ -228,7 +210,6 @@ { "cell_type": "code", "execution_count": 6, - "id": "1a2c32a2", "metadata": { "scrolled": true }, @@ -315,7 +296,6 @@ { "cell_type": "code", "execution_count": 7, - "id": "9c242230", "metadata": {}, "outputs": [ { @@ -339,7 +319,6 @@ }, { "cell_type": "markdown", - "id": "ba844fd9", "metadata": {}, "source": [ "## 3. Results" @@ -347,7 +326,6 @@ }, { "cell_type": "markdown", - "id": "3467b83d", "metadata": {}, "source": [ "Let's now visualize the trajectories produced using the learned initializations, running the optimizer for a few more iterations. The following functions will be useful to plot the trajectories from the variable value dictionaries." @@ -356,7 +334,6 @@ { "cell_type": "code", "execution_count": 8, - "id": "d4c9b5e2", "metadata": {}, "outputs": [], "source": [ @@ -394,7 +371,6 @@ }, { "cell_type": "markdown", - "id": "cdece815", "metadata": {}, "source": [ "### 3.1. Trajectories initialized from straight lines" @@ -402,7 +378,6 @@ }, { "cell_type": "markdown", - "id": "d8acbdc6", "metadata": {}, "source": [ "As reference, below we show the quality of trajectories obtained after 10 optimizer iterations when initialized from a straight line. As the plots show, the trajectories produced from a straight line are of bad quality; more than 10 iterations are neeed to produce good quality trajectories (in part 1, we used 50). " @@ -411,12 +386,11 @@ { "cell_type": "code", "execution_count": 9, - "id": "0de3204f", "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -426,7 +400,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -453,7 +427,6 @@ }, { "cell_type": "markdown", - "id": "f93335fb", "metadata": {}, "source": [ "### 3.2 Learned initial trajectories" @@ -461,7 +434,6 @@ }, { "cell_type": "markdown", - "id": "3a5e96a1", "metadata": {}, "source": [ "On the other hand, with learned initial trajectories the plots below show 10 iterations is enough to produce smooth trajectories that avoid all obstacles, illustrating the potential of differentiating through the trajectories planner.trj" @@ -470,12 +442,11 @@ { "cell_type": "code", "execution_count": 10, - "id": "b34967ba", "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -485,7 +456,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] From c1fbf7de69799acbcf6a0c89b15b959cf0e6788c Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Wed, 24 Aug 2022 10:37:17 -0400 Subject: [PATCH 11/38] Added a script for building wheels on a new docker image. (#257) * Added a script for building theseus on a new docker image. * Add missing newline. * Fixed dockerfile generation to work with other CUDA versions. * Changed build script to pass CUDA version as an arg, and added option for CPU-only. * Changed build script to get tar.gz sources and added also default CUDA version naming. * Replaced theseus-ai by theseus-opt. --- build_scripts/build_wheel.sh | 80 +++++++++++++++++++++++++++++++++ docs/source/getting-started.rst | 2 +- setup.py | 2 +- 3 files changed, 82 insertions(+), 2 deletions(-) create mode 100755 build_scripts/build_wheel.sh diff --git a/build_scripts/build_wheel.sh b/build_scripts/build_wheel.sh new file mode 100755 index 000000000..6079894eb --- /dev/null +++ b/build_scripts/build_wheel.sh @@ -0,0 +1,80 @@ +#bin/bash + +# Ensure that 2 arguments (ROOT_DIR, TAG, CUDA_VERSION) are provided +die () { + echo >&2 "$@" + exit 1 +} +[ "$#" -eq 3 ] || die "3 arguments required, $# provided" +ROOT_DIR=$1 +TAG=$2 +CUDA_VERSION=$3 + +CUDA_VERSION_SUPPORTED=$(echo "cpu 10.2 11.3 11.6" | grep -w ${CUDA_VERSION}) +[ "${CUDA_VERSION_SUPPORTED}" ] || die "CUDA_VERSION must be one of (cpu, 10.2, 11.3, 11.6)" + + +CUDA_SUFFIX=$(echo ${CUDA_VERSION} | sed 's/[.]//g') + +if [[ ${CUDA_VERSION} == "cpu" ]] +then + DEVICE_TAG=cpu + IMAGE_NAME="pytorch/manylinux-cuda102" + GPU_ARGS="" +else + DEVICE_TAG="cu${CUDA_SUFFIX}" + IMAGE_NAME="pytorch/manylinux-cuda${CUDA_SUFFIX}" + GPU_ARGS=" --gpus all" +fi + +for PYTHON_VERSION in 3.9; do + # Create dockerfile to build in manylinux container + DOCKER_DIR=${ROOT_DIR}/docker_${PYTHON_VERSION} + mkdir -p ${DOCKER_DIR} + echo """FROM ${IMAGE_NAME} + ENV CONDA_DIR /opt/conda + RUN wget --quiet https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda.sh && \ + /bin/bash ~/miniconda.sh -b -p /opt/conda + ENV PATH \$CONDA_DIR/bin:\$PATH + RUN conda create --name theseus python=${PYTHON_VERSION} + RUN source activate theseus + RUN which python + ENV CUDA_HOME /usr/local/cuda-${CUDA_VERSION} + RUN pip install torch --extra-index-url https://download.pytorch.org/whl/${DEVICE_TAG} + RUN conda install -c conda-forge suitesparse + RUN pip install build wheel + RUN git clone https://github.com/facebookresearch/theseus.git + WORKDIR theseus + RUN git checkout ${TAG} -b tmp_build + CMD python3 -m build --no-isolation + """ > ${DOCKER_DIR}/Dockerfile + + # Run the container + cd ${DOCKER_DIR} + echo $(pwd) + DOCKER_NAME=theseus_${PYTHON_VERSION} + sudo docker build -t "${DOCKER_NAME}_img" . + sudo docker run${GPU_ARGS} --name ${DOCKER_NAME} ${DOCKER_NAME}_img + + # Copy the wheel to host + CP_STR="cp"$(echo ${PYTHON_VERSION} | sed 's/[.]//g') + if [[ ${CUDA_VERSION} == "cpu" ]] + then + DOCKER_WHL="theseus/dist/theseus_opt-${TAG}-py3-none-any.whl" + HOST_WHL="theseus_opt-${TAG}-py3-none-any.whl" + else + DOCKER_WHL="theseus/dist/theseus_opt-${TAG}-${CP_STR}-${CP_STR}-linux_x86_64.whl" + if [[ ${CUDA_VERSION} == "10.2" ]] + then + PLUS_CU_TAG="" # 10.2 will be the pypi version, so don't add +cu102 + else + PLUS_CU_TAG="+${DEVICE_TAG}" + fi + HOST_WHL="theseus_ai-${TAG}${PLUS_CU_TAG}-${CP_STR}-${CP_STR}-manylinux_2_17_x86_64.whl" + fi + + sudo docker cp "${DOCKER_NAME}:theseus/dist/theseus-opt-${TAG}.tar.gz" "${DOCKER_DIR}/theseus-opt-${TAG}.tar.gz" + sudo docker cp "${DOCKER_NAME}:${DOCKER_WHL}" ${DOCKER_DIR}/${HOST_WHL} + sudo docker rm ${DOCKER_NAME} + sudo docker image rm "${DOCKER_NAME}_img" +done diff --git a/docs/source/getting-started.rst b/docs/source/getting-started.rst index 85d8255b9..042d40db1 100644 --- a/docs/source/getting-started.rst +++ b/docs/source/getting-started.rst @@ -17,7 +17,7 @@ Installing ^^^^^^^^^^ .. code-block:: bash - pip install theseus-ai + pip install theseus-opt If you are interested in contributing to ``theseus``, instead install diff --git a/setup.py b/setup.py index fbbb0550c..ccb6ab068 100644 --- a/setup.py +++ b/setup.py @@ -58,7 +58,7 @@ def parse_requirements_file(path): ext_modules = [] setuptools.setup( - name="theseus-ai", + name="theseus-opt", version=version, author="Meta Research", description="A library for differentiable nonlinear optimization.", From e96bb4f757254db823e4d4eea03fa33e1fc8e8fa Mon Sep 17 00:00:00 2001 From: Luiz Gustavo Hafemann Date: Wed, 24 Aug 2022 12:05:17 -0400 Subject: [PATCH 12/38] homography estimation - create data folder before downloading data (#275) Co-authored-by: Luiz Gustavo Hafemann --- examples/homography_estimation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index 5cb2441d4..c23208dc1 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -49,10 +49,10 @@ def prepare_data(): print("Downloading data") url_root = "http://ptak.felk.cvut.cz/revisitop/revisitop1m/jpg/" tar = "%s.tar.gz" % chunk + os.makedirs(dataset_path) cmd = "wget %s/%s -O %s/%s" % (url_root, tar, dataset_root, tar) print("Running command: ", cmd) os.system(cmd) - os.makedirs(dataset_path) cmd = "tar -xf %s/%s -C %s" % (dataset_root, tar, dataset_path) print("Running command: ", cmd) os.system(cmd) From cd1f1797dd5f2bd750d105b9cee14ba5e36e4ca4 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Wed, 24 Aug 2022 14:32:18 -0400 Subject: [PATCH 13/38] Added pip install theseus-ai instructions. (#276) * Added pip install theseus-ai instructions. * Fix typo and add instructions for build script. * Changed README images to see if they render properly in pypi. * Added pypi badge to README. * Added downloads counter to README. * Added more description to build_wheels.sh --- README.md | 27 +++++++++++++++++++++++++-- build_scripts/build_wheel.sh | 31 +++++++++++++++++++++++++------ docs/source/getting-started.rst | 22 +++++++++++++++++++--- setup.py | 2 +- 4 files changed, 70 insertions(+), 12 deletions(-) diff --git a/README.md b/README.md index 99da3a42f..b8f986555 100644 --- a/README.md +++ b/README.md @@ -1,21 +1,35 @@ -![Theseus Logo](https://raw.githubusercontent.com/facebookresearch/theseus/main/docs/source/img/theseus-color-horizontal.png) +![](https://raw.githubusercontent.com/facebookresearch/theseus/main/docs/source/img/theseus-color-horizontal.png)

+ CircleCI + License + + + pypi + + + PyPi Downloads + + Python + pre-commit + black + PRs @@ -35,7 +49,7 @@ Theseus is an efficient application-agnostic library for building custom nonlinear optimization layers in PyTorch to support constructing various problems in robotics and vision as end-to-end differentiable architectures. -TheseusLayer +![](https://raw.githubusercontent.com/facebookresearch/theseus/main/docs/source/img/theseuslayer.png) Differentiable nonlinear optimization provides a general scheme to encode inductive priors, as the objective function can be partly parameterized by neural models and partly with expert domain-specific differentiable models. The ability to compute gradients end-to-end is retained by differentiating through the optimizer which allows neural models to train on the final task loss, while also taking advantage of priors captured by the optimizer. @@ -72,6 +86,15 @@ We support several features that improve computation times and memory consumptio - `conda install -c conda-forge suitesparse` (Mac). ### Installing +#### **pypi** +```bash +pip install theseus-ai +``` +We currently provide wheels with our CUDA extensions compiled using CUDA 10.2 and Python 3.9. +For other CUDA versions, consider installing from source or using our +[build script](https://github.com/facebookresearch/theseus/blob/main/build_scripts/build_wheel.sh). + +#### **From source** ```bash git clone https://github.com/facebookresearch/theseus.git && cd theseus pip install -e . diff --git a/build_scripts/build_wheel.sh b/build_scripts/build_wheel.sh index 6079894eb..f594cb1e1 100755 --- a/build_scripts/build_wheel.sh +++ b/build_scripts/build_wheel.sh @@ -1,6 +1,25 @@ #bin/bash -# Ensure that 2 arguments (ROOT_DIR, TAG, CUDA_VERSION) are provided +# ----------------- +# This script creates and runs a docker image for compiling a wheel +# to install theseus. +# +# To use this script, from root theesus folder run +# ./build_scripts/build_wheel.sh ROOT_DIR TAG CUDA_VERSION +# +# ROOT_DIR: is the directory where the Dockerfile, tar.gz and .whl files will be stored +# (under a new subdirectory named theseus_docker_3.9) +# TAG: is a theseus tag (e.g., 0.1.0) +# CUDA_VERSION: the version of CUDA to use. We have tested 10.2, 11.3, and 11.6. +# You can also pass "cpu" to compile without CUDA extensions. +# +# For example +# ./build_scripts/build_wheel.sh . 0.1.0 10.2 +# +# will run and store results under ./theseus_docker_3.9 +# ----------------- + +# Ensure that 3 arguments (ROOT_DIR, TAG, CUDA_VERSION) are provided die () { echo >&2 "$@" exit 1 @@ -29,7 +48,7 @@ fi for PYTHON_VERSION in 3.9; do # Create dockerfile to build in manylinux container - DOCKER_DIR=${ROOT_DIR}/docker_${PYTHON_VERSION} + DOCKER_DIR=${ROOT_DIR}/theseus_docker_${PYTHON_VERSION} mkdir -p ${DOCKER_DIR} echo """FROM ${IMAGE_NAME} ENV CONDA_DIR /opt/conda @@ -60,10 +79,10 @@ for PYTHON_VERSION in 3.9; do CP_STR="cp"$(echo ${PYTHON_VERSION} | sed 's/[.]//g') if [[ ${CUDA_VERSION} == "cpu" ]] then - DOCKER_WHL="theseus/dist/theseus_opt-${TAG}-py3-none-any.whl" - HOST_WHL="theseus_opt-${TAG}-py3-none-any.whl" + DOCKER_WHL="theseus/dist/theseus_ai-${TAG}-py3-none-any.whl" + HOST_WHL="theseus_ai-${TAG}-py3-none-any.whl" else - DOCKER_WHL="theseus/dist/theseus_opt-${TAG}-${CP_STR}-${CP_STR}-linux_x86_64.whl" + DOCKER_WHL="theseus/dist/theseus_ai-${TAG}-${CP_STR}-${CP_STR}-linux_x86_64.whl" if [[ ${CUDA_VERSION} == "10.2" ]] then PLUS_CU_TAG="" # 10.2 will be the pypi version, so don't add +cu102 @@ -73,7 +92,7 @@ for PYTHON_VERSION in 3.9; do HOST_WHL="theseus_ai-${TAG}${PLUS_CU_TAG}-${CP_STR}-${CP_STR}-manylinux_2_17_x86_64.whl" fi - sudo docker cp "${DOCKER_NAME}:theseus/dist/theseus-opt-${TAG}.tar.gz" "${DOCKER_DIR}/theseus-opt-${TAG}.tar.gz" + sudo docker cp "${DOCKER_NAME}:theseus/dist/theseus-ai-${TAG}.tar.gz" "${DOCKER_DIR}/theseus-ai-${TAG}.tar.gz" sudo docker cp "${DOCKER_NAME}:${DOCKER_WHL}" ${DOCKER_DIR}/${HOST_WHL} sudo docker rm ${DOCKER_NAME} sudo docker image rm "${DOCKER_NAME}_img" diff --git a/docs/source/getting-started.rst b/docs/source/getting-started.rst index 042d40db1..aff03556e 100644 --- a/docs/source/getting-started.rst +++ b/docs/source/getting-started.rst @@ -15,18 +15,34 @@ Prerequisites Installing ^^^^^^^^^^ + +pypi +"""" + .. code-block:: bash - pip install theseus-opt + pip install theseus-ai + +We currently provide wheels with our CUDA extensions compiled using CUDA 10.2 and Python 3.9. +For other CUDA versions, consider installing from source or using our +`build script `_. -If you are interested in contributing to ``theseus``, instead install +From source +""""""""""" +To install from source code, you can use .. code-block:: bash git clone https://github.com/facebookresearch/theseus.git - pip install -e ".[dev]" + pip install -e . python -m pytest theseus +If you are interested in contributing to ``theseus``, instead install using + +.. code-block:: bash + + pip install -e ".[dev]" + and follow the more detailed instructions in `CONTRIBUTING `_. By default, unit tests include tests for our CUDA extensions. You can add the option ``-m "not cudaext"`` to diff --git a/setup.py b/setup.py index ccb6ab068..fbbb0550c 100644 --- a/setup.py +++ b/setup.py @@ -58,7 +58,7 @@ def parse_requirements_file(path): ext_modules = [] setuptools.setup( - name="theseus-opt", + name="theseus-ai", version=version, author="Meta Research", description="A library for differentiable nonlinear optimization.", From 73c5b3288b1e3d1a36ed7c5b8d3fc28a4795fc1a Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Fri, 26 Aug 2022 11:46:45 -0400 Subject: [PATCH 14/38] Refactored MotionPlanner so that objective can be passed separately. (#277) * Refactored MotionPlanner so that objective can be passed separately. * Made MotionPlannerObjective accessible from theseus.utils.examples. * Removed irrelevant text from notebooks. --- examples/motion_planning_2d.py | 14 +-- theseus/utils/examples/__init__.py | 1 + .../examples/motion_planning/__init__.py | 2 +- .../utils/examples/motion_planning/models.py | 6 +- .../motion_planning/motion_planner.py | 112 ++++++++++++------ tutorials/04_motion_planning.ipynb | 48 +++++++- .../05_differentiable_motion_planning.ipynb | 37 +++++- 7 files changed, 167 insertions(+), 53 deletions(-) diff --git a/examples/motion_planning_2d.py b/examples/motion_planning_2d.py index c781454df..1e97e4d69 100644 --- a/examples/motion_planning_2d.py +++ b/examples/motion_planning_2d.py @@ -69,15 +69,15 @@ def run_learning_loop(cfg): ) motion_planner = theg.MotionPlanner( - cfg.img_size, - cfg.obs_params.safety_dist + cfg.robot_radius, - cfg.total_time, - cfg.obs_params.weight, - cfg.gp_params.Qc_inv, - cfg.num_time_steps, cfg.optim_params.method, cfg.optim_params.max_iters, - cfg.optim_params.step_size, + step_size=cfg.optim_params.step_size, + map_size=cfg.img_size, + epsilon_dist=cfg.obs_params.safety_dist + cfg.robot_radius, + total_time=cfg.total_time, + collision_weight=cfg.obs_params.weight, + Qc_inv=cfg.gp_params.Qc_inv, + num_time_steps=cfg.num_time_steps, use_single_collision_weight=True, device=cfg.device, ) diff --git a/theseus/utils/examples/__init__.py b/theseus/utils/examples/__init__.py index 96a81d661..6e3a14468 100644 --- a/theseus/utils/examples/__init__.py +++ b/theseus/utils/examples/__init__.py @@ -10,6 +10,7 @@ from .motion_planning import ( InitialTrajectoryModel, MotionPlanner, + MotionPlannerObjective, ScalarCollisionWeightAndCostEpstModel, ScalarCollisionWeightModel, TrajectoryDataset, diff --git a/theseus/utils/examples/motion_planning/__init__.py b/theseus/utils/examples/motion_planning/__init__.py index a40e1366c..a523092ab 100644 --- a/theseus/utils/examples/motion_planning/__init__.py +++ b/theseus/utils/examples/motion_planning/__init__.py @@ -9,4 +9,4 @@ ScalarCollisionWeightAndCostEpstModel, ScalarCollisionWeightModel, ) -from .motion_planner import MotionPlanner +from .motion_planner import MotionPlanner, MotionPlannerObjective diff --git a/theseus/utils/examples/motion_planning/models.py b/theseus/utils/examples/motion_planning/models.py index 5d3ecf99d..46c2823a6 100644 --- a/theseus/utils/examples/motion_planning/models.py +++ b/theseus/utils/examples/motion_planning/models.py @@ -121,7 +121,7 @@ def __init__( nn.ReLU(), nn.Linear(hid_size, hid_size), nn.ReLU(), - nn.Linear(hid_size, 4 * (planner.num_time_steps + 1)), + nn.Linear(hid_size, 4 * (planner.objective.num_time_steps + 1)), ) # Learns a quadratic offset in normal direction to bend the mean trajectory. @@ -141,7 +141,7 @@ def init_weights(m_): self.bend_factor.apply(init_weights) - self.dt = planner.total_time / planner.num_time_steps + self.dt = planner.objective.total_time / planner.objective.num_time_steps self.num_images = max_num_images @@ -157,7 +157,7 @@ def forward(self, batch: Dict[str, Any]): one_hot_dummy[batch_idx, idx] = 1 # Compute straight line positions to use as mean of initial trajectory - trajectory_len = self.aux_motion_planner.trajectory_len + trajectory_len = self.aux_motion_planner.objective.trajectory_len dist_vec = goal - start pos_incr_per_step = dist_vec / (trajectory_len - 1) trajectory = torch.zeros(start.shape[0], 4 * trajectory_len).to( diff --git a/theseus/utils/examples/motion_planning/motion_planner.py b/theseus/utils/examples/motion_planning/motion_planner.py index e9477c106..08ff9b45c 100644 --- a/theseus/utils/examples/motion_planning/motion_planner.py +++ b/theseus/utils/examples/motion_planning/motion_planner.py @@ -11,7 +11,7 @@ import theseus as th -class MotionPlanner: +class MotionPlannerObjective(th.Objective): def __init__( self, map_size: int, @@ -20,25 +20,27 @@ def __init__( collision_weight: float, Qc_inv: List[List[int]], num_time_steps: int, - optim_method: str, - max_optim_iters: int, - step_size: float = 1.0, use_single_collision_weight: bool = True, - device: str = "cpu", dtype: torch.dtype = torch.double, ): + for v in [ + map_size, + epsilon_dist, + total_time, + collision_weight, + Qc_inv, + num_time_steps, + ]: + assert v is not None + + super().__init__(dtype=dtype) self.map_size = map_size self.epsilon_dist = epsilon_dist self.total_time = total_time self.collision_weight = collision_weight self.Qc_inv = copy.deepcopy(Qc_inv) self.num_time_steps = num_time_steps - self.optim_method = optim_method - self.max_optim_iters = max_optim_iters - self.step_size = step_size self.use_single_collision_weight = use_single_collision_weight - self.device = device - self.dtype = dtype self.trajectory_len = num_time_steps + 1 @@ -112,16 +114,13 @@ def __init__( # --------------------------------------------------------------------------- # # ------------------------------ Cost functions ----------------------------- # # --------------------------------------------------------------------------- # - # Create a Theseus objective for adding the cost functions - objective = th.Objective(dtype=self.dtype) - # First create the cost functions for the end point positions and velocities # which are hard constraints, and can be implemented via Difference cost # functions. - objective.add( + self.add( th.Difference(poses[0], start_point, boundary_cost_weight, name="pose_0") ) - objective.add( + self.add( th.Difference( velocities[0], th.Point2(tensor=torch.zeros(1, 2, dtype=dtype)), @@ -129,10 +128,10 @@ def __init__( name="vel_0", ) ) - objective.add( + self.add( th.Difference(poses[-1], goal_point, boundary_cost_weight, name="pose_N") ) - objective.add( + self.add( th.Difference( velocities[-1], th.Point2(tensor=torch.zeros(1, 2, dtype=dtype)), @@ -145,7 +144,7 @@ def __init__( # cost weights created above. We need a separate cost function for each time # step for i in range(1, self.trajectory_len): - objective.add( + self.add( th.eb.Collision2D( poses[i], sdf_origin, @@ -158,7 +157,7 @@ def __init__( name=f"collision_{i}", ) ) - objective.add( + self.add( ( th.eb.GPMotionModel( poses[i - 1], @@ -172,25 +171,64 @@ def __init__( ) ) + +class MotionPlanner: + # If objective is given, this overrides problem arguments + def __init__( + self, + optim_method: str, + max_optim_iters: int, + step_size: float = 1.0, + objective: Optional[MotionPlannerObjective] = None, + device: str = "cpu", + dtype: torch.dtype = torch.double, + # The following are only used if objective is None + map_size: Optional[int] = None, + epsilon_dist: Optional[float] = None, + total_time: Optional[float] = None, + collision_weight: Optional[float] = None, + Qc_inv: Optional[List[List[int]]] = None, + num_time_steps: Optional[int] = None, + use_single_collision_weight: bool = True, + ): + if objective is None: + self.objective = MotionPlannerObjective( + map_size, + epsilon_dist, + total_time, + collision_weight, + Qc_inv, + num_time_steps, + use_single_collision_weight=use_single_collision_weight, + dtype=dtype, + ) + else: + self.objective = objective + + self.optim_method = optim_method + self.max_optim_iters = max_optim_iters + self.step_size = step_size + self.device = device + self.dtype = dtype + # Finally, create the Nonlinear Least Squares optimizer for this objective # and wrap both into a TheseusLayer optimizer: th.NonlinearLeastSquares if optim_method == "gauss_newton": optimizer = th.GaussNewton( - objective, + self.objective, th.CholeskyDenseSolver, max_iterations=max_optim_iters, step_size=step_size, ) elif optim_method == "levenberg_marquardt": optimizer = th.LevenbergMarquardt( - objective, + self.objective, th.CholeskyDenseSolver, max_iterations=max_optim_iters, step_size=step_size, ) - self.objective = objective self.layer = th.TheseusLayer(optimizer) self.layer.to(device=device, dtype=dtype) @@ -249,10 +287,10 @@ def get_variable_values_from_straight_line( # Returns a dictionary of variable names to values that represent a straight # line trajectory from start to goal. start_goal_dist = goal - start - avg_vel = start_goal_dist / self.total_time - unit_trajectory_len = start_goal_dist / (self.trajectory_len - 1) + avg_vel = start_goal_dist / self.objective.total_time + unit_trajectory_len = start_goal_dist / (self.objective.trajectory_len - 1) input_dict: Dict[str, torch.Tensor] = {} - for i in range(self.trajectory_len): + for i in range(self.objective.trajectory_len): input_dict[f"pose_{i}"] = start + unit_trajectory_len * i input_dict[f"vel_{i}"] = avg_vel return input_dict @@ -262,7 +300,7 @@ def get_random_variable_values( ) -> Dict[str, torch.Tensor]: # Returns a dictionary of variable names with random initial poses. input_dict: Dict[str, torch.Tensor] = {} - for i in range(self.trajectory_len): + for i in range(self.objective.trajectory_len): input_dict[f"pose_{i}"] = torch.randn_like(start) input_dict[f"vel_{i}"] = torch.randn_like(start) return input_dict @@ -273,9 +311,9 @@ def get_variable_values_from_trajectory( # Returns a dictionary of variable names to values, so that values # are assigned with the data from the given trajectory. Trajectory should be a # tensor of shape (batch_size, 4, planner.trajectory_len). - assert trajectory.shape[1:] == (4, self.trajectory_len) + assert trajectory.shape[1:] == (4, self.objective.trajectory_len) input_dict: Dict[str, torch.Tensor] = {} - for i in range(self.trajectory_len): + for i in range(self.objective.trajectory_len): input_dict[f"pose_{i}"] = trajectory[:, :2, i] input_dict[f"vel_{i}"] = trajectory[:, :2, i] return input_dict @@ -296,11 +334,11 @@ def get_trajectory( trajectory = torch.empty( self.objective.batch_size, 4, - self.trajectory_len, + self.objective.trajectory_len, device=self.objective.device, ) variables = self.objective.optim_vars - for i in range(self.trajectory_len): + for i in range(self.objective.trajectory_len): if values_dict is None: trajectory[:, :2, i] = variables[f"pose_{i}"].tensor.clone() trajectory[:, 2:, i] = variables[f"vel_{i}"].tensor.clone() @@ -321,16 +359,16 @@ def get_total_squared_errors(self) -> Tuple[torch.Tensor, torch.Tensor]: def copy(self, collision_weight: Optional[float] = None) -> "MotionPlanner": return MotionPlanner( - self.map_size, - self.epsilon_dist, - self.total_time, - collision_weight or self.collision_weight, - self.Qc_inv, - self.num_time_steps, self.optim_method, self.max_optim_iters, step_size=self.step_size, - use_single_collision_weight=self.use_single_collision_weight, + map_size=self.objective.map_size, + epsilon_dist=self.objective.epsilon_dist, + total_time=self.objective.total_time, + collision_weight=collision_weight or self.objective.collision_weight, + Qc_inv=self.objective.Qc_inv, + num_time_steps=self.objective.num_time_steps, + use_single_collision_weight=self.objective.use_single_collision_weight, device=self.device, dtype=self.dtype, ) diff --git a/tutorials/04_motion_planning.ipynb b/tutorials/04_motion_planning.ipynb index 96059c559..773b4a168 100644 --- a/tutorials/04_motion_planning.ipynb +++ b/tutorials/04_motion_planning.ipynb @@ -2,6 +2,7 @@ "cells": [ { "cell_type": "markdown", + "id": "193353d2", "metadata": {}, "source": [ "# Motion Planning Part 1: motion planning as nonlinear least squares optimization" @@ -9,6 +10,7 @@ }, { "cell_type": "markdown", + "id": "8e64a306", "metadata": {}, "source": [ "In this tutorial, we will learn how to implement the [GPMP2](https://journals.sagepub.com/doi/pdf/10.1177/0278364918790369) (Mukadam et al, 2018) motion planning algorithm, for a 2D robot in a planar environment.\n", @@ -22,6 +24,7 @@ { "cell_type": "code", "execution_count": 1, + "id": "51ef8453", "metadata": {}, "outputs": [], "source": [ @@ -52,6 +55,7 @@ }, { "cell_type": "markdown", + "id": "77448aa6", "metadata": {}, "source": [ "## 1. Loading and visualizing the trajectory data" @@ -59,6 +63,7 @@ }, { "cell_type": "markdown", + "id": "f94fbf89", "metadata": {}, "source": [ "First, let's load some motion planning problems from a dataset of maps and trajectories generated using the code in [dgpmp2](https://github.com/mhmukadam/dgpmp2)." @@ -67,6 +72,7 @@ { "cell_type": "code", "execution_count": 2, + "id": "2e3714cd", "metadata": {}, "outputs": [], "source": [ @@ -79,6 +85,7 @@ }, { "cell_type": "markdown", + "id": "b35c0497", "metadata": {}, "source": [ "The batch is a dictionary of strings to `torch.Tensor` containing the following keys:" @@ -87,6 +94,7 @@ { "cell_type": "code", "execution_count": 3, + "id": "6554376a", "metadata": {}, "outputs": [ { @@ -109,6 +117,7 @@ }, { "cell_type": "markdown", + "id": "6dde2d5b", "metadata": {}, "source": [ "Let's plot the maps and trajectories loaded. `th.eb.SignedDistanceField2D` is a signed distance field object, which includes a function to convert *x,y*-coordinates to map cells that we use here for plotting. For completeness, we show the expert trajectories loaded, although we won't use them in this example (we will do so in Part 2 of this tutorial). We also illustrate the signed distance field for each map." @@ -117,6 +126,7 @@ { "cell_type": "code", "execution_count": 4, + "id": "bb5975da", "metadata": { "scrolled": false }, @@ -164,6 +174,7 @@ }, { "cell_type": "markdown", + "id": "12c8250b", "metadata": {}, "source": [ "The following are some constants that we will use throughout the example" @@ -172,6 +183,7 @@ { "cell_type": "code", "execution_count": 5, + "id": "3fc8c4ba", "metadata": {}, "outputs": [], "source": [ @@ -189,6 +201,7 @@ }, { "cell_type": "markdown", + "id": "53ee210f", "metadata": {}, "source": [ "## 2. Modeling the problem" @@ -196,6 +209,7 @@ }, { "cell_type": "markdown", + "id": "59f8e07e", "metadata": {}, "source": [ "### 2.1. Defining Variable objects" @@ -203,6 +217,7 @@ }, { "cell_type": "markdown", + "id": "58e3d84f", "metadata": {}, "source": [ "Our goal in this example will be to use `Theseus` to produce plans for the maps loaded above. As mentioned in the introduction, we need a 2D pose and a 2D velocity for each point along the trajectory to be optimized. For this, we will create a set of `th.Point2` variables with individual names, and store them in two lists so that they can be later passed to the appropriate cost functions." @@ -211,6 +226,7 @@ { "cell_type": "code", "execution_count": 6, + "id": "f97f35b9", "metadata": {}, "outputs": [], "source": [ @@ -224,6 +240,7 @@ }, { "cell_type": "markdown", + "id": "883e4cb4", "metadata": {}, "source": [ "In addition to the optimization variables, we will also need a set of *auxiliary* variables to wrap map-dependent quantities involved in cost function computation, but that are constant throughout the optimization. This includes start/goal target values, as well as parameters for collision and dynamics cost functions." @@ -232,6 +249,7 @@ { "cell_type": "code", "execution_count": 7, + "id": "f4576658", "metadata": {}, "outputs": [], "source": [ @@ -251,6 +269,7 @@ }, { "cell_type": "markdown", + "id": "4507e8ec", "metadata": {}, "source": [ "### 2.2. Cost weights" @@ -258,6 +277,7 @@ }, { "cell_type": "markdown", + "id": "825fef77", "metadata": {}, "source": [ "Next we will create a series of cost weights to use for each of the cost functions involved in our optimization problem." @@ -266,6 +286,7 @@ { "cell_type": "code", "execution_count": 8, + "id": "ae4c2c9b", "metadata": {}, "outputs": [], "source": [ @@ -282,6 +303,7 @@ }, { "cell_type": "markdown", + "id": "b4eabdb8", "metadata": {}, "source": [ "### 2.3. Cost functions" @@ -289,6 +311,7 @@ }, { "cell_type": "markdown", + "id": "f7053e1b", "metadata": {}, "source": [ "In this section, we will now create a `Theseus` objective and add the GPMP2 cost functions for motion planning. First, we create the objective:" @@ -297,6 +320,7 @@ { "cell_type": "code", "execution_count": 9, + "id": "0569732d", "metadata": {}, "outputs": [], "source": [ @@ -305,6 +329,7 @@ }, { "cell_type": "markdown", + "id": "d2feb2bc", "metadata": {}, "source": [ "#### Boundary cost functions" @@ -312,6 +337,7 @@ }, { "cell_type": "markdown", + "id": "050b43d9", "metadata": {}, "source": [ "Here we create cost functions for the boundary conditions, assign names to them, and add them to the `Objective`. For boundaries, we need four cost functions, and for each we use a cost function of type `th.Difference`. This cost function type takes as input an optimization variable, a cost weight, a target auxiliary variable, and a name. Its error function is the local difference between the optimization variable and the target.\n", @@ -324,6 +350,7 @@ { "cell_type": "code", "execution_count": 10, + "id": "e308ad0b", "metadata": {}, "outputs": [], "source": [ @@ -357,6 +384,7 @@ }, { "cell_type": "markdown", + "id": "696f499d", "metadata": {}, "source": [ "#### Collision cost functions" @@ -364,6 +392,7 @@ }, { "cell_type": "markdown", + "id": "8c202611", "metadata": {}, "source": [ "For collision avoidance, we use a `th.eb.Collision2D` cost function type, which receives the following inputs:\n", @@ -380,6 +409,7 @@ { "cell_type": "code", "execution_count": 11, + "id": "ced3a7cf", "metadata": {}, "outputs": [], "source": [ @@ -399,6 +429,7 @@ }, { "cell_type": "markdown", + "id": "da09bdd7", "metadata": {}, "source": [ "#### GP-dynamics cost functions" @@ -406,6 +437,7 @@ }, { "cell_type": "markdown", + "id": "e84a8ab9", "metadata": {}, "source": [ "For ensuring smooth trajectories, we use a `th.eb.GPMotionModel` cost function, which receives the following inputs:\n", @@ -420,6 +452,7 @@ { "cell_type": "code", "execution_count": 12, + "id": "1753ad16", "metadata": {}, "outputs": [], "source": [ @@ -441,6 +474,7 @@ }, { "cell_type": "markdown", + "id": "64fc08ba", "metadata": {}, "source": [ "## Creating the TheseusLayer for motion planning" @@ -448,6 +482,7 @@ }, { "cell_type": "markdown", + "id": "e97885ff", "metadata": {}, "source": [ "For this example, we will use Levenberg-Marquardt as the non-linear optimizer, coupled with a dense linear solver based on Cholesky decomposition." @@ -456,6 +491,7 @@ { "cell_type": "code", "execution_count": 13, + "id": "cd90fe97", "metadata": {}, "outputs": [], "source": [ @@ -471,6 +507,7 @@ }, { "cell_type": "markdown", + "id": "2e8faa3b", "metadata": {}, "source": [ "## 3. Running the optimizer" @@ -478,6 +515,7 @@ }, { "cell_type": "markdown", + "id": "95e0c8a9", "metadata": {}, "source": [ "Finally, we are ready to generate some optimal plans. We first initialize all auxiliary variables whose values are map dependent (e.g., start and goal positions, or SDF data). We also provide some sensible initial values for the optimization variables; in this example, we will initialize the optimizaton variables to be on a straight line from start to goal. The following helper function will be useful for this:" @@ -486,6 +524,7 @@ { "cell_type": "code", "execution_count": 14, + "id": "f6ba7b47", "metadata": {}, "outputs": [], "source": [ @@ -507,6 +546,7 @@ }, { "cell_type": "markdown", + "id": "fd2ce0cb", "metadata": {}, "source": [ "Now, let's pass the motion planning data to our `TheseusLayer` and start create some trajectories; note that we can solve for both trajectories simultaneously by taking advantage of Theseus' batch support. For initializing variables, we create a dictionary mapping strings to `torch.Tensor`, where the keys are `th.Variable` names, and the values are the tensors that should be used for their initial values. " @@ -515,6 +555,7 @@ { "cell_type": "code", "execution_count": 15, + "id": "e9282313", "metadata": { "scrolled": false }, @@ -601,6 +642,7 @@ }, { "cell_type": "markdown", + "id": "3cdefe87", "metadata": {}, "source": [ "## 4. Results" @@ -608,6 +650,7 @@ }, { "cell_type": "markdown", + "id": "3f3297b9", "metadata": {}, "source": [ "After the optimization is completed, we can query the optimization variables to obtain the final trajectory and visualize the result. The following function creates a trajectory tensor from the output dictionary of `TheseusLayer`." @@ -616,6 +659,7 @@ { "cell_type": "code", "execution_count": 16, + "id": "bbc60e10", "metadata": {}, "outputs": [], "source": [ @@ -629,6 +673,7 @@ }, { "cell_type": "markdown", + "id": "bc0b850f", "metadata": {}, "source": [ "Let's now plot the final trajectories" @@ -637,6 +682,7 @@ { "cell_type": "code", "execution_count": 17, + "id": "1cca481d", "metadata": {}, "outputs": [ { @@ -687,7 +733,7 @@ "hash": "3095d307436ac388e461a5585c0eeaa747818d9658111384e6a455f40a311fed" }, "kernelspec": { - "display_name": "Theseus", + "display_name": "theseus_test", "language": "python", "name": "theseus_test" }, diff --git a/tutorials/05_differentiable_motion_planning.ipynb b/tutorials/05_differentiable_motion_planning.ipynb index 38da61568..54477ed1c 100644 --- a/tutorials/05_differentiable_motion_planning.ipynb +++ b/tutorials/05_differentiable_motion_planning.ipynb @@ -2,6 +2,7 @@ "cells": [ { "cell_type": "markdown", + "id": "60aa3d02", "metadata": {}, "source": [ "# Motion Planning Part 2: differentiable motion planning" @@ -9,6 +10,7 @@ }, { "cell_type": "markdown", + "id": "aa934017", "metadata": {}, "source": [ "In this tutorial, we will build on the [first part](https://github.com/facebookresearch/theseus/blob/main/tutorials/04_motion_planning.ipynb) of the motion planning tutorial to illustrate how we can differentiate through a motion planner implemented using `Theseus`. In particular, we will show how to set up an imitation learning loop in `torch` to produce values to initialize the `TheseusLayer` so that it converges to a high quality trajectory faster. If you haven't already, we encourage you to review part 1 of the motion planning tutorial before proceeding with this one." @@ -17,6 +19,7 @@ { "cell_type": "code", "execution_count": 1, + "id": "48c45eca", "metadata": {}, "outputs": [], "source": [ @@ -49,6 +52,7 @@ }, { "cell_type": "markdown", + "id": "cf59cfe0", "metadata": {}, "source": [ "## 1. Initial setup" @@ -56,6 +60,7 @@ }, { "cell_type": "markdown", + "id": "3dc2f1c4", "metadata": {}, "source": [ "As in part 1 of the motion planning tutorial, the first step is to load a few planning problems from the dataset, and set up some constant quantities to use throughout the experiment. During this example, we will use a batch of 2 problems obtained from the loader." @@ -64,6 +69,7 @@ { "cell_type": "code", "execution_count": 2, + "id": "9b84cd4f", "metadata": {}, "outputs": [], "source": [ @@ -88,6 +94,7 @@ }, { "cell_type": "markdown", + "id": "78748281", "metadata": {}, "source": [ "Next we create the motion planner. Class `theg.MotionPlanner` stores a `TheseusLayer` constructed by following the steps described in part 1, and also provides some useful utility functions to retrieve trajectories from the current variables of the optimizer. " @@ -96,25 +103,27 @@ { "cell_type": "code", "execution_count": 3, + "id": "18df83c7", "metadata": {}, "outputs": [], "source": [ "planner = theg.MotionPlanner(\n", + " optim_method=\"levenberg_marquardt\",\n", + " max_optim_iters=2,\n", + " step_size=0.3,\n", " map_size=map_size,\n", " epsilon_dist=safety_distance + robot_radius,\n", " total_time=total_time,\n", " collision_weight=collision_w,\n", " Qc_inv=Qc_inv,\n", " num_time_steps=num_time_steps,\n", - " optim_method=\"levenberg_marquardt\",\n", - " max_optim_iters=2,\n", - " step_size=0.3,\n", " device=device,\n", ")" ] }, { "cell_type": "markdown", + "id": "bc1c70d5", "metadata": {}, "source": [ "Since we are working with a single batch of data, we can initialize the input dictionary for the motion planner with some tensors that will be throughout this example. As a reminder, the input dictionary associates `th.Variable` names in the `TheseusLayer` with tensor values for each of them." @@ -123,6 +132,7 @@ { "cell_type": "code", "execution_count": 4, + "id": "043cabb3", "metadata": {}, "outputs": [], "source": [ @@ -139,6 +149,7 @@ }, { "cell_type": "markdown", + "id": "8be6b791", "metadata": {}, "source": [ "## 2. Imitation learning loop" @@ -146,6 +157,7 @@ }, { "cell_type": "markdown", + "id": "76b3d870", "metadata": {}, "source": [ "### Overview" @@ -153,6 +165,7 @@ }, { "cell_type": "markdown", + "id": "ae4540b1", "metadata": {}, "source": [ "We consider the following imitation learning pipeline in this example (see Section 2.2):\n", @@ -167,6 +180,7 @@ }, { "cell_type": "markdown", + "id": "770b4363", "metadata": {}, "source": [ "### 2.1. A basic initial trajectory model" @@ -174,6 +188,7 @@ }, { "cell_type": "markdown", + "id": "4ccacafe", "metadata": {}, "source": [ "The following cell creates a basic model for generating initial trajectories. This model takes as input a one hot representation of the map's ID and generates a trajectory between the map's start and goal positions. The output is a dictionary with keys mapping to variable names, and values mapping to initial values (tensors) for each of them that represent the resulting trajectory.\n", @@ -185,6 +200,7 @@ { "cell_type": "code", "execution_count": 5, + "id": "6a692d27", "metadata": {}, "outputs": [], "source": [ @@ -195,6 +211,7 @@ }, { "cell_type": "markdown", + "id": "90c6d05e", "metadata": {}, "source": [ "### 2.2. Learning loop" @@ -202,6 +219,7 @@ }, { "cell_type": "markdown", + "id": "25e5aecb", "metadata": {}, "source": [ "With the model in place, we can now put all of this together to differentiate through the motion planner, and find good initial trajectories for optimization on two maps. This loop essentially follows steps 1-4 from the overview subsection." @@ -210,6 +228,7 @@ { "cell_type": "code", "execution_count": 6, + "id": "c1b3e571", "metadata": { "scrolled": true }, @@ -296,6 +315,7 @@ { "cell_type": "code", "execution_count": 7, + "id": "57089331", "metadata": {}, "outputs": [ { @@ -319,6 +339,7 @@ }, { "cell_type": "markdown", + "id": "20e807d3", "metadata": {}, "source": [ "## 3. Results" @@ -326,6 +347,7 @@ }, { "cell_type": "markdown", + "id": "0f458dfe", "metadata": {}, "source": [ "Let's now visualize the trajectories produced using the learned initializations, running the optimizer for a few more iterations. The following functions will be useful to plot the trajectories from the variable value dictionaries." @@ -334,6 +356,7 @@ { "cell_type": "code", "execution_count": 8, + "id": "67f560ef", "metadata": {}, "outputs": [], "source": [ @@ -371,6 +394,7 @@ }, { "cell_type": "markdown", + "id": "53dc8542", "metadata": {}, "source": [ "### 3.1. Trajectories initialized from straight lines" @@ -378,6 +402,7 @@ }, { "cell_type": "markdown", + "id": "92c597b5", "metadata": {}, "source": [ "As reference, below we show the quality of trajectories obtained after 10 optimizer iterations when initialized from a straight line. As the plots show, the trajectories produced from a straight line are of bad quality; more than 10 iterations are neeed to produce good quality trajectories (in part 1, we used 50). " @@ -386,6 +411,7 @@ { "cell_type": "code", "execution_count": 9, + "id": "2a078edf", "metadata": {}, "outputs": [ { @@ -427,6 +453,7 @@ }, { "cell_type": "markdown", + "id": "0fc1db3e", "metadata": {}, "source": [ "### 3.2 Learned initial trajectories" @@ -434,6 +461,7 @@ }, { "cell_type": "markdown", + "id": "e6fccfe1", "metadata": {}, "source": [ "On the other hand, with learned initial trajectories the plots below show 10 iterations is enough to produce smooth trajectories that avoid all obstacles, illustrating the potential of differentiating through the trajectories planner.trj" @@ -442,6 +470,7 @@ { "cell_type": "code", "execution_count": 10, + "id": "d2b95a5c", "metadata": {}, "outputs": [ { @@ -485,7 +514,7 @@ "hash": "79897f2dca37465f1a50ce007bdb1248c5125cbdf40b2afbe1ada0fadb4cca51" }, "kernelspec": { - "display_name": "Theseus", + "display_name": "theseus_test", "language": "python", "name": "theseus_test" }, From ad62822fdc25e05102a8894831b1a23d72fc23f0 Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Mon, 29 Aug 2022 14:02:34 -0400 Subject: [PATCH 15/38] add numel() to Manifold (#280) * add numel() to Manifold --- theseus/core/tests/common.py | 3 +++ theseus/core/tests/test_manifold.py | 3 +++ theseus/geometry/manifold.py | 3 +++ theseus/optimizer/tests/linearization_test_utils.py | 3 +++ 4 files changed, 12 insertions(+) diff --git a/theseus/core/tests/common.py b/theseus/core/tests/common.py index 2fc9b4288..2cfd579e1 100644 --- a/theseus/core/tests/common.py +++ b/theseus/core/tests/common.py @@ -29,6 +29,9 @@ def normalize(tensor: torch.Tensor) -> torch.Tensor: def dof(self): return 0 + def numel(self): + return 0 + def _local_impl(self, variable2): pass diff --git a/theseus/core/tests/test_manifold.py b/theseus/core/tests/test_manifold.py index d36f2956f..d844ca2d3 100644 --- a/theseus/core/tests/test_manifold.py +++ b/theseus/core/tests/test_manifold.py @@ -57,6 +57,9 @@ def normalize(tensor: torch.Tensor) -> torch.Tensor: def dof(self): return 0 + def numel(self): + return 0 + def _local_impl(self, variable2): pass diff --git a/theseus/geometry/manifold.py b/theseus/geometry/manifold.py index 884940e16..77550362d 100644 --- a/theseus/geometry/manifold.py +++ b/theseus/geometry/manifold.py @@ -64,6 +64,9 @@ def _init_tensor(*args: Any) -> torch.Tensor: def dof(self) -> int: pass + def numel(self) -> int: + return self.tensor[0].numel() + @abc.abstractmethod def _local_impl( self, variable2: "Manifold", jacobians: Optional[List[torch.Tensor]] = None diff --git a/theseus/optimizer/tests/linearization_test_utils.py b/theseus/optimizer/tests/linearization_test_utils.py index de6a83a26..8af1924ea 100644 --- a/theseus/optimizer/tests/linearization_test_utils.py +++ b/theseus/optimizer/tests/linearization_test_utils.py @@ -26,6 +26,9 @@ def normalize(tensor: torch.Tensor) -> torch.Tensor: def dof(self): return self.tensor.shape[1] + def numel(self): + return self.tensor.shape[1] + def _local_impl(self, variable2): return torch.zeros(1) From db154c9e283c79df978fa5edc05b2cbf45b5f3d8 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Tue, 30 Aug 2022 13:14:45 -0400 Subject: [PATCH 16/38] Add support for SE2 poses in Collision2D (#278) * Changed SE2.xy() to return a Point2 instead of a tensor. * Added support for SE2 in Collision2D. * Minor cleanup in collision jacobians test. * SE2.translation is now an alias for SE2.xy(). --- theseus/embodied/collision/collision.py | 23 ++++++++++++++----- theseus/embodied/collision/eff_obj_contact.py | 2 +- .../collision/tests/test_collision_factor.py | 7 +++--- .../quasi_static_pushing_planar.py | 12 ++++++---- theseus/geometry/se2.py | 6 ++--- theseus/geometry/tests/test_se2.py | 2 +- .../tactile_pose_estimation/models.py | 2 +- 7 files changed, 34 insertions(+), 20 deletions(-) diff --git a/theseus/embodied/collision/collision.py b/theseus/embodied/collision/collision.py index 2e966c22c..d1093199b 100644 --- a/theseus/embodied/collision/collision.py +++ b/theseus/embodied/collision/collision.py @@ -9,7 +9,7 @@ from theseus.core import CostFunction, CostWeight, Variable from theseus.embodied.kinematics import IdentityModel, KinematicsModel -from theseus.geometry import Point2 +from theseus.geometry import Point2, SE2 from .signed_distance_field import SignedDistanceField2D @@ -17,7 +17,7 @@ class Collision2D(CostFunction): def __init__( self, - pose: Point2, + pose: Union[Point2, SE2], sdf_origin: Union[Point2, torch.Tensor], sdf_data: Union[torch.Tensor, Variable], sdf_cell_size: Union[float, torch.Tensor, Variable], @@ -25,8 +25,8 @@ def __init__( cost_weight: CostWeight, name: Optional[str] = None, ): - if not isinstance(pose, Point2): - raise ValueError("Collision2D only accepts Point2 poses.") + if not isinstance(pose, Point2) and not isinstance(pose, SE2): + raise ValueError("Collision2D only accepts Point2 or SE2 poses.") super().__init__(cost_weight, name=name) self.pose = pose self.sdf_origin = SignedDistanceField2D.convert_origin(sdf_origin) @@ -49,8 +49,19 @@ def __init__( def _compute_distances_and_jacobians( self, ) -> Tuple[torch.Tensor, torch.Tensor]: - robot_state = cast(Point2, self.robot.forward_kinematics(self.pose)["state"]) - return self.sdf.signed_distance(robot_state.tensor.view(-1, 2, 1)) + jac_xy: Optional[torch.Tensor] = None + if isinstance(self.pose, SE2): + aux: List[torch.Tensor] = [] + xy_pos = self.pose.xy(jacobians=aux) + jac_xy = aux[0] + else: + xy_pos = cast(Point2, self.pose) + + robot_state = self.robot.forward_kinematics(xy_pos)["state"] + dist, jac = self.sdf.signed_distance(robot_state.tensor.view(-1, 2, 1)) + if jac_xy is not None: + jac = jac.matmul(jac_xy) + return dist, jac def _error_from_distances(self, distances: torch.Tensor): return (self.cost_eps.tensor - distances).clamp(min=0) diff --git a/theseus/embodied/collision/eff_obj_contact.py b/theseus/embodied/collision/eff_obj_contact.py index c164832b9..8ae484313 100644 --- a/theseus/embodied/collision/eff_obj_contact.py +++ b/theseus/embodied/collision/eff_obj_contact.py @@ -63,7 +63,7 @@ def _compute_distances_and_jacobians( J_transf: List[torch.Tensor] = [] J_xy: List[torch.Tensor] = [] eff__obj = self.obj.transform_to( - self.eff.xy(jacobians=J_xy), jacobians=J_transf + self.eff.xy(jacobians=J_xy).tensor, jacobians=J_transf ) J_transf_obj = J_transf[0] J_transf_eff = J_transf[1].matmul(J_xy[0]) diff --git a/theseus/embodied/collision/tests/test_collision_factor.py b/theseus/embodied/collision/tests/test_collision_factor.py index 49e21708a..bcc573d80 100644 --- a/theseus/embodied/collision/tests/test_collision_factor.py +++ b/theseus/embodied/collision/tests/test_collision_factor.py @@ -76,13 +76,14 @@ def test_collision2d_copy(): assert cost_function2.name == "new_name" -def test_collision2d_jacobians(): +@pytest.mark.parametrize("pose_cls", [th.Point2, th.SE2]) +def test_collision2d_jacobians(pose_cls): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): - for batch_size in [1, 10, 100, 1000]: + for batch_size in [1, 10, 100]: cost_weight = th.ScaleCostWeight(torch.ones(1).squeeze().double()) - pose = th.Point2(tensor=torch.randn(batch_size, 2, generator=rng).double()) + pose = pose_cls.randn(batch_size, generator=rng, dtype=torch.float64) origin = th.Point2(torch.ones(batch_size, 2).double()) sdf_data = th.Variable( torch.randn(batch_size, 10, 10, generator=rng).double() diff --git a/theseus/embodied/motionmodel/quasi_static_pushing_planar.py b/theseus/embodied/motionmodel/quasi_static_pushing_planar.py index 3b8cdb877..09abd67bb 100644 --- a/theseus/embodied/motionmodel/quasi_static_pushing_planar.py +++ b/theseus/embodied/motionmodel/quasi_static_pushing_planar.py @@ -8,7 +8,7 @@ import torch from theseus.core import CostFunction, CostWeight, Variable -from theseus.geometry import SE2, OptionalJacobians, Point2 +from theseus.geometry import SE2, OptionalJacobians from theseus.geometry.so2 import SO2 @@ -115,7 +115,9 @@ def _compute_V( vel_xy_obj__world = self.obj2.xy(jacobians=J_o2xy_o2) - self.obj1.xy( jacobians=J_o1xy_o1 ) - vel_xy_obj__obj = obj2_angle.unrotate(vel_xy_obj__world, jacobians=J_vxyoo) + vel_xy_obj__obj = obj2_angle.unrotate( + vel_xy_obj__world.tensor, jacobians=J_vxyoo + ) # Putting V together obj_diff__world = cast(SE2, self.obj1.between(self.obj2, jacobians=J_odw)) @@ -173,8 +175,8 @@ def _compute_Vp( J_vxyco: OptionalJacobians = [] if get_jacobians else None # Compute contact point velocities using consecutive end effector poses - contact_point_1 = self.eff1.xy(jacobians=J_cp1_e1) - vel_xy_contact__world = cast(Point2, contact_point_2 - contact_point_1) + contact_point_1 = self.eff1.xy(jacobians=J_cp1_e1).tensor + vel_xy_contact__world = contact_point_2 - contact_point_1 # Transform velocity to object's 2 frame vel_xy_contact__obj = obj2_angle.unrotate( @@ -220,7 +222,7 @@ def _error_and_jacobians_impl( # These quantities are needed by two or more of D, V, Vp, so we compute once. obj2_angle = self.obj2.rotation self.obj2.theta(jacobians=J_o2angle_o2) - contact_point_2 = self.eff2.xy(jacobians=J_cp2_e2) + contact_point_2 = self.eff2.xy(jacobians=J_cp2_e2).tensor # D * V = Vp, See Zhou et al. # A Fast Stochastic Contact Model for Planar Pushing and Grasping: diff --git a/theseus/geometry/se2.py b/theseus/geometry/se2.py index 49fda5d61..bb7b63b7e 100644 --- a/theseus/geometry/se2.py +++ b/theseus/geometry/se2.py @@ -134,9 +134,9 @@ def theta(self, jacobians: Optional[List[torch.Tensor]] = None) -> torch.Tensor: @property def translation(self) -> Point2: - return Point2(tensor=self[:, :2]) + return self.xy() - def xy(self, jacobians: Optional[List[torch.Tensor]] = None) -> torch.Tensor: + def xy(self, jacobians: Optional[List[torch.Tensor]] = None) -> Point2: if jacobians is not None: self._check_jacobians_list(jacobians) rotation = self.rotation @@ -145,7 +145,7 @@ def xy(self, jacobians: Optional[List[torch.Tensor]] = None) -> torch.Tensor: ) J_out[:, :2, :2] = rotation.to_matrix() jacobians.append(J_out) - return self.translation.tensor + return Point2(tensor=self[:, :2]) def update_from_x_y_theta(self, x_y_theta: torch.Tensor): rotation = SO2(theta=x_y_theta[:, 2:]) diff --git a/theseus/geometry/tests/test_se2.py b/theseus/geometry/tests/test_se2.py index 98a5a0462..e1610498f 100644 --- a/theseus/geometry/tests/test_se2.py +++ b/theseus/geometry/tests/test_se2.py @@ -170,7 +170,7 @@ def test_xy_jacobian(dtype): jacobian = [] se2.xy(jacobians=jacobian) expected_jac = numeric_jacobian( - lambda groups: th.Point2(groups[0].xy()), [se2], function_dim=2 + lambda groups: groups[0].xy(), [se2], function_dim=2 ) torch.allclose(jacobian[0], expected_jac[0]) diff --git a/theseus/utils/examples/tactile_pose_estimation/models.py b/theseus/utils/examples/tactile_pose_estimation/models.py index 47e347e5e..5804ca8bc 100644 --- a/theseus/utils/examples/tactile_pose_estimation/models.py +++ b/theseus/utils/examples/tactile_pose_estimation/models.py @@ -171,7 +171,7 @@ def get_tactile_nn_measurements_inputs( model_measurements.append( torch.cat( ( - meas_pose_rel.xy(), + meas_pose_rel.xy().tensor, meas_pose_rel.theta().cos(), meas_pose_rel.theta().sin(), ), From cca7362cf16e6031041d24805e8a3f8c10c1ec72 Mon Sep 17 00:00:00 2001 From: Brent Yi Date: Wed, 31 Aug 2022 10:43:49 -0700 Subject: [PATCH 17/38] Implement probabilistically correct SO3 sampling (#286) --- theseus/geometry/so3.py | 37 +++++++++++++++++++++++++------------ 1 file changed, 25 insertions(+), 12 deletions(-) diff --git a/theseus/geometry/so3.py b/theseus/geometry/so3.py index 99dd7165d..39805701b 100644 --- a/theseus/geometry/so3.py +++ b/theseus/geometry/so3.py @@ -44,21 +44,34 @@ def rand( device: Optional[torch.device] = None, requires_grad: bool = False, ) -> "SO3": + # Reference: + # https://web.archive.org/web/20211105205926/http://planning.cs.uiuc.edu/node198.html if len(size) != 1: raise ValueError("The size should be 1D.") - return SO3.exp_map( - 2 - * theseus.constants.PI - * torch.rand( - size[0], - 3, - generator=generator, - dtype=dtype, - device=device, - requires_grad=requires_grad, - ) - - theseus.constants.PI + u = torch.rand( + 3, + size[0], + generator=generator, + dtype=dtype, + device=device, + requires_grad=requires_grad, + ) + u1 = u[0] + u2, u3 = u[1:3] * 2 * torch.pi + + a = torch.sqrt(1.0 - u1) + b = torch.sqrt(u1) + quaternion = torch.stack( + [ + a * torch.sin(u2), + a * torch.cos(u2), + b * torch.sin(u3), + b * torch.cos(u3), + ], + dim=1, ) + assert quaternion.shape == (size[0], 4) + return SO3(quaternion=quaternion) @staticmethod def randn( From 36a1b32982b112e5e5f3d3d19c0944e035a2d544 Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Wed, 7 Sep 2022 16:56:48 -0400 Subject: [PATCH 18/38] Refactor SO3 and SE3 to be consistent with functorch (#266) * fixed some bugs in SO3.log_map * refactor SO3 to be consistent with functorch * fixed a bug in SO3._project_impl * add more tests for SO3 * SE3 refactored to be consistent with functorch * simplify SO3 and SE3 for functorch * refactor so2 to be consistent with functorch * torch.zeros() -> tensor.new_zeros() * simplify the code using new_zeros * refactor se2 * refactor the projection map for SE3 * fixed a bug in SO2._rotate_from_cos_sin * fixed a bug for functorch * refactor SO3.log_map_impl * refactor SO3 and remove functorch context for log_map_impl() and to_quaternion() * refactor SE3._log_map_impl * SO3 refactored * functorhc refactored * add more warning info for functorch * fixed a bug in warnings message about tensor check for functorch * rename functorch context * rename lie_group_tensor to lie_group * some changes are made * rename lie_group_tensor_check to lie_group_check * fixed the logic bug --- theseus/geometry/lie_group_check.py | 52 ++++ theseus/geometry/manifold.py | 10 +- theseus/geometry/se2.py | 48 +-- theseus/geometry/se3.py | 217 +++++++++++--- theseus/geometry/so2.py | 40 ++- theseus/geometry/so3.py | 248 ++++++++++++---- theseus/geometry/tests/common.py | 434 +++++++++++++++------------- theseus/geometry/tests/test_se3.py | 130 +++++---- theseus/geometry/tests/test_so3.py | 56 ++-- 9 files changed, 805 insertions(+), 430 deletions(-) create mode 100644 theseus/geometry/lie_group_check.py diff --git a/theseus/geometry/lie_group_check.py b/theseus/geometry/lie_group_check.py new file mode 100644 index 000000000..fe71d538f --- /dev/null +++ b/theseus/geometry/lie_group_check.py @@ -0,0 +1,52 @@ +# Copyright (c) Meta Platforms, Inc. and affiliates. +# +# This source code is licensed under the MIT license found in the +# LICENSE file in the root directory of this source tree. + +import threading +from typing import Any + + +class _LieGroupCheckContext: + contexts = threading.local() + + @classmethod + def get_context(cls): + if not hasattr(cls.contexts, "check_lie_group"): + cls.contexts.check_lie_group = False + return cls.contexts.check_lie_group + + @classmethod + def set_context(cls, check_lie_group: bool): + cls.contexts.check_lie_group = check_lie_group + + +class set_lie_group_check_enabled: + def __init__(self, mode: bool) -> None: + self.prev = _LieGroupCheckContext.get_context() + _LieGroupCheckContext.set_context(mode) + + def __enter__(self) -> None: + pass + + def __exit__(self, exc_type: Any, exc_value: Any, traceback: Any) -> None: + _LieGroupCheckContext.set_context(self.prev) + + +class enable_lie_group_check(_LieGroupCheckContext): + def __enter__(self) -> None: + self.prev = _LieGroupCheckContext.get_context() + _LieGroupCheckContext.set_context(True) + + def __exit__(self, typ, value, traceback) -> None: + _LieGroupCheckContext.set_context(self.prev) + + +class no_lie_group_check(_LieGroupCheckContext): + def __enter__(self): + self.prev = super().get_context() + _LieGroupCheckContext.set_context(False) + return self + + def __exit__(self, typ, value, traceback): + _LieGroupCheckContext.set_context(self.prev) diff --git a/theseus/geometry/manifold.py b/theseus/geometry/manifold.py index 77550362d..f78754ea5 100644 --- a/theseus/geometry/manifold.py +++ b/theseus/geometry/manifold.py @@ -11,6 +11,7 @@ from theseus.constants import _CHECK_DTYPE_SUPPORTED from theseus.core.variable import Variable +from .lie_group_check import _LieGroupCheckContext OptionalJacobians = Optional[List[torch.Tensor]] @@ -40,7 +41,14 @@ def __init__( if tensor is None and dtype is None: dtype = torch.get_default_dtype() if tensor is not None: - tensor = self._check_tensor(tensor, strict) + if _LieGroupCheckContext.get_context(): + tensor = self._check_tensor(tensor, strict) + else: + warnings.warn( + f"functorch is enabled and tensor is not checked " + f"for {self.__class__.__name__}.", + RuntimeWarning, + ) if dtype is not None and tensor.dtype != dtype: warnings.warn( f"tensor.dtype {tensor.dtype} does not match given dtype {dtype}, " diff --git a/theseus/geometry/se2.py b/theseus/geometry/se2.py index bb7b63b7e..d39bdd67c 100644 --- a/theseus/geometry/se2.py +++ b/theseus/geometry/se2.py @@ -125,9 +125,7 @@ def rotation(self) -> SO2: def theta(self, jacobians: Optional[List[torch.Tensor]] = None) -> torch.Tensor: if jacobians is not None: self._check_jacobians_list(jacobians) - J_out = torch.zeros( - self.shape[0], 1, 3, device=self.device, dtype=self.dtype - ) + J_out = self.tensor.new_zeros(self.shape[0], 1, 3) J_out[:, 0, 2] = 1 jacobians.append(J_out) return self.rotation.theta() @@ -140,9 +138,7 @@ def xy(self, jacobians: Optional[List[torch.Tensor]] = None) -> Point2: if jacobians is not None: self._check_jacobians_list(jacobians) rotation = self.rotation - J_out = torch.zeros( - self.shape[0], 2, 3, device=self.device, dtype=self.dtype - ) + J_out = self.tensor.new_zeros(self.shape[0], 2, 3) J_out[:, :2, :2] = rotation.to_matrix() jacobians.append(J_out) return Point2(tensor=self[:, :2]) @@ -154,9 +150,7 @@ def update_from_x_y_theta(self, x_y_theta: torch.Tensor): def update_from_rot_and_trans(self, rotation: SO2, translation: Point2): batch_size = rotation.shape[0] - self.tensor = torch.empty(batch_size, 4).to( - device=rotation.device, dtype=rotation.dtype - ) + self.tensor = rotation.tensor.new_empty(batch_size, 4) self[:, :2] = translation.tensor cosine, sine = rotation.to_cos_sin() self[:, 2] = cosine @@ -186,12 +180,10 @@ def _log_map_impl( if jacobians is not None: SE2._check_jacobians_list(jacobians) - jac = torch.zeros( + jac = self.tensor.new_zeros( self.shape[0], 3, 3, - dtype=self.dtype, - device=self.device, ) theta2 = theta**2 @@ -272,12 +264,10 @@ def exp_map( cosine_minus_one_by_theta2 = torch.where( small_theta, -0.5 + theta2 / 24, (cosine - 1) / theta2_nz ) - jac = torch.zeros( + jac = tangent_vector.new_zeros( tangent_vector.shape[0], 3, 3, - dtype=tangent_vector.dtype, - device=tangent_vector.device, ) jac[:, 0, 0] = sine_by_theta jac[:, 0, 1] = -cosine_minus_one_by_theta @@ -304,7 +294,7 @@ def normalize(tensor: torch.Tensor) -> torch.Tensor: return torch.cat([tensor[:, :2], SO2.normalize(tensor[:, 2:])], dim=1) def _adjoint_impl(self) -> torch.Tensor: - ret = torch.zeros(self.shape[0], 3, 3).to(device=self.device, dtype=self.dtype) + ret = self.tensor.new_zeros(self.shape[0], 3, 3) ret[:, :2, :2] = self.rotation.to_matrix() ret[:, 0, 2] = self[:, 1] ret[:, 1, 2] = -self[:, 0] @@ -339,11 +329,7 @@ def _project_impl( self, euclidean_grad: torch.Tensor, is_sparse: bool = False ) -> torch.Tensor: self._project_check(euclidean_grad, is_sparse) - ret = torch.zeros( - euclidean_grad.shape[:-1] + torch.Size([3]), - dtype=self.dtype, - device=self.device, - ) + ret = self.tensor.new_zeros(euclidean_grad.shape[:-1] + torch.Size([3])) temp = torch.stack((-self[:, 3], self[:, 2]), dim=1) @@ -366,9 +352,7 @@ def _project_impl( return ret def to_matrix(self) -> torch.Tensor: - matrix = torch.zeros(self.shape[0], 3, 3).to( - device=self.device, dtype=self.dtype - ) + matrix = self.tensor.new_zeros(self.shape[0], 3, 3) matrix[:, :2, :2] = self.rotation.to_matrix() matrix[:, :2, 2] = self[:, :2] matrix[:, 2, 2] = 1.0 @@ -378,9 +362,7 @@ def to_matrix(self) -> torch.Tensor: def hat(tangent_vector: torch.Tensor) -> torch.Tensor: theta = tangent_vector[:, 2] u = tangent_vector[:, :2] - matrix = torch.zeros(tangent_vector.shape[0], 3, 3).to( - device=tangent_vector.device, dtype=tangent_vector.dtype - ) + matrix = tangent_vector.new_zeros(tangent_vector.shape[0], 3, 3) matrix[:, 0, 1] = -theta matrix[:, 1, 0] = theta matrix[:, :2, 2] = u @@ -396,9 +378,7 @@ def vee(matrix: torch.Tensor) -> torch.Tensor: if not _check: raise ValueError("Invalid hat matrix for SE2.") batch_size = matrix.shape[0] - tangent_vector = torch.zeros(batch_size, 3).to( - device=matrix.device, dtype=matrix.dtype - ) + tangent_vector = matrix.new_zeros(batch_size, 3) tangent_vector[:, 2] = matrix[:, 1, 0] tangent_vector[:, :2] = matrix[:, :2, 2] return tangent_vector @@ -422,13 +402,13 @@ def transform_to( if jacobians is not None: self._check_jacobians_list(jacobians) - Jg = torch.zeros(batch_size, 2, 3, dtype=self.dtype, device=self.device) + Jg = self.tensor.new_zeros(batch_size, 2, 3) Jg[:, 0, 0] = -1 Jg[:, 1, 1] = -1 Jg[:, 0, 2] = ret.y() Jg[:, 1, 2] = -ret.x() - Jpnt = torch.zeros(batch_size, 2, 2, dtype=self.dtype, device=self.device) + Jpnt = self.tensor.new_zeros(batch_size, 2, 2) Jpnt[:, 0, 0] = cosine Jpnt[:, 0, 1] = sine Jpnt[:, 1, 0] = -sine @@ -453,7 +433,7 @@ def transform_from( if jacobians is not None: self._check_jacobians_list(jacobians) - Jg = torch.zeros(batch_size, 2, 3, dtype=self.dtype, device=self.device) + Jg = self.tensor.new_zeros(batch_size, 2, 3) Jg[:, 0, 0] = cosine Jg[:, 0, 1] = -sine Jg[:, 1, 0] = sine @@ -461,7 +441,7 @@ def transform_from( Jg[:, 0, 2] = -temp.y() Jg[:, 1, 2] = temp.x() - Jpnt = torch.zeros(batch_size, 2, 2, dtype=self.dtype, device=self.device) + Jpnt = self.tensor.new_zeros(batch_size, 2, 2) Jpnt[:, 0, 0] = cosine Jpnt[:, 0, 1] = -sine Jpnt[:, 1, 0] = sine diff --git a/theseus/geometry/se3.py b/theseus/geometry/se3.py index 57a6a1eb7..8a2b0b852 100644 --- a/theseus/geometry/se3.py +++ b/theseus/geometry/se3.py @@ -4,6 +4,7 @@ # LICENSE file in the root directory of this source tree. from typing import List, Optional, Union, cast +import warnings import torch @@ -13,6 +14,7 @@ from .lie_group import LieGroup from .point_types import Point3 from .so3 import SO3 +from .lie_group_check import _LieGroupCheckContext class SE3(LieGroup): @@ -109,7 +111,7 @@ def __str__(self) -> str: return f"SE3(matrix={self.tensor}), name={self.name})" def _adjoint_impl(self) -> torch.Tensor: - ret = torch.zeros(self.shape[0], 6, 6).to(dtype=self.dtype, device=self.device) + ret = self.tensor.new_zeros(self.shape[0], 6, 6) ret[:, :3, :3] = self[:, :3, :3] ret[:, 3:, 3:] = self[:, :3, :3] ret[:, :3, 3:] = SO3.hat(self[:, :3, 3]) @ self[:, :3, :3] @@ -120,11 +122,7 @@ def _project_impl( self, euclidean_grad: torch.Tensor, is_sparse: bool = False ) -> torch.Tensor: self._project_check(euclidean_grad, is_sparse) - ret = torch.zeros( - euclidean_grad.shape[:-2] + torch.Size([6]), - dtype=self.dtype, - device=self.device, - ) + ret = self.tensor.new_zeros(euclidean_grad.shape[:-2] + torch.Size([6])) if is_sparse: temp = torch.einsum( @@ -176,14 +174,23 @@ def _hat_matrix_check(matrix: torch.Tensor): if matrix.ndim != 3 or matrix.shape[1:] != (4, 4): raise ValueError("Hat matrices of SE3 can only be 4x4 matrices") - if matrix[:, 3].abs().max().item() > HAT_EPS: - raise ValueError("The last row of hat matrices of SE3 can only be zero.") - - if ( - matrix[:, :3, :3].transpose(1, 2) + matrix[:, :3, :3] - ).abs().max().item() > HAT_EPS: - raise ValueError( - "The 3x3 top-left corner of hat matrices of SE3 can only be skew-symmetric." + if _LieGroupCheckContext.get_context(): + if matrix[:, 3].abs().max().item() > HAT_EPS: + raise ValueError( + "The last row of hat matrices of SE3 can only be zero." + ) + + if ( + matrix[:, :3, :3].transpose(1, 2) + matrix[:, :3, :3] + ).abs().max().item() > HAT_EPS: + raise ValueError( + "The 3x3 top-left corner of hat matrices of SE3 can only be skew-symmetric." + ) + else: + warnings.warn( + "functorch is enabled and the skew-symmetry of hat matrices is " + "not checked for SE3.", + RuntimeWarning, ) @staticmethod @@ -219,9 +226,7 @@ def exp_map( one_minus_cosine_by_theta2 = torch.where( near_zero, 0.5 * sine_by_theta, (1 - cosine) / theta2_nz ) - ret.tensor = torch.zeros(tangent_vector.shape[0], 3, 4).to( - dtype=tangent_vector.dtype, device=tangent_vector.device - ) + ret.tensor = tangent_vector.new_zeros(tangent_vector.shape[0], 3, 4) ret.tensor[:, :3, :3] = ( one_minus_cosine_by_theta2 * tangent_vector_ang @@ -263,12 +268,10 @@ def exp_map( theta_minus_sine_by_theta3_rot = torch.where( near_zero, torch.zeros_like(theta), theta_minus_sine_by_theta3_t ) - jac = torch.zeros( + jac = tangent_vector.new_zeros( tangent_vector.shape[0], 6, 6, - dtype=tangent_vector.dtype, - device=tangent_vector.device, ) jac[:, :3, :3] = ( theta_minus_sine_by_theta3_rot @@ -348,7 +351,6 @@ def normalize(tensor: torch.Tensor) -> torch.Tensor: def _log_map_impl( self, jacobians: Optional[List[torch.Tensor]] = None ) -> torch.Tensor: - sine_axis = torch.zeros(self.shape[0], 3, dtype=self.dtype, device=self.device) sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) sine_axis[:, 1] = 0.5 * (self[:, 0, 2] - self[:, 2, 0]) @@ -360,35 +362,38 @@ def _log_map_impl( non_zero = torch.ones(1, dtype=self.dtype, device=self.device) near_zero = theta < self._NEAR_ZERO_EPS + near_pi = 1 + cosine <= self._NEAR_PI_EPS # Compute the rotation - not_near_pi = 1 + cosine > self._NEAR_PI_EPS - # theta is not near pi - near_zero_not_near_pi = near_zero[not_near_pi] + near_zero_or_near_pi = torch.logical_or(near_zero, near_pi) # Compute the approximation of theta / sin(theta) when theta is near to 0 - sine_nz = torch.where(near_zero_not_near_pi, non_zero, sine[not_near_pi]) + sine_nz = torch.where(near_zero_or_near_pi, non_zero, sine) scale = torch.where( - near_zero_not_near_pi, - 1 + sine[not_near_pi] ** 2 / 6, - theta[not_near_pi] / sine_nz, + near_zero_or_near_pi, + 1 + sine**2 / 6, + theta / sine_nz, ) - ret_ang = torch.zeros_like(sine_axis) - ret_ang[not_near_pi] = sine_axis[not_near_pi] * scale.view(-1, 1) + ret_ang = sine_axis * scale.view(-1, 1) # theta is near pi - near_pi = ~not_near_pi - ddiag = torch.diagonal(self[near_pi], dim1=1, dim2=2) + ddiag = torch.diagonal(self.tensor, dim1=1, dim2=2) # Find the index of major coloumns and diagonals major = torch.logical_and( ddiag[:, 1] > ddiag[:, 0], ddiag[:, 1] > ddiag[:, 2] ) + 2 * torch.logical_and(ddiag[:, 2] > ddiag[:, 0], ddiag[:, 2] > ddiag[:, 1]) - sel_rows = 0.5 * (self[near_pi, major, :3] + self[near_pi, :3, major]) - aux = torch.ones(sel_rows.shape[0], dtype=torch.bool) - sel_rows[aux, major] -= cosine[near_pi] - axis = sel_rows / sel_rows.norm(dim=1, keepdim=True) - sign_tmp = sine_axis[near_pi, major].sign() + aux = torch.ones(self.shape[0], dtype=torch.bool) + sel_rows = 0.5 * (self[aux, major, :3] + self[aux, :3, major]) + sel_rows[aux, major] -= cosine + axis = sel_rows / torch.where( + near_zero.view(-1, 1), + non_zero.view(-1, 1), + sel_rows.norm(dim=1, keepdim=True), + ) + sign_tmp = sine_axis[aux, major].sign() sign = torch.where(sign_tmp != 0, sign_tmp, torch.ones_like(sign_tmp)) - ret_ang[near_pi] = axis * (theta[near_pi] * sign).view(-1, 1) + ret_ang = torch.where( + near_pi.view(-1, 1), axis * (theta * sign).view(-1, 1), ret_ang + ) # Compute the translation sine_theta = sine * theta @@ -416,7 +421,7 @@ def _log_map_impl( if jacobians is not None: SE3._check_jacobians_list(jacobians) - jac = torch.zeros(self.shape[0], 6, 6, dtype=self.dtype, device=self.device) + jac = self.tensor.new_zeros(self.shape[0], 6, 6) b_ret_ang = b.view(-1, 1) * ret_ang jac[:, :3, :3] = b_ret_ang.view(-1, 3, 1) * ret_ang.view(-1, 1, 3) @@ -473,7 +478,7 @@ def _compose_impl(self, se3_2: LieGroup) -> "SE3": se3_2 = cast(SE3, se3_2) batch_size = max(self.shape[0], se3_2.shape[0]) ret = SE3() - ret.tensor = torch.zeros(batch_size, 3, 4, dtype=self.dtype, device=self.device) + ret.tensor = self.tensor.new_zeros(batch_size, 3, 4) ret[:, :, :3] = self[:, :, :3] @ se3_2[:, :, :3] ret[:, :, 3] = self[:, :, 3] ret[:, :, 3:] += self[:, :, :3] @ se3_2[:, :, 3:] @@ -481,7 +486,7 @@ def _compose_impl(self, se3_2: LieGroup) -> "SE3": return ret def _inverse_impl(self, get_jacobian: bool = False) -> "SE3": - ret = torch.zeros(self.shape[0], 3, 4).to(dtype=self.dtype, device=self.device) + ret = self.tensor.new_empty(self.shape[0], 3, 4) rotT = self.tensor[:, :3, :3].transpose(1, 2) ret[:, :, :3] = rotT ret[:, :, 3] = -(rotT @ self.tensor[:, :3, 3].unsqueeze(2)).view(-1, 3) @@ -489,7 +494,7 @@ def _inverse_impl(self, get_jacobian: bool = False) -> "SE3": return SE3(tensor=ret, strict=False) def to_matrix(self) -> torch.Tensor: - ret = torch.zeros(self.shape[0], 4, 4).to(dtype=self.dtype, device=self.device) + ret = self.tensor.new_zeros(self.shape[0], 4, 4) ret[:, :3] = self.tensor ret[:, 3, 3] = 1 return ret @@ -516,9 +521,8 @@ def hat(tangent_vector: torch.Tensor) -> torch.Tensor: _check = tangent_vector.ndim == 2 and tangent_vector.shape[1] == 6 if not _check: raise ValueError("Invalid vee matrix for SE3.") - matrix = torch.zeros(tangent_vector.shape[0], 4, 4).to( - dtype=tangent_vector.dtype, device=tangent_vector.device - ) + + matrix = tangent_vector.new_zeros(tangent_vector.shape[0], 4, 4) matrix[:, :3, :3] = SO3.hat(tangent_vector[:, 3:]) matrix[:, :3, 3] = tangent_vector[:, :3] @@ -623,6 +627,129 @@ def to(self, *args, **kwargs): super().to(*args, **kwargs) self._resolve_eps() + def _deprecated_log_map_impl( + self, jacobians: Optional[List[torch.Tensor]] = None + ) -> torch.Tensor: + sine_axis = torch.zeros(self.shape[0], 3, dtype=self.dtype, device=self.device) + sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) + sine_axis[:, 1] = 0.5 * (self[:, 0, 2] - self[:, 2, 0]) + sine_axis[:, 2] = 0.5 * (self[:, 1, 0] - self[:, 0, 1]) + cosine = 0.5 * (self[:, 0, 0] + self[:, 1, 1] + self[:, 2, 2] - 1) + sine = sine_axis.norm(dim=1) + theta = torch.atan2(sine, cosine) + theta2 = theta**2 + non_zero = torch.ones(1, dtype=self.dtype, device=self.device) + + near_zero = theta < self._NEAR_ZERO_EPS + near_pi = 1 + cosine <= self._NEAR_PI_EPS + + # Compute the rotation + not_near_pi = ~near_pi + # theta is not near pi + near_zero_not_near_pi = near_zero[not_near_pi] + # Compute the approximation of theta / sin(theta) when theta is near to 0 + sine_nz = torch.where(near_zero_not_near_pi, non_zero, sine[not_near_pi]) + scale = torch.where( + near_zero_not_near_pi, + 1 + sine[not_near_pi] ** 2 / 6, + theta[not_near_pi] / sine_nz, + ) + ret_ang = torch.zeros_like(sine_axis) + ret_ang[not_near_pi] = sine_axis[not_near_pi] * scale.view(-1, 1) + + # theta is near pi + ddiag = torch.diagonal(self[near_pi], dim1=1, dim2=2) + # Find the index of major coloumns and diagonals + major = torch.logical_and( + ddiag[:, 1] > ddiag[:, 0], ddiag[:, 1] > ddiag[:, 2] + ) + 2 * torch.logical_and(ddiag[:, 2] > ddiag[:, 0], ddiag[:, 2] > ddiag[:, 1]) + sel_rows = 0.5 * (self[near_pi, major, :3] + self[near_pi, :3, major]) + aux = torch.ones(sel_rows.shape[0], dtype=torch.bool) + sel_rows[aux, major] -= cosine[near_pi] + axis = sel_rows / sel_rows.norm(dim=1, keepdim=True) + sign_tmp = sine_axis[near_pi, major].sign() + sign = torch.where(sign_tmp != 0, sign_tmp, torch.ones_like(sign_tmp)) + ret_ang[near_pi] = axis * (theta[near_pi] * sign).view(-1, 1) + + # Compute the translation + sine_theta = sine * theta + two_cosine_minus_two = 2 * cosine - 2 + two_cosine_minus_two_nz = torch.where(near_zero, non_zero, two_cosine_minus_two) + + theta2_nz = torch.where(near_zero, non_zero, theta2) + + a = torch.where( + near_zero, 1 - theta2 / 12, -sine_theta / two_cosine_minus_two_nz + ) + b = torch.where( + near_zero, + 1.0 / 12 + theta2 / 720, + (sine_theta + two_cosine_minus_two) / (theta2_nz * two_cosine_minus_two_nz), + ) + + translation = self[:, :, 3].view(-1, 3, 1) + ret_lin = a.view(-1, 1) * self[:, :, 3] + ret_lin -= 0.5 * torch.cross(ret_ang, self[:, :, 3], dim=1) + ret_ang_ext = ret_ang.view(-1, 3, 1) + ret_lin += b.view(-1, 1) * ( + ret_ang_ext @ (ret_ang_ext.transpose(1, 2) @ translation) + ).view(-1, 3) + + if jacobians is not None: + SE3._check_jacobians_list(jacobians) + jac = self.tensor.new_zeros(self.shape[0], 6, 6) + + b_ret_ang = b.view(-1, 1) * ret_ang + jac[:, :3, :3] = b_ret_ang.view(-1, 3, 1) * ret_ang.view(-1, 1, 3) + + half_ret_ang = 0.5 * ret_ang + jac[:, 0, 1] -= half_ret_ang[:, 2] + jac[:, 1, 0] += half_ret_ang[:, 2] + jac[:, 0, 2] += half_ret_ang[:, 1] + jac[:, 2, 0] -= half_ret_ang[:, 1] + jac[:, 1, 2] -= half_ret_ang[:, 0] + jac[:, 2, 1] += half_ret_ang[:, 0] + + diag_jac_rot = torch.diagonal(jac[:, :3, :3], dim1=1, dim2=2) + diag_jac_rot += a.view(-1, 1) + + jac[:, 3:, 3:] = jac[:, :3, :3] + + theta_nz = torch.where(near_zero, non_zero, theta) + theta4_nz = theta2_nz**2 + c = torch.where( + near_zero, + -1 / 360.0 - theta2 / 7560.0, + -(2 * two_cosine_minus_two + theta * sine + theta2) + / (theta4_nz * two_cosine_minus_two_nz), + ) + d = torch.where( + near_zero, + -1 / 6.0 - theta2 / 180.0, + (theta - sine) / (theta_nz * two_cosine_minus_two_nz), + ) + e = (ret_ang.view(-1, 1, 3) @ ret_lin.view(-1, 3, 1)).view(-1) + + ce_ret_ang = (c * e).view(-1, 1) * ret_ang + jac[:, :3, 3:] = ce_ret_ang.view(-1, 3, 1) * ret_ang.view(-1, 1, 3) + jac[:, :3, 3:] += b_ret_ang.view(-1, 3, 1) * ret_lin.view( + -1, 1, 3 + ) + ret_lin.view(-1, 3, 1) * b_ret_ang.view(-1, 1, 3) + diag_jac_t = torch.diagonal(jac[:, :3, 3:], dim1=1, dim2=2) + diag_jac_t += (e * d).view(-1, 1) + + half_ret_lin = 0.5 * ret_lin + jac[:, 0, 4] -= half_ret_lin[:, 2] + jac[:, 1, 3] += half_ret_lin[:, 2] + jac[:, 0, 5] += half_ret_lin[:, 1] + jac[:, 2, 3] -= half_ret_lin[:, 1] + jac[:, 1, 5] -= half_ret_lin[:, 0] + jac[:, 2, 4] += half_ret_lin[:, 0] + + jacobians.append(jac) + + return torch.cat([ret_lin, ret_ang], dim=1) + rand_se3 = SE3.rand randn_se3 = SE3.randn diff --git a/theseus/geometry/so2.py b/theseus/geometry/so2.py index e2e14bd7c..14849508b 100644 --- a/theseus/geometry/so2.py +++ b/theseus/geometry/so2.py @@ -4,6 +4,7 @@ # LICENSE file in the root directory of this source tree. from typing import List, Optional, Tuple, Union, cast +import warnings import torch @@ -11,6 +12,7 @@ from .lie_group import LieGroup from .point_types import Point2 +from .lie_group_check import _LieGroupCheckContext class SO2(LieGroup): @@ -134,6 +136,24 @@ def _check_tensor_impl(tensor: torch.Tensor) -> bool: return _check + @staticmethod + def _hat_matrix_check(matrix: torch.Tensor): + _check = matrix.ndim == 3 and matrix.shape[1:] == (2, 2) + + if _LieGroupCheckContext.get_context(): + _check &= matrix[:, 0, 0].abs().max().item() < theseus.constants.EPS + _check &= matrix[:, 1, 1].abs().max().item() < theseus.constants.EPS + _check &= torch.allclose(matrix[:, 0, 1], -matrix[:, 1, 0]) + else: + warnings.warn( + "functorch is enabled and the skew-symmetry of hat matrices is " + "not checked for SO2.", + RuntimeWarning, + ) + + if not _check: + raise ValueError("Invalid hat matrix for SO2.") + @staticmethod def exp_map( tangent_vector: torch.Tensor, jacobians: Optional[List[torch.Tensor]] = None @@ -239,9 +259,7 @@ def _rotate_from_cos_sin( else: point_tensor = point.tensor px, py = point_tensor[:, 0], point_tensor[:, 1] - new_point_tensor = torch.empty( - batch_size, 2, device=cosine.device, dtype=cosine.dtype - ) + new_point_tensor = point_tensor.new_empty(batch_size, 2) new_point_tensor[:, 0] = cosine * px - sine * py new_point_tensor[:, 1] = sine * px + cosine * py return Point2(tensor=new_point_tensor) @@ -280,9 +298,7 @@ def to_cos_sin(self) -> Tuple[torch.Tensor, torch.Tensor]: return self[:, 0], self[:, 1] def to_matrix(self) -> torch.Tensor: - matrix = torch.empty(self.shape[0], 2, 2).to( - device=self.device, dtype=self.dtype - ) + matrix = self.tensor.new_empty(self.shape[0], 2, 2) cosine, sine = self.to_cos_sin() matrix[:, 0, 0] = cosine matrix[:, 0, 1] = -sine @@ -292,22 +308,14 @@ def to_matrix(self) -> torch.Tensor: @staticmethod def hat(tangent_vector: torch.Tensor) -> torch.Tensor: - matrix = torch.zeros(tangent_vector.shape[0], 2, 2).to( - dtype=tangent_vector.dtype, - device=tangent_vector.device, - ) + matrix = tangent_vector.new_zeros(tangent_vector.shape[0], 2, 2) matrix[:, 0, 1] = -tangent_vector.view(-1) matrix[:, 1, 0] = tangent_vector.view(-1) return matrix @staticmethod def vee(matrix: torch.Tensor) -> torch.Tensor: - _check = matrix.ndim == 3 and matrix.shape[1:] == (2, 2) - _check &= matrix[:, 0, 0].abs().max().item() < theseus.constants.EPS - _check &= matrix[:, 1, 1].abs().max().item() < theseus.constants.EPS - _check &= torch.allclose(matrix[:, 0, 1], -matrix[:, 1, 0]) - if not _check: - raise ValueError("Invalid hat matrix for SO2.") + SO2._hat_matrix_check(matrix) return matrix[:, 1, 0].clone().view(-1, 1) def _copy_impl(self, new_name: Optional[str] = None) -> "SO2": diff --git a/theseus/geometry/so3.py b/theseus/geometry/so3.py index 39805701b..936d788a5 100644 --- a/theseus/geometry/so3.py +++ b/theseus/geometry/so3.py @@ -4,6 +4,7 @@ # LICENSE file in the root directory of this source tree. from typing import List, Optional, Union, cast +import warnings import torch @@ -11,6 +12,7 @@ from .lie_group import LieGroup from .point_types import Point3 +from .lie_group_check import _LieGroupCheckContext class SO3(LieGroup): @@ -119,9 +121,7 @@ def _project_impl( self, euclidean_grad: torch.Tensor, is_sparse: bool = False ) -> torch.Tensor: self._project_check(euclidean_grad, is_sparse) - ret = torch.zeros( - euclidean_grad.shape[:-1], dtype=self.dtype, device=self.device - ) + ret = self.tensor.new_zeros(euclidean_grad.shape[:-1]) if is_sparse: temp = torch.einsum("i...jk,i...jl->i...lk", euclidean_grad, self.tensor) else: @@ -156,25 +156,39 @@ def _unit_quaternion_check(quaternion: torch.Tensor): if quaternion.ndim != 2 or quaternion.shape[1] != 4: raise ValueError("Quaternions can only be 4-D vectors.") - QUANTERNION_EPS = theseus.constants._SO3_QUATERNION_EPS[quaternion.dtype] + if _LieGroupCheckContext.get_context(): + QUANTERNION_EPS = theseus.constants._SO3_QUATERNION_EPS[quaternion.dtype] - if quaternion.dtype != torch.float64: - quaternion = quaternion.double() + if quaternion.dtype != torch.float64: + quaternion = quaternion.double() - if ( - torch.linalg.norm(quaternion, dim=1) - 1 - ).abs().max().item() >= QUANTERNION_EPS: - raise ValueError("Not unit quaternions.") + if ( + torch.linalg.norm(quaternion, dim=1) - 1 + ).abs().max().item() >= QUANTERNION_EPS: + raise ValueError("Not unit quaternions.") + else: + warnings.warn( + "functorch is enabled and the validness of unit quaternions are not " + "checked for SO3.", + RuntimeWarning, + ) @staticmethod def _hat_matrix_check(matrix: torch.Tensor): if matrix.ndim != 3 or matrix.shape[1:] != (3, 3): raise ValueError("Hat matrices of SO(3) can only be 3x3 matrices") - if ( - matrix.transpose(1, 2) + matrix - ).abs().max().item() > theseus.constants._SO3_HAT_EPS[matrix.dtype]: - raise ValueError("Hat matrices of SO(3) can only be skew-symmetric.") + if _LieGroupCheckContext.get_context(): + warnings.warn( + "functorch is enabled and the skew-symmetry of hat matrices is " + "not checked for SO3.", + RuntimeWarning, + ) + else: + if ( + matrix.transpose(1, 2) + matrix + ).abs().max().item() > theseus.constants._SO3_HAT_EPS[matrix.dtype]: + raise ValueError("Hat matrices of SO(3) can only be skew-symmetric.") @staticmethod def exp_map( @@ -261,7 +275,7 @@ def normalize(tensor: torch.Tensor) -> torch.Tensor: def _log_map_impl( self, jacobians: Optional[List[torch.Tensor]] = None ) -> torch.Tensor: - sine_axis = torch.zeros(self.shape[0], 3, dtype=self.dtype, device=self.device) + sine_axis = self.tensor.new_zeros(self.shape[0], 3) sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) sine_axis[:, 1] = 0.5 * (self[:, 0, 2] - self[:, 2, 0]) sine_axis[:, 2] = 0.5 * (self[:, 1, 0] - self[:, 0, 1]) @@ -271,37 +285,39 @@ def _log_map_impl( near_zero = theta < self._NEAR_ZERO_EPS - not_near_pi = 1 + cosine > self._NEAR_PI_EPS + near_pi = 1 + cosine <= self._NEAR_PI_EPS # theta != pi - near_zero_not_near_pi = near_zero[not_near_pi] + near_zero_or_near_pi = torch.logical_or(near_zero, near_pi) # Compute the approximation of theta / sin(theta) when theta is near to 0 non_zero = torch.ones(1, dtype=self.dtype, device=self.device) - sine_nz = torch.where(near_zero_not_near_pi, non_zero, sine[not_near_pi]) + sine_nz = torch.where(near_zero_or_near_pi, non_zero, sine) scale = torch.where( - near_zero_not_near_pi, - 1 + sine[not_near_pi] ** 2 / 6, - theta[not_near_pi] / sine_nz, + near_zero_or_near_pi, + 1 + sine**2 / 6, + theta / sine_nz, ) - ret = torch.zeros_like(sine_axis) - ret[not_near_pi] = sine_axis[not_near_pi] * scale.view(-1, 1) + ret = sine_axis * scale.view(-1, 1) + # # theta ~ pi - near_pi = ~not_near_pi - ddiag = torch.diagonal(self[near_pi], dim1=1, dim2=2) + ddiag = torch.diagonal(self.tensor, dim1=1, dim2=2) # Find the index of major coloumns and diagonals major = torch.logical_and( ddiag[:, 1] > ddiag[:, 0], ddiag[:, 1] > ddiag[:, 2] ) + 2 * torch.logical_and(ddiag[:, 2] > ddiag[:, 0], ddiag[:, 2] > ddiag[:, 1]) - sel_rows = 0.5 * (self[near_pi, major] + self[near_pi, :, major]) - aux = torch.ones(sel_rows.shape[0], dtype=torch.bool) - sel_rows[aux, major] -= cosine[near_pi] - axis = sel_rows / sel_rows.norm(dim=1, keepdim=True) - sign_tmp = sine_axis[near_pi, major].sign() + aux = torch.ones(self.shape[0], dtype=torch.bool) + sel_rows = 0.5 * (self[aux, major] + self[aux, :, major]) + sel_rows[aux, major] -= cosine + axis = sel_rows / torch.where( + near_zero, + non_zero, + sel_rows.norm(dim=1), + ).view(-1, 1) + sign_tmp = sine_axis[aux, major].sign() sign = torch.where(sign_tmp != 0, sign_tmp, torch.ones_like(sign_tmp)) - ret[near_pi] = axis * (theta[near_pi] * sign).view(-1, 1) + ret = torch.where(near_pi.view(-1, 1), axis * (theta * sign).view(-1, 1), ret) if jacobians is not None: SO3._check_jacobians_list(jacobians) - jac = torch.zeros_like(self.tensor) theta2 = theta**2 sine_theta = sine * theta @@ -353,40 +369,44 @@ def to_matrix(self) -> torch.Tensor: return self.tensor.clone() def to_quaternion(self) -> torch.Tensor: - ret = torch.zeros(self.shape[0], 4, dtype=self.dtype, device=self.device) - - sine_axis = torch.zeros(self.shape[0], 3, dtype=self.dtype, device=self.device) + sine_axis = self.tensor.new_zeros(self.shape[0], 3) sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) sine_axis[:, 1] = 0.5 * (self[:, 0, 2] - self[:, 2, 0]) sine_axis[:, 2] = 0.5 * (self[:, 1, 0] - self[:, 0, 1]) w = 0.5 * (1 + self[:, 0, 0] + self[:, 1, 1] + self[:, 2, 2]).clamp(0, 4).sqrt() - ret[:, 0] = w + near_zero = w > 1 - self._NEAR_ZERO_EPS + near_pi = w <= self._NEAR_PI_EPS + non_zero = self.tensor.new_ones([1]) + ret = self.tensor.new_zeros(self.shape[0], 4) # theta != pi - not_near_pi = ret[:, 0] > self._NEAR_PI_EPS - ret[:, 1:] = 0.5 * sine_axis / w.view(-1, 1) + ret[:, 0] = w + ret[:, 1:] = 0.5 * sine_axis / torch.where(near_pi, non_zero, w).view(-1, 1) # theta ~ pi - near_pi = ~not_near_pi - ddiag = torch.diagonal(self[near_pi], dim1=1, dim2=2) + ddiag = torch.diagonal(self.tensor, dim1=1, dim2=2) # Find the index of major coloumns and diagonals major = torch.logical_and( ddiag[:, 1] > ddiag[:, 0], ddiag[:, 1] > ddiag[:, 2] ) + 2 * torch.logical_and(ddiag[:, 2] > ddiag[:, 0], ddiag[:, 2] > ddiag[:, 1]) - sel_rows = 0.5 * (self[near_pi, major] + self[near_pi, :, major]) - aux = torch.ones(sel_rows.shape[0], dtype=torch.bool) - cosine_near_pi = 0.5 * ( - self[near_pi, 0, 0] + self[near_pi, 1, 1] + self[near_pi, 2, 2] - 1 - ) + aux = torch.ones(self.shape[0], dtype=torch.bool) + sel_rows = 0.5 * (self[aux, major] + self[aux, :, major]) + cosine_near_pi = 0.5 * (self[:, 0, 0] + self[:, 1, 1] + self[:, 2, 2] - 1) sel_rows[aux, major] -= cosine_near_pi axis = ( sel_rows - / sel_rows.norm(dim=1, keepdim=True) - * sine_axis[near_pi, major].sign().view(-1, 1) + / torch.where( + near_zero.view(-1, 1), + non_zero.view(-1, 1), + sel_rows.norm(dim=1, keepdim=True), + ) + * sine_axis[aux, major].sign().view(-1, 1) ) sine_half_theta = (0.5 * (1 - cosine_near_pi)).clamp(0, 1).sqrt().view(-1, 1) - ret[near_pi, 1:] = axis * sine_half_theta + ret[:, 1:] = torch.where( + near_pi.view(-1, 1), axis * sine_half_theta, ret[:, 1:] + ) return ret @@ -396,15 +416,15 @@ def hat(tangent_vector: torch.Tensor) -> torch.Tensor: _check |= tangent_vector.ndim == 2 and tangent_vector.shape[1] == 3 if not _check: raise ValueError("Invalid vee matrix for SO3.") - matrix = torch.zeros(tangent_vector.shape[0], 3, 3).to( - dtype=tangent_vector.dtype, device=tangent_vector.device - ) + matrix = tangent_vector.new_zeros(tangent_vector.shape[0], 3, 3) + matrix[:, 0, 1] = -tangent_vector[:, 2].view(-1) matrix[:, 0, 2] = tangent_vector[:, 1].view(-1) matrix[:, 1, 2] = -tangent_vector[:, 0].view(-1) matrix[:, 1, 0] = tangent_vector[:, 2].view(-1) matrix[:, 2, 0] = -tangent_vector[:, 1].view(-1) matrix[:, 2, 1] = tangent_vector[:, 0].view(-1) + return matrix @staticmethod @@ -430,7 +450,7 @@ def _rotate_shape_check(self, point: Union[Point3, torch.Tensor]): raise ValueError(err_msg) @staticmethod - def unit_quaternion_to_SO3(quaternion: torch.torch.Tensor) -> "SO3": + def unit_quaternion_to_SO3(quaternion: torch.Tensor) -> "SO3": if quaternion.ndim == 1: quaternion = quaternion.unsqueeze(0) SO3._unit_quaternion_check(quaternion) @@ -451,9 +471,8 @@ def unit_quaternion_to_SO3(quaternion: torch.torch.Tensor) -> "SO3": q33 = q3 * q3 ret = SO3() - ret.tensor = torch.zeros(quaternion.shape[0], 3, 3).to( - dtype=quaternion.dtype, device=quaternion.device - ) + ret.tensor = quaternion.new_zeros(quaternion.shape[0], 3, 3) + ret[:, 0, 0] = 2 * (q00 + q11) - 1 ret[:, 0, 1] = 2 * (q12 - q03) ret[:, 0, 2] = 2 * (q13 + q02) @@ -513,7 +532,7 @@ def unrotate( if jacobians is not None: self._check_jacobians_list(jacobians) # Left jacobians for SO3 are computed - Jrot = torch.zeros(batch_size, 3, 3, dtype=self.dtype, device=self.device) + Jrot = self.tensor.new_zeros(batch_size, 3, 3) Jrot[:, 0, 1] = -ret[:, 2] Jrot[:, 1, 0] = ret[:, 2] Jrot[:, 0, 2] = ret[:, 1] @@ -527,6 +546,123 @@ def unrotate( return ret + def _deprecated_log_map_impl( + self, jacobians: Optional[List[torch.Tensor]] = None + ) -> torch.Tensor: + sine_axis = self.tensor.new_zeros(self.shape[0], 3) + sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) + sine_axis[:, 1] = 0.5 * (self[:, 0, 2] - self[:, 2, 0]) + sine_axis[:, 2] = 0.5 * (self[:, 1, 0] - self[:, 0, 1]) + cosine = 0.5 * (self[:, 0, 0] + self[:, 1, 1] + self[:, 2, 2] - 1) + sine = sine_axis.norm(dim=1) + theta = torch.atan2(sine, cosine) + + near_zero = theta < self._NEAR_ZERO_EPS + + near_pi = 1 + cosine <= self._NEAR_PI_EPS + # theta != pi + near_zero_or_near_pi = torch.logical_or(near_zero, near_pi) + # Compute the approximation of theta / sin(theta) when theta is near to 0 + non_zero = torch.ones(1, dtype=self.dtype, device=self.device) + sine_nz = torch.where(near_zero_or_near_pi, non_zero, sine) + scale = torch.where( + near_zero_or_near_pi, + 1 + sine**2 / 6, + theta / sine_nz, + ) + ret = sine_axis * scale.view(-1, 1) + + if near_pi.any(): + ddiag = torch.diagonal(self[near_pi], dim1=1, dim2=2) + # Find the index of major coloumns and diagonals + major = torch.logical_and( + ddiag[:, 1] > ddiag[:, 0], ddiag[:, 1] > ddiag[:, 2] + ) + 2 * torch.logical_and( + ddiag[:, 2] > ddiag[:, 0], ddiag[:, 2] > ddiag[:, 1] + ) + sel_rows = 0.5 * (self[near_pi, major] + self[near_pi, :, major]) + aux = torch.ones(sel_rows.shape[0], dtype=torch.bool) + sel_rows[aux, major] -= cosine[near_pi] + axis = sel_rows / sel_rows.norm(dim=1, keepdim=True) + sign_tmp = sine_axis[near_pi, major].sign() + sign = torch.where(sign_tmp != 0, sign_tmp, torch.ones_like(sign_tmp)) + ret[near_pi] = axis * (theta[near_pi] * sign).view(-1, 1) + + if jacobians is not None: + SO3._check_jacobians_list(jacobians) + + theta2 = theta**2 + sine_theta = sine * theta + two_cosine_minus_two = 2 * cosine - 2 + two_cosine_minus_two_nz = torch.where( + near_zero, non_zero, two_cosine_minus_two + ) + theta2_nz = torch.where(near_zero, non_zero, theta2) + + a = torch.where( + near_zero, 1 - theta2 / 12, -sine_theta / two_cosine_minus_two_nz + ) + b = torch.where( + near_zero, + 1.0 / 12 + theta2 / 720, + (sine_theta + two_cosine_minus_two) + / (theta2_nz * two_cosine_minus_two_nz), + ) + + jac = (b.view(-1, 1) * ret).view(-1, 3, 1) * ret.view(-1, 1, 3) + + half_ret = 0.5 * ret + jac[:, 0, 1] -= half_ret[:, 2] + jac[:, 1, 0] += half_ret[:, 2] + jac[:, 0, 2] += half_ret[:, 1] + jac[:, 2, 0] -= half_ret[:, 1] + jac[:, 1, 2] -= half_ret[:, 0] + jac[:, 2, 1] += half_ret[:, 0] + + diag_jac = torch.diagonal(jac, dim1=1, dim2=2) + diag_jac += a.view(-1, 1) + + jacobians.append(jac) + + return ret + + def _deprecated_to_quaternion(self) -> torch.Tensor: + sine_axis = self.tensor.new_zeros(self.shape[0], 3) + sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) + sine_axis[:, 1] = 0.5 * (self[:, 0, 2] - self[:, 2, 0]) + sine_axis[:, 2] = 0.5 * (self[:, 1, 0] - self[:, 0, 1]) + w = 0.5 * (1 + self[:, 0, 0] + self[:, 1, 1] + self[:, 2, 2]).clamp(0, 4).sqrt() + + near_pi = w <= self._NEAR_PI_EPS + non_zero = self.tensor.new_ones([1]) + + ret = self.tensor.new_zeros(self.shape[0], 4) + # theta != pi + ret[:, 0] = w + ret[:, 1:] = 0.5 * sine_axis / torch.where(near_pi, non_zero, w).view(-1, 1) + + # theta ~ pi + ddiag = torch.diagonal(self[near_pi], dim1=1, dim2=2) + # Find the index of major coloumns and diagonals + major = torch.logical_and( + ddiag[:, 1] > ddiag[:, 0], ddiag[:, 1] > ddiag[:, 2] + ) + 2 * torch.logical_and(ddiag[:, 2] > ddiag[:, 0], ddiag[:, 2] > ddiag[:, 1]) + sel_rows = 0.5 * (self[near_pi, major] + self[near_pi, :, major]) + aux = torch.ones(sel_rows.shape[0], dtype=torch.bool) + cosine_near_pi = 0.5 * ( + self[near_pi, 0, 0] + self[near_pi, 1, 1] + self[near_pi, 2, 2] - 1 + ) + sel_rows[aux, major] -= cosine_near_pi + axis = ( + sel_rows + / sel_rows.norm(dim=1, keepdim=True) + * sine_axis[near_pi, major].sign().view(-1, 1) + ) + sine_half_theta = (0.5 * (1 - cosine_near_pi)).clamp(0, 1).sqrt().view(-1, 1) + ret[near_pi, 1:] = axis * sine_half_theta + + return ret + rand_so3 = SO3.rand randn_so3 = SO3.randn diff --git a/theseus/geometry/tests/common.py b/theseus/geometry/tests/common.py index 20ab5e8a0..f09bd7a5a 100644 --- a/theseus/geometry/tests/common.py +++ b/theseus/geometry/tests/common.py @@ -7,77 +7,87 @@ from theseus.constants import TEST_EPS from theseus.utils import numeric_jacobian +from theseus.geometry.lie_group_check import set_lie_group_check_enabled + + +def check_exp_map(tangent_vector, group_cls, atol=TEST_EPS, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + group = group_cls.exp_map(tangent_vector) + tangent_vector_double = tangent_vector.double() + tangent_vector_double.to(dtype=torch.float64) + assert torch.allclose( + group_cls.hat(tangent_vector_double).matrix_exp(), + group.to_matrix().double(), + atol=atol, + ) -def check_exp_map(tangent_vector, group_cls, atol=TEST_EPS): - group = group_cls.exp_map(tangent_vector) - tangent_vector_double = tangent_vector.double() - tangent_vector_double.to(dtype=torch.float64) - assert torch.allclose( - group_cls.hat(tangent_vector_double).matrix_exp(), - group.to_matrix().double(), - atol=atol, - ) - - -def check_log_map(tangent_vector, group_cls, atol=TEST_EPS): - assert torch.allclose( - tangent_vector, group_cls.exp_map(tangent_vector).log_map(), atol=atol - ) - - -def check_compose(group_1, group_2): - Jcmp = [] - composition = group_1.compose(group_2, jacobians=Jcmp) - expected_matrix = group_1.to_matrix() @ group_2.to_matrix() - group_1_double = group_1.copy() - group_1_double.to(torch.float64) - group_2_double = group_2.copy() - group_2_double.to(torch.float64) - expected_jacs = numeric_jacobian( - lambda groups: groups[0].compose(groups[1]), - [group_1_double, group_2_double], - ) - batch = group_1.shape[0] - dof = group_1.dof() - assert torch.allclose(composition.to_matrix(), expected_matrix, atol=TEST_EPS) - assert torch.allclose(Jcmp[0].double(), expected_jacs[0], atol=TEST_EPS) - assert torch.allclose( - Jcmp[1].double(), - torch.eye(dof, dof, dtype=torch.float64).unsqueeze(0).expand(batch, dof, dof), - atol=TEST_EPS, - ) - if group_1.dtype == torch.float64: - assert torch.allclose(Jcmp[1].double(), expected_jacs[1], atol=TEST_EPS) +def check_log_map(tangent_vector, group_cls, atol=TEST_EPS, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + assert torch.allclose( + tangent_vector, group_cls.exp_map(tangent_vector).log_map(), atol=atol + ) -def check_inverse(group): - tangent_vector = group.log_map() - inverse_group = group.exp_map(-tangent_vector.double()) - jac = [] - inverse_result = group.inverse(jacobian=jac) - group_double = group.copy() - group_double.to(torch.float64) - expected_jac = numeric_jacobian(lambda groups: groups[0].inverse(), [group_double]) - assert torch.allclose( - inverse_group.to_matrix().double(), - inverse_result.to_matrix().double(), - atol=TEST_EPS, - ) - assert torch.allclose(jac[0].double(), expected_jac[0], atol=TEST_EPS) +def check_compose(group_1, group_2, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + Jcmp = [] + composition = group_1.compose(group_2, jacobians=Jcmp) + expected_matrix = group_1.to_matrix() @ group_2.to_matrix() + group_1_double = group_1.copy() + group_1_double.to(torch.float64) + group_2_double = group_2.copy() + group_2_double.to(torch.float64) + expected_jacs = numeric_jacobian( + lambda groups: groups[0].compose(groups[1]), + [group_1_double, group_2_double], + ) + batch = group_1.shape[0] + dof = group_1.dof() + assert torch.allclose(composition.to_matrix(), expected_matrix, atol=TEST_EPS) + assert torch.allclose(Jcmp[0].double(), expected_jacs[0], atol=TEST_EPS) + assert torch.allclose( + Jcmp[1].double(), + torch.eye(dof, dof, dtype=torch.float64) + .unsqueeze(0) + .expand(batch, dof, dof), + atol=TEST_EPS, + ) + if group_1.dtype == torch.float64: + assert torch.allclose(Jcmp[1].double(), expected_jacs[1], atol=TEST_EPS) + + +def check_inverse(group, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + tangent_vector = group.log_map() + inverse_group = group.exp_map(-tangent_vector.double()) + jac = [] + inverse_result = group.inverse(jacobian=jac) + group_double = group.copy() + group_double.to(torch.float64) + expected_jac = numeric_jacobian( + lambda groups: groups[0].inverse(), [group_double] + ) + assert torch.allclose( + inverse_group.to_matrix().double(), + inverse_result.to_matrix().double(), + atol=TEST_EPS, + ) + assert torch.allclose(jac[0].double(), expected_jac[0], atol=TEST_EPS) -def check_adjoint(group, tangent_vector): - tangent_left = group.__class__.adjoint(group) @ tangent_vector.unsqueeze(2) - group_matrix = group.to_matrix() - tangent_right = group.__class__.vee( - group_matrix.double() - @ group.hat(tangent_vector.double()) - @ group.inverse().to_matrix().double() - ) - assert torch.allclose( - tangent_left.double().squeeze(2), tangent_right, atol=TEST_EPS - ) +def check_adjoint(group, tangent_vector, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + tangent_left = group.__class__.adjoint(group) @ tangent_vector.unsqueeze(2) + group_matrix = group.to_matrix() + tangent_right = group.__class__.vee( + group_matrix.double() + @ group.hat(tangent_vector.double()) + @ group.inverse().to_matrix().double() + ) + assert torch.allclose( + tangent_left.double().squeeze(2), tangent_right, atol=TEST_EPS + ) # Func can be SO2.rotate, SE2.transform_to, SO3.unrotate, etc., whose third argument @@ -138,185 +148,201 @@ def func(g, p): def check_projection_for_compose( - Group, batch_size, generator=None, dtype=torch.float64 + Group, batch_size, generator=None, dtype=torch.float64, enable_functorch=False ): - group1_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) - group2_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) - group1 = group1_double.copy() - group1.to(dtype) - group2 = group2_double.copy() - group2.to(dtype) - - jac = [] - rets = group1.compose(group2, jacobians=jac) - - def func(g1, g2): - return Group(tensor=g1).compose(Group(tensor=g2)).to_matrix() - - jac_raw = torch.autograd.functional.jacobian( - func, (group1_double.tensor, group2_double.tensor) - ) + with set_lie_group_check_enabled(enable_functorch): + group1_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) + group2_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) + group1 = group1_double.copy() + group1.to(dtype) + group2 = group2_double.copy() + group2.to(dtype) + + jac = [] + rets = group1.compose(group2, jacobians=jac) + + def func(g1, g2): + return Group(tensor=g1).compose(Group(tensor=g2)).to_matrix() + + jac_raw = torch.autograd.functional.jacobian( + func, (group1_double.tensor, group2_double.tensor) + ) - # Check returns - assert torch.allclose(rets.to_matrix(), func(group1.tensor, group2.tensor)) + # Check returns + assert torch.allclose(rets.to_matrix(), func(group1.tensor, group2.tensor)) - # Check for dense jacobian matrices - if dtype == torch.float32: - jac_raw = [jac_raw_n.float() for jac_raw_n in jac_raw] + # Check for dense jacobian matrices + if dtype == torch.float32: + jac_raw = [jac_raw_n.float() for jac_raw_n in jac_raw] - temp = [group1.project(jac_raw[0]), group2.project(jac_raw[1])] - actual = [ - torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), - torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), - ] + temp = [group1.project(jac_raw[0]), group2.project(jac_raw[1])] + actual = [ + torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), + torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), + ] - for n in torch.arange(batch_size): - for i in torch.arange(rets.dof()): - actual[0][:, :, n, i] = rets.vee( - rets.inverse().to_matrix() @ temp[0][:, :, :, n, i] - ) - actual[1][:, :, n, i] = rets.vee( - rets.inverse().to_matrix() @ temp[1][:, :, :, n, i] - ) + for n in torch.arange(batch_size): + for i in torch.arange(rets.dof()): + actual[0][:, :, n, i] = rets.vee( + rets.inverse().to_matrix() @ temp[0][:, :, :, n, i] + ) + actual[1][:, :, n, i] = rets.vee( + rets.inverse().to_matrix() @ temp[1][:, :, :, n, i] + ) - expected = [ - torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), - torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), - ] + expected = [ + torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), + torch.zeros(batch_size, rets.dof(), batch_size, rets.dof(), dtype=dtype), + ] - aux_id = torch.arange(batch_size) + aux_id = torch.arange(batch_size) - expected[0][aux_id, :, aux_id, :] = jac[0] - expected[1][aux_id, :, aux_id, :] = jac[1] + expected[0][aux_id, :, aux_id, :] = jac[0] + expected[1][aux_id, :, aux_id, :] = jac[1] - assert torch.allclose(actual[0], expected[0], atol=TEST_EPS) - assert torch.allclose(actual[1], expected[1], atol=TEST_EPS) + assert torch.allclose(actual[0], expected[0], atol=TEST_EPS) + assert torch.allclose(actual[1], expected[1], atol=TEST_EPS) - # Check for sparse jacobian matrices - temp = [ - group1.project(jac_raw[0][aux_id, :, :, aux_id], is_sparse=True), - group2.project(jac_raw[1][aux_id, :, :, aux_id], is_sparse=True), - ] - actual = [ - torch.zeros(batch_size, rets.dof(), rets.dof(), dtype=dtype), - torch.zeros(batch_size, rets.dof(), rets.dof(), dtype=dtype), - ] + # Check for sparse jacobian matrices + temp = [ + group1.project(jac_raw[0][aux_id, :, :, aux_id], is_sparse=True), + group2.project(jac_raw[1][aux_id, :, :, aux_id], is_sparse=True), + ] + actual = [ + torch.zeros(batch_size, rets.dof(), rets.dof(), dtype=dtype), + torch.zeros(batch_size, rets.dof(), rets.dof(), dtype=dtype), + ] - for i in torch.arange(rets.dof()): - actual[0][:, :, i] = rets.vee(rets.inverse().to_matrix() @ temp[0][:, :, :, i]) - actual[1][:, :, i] = rets.vee(rets.inverse().to_matrix() @ temp[1][:, :, :, i]) + for i in torch.arange(rets.dof()): + actual[0][:, :, i] = rets.vee( + rets.inverse().to_matrix() @ temp[0][:, :, :, i] + ) + actual[1][:, :, i] = rets.vee( + rets.inverse().to_matrix() @ temp[1][:, :, :, i] + ) - expected = jac + expected = jac - assert torch.allclose(actual[0], expected[0], atol=TEST_EPS) - assert torch.allclose(actual[1], expected[1], atol=TEST_EPS) + assert torch.allclose(actual[0], expected[0], atol=TEST_EPS) + assert torch.allclose(actual[1], expected[1], atol=TEST_EPS) def check_projection_for_inverse( - Group, batch_size, generator=None, dtype=torch.float64 + Group, batch_size, generator=None, dtype=torch.float64, enable_functorch=False ): - group_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) - group = group_double.copy() - group.to(dtype) - - jac = [] - rets = group.inverse(jacobian=jac) - - def func(g): - return Group(tensor=g).inverse().to_matrix() - - jac_raw = torch.autograd.functional.jacobian(func, (group_double.tensor)) - - if dtype == torch.float32: - jac_raw = jac_raw.float() - - # Check returns - assert torch.allclose(rets.to_matrix(), func(group.tensor), atol=TEST_EPS) + with set_lie_group_check_enabled(enable_functorch): + group_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) + group = group_double.copy() + group.to(dtype) - # Check for dense jacobian matrices - temp = group.project(jac_raw) - actual = torch.zeros(batch_size, group.dof(), batch_size, group.dof(), dtype=dtype) + jac = [] + rets = group.inverse(jacobian=jac) - for n in torch.arange(batch_size): - for i in torch.arange(group.dof()): - actual[:, :, n, i] = group.vee(group.to_matrix() @ temp[:, :, :, n, i]) + def func(g): + return Group(tensor=g).inverse().to_matrix() - expected = torch.zeros( - batch_size, group.dof(), batch_size, group.dof(), dtype=dtype - ) + jac_raw = torch.autograd.functional.jacobian(func, (group_double.tensor)) - aux_id = torch.arange(batch_size) + if dtype == torch.float32: + jac_raw = jac_raw.float() - expected[aux_id, :, aux_id, :] = jac[0] + # Check returns + assert torch.allclose(rets.to_matrix(), func(group.tensor), atol=TEST_EPS) - assert torch.allclose(actual, expected, atol=TEST_EPS) + # Check for dense jacobian matrices + temp = group.project(jac_raw) + actual = torch.zeros( + batch_size, group.dof(), batch_size, group.dof(), dtype=dtype + ) - # Check for sparse jacobian matrices - temp = group.project(jac_raw[aux_id, :, :, aux_id], is_sparse=True) - actual = torch.zeros(batch_size, group.dof(), group.dof(), dtype=dtype) + for n in torch.arange(batch_size): + for i in torch.arange(group.dof()): + actual[:, :, n, i] = group.vee(group.to_matrix() @ temp[:, :, :, n, i]) - for i in torch.arange(group.dof()): - actual[:, :, i] = group.vee(group.to_matrix() @ temp[:, :, :, i]) + expected = torch.zeros( + batch_size, group.dof(), batch_size, group.dof(), dtype=dtype + ) - expected = jac[0] + aux_id = torch.arange(batch_size) - assert torch.allclose(actual, expected, atol=TEST_EPS) + expected[aux_id, :, aux_id, :] = jac[0] + assert torch.allclose(actual, expected, atol=TEST_EPS) -def check_projection_for_exp_map(tangent_vector, Group, is_projected=True, atol=1e-8): - batch_size = tangent_vector.shape[0] - dof = tangent_vector.shape[1] - aux_id = torch.arange(batch_size) + # Check for sparse jacobian matrices + temp = group.project(jac_raw[aux_id, :, :, aux_id], is_sparse=True) + actual = torch.zeros(batch_size, group.dof(), group.dof(), dtype=dtype) - def exp_func(xi): - return Group.exp_map(xi).to_matrix() + for i in torch.arange(group.dof()): + actual[:, :, i] = group.vee(group.to_matrix() @ temp[:, :, :, i]) - actual = [] - _ = Group.exp_map(tangent_vector, jacobians=actual).to_matrix() + expected = jac[0] - tangent_vector_double = tangent_vector.double() - group_double = Group.exp_map(tangent_vector_double).to_matrix() - jac_raw = torch.autograd.functional.jacobian(exp_func, (tangent_vector_double)) + assert torch.allclose(actual, expected, atol=TEST_EPS) - if is_projected: - jac_raw = jac_raw[aux_id, :, :, aux_id] - expected = torch.cat( - [ - Group.vee(group_double.inverse() @ jac_raw[:, :, :, i]).view(-1, dof, 1) - for i in torch.arange(dof) - ], - dim=2, - ) - else: - expected = jac_raw[aux_id, :, aux_id] - - assert torch.allclose(actual[0].double(), expected, atol=atol) +def check_projection_for_exp_map( + tangent_vector, Group, is_projected=True, atol=1e-8, enable_functorch=False +): + with set_lie_group_check_enabled(enable_functorch): + batch_size = tangent_vector.shape[0] + dof = tangent_vector.shape[1] + aux_id = torch.arange(batch_size) + + def exp_func(xi): + return Group.exp_map(xi).to_matrix() + + actual = [] + _ = Group.exp_map(tangent_vector, jacobians=actual).to_matrix() + + tangent_vector_double = tangent_vector.double() + group_double = Group.exp_map(tangent_vector_double).to_matrix() + jac_raw = torch.autograd.functional.jacobian(exp_func, (tangent_vector_double)) + + if is_projected: + jac_raw = jac_raw[aux_id, :, :, aux_id] + expected = torch.cat( + [ + Group.vee(group_double.inverse() @ jac_raw[:, :, :, i]).view( + -1, dof, 1 + ) + for i in torch.arange(dof) + ], + dim=2, + ) + else: + expected = jac_raw[aux_id, :, aux_id] -def check_projection_for_log_map(tangent_vector, Group, is_projected=True, atol=1e-8): - batch_size = tangent_vector.shape[0] - aux_id = torch.arange(batch_size) - group_double = Group.exp_map(tangent_vector.double()) - group = group_double.copy() - if tangent_vector.dtype == torch.float32: - group.tensor = group.tensor.float() + assert torch.allclose(actual[0].double(), expected, atol=atol) - def log_func(group): - return Group(tensor=group).log_map() - jac_raw = torch.autograd.functional.jacobian(log_func, (group_double.tensor))[ - aux_id, :, aux_id - ] +def check_projection_for_log_map( + tangent_vector, Group, is_projected=True, atol=1e-8, enable_functorch=False +): + with set_lie_group_check_enabled(enable_functorch): + batch_size = tangent_vector.shape[0] + aux_id = torch.arange(batch_size) + group_double = Group.exp_map(tangent_vector.double()) + group = group_double.copy() + if tangent_vector.dtype == torch.float32: + group.tensor = group.tensor.float() + + def log_func(group): + return Group(tensor=group).log_map() + + jac_raw = torch.autograd.functional.jacobian(log_func, (group_double.tensor))[ + aux_id, :, aux_id + ] - if is_projected: - expected = group_double.project(jac_raw, is_sparse=True) - else: - expected = jac_raw + if is_projected: + expected = group_double.project(jac_raw, is_sparse=True) + else: + expected = jac_raw - actual = [] - _ = group.log_map(jacobians=actual) + actual = [] + _ = group.log_map(jacobians=actual) - assert torch.allclose(actual[0].double(), expected, atol=atol) + assert torch.allclose(actual[0].double(), expected, atol=atol) def check_jacobian_for_local(group0, group1, Group, is_projected=True, atol=TEST_EPS): diff --git a/theseus/geometry/tests/test_se3.py b/theseus/geometry/tests/test_se3.py index a56046c9e..54705ebd8 100644 --- a/theseus/geometry/tests/test_se3.py +++ b/theseus/geometry/tests/test_se3.py @@ -9,6 +9,7 @@ import theseus as th from theseus.constants import TEST_EPS +from theseus.geometry.lie_group_check import set_lie_group_check_enabled from theseus.utils import numeric_jacobian from .common import ( @@ -26,9 +27,10 @@ ) -def check_SE3_log_map(tangent_vector, atol=TEST_EPS): - g = th.SE3.exp_map(tangent_vector) - assert torch.allclose(th.SE3.exp_map(g.log_map()).tensor, g.tensor, atol=atol) +def check_SE3_log_map(tangent_vector, atol=TEST_EPS, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + g = th.SE3.exp_map(tangent_vector) + assert torch.allclose(th.SE3.exp_map(g.log_map()).tensor, g.tensor, atol=atol) def _create_tangent_vector(batch_size, ang_factor, rng, dtype): @@ -45,7 +47,8 @@ def _create_tangent_vector(batch_size, ang_factor, rng, dtype): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] ) -def test_exp_map(batch_size, dtype, ang_factor): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_exp_map(batch_size, dtype, ang_factor, enable_functorch): rng = torch.Generator() rng.manual_seed(0) ATOL = 2e-4 if dtype == torch.float32 else 1e-6 @@ -55,8 +58,10 @@ def test_exp_map(batch_size, dtype, ang_factor): torch.rand(batch_size, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi ) tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) - check_exp_map(tangent_vector, th.SE3, atol=ATOL) - check_projection_for_exp_map(tangent_vector, th.SE3, atol=ATOL) + check_exp_map(tangent_vector, th.SE3, atol=ATOL, enable_functorch=enable_functorch) + check_projection_for_exp_map( + tangent_vector, th.SE3, atol=ATOL, enable_functorch=enable_functorch + ) # This test checks that cross products are done correctly @@ -64,24 +69,28 @@ def test_exp_map(batch_size, dtype, ang_factor): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] ) -def test_batch_size_3_exp_map(dtype, ang_factor): - rng = torch.Generator() - rng.manual_seed(0) - ATOL = 1e-4 if dtype == torch.float32 else 1e-6 - - if ang_factor is None: - ang_factor = torch.rand(6, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi - tangent_vector = _create_tangent_vector(6, ang_factor, rng, dtype) +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_batch_size_3_exp_map(dtype, ang_factor, enable_functorch): + with set_lie_group_check_enabled(enable_functorch): + rng = torch.Generator() + rng.manual_seed(0) + ATOL = 1e-4 if dtype == torch.float32 else 1e-6 + + if ang_factor is None: + ang_factor = ( + torch.rand(6, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi + ) + tangent_vector = _create_tangent_vector(6, ang_factor, rng, dtype) - jac, jac1, jac2 = [], [], [] - g = th.SE3.exp_map(tangent_vector, jac) - g1 = th.SE3.exp_map(tangent_vector[:3], jac1) - g2 = th.SE3.exp_map(tangent_vector[3:], jac2) + jac, jac1, jac2 = [], [], [] + g = th.SE3.exp_map(tangent_vector, jac) + g1 = th.SE3.exp_map(tangent_vector[:3], jac1) + g2 = th.SE3.exp_map(tangent_vector[3:], jac2) - torch.allclose(g.tensor[:3], g1.tensor, atol=1e-6) - torch.allclose(g.tensor[3:], g2.tensor, atol=1e-6) - torch.allclose(jac[0][:3], jac1[0], atol=ATOL) - torch.allclose(jac[0][3:], jac2[0], atol=ATOL) + torch.allclose(g.tensor[:3], g1.tensor, atol=1e-6) + torch.allclose(g.tensor[3:], g2.tensor, atol=1e-6) + torch.allclose(jac[0][:3], jac1[0], atol=ATOL) + torch.allclose(jac[0][3:], jac2[0], atol=ATOL) @pytest.mark.parametrize("batch_size", [1, 20, 100]) @@ -89,7 +98,8 @@ def test_batch_size_3_exp_map(dtype, ang_factor): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-7, np.pi - 1e-10] ) -def test_log_map(batch_size, dtype, ang_factor): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_log_map(batch_size, dtype, ang_factor, enable_functorch): if dtype == torch.float32 and ang_factor == np.pi - 1e-10: return @@ -102,8 +112,10 @@ def test_log_map(batch_size, dtype, ang_factor): torch.rand(batch_size, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi ) tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) - check_SE3_log_map(tangent_vector, atol=ATOL) - check_projection_for_log_map(tangent_vector, th.SE3, atol=PROJECTION_ATOL) + check_SE3_log_map(tangent_vector, atol=ATOL, enable_functorch=enable_functorch) + check_projection_for_log_map( + tangent_vector, th.SE3, atol=PROJECTION_ATOL, enable_functorch=enable_functorch + ) # This test checks that cross products are done correctly @@ -111,57 +123,64 @@ def test_log_map(batch_size, dtype, ang_factor): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] ) -def test_batch_size_3_log_map(dtype, ang_factor): - rng = torch.Generator() - rng.manual_seed(0) - ATOL = 1e-3 if dtype == torch.float32 else 1e-6 - - if ang_factor is None: - ang_factor = torch.rand(6, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi - tangent_vector = _create_tangent_vector(6, ang_factor, rng, dtype) +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_batch_size_3_log_map(dtype, ang_factor, enable_functorch): + with set_lie_group_check_enabled(enable_functorch): + rng = torch.Generator() + rng.manual_seed(0) + ATOL = 1e-3 if dtype == torch.float32 else 1e-6 + + if ang_factor is None: + ang_factor = ( + torch.rand(6, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi + ) + tangent_vector = _create_tangent_vector(6, ang_factor, rng, dtype) - g = th.SE3.exp_map(tangent_vector) - g1 = th.SE3(tensor=g.tensor[:3]) - g2 = th.SE3(tensor=g.tensor[3:]) + g = th.SE3.exp_map(tangent_vector) + g1 = th.SE3(tensor=g.tensor[:3]) + g2 = th.SE3(tensor=g.tensor[3:]) - jac, jac1, jac2 = [], [], [] - d = g.log_map(jac) - d1 = g1.log_map(jac1) - d2 = g2.log_map(jac2) + jac, jac1, jac2 = [], [], [] + d = g.log_map(jac) + d1 = g1.log_map(jac1) + d2 = g2.log_map(jac2) - torch.allclose(d[:3], d1, atol=ATOL) - torch.allclose(d[3:], d2, atol=ATOL) - torch.allclose(jac[0][:3], jac1[0], atol=ATOL) - torch.allclose(jac[0][3:], jac2[0], atol=ATOL) + torch.allclose(d[:3], d1, atol=ATOL) + torch.allclose(d[3:], d2, atol=ATOL) + torch.allclose(jac[0][:3], jac1[0], atol=ATOL) + torch.allclose(jac[0][3:], jac2[0], atol=ATOL) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_compose(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_compose(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for batch_size in [1, 20, 100]: se3_1 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) se3_2 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) - check_compose(se3_1, se3_2) + check_compose(se3_1, se3_2, enable_functorch) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_inverse(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_inverse(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for batch_size in [1, 20, 100]: se3 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) - check_inverse(se3) + check_inverse(se3, enable_functorch) @pytest.mark.parametrize("batch_size", [1, 20, 100]) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_adjoint(batch_size, dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_adjoint(batch_size, dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) se3 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) tangent = torch.randn(batch_size, 6, generator=rng, dtype=dtype) - check_adjoint(se3, tangent) + check_adjoint(se3, tangent, enable_functorch) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @@ -229,7 +248,8 @@ def test_transform_from_and_to(dtype): @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_projection(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_projection(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times @@ -245,10 +265,14 @@ def test_projection(dtype): ) # Test SE3.compose - check_projection_for_compose(th.SE3, batch_size, rng, dtype=dtype) + check_projection_for_compose( + th.SE3, batch_size, rng, dtype=dtype, enable_functorch=enable_functorch + ) # Test SE3.inverse - check_projection_for_inverse(th.SE3, batch_size, rng, dtype=dtype) + check_projection_for_inverse( + th.SE3, batch_size, rng, dtype=dtype, enable_functorch=enable_functorch + ) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) diff --git a/theseus/geometry/tests/test_so3.py b/theseus/geometry/tests/test_so3.py index f7f1a6d49..94e2a4efd 100644 --- a/theseus/geometry/tests/test_so3.py +++ b/theseus/geometry/tests/test_so3.py @@ -9,6 +9,7 @@ import theseus as th from theseus.constants import TEST_EPS +from theseus.geometry.lie_group_check import set_lie_group_check_enabled from theseus.utils import numeric_jacobian from .common import ( @@ -25,17 +26,19 @@ ) -def check_SO3_log_map(tangent_vector, atol=1e-7): - error = (tangent_vector - th.SO3.exp_map(tangent_vector).log_map()).norm(dim=1) - error = torch.minimum(error, (error - 2 * np.pi).abs()) - assert torch.allclose(error, torch.zeros_like(error), atol=atol) +def check_SO3_log_map(tangent_vector, atol=1e-7, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + error = (tangent_vector - th.SO3.exp_map(tangent_vector).log_map()).norm(dim=1) + error = torch.minimum(error, (error - 2 * np.pi).abs()) + assert torch.allclose(error, torch.zeros_like(error), atol=atol) -def check_SO3_to_quaternion(so3: th.SO3, atol=1e-10): - quaternions = so3.to_quaternion() - assert torch.allclose( - th.SO3(quaternion=quaternions).to_matrix(), so3.to_matrix(), atol=atol - ) +def check_SO3_to_quaternion(so3: th.SO3, atol=1e-10, enable_functorch=False): + with set_lie_group_check_enabled(enable_functorch): + quaternions = so3.to_quaternion() + assert torch.allclose( + th.SO3(quaternion=quaternions).to_matrix(), so3.to_matrix(), atol=atol + ) def _create_tangent_vector(batch_size, ang_factor, rng, dtype): @@ -50,7 +53,8 @@ def _create_tangent_vector(batch_size, ang_factor, rng, dtype): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-7, np.pi - 1e-11] ) -def test_exp_map(batch_size, dtype, ang_factor): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_exp_map(batch_size, dtype, ang_factor, enable_functorch): rng = torch.Generator() rng.manual_seed(0) ATOL = 2e-4 if dtype == torch.float32 else 1e-6 @@ -61,7 +65,7 @@ def test_exp_map(batch_size, dtype, ang_factor): ) tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) - check_exp_map(tangent_vector, th.SO3, atol=ATOL) + check_exp_map(tangent_vector, th.SO3, atol=ATOL, enable_functorch=enable_functorch) check_projection_for_exp_map(tangent_vector, th.SO3, atol=ATOL) @@ -70,7 +74,8 @@ def test_exp_map(batch_size, dtype, ang_factor): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] ) -def test_log_map(batch_size, dtype, ang_factor): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_log_map(batch_size, dtype, ang_factor, enable_functorch): if dtype == torch.float32 and ang_factor == np.pi - 1e-11: return @@ -85,8 +90,10 @@ def test_log_map(batch_size, dtype, ang_factor): ) tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) - check_SO3_log_map(tangent_vector, atol=ATOL) - check_projection_for_log_map(tangent_vector, th.SO3, atol=PROJECTION_ATOL) + check_SO3_log_map(tangent_vector, atol=ATOL, enable_functorch=enable_functorch) + check_projection_for_log_map( + tangent_vector, th.SO3, atol=PROJECTION_ATOL, enable_functorch=enable_functorch + ) @pytest.mark.parametrize("batch_size", [1, 20, 100]) @@ -94,7 +101,8 @@ def test_log_map(batch_size, dtype, ang_factor): @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] ) -def test_quaternion(batch_size, dtype, ang_factor): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_quaternion(batch_size, dtype, ang_factor, enable_functorch): rng = torch.Generator() rng.manual_seed(0) ATOL = 1e-3 if dtype == torch.float32 else 1e-8 @@ -106,17 +114,18 @@ def test_quaternion(batch_size, dtype, ang_factor): tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) so3 = th.SO3.exp_map(tangent_vector) - check_SO3_to_quaternion(so3, atol=ATOL) + check_SO3_to_quaternion(so3, atol=ATOL, enable_functorch=enable_functorch) @pytest.mark.parametrize("batch_size", [1, 20, 100]) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_adjoint(batch_size, dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_adjoint(batch_size, dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) so3 = th.SO3.rand(batch_size, generator=rng, dtype=dtype) tangent = torch.randn(batch_size, 3, dtype=dtype) - check_adjoint(so3, tangent) + check_adjoint(so3, tangent, enable_functorch) @pytest.mark.parametrize("batch_size", [1, 20, 100]) @@ -194,7 +203,8 @@ def test_rotate_and_unrotate(dtype): @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_projection(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_projection(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times @@ -210,10 +220,14 @@ def test_projection(dtype): ) # Test SO3.compose - check_projection_for_compose(th.SO3, batch_size, rng, dtype=dtype) + check_projection_for_compose( + th.SO3, batch_size, rng, dtype=dtype, enable_functorch=enable_functorch + ) # Test SO3.inverse - check_projection_for_inverse(th.SO3, batch_size, rng, dtype=dtype) + check_projection_for_inverse( + th.SO3, batch_size, rng, dtype=dtype, enable_functorch=enable_functorch + ) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) From d2b4e812e5b6de91c3be66c810bc72d5ba2d64e7 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Wed, 7 Sep 2022 18:07:21 -0400 Subject: [PATCH 19/38] Add SE2 support in MotionPlanner (#282) * Refactored MotionPlanner so that objective can be passed separately. * Added SE2 support in motion planner class. * Removed changes to notebooks. * Modified motion planning utility functions to support SE2. * Bug fixes and improvements to SE2 trajectory plot. * Simplified some motion planning utils using var.numel(). --- .pre-commit-config.yaml | 2 +- .../utils/examples/motion_planning/misc.py | 41 +++++- .../motion_planning/motion_planner.py | 131 ++++++++++++++---- 3 files changed, 141 insertions(+), 33 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e91909664..ba0f3b271 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -13,7 +13,7 @@ repos: rev: v0.931 hooks: - id: mypy - additional_dependencies: [torch==1.9.0, tokenize-rt==3.2.0, types-PyYAML, types-mock] + additional_dependencies: [torch, tokenize-rt==3.2.0, types-PyYAML, types-mock] args: [--no-strict-optional, --ignore-missing-imports] exclude: setup.py diff --git a/theseus/utils/examples/motion_planning/misc.py b/theseus/utils/examples/motion_planning/misc.py index 5c74e4a54..122bf1900 100644 --- a/theseus/utils/examples/motion_planning/misc.py +++ b/theseus/utils/examples/motion_planning/misc.py @@ -132,13 +132,34 @@ def _create_line_from_trajectory( return line -def _add_robot_to_trajectory(x_list, y_list, radius, color="magenta", alpha=0.05): +def _get_triangle_pts(x, y, theta, radius): + triangle_pts = [] + + def _append(new_theta, scale=1.0): + x_new = x + radius * np.cos(new_theta) * scale + y_new = y + radius * np.sin(new_theta) * scale + triangle_pts.append((x_new, y_new)) + + _append(theta, 1.0) + _append(theta + np.pi / 2, 0.5) + _append(theta - np.pi / 2, 0.5) + return triangle_pts + + +def _add_robot_to_trajectory( + x_list, y_list, radius, color="magenta", alpha=0.05, theta=None +): patches = [] for i in range(x_list.shape[0]): - patch = mpl.patches.Circle((x_list[i], y_list[i]), radius) - patches.append(patch) + if theta is None: + patches.append(mpl.patches.Circle((x_list[i], y_list[i]), radius)) + alpha_ = alpha + else: + triangle_pts = _get_triangle_pts(x_list[i], y_list[i], theta[i], radius) + patches.append(mpl.patches.Polygon(triangle_pts)) + alpha_ = 2 * alpha patch_collection = mpl.collections.PatchCollection( - patches, alpha=alpha, color=color + patches, alpha=alpha_, color=color ) return patch_collection @@ -158,10 +179,17 @@ def generate_trajectory_figs( # cell rows/cols for each batch of trajectories traj_rows = [] traj_cols = [] + traj_angles = [] + # Trajectories in the list correspond to different sources + # (e.g., motion planner, expert, straight line, etc.) + # Each trajectory tensor has shape (num_maps, data_size, traj_len) for trajectory in trajectories: row, col, _ = sdf.convert_points_to_cell(trajectory[:, :2, :]) traj_rows.append(np.clip(row, 0, map_tensor.shape[1] - 1)) traj_cols.append(np.clip(col, 0, map_tensor.shape[1] - 1)) + if trajectory.shape[1] == 7: # SE2 trajectory + traj_angles.append(torch.atan2(trajectory[:, 3], trajectory[:, 2]).numpy()) + assert len(traj_angles) == 0 or len(traj_angles) == len(traj_rows) # Generate a separate figure for each batch index colors = ["green", "blue", "red"] @@ -189,12 +217,15 @@ def generate_trajectory_figs( for t_idx, trajectory in enumerate(trajectories): row = traj_rows[t_idx][map_idx] col = traj_cols[t_idx][map_idx] + theta = None if len(traj_angles) == 0 else traj_angles[t_idx][map_idx] line = _create_line_from_trajectory(col, row, color=colors[t_idx]) path_ax.add_line(line) if t_idx == fig_idx_robot: # solution trajectory cs_idx = map_idx if cell_size.shape[0] > 1 else 0 radius = robot_radius / cell_size[cs_idx][0] - patch_coll = _add_robot_to_trajectory(col, row, radius, alpha=0.10) + patch_coll = _add_robot_to_trajectory( + col, row, radius, alpha=0.10, theta=theta + ) path_ax.add_collection(patch_coll) patches.append(mpl.patches.Patch(color=colors[t_idx], label=labels[t_idx])) patches.append( diff --git a/theseus/utils/examples/motion_planning/motion_planner.py b/theseus/utils/examples/motion_planning/motion_planner.py index 08ff9b45c..c157fde6c 100644 --- a/theseus/utils/examples/motion_planning/motion_planner.py +++ b/theseus/utils/examples/motion_planning/motion_planner.py @@ -4,13 +4,55 @@ # LICENSE file in the root directory of this source tree. import copy -from typing import Any, Dict, List, Optional, Tuple +from typing import Any, Dict, List, Optional, Tuple, Type, Union import torch import theseus as th +class _XYDifference(th.CostFunction): + def __init__( + self, + var: th.SE2, + target: th.Point2, + cost_weight: th.CostWeight, + name: Optional[str] = None, + ): + super().__init__(cost_weight, name=name) + if not isinstance(var, th.SE2) and not isinstance(target, th.Point2): + raise ValueError( + "XYDifference expects var of type SE2 and target of type Point2." + ) + self.var = var + self.target = target + self.register_optim_vars(["var"]) + self.register_aux_vars(["target"]) + + def _jacobians_and_error_impl( + self, compute_jacobians: bool = False + ) -> Tuple[List[torch.Tensor], torch.Tensor]: + Jlocal: List[torch.Tensor] = [] if compute_jacobians else None + Jxy: List[torch.Tensor] = [] if compute_jacobians else None + error = self.target.local(self.var.xy(jacobians=Jxy), jacobians=Jlocal) + jac = [Jlocal[1].matmul(Jxy[0])] if compute_jacobians else None + return jac, error + + def error(self) -> torch.Tensor: + return self._jacobians_and_error_impl(compute_jacobians=False)[1] + + def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: + return self._jacobians_and_error_impl(compute_jacobians=True) + + def dim(self) -> int: + return 2 + + def _copy_impl(self, new_name: Optional[str] = None) -> "_XYDifference": + return _XYDifference( # type: ignore + self.var.copy(), self.target.copy(), self.weight.copy(), name=new_name + ) + + class MotionPlannerObjective(th.Objective): def __init__( self, @@ -21,6 +63,7 @@ def __init__( Qc_inv: List[List[int]], num_time_steps: int, use_single_collision_weight: bool = True, + pose_type: Union[Type[th.Point2], Type[th.SE2]] = th.Point2, dtype: torch.dtype = torch.double, ): for v in [ @@ -41,6 +84,7 @@ def __init__( self.Qc_inv = copy.deepcopy(Qc_inv) self.num_time_steps = num_time_steps self.use_single_collision_weight = use_single_collision_weight + self.pose_type = pose_type self.trajectory_len = num_time_steps + 1 @@ -54,7 +98,7 @@ def __init__( # By giving them names, we can update for each batch (if needed), # via the motion planner's forward method. sdf_origin = th.Point2(name="sdf_origin", dtype=dtype) - start_point = th.Point2(name="start", dtype=dtype) + start_pose = pose_type(name="start", dtype=dtype) goal_point = th.Point2(name="goal", dtype=dtype) cell_size = th.Variable(torch.empty(1, 1, dtype=dtype), name="cell_size") sdf_data = th.Variable( @@ -103,13 +147,13 @@ def __init__( # --------------------------------------------------------------------------- # # -------------------------- Optimization variables ------------------------- # # --------------------------------------------------------------------------- # - # The optimization variables for the motion planer are 2-D positions and - # velocities for each of the discrete time steps - poses = [] - velocities = [] + # The optimization variables for the motion planer are poses (Point2/SE2) and + # velocities (Vector) for each of the discrete time steps + poses: List[Union[th.Point2, th.SE2]] = [] + velocities: List[th.Vector] = [] for i in range(self.trajectory_len): - poses.append(th.Point2(name=f"pose_{i}", dtype=dtype)) - velocities.append(th.Point2(name=f"vel_{i}", dtype=dtype)) + poses.append(pose_type(name=f"pose_{i}", dtype=dtype)) + velocities.append(th.Vector(poses[-1].dof(), name=f"vel_{i}", dtype=dtype)) # --------------------------------------------------------------------------- # # ------------------------------ Cost functions ----------------------------- # @@ -118,23 +162,30 @@ def __init__( # which are hard constraints, and can be implemented via Difference cost # functions. self.add( - th.Difference(poses[0], start_point, boundary_cost_weight, name="pose_0") + th.Difference(poses[0], start_pose, boundary_cost_weight, name="pose_0") ) self.add( th.Difference( velocities[0], - th.Point2(tensor=torch.zeros(1, 2, dtype=dtype)), + th.Vector(tensor=torch.zeros(1, velocities[0].dof(), dtype=dtype)), boundary_cost_weight, name="vel_0", ) ) + assert pose_type in [th.Point2, th.SE2] + goal_cost_cls = th.Difference if pose_type == th.Point2 else _XYDifference self.add( - th.Difference(poses[-1], goal_point, boundary_cost_weight, name="pose_N") + goal_cost_cls( + poses[-1], # type: ignore + goal_point, + boundary_cost_weight, + name="pose_N", + ) ) self.add( th.Difference( velocities[-1], - th.Point2(tensor=torch.zeros(1, 2, dtype=dtype)), + th.Vector(tensor=torch.zeros(1, velocities[-1].dof(), dtype=dtype)), boundary_cost_weight, name="vel_N", ) @@ -190,6 +241,7 @@ def __init__( Qc_inv: Optional[List[List[int]]] = None, num_time_steps: Optional[int] = None, use_single_collision_weight: bool = True, + pose_type: Union[Type[th.Point2], Type[th.SE2]] = th.Point2, ): if objective is None: self.objective = MotionPlannerObjective( @@ -200,6 +252,7 @@ def __init__( Qc_inv, num_time_steps, use_single_collision_weight=use_single_collision_weight, + pose_type=pose_type, dtype=dtype, ) else: @@ -286,36 +339,57 @@ def get_variable_values_from_straight_line( ) -> Dict[str, torch.Tensor]: # Returns a dictionary of variable names to values that represent a straight # line trajectory from start to goal. - start_goal_dist = goal - start + # For SE2 variables, the start's angle is used for the full trajectory + start_goal_dist = goal[:, :2] - start[:, :2] avg_vel = start_goal_dist / self.objective.total_time unit_trajectory_len = start_goal_dist / (self.objective.trajectory_len - 1) input_dict: Dict[str, torch.Tensor] = {} for i in range(self.objective.trajectory_len): - input_dict[f"pose_{i}"] = start + unit_trajectory_len * i - input_dict[f"vel_{i}"] = avg_vel + if self.objective.pose_type == th.SE2: + cur_pos = start[:, :2] + unit_trajectory_len * i + input_dict[f"pose_{i}"] = torch.cat([cur_pos, start[:, 2:]], dim=1) + input_dict[f"vel_{i}"] = torch.cat( + [avg_vel, torch.zeros(avg_vel.shape[0], 1)], dim=1 + ) + else: + input_dict[f"pose_{i}"] = start + unit_trajectory_len * i + input_dict[f"vel_{i}"] = avg_vel return input_dict - def get_random_variable_values( - self, start: torch.Tensor + def get_randn_trajectory_like( + self, + start: torch.Tensor, ) -> Dict[str, torch.Tensor]: # Returns a dictionary of variable names with random initial poses. + # The batch size, device and dtype are obtained from given start + pose_numel = self.objective.optim_vars["pose_0"].numel() + vel_numel = self.objective.optim_vars["vel_0"].numel() input_dict: Dict[str, torch.Tensor] = {} + assert start.shape[1] == pose_numel for i in range(self.objective.trajectory_len): input_dict[f"pose_{i}"] = torch.randn_like(start) - input_dict[f"vel_{i}"] = torch.randn_like(start) + input_dict[f"vel_{i}"] = torch.randn_like(start[:, :vel_numel]) return input_dict def get_variable_values_from_trajectory( self, trajectory: torch.Tensor ) -> Dict[str, torch.Tensor]: # Returns a dictionary of variable names to values, so that values - # are assigned with the data from the given trajectory. Trajectory should be a + # are assigned with the data from the given trajectory. + # For Point2 trajectories, trajectory should be a # tensor of shape (batch_size, 4, planner.trajectory_len). - assert trajectory.shape[1:] == (4, self.objective.trajectory_len) + # For SE2 trajectories, it should be a tensor of shape + # tensor of shape (batch_size, 7, planner.trajectory_len). + pose_numel = self.objective.optim_vars["pose_0"].numel() + vel_numel = self.objective.optim_vars["vel_0"].numel() + assert trajectory.shape[1:] == ( + pose_numel + vel_numel, + self.objective.trajectory_len, + ) input_dict: Dict[str, torch.Tensor] = {} for i in range(self.objective.trajectory_len): - input_dict[f"pose_{i}"] = trajectory[:, :2, i] - input_dict[f"vel_{i}"] = trajectory[:, :2, i] + input_dict[f"pose_{i}"] = trajectory[:, :pose_numel, i] + input_dict[f"vel_{i}"] = trajectory[:, pose_numel:, i] return input_dict def error(self) -> float: @@ -331,20 +405,22 @@ def get_trajectory( # Returns the a tensor with the trajectory that the given variable # values represent. If no dictionary is passed, it will used the latest # values stored in the objective's variables. + pose_numel = 2 if self.objective.pose_type == th.Point2 else 4 + vel_numel = 2 if self.objective.pose_type == th.Point2 else 3 trajectory = torch.empty( self.objective.batch_size, - 4, + pose_numel + vel_numel, self.objective.trajectory_len, device=self.objective.device, ) variables = self.objective.optim_vars for i in range(self.objective.trajectory_len): if values_dict is None: - trajectory[:, :2, i] = variables[f"pose_{i}"].tensor.clone() - trajectory[:, 2:, i] = variables[f"vel_{i}"].tensor.clone() + trajectory[:, :pose_numel, i] = variables[f"pose_{i}"].tensor.clone() + trajectory[:, pose_numel:, i] = variables[f"vel_{i}"].tensor.clone() else: - trajectory[:, :2, i] = values_dict[f"pose_{i}"] - trajectory[:, 2:, i] = values_dict[f"vel_{i}"] + trajectory[:, :pose_numel, i] = values_dict[f"pose_{i}"] + trajectory[:, pose_numel:, i] = values_dict[f"vel_{i}"] return trajectory.detach() if detach else trajectory def get_total_squared_errors(self) -> Tuple[torch.Tensor, torch.Tensor]: @@ -370,5 +446,6 @@ def copy(self, collision_weight: Optional[float] = None) -> "MotionPlanner": num_time_steps=self.objective.num_time_steps, use_single_collision_weight=self.objective.use_single_collision_weight, device=self.device, + pose_type=self.objective.pose_type, dtype=self.dtype, ) From c5302df09c42a21756982ba71c2a3433b7cfbe77 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Thu, 8 Sep 2022 09:04:49 -0400 Subject: [PATCH 20/38] Fixed bug in visualization of SE2 motion plans. (#293) --- theseus/utils/examples/motion_planning/motion_planner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/theseus/utils/examples/motion_planning/motion_planner.py b/theseus/utils/examples/motion_planning/motion_planner.py index c157fde6c..ac7696812 100644 --- a/theseus/utils/examples/motion_planning/motion_planner.py +++ b/theseus/utils/examples/motion_planning/motion_planner.py @@ -349,7 +349,7 @@ def get_variable_values_from_straight_line( cur_pos = start[:, :2] + unit_trajectory_len * i input_dict[f"pose_{i}"] = torch.cat([cur_pos, start[:, 2:]], dim=1) input_dict[f"vel_{i}"] = torch.cat( - [avg_vel, torch.zeros(avg_vel.shape[0], 1)], dim=1 + [avg_vel, torch.zeros_like(avg_vel[:, :1])], dim=1 ) else: input_dict[f"pose_{i}"] = start + unit_trajectory_len * i From 682247115025138b2a05d6e7a04d57086e9ec09b Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Thu, 8 Sep 2022 11:01:10 -0400 Subject: [PATCH 21/38] Add functorch support for AutoDiffCostFunction (#268) * add autograd_use_functorch option * refactor AutoDiffCost for functorch * add functorch support for AutoDiffCostFunction * add some functorch tests for lie groups * add more functorch tests for lie groups * add more tests * so2 tests passed * add random seed for test_local_map * change the TEST_EPS for check_adjoint * update config file for circleci * add install_functorch to each job for circleci * add functorch installation in circleci * add functorch to requirements/main.txt * gcc-8 -> gcc-7 * remove a comment * change the order of functorch install for circleci * small refactor of AutoDiffCostFunction * add comments for _make_jac_fn_functorch * update circle ci * update torch version in circleci * test_autodiff_cost_function_error_and_jacobinas_shape pass * fixed bugs of copy() and to() in AutoDiffCostFunction * all tests are passed * add tolerance for test_autodiff_cost_function_error_and_jacobians_shape * update the warning message * fixed some bugs * fixed the logic bug in AutoDiffCostFunction * change the logic for tests * change warning messages * Lie group -> Manifold in the warning message * set lie group check to be true by default --- .circleci/config.yml | 33 ++++- requirements/main.txt | 3 +- theseus/core/cost_function.py | 72 ++++++++-- theseus/core/tests/test_cost_function.py | 52 +++++-- theseus/geometry/lie_group_check.py | 2 +- theseus/geometry/manifold.py | 2 +- theseus/geometry/se3.py | 2 +- theseus/geometry/so2.py | 2 +- theseus/geometry/so3.py | 6 +- theseus/geometry/tests/common.py | 164 +++++++++++++++++++++-- theseus/geometry/tests/test_se2.py | 39 ++++-- theseus/geometry/tests/test_se3.py | 10 +- theseus/geometry/tests/test_so2.py | 21 ++- theseus/geometry/tests/test_so3.py | 26 +++- 14 files changed, 361 insertions(+), 73 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 5fcd93253..17d39f164 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -53,6 +53,7 @@ setup_cuda10_libs: &setup_cuda10_libs working_directory: ~/ command: | # ubuntu's default gcc9.3 is too recent for cuda10.2 + sudo apt-get install -y gcc-7 g++-7 sudo apt-get install -y gcc-8 g++-8 sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-9 10 sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-8 20 @@ -93,7 +94,7 @@ install_torch_cuda10: &install_torch_cuda10 name: Install Torch for cuda10 working_directory: ~/project command: | - pip install --progress-bar off torch==1.10.0+cu102 torchvision==0.11.1+cu102 torchaudio==0.10.0+cu102 -f https://download.pytorch.org/whl/cu102/torch_stable.html + pip install --progress-bar off torch==1.12.1+cu102 torchvision==0.13.1+cu102 torchaudio==0.12.1+cu102 -f https://download.pytorch.org/whl/cu102/torch_stable.html python -c 'import torch; print("Torch version:", torch.__version__); assert torch.cuda.is_available()' install_torch_cuda11: &install_torch_cuda11 @@ -101,12 +102,27 @@ install_torch_cuda11: &install_torch_cuda11 name: Install Torch for cuda11 working_directory: ~/project command: | - pip install --progress-bar off torch==1.10.0+cu113 torchvision==0.11.1+cu113 torchaudio==0.10.0+cu113 -f https://download.pytorch.org/whl/cu113/torch_stable.html + pip install --progress-bar off torch==1.12.1+cu113 torchvision==0.13.1+cu113 torchaudio==0.12.1+cu113 -f https://download.pytorch.org/whl/cu113/torch_stable.html python -c 'import torch; print("Torch version:", torch.__version__); assert torch.cuda.is_available()' -setup_project: &setup_project +install_functorch: &install_functorch - run: - name: Setting up project + name: Install Functorch + working_directory: ~/project + command: | + pip install functorch + +setup_project_cuda10: &setup_project_cuda10 + - run: + name: Setting up project for cuda10 + working_directory: ~/project + command: | + CXX=g++-7 CC=gcc-7 LD=g++-7 pip install --progress-bar off -e . + CXX=g++-7 CC=gcc-7 LD=g++-7 pip install -r requirements/dev.txt + +setup_project_cuda11: &setup_project_cuda11 + - run: + name: Setting up project for cuda11 working_directory: ~/project command: | pip install --progress-bar off -e . @@ -130,6 +146,7 @@ jobs: steps: - checkout - <<: *install_suitesparse + - <<: *install_functorch - <<: *install_nox - run: name: "Testing theseus" @@ -144,6 +161,7 @@ jobs: steps: - checkout - <<: *install_suitesparse + - <<: *install_functorch - <<: *install_nox - run: name: "Testing theseus" @@ -158,6 +176,7 @@ jobs: steps: - checkout - <<: *install_suitesparse + - <<: *install_functorch - <<: *install_nox - run: name: "Testing theseus" @@ -175,7 +194,8 @@ jobs: - <<: *setup_cuda10_libs - <<: *setup_environment - <<: *install_torch_cuda10 - - <<: *setup_project + - <<: *install_functorch + - <<: *setup_project_cuda10 - <<: *run_tests unittests_gpu17_cuda11: @@ -187,7 +207,8 @@ jobs: - <<: *setup_cuda11_libs - <<: *setup_environment - <<: *install_torch_cuda11 - - <<: *setup_project + - <<: *install_functorch + - <<: *setup_project_cuda11 - <<: *run_tests workflows: diff --git a/requirements/main.txt b/requirements/main.txt index c1494b620..9ab32057a 100644 --- a/requirements/main.txt +++ b/requirements/main.txt @@ -6,4 +6,5 @@ scikit-sparse>=0.4.5 pytest>=6.2.1 numdifftools>=0.9.40 pybind11>=2.7.1 -mock>=4.0.3 \ No newline at end of file +mock>=4.0.3 +functorch>=0.2.1 \ No newline at end of file diff --git a/theseus/core/cost_function.py b/theseus/core/cost_function.py index 77c183d9e..58d95dc01 100644 --- a/theseus/core/cost_function.py +++ b/theseus/core/cost_function.py @@ -5,12 +5,16 @@ import abc from typing import Callable, List, Optional, Sequence, Tuple, cast +import warnings import torch import torch.autograd.functional as autogradF from typing_extensions import Protocol +from functorch import vmap, jacrev + from theseus.geometry import Manifold +from theseus.geometry.lie_group_check import no_lie_group_check from .cost_weight import CostWeight, ScaleCostWeight from .theseus_function import TheseusFunction @@ -111,6 +115,7 @@ def __init__( autograd_strict: bool = False, autograd_vectorize: bool = False, autograd_loop_over_batch: bool = False, + autograd_functorch: bool = False, ): if cost_weight is None: cost_weight = ScaleCostWeight(1.0) @@ -133,11 +138,21 @@ def __init__( # The following are auxiliary Variable objects to hold tensor data # during jacobian computation without modifying the original Variable objects self._tmp_optim_vars = tuple(v.copy() for v in optim_vars) - + self._tmp_aux_vars = None self._tmp_optim_vars_for_loop = None self._tmp_aux_vars_for_loop = None - if autograd_loop_over_batch: + self._autograd_loop_over_batch = autograd_loop_over_batch + self._autograd_functorch = autograd_functorch + + if autograd_functorch and self._autograd_loop_over_batch: + self._autograd_loop_over_batch = False + warnings.warn( + "autograd_use_functorch=True overrides given autograd_loop_over_batch=True, " + "so the latter will be set to False" + ) + + if self._autograd_loop_over_batch: self._tmp_optim_vars_for_loop = tuple(v.copy() for v in optim_vars) self._tmp_aux_vars_for_loop = tuple(v.copy() for v in aux_vars) @@ -147,7 +162,8 @@ def __init__( for i, aux_var in enumerate(aux_vars): self._tmp_aux_vars_for_loop[i].update(aux_var.tensor) - self._autograd_loop_over_batch = autograd_loop_over_batch + if self._autograd_functorch: + self._tmp_aux_vars = tuple(v.copy() for v in aux_vars) def _compute_error( self, @@ -187,11 +203,43 @@ def _compute_autograd_jacobian( vectorize=self._autograd_vectorize, ) - # Returns (jacobians, error) + def _make_jac_fn_functorch( + self, tmp_optim_vars: Tuple[Manifold, ...], tmp_aux_vars: Tuple[Variable, ...] + ): + def jac_fn(optim_vars_tensors_, aux_vars_tensors_): + assert len(optim_vars_tensors_) == len(tmp_optim_vars) + + # disable tensor checks and other operations that are incompatible with functorch + with no_lie_group_check(): + for i, tensor in enumerate(optim_vars_tensors_): + tmp_optim_vars[i].update(tensor.unsqueeze(0)) + + # only aux_var in current batch is evaluated + for i, tensor in enumerate(aux_vars_tensors_): + tmp_aux_vars[i].update(tensor.unsqueeze(0)) + + # return [0] since functorch expects no batch output + return self._err_fn(optim_vars=tmp_optim_vars, aux_vars=tmp_aux_vars)[0] + + return jac_fn + + def _compute_autograd_jacobian_functorch( + self, + optim_tensors: Tuple[torch.Tensor, ...], + aux_tensors: Tuple[torch.Tensor, ...], + jac_fn: Callable, + ) -> Tuple[torch.Tensor, ...]: + return vmap(jacrev(jac_fn, argnums=0))(optim_tensors, aux_tensors) + def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: err, optim_vars, aux_vars = self._compute_error() - - if self._autograd_loop_over_batch: + if self._autograd_functorch: + jacobians_full = self._compute_autograd_jacobian_functorch( + tuple(v.tensor for v in optim_vars), + tuple(v.tensor for v in aux_vars), + self._make_jac_fn_functorch(self._tmp_optim_vars, self._tmp_aux_vars), + ) + elif self._autograd_loop_over_batch: jacobians_raw_loop: List[Tuple[torch.Tensor, ...]] = [] for n in range(optim_vars[0].shape[0]): for i, aux_var in enumerate(aux_vars): @@ -205,17 +253,17 @@ def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: ) jacobians_raw_loop.append(jacobians_n) - jacobians_full = [ + jacobians_full = tuple( torch.cat([jac[k][:, :, 0, :] for jac in jacobians_raw_loop], dim=0) for k in range(len(optim_vars)) - ] + ) else: jacobians_raw = self._compute_autograd_jacobian( tuple(v.tensor for v in optim_vars), self._make_jac_fn(self._tmp_optim_vars, aux_vars), ) aux_idx = torch.arange(err.shape[0]) # batch_size - jacobians_full = [jac[aux_idx, :, aux_idx, :] for jac in jacobians_raw] + jacobians_full = tuple(jac[aux_idx, :, aux_idx, :] for jac in jacobians_raw) # torch autograd returns shape (batch_size, dim, batch_size, var_dim), which # includes derivatives of batches against each other. @@ -237,6 +285,8 @@ def _copy_impl(self, new_name: Optional[str] = None) -> "AutoDiffCostFunction": aux_vars=[v.copy() for v in self.aux_vars], cost_weight=self.weight.copy(), name=new_name, + autograd_loop_over_batch=self._autograd_loop_over_batch, + autograd_functorch=self._autograd_functorch, ) def to(self, *args, **kwargs): @@ -251,3 +301,7 @@ def to(self, *args, **kwargs): for var in self._tmp_aux_vars_for_loop: var.to(*args, **kwargs) + + if self._autograd_functorch: + for var in self._tmp_aux_vars: + var.to(*args, **kwargs) diff --git a/theseus/core/tests/test_cost_function.py b/theseus/core/tests/test_cost_function.py index 1c186e657..1c3779459 100644 --- a/theseus/core/tests/test_cost_function.py +++ b/theseus/core/tests/test_cost_function.py @@ -57,7 +57,12 @@ def test_default_name_and_ids(): @pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -def test_autodiff_cost_function_error_and_jacobians_shape(autograd_loop_over_batch): +@pytest.mark.parametrize("autograd_functorch", [True, False]) +def test_autodiff_cost_function_error_and_jacobians_shape( + autograd_loop_over_batch, autograd_functorch +): + rng = torch.Generator() + rng.manual_seed(0) for i in range(100): num_optim_vars = np.random.randint(0, 5) num_aux_vars = np.random.randint(0, 5) @@ -65,7 +70,7 @@ def test_autodiff_cost_function_error_and_jacobians_shape(autograd_loop_over_bat err_dim = np.random.randint(1, 5) optim_vars = [] aux_vars = [] - variable_values = torch.randn(num_optim_vars + num_aux_vars) + variable_values = torch.randn(num_optim_vars + num_aux_vars, generator=rng) idx = 0 for i in range(num_optim_vars): optim_vars.append( @@ -100,15 +105,17 @@ def error_fn(optim_vars, aux_vars): all_vars = optim_vars + aux_vars - vals = [] for i, arg in enumerate(all_vars): assert isinstance(arg, th.Variable) assert arg.shape == (batch_size, i + 1) or arg.shape == (1, i + 1) - assert arg.tensor.allclose( - variable_values[i] * torch.ones_like(arg.tensor) + if not autograd_functorch: + assert arg.tensor.allclose( + variable_values[i] * torch.ones_like(arg.tensor) + ) + ret_val = ret_val + arg.tensor.view(arg.shape[0], -1).mean( + dim=1, keepdim=True ) - vals.append(arg[0, 0]) - return ret_val + torch.Tensor(vals).sum() + return ret_val # this checks that 0 optimization variables is not allowed if len(optim_vars) < 1: @@ -129,9 +136,12 @@ def error_fn(optim_vars, aux_vars): cost_weight=cost_weight, aux_vars=aux_vars, autograd_loop_over_batch=autograd_loop_over_batch, + autograd_functorch=autograd_functorch, ) err = cost_function.error() - assert err.allclose(variable_values.sum() * torch.ones(batch_size, err_dim)) + assert err.allclose( + variable_values.sum() * torch.ones(batch_size, err_dim), atol=1e-7 + ) # Now checking the jacobians jacobians, err_jac = cost_function.jacobians() @@ -143,7 +153,10 @@ def error_fn(optim_vars, aux_vars): @pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -def test_autodiff_cost_function_cost_weight(autograd_loop_over_batch): +@pytest.mark.parametrize("autograd_functorch", [True, False]) +def test_autodiff_cost_function_cost_weight( + autograd_loop_over_batch, autograd_functorch +): batch_size = 10 optim_vars = [] aux_vars = [] @@ -175,6 +188,7 @@ def error_fn(optim_vars, aux_vars): 1, aux_vars=aux_vars, autograd_loop_over_batch=autograd_loop_over_batch, + autograd_functorch=autograd_functorch, ) assert isinstance(cost_function.weight, ScaleCostWeight) assert torch.allclose(cost_function.weight.scale.tensor, torch.ones(1, 1)) @@ -202,7 +216,8 @@ def error_fn(optim_vars, aux_vars): @pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -def test_autodiff_cost_function_to(autograd_loop_over_batch): +@pytest.mark.parametrize("autograd_functorch", [True, False]) +def test_autodiff_cost_function_to(autograd_loop_over_batch, autograd_functorch): batch_size = 10 optim_vars = [] aux_vars = [] @@ -236,6 +251,7 @@ def error_fn(optim_vars, aux_vars): 1, aux_vars=aux_vars, autograd_loop_over_batch=autograd_loop_over_batch, + autograd_functorch=autograd_functorch, ) for var in optim_vars: @@ -251,8 +267,9 @@ def error_fn(optim_vars, aux_vars): @pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) +@pytest.mark.parametrize("autograd_functorch", [True, False]) def test_autodiff_cost_function_error_and_jacobians_shape_on_SO3( - autograd_loop_over_batch, + autograd_loop_over_batch, autograd_functorch ): for i in range(100): num_vars = np.random.randint(0, 5) @@ -277,7 +294,9 @@ def error_fn(optim_vars, aux_vars): ret_val = torch.zeros(optim_vars[0].shape[0], err_dim) for optim_var, aux_var in zip(optim_vars, aux_vars): - ret_val += th.SO3(tensor=optim_var.tensor).rotate(aux_var).tensor + ret_val = ( + ret_val + th.SO3(tensor=optim_var.tensor).rotate(aux_var).tensor + ) return ret_val @@ -300,6 +319,7 @@ def error_fn(optim_vars, aux_vars): cost_weight=cost_weight, aux_vars=aux_vars, autograd_loop_over_batch=autograd_loop_over_batch, + autograd_functorch=autograd_functorch, ) err = cost_function.error() @@ -313,8 +333,9 @@ def error_fn(optim_vars, aux_vars): @pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) +@pytest.mark.parametrize("autograd_functorch", [True, False]) def test_autodiff_cost_function_error_and_jacobians_value_on_SO3( - autograd_loop_over_batch, + autograd_loop_over_batch, autograd_functorch ): for i in range(100): num_vars = np.random.randint(0, 5) @@ -339,7 +360,9 @@ def error_fn(optim_vars, aux_vars): ret_val = torch.zeros(optim_vars[0].shape[0], err_dim, dtype=torch.float64) for optim_var, aux_var in zip(optim_vars, aux_vars): - ret_val += th.SO3(tensor=optim_var.tensor).rotate(aux_var).tensor + ret_val = ( + ret_val + th.SO3(tensor=optim_var.tensor).rotate(aux_var).tensor + ) return ret_val @@ -362,6 +385,7 @@ def error_fn(optim_vars, aux_vars): cost_weight=cost_weight, aux_vars=aux_vars, autograd_loop_over_batch=autograd_loop_over_batch, + autograd_functorch=autograd_functorch, ) jac_actual, err_actual = cost_function.jacobians() diff --git a/theseus/geometry/lie_group_check.py b/theseus/geometry/lie_group_check.py index fe71d538f..afb42f0dd 100644 --- a/theseus/geometry/lie_group_check.py +++ b/theseus/geometry/lie_group_check.py @@ -13,7 +13,7 @@ class _LieGroupCheckContext: @classmethod def get_context(cls): if not hasattr(cls.contexts, "check_lie_group"): - cls.contexts.check_lie_group = False + cls.contexts.check_lie_group = True return cls.contexts.check_lie_group @classmethod diff --git a/theseus/geometry/manifold.py b/theseus/geometry/manifold.py index f78754ea5..09b2e2501 100644 --- a/theseus/geometry/manifold.py +++ b/theseus/geometry/manifold.py @@ -45,7 +45,7 @@ def __init__( tensor = self._check_tensor(tensor, strict) else: warnings.warn( - f"functorch is enabled and tensor is not checked " + f"Manifold consistency checks are disabled " f"for {self.__class__.__name__}.", RuntimeWarning, ) diff --git a/theseus/geometry/se3.py b/theseus/geometry/se3.py index 8a2b0b852..5cc78c2f6 100644 --- a/theseus/geometry/se3.py +++ b/theseus/geometry/se3.py @@ -188,7 +188,7 @@ def _hat_matrix_check(matrix: torch.Tensor): ) else: warnings.warn( - "functorch is enabled and the skew-symmetry of hat matrices is " + "Lie group checks are disabled, so the skew-symmetry of hat matrices is " "not checked for SE3.", RuntimeWarning, ) diff --git a/theseus/geometry/so2.py b/theseus/geometry/so2.py index 14849508b..1d6bafbfe 100644 --- a/theseus/geometry/so2.py +++ b/theseus/geometry/so2.py @@ -146,7 +146,7 @@ def _hat_matrix_check(matrix: torch.Tensor): _check &= torch.allclose(matrix[:, 0, 1], -matrix[:, 1, 0]) else: warnings.warn( - "functorch is enabled and the skew-symmetry of hat matrices is " + "Lie group checks are disabled, so the skew-symmetry of hat matrices is " "not checked for SO2.", RuntimeWarning, ) diff --git a/theseus/geometry/so3.py b/theseus/geometry/so3.py index 936d788a5..6cbb2ba31 100644 --- a/theseus/geometry/so3.py +++ b/theseus/geometry/so3.py @@ -59,7 +59,7 @@ def rand( requires_grad=requires_grad, ) u1 = u[0] - u2, u3 = u[1:3] * 2 * torch.pi + u2, u3 = u[1:3] * 2 * theseus.constants.PI a = torch.sqrt(1.0 - u1) b = torch.sqrt(u1) @@ -168,7 +168,7 @@ def _unit_quaternion_check(quaternion: torch.Tensor): raise ValueError("Not unit quaternions.") else: warnings.warn( - "functorch is enabled and the validness of unit quaternions are not " + "Lie group checks are disabled, so the validness of unit quaternions is not " "checked for SO3.", RuntimeWarning, ) @@ -180,7 +180,7 @@ def _hat_matrix_check(matrix: torch.Tensor): if _LieGroupCheckContext.get_context(): warnings.warn( - "functorch is enabled and the skew-symmetry of hat matrices is " + "Lie group checks are disabled, so the skew-symmetry of hat matrices is " "not checked for SO3.", RuntimeWarning, ) diff --git a/theseus/geometry/tests/common.py b/theseus/geometry/tests/common.py index f09bd7a5a..96ad07479 100644 --- a/theseus/geometry/tests/common.py +++ b/theseus/geometry/tests/common.py @@ -8,10 +8,12 @@ from theseus.constants import TEST_EPS from theseus.utils import numeric_jacobian from theseus.geometry.lie_group_check import set_lie_group_check_enabled +from theseus.geometry.vector import Vector +from theseus.core.cost_function import AutoDiffCostFunction def check_exp_map(tangent_vector, group_cls, atol=TEST_EPS, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): group = group_cls.exp_map(tangent_vector) tangent_vector_double = tangent_vector.double() tangent_vector_double.to(dtype=torch.float64) @@ -21,16 +23,82 @@ def check_exp_map(tangent_vector, group_cls, atol=TEST_EPS, enable_functorch=Fal atol=atol, ) + if enable_functorch: + optim_vars = [Vector(tensor=tangent_vector)] + + def err_fn(optim_vars, aux_vars): + group = group_cls.exp_map(optim_vars[0].tensor) + dim = list(range(1, len(group.shape))) + return group.tensor.sum(dim=dim).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=atol) + + def err_fn(optim_vars, aux_vars): + jacobians = [] + group_cls.exp_map(optim_vars[0].tensor, jacobians=jacobians) + dim = list(range(1, len(jacobians[0].shape))) + return jacobians[0].sum(dim=dim).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=atol) + def check_log_map(tangent_vector, group_cls, atol=TEST_EPS, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): assert torch.allclose( tangent_vector, group_cls.exp_map(tangent_vector).log_map(), atol=atol ) + if enable_functorch: + optim_vars = [group_cls.exp_map(tangent_vector)] + + def err_fn(optim_vars, aux_vars): + return optim_vars[0].log_map().sum(dim=[1]).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=atol) + + def err_fn(optim_vars, aux_vars): + jacobians = [] + optim_vars[0].log_map(jacobians=jacobians) + dim = list(range(1, len(jacobians[0].shape))) + return jacobians[0].sum(dim=dim).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=atol) + def check_compose(group_1, group_2, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): Jcmp = [] composition = group_1.compose(group_2, jacobians=Jcmp) expected_matrix = group_1.to_matrix() @ group_2.to_matrix() @@ -56,9 +124,50 @@ def check_compose(group_1, group_2, enable_functorch=False): if group_1.dtype == torch.float64: assert torch.allclose(Jcmp[1].double(), expected_jacs[1], atol=TEST_EPS) + if enable_functorch: + optim_vars = [group_1, group_2] + + def err_fn(optim_vars, aux_vars): + dim = list(range(1, len(optim_vars[0].shape))) + return optim_vars[0].compose(optim_vars[1]).tensor.sum(dim=dim).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=TEST_EPS) + assert torch.allclose(jacs[1], jacs_vec[1], atol=TEST_EPS) + + def err_fn(optim_vars, aux_vars): + jacobians = [] + optim_vars[0].compose(optim_vars[1], jacobians=jacobians) + dim = [ + list(range(1, len(jacobians[0].shape))), + list(range(1, len(jacobians[1].shape))), + ] + + return jacobians[0].sum(dim=dim[0]).view(-1, 1) + jacobians[1].sum( + dim=dim[1] + ).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=TEST_EPS) + assert torch.allclose(jacs[1], jacs_vec[1], atol=TEST_EPS) + def check_inverse(group, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): tangent_vector = group.log_map() inverse_group = group.exp_map(-tangent_vector.double()) jac = [] @@ -75,9 +184,26 @@ def check_inverse(group, enable_functorch=False): ) assert torch.allclose(jac[0].double(), expected_jac[0], atol=TEST_EPS) + if enable_functorch: + optim_vars = [group] + + def err_fn(optim_vars, aux_vars): + dim = list(range(1, len(optim_vars[0].shape))) + return optim_vars[0].inverse().tensor.sum(dim=dim).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=TEST_EPS) + def check_adjoint(group, tangent_vector, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): tangent_left = group.__class__.adjoint(group) @ tangent_vector.unsqueeze(2) group_matrix = group.to_matrix() tangent_right = group.__class__.vee( @@ -86,9 +212,27 @@ def check_adjoint(group, tangent_vector, enable_functorch=False): @ group.inverse().to_matrix().double() ) assert torch.allclose( - tangent_left.double().squeeze(2), tangent_right, atol=TEST_EPS + tangent_left.double().squeeze(2), tangent_right, atol=1e-5 ) + if enable_functorch: + optim_vars = [group] + + def err_fn(optim_vars, aux_vars): + adjoint = optim_vars[0].adjoint() + dim = list(range(1, len(adjoint.shape))) + return adjoint.sum(dim=dim).view(-1, 1) + + cost_fn = AutoDiffCostFunction(optim_vars, err_fn, dim=1) + jacs, _ = cost_fn.jacobians() + + cost_fn_vec = AutoDiffCostFunction( + optim_vars, err_fn, dim=1, autograd_functorch=True + ) + jacs_vec, _ = cost_fn_vec.jacobians() + + assert torch.allclose(jacs[0], jacs_vec[0], atol=TEST_EPS) + # Func can be SO2.rotate, SE2.transform_to, SO3.unrotate, etc., whose third argument # populates the jacobians @@ -150,7 +294,7 @@ def func(g, p): def check_projection_for_compose( Group, batch_size, generator=None, dtype=torch.float64, enable_functorch=False ): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): group1_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) group2_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) group1 = group1_double.copy() @@ -230,7 +374,7 @@ def func(g1, g2): def check_projection_for_inverse( Group, batch_size, generator=None, dtype=torch.float64, enable_functorch=False ): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): group_double = Group.rand(batch_size, generator=generator, dtype=torch.float64) group = group_double.copy() group.to(dtype) @@ -284,7 +428,7 @@ def func(g): def check_projection_for_exp_map( tangent_vector, Group, is_projected=True, atol=1e-8, enable_functorch=False ): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): batch_size = tangent_vector.shape[0] dof = tangent_vector.shape[1] aux_id = torch.arange(batch_size) @@ -319,7 +463,7 @@ def exp_func(xi): def check_projection_for_log_map( tangent_vector, Group, is_projected=True, atol=1e-8, enable_functorch=False ): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): batch_size = tangent_vector.shape[0] aux_id = torch.arange(batch_size) group_double = Group.exp_map(tangent_vector.double()) diff --git a/theseus/geometry/tests/test_se2.py b/theseus/geometry/tests/test_se2.py index e1610498f..af1b6bee7 100644 --- a/theseus/geometry/tests/test_se2.py +++ b/theseus/geometry/tests/test_se2.py @@ -34,55 +34,72 @@ def create_random_se2(batch_size, rng, dtype=torch.float64): @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_exp_map(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_exp_map(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) + ATOL = 2e-4 if dtype == torch.float32 else 1e-6 + for batch_size in [1, 20, 100]: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)) u = torch.randn(batch_size, 2, dtype=dtype, generator=rng) tangent_vector = torch.cat([u, theta.unsqueeze(1)], dim=1) - check_exp_map(tangent_vector.to(dtype=dtype), th.SE2) + check_exp_map( + tangent_vector.to(dtype=dtype), th.SE2, enable_functorch=enable_functorch + ) + check_projection_for_exp_map( + tangent_vector.to(dtype=dtype), + th.SE2, + atol=ATOL, + enable_functorch=enable_functorch, + ) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_log_map(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_log_map(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for batch_size in [1, 20, 100]: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)) u = torch.randn(batch_size, 2, dtype=dtype, generator=rng) tangent_vector = torch.cat([u, theta.unsqueeze(1)], dim=1) - check_log_map(tangent_vector, th.SE2) - check_projection_for_exp_map(tangent_vector, th.SE2) + check_log_map(tangent_vector, th.SE2, enable_functorch=enable_functorch) + check_projection_for_exp_map( + tangent_vector, th.SE2, enable_functorch=enable_functorch + ) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_compose(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_compose(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for batch_size in [1, 20, 100]: se2_1 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) se2_2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) - check_compose(se2_1, se2_2) + check_compose(se2_1, se2_2, enable_functorch=enable_functorch) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_inverse(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_inverse(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for batch_size in [1, 20, 100]: se2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) - check_inverse(se2) + check_inverse(se2, enable_functorch=enable_functorch) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) -def test_adjoint(dtype): +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_adjoint(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for batch_size in [1, 20, 100]: se2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) tangent = torch.randn(batch_size, 3, dtype=dtype) - check_adjoint(se2, tangent) + check_adjoint(se2, tangent, enable_functorch=enable_functorch) def test_copy(): diff --git a/theseus/geometry/tests/test_se3.py b/theseus/geometry/tests/test_se3.py index 54705ebd8..295d7a016 100644 --- a/theseus/geometry/tests/test_se3.py +++ b/theseus/geometry/tests/test_se3.py @@ -28,7 +28,7 @@ def check_SE3_log_map(tangent_vector, atol=TEST_EPS, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): g = th.SE3.exp_map(tangent_vector) assert torch.allclose(th.SE3.exp_map(g.log_map()).tensor, g.tensor, atol=atol) @@ -71,7 +71,7 @@ def test_exp_map(batch_size, dtype, ang_factor, enable_functorch): ) @pytest.mark.parametrize("enable_functorch", [True, False]) def test_batch_size_3_exp_map(dtype, ang_factor, enable_functorch): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): rng = torch.Generator() rng.manual_seed(0) ATOL = 1e-4 if dtype == torch.float32 else 1e-6 @@ -125,7 +125,7 @@ def test_log_map(batch_size, dtype, ang_factor, enable_functorch): ) @pytest.mark.parametrize("enable_functorch", [True, False]) def test_batch_size_3_log_map(dtype, ang_factor, enable_functorch): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): rng = torch.Generator() rng.manual_seed(0) ATOL = 1e-3 if dtype == torch.float32 else 1e-6 @@ -282,8 +282,8 @@ def test_local_map(dtype): ATOL = 3e-5 if dtype == torch.float32 else 1e-7 for batch_size in [1, 20, 100]: - group0 = th.SE3.rand(batch_size, dtype=dtype) - group1 = th.SE3.rand(batch_size, dtype=dtype) + group0 = th.SE3.rand(batch_size, dtype=dtype, generator=rng) + group1 = th.SE3.rand(batch_size, dtype=dtype, generator=rng) check_jacobian_for_local( group0, group1, Group=th.SE3, is_projected=True, atol=ATOL ) diff --git a/theseus/geometry/tests/test_so2.py b/theseus/geometry/tests/test_so2.py index baf02a269..5b6fc363b 100644 --- a/theseus/geometry/tests/test_so2.py +++ b/theseus/geometry/tests/test_so2.py @@ -31,15 +31,19 @@ def test_exp_map(): for batch_size in [1, 20, 100]: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)).view(-1, 1) - check_exp_map(theta, th.SO2, EPS) - check_projection_for_exp_map(theta, th.SO2) + check_exp_map(theta, th.SO2, EPS, enable_functorch=False) + check_projection_for_exp_map(theta, th.SO2, enable_functorch=False) + check_exp_map(theta, th.SO2, EPS, enable_functorch=True) + check_projection_for_exp_map(theta, th.SO2, enable_functorch=True) def test_log_map(): for batch_size in [1, 2, 100]: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)).view(-1, 1) - check_log_map(theta, th.SO2, EPS) - check_projection_for_log_map(theta, th.SO2) + check_log_map(theta, th.SO2, EPS, enable_functorch=False) + check_projection_for_log_map(theta, th.SO2, enable_functorch=False) + check_log_map(theta, th.SO2, EPS, enable_functorch=True) + check_projection_for_log_map(theta, th.SO2, enable_functorch=True) def test_compose(): @@ -48,7 +52,8 @@ def test_compose(): for batch_size in [1, 20, 100]: so2_1 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) so2_2 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) - check_compose(so2_1, so2_2) + check_compose(so2_1, so2_2, enable_functorch=False) + check_compose(so2_1, so2_2, enable_functorch=True) def test_inverse(): @@ -56,7 +61,8 @@ def test_inverse(): rng.manual_seed(0) for batch_size in [1, 20, 100]: so2 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) - check_inverse(so2) + check_inverse(so2, enable_functorch=False) + check_inverse(so2, enable_functorch=True) def test_rotate_and_unrotate(): @@ -118,7 +124,8 @@ def test_adjoint(): for batch_size in [1, 20, 100]: so2 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) tangent = torch.randn(batch_size, 1).double() - check_adjoint(so2, tangent) + check_adjoint(so2, tangent, enable_functorch=False) + check_adjoint(so2, tangent, enable_functorch=True) def test_copy(): diff --git a/theseus/geometry/tests/test_so3.py b/theseus/geometry/tests/test_so3.py index 94e2a4efd..a0ea5e408 100644 --- a/theseus/geometry/tests/test_so3.py +++ b/theseus/geometry/tests/test_so3.py @@ -16,6 +16,8 @@ check_adjoint, check_compose, check_exp_map, + check_log_map, + check_inverse, check_jacobian_for_local, check_projection_for_compose, check_projection_for_exp_map, @@ -27,14 +29,14 @@ def check_SO3_log_map(tangent_vector, atol=1e-7, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): error = (tangent_vector - th.SO3.exp_map(tangent_vector).log_map()).norm(dim=1) error = torch.minimum(error, (error - 2 * np.pi).abs()) assert torch.allclose(error, torch.zeros_like(error), atol=atol) def check_SO3_to_quaternion(so3: th.SO3, atol=1e-10, enable_functorch=False): - with set_lie_group_check_enabled(enable_functorch): + with set_lie_group_check_enabled(not enable_functorch): quaternions = so3.to_quaternion() assert torch.allclose( th.SO3(quaternion=quaternions).to_matrix(), so3.to_matrix(), atol=atol @@ -66,7 +68,9 @@ def test_exp_map(batch_size, dtype, ang_factor, enable_functorch): tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) check_exp_map(tangent_vector, th.SO3, atol=ATOL, enable_functorch=enable_functorch) - check_projection_for_exp_map(tangent_vector, th.SO3, atol=ATOL) + check_projection_for_exp_map( + tangent_vector, th.SO3, atol=ATOL, enable_functorch=enable_functorch + ) @pytest.mark.parametrize("batch_size", [1, 20, 100]) @@ -91,11 +95,27 @@ def test_log_map(batch_size, dtype, ang_factor, enable_functorch): tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) check_SO3_log_map(tangent_vector, atol=ATOL, enable_functorch=enable_functorch) + if tangent_vector.norm(dim=1).max() < 2 * np.pi - 1e-3: + check_log_map( + tangent_vector, th.SO3, atol=ATOL, enable_functorch=enable_functorch + ) check_projection_for_log_map( tangent_vector, th.SO3, atol=PROJECTION_ATOL, enable_functorch=enable_functorch ) +@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_inverse(batch_size, dtype, enable_functorch): + rng = torch.Generator() + rng.manual_seed(0) + + group = th.SO3.rand(batch_size, generator=rng, dtype=dtype) + + check_inverse(group, enable_functorch=enable_functorch) + + @pytest.mark.parametrize("batch_size", [1, 20, 100]) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( From dfcbcc46de89f64700950c59723282a4e0e09e8a Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Fri, 9 Sep 2022 08:09:41 -0400 Subject: [PATCH 22/38] Changed requirements so that main.txt only includes essential dependencies (#294) * Changed requirements so that main.txt only includes essential dependencies. * Reverted black, mypi, flake and isort versions in requirements file. * Fixed some mypy issues. Added drm to dev requirements so unit tests pass. --- README.md | 4 ++-- docs/source/getting-started.rst | 8 ++++++++ examples/README.md | 5 +++++ examples/homography_estimation.py | 10 +++++----- requirements/dev.txt | 3 +++ requirements/main.txt | 3 --- theseus/embodied/kinematics/kinematics_model.py | 10 +++++++++- theseus/optimizer/linear_system.py | 2 +- theseus/theseus_layer.py | 2 +- theseus/utils/examples/tactile_pose_estimation/misc.py | 10 +++++----- 10 files changed, 39 insertions(+), 18 deletions(-) diff --git a/README.md b/README.md index b8f986555..73624356a 100644 --- a/README.md +++ b/README.md @@ -105,9 +105,9 @@ pip install -e ".[dev]" ``` and follow the more detailed instructions in [CONTRIBUTING](https://github.com/facebookresearch/theseus/blob/main/CONTRIBUTING.md). -### Running unit tests +### Running unit tests (requires `dev` installation) ```bash -pytest theseus +python -m pytest theseus ``` By default, unit tests include tests for our CUDA extensions. You can add the option `-m "not cudaext"` to skip them when installing without CUDA support. diff --git a/docs/source/getting-started.rst b/docs/source/getting-started.rst index aff03556e..71c66bb8a 100644 --- a/docs/source/getting-started.rst +++ b/docs/source/getting-started.rst @@ -45,6 +45,14 @@ If you are interested in contributing to ``theseus``, instead install using and follow the more detailed instructions in `CONTRIBUTING `_. +Unit tests +"""""""""" +With ``dev`` installation, you can run unit tests via + +.. code-block:: bash + + python -m pytest theseus + By default, unit tests include tests for our CUDA extensions. You can add the option ``-m "not cudaext"`` to skip them when installing without CUDA support. diff --git a/examples/README.md b/examples/README.md index e234bcbdf..8d3c461bd 100644 --- a/examples/README.md +++ b/examples/README.md @@ -37,6 +37,11 @@ The motion planning and tactile estimation examples require `hydra` installation ```bash pip install hydra-core ``` +The backward modes example requires `numdifftools`, which you can install with + +```bash +pip install numdifftools +``` The homography example requires `kornia` and `OpenCV`, which you can install with diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index c23208dc1..c23c5574e 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -17,7 +17,7 @@ from torch.utils.data import DataLoader, Dataset import theseus as th -from theseus.third_party.easyaug import RandomGeoAug, GeoAugParam, RandomPhotoAug +from theseus.third_party.easyaug import GeoAugParam, RandomGeoAug, RandomPhotoAug from theseus.third_party.utils import grid_sample FONT = cv2.FONT_HERSHEY_DUPLEX @@ -36,10 +36,10 @@ def prepare_data(): dataset_root = os.path.join(os.getcwd(), "data") chunks = [ "revisitop1m.1", - #"revisitop1m.2", # Uncomment for more data. - #"revisitop1m.3", - #"revisitop1m.4", - #"revisitop1m.5", + # "revisitop1m.2", # Uncomment for more data. + # "revisitop1m.3", + # "revisitop1m.4", + # "revisitop1m.5", ] dataset_paths = [] for chunk in chunks: diff --git a/requirements/dev.txt b/requirements/dev.txt index 032cd9529..24fe1e3b1 100644 --- a/requirements/dev.txt +++ b/requirements/dev.txt @@ -4,7 +4,10 @@ mypy>=0.910 nox==2020.8.22 pre-commit>=2.9.2 isort>=5.6.4 +differentiable-robot-model>=0.2.3 types-PyYAML==5.4.3 +numdifftools>=0.9.40 +mock>=4.0.3 types-mock>=4.0.8 Sphinx==5.0.2 sphinx-rtd-theme==1.0.0 \ No newline at end of file diff --git a/requirements/main.txt b/requirements/main.txt index 9ab32057a..2d854d5f8 100644 --- a/requirements/main.txt +++ b/requirements/main.txt @@ -1,10 +1,7 @@ -differentiable-robot-model>=0.2.3 numpy>=1.19.2 scipy>=1.5.3 scikit-sparse>=0.4.5 # torch>=1.7.1 will do separate install instructions for now (CUDA dependent) pytest>=6.2.1 -numdifftools>=0.9.40 pybind11>=2.7.1 -mock>=4.0.3 functorch>=0.2.1 \ No newline at end of file diff --git a/theseus/embodied/kinematics/kinematics_model.py b/theseus/embodied/kinematics/kinematics_model.py index 57438a823..15820ab9e 100644 --- a/theseus/embodied/kinematics/kinematics_model.py +++ b/theseus/embodied/kinematics/kinematics_model.py @@ -6,7 +6,6 @@ import abc from typing import Dict, Optional, Union -import differentiable_robot_model as drm import torch from theseus.geometry import SE3, LieGroup, Point2, Vector @@ -38,6 +37,15 @@ def forward_kinematics(self, robot_pose: RobotModelInput) -> Dict[str, LieGroup] class UrdfRobotModel(KinematicsModel): def __init__(self, urdf_path: str): + try: + import differentiable_robot_model as drm + except ModuleNotFoundError as e: + print( + "UrdfRobotModel requires installing differentiable-robot-model. " + "Please run `pip install differentiable-robot-model`." + ) + raise e + self.drm_model = drm.DifferentiableRobotModel(urdf_path) def _postprocess_quaternion(self, quat): diff --git a/theseus/optimizer/linear_system.py b/theseus/optimizer/linear_system.py index bf68dc60a..fd8d1d09c 100644 --- a/theseus/optimizer/linear_system.py +++ b/theseus/optimizer/linear_system.py @@ -16,7 +16,7 @@ def __init__( row_ptr: np.ndarray, num_rows: int, num_cols: int, - dtype: np.dtype = np.float_, + dtype: np.dtype = np.float_, # type: ignore ): self.col_ind = col_ind self.row_ptr = row_ptr diff --git a/theseus/theseus_layer.py b/theseus/theseus_layer.py index 941b40d18..5555e007b 100644 --- a/theseus/theseus_layer.py +++ b/theseus/theseus_layer.py @@ -298,7 +298,7 @@ def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: return [self.var.project(euclidean_grad, is_sparse=True)], self.error() def dim(self) -> int: - return np.prod(self.var.tensor.shape[1:]) + return int(np.prod(self.var.tensor.shape[1:])) def _copy_impl(self, new_name: Optional[str] = None) -> "CostFunction": return _DLMPerturbation( diff --git a/theseus/utils/examples/tactile_pose_estimation/misc.py b/theseus/utils/examples/tactile_pose_estimation/misc.py index f91c844ed..88354ccaa 100644 --- a/theseus/utils/examples/tactile_pose_estimation/misc.py +++ b/theseus/utils/examples/tactile_pose_estimation/misc.py @@ -47,11 +47,11 @@ def __init__( stop = max(int(np.ceil(num_episodes * val_ratio)), 2) idx = order[:stop] if data_mode == "val" else order[stop:] - self.img_feats = data["img_feats"][idx] - self.eff_poses = data["eff_poses"][idx] - self.obj_poses = data["obj_poses"][idx] - self.contact_episode = data["contact_episode"][idx] - self.contact_flag = data["contact_flag"][idx] + self.img_feats = data["img_feats"][idx] # type: ignore + self.eff_poses = data["eff_poses"][idx] # type: ignore + self.obj_poses = data["obj_poses"][idx] # type: ignore + self.contact_episode = data["contact_episode"][idx] # type: ignore + self.contact_flag = data["contact_flag"][idx] # type: ignore # Check sizes of the attributes assigned above self.dataset_size: int = -1 for key in data: From 41455744df90e31f0c205fca5f76f59adc0658a8 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Tue, 13 Sep 2022 13:35:25 -0700 Subject: [PATCH 23/38] Update git checkout command in docker build script. --- build_scripts/build_wheel.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build_scripts/build_wheel.sh b/build_scripts/build_wheel.sh index f594cb1e1..27072a55f 100755 --- a/build_scripts/build_wheel.sh +++ b/build_scripts/build_wheel.sh @@ -64,7 +64,7 @@ for PYTHON_VERSION in 3.9; do RUN pip install build wheel RUN git clone https://github.com/facebookresearch/theseus.git WORKDIR theseus - RUN git checkout ${TAG} -b tmp_build + RUN git checkout -b tmp_build --track origin/${TAG} CMD python3 -m build --no-isolation """ > ${DOCKER_DIR}/Dockerfile From a9b9b0332ea355b3926ed4939f08eeabb852bc97 Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Wed, 14 Sep 2022 15:25:51 -0400 Subject: [PATCH 24/38] Add to_quaternion, rotation, translation and convention comment (#295) * add [w x y z] info about quaternions * add SE3.to_x_y_z_quaternion * add [w x y z] convention comment to SE3 * SE3.to_x_y_z_quaternion tested * add SE3.rotation and SE3.translation * add more explicit comments to SE3.x_y_z_quaternion * break the comments --- theseus/geometry/se2.py | 7 +++++-- theseus/geometry/se3.py | 21 +++++++++++++++++++- theseus/geometry/so3.py | 30 +++++++++++++++-------------- theseus/geometry/tests/test_se3.py | 31 ++++++++++++++++++++++++++++++ 4 files changed, 72 insertions(+), 17 deletions(-) diff --git a/theseus/geometry/se2.py b/theseus/geometry/se2.py index d39bdd67c..7484db3cd 100644 --- a/theseus/geometry/se2.py +++ b/theseus/geometry/se2.py @@ -8,6 +8,7 @@ import torch import theseus.constants +from theseus.geometry.lie_group_check import no_lie_group_check from .lie_group import LieGroup from .point_types import Point2 @@ -120,7 +121,8 @@ def __str__(self) -> str: @property def rotation(self) -> SO2: - return SO2(tensor=self[:, 2:]) + with no_lie_group_check(): + return SO2(tensor=self[:, 2:]) def theta(self, jacobians: Optional[List[torch.Tensor]] = None) -> torch.Tensor: if jacobians is not None: @@ -132,7 +134,8 @@ def theta(self, jacobians: Optional[List[torch.Tensor]] = None) -> torch.Tensor: @property def translation(self) -> Point2: - return self.xy() + with no_lie_group_check(): + return self.xy() def xy(self, jacobians: Optional[List[torch.Tensor]] = None) -> Point2: if jacobians is not None: diff --git a/theseus/geometry/se3.py b/theseus/geometry/se3.py index 5cc78c2f6..3494d19b8 100644 --- a/theseus/geometry/se3.py +++ b/theseus/geometry/se3.py @@ -14,7 +14,7 @@ from .lie_group import LieGroup from .point_types import Point3 from .so3 import SO3 -from .lie_group_check import _LieGroupCheckContext +from .lie_group_check import _LieGroupCheckContext, no_lie_group_check class SE3(LieGroup): @@ -499,6 +499,7 @@ def to_matrix(self) -> torch.Tensor: ret[:, 3, 3] = 1 return ret + # The quaternion takes the [w x y z] convention def update_from_x_y_z_quaternion(self, x_y_z_quaternion: torch.Tensor): self.update(SE3.x_y_z_unit_quaternion_to_SE3(x_y_z_quaternion)) @@ -622,6 +623,24 @@ def transform_to( return ret + # The returned tensor will have 7 elements, [x, y, z, qw, qx, qy, qz] where + # [x y z] corresponds to the translation and [qw qx qy qz] to the quaternion + # using the [w x y z] convention + def to_x_y_z_quaternion(self) -> torch.Tensor: + ret = self.tensor.new_zeros(self.shape[0], 7) + ret[:, :3] = self.tensor[:, :, 3] + with no_lie_group_check(): + ret[:, 3:] = SO3(tensor=self.tensor[:, :, :3]).to_quaternion() + return ret + + def rotation(self) -> SO3: + with no_lie_group_check(): + return SO3(tensor=self.tensor[:, :, :3]) + + def translation(self) -> Point3: + with no_lie_group_check(): + return Point3(tensor=self.tensor[:, :, 3].view(-1, 3)) + # calls to() on the internal tensors def to(self, *args, **kwargs): super().to(*args, **kwargs) diff --git a/theseus/geometry/so3.py b/theseus/geometry/so3.py index 6cbb2ba31..881c18d8b 100644 --- a/theseus/geometry/so3.py +++ b/theseus/geometry/so3.py @@ -368,6 +368,7 @@ def _inverse_impl(self, get_jacobian: bool = False) -> "SO3": def to_matrix(self) -> torch.Tensor: return self.tensor.clone() + # The quaternion takes the [w x y z] convention def to_quaternion(self) -> torch.Tensor: sine_axis = self.tensor.new_zeros(self.shape[0], 3) sine_axis[:, 0] = 0.5 * (self[:, 2, 1] - self[:, 1, 2]) @@ -449,26 +450,27 @@ def _rotate_shape_check(self, point: Union[Point3, torch.Tensor]): ): raise ValueError(err_msg) + # The quaternion takes the [w x y z] convention @staticmethod def unit_quaternion_to_SO3(quaternion: torch.Tensor) -> "SO3": if quaternion.ndim == 1: quaternion = quaternion.unsqueeze(0) SO3._unit_quaternion_check(quaternion) - q0 = quaternion[:, 0] - q1 = quaternion[:, 1] - q2 = quaternion[:, 2] - q3 = quaternion[:, 3] - q00 = q0 * q0 - q01 = q0 * q1 - q02 = q0 * q2 - q03 = q0 * q3 - q11 = q1 * q1 - q12 = q1 * q2 - q13 = q1 * q3 - q22 = q2 * q2 - q23 = q2 * q3 - q33 = q3 * q3 + w = quaternion[:, 0] + x = quaternion[:, 1] + y = quaternion[:, 2] + z = quaternion[:, 3] + q00 = w * w + q01 = w * x + q02 = w * y + q03 = w * z + q11 = x * x + q12 = x * y + q13 = x * z + q22 = y * y + q23 = y * z + q33 = z * z ret = SO3() ret.tensor = quaternion.new_zeros(quaternion.shape[0], 3, 3) diff --git a/theseus/geometry/tests/test_se3.py b/theseus/geometry/tests/test_se3.py index 295d7a016..e662346ac 100644 --- a/theseus/geometry/tests/test_se3.py +++ b/theseus/geometry/tests/test_se3.py @@ -33,6 +33,16 @@ def check_SE3_log_map(tangent_vector, atol=TEST_EPS, enable_functorch=False): assert torch.allclose(th.SE3.exp_map(g.log_map()).tensor, g.tensor, atol=atol) +def check_SE3_to_x_y_z_quaternion(se3: th.SE3, atol=1e-10, enable_functorch=False): + with set_lie_group_check_enabled(not enable_functorch): + x_y_z_quaternion = se3.to_x_y_z_quaternion() + assert torch.allclose( + th.SE3(x_y_z_quaternion=x_y_z_quaternion).to_matrix(), + se3.to_matrix(), + atol=atol, + ) + + def _create_tangent_vector(batch_size, ang_factor, rng, dtype): tangent_vector_ang = torch.rand(batch_size, 3, generator=rng, dtype=dtype) - 0.5 tangent_vector_ang /= tangent_vector_ang.norm(dim=1, keepdim=True) @@ -172,6 +182,27 @@ def test_inverse(dtype, enable_functorch): check_inverse(se3, enable_functorch) +@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) +@pytest.mark.parametrize( + "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] +) +@pytest.mark.parametrize("enable_functorch", [True, False]) +def test_x_y_z_quaternion(batch_size, dtype, ang_factor, enable_functorch): + rng = torch.Generator() + rng.manual_seed(0) + ATOL = 1e-3 if dtype == torch.float32 else 1e-8 + + if ang_factor is None: + ang_factor = ( + torch.rand(batch_size, 1, generator=rng, dtype=dtype) * 2 * np.pi - np.pi + ) + + tangent_vector = _create_tangent_vector(batch_size, ang_factor, rng, dtype) + se3 = th.SE3.exp_map(tangent_vector) + check_SE3_to_x_y_z_quaternion(se3, atol=ATOL, enable_functorch=enable_functorch) + + @pytest.mark.parametrize("batch_size", [1, 20, 100]) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize("enable_functorch", [True, False]) From 1b4028aa483854ba7424743bb1490f4f269e01ae Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Mon, 19 Sep 2022 12:17:33 -0400 Subject: [PATCH 25/38] Added th.as_variable() function to simplify creating new variables. (#299) --- theseus/__init__.py | 1 + theseus/core/__init__.py | 2 +- theseus/core/cost_weight.py | 16 +++---------- theseus/core/variable.py | 19 ++++++++++++++- theseus/embodied/collision/collision.py | 9 ++----- theseus/embodied/collision/eff_obj_contact.py | 9 ++----- .../collision/signed_distance_field.py | 5 ++-- .../embodied/motionmodel/double_integrator.py | 24 ++++--------------- .../quasi_static_pushing_planar.py | 7 ++---- 9 files changed, 36 insertions(+), 56 deletions(-) diff --git a/theseus/__init__.py b/theseus/__init__.py index 7f21e31b2..eeff66f21 100644 --- a/theseus/__init__.py +++ b/theseus/__init__.py @@ -18,6 +18,7 @@ RobustCostFunction, HuberLoss, WelschLoss, + as_variable, ) from .geometry import ( SE2, diff --git a/theseus/core/__init__.py b/theseus/core/__init__.py index 5d24e95d6..faebee6ba 100644 --- a/theseus/core/__init__.py +++ b/theseus/core/__init__.py @@ -8,5 +8,5 @@ from .objective import Objective from .robust_cost_function import RobustCostFunction from .robust_loss import HuberLoss, RobustLoss, WelschLoss -from .variable import Variable +from .variable import Variable, as_variable from .vectorizer import Vectorize diff --git a/theseus/core/cost_weight.py b/theseus/core/cost_weight.py index 62b0357f4..7c4c22fa9 100644 --- a/theseus/core/cost_weight.py +++ b/theseus/core/cost_weight.py @@ -10,7 +10,7 @@ import torch from .theseus_function import TheseusFunction -from .variable import Variable +from .variable import Variable, as_variable # Abstract class for representing cost weights (aka, precisions, inverse covariance) @@ -59,12 +59,7 @@ def __init__( name: Optional[str] = None, ): super().__init__(name=name) - if not isinstance(scale, Variable): - if not isinstance(scale, torch.Tensor): - scale = torch.tensor(scale) - self.scale = Variable(scale) - else: - self.scale = scale + self.scale = as_variable(scale) if not self.scale.tensor.squeeze().ndim in [0, 1]: raise ValueError( "ScaleCostWeight only accepts 0- or 1-dim (batched) tensors." @@ -99,12 +94,7 @@ def __init__( name: Optional[str] = None, ): super().__init__(name=name) - if not isinstance(diagonal, Variable): - if not isinstance(diagonal, torch.Tensor): - diagonal = torch.tensor(diagonal) - self.diagonal = Variable(diagonal) - else: - self.diagonal = diagonal + self.diagonal = as_variable(diagonal) if not self.diagonal.tensor.squeeze().ndim < 3: raise ValueError("DiagonalCostWeight only accepts tensors with ndim < 3.") if self.diagonal.tensor.ndim == 0: diff --git a/theseus/core/variable.py b/theseus/core/variable.py index 87e889d95..f25c2f450 100644 --- a/theseus/core/variable.py +++ b/theseus/core/variable.py @@ -4,7 +4,7 @@ # LICENSE file in the root directory of this source tree. from itertools import count -from typing import Optional, Union +from typing import Optional, Sequence, Union import torch @@ -100,3 +100,20 @@ def __getitem__(self, item): def __setitem__(self, item, value): self.tensor[item] = value + + +# If value is a variable, this returns the same variable +# Otherwise value is wrapper into a variable (and a tensor, if needed) +# In this case, the device, dtype and name can be specified. +def as_variable( + value: Union[float, Sequence[float], torch.Tensor, Variable], + device: Optional[torch.device] = None, + dtype: Optional[torch.dtype] = None, + name: Optional[str] = None, +) -> Variable: + if isinstance(value, Variable): + return value + tensor = torch.as_tensor(value, dtype=dtype, device=device) + if isinstance(value, float): + tensor = tensor.view(1, 1) + return Variable(tensor, name=name) diff --git a/theseus/embodied/collision/collision.py b/theseus/embodied/collision/collision.py index d1093199b..761462060 100644 --- a/theseus/embodied/collision/collision.py +++ b/theseus/embodied/collision/collision.py @@ -7,7 +7,7 @@ import torch -from theseus.core import CostFunction, CostWeight, Variable +from theseus.core import CostFunction, CostWeight, Variable, as_variable from theseus.embodied.kinematics import IdentityModel, KinematicsModel from theseus.geometry import Point2, SE2 @@ -32,12 +32,7 @@ def __init__( self.sdf_origin = SignedDistanceField2D.convert_origin(sdf_origin) self.sdf_data = SignedDistanceField2D.convert_sdf_data(sdf_data) self.sdf_cell_size = SignedDistanceField2D.convert_cell_size(sdf_cell_size) - if not isinstance(cost_eps, Variable): - if not isinstance(cost_eps, torch.Tensor): - cost_eps = torch.tensor(cost_eps) - self.cost_eps = Variable(cost_eps) - else: - self.cost_eps = cost_eps + self.cost_eps = as_variable(cost_eps) self.cost_eps.tensor = self.cost_eps.tensor.view(-1, 1) self.register_optim_vars(["pose"]) self.register_aux_vars(["sdf_origin", "sdf_data", "sdf_cell_size", "cost_eps"]) diff --git a/theseus/embodied/collision/eff_obj_contact.py b/theseus/embodied/collision/eff_obj_contact.py index 8ae484313..e1f7b98e7 100644 --- a/theseus/embodied/collision/eff_obj_contact.py +++ b/theseus/embodied/collision/eff_obj_contact.py @@ -7,7 +7,7 @@ import torch -from theseus.core import CostFunction, CostWeight, Variable +from theseus.core import CostFunction, CostWeight, Variable, as_variable from theseus.embodied.kinematics import IdentityModel from theseus.geometry import SE2, Point2 @@ -33,12 +33,7 @@ def __init__( self.sdf_origin = SignedDistanceField2D.convert_origin(sdf_origin) self.sdf_data = SignedDistanceField2D.convert_sdf_data(sdf_data) self.sdf_cell_size = SignedDistanceField2D.convert_cell_size(sdf_cell_size) - if not isinstance(eff_radius, Variable): - if not isinstance(eff_radius, torch.Tensor): - eff_radius = torch.tensor(eff_radius) - self.eff_radius = Variable(eff_radius) - else: - self.eff_radius = eff_radius + self.eff_radius = as_variable(eff_radius) if self.eff_radius.tensor.squeeze().ndim > 1: raise ValueError("eff_radius must be a 0-D or 1-D tensor.") self.eff_radius.tensor = self.eff_radius.tensor.view(-1, 1) diff --git a/theseus/embodied/collision/signed_distance_field.py b/theseus/embodied/collision/signed_distance_field.py index 9eac66781..3c55ab5ff 100644 --- a/theseus/embodied/collision/signed_distance_field.py +++ b/theseus/embodied/collision/signed_distance_field.py @@ -8,7 +8,7 @@ import torch from scipy import ndimage -from theseus.core import Variable +from theseus.core import Variable, as_variable from theseus.geometry import Point2 from theseus.utils import gather_from_rows_cols @@ -128,8 +128,7 @@ def convert_cell_size(cell_size: Union[float, torch.Tensor, Variable]) -> Variab @staticmethod def convert_sdf_data(sdf_data: Union[torch.Tensor, Variable]) -> Variable: - if not isinstance(sdf_data, Variable): - sdf_data = Variable(sdf_data) + sdf_data = as_variable(sdf_data) if sdf_data.ndim != 3: raise ValueError( "Argument sdf_data to SignedDistanceField2D must be a " diff --git a/theseus/embodied/motionmodel/double_integrator.py b/theseus/embodied/motionmodel/double_integrator.py index 8bc0cc9a1..e799e2f39 100644 --- a/theseus/embodied/motionmodel/double_integrator.py +++ b/theseus/embodied/motionmodel/double_integrator.py @@ -7,7 +7,7 @@ import torch -from theseus.core import CostFunction, CostWeight, Variable +from theseus.core import CostFunction, CostWeight, Variable, as_variable from theseus.geometry import LieGroup, Vector @@ -28,12 +28,7 @@ def __init__( raise ValueError( "All variables for a DoubleIntegrator must have the same dimension." ) - if not isinstance(dt, Variable): - if not isinstance(dt, torch.Tensor): - dt = torch.tensor(dt) - self.dt = Variable(dt) - else: - self.dt = dt + self.dt = as_variable(dt) if self.dt.tensor.squeeze().ndim > 1: raise ValueError( "dt data must be a 0-D or 1-D tensor with numel in {1, batch_size}." @@ -106,17 +101,13 @@ def __init__( name: Optional[str] = None, ): super().__init__(name=name) - if not isinstance(dt, Variable): - if not isinstance(dt, torch.Tensor): - dt = torch.tensor(dt) - dt = Variable(dt) + dt = as_variable(dt) if dt.tensor.squeeze().ndim > 1: raise ValueError("dt must be a 0-D or 1-D tensor.") self.dt = dt self.dt.tensor = self.dt.tensor.view(-1, 1) - if not isinstance(Qc_inv, Variable): - Qc_inv = Variable(Qc_inv) + Qc_inv = as_variable(Qc_inv) if Qc_inv.ndim not in [2, 3]: raise ValueError("Qc_inv must be a single matrix or a batch of matrices.") if not Qc_inv.shape[-2] == Qc_inv.shape[-1]: @@ -191,12 +182,7 @@ def __init__( "GPMotionModel only accepts cost weights of type GPCostWeight. " "For other weight types, consider using DoubleIntegrator instead." ) - if not isinstance(dt, Variable): - if not isinstance(dt, torch.Tensor): - dt = torch.tensor(dt) - self.dt = Variable(dt) - else: - self.dt = dt + self.dt = as_variable(dt) if self.dt.tensor.squeeze().ndim > 1: raise ValueError("dt must be a 0-D or 1-D tensor.") self.dt.tensor = self.dt.tensor.view(-1, 1) diff --git a/theseus/embodied/motionmodel/quasi_static_pushing_planar.py b/theseus/embodied/motionmodel/quasi_static_pushing_planar.py index 09abd67bb..2b9e82201 100644 --- a/theseus/embodied/motionmodel/quasi_static_pushing_planar.py +++ b/theseus/embodied/motionmodel/quasi_static_pushing_planar.py @@ -7,7 +7,7 @@ import torch -from theseus.core import CostFunction, CostWeight, Variable +from theseus.core import CostFunction, CostWeight, Variable, as_variable from theseus.geometry import SE2, OptionalJacobians from theseus.geometry.so2 import SO2 @@ -34,10 +34,7 @@ def __init__( self.eff2 = eff2 self.register_optim_vars(["obj1", "obj2", "eff1", "eff2"]) - if not isinstance(c_square, Variable): - if isinstance(c_square, float): - c_square = torch.tensor(c_square, dtype=self.obj1.dtype).view(1, 1) - c_square = Variable(c_square, name=f"csquare_{name}") + c_square = as_variable(c_square, dtype=self.obj1.dtype, name=f"csquare_{name}") if c_square.tensor.squeeze().ndim > 1: raise ValueError("dt must be a 0-D or 1-D tensor.") self.c_square = c_square From 542937efb290153399e9d21d28680958636e9b3d Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Tue, 20 Sep 2022 16:16:34 -0400 Subject: [PATCH 26/38] Added an optional end-of-step callback to NonlinearOptimizer.optimize(). (#297) * Added an optional end-of-step callback to NonlinearOptimizer.optimize(). * Renamed callback to end_iter_callback. --- .../optimizer/nonlinear/nonlinear_optimizer.py | 18 +++++++++++++++++- theseus/optimizer/nonlinear/tests/common.py | 15 ++++++++++++++- 2 files changed, 31 insertions(+), 2 deletions(-) diff --git a/theseus/optimizer/nonlinear/nonlinear_optimizer.py b/theseus/optimizer/nonlinear/nonlinear_optimizer.py index 2a50940b8..5111d4b46 100644 --- a/theseus/optimizer/nonlinear/nonlinear_optimizer.py +++ b/theseus/optimizer/nonlinear/nonlinear_optimizer.py @@ -8,7 +8,7 @@ import warnings from dataclasses import dataclass from enum import Enum -from typing import Any, Dict, Optional, Type +from typing import Any, Callable, Dict, NoReturn, Optional, Type import numpy as np import torch @@ -59,6 +59,11 @@ class BackwardMode(Enum): DLM = 3 +EndIterCallbackType = Callable[ + ["NonlinearOptimizer", NonlinearOptimizerInfo, torch.Tensor, int], NoReturn +] + + class NonlinearOptimizer(Optimizer, abc.ABC): def __init__( self, @@ -254,6 +259,7 @@ def _optimize_loop( info: NonlinearOptimizerInfo, verbose: bool, truncated_grad_loop: bool, + end_iter_callback: Optional[EndIterCallbackType] = None, **kwargs, ) -> int: converged_indices = torch.zeros_like(info.last_err).bool() @@ -325,6 +331,9 @@ def _optimize_loop( break # nothing else will happen at this point info.last_err = err + if end_iter_callback is not None: + end_iter_callback(self, info, delta, it_) + info.status[ info.status == NonlinearOptimizerStatus.START ] = NonlinearOptimizerStatus.MAX_ITERATIONS @@ -333,6 +342,9 @@ def _optimize_loop( # `track_best_solution` keeps a **detached** copy (as in no gradient info) # of the best variables found, but it is optional to avoid unnecessary copying # if this is not needed + # + # If `end_iter_callback` is passed, it's called at the very end of each optimizer + # iteration, with four input arguments: (optimizer, info, delta, step_idx). def _optimize_impl( self, track_best_solution: bool = False, @@ -340,6 +352,7 @@ def _optimize_impl( track_state_history: bool = False, verbose: bool = False, backward_mode: BackwardMode = BackwardMode.FULL, + end_iter_callback: Optional[EndIterCallbackType] = None, **kwargs, ) -> OptimizerInfo: with torch.no_grad(): @@ -360,6 +373,7 @@ def _optimize_impl( info=info, verbose=verbose, truncated_grad_loop=False, + end_iter_callback=end_iter_callback, **kwargs, ) # If didn't coverge, remove misleading converged_iter value @@ -394,6 +408,7 @@ def _optimize_impl( info=info, verbose=verbose, truncated_grad_loop=False, + end_iter_callback=end_iter_callback, **kwargs, ) @@ -405,6 +420,7 @@ def _optimize_impl( info=grad_loop_info, verbose=verbose, truncated_grad_loop=True, + end_iter_callback=end_iter_callback, **kwargs, ) diff --git a/theseus/optimizer/nonlinear/tests/common.py b/theseus/optimizer/nonlinear/tests/common.py index 8152db2d9..809c40dd5 100644 --- a/theseus/optimizer/nonlinear/tests/common.py +++ b/theseus/optimizer/nonlinear/tests/common.py @@ -146,8 +146,21 @@ def _check_nonlinear_least_squares_fit( optimizer = nonlinear_optim_cls(objective) assert isinstance(optimizer.linear_solver, th.CholeskyDenseSolver) optimizer.set_params(max_iterations=max_iterations) + + callback_expected_iter = [0] + + def callback(opt_, info_, delta_, it_): + assert opt_ is optimizer + assert isinstance(info_, th.optimizer.OptimizerInfo) + assert isinstance(delta_, torch.Tensor) + assert it_ == callback_expected_iter[0] + callback_expected_iter[0] += 1 + info = optimizer.optimize( - track_best_solution=True, track_err_history=True, **optimize_kwargs + track_best_solution=True, + track_err_history=True, + end_iter_callback=callback, + **optimize_kwargs, ) # Solution must now match the true coefficients assert variables[0].tensor.allclose(true_coeffs.repeat(batch_size, 1), atol=1e-6) From afa7ce43b079ec420fe5463cb8f73be8950e4014 Mon Sep 17 00:00:00 2001 From: Luis Pineda <4759586+luisenp@users.noreply.github.com> Date: Wed, 21 Sep 2022 10:47:54 -0700 Subject: [PATCH 27/38] Updated tactile pose estimation configuration. --- examples/configs/tactile_pose_estimation.yaml | 24 +++++++++---------- 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/examples/configs/tactile_pose_estimation.yaml b/examples/configs/tactile_pose_estimation.yaml index f02b65239..3adf84eb6 100644 --- a/examples/configs/tactile_pose_estimation.yaml +++ b/examples/configs/tactile_pose_estimation.yaml @@ -4,33 +4,33 @@ save_all: true dataset_name: "rectangle-pushing-corners-keypoints" sdf_name: "rect" -episode_length: 100 -max_steps: 100 -max_episodes: 1 # if split = true, actual number might be slightly larger +episode_length: 25 +max_steps: 200 +max_episodes: 100 # if split = true, actual number might be slightly larger split_episodes: true inner_optim: - max_iters: 50 + max_iters: 5 optimizer: GaussNewton reg_w: 0 backward_mode: IMPLICIT - backward_num_iterations: 2 # only needed by TRUNCATED backward mode - dlm_epsilon: None + backward_num_iterations: None # only needed by TRUNCATED backward mode + dlm_epsilon: None # only needed by DLM backward mode force_implicit_by_epoch: 10000 - step_size: 0.3 + step_size: 0.05 keep_step_size: true - force_max_iters: false + force_max_iters: true val_iters: 50 train: # options: "weights_only" or "weights_and_measurement_nn" mode: "weights_and_measurement_nn" - batch_size: 1 - num_epochs: 200 - lr: 3e-4 + batch_size: 8 + num_epochs: 100 + lr: 1e-4 optimizer: "adam" # "adam", "rmsprop" lr_decay: 0.98 - val_ratio: 0 + val_ratio: 0.1 max_num_batches: 100 # 0: disc, 1: rect-edges, 2: rect-corners, 3: ellip From a78f5248108d6282fbfcc68390a574d56b01c7fe Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Wed, 21 Sep 2022 15:46:39 -0400 Subject: [PATCH 28/38] Add AutogradMode to AutoDiffCostFunction (#300) * add some AutoGradMode * update AutoGradMode to test_cost_function.py * rename functorch to vmap * AutoGradMode -> AutogradMode * update tests in geometry --- theseus/__init__.py | 1 + theseus/core/__init__.py | 2 +- theseus/core/cost_function.py | 46 ++++++++---------- theseus/core/tests/test_cost_function.py | 61 +++++++++++------------- theseus/geometry/tests/common.py | 18 +++---- 5 files changed, 58 insertions(+), 70 deletions(-) diff --git a/theseus/__init__.py b/theseus/__init__.py index eeff66f21..629292692 100644 --- a/theseus/__init__.py +++ b/theseus/__init__.py @@ -15,6 +15,7 @@ Vectorize, RobustLoss, AutoDiffCostFunction, + AutogradMode, RobustCostFunction, HuberLoss, WelschLoss, diff --git a/theseus/core/__init__.py b/theseus/core/__init__.py index faebee6ba..74e8d095f 100644 --- a/theseus/core/__init__.py +++ b/theseus/core/__init__.py @@ -3,7 +3,7 @@ # This source code is licensed under the MIT license found in the # LICENSE file in the root directory of this source tree. -from .cost_function import AutoDiffCostFunction, CostFunction, ErrFnType +from .cost_function import AutoDiffCostFunction, AutogradMode, CostFunction, ErrFnType from .cost_weight import CostWeight, DiagonalCostWeight, ScaleCostWeight from .objective import Objective from .robust_cost_function import RobustCostFunction diff --git a/theseus/core/cost_function.py b/theseus/core/cost_function.py index 58d95dc01..2899193a1 100644 --- a/theseus/core/cost_function.py +++ b/theseus/core/cost_function.py @@ -5,7 +5,7 @@ import abc from typing import Callable, List, Optional, Sequence, Tuple, cast -import warnings +from enum import Enum import torch import torch.autograd.functional as autogradF @@ -96,6 +96,12 @@ def __call__( ... +class AutogradMode(Enum): + DENSE = 0 + LOOP_BATCH = 1 + VMAP = 2 + + # The error function is assumed to receive variables in the format # err_fn( # optim_vars=(optim_vars[0].tensor, ..., optim_vars[N - 1].tensor), @@ -114,8 +120,7 @@ def __init__( name: Optional[str] = None, autograd_strict: bool = False, autograd_vectorize: bool = False, - autograd_loop_over_batch: bool = False, - autograd_functorch: bool = False, + autograd_mode: AutogradMode = AutogradMode.DENSE, ): if cost_weight is None: cost_weight = ScaleCostWeight(1.0) @@ -142,17 +147,9 @@ def __init__( self._tmp_optim_vars_for_loop = None self._tmp_aux_vars_for_loop = None - self._autograd_loop_over_batch = autograd_loop_over_batch - self._autograd_functorch = autograd_functorch - - if autograd_functorch and self._autograd_loop_over_batch: - self._autograd_loop_over_batch = False - warnings.warn( - "autograd_use_functorch=True overrides given autograd_loop_over_batch=True, " - "so the latter will be set to False" - ) + self._autograd_mode = autograd_mode - if self._autograd_loop_over_batch: + if self._autograd_mode == AutogradMode.LOOP_BATCH: self._tmp_optim_vars_for_loop = tuple(v.copy() for v in optim_vars) self._tmp_aux_vars_for_loop = tuple(v.copy() for v in aux_vars) @@ -161,8 +158,7 @@ def __init__( for i, aux_var in enumerate(aux_vars): self._tmp_aux_vars_for_loop[i].update(aux_var.tensor) - - if self._autograd_functorch: + elif self._autograd_mode == AutogradMode.VMAP: self._tmp_aux_vars = tuple(v.copy() for v in aux_vars) def _compute_error( @@ -203,7 +199,7 @@ def _compute_autograd_jacobian( vectorize=self._autograd_vectorize, ) - def _make_jac_fn_functorch( + def _make_jac_fn_vmap( self, tmp_optim_vars: Tuple[Manifold, ...], tmp_aux_vars: Tuple[Variable, ...] ): def jac_fn(optim_vars_tensors_, aux_vars_tensors_): @@ -223,7 +219,7 @@ def jac_fn(optim_vars_tensors_, aux_vars_tensors_): return jac_fn - def _compute_autograd_jacobian_functorch( + def _compute_autograd_jacobian_vmap( self, optim_tensors: Tuple[torch.Tensor, ...], aux_tensors: Tuple[torch.Tensor, ...], @@ -233,13 +229,13 @@ def _compute_autograd_jacobian_functorch( def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: err, optim_vars, aux_vars = self._compute_error() - if self._autograd_functorch: - jacobians_full = self._compute_autograd_jacobian_functorch( + if self._autograd_mode == AutogradMode.VMAP: + jacobians_full = self._compute_autograd_jacobian_vmap( tuple(v.tensor for v in optim_vars), tuple(v.tensor for v in aux_vars), - self._make_jac_fn_functorch(self._tmp_optim_vars, self._tmp_aux_vars), + self._make_jac_fn_vmap(self._tmp_optim_vars, self._tmp_aux_vars), ) - elif self._autograd_loop_over_batch: + elif self._autograd_mode == AutogradMode.LOOP_BATCH: jacobians_raw_loop: List[Tuple[torch.Tensor, ...]] = [] for n in range(optim_vars[0].shape[0]): for i, aux_var in enumerate(aux_vars): @@ -285,8 +281,7 @@ def _copy_impl(self, new_name: Optional[str] = None) -> "AutoDiffCostFunction": aux_vars=[v.copy() for v in self.aux_vars], cost_weight=self.weight.copy(), name=new_name, - autograd_loop_over_batch=self._autograd_loop_over_batch, - autograd_functorch=self._autograd_functorch, + autograd_mode=self._autograd_mode, ) def to(self, *args, **kwargs): @@ -295,13 +290,12 @@ def to(self, *args, **kwargs): for var in self._tmp_optim_vars: var.to(*args, **kwargs) - if self._autograd_loop_over_batch: + if self._autograd_mode == AutogradMode.LOOP_BATCH: for var in self._tmp_optim_vars_for_loop: var.to(*args, **kwargs) for var in self._tmp_aux_vars_for_loop: var.to(*args, **kwargs) - - if self._autograd_functorch: + elif self._autograd_mode == AutogradMode.VMAP: for var in self._tmp_aux_vars: var.to(*args, **kwargs) diff --git a/theseus/core/tests/test_cost_function.py b/theseus/core/tests/test_cost_function.py index 1c3779459..742d3cbd2 100644 --- a/theseus/core/tests/test_cost_function.py +++ b/theseus/core/tests/test_cost_function.py @@ -10,6 +10,7 @@ import torch import theseus as th +from theseus.core.cost_function import AutogradMode from theseus.core.cost_weight import ScaleCostWeight from .common import ( @@ -56,11 +57,10 @@ def test_default_name_and_ids(): assert len(seen_ids) == reps -@pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -@pytest.mark.parametrize("autograd_functorch", [True, False]) -def test_autodiff_cost_function_error_and_jacobians_shape( - autograd_loop_over_batch, autograd_functorch -): +@pytest.mark.parametrize( + "autograd_mode", [AutogradMode.DENSE, AutogradMode.LOOP_BATCH, AutogradMode.VMAP] +) +def test_autodiff_cost_function_error_and_jacobians_shape(autograd_mode): rng = torch.Generator() rng.manual_seed(0) for i in range(100): @@ -108,7 +108,7 @@ def error_fn(optim_vars, aux_vars): for i, arg in enumerate(all_vars): assert isinstance(arg, th.Variable) assert arg.shape == (batch_size, i + 1) or arg.shape == (1, i + 1) - if not autograd_functorch: + if autograd_mode != AutogradMode.VMAP: assert arg.tensor.allclose( variable_values[i] * torch.ones_like(arg.tensor) ) @@ -135,8 +135,7 @@ def error_fn(optim_vars, aux_vars): err_dim, cost_weight=cost_weight, aux_vars=aux_vars, - autograd_loop_over_batch=autograd_loop_over_batch, - autograd_functorch=autograd_functorch, + autograd_mode=autograd_mode, ) err = cost_function.error() assert err.allclose( @@ -152,11 +151,10 @@ def error_fn(optim_vars, aux_vars): assert jacobians[i].shape == (batch_size, err_dim, i + 1) -@pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -@pytest.mark.parametrize("autograd_functorch", [True, False]) -def test_autodiff_cost_function_cost_weight( - autograd_loop_over_batch, autograd_functorch -): +@pytest.mark.parametrize( + "autograd_mode", [AutogradMode.DENSE, AutogradMode.LOOP_BATCH, AutogradMode.VMAP] +) +def test_autodiff_cost_function_cost_weight(autograd_mode): batch_size = 10 optim_vars = [] aux_vars = [] @@ -187,8 +185,7 @@ def error_fn(optim_vars, aux_vars): error_fn, 1, aux_vars=aux_vars, - autograd_loop_over_batch=autograd_loop_over_batch, - autograd_functorch=autograd_functorch, + autograd_mode=autograd_mode, ) assert isinstance(cost_function.weight, ScaleCostWeight) assert torch.allclose(cost_function.weight.scale.tensor, torch.ones(1, 1)) @@ -215,9 +212,10 @@ def error_fn(optim_vars, aux_vars): assert torch.allclose(weighted_error, direct_error_computation) -@pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -@pytest.mark.parametrize("autograd_functorch", [True, False]) -def test_autodiff_cost_function_to(autograd_loop_over_batch, autograd_functorch): +@pytest.mark.parametrize( + "autograd_mode", [AutogradMode.DENSE, AutogradMode.LOOP_BATCH, AutogradMode.VMAP] +) +def test_autodiff_cost_function_to(autograd_mode): batch_size = 10 optim_vars = [] aux_vars = [] @@ -250,8 +248,7 @@ def error_fn(optim_vars, aux_vars): error_fn, 1, aux_vars=aux_vars, - autograd_loop_over_batch=autograd_loop_over_batch, - autograd_functorch=autograd_functorch, + autograd_mode=autograd_mode, ) for var in optim_vars: @@ -266,11 +263,10 @@ def error_fn(optim_vars, aux_vars): cost_function.jacobians() -@pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -@pytest.mark.parametrize("autograd_functorch", [True, False]) -def test_autodiff_cost_function_error_and_jacobians_shape_on_SO3( - autograd_loop_over_batch, autograd_functorch -): +@pytest.mark.parametrize( + "autograd_mode", [AutogradMode.DENSE, AutogradMode.LOOP_BATCH, AutogradMode.VMAP] +) +def test_autodiff_cost_function_error_and_jacobians_shape_on_SO3(autograd_mode): for i in range(100): num_vars = np.random.randint(0, 5) batch_size = np.random.randint(1, 10) @@ -318,8 +314,7 @@ def error_fn(optim_vars, aux_vars): err_dim, cost_weight=cost_weight, aux_vars=aux_vars, - autograd_loop_over_batch=autograd_loop_over_batch, - autograd_functorch=autograd_functorch, + autograd_mode=autograd_mode, ) err = cost_function.error() @@ -332,11 +327,10 @@ def error_fn(optim_vars, aux_vars): assert jacobians[i].shape == (batch_size, err_dim, 3) -@pytest.mark.parametrize("autograd_loop_over_batch", [True, False]) -@pytest.mark.parametrize("autograd_functorch", [True, False]) -def test_autodiff_cost_function_error_and_jacobians_value_on_SO3( - autograd_loop_over_batch, autograd_functorch -): +@pytest.mark.parametrize( + "autograd_mode", [AutogradMode.DENSE, AutogradMode.LOOP_BATCH, AutogradMode.VMAP] +) +def test_autodiff_cost_function_error_and_jacobians_value_on_SO3(autograd_mode): for i in range(100): num_vars = np.random.randint(0, 5) batch_size = np.random.randint(1, 10) @@ -384,8 +378,7 @@ def error_fn(optim_vars, aux_vars): err_dim, cost_weight=cost_weight, aux_vars=aux_vars, - autograd_loop_over_batch=autograd_loop_over_batch, - autograd_functorch=autograd_functorch, + autograd_mode=autograd_mode, ) jac_actual, err_actual = cost_function.jacobians() diff --git a/theseus/geometry/tests/common.py b/theseus/geometry/tests/common.py index 96ad07479..2559f0af9 100644 --- a/theseus/geometry/tests/common.py +++ b/theseus/geometry/tests/common.py @@ -9,7 +9,7 @@ from theseus.utils import numeric_jacobian from theseus.geometry.lie_group_check import set_lie_group_check_enabled from theseus.geometry.vector import Vector -from theseus.core.cost_function import AutoDiffCostFunction +from theseus.core.cost_function import AutoDiffCostFunction, AutogradMode def check_exp_map(tangent_vector, group_cls, atol=TEST_EPS, enable_functorch=False): @@ -35,7 +35,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -51,7 +51,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -74,7 +74,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -90,7 +90,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -135,7 +135,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -158,7 +158,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -195,7 +195,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() @@ -227,7 +227,7 @@ def err_fn(optim_vars, aux_vars): jacs, _ = cost_fn.jacobians() cost_fn_vec = AutoDiffCostFunction( - optim_vars, err_fn, dim=1, autograd_functorch=True + optim_vars, err_fn, dim=1, autograd_mode=AutogradMode.VMAP ) jacs_vec, _ = cost_fn_vec.jacobians() From 98df1c5d6e52472691c2aa2f511c5da815a6b4e0 Mon Sep 17 00:00:00 2001 From: Taosha Fan <6612911+fantaosha@users.noreply.github.com> Date: Wed, 21 Sep 2022 16:26:19 -0400 Subject: [PATCH 29/38] Profile AutoDiffCostFunction and refactor the homography example (#296) * add logging and functorch to homography example * add homography profiling script * backup * import cast from typing * add hydra for homography * update homography example * update homography_estimation.py with AutogradMode * update homography example * add profile_auto_diff_cost_function.sh * move profile_auto_diff_cost_function.sh to evaluations * add "time/per peoch" to homography_estimation * update evaluations/README.md * 1025->1024 * refactor readme * move comments * add a new line * add a condition to ignore warning for the homography example --- evaluations/README.md | 6 +- .../autodiff_cost_function_ablation.sh | 3 + examples/README.md | 3 +- examples/configs/homography_estimation.yaml | 14 ++ examples/configs/motion_planning_2d.yaml | 2 +- examples/homography_estimation.py | 179 +++++++++++++----- theseus/__init__.py | 1 + theseus/core/cost_function.py | 6 +- theseus/optimizer/nonlinear/__init__.py | 1 + 9 files changed, 165 insertions(+), 50 deletions(-) create mode 100644 evaluations/autodiff_cost_function_ablation.sh create mode 100644 examples/configs/homography_estimation.yaml diff --git a/evaluations/README.md b/evaluations/README.md index c555f8c5b..1bb919e75 100644 --- a/evaluations/README.md +++ b/evaluations/README.md @@ -6,6 +6,7 @@ scripts are available, with reference to corresponding figure in our white paper - `pose_graph_synthetic.sh`: Same as above, but can change linear solver and problem size (Fig. 2). - `pose_graph_cube.sh`: Same as above, but using the cube data for Ceres comparison (Fig. 3). - `backward_modes_tactile.sh`: Runs tactile state estimation with different backward modes (Fig. 4). + - `autodiff_cost_function_ablation.sh`: Runs homography estimation with different autograd modes. Some other relevant files to look at: @@ -21,4 +22,7 @@ Some other relevant files to look at: * Motion Planning: - `theseus/utils/examples/motion_planning/motion_planner.py`: Puts together optimization layer. - - `examples/motion_planning_2d.py`: Implements outer loop. \ No newline at end of file + - `examples/motion_planning_2d.py`: Implements outer loop. + +* Homography Estimation: + - `examples/homography_estimation.py`: Puts together optimization layer and implements outer loop. \ No newline at end of file diff --git a/evaluations/autodiff_cost_function_ablation.sh b/evaluations/autodiff_cost_function_ablation.sh new file mode 100644 index 000000000..e2a8fd5ca --- /dev/null +++ b/evaluations/autodiff_cost_function_ablation.sh @@ -0,0 +1,3 @@ +python examples/homography_estimation.py autograd_mode=dense outer_optim.batch_size=64 outer_optim.num_epochs=1 inner_optim.max_iters=10 +python examples/homography_estimation.py autograd_mode=loop_batch outer_optim.batch_size=64 outer_optim.num_epochs=1 inner_optim.max_iters=10 +python examples/homography_estimation.py autograd_mode=vmap outer_optim.batch_size=64 outer_optim.num_epochs=1 inner_optim.max_iters=10 diff --git a/examples/README.md b/examples/README.md index 8d3c461bd..b180195d2 100644 --- a/examples/README.md +++ b/examples/README.md @@ -43,9 +43,10 @@ The backward modes example requires `numdifftools`, which you can install with pip install numdifftools ``` -The homography example requires `kornia` and `OpenCV`, which you can install with +The homography example requires `hydra`, `kornia` and `OpenCV`, which you can install with ```bash +pip install hydra-core pip install kornia pip install opencv-python ``` diff --git a/examples/configs/homography_estimation.yaml b/examples/configs/homography_estimation.yaml new file mode 100644 index 000000000..a05333b12 --- /dev/null +++ b/examples/configs/homography_estimation.yaml @@ -0,0 +1,14 @@ +autograd_mode: vmap + +outer_optim: + num_epochs: 999 + batch_size: 128 + lr: 1e-4 + +inner_optim: + max_iters: 50 + step_size: 0.1 + +hydra: + run: + dir: examples/outputs/homography_estimation \ No newline at end of file diff --git a/examples/configs/motion_planning_2d.yaml b/examples/configs/motion_planning_2d.yaml index 7e4918d02..45bcd32ff 100644 --- a/examples/configs/motion_planning_2d.yaml +++ b/examples/configs/motion_planning_2d.yaml @@ -39,4 +39,4 @@ optim_params: hydra: run: - dir: examples/outputs \ No newline at end of file + dir: examples/outputs diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index c23c5574e..90d7187fb 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -4,11 +4,15 @@ # LICENSE file in the root directory of this source tree. import glob +import logging import os import shutil -from typing import List +import sys +import warnings +from typing import Dict, List, Tuple, cast import cv2 +import hydra import kornia import numpy as np import torch @@ -17,9 +21,13 @@ from torch.utils.data import DataLoader, Dataset import theseus as th +from theseus.core.cost_function import AutogradMode, ErrFnType from theseus.third_party.easyaug import GeoAugParam, RandomGeoAug, RandomPhotoAug from theseus.third_party.utils import grid_sample +if not sys.warnoptions: + warnings.filterwarnings("ignore", category=UserWarning) + FONT = cv2.FONT_HERSHEY_DUPLEX FONT_SZ = 0.5 FONT_PT = (5, 15) @@ -30,8 +38,12 @@ "truncated": th.BackwardMode.TRUNCATED, } +# Logger +logger = logging.getLogger(__name__) # Download and extract data + + def prepare_data(): dataset_root = os.path.join(os.getcwd(), "data") chunks = [ @@ -46,15 +58,15 @@ def prepare_data(): dataset_path = os.path.join(dataset_root, chunk) dataset_paths.append(dataset_path) if not os.path.exists(dataset_path): - print("Downloading data") + logger.info("Downloading data") url_root = "http://ptak.felk.cvut.cz/revisitop/revisitop1m/jpg/" tar = "%s.tar.gz" % chunk os.makedirs(dataset_path) cmd = "wget %s/%s -O %s/%s" % (url_root, tar, dataset_root, tar) - print("Running command: ", cmd) + logger.info("Running command: ", cmd) os.system(cmd) cmd = "tar -xf %s/%s -C %s" % (dataset_root, tar, dataset_path) - print("Running command: ", cmd) + logger.info("Running command: ", cmd) os.system(cmd) return dataset_paths @@ -68,7 +80,7 @@ def __init__(self, img_dirs, imgH, imgW, photo_aug=True, train=True): for direc in img_dirs: self.img_paths.extend(glob.glob(direc + "/**/*.jpg", recursive=True)) assert len(self.img_paths) > 0, "no images found" - print("Found %d total images in dataset" % len(self.img_paths)) + logger.info("Found %d total images in dataset" % len(self.img_paths)) sc = 0.1 self.rga = RandomGeoAug( rotate_param=GeoAugParam(min=-30 * sc, max=30 * sc), @@ -98,9 +110,9 @@ def __init__(self, img_dirs, imgH, imgW, photo_aug=True, train=True): self.img_paths = self.img_paths[split_ix:] self.train = train if self.train: - print("Using %d images for training" % len(self.img_paths)) + logger.info("Using %d images for training" % len(self.img_paths)) else: - print("Using %d images for testing" % len(self.img_paths)) + logger.info("Using %d images for testing" % len(self.img_paths)) def __len__(self): return len(self.img_paths) @@ -143,11 +155,12 @@ def warp_perspective_norm(H, img): # loss is difference between warped and target image -def homography_error_fn(optim_vars: List[th.Manifold], aux_vars: List[th.Variable]): +def homography_error_fn(optim_vars: Tuple[th.Manifold], aux_vars: Tuple[th.Variable]): H8_1_2 = optim_vars[0].tensor.reshape(-1, 8) # Force the last element H[2,2] to be 1. H_1_2 = torch.cat([H8_1_2, H8_1_2.new_ones(H8_1_2.shape[0], 1)], dim=-1) # type: ignore - img1, img2 = aux_vars + img1: th.Variable = aux_vars[0] + img2: th.Variable = aux_vars[-1] img1_dst = warp_perspective_norm(H_1_2.reshape(-1, 3, 3), img1.tensor) loss = torch.nn.functional.mse_loss(img1_dst, img2.tensor, reduction="none") ones = warp_perspective_norm( @@ -228,7 +241,7 @@ def write_gif_batch(log_dir, img1, img2, H_hist, Hgt_1_2, err_hist): viz_warp(path, img1[0], img2[0], img1_dsts[0], it, err=err, fc_err=fc_err) anim_path = os.path.join(log_dir, "animation.gif") cmd = f"convert -delay 10 -loop 0 {anim_dir}/*.png {anim_path}" - print("Generating gif here: %s" % anim_path) + logger.info("Generating gif here: %s" % anim_path) os.system(cmd) shutil.rmtree(anim_dir) return @@ -268,21 +281,32 @@ def forward(self, img): return self.conv2(x) -def run(): - batch_size = 64 - max_iterations = 50 - step_size = 0.1 - verbose = True +def run( + batch_size: int = 64, + num_epochs: int = 999, + outer_lr: float = 1e-4, + max_iterations: int = 50, + step_size: float = 0.1, + autograd_mode: AutogradMode = AutogradMode.VMAP, +): + logger.info( + "===============================================================" + "===========================" + ) + logger.info(f"Batch Size: {batch_size}, " f"Autograd Mode: {autograd_mode}, ") + + logger.info( + "---------------------------------------------------------------" + "---------------------------" + ) + verbose = False imgH, imgW = 60, 80 use_gpu = True viz_every = 10 - disp_every = 10 save_every = 100 - num_epochs = 999 - outer_lr = 1e-4 use_cnn = True - log_dir = os.path.join(os.getcwd(), "examples/outputs/viz") + log_dir = os.path.join(os.getcwd(), "viz") os.makedirs(log_dir, exist_ok=True) device = "cuda" if torch.cuda.is_available() and use_gpu else "cpu" @@ -309,15 +333,16 @@ def run(): # Set up inner loop optimization. homography_cf = th.AutoDiffCostFunction( optim_vars=[H8_1_2], - err_fn=homography_error_fn, + err_fn=cast(ErrFnType, homography_error_fn), dim=1, aux_vars=[feat1, feat2], + autograd_mode=autograd_mode, ) objective.add(homography_cf) # Regularization helps avoid crash with using implicit mode. - reg_w = 1e-2 - reg_w = th.ScaleCostWeight(np.sqrt(reg_w)) + reg_w_value = 1e-2 + reg_w = th.ScaleCostWeight(np.sqrt(reg_w_value)) reg_w.to(dtype=H8_init.dtype) vals = torch.tensor([[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]]) H8_1_2_id = th.Vector(tensor=vals, name="identity") @@ -339,10 +364,20 @@ def run(): itr = 0 + start_event = torch.cuda.Event(enable_timing=True) + end_event = torch.cuda.Event(enable_timing=True) + + logger.info( + "---------------------------------------------------------------" + "---------------------------" + ) for epoch in range(num_epochs): + forward_times: List[float] = [] + forward_mems: List[float] = [] + backward_times: List[float] = [] + backward_mems: List[float] = [] for _, data in enumerate(dataloader): - outer_optim.zero_grad() img1 = data["img1"].to(device) @@ -350,50 +385,72 @@ def run(): Hgt_1_2 = data["H_1_2"].to(device) if use_cnn: # Use cnn features. - feat1 = cnn_model.forward(img1) - feat2 = cnn_model.forward(img2) + feat1_tensor = cnn_model.forward(img1) + feat2_tensor = cnn_model.forward(img2) else: # Use image pixels. - feat1 = img1 - feat2 = img2 + feat1_tensor = img1 + feat2_tensor = img2 H8_init = torch.eye(3).reshape(1, 9)[:, :-1].repeat(batch_size, 1) H8_init = H8_init.to(device) - inputs = { + inputs: Dict[str, torch.Tensor] = { "H8_1_2": H8_init, - "feat1": feat1, - "feat2": feat2, + "feat1": feat1_tensor, + "feat2": feat2_tensor, } - if itr % disp_every == 0: - verbose2 = verbose - else: - verbose2 = False - info = theseus_layer.forward( + start_event.record() + torch.cuda.reset_peak_memory_stats() + _, info = theseus_layer.forward( inputs, optimizer_kwargs={ - "verbose": verbose2, + "verbose": verbose, "track_err_history": True, "track_state_history": True, "backward_mode": BACKWARD_MODE["implicit"], }, ) - err_hist = info[1].err_history - H_hist = info[1].state_history + end_event.record() + torch.cuda.synchronize() + forward_time = start_event.elapsed_time(end_event) + forward_mem = torch.cuda.max_memory_allocated() / 1024 / 1024 + forward_times.append(forward_time) + forward_mems.append(forward_mem) + + optimizer_info: th.NonlinearOptimizerInfo = cast( + th.NonlinearOptimizerInfo, info + ) + err_hist = optimizer_info.err_history + H_hist = optimizer_info.state_history # print("Finished inner loop in %d iters" % len(H_hist)) Hgt_1_2 = Hgt_1_2.reshape(-1, 9) - H8_1_2 = theseus_layer.objective.get_optim_var("H8_1_2").tensor.reshape( - -1, 8 + H8_1_2_tensor = theseus_layer.objective.get_optim_var( + "H8_1_2" + ).tensor.reshape(-1, 8) + H_1_2 = torch.cat( + [H8_1_2_tensor, H8_1_2_tensor.new_ones(H8_1_2_tensor.shape[0], 1)], + dim=-1, ) - H_1_2 = torch.cat([H8_1_2, H8_1_2.new_ones(H8_1_2.shape[0], 1)], dim=-1) # Loss is on four corner error. fc_dist = four_corner_dist( H_1_2.reshape(-1, 3, 3), Hgt_1_2.reshape(-1, 3, 3), imgH, imgW ) outer_loss = fc_dist.mean() + + start_event.record() + torch.cuda.reset_peak_memory_stats() outer_loss.backward() + end_event.record() + torch.cuda.synchronize() + backward_time = start_event.elapsed_time(end_event) + backward_mem = torch.cuda.max_memory_allocated() / 1024 / 1024 + + backward_times.append(backward_time) + backward_mems.append(backward_mem) + outer_optim.step() - print( + logger.info( "Epoch %d, iteration %d, outer_loss: %.3f" % (epoch, itr, outer_loss.item()) ) @@ -407,9 +464,43 @@ def run(): itr += 1 + logger.info( + "---------------------------------------------------------------" + "---------------------------" + ) + logger.info(f"Forward pass took {sum(forward_times)} ms/epoch.") + logger.info(f"Forward pass took {sum(forward_mems)/len(forward_mems)} MBs.") + logger.info(f"Backward pass took {sum(backward_times)} ms/epoch.") + logger.info(f"Backward pass took {sum(backward_mems)/len(backward_mems)} MBs.") + logger.info( + "---------------------------------------------------------------" + "---------------------------" + ) -def main(): - run() + +@hydra.main(config_path="./configs/", config_name="homography_estimation") +def main(cfg): + autograd_modes = { + "dense": AutogradMode.DENSE, + "loop_batch": AutogradMode.LOOP_BATCH, + "vmap": AutogradMode.VMAP, + } + + num_epochs: int = cfg.outer_optim.num_epochs + batch_size: int = cfg.outer_optim.batch_size + outer_lr: float = cfg.outer_optim.lr + max_iterations: int = cfg.inner_optim.max_iters + step_size: float = cfg.inner_optim.step_size + autograd_mode = autograd_modes[cfg.autograd_mode] + + run( + batch_size=batch_size, + outer_lr=outer_lr, + num_epochs=num_epochs, + max_iterations=max_iterations, + step_size=step_size, + autograd_mode=autograd_mode, + ) if __name__ == "__main__": diff --git a/theseus/__init__.py b/theseus/__init__.py index 629292692..51ad5f164 100644 --- a/theseus/__init__.py +++ b/theseus/__init__.py @@ -81,6 +81,7 @@ NonlinearLeastSquares, NonlinearOptimizerParams, NonlinearOptimizerStatus, + NonlinearOptimizerInfo, BackwardMode, ) from .theseus_layer import TheseusLayer diff --git a/theseus/core/cost_function.py b/theseus/core/cost_function.py index 2899193a1..2db9408e8 100644 --- a/theseus/core/cost_function.py +++ b/theseus/core/cost_function.py @@ -249,6 +249,9 @@ def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: ) jacobians_raw_loop.append(jacobians_n) + # torch autograd returns shape (batch_size, dim, batch_size, var_dim), which + # includes derivatives of batches against each other. + # this indexing recovers only the derivatives wrt the same batch jacobians_full = tuple( torch.cat([jac[k][:, :, 0, :] for jac in jacobians_raw_loop], dim=0) for k in range(len(optim_vars)) @@ -261,9 +264,6 @@ def jacobians(self) -> Tuple[List[torch.Tensor], torch.Tensor]: aux_idx = torch.arange(err.shape[0]) # batch_size jacobians_full = tuple(jac[aux_idx, :, aux_idx, :] for jac in jacobians_raw) - # torch autograd returns shape (batch_size, dim, batch_size, var_dim), which - # includes derivatives of batches against each other. - # this indexing recovers only the derivatives wrt the same batch jacobians = list( v.project(jac, is_sparse=True) for v, jac in zip(optim_vars, jacobians_full) ) diff --git a/theseus/optimizer/nonlinear/__init__.py b/theseus/optimizer/nonlinear/__init__.py index 236c69c36..5eb687974 100644 --- a/theseus/optimizer/nonlinear/__init__.py +++ b/theseus/optimizer/nonlinear/__init__.py @@ -11,4 +11,5 @@ NonlinearOptimizer, NonlinearOptimizerParams, NonlinearOptimizerStatus, + NonlinearOptimizerInfo, ) From 1757a981d6a2074b0db72b760224a1163a5c8822 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Wed, 21 Sep 2022 16:33:30 -0400 Subject: [PATCH 30/38] Changed unit tests so that the batch sizes to tests are defined in a central import (#298) * Changed unit tests to use [1, 10] batch size instead of [1, 20, 100]. * Changed remaining tests to use BATCH_SIZES_TO_TEST. --- theseus/core/tests/common.py | 3 +++ theseus/core/tests/test_cost_weight.py | 9 ++++--- theseus/core/tests/test_robust_cost.py | 7 ++--- theseus/core/tests/test_vectorizer.py | 3 ++- .../collision/tests/test_collision_factor.py | 9 ++++--- .../collision/tests/test_eff_obj_contact.py | 5 ++-- .../tests/test_signed_distance_field.py | 11 ++++---- .../measurements/tests/test_between.py | 7 ++--- .../tests/test_moving_frame_between.py | 3 ++- .../misc/tests/test_variable_difference.py | 5 ++-- .../tests/test_double_integrator.py | 11 +++++--- .../tests/test_quasi_static_pushing_planar.py | 27 +++++++++---------- theseus/geometry/tests/common.py | 1 + theseus/geometry/tests/test_point_types.py | 17 ++++++------ theseus/geometry/tests/test_se2.py | 23 ++++++++-------- theseus/geometry/tests/test_se3.py | 19 ++++++------- theseus/geometry/tests/test_so2.py | 21 ++++++++------- theseus/geometry/tests/test_so3.py | 23 ++++++++-------- theseus/geometry/tests/test_vector.py | 7 ++--- theseus/tests/test_dlm_perturbation.py | 3 ++- 20 files changed, 118 insertions(+), 96 deletions(-) diff --git a/theseus/core/tests/common.py b/theseus/core/tests/common.py index 2cfd579e1..820253d76 100644 --- a/theseus/core/tests/common.py +++ b/theseus/core/tests/common.py @@ -10,6 +10,9 @@ import theseus as th +BATCH_SIZES_TO_TEST = (1, 10) + + class MockVar(th.Manifold): def __init__(self, length, tensor=None, name=None): super().__init__(length, tensor=tensor, name=name) diff --git a/theseus/core/tests/test_cost_weight.py b/theseus/core/tests/test_cost_weight.py index bd300f502..9d2fe48e2 100644 --- a/theseus/core/tests/test_cost_weight.py +++ b/theseus/core/tests/test_cost_weight.py @@ -13,6 +13,7 @@ from .common import ( check_another_theseus_function_is_copy, check_another_theseus_tensor_is_copy, + BATCH_SIZES_TO_TEST, ) @@ -33,8 +34,8 @@ def test_copy_diagonal_cost_weight(): def test_scale_cost_weight(): - for dim in [1, 2, 10]: - for batch_size in [1, 2, 10]: + for dim in BATCH_SIZES_TO_TEST: + for batch_size in BATCH_SIZES_TO_TEST: v1 = th.Vector(tensor=torch.ones(batch_size, dim)) z = th.Vector(tensor=torch.zeros(batch_size, dim)) scale = torch.randn(1).item() @@ -69,8 +70,8 @@ def _check(cw): def test_diagonal_cost_weight(): - for dim in [1, 2, 10]: - for batch_size in [1, 2, 10]: + for dim in BATCH_SIZES_TO_TEST: + for batch_size in BATCH_SIZES_TO_TEST: v1 = th.Vector(tensor=torch.ones(batch_size, dim)) z = th.Vector(tensor=torch.zeros(batch_size, dim)) diagonal = torch.randn(dim) diff --git a/theseus/core/tests/test_robust_cost.py b/theseus/core/tests/test_robust_cost.py index ab0781715..f1441e6a0 100644 --- a/theseus/core/tests/test_robust_cost.py +++ b/theseus/core/tests/test_robust_cost.py @@ -6,6 +6,7 @@ import torch import theseus as th +from theseus.core.tests.common import BATCH_SIZES_TO_TEST def _new_robust_cf(batch_size, loss_cls, generator) -> th.RobustCostFunction: @@ -25,7 +26,7 @@ def test_robust_cost_weighted_error(): generator = torch.Generator() generator.manual_seed(0) for _ in range(10): - for batch_size in [1, 2, 10]: + for batch_size in BATCH_SIZES_TO_TEST: for loss_cls in [th.WelschLoss, th.HuberLoss]: robust_cf = _new_robust_cf(batch_size, loss_cls, generator) cf = robust_cf.cost_function @@ -44,7 +45,7 @@ def test_robust_cost_grad_form(): generator = torch.Generator() generator.manual_seed(0) for _ in range(10): - for batch_size in [1, 2, 10]: + for batch_size in BATCH_SIZES_TO_TEST: for loss_cls in [th.WelschLoss, th.HuberLoss]: robust_cf = _new_robust_cf(batch_size, loss_cls, generator) cf = robust_cf.cost_function @@ -66,7 +67,7 @@ def test_robust_cost_jacobians(): generator.manual_seed(0) for _ in range(10): - for batch_size in [1, 2, 10]: + for batch_size in BATCH_SIZES_TO_TEST: for loss_cls in [th.WelschLoss, th.HuberLoss]: robust_cf = _new_robust_cf(batch_size, loss_cls, generator) v1, v2 = robust_cf.cost_function.var, robust_cf.cost_function.target diff --git a/theseus/core/tests/test_vectorizer.py b/theseus/core/tests/test_vectorizer.py index 33ed1f4f5..39290e258 100644 --- a/theseus/core/tests/test_vectorizer.py +++ b/theseus/core/tests/test_vectorizer.py @@ -8,6 +8,7 @@ import torch import theseus as th +from theseus.core.tests.common import BATCH_SIZES_TO_TEST from theseus.core.vectorizer import _CostFunctionWrapper @@ -207,7 +208,7 @@ def test_vectorized_retract(): variables = [] deltas = [] batch_size = rng.choice(range(1, 11)) - n_vars = rng.choice([1, 10, 100]) + n_vars = rng.choice(BATCH_SIZES_TO_TEST) for _ in range(n_vars): var_type: th.LieGroup = rng.choice( [th.Vector, th.SE2, th.SE3, th.SO2, th.SO3] diff --git a/theseus/embodied/collision/tests/test_collision_factor.py b/theseus/embodied/collision/tests/test_collision_factor.py index bcc573d80..78ea95d81 100644 --- a/theseus/embodied/collision/tests/test_collision_factor.py +++ b/theseus/embodied/collision/tests/test_collision_factor.py @@ -11,6 +11,7 @@ check_another_theseus_function_is_copy, check_another_theseus_tensor_is_copy, check_another_torch_tensor_is_copy, + BATCH_SIZES_TO_TEST, ) from theseus.utils import numeric_jacobian from .utils import random_scalar, random_origin, random_sdf_data @@ -18,9 +19,9 @@ def test_collision2d_error_shapes(): cost_weight = th.ScaleCostWeight(1.0) - for batch_size in [1, 10, 100]: - for field_widht in [1, 10, 100]: - for field_height in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: + for field_widht in BATCH_SIZES_TO_TEST: + for field_height in BATCH_SIZES_TO_TEST: pose = th.Point2(tensor=torch.randn(batch_size, 2).double()) origin = random_origin(batch_size) sdf_data = random_sdf_data(batch_size, field_widht, field_height) @@ -81,7 +82,7 @@ def test_collision2d_jacobians(pose_cls): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: cost_weight = th.ScaleCostWeight(torch.ones(1).squeeze().double()) pose = pose_cls.randn(batch_size, generator=rng, dtype=torch.float64) origin = th.Point2(torch.ones(batch_size, 2).double()) diff --git a/theseus/embodied/collision/tests/test_eff_obj_contact.py b/theseus/embodied/collision/tests/test_eff_obj_contact.py index b3b9f4b9b..a62d055f7 100644 --- a/theseus/embodied/collision/tests/test_eff_obj_contact.py +++ b/theseus/embodied/collision/tests/test_eff_obj_contact.py @@ -8,6 +8,7 @@ import torch import theseus as th +from theseus.core.tests.common import BATCH_SIZES_TO_TEST from theseus.embodied.collision.tests.utils import ( random_origin, random_sdf_data, @@ -20,7 +21,7 @@ def test_eff_obj_interesect_jacobians(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: obj = create_random_se2(batch_size, rng) eff = create_random_se2(batch_size, rng) origin = random_origin(batch_size) @@ -160,7 +161,7 @@ def test_eff_obj_variable_type(): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: obj = create_random_se2(batch_size, rng) eff = create_random_se2(batch_size, rng) origin = random_origin(batch_size) diff --git a/theseus/embodied/collision/tests/test_signed_distance_field.py b/theseus/embodied/collision/tests/test_signed_distance_field.py index ceb7ab059..714d04d93 100644 --- a/theseus/embodied/collision/tests/test_signed_distance_field.py +++ b/theseus/embodied/collision/tests/test_signed_distance_field.py @@ -7,6 +7,7 @@ import torch import theseus as th +from theseus.core.tests.common import BATCH_SIZES_TO_TEST from theseus.utils import numeric_jacobian from .utils import random_sdf @@ -14,10 +15,10 @@ def test_sdf_2d_shapes(): generator = torch.Generator() generator.manual_seed(0) - for batch_size in [1, 10, 100]: - for field_width in [1, 10, 100]: - for field_height in [1, 10, 100]: - for num_points in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: + for field_width in BATCH_SIZES_TO_TEST: + for field_height in BATCH_SIZES_TO_TEST: + for num_points in BATCH_SIZES_TO_TEST: points = th.Variable(tensor=torch.randn(batch_size, 2, num_points)) sdf = random_sdf(batch_size, field_width, field_height) dist, jac = sdf.signed_distance(points) @@ -85,7 +86,7 @@ def test_sdf_2d_creation(): def test_signed_distance_2d_jacobian(): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: sdf = random_sdf(batch_size, 10, 10) for num_points in [1, 10]: points = torch.randn(batch_size, 2, num_points).double() diff --git a/theseus/embodied/measurements/tests/test_between.py b/theseus/embodied/measurements/tests/test_between.py index 2cb304690..dd1658d5b 100644 --- a/theseus/embodied/measurements/tests/test_between.py +++ b/theseus/embodied/measurements/tests/test_between.py @@ -10,6 +10,7 @@ from theseus.core.tests.common import ( check_another_theseus_function_is_copy, check_another_theseus_tensor_is_copy, + BATCH_SIZES_TO_TEST, ) from theseus.utils import numeric_jacobian @@ -18,7 +19,7 @@ def evaluate_numerical_jacobian_between(Group, tol): rng = torch.Generator() rng.manual_seed(0) cost_weight = th.ScaleCostWeight(1) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: v0 = Group.rand(batch_size, dtype=torch.float64, generator=rng) v1 = Group.rand(batch_size, dtype=torch.float64, generator=rng) measurement = Group.rand(batch_size, dtype=torch.float64, generator=rng) @@ -69,7 +70,7 @@ def test_error_between_point2(): rng = torch.Generator() rng.manual_seed(0) cost_weight = th.ScaleCostWeight(1) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: p1 = th.Point2(torch.randn(batch_size, 2, generator=rng)) p2 = th.Point2(torch.randn(batch_size, 2, generator=rng)) measurement = th.Point2(torch.randn(batch_size, 2, generator=rng)) @@ -130,7 +131,7 @@ def test_error_between_se2(): def test_jacobian_between_se3(): - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: aux_id = torch.arange(batch_size) se3_1 = th.SE3.rand(batch_size, dtype=torch.float64) se3_2 = th.SE3.rand(batch_size, dtype=torch.float64) diff --git a/theseus/embodied/measurements/tests/test_moving_frame_between.py b/theseus/embodied/measurements/tests/test_moving_frame_between.py index f2de9d0ee..ea3b11929 100644 --- a/theseus/embodied/measurements/tests/test_moving_frame_between.py +++ b/theseus/embodied/measurements/tests/test_moving_frame_between.py @@ -12,6 +12,7 @@ from theseus.core.tests.common import ( check_another_theseus_function_is_copy, check_another_theseus_tensor_is_copy, + BATCH_SIZES_TO_TEST, ) from theseus.geometry.tests.test_se2 import create_random_se2 from theseus.utils import numeric_jacobian @@ -47,7 +48,7 @@ def test_jacobian_moving_frame_between(): rng = torch.Generator() rng.manual_seed(0) cost_weight = thcore.ScaleCostWeight(1) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: f1 = create_random_se2(batch_size, rng) f2 = create_random_se2(batch_size, rng) p1 = create_random_se2(batch_size, rng) diff --git a/theseus/embodied/misc/tests/test_variable_difference.py b/theseus/embodied/misc/tests/test_variable_difference.py index 5b14f823f..630efed36 100644 --- a/theseus/embodied/misc/tests/test_variable_difference.py +++ b/theseus/embodied/misc/tests/test_variable_difference.py @@ -10,6 +10,7 @@ from theseus.core.tests.common import ( check_another_theseus_function_is_copy, check_another_theseus_tensor_is_copy, + BATCH_SIZES_TO_TEST, ) from theseus.utils import numeric_jacobian @@ -18,7 +19,7 @@ def evaluate_numerical_jacobian_local_cost_fn(Group, tol): rng = torch.Generator() rng.manual_seed(1) cost_weight = th.ScaleCostWeight(1) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: v0 = Group.rand(batch_size, dtype=torch.float64, generator=rng) target = Group.rand(batch_size, dtype=torch.float64, generator=rng) cost_function = th.Difference(v0, target, cost_weight) @@ -63,7 +64,7 @@ def test_error_local_cost_fn_point2(): rng = torch.Generator() rng.manual_seed(0) cost_weight = th.ScaleCostWeight(1) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: p0 = th.Point2(torch.randn(batch_size, 2, generator=rng)) target = th.Point2(torch.randn(batch_size, 2, generator=rng)) cost_function = th.Difference(p0, target, cost_weight) diff --git a/theseus/embodied/motionmodel/tests/test_double_integrator.py b/theseus/embodied/motionmodel/tests/test_double_integrator.py index f641e37ed..76af0f5fa 100644 --- a/theseus/embodied/motionmodel/tests/test_double_integrator.py +++ b/theseus/embodied/motionmodel/tests/test_double_integrator.py @@ -11,13 +11,16 @@ import theseus as th from theseus.core import Variable -from theseus.core.tests.common import check_another_theseus_function_is_copy +from theseus.core.tests.common import ( + check_another_theseus_function_is_copy, + BATCH_SIZES_TO_TEST, +) from theseus.utils import numeric_jacobian def test_gp_motion_model_cost_weight_weights(): for dof in range(1, 10): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: aux = torch.randn(batch_size, dof, dof).double() q_inv = aux.transpose(-2, -1).bmm(aux) dt = torch.rand(1).double() @@ -64,7 +67,7 @@ def test_gp_motion_model_cost_weight_copy(): def test_gp_motion_model_variable_type(): for dof in range(1, 10): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: aux = torch.randn(batch_size, dof, dof).double() q_inv = aux.transpose(-2, -1).bmm(aux) dt = torch.rand(1).double() @@ -91,7 +94,7 @@ def test_gp_motion_model_variable_type(): def test_gp_motion_model_cost_function_error_vector_vars(): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: for dof in range(1, 10): vars = [ th.Vector(tensor=torch.randn(batch_size, dof).double()) diff --git a/theseus/embodied/motionmodel/tests/test_quasi_static_pushing_planar.py b/theseus/embodied/motionmodel/tests/test_quasi_static_pushing_planar.py index a0cae820b..3e1e9b0af 100644 --- a/theseus/embodied/motionmodel/tests/test_quasi_static_pushing_planar.py +++ b/theseus/embodied/motionmodel/tests/test_quasi_static_pushing_planar.py @@ -6,9 +6,8 @@ import numpy as np import torch -import theseus.core as thcore -import theseus.embodied as thembod -import theseus.geometry as thgeom +import theseus as th +from theseus.core.tests.common import BATCH_SIZES_TO_TEST from theseus.geometry.tests.test_se2 import create_random_se2 from theseus.utils import numeric_jacobian @@ -17,7 +16,7 @@ def test_error_quasi_static_pushing_planar_se2(): # c_square is c**2, c = max_torque / max_force is a hyper param dependent on object c_square = torch.Tensor([1.0]) - cost_weight = thcore.ScaleCostWeight(1) + cost_weight = th.ScaleCostWeight(1) inputs = { "obj1": torch.DoubleTensor( @@ -71,12 +70,12 @@ def test_error_quasi_static_pushing_planar_se2(): } n_tests = outputs["error"].shape[0] for i in range(0, n_tests): - obj1 = thgeom.SE2(x_y_theta=(inputs["obj1"][i, :]).unsqueeze(0)) - obj2 = thgeom.SE2(x_y_theta=(inputs["obj2"][i, :]).unsqueeze(0)) - eff1 = thgeom.SE2(x_y_theta=(inputs["eff1"][i, :]).unsqueeze(0)) - eff2 = thgeom.SE2(x_y_theta=(inputs["eff2"][i, :]).unsqueeze(0)) + obj1 = th.SE2(x_y_theta=(inputs["obj1"][i, :]).unsqueeze(0)) + obj2 = th.SE2(x_y_theta=(inputs["obj2"][i, :]).unsqueeze(0)) + eff1 = th.SE2(x_y_theta=(inputs["eff1"][i, :]).unsqueeze(0)) + eff2 = th.SE2(x_y_theta=(inputs["eff2"][i, :]).unsqueeze(0)) - cost_fn = thembod.QuasiStaticPushingPlanar( + cost_fn = th.eb.QuasiStaticPushingPlanar( obj1, obj2, eff1, eff2, c_square, cost_weight ) @@ -95,24 +94,24 @@ def test_quasi_static_pushing_planar_jacobians(): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a bunch of times - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: obj1 = create_random_se2(batch_size, rng) obj2 = create_random_se2(batch_size, rng) eff1 = create_random_se2(batch_size, rng) eff2 = create_random_se2(batch_size, rng) c_square = torch.Tensor([1.0]) - cost_weight = thcore.ScaleCostWeight(1) + cost_weight = th.ScaleCostWeight(1) - cost_fn = thembod.QuasiStaticPushingPlanar( + cost_fn = th.eb.QuasiStaticPushingPlanar( obj1, obj2, eff1, eff2, c_square, cost_weight ) jacobians, _ = cost_fn.jacobians() def new_error_fn(groups): - new_cost_fn = thembod.QuasiStaticPushingPlanar( + new_cost_fn = th.eb.QuasiStaticPushingPlanar( groups[0], groups[1], groups[2], groups[3], c_square, cost_weight ) - return thgeom.Vector(tensor=new_cost_fn.error()) + return th.Vector(tensor=new_cost_fn.error()) expected_jacs = numeric_jacobian( new_error_fn, [obj1, obj2, eff1, eff2], delta_mag=1e-6 diff --git a/theseus/geometry/tests/common.py b/theseus/geometry/tests/common.py index 2559f0af9..0ca29926a 100644 --- a/theseus/geometry/tests/common.py +++ b/theseus/geometry/tests/common.py @@ -5,6 +5,7 @@ import torch +from theseus.core.tests.common import BATCH_SIZES_TO_TEST # noqa: F401 from theseus.constants import TEST_EPS from theseus.utils import numeric_jacobian from theseus.geometry.lie_group_check import set_lie_group_check_enabled diff --git a/theseus/geometry/tests/test_point_types.py b/theseus/geometry/tests/test_point_types.py index 2c7be9529..fded6b7cd 100644 --- a/theseus/geometry/tests/test_point_types.py +++ b/theseus/geometry/tests/test_point_types.py @@ -13,12 +13,13 @@ check_jacobian_for_local, check_projection_for_exp_map, check_projection_for_log_map, + BATCH_SIZES_TO_TEST, ) def test_xy_point2(): for _ in range(100): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: point = th.Point2(tensor=torch.randn(batch_size, 2)) assert point.x().allclose(point.tensor[:, 0]) assert point.y().allclose(point.tensor[:, 1]) @@ -26,7 +27,7 @@ def test_xy_point2(): def test_xyz_point3(): for _ in range(100): - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: point = th.Point3(tensor=torch.randn(batch_size, 3)) assert point.x().allclose(point.tensor[:, 0]) assert point.y().allclose(point.tensor[:, 1]) @@ -70,7 +71,7 @@ def test_exp_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: tangent_vector = torch.rand(batch_size, 2, generator=rng).double() - 0.5 ret = th.Point2.exp_map(tangent_vector) @@ -79,7 +80,7 @@ def test_exp_map(): tangent_vector, Group=th.Point2, is_projected=False ) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: tangent_vector = torch.rand(batch_size, 3, generator=rng).double() - 0.5 ret = th.Point3.exp_map(tangent_vector) @@ -93,7 +94,7 @@ def test_log_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group = th.Point2.rand(batch_size) ret = group.log_map() @@ -102,7 +103,7 @@ def test_log_map(): tangent_vector=ret, Group=th.Point2, is_projected=False ) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group = th.Point3.rand(batch_size) ret = group.log_map() @@ -116,13 +117,13 @@ def test_local_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group0 = th.Point2.rand(batch_size) group1 = th.Point2.rand(batch_size) check_jacobian_for_local(group0, group1, Group=th.Point2, is_projected=False) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group0 = th.Point3.rand(batch_size) group1 = th.Point3.rand(batch_size) diff --git a/theseus/geometry/tests/test_se2.py b/theseus/geometry/tests/test_se2.py index af1b6bee7..230a03fd6 100644 --- a/theseus/geometry/tests/test_se2.py +++ b/theseus/geometry/tests/test_se2.py @@ -23,6 +23,7 @@ check_projection_for_exp_map, check_projection_for_inverse, check_projection_for_rotate_and_transform, + BATCH_SIZES_TO_TEST, ) @@ -40,7 +41,7 @@ def test_exp_map(dtype, enable_functorch): rng.manual_seed(0) ATOL = 2e-4 if dtype == torch.float32 else 1e-6 - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)) u = torch.randn(batch_size, 2, dtype=dtype, generator=rng) tangent_vector = torch.cat([u, theta.unsqueeze(1)], dim=1) @@ -60,7 +61,7 @@ def test_exp_map(dtype, enable_functorch): def test_log_map(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)) u = torch.randn(batch_size, 2, dtype=dtype, generator=rng) tangent_vector = torch.cat([u, theta.unsqueeze(1)], dim=1) @@ -75,7 +76,7 @@ def test_log_map(dtype, enable_functorch): def test_compose(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se2_1 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) se2_2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) check_compose(se2_1, se2_2, enable_functorch=enable_functorch) @@ -86,7 +87,7 @@ def test_compose(dtype, enable_functorch): def test_inverse(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) check_inverse(se2, enable_functorch=enable_functorch) @@ -96,7 +97,7 @@ def test_inverse(dtype, enable_functorch): def test_adjoint(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) tangent = torch.randn(batch_size, 3, dtype=dtype) check_adjoint(se2, tangent, enable_functorch=enable_functorch) @@ -113,8 +114,8 @@ def test_transform_from_and_to(dtype): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size_se2 in [1, 20, 100]: - for batch_size_pnt in [1, 20, 100]: + for batch_size_se2 in BATCH_SIZES_TO_TEST: + for batch_size_pnt in BATCH_SIZES_TO_TEST: if ( batch_size_se2 != 1 and batch_size_pnt != 1 @@ -182,7 +183,7 @@ def test_transform_from_and_to(dtype): def test_xy_jacobian(dtype): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) jacobian = [] se2.xy(jacobians=jacobian) @@ -196,7 +197,7 @@ def test_xy_jacobian(dtype): def test_theta_jacobian(dtype): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se2 = th.SE2.rand(batch_size, generator=rng, dtype=dtype) jacobian = [] se2.theta(jacobians=jacobian) @@ -210,7 +211,7 @@ def test_projection(): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: # Test SE2.transform_to check_projection_for_rotate_and_transform( th.SE2, th.Point2, th.SE2.transform_to, batch_size, rng @@ -228,7 +229,7 @@ def test_projection(): check_projection_for_inverse(th.SE2, batch_size, rng) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) def test_normalization(batch_size, dtype): check_normalize(th.SE2, batch_size, dtype) diff --git a/theseus/geometry/tests/test_se3.py b/theseus/geometry/tests/test_se3.py index e662346ac..2cfbd889a 100644 --- a/theseus/geometry/tests/test_se3.py +++ b/theseus/geometry/tests/test_se3.py @@ -24,6 +24,7 @@ check_projection_for_log_map, check_projection_for_rotate_and_transform, check_so3_se3_normalize, + BATCH_SIZES_TO_TEST, ) @@ -52,7 +53,7 @@ def _create_tangent_vector(batch_size, ang_factor, rng, dtype): return tangent_vector -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] @@ -103,7 +104,7 @@ def test_batch_size_3_exp_map(dtype, ang_factor, enable_functorch): torch.allclose(jac[0][3:], jac2[0], atol=ATOL) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-7, np.pi - 1e-10] @@ -166,7 +167,7 @@ def test_batch_size_3_log_map(dtype, ang_factor, enable_functorch): def test_compose(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se3_1 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) se3_2 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) check_compose(se3_1, se3_2, enable_functorch) @@ -177,12 +178,12 @@ def test_compose(dtype, enable_functorch): def test_inverse(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: se3 = th.SE3.rand(batch_size, generator=rng, dtype=dtype) check_inverse(se3, enable_functorch) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] @@ -203,7 +204,7 @@ def test_x_y_z_quaternion(batch_size, dtype, ang_factor, enable_functorch): check_SE3_to_x_y_z_quaternion(se3, atol=ATOL, enable_functorch=enable_functorch) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize("enable_functorch", [True, False]) def test_adjoint(batch_size, dtype, enable_functorch): @@ -284,7 +285,7 @@ def test_projection(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size in [1, 20]: + for batch_size in BATCH_SIZES_TO_TEST: # Test SE3.transform_to check_projection_for_rotate_and_transform( th.SE3, th.Point3, th.SE3.transform_to, batch_size, rng, dtype=dtype @@ -312,7 +313,7 @@ def test_local_map(dtype): rng.manual_seed(0) ATOL = 3e-5 if dtype == torch.float32 else 1e-7 - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group0 = th.SE3.rand(batch_size, dtype=dtype, generator=rng) group1 = th.SE3.rand(batch_size, dtype=dtype, generator=rng) check_jacobian_for_local( @@ -320,7 +321,7 @@ def test_local_map(dtype): ) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) def test_normalization(batch_size, dtype): check_so3_se3_normalize(th.SE3, batch_size, dtype) diff --git a/theseus/geometry/tests/test_so2.py b/theseus/geometry/tests/test_so2.py index 5b6fc363b..a9bdb2ce3 100644 --- a/theseus/geometry/tests/test_so2.py +++ b/theseus/geometry/tests/test_so2.py @@ -25,11 +25,12 @@ check_projection_for_inverse, check_projection_for_log_map, check_projection_for_rotate_and_transform, + BATCH_SIZES_TO_TEST, ) def test_exp_map(): - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)).view(-1, 1) check_exp_map(theta, th.SO2, EPS, enable_functorch=False) check_projection_for_exp_map(theta, th.SO2, enable_functorch=False) @@ -38,7 +39,7 @@ def test_exp_map(): def test_log_map(): - for batch_size in [1, 2, 100]: + for batch_size in BATCH_SIZES_TO_TEST: theta = torch.from_numpy(np.linspace(-np.pi, np.pi, batch_size)).view(-1, 1) check_log_map(theta, th.SO2, EPS, enable_functorch=False) check_projection_for_log_map(theta, th.SO2, enable_functorch=False) @@ -49,7 +50,7 @@ def test_log_map(): def test_compose(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: so2_1 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) so2_2 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) check_compose(so2_1, so2_2, enable_functorch=False) @@ -59,7 +60,7 @@ def test_compose(): def test_inverse(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: so2 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) check_inverse(so2, enable_functorch=False) check_inverse(so2, enable_functorch=True) @@ -69,8 +70,8 @@ def test_rotate_and_unrotate(): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size_so2 in [1, 20, 100]: - for batch_size_pnt in [1, 20, 100]: + for batch_size_so2 in BATCH_SIZES_TO_TEST: + for batch_size_pnt in BATCH_SIZES_TO_TEST: if ( batch_size_so2 != 1 and batch_size_pnt != 1 @@ -121,7 +122,7 @@ def test_rotate_and_unrotate(): def test_adjoint(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: so2 = th.SO2.rand(batch_size, generator=rng, dtype=torch.float64) tangent = torch.randn(batch_size, 1).double() check_adjoint(so2, tangent, enable_functorch=False) @@ -139,7 +140,7 @@ def test_projection(): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: # Test SO2.rotate check_projection_for_rotate_and_transform( th.SO2, th.Point2, th.SO2.rotate, batch_size, rng @@ -161,14 +162,14 @@ def test_local_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group0 = th.SO2.rand(batch_size) group1 = th.SO2.rand(batch_size) check_jacobian_for_local(group0, group1, Group=th.SO2, is_projected=True) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) def test_normalization(batch_size, dtype): check_normalize(th.SO2, batch_size, dtype) diff --git a/theseus/geometry/tests/test_so3.py b/theseus/geometry/tests/test_so3.py index a0ea5e408..9148cbb55 100644 --- a/theseus/geometry/tests/test_so3.py +++ b/theseus/geometry/tests/test_so3.py @@ -25,6 +25,7 @@ check_projection_for_log_map, check_projection_for_rotate_and_transform, check_so3_se3_normalize, + BATCH_SIZES_TO_TEST, ) @@ -50,7 +51,7 @@ def _create_tangent_vector(batch_size, ang_factor, rng, dtype): return tangent_vector -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-7, np.pi - 1e-11] @@ -73,7 +74,7 @@ def test_exp_map(batch_size, dtype, ang_factor, enable_functorch): ) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] @@ -104,7 +105,7 @@ def test_log_map(batch_size, dtype, ang_factor, enable_functorch): ) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize("enable_functorch", [True, False]) def test_inverse(batch_size, dtype, enable_functorch): @@ -116,7 +117,7 @@ def test_inverse(batch_size, dtype, enable_functorch): check_inverse(group, enable_functorch=enable_functorch) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize( "ang_factor", [None, 1e-5, 3e-3, 2 * np.pi - 1e-11, np.pi - 1e-11] @@ -137,7 +138,7 @@ def test_quaternion(batch_size, dtype, ang_factor, enable_functorch): check_SO3_to_quaternion(so3, atol=ATOL, enable_functorch=enable_functorch) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) @pytest.mark.parametrize("enable_functorch", [True, False]) def test_adjoint(batch_size, dtype, enable_functorch): @@ -148,7 +149,7 @@ def test_adjoint(batch_size, dtype, enable_functorch): check_adjoint(so3, tangent, enable_functorch) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) def test_compose(batch_size, dtype): rng = torch.Generator() @@ -163,8 +164,8 @@ def test_rotate_and_unrotate(dtype): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size_group in [1, 20, 100]: - for batch_size_pnt in [1, 20, 100]: + for batch_size_group in BATCH_SIZES_TO_TEST: + for batch_size_pnt in BATCH_SIZES_TO_TEST: if ( batch_size_group != 1 and batch_size_pnt != 1 @@ -228,7 +229,7 @@ def test_projection(dtype, enable_functorch): rng = torch.Generator() rng.manual_seed(0) for _ in range(10): # repeat a few times - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: # Test SO3.rotate check_projection_for_rotate_and_transform( th.SO3, th.Point3, th.SO3.rotate, batch_size, rng, dtype=dtype @@ -256,7 +257,7 @@ def test_local_map(dtype): rng.manual_seed(0) ATOL = 3e-5 if dtype == torch.float32 else 1e-7 - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: group0 = th.SO3.rand(batch_size, dtype=dtype) group1 = th.SO3.rand(batch_size, dtype=dtype) @@ -265,7 +266,7 @@ def test_local_map(dtype): ) -@pytest.mark.parametrize("batch_size", [1, 20, 100]) +@pytest.mark.parametrize("batch_size", BATCH_SIZES_TO_TEST) @pytest.mark.parametrize("dtype", [torch.float32, torch.float64]) def test_normalization(batch_size, dtype): check_so3_se3_normalize(th.SO3, batch_size, dtype) diff --git a/theseus/geometry/tests/test_vector.py b/theseus/geometry/tests/test_vector.py index 29552039a..e10a09b6b 100644 --- a/theseus/geometry/tests/test_vector.py +++ b/theseus/geometry/tests/test_vector.py @@ -15,6 +15,7 @@ check_jacobian_for_local, check_projection_for_exp_map, check_projection_for_log_map, + BATCH_SIZES_TO_TEST, ) torch.manual_seed(0) @@ -191,7 +192,7 @@ def test_exp_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: dim = torch.randint(1, 10, size=[1], generator=rng)[0] tangent_vector = torch.rand(batch_size, dim, generator=rng).double() - 0.5 ret = th.Vector.exp_map(tangent_vector) @@ -206,7 +207,7 @@ def test_log_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: dim = torch.randint(1, 10, size=[1], generator=rng)[0] group = th.Vector.rand(batch_size, dim, generator=rng) ret = group.log_map() @@ -221,7 +222,7 @@ def test_local_map(): rng = torch.Generator() rng.manual_seed(0) - for batch_size in [1, 20, 100]: + for batch_size in BATCH_SIZES_TO_TEST: dim = torch.randint(1, 10, size=[1], generator=rng)[0] group0 = th.Vector.rand(batch_size, dim, generator=rng) group1 = th.Vector.rand(batch_size, dim, generator=rng) diff --git a/theseus/tests/test_dlm_perturbation.py b/theseus/tests/test_dlm_perturbation.py index 2c7aac892..f8faf7ac4 100644 --- a/theseus/tests/test_dlm_perturbation.py +++ b/theseus/tests/test_dlm_perturbation.py @@ -7,6 +7,7 @@ import torch import theseus as th +from theseus.core.tests.common import BATCH_SIZES_TO_TEST from theseus.theseus_layer import _DLMPerturbation from theseus.utils import numeric_jacobian @@ -25,7 +26,7 @@ def test_dlm_perturbation_jacobian(): dtype = torch.float64 for _ in range(100): group_cls = rng.choice([th.Vector, th.SE3, th.SE2, th.SO2, th.SO3]) - for batch_size in [1, 10, 100]: + for batch_size in BATCH_SIZES_TO_TEST: epsilon = th.Variable( tensor=torch.randn(batch_size, 1, dtype=dtype, generator=generator) ) From c03177f7ca3c8e30a787cc8b96c79503c04e370d Mon Sep 17 00:00:00 2001 From: Taosha Fan Date: Thu, 22 Sep 2022 08:17:30 -0700 Subject: [PATCH 31/38] remove blank lines in homography estimation --- examples/homography_estimation.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index 90d7187fb..60a8fbf54 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -41,9 +41,8 @@ # Logger logger = logging.getLogger(__name__) -# Download and extract data - +# Download and extract data def prepare_data(): dataset_root = os.path.join(os.getcwd(), "data") chunks = [ From 659c73dd6e112bcd1e58e757444bd8921aee4ff5 Mon Sep 17 00:00:00 2001 From: Luis Pineda <4759586+luisenp@users.noreply.github.com> Date: Thu, 22 Sep 2022 12:56:21 -0700 Subject: [PATCH 32/38] Fixed bug in tactile pose estimation example that was preventing val ratio and seed to be used in dataset. --- examples/configs/tactile_pose_estimation.yaml | 2 +- theseus/utils/examples/tactile_pose_estimation/trainer.py | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/examples/configs/tactile_pose_estimation.yaml b/examples/configs/tactile_pose_estimation.yaml index 3adf84eb6..dc1f47c8a 100644 --- a/examples/configs/tactile_pose_estimation.yaml +++ b/examples/configs/tactile_pose_estimation.yaml @@ -1,4 +1,4 @@ -seed: 0 +seed: 1234567 save_all: true dataset_name: "rectangle-pushing-corners-keypoints" diff --git a/theseus/utils/examples/tactile_pose_estimation/trainer.py b/theseus/utils/examples/tactile_pose_estimation/trainer.py index d560100a1..87611e520 100644 --- a/theseus/utils/examples/tactile_pose_estimation/trainer.py +++ b/theseus/utils/examples/tactile_pose_estimation/trainer.py @@ -64,6 +64,8 @@ def __init__( cfg.max_steps, device, split_episodes=cfg.split_episodes, + val_ratio=cfg.train.val_ratio, + seed=cfg.seed, data_mode="train", ) self.dataset_val = TactilePushingDataset( @@ -75,6 +77,8 @@ def __init__( cfg.max_steps, device, split_episodes=cfg.split_episodes, + val_ratio=cfg.train.val_ratio, + seed=cfg.seed, data_mode="val", ) From edff2273cdf2f5812063cb5f037e86cfa40d079b Mon Sep 17 00:00:00 2001 From: Christopher6488 <49382510+Christopher6488@users.noreply.github.com> Date: Mon, 26 Sep 2022 21:39:30 +0800 Subject: [PATCH 33/38] enhance the efficiency of Objectve.add() (#303) Co-authored-by: lihao33 --- theseus/core/objective.py | 27 +++++++++++++++++++++++---- 1 file changed, 23 insertions(+), 4 deletions(-) diff --git a/theseus/core/objective.py b/theseus/core/objective.py index 639abebfc..0a124d3b8 100644 --- a/theseus/core/objective.py +++ b/theseus/core/objective.py @@ -4,6 +4,7 @@ # LICENSE file in the root directory of this source tree. import warnings +import itertools from collections import OrderedDict from typing import Any, Callable, Dict, Iterable, List, Optional, Sequence, Union @@ -101,6 +102,7 @@ def _add_function_variables( function_vars = function.aux_vars # type: ignore self_var_to_fn_map = self.functions_for_aux_vars # type: ignore self_vars_of_this_type = self.aux_vars # type: ignore + for variable in function_vars: # Check that variables have name and correct dtype if variable.name is None: @@ -195,11 +197,28 @@ def add(self, cost_function: CostFunction): self.cost_functions_for_weights[cost_function.weight].append(cost_function) - if self.optim_vars.keys() & self.aux_vars.keys(): - raise ValueError( - "Objective does not support a variable being both " - "an optimization variable and an auxiliary variable." + optim_vars_names = [ + var.name + for var in itertools.chain( + cost_function.optim_vars, cost_function.weight.optim_vars ) + ] + aux_vars_names = [ + var.name + for var in itertools.chain( + cost_function.aux_vars, cost_function.weight.aux_vars + ) + ] + dual_var_err_msg = ( + "Objective does not support a variable being both " + + "an optimization variable and an auxiliary variable." + ) + for optim_name in optim_vars_names: + if self.has_aux_var(optim_name): + raise ValueError(dual_var_err_msg) + for aux_name in aux_vars_names: + if self.has_optim_var(aux_name): + raise ValueError(dual_var_err_msg) # returns a reference to the cost function with the given name def get_cost_function(self, name: str) -> CostFunction: From 26a616b9cc2b33069bd68ec90ad76afea17ee4dd Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Mon, 26 Sep 2022 17:41:58 -0400 Subject: [PATCH 34/38] Added missing end newlines. (#307) --- evaluations/README.md | 2 +- examples/configs/bundle_adjustment.yaml | 2 +- requirements/dev.txt | 2 +- requirements/docs.txt | 2 +- requirements/main.txt | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/evaluations/README.md b/evaluations/README.md index 1bb919e75..b723874cc 100644 --- a/evaluations/README.md +++ b/evaluations/README.md @@ -25,4 +25,4 @@ Some other relevant files to look at: - `examples/motion_planning_2d.py`: Implements outer loop. * Homography Estimation: - - `examples/homography_estimation.py`: Puts together optimization layer and implements outer loop. \ No newline at end of file + - `examples/homography_estimation.py`: Puts together optimization layer and implements outer loop. diff --git a/examples/configs/bundle_adjustment.yaml b/examples/configs/bundle_adjustment.yaml index 06dd7531b..f228e4abb 100644 --- a/examples/configs/bundle_adjustment.yaml +++ b/examples/configs/bundle_adjustment.yaml @@ -23,4 +23,4 @@ outer_optim: hydra: run: - dir: examples/outputs \ No newline at end of file + dir: examples/outputs diff --git a/requirements/dev.txt b/requirements/dev.txt index 24fe1e3b1..6b194ed69 100644 --- a/requirements/dev.txt +++ b/requirements/dev.txt @@ -10,4 +10,4 @@ numdifftools>=0.9.40 mock>=4.0.3 types-mock>=4.0.8 Sphinx==5.0.2 -sphinx-rtd-theme==1.0.0 \ No newline at end of file +sphinx-rtd-theme==1.0.0 diff --git a/requirements/docs.txt b/requirements/docs.txt index baa4d1877..9ba8e329d 100644 --- a/requirements/docs.txt +++ b/requirements/docs.txt @@ -8,4 +8,4 @@ numdifftools>=0.9.40 pybind11>=2.7.1 mock>=4.0.3 Sphinx==5.0.2 -sphinx-rtd-theme==1.0.0 \ No newline at end of file +sphinx-rtd-theme==1.0.0 diff --git a/requirements/main.txt b/requirements/main.txt index 2d854d5f8..5f483939e 100644 --- a/requirements/main.txt +++ b/requirements/main.txt @@ -4,4 +4,4 @@ scikit-sparse>=0.4.5 # torch>=1.7.1 will do separate install instructions for now (CUDA dependent) pytest>=6.2.1 pybind11>=2.7.1 -functorch>=0.2.1 \ No newline at end of file +functorch>=0.2.1 From a18eec7febd355bd9f25345be1a84561d0feb0b3 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Tue, 27 Sep 2022 14:11:09 -0400 Subject: [PATCH 35/38] Rename BackwardMode.FULL --> UNROLL and simplify backward mode config (#305) * Added code so that backward mode can be resolved from string. * Replaced BackwardMode.FULL for BackwardModel.UNROLL. --- README.md | 2 +- examples/backward_modes.py | 16 ++++----- examples/bundle_adjustment.py | 9 +---- examples/homography_estimation.py | 7 +--- examples/pose_graph/pose_graph_synthetic.py | 14 +------- examples/simple_example.py | 2 +- .../nonlinear/nonlinear_optimizer.py | 34 ++++++++++++++++--- .../nonlinear/tests/test_backwards.py | 4 +-- theseus/tests/test_dlm_perturbation.py | 2 +- theseus/theseus_layer.py | 5 ++- .../tactile_pose_estimation/trainer.py | 2 +- 11 files changed, 51 insertions(+), 46 deletions(-) diff --git a/README.md b/README.md index 73624356a..4b0322677 100644 --- a/README.md +++ b/README.md @@ -141,7 +141,7 @@ outer_optimizer = torch.optim.RMSprop([phi], lr=0.001) for epoch in range(10): solution, info = layer.forward( input_tensors={"x": phi.clone(), "v": torch.ones(1, 1)}, - optimizer_kwargs={"backward_mode": th.BackwardMode.IMPLICIT}) + optimizer_kwargs={"backward_mode": "implicit"}) outer_loss = torch.nn.functional.mse_loss(solution["v"], v_true) outer_loss.backward() outer_optimizer.step() diff --git a/examples/backward_modes.py b/examples/backward_modes.py index 968287553..35a165495 100755 --- a/examples/backward_modes.py +++ b/examples/backward_modes.py @@ -82,7 +82,7 @@ def quad_error_fn(optim_vars, aux_vars): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.FULL, + "backward_mode": "unroll", }, ) @@ -103,7 +103,7 @@ def quad_error_fn(optim_vars, aux_vars): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.IMPLICIT, + "backward_mode": "implicit", }, ) @@ -117,7 +117,7 @@ def quad_error_fn(optim_vars, aux_vars): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.TRUNCATED, + "backward_mode": "truncated", "backward_num_iterations": 5, }, ) @@ -134,7 +134,7 @@ def quad_error_fn(optim_vars, aux_vars): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.DLM, + "backward_mode": "dlm", "dlm_epsilon": 1e-3, }, ) @@ -175,7 +175,7 @@ def fit_x(data_x_np): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.FULL, + "backward_mode": "unroll", }, ) times["fwd"].append(time.time() - start) @@ -191,7 +191,7 @@ def fit_x(data_x_np): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.IMPLICIT, + "backward_mode": "implicit", }, ) start = time.time() @@ -205,7 +205,7 @@ def fit_x(data_x_np): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.TRUNCATED, + "backward_mode": "truncated", "backward_num_iterations": 5, }, ) @@ -220,7 +220,7 @@ def fit_x(data_x_np): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.DLM, + "backward_mode": "dlm", "dlm_epsilon": 1e-3, }, ) diff --git a/examples/bundle_adjustment.py b/examples/bundle_adjustment.py index 08078e923..00f73a385 100644 --- a/examples/bundle_adjustment.py +++ b/examples/bundle_adjustment.py @@ -17,13 +17,6 @@ import theseus as th import theseus.utils.examples as theg -BACKWARD_MODE = { - "implicit": th.BackwardMode.IMPLICIT, - "full": th.BackwardMode.FULL, - "truncated": th.BackwardMode.TRUNCATED, -} - - # Logger log = logging.getLogger(__name__) @@ -211,7 +204,7 @@ def run(cfg: omegaconf.OmegaConf, results_path: pathlib.Path): optimizer_kwargs={ "verbose": cfg.inner_optim.verbose, "track_err_history": cfg.inner_optim.track_err_history, - "backward_mode": BACKWARD_MODE[cfg.inner_optim.backward_mode], + "backward_mode": cfg.inner_optim.backward_mode, "__keep_final_step_size__": cfg.inner_optim.keep_step_size, }, ) diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index 60a8fbf54..e983d16c2 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -32,11 +32,6 @@ FONT_SZ = 0.5 FONT_PT = (5, 15) -BACKWARD_MODE = { - "implicit": th.BackwardMode.IMPLICIT, - "full": th.BackwardMode.FULL, - "truncated": th.BackwardMode.TRUNCATED, -} # Logger logger = logging.getLogger(__name__) @@ -406,7 +401,7 @@ def run( "verbose": verbose, "track_err_history": True, "track_state_history": True, - "backward_mode": BACKWARD_MODE["implicit"], + "backward_mode": "implicit", }, ) end_event.record() diff --git a/examples/pose_graph/pose_graph_synthetic.py b/examples/pose_graph/pose_graph_synthetic.py index 3971aef27..2102d15d3 100644 --- a/examples/pose_graph/pose_graph_synthetic.py +++ b/examples/pose_graph/pose_graph_synthetic.py @@ -24,12 +24,6 @@ from theseus.optimizer.linear import LinearSolver from theseus.optimizer.linearization import Linearization -BACKWARD_MODE = { - "implicit": th.BackwardMode.IMPLICIT, - "full": th.BackwardMode.FULL, - "truncated": th.BackwardMode.TRUNCATED, -} - LINEARIZATION_MODE: Dict[str, Type[Linearization]] = { "sparse": th.SparseLinearization, "dense": th.DenseLinearization, @@ -98,12 +92,6 @@ def run( dtype = torch.float64 pr = cProfile.Profile() - BACKWARD_MODE = { - "implicit": th.BackwardMode.IMPLICIT, - "full": th.BackwardMode.FULL, - "truncated": th.BackwardMode.TRUNCATED, - } - LINEARIZATION_MODE: Dict[str, Type[Linearization]] = { "sparse": th.SparseLinearization, "dense": th.DenseLinearization, @@ -232,7 +220,7 @@ def run_batch(batch_idx: int): optimizer_kwargs={ "verbose": cfg.inner_optim.verbose, "track_err_history": cfg.inner_optim.track_err_history, - "backward_mode": BACKWARD_MODE[cfg.inner_optim.backward_mode], + "backward_mode": cfg.inner_optim.backward_mode, "__keep_final_step_size__": cfg.inner_optim.keep_step_size, }, ) diff --git a/examples/simple_example.py b/examples/simple_example.py index ee1a6d96d..b8ec5f689 100644 --- a/examples/simple_example.py +++ b/examples/simple_example.py @@ -49,7 +49,7 @@ def error_fn(optim_vars, aux_vars): # returns y - v * exp(x) for epoch in range(20): solution, info = layer.forward( input_tensors={"x": phi.clone(), "v": torch.ones(1, 1)}, - optimizer_kwargs={"backward_mode": th.BackwardMode.IMPLICIT}, + optimizer_kwargs={"backward_mode": "implicit"}, ) outer_loss = torch.nn.functional.mse_loss(solution["v"], v_true) outer_loss.backward() diff --git a/theseus/optimizer/nonlinear/nonlinear_optimizer.py b/theseus/optimizer/nonlinear/nonlinear_optimizer.py index 5111d4b46..d34273f69 100644 --- a/theseus/optimizer/nonlinear/nonlinear_optimizer.py +++ b/theseus/optimizer/nonlinear/nonlinear_optimizer.py @@ -8,7 +8,7 @@ import warnings from dataclasses import dataclass from enum import Enum -from typing import Any, Callable, Dict, NoReturn, Optional, Type +from typing import Any, Callable, Dict, NoReturn, Optional, Type, Union import numpy as np import torch @@ -53,10 +53,35 @@ class NonlinearOptimizerInfo(OptimizerInfo): class BackwardMode(Enum): - FULL = 0 + UNROLL = 0 IMPLICIT = 1 TRUNCATED = 2 DLM = 3 + FULL = -1 + + @staticmethod + def resolve(key: Union[str, "BackwardMode"]) -> "BackwardMode": + if isinstance(key, BackwardMode): + if key == BackwardMode.FULL: + warnings.warn( + "BackwardMode.FULL is deprecated and will be " + "replaced by BackwardMode.UNROLL in future versions.", + DeprecationWarning, + ) + return BackwardMode.UNROLL + return key + + if not isinstance(key, str): + raise ValueError("Backward mode must be th.BackwardMode or string.") + + try: + backward_mode = BackwardMode[key.upper()] + except KeyError: + raise ValueError( + f"Unrecognized backward mode f{key}." + f"Valid choices are full, implicit, truncated, dlm." + ) + return backward_mode EndIterCallbackType = Callable[ @@ -351,10 +376,11 @@ def _optimize_impl( track_err_history: bool = False, track_state_history: bool = False, verbose: bool = False, - backward_mode: BackwardMode = BackwardMode.FULL, + backward_mode: Union[str, BackwardMode] = BackwardMode.UNROLL, end_iter_callback: Optional[EndIterCallbackType] = None, **kwargs, ) -> OptimizerInfo: + backward_mode = BackwardMode.resolve(backward_mode) with torch.no_grad(): info = self._init_info( track_best_solution, track_err_history, track_state_history @@ -366,7 +392,7 @@ def _optimize_impl( f"Error: {info.last_err.mean().item()}" ) - if backward_mode in [BackwardMode.FULL, BackwardMode.DLM]: + if backward_mode in [BackwardMode.UNROLL, BackwardMode.DLM]: self._optimize_loop( start_iter=0, num_iter=self.params.max_iterations, diff --git a/theseus/optimizer/nonlinear/tests/test_backwards.py b/theseus/optimizer/nonlinear/tests/test_backwards.py index 5bea260dd..a9c7b0b59 100644 --- a/theseus/optimizer/nonlinear/tests/test_backwards.py +++ b/theseus/optimizer/nonlinear/tests/test_backwards.py @@ -85,7 +85,7 @@ def fit_x(data_x_np): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.FULL, + "backward_mode": "unroll", }, ) da_dx_full = torch.autograd.grad(updated_inputs["a"], data_x, retain_graph=True)[ @@ -111,7 +111,7 @@ def fit_x(data_x_np): optimizer_kwargs={ "track_best_solution": True, "verbose": False, - "backward_mode": th.BackwardMode.TRUNCATED, + "backward_mode": "TRUNCATED", "backward_num_iterations": 5, }, ) diff --git a/theseus/tests/test_dlm_perturbation.py b/theseus/tests/test_dlm_perturbation.py index f8faf7ac4..dc98d4a3c 100644 --- a/theseus/tests/test_dlm_perturbation.py +++ b/theseus/tests/test_dlm_perturbation.py @@ -97,7 +97,7 @@ def test_backward_pass_se3_runs(): out, _ = layer.forward( {"target": target_data}, optimizer_kwargs={ - "backward_mode": th.BackwardMode.DLM, + "backward_mode": "dlm", "verbose": False, }, ) diff --git a/theseus/theseus_layer.py b/theseus/theseus_layer.py index 5555e007b..b17833ad6 100644 --- a/theseus/theseus_layer.py +++ b/theseus/theseus_layer.py @@ -51,7 +51,10 @@ def forward( "currently not supported." ) optimizer_kwargs = optimizer_kwargs or {} - backward_mode = optimizer_kwargs.get("backward_mode", None) + # Defaults to "unroll" to avoid error, we only care to see if it's not dlm. + backward_mode = BackwardMode.resolve( + optimizer_kwargs.get("backward_mode", "unroll") + ) if backward_mode == BackwardMode.DLM: dlm_epsilon = optimizer_kwargs.get( TheseusLayerDLMForward._DLM_EPSILON_STR, 1e-2 diff --git a/theseus/utils/examples/tactile_pose_estimation/trainer.py b/theseus/utils/examples/tactile_pose_estimation/trainer.py index 87611e520..ac5ec8b8b 100644 --- a/theseus/utils/examples/tactile_pose_estimation/trainer.py +++ b/theseus/utils/examples/tactile_pose_estimation/trainer.py @@ -192,7 +192,7 @@ def _resolve_backward_mode(self, epoch: int) -> th.BackwardMode: logger.info("Forcing IMPLICIT backward mode.") return th.BackwardMode.IMPLICIT else: - return getattr(th.BackwardMode, self.cfg.inner_optim.backward_mode) + return self.cfg.inner_optim.backward_mode def compute_loss( self, epoch: int, update: bool = True From 195797827d33132f02b0b318e1ab08afa7b37f6d Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Tue, 27 Sep 2022 14:38:29 -0400 Subject: [PATCH 36/38] Simplified autograd mode specification. (#306) --- examples/homography_estimation.py | 12 +++--------- theseus/core/cost_function.py | 22 +++++++++++++++++++--- theseus/core/tests/test_cost_function.py | 5 ++--- 3 files changed, 24 insertions(+), 15 deletions(-) diff --git a/examples/homography_estimation.py b/examples/homography_estimation.py index e983d16c2..f74d392ee 100644 --- a/examples/homography_estimation.py +++ b/examples/homography_estimation.py @@ -21,7 +21,7 @@ from torch.utils.data import DataLoader, Dataset import theseus as th -from theseus.core.cost_function import AutogradMode, ErrFnType +from theseus.core.cost_function import ErrFnType from theseus.third_party.easyaug import GeoAugParam, RandomGeoAug, RandomPhotoAug from theseus.third_party.utils import grid_sample @@ -281,7 +281,7 @@ def run( outer_lr: float = 1e-4, max_iterations: int = 50, step_size: float = 0.1, - autograd_mode: AutogradMode = AutogradMode.VMAP, + autograd_mode: str = "vmap", ): logger.info( "===============================================================" @@ -474,18 +474,12 @@ def run( @hydra.main(config_path="./configs/", config_name="homography_estimation") def main(cfg): - autograd_modes = { - "dense": AutogradMode.DENSE, - "loop_batch": AutogradMode.LOOP_BATCH, - "vmap": AutogradMode.VMAP, - } - num_epochs: int = cfg.outer_optim.num_epochs batch_size: int = cfg.outer_optim.batch_size outer_lr: float = cfg.outer_optim.lr max_iterations: int = cfg.inner_optim.max_iters step_size: float = cfg.inner_optim.step_size - autograd_mode = autograd_modes[cfg.autograd_mode] + autograd_mode = cfg.autograd_mode run( batch_size=batch_size, diff --git a/theseus/core/cost_function.py b/theseus/core/cost_function.py index 2db9408e8..8ba1376dc 100644 --- a/theseus/core/cost_function.py +++ b/theseus/core/cost_function.py @@ -4,7 +4,7 @@ # LICENSE file in the root directory of this source tree. import abc -from typing import Callable, List, Optional, Sequence, Tuple, cast +from typing import Callable, List, Optional, Sequence, Tuple, Union, cast from enum import Enum import torch @@ -101,6 +101,22 @@ class AutogradMode(Enum): LOOP_BATCH = 1 VMAP = 2 + @staticmethod + def resolve(key: Union[str, "AutogradMode"]) -> "AutogradMode": + if isinstance(key, AutogradMode): + return key + if not isinstance(key, str): + raise ValueError("Autograd mode must be of type th.AutogradMode or string.") + + try: + mode = AutogradMode[key.upper()] + except KeyError: + raise ValueError( + f"Invalid autograd mode {key}. " + "Valid options are dense, loop_batch, and vmap." + ) + return mode + # The error function is assumed to receive variables in the format # err_fn( @@ -120,7 +136,7 @@ def __init__( name: Optional[str] = None, autograd_strict: bool = False, autograd_vectorize: bool = False, - autograd_mode: AutogradMode = AutogradMode.DENSE, + autograd_mode: Union[str, AutogradMode] = AutogradMode.DENSE, ): if cost_weight is None: cost_weight = ScaleCostWeight(1.0) @@ -147,7 +163,7 @@ def __init__( self._tmp_optim_vars_for_loop = None self._tmp_aux_vars_for_loop = None - self._autograd_mode = autograd_mode + self._autograd_mode = AutogradMode.resolve(autograd_mode) if self._autograd_mode == AutogradMode.LOOP_BATCH: self._tmp_optim_vars_for_loop = tuple(v.copy() for v in optim_vars) diff --git a/theseus/core/tests/test_cost_function.py b/theseus/core/tests/test_cost_function.py index 742d3cbd2..483aae0c7 100644 --- a/theseus/core/tests/test_cost_function.py +++ b/theseus/core/tests/test_cost_function.py @@ -57,9 +57,8 @@ def test_default_name_and_ids(): assert len(seen_ids) == reps -@pytest.mark.parametrize( - "autograd_mode", [AutogradMode.DENSE, AutogradMode.LOOP_BATCH, AutogradMode.VMAP] -) +# Adding three formatting options to include coverage for autograd mode resolution +@pytest.mark.parametrize("autograd_mode", ["DENSE", "loop_batch", AutogradMode.VMAP]) def test_autodiff_cost_function_error_and_jacobians_shape(autograd_mode): rng = torch.Generator() rng.manual_seed(0) From b1ebc8e15bb0904005d3b51ea028930ccf812970 Mon Sep 17 00:00:00 2001 From: Luis Pineda Date: Tue, 27 Sep 2022 18:11:18 -0400 Subject: [PATCH 37/38] Clean up test_theseus_layer (#308) * Simplified code for test_theseus_layer and relaxed success condition to make it faster. * Fix test_ellipsoidal_damping_compatibility_cuda to skip if cuda is not available. --- .../tests/test_levenberg_marquardt.py | 2 + theseus/tests/test_theseus_layer.py | 115 ++++++------------ 2 files changed, 37 insertions(+), 80 deletions(-) diff --git a/theseus/optimizer/nonlinear/tests/test_levenberg_marquardt.py b/theseus/optimizer/nonlinear/tests/test_levenberg_marquardt.py index 16e18313e..8b14944b1 100644 --- a/theseus/optimizer/nonlinear/tests/test_levenberg_marquardt.py +++ b/theseus/optimizer/nonlinear/tests/test_levenberg_marquardt.py @@ -51,6 +51,8 @@ def test_ellipsoidal_damping_compatibility(mock_objective): @pytest.mark.cudaext def test_ellipsoidal_damping_compatibility_cuda(mock_objective): + if not torch.cuda.is_available(): + return mock_objective.to(device="cuda", dtype=torch.double) batch_size = 2 mock_objective.update( diff --git a/theseus/tests/test_theseus_layer.py b/theseus/tests/test_theseus_layer.py index 86c0366f9..04617d26a 100644 --- a/theseus/tests/test_theseus_layer.py +++ b/theseus/tests/test_theseus_layer.py @@ -359,91 +359,46 @@ def cost_weight_fn(): loss.backward() optimizer.step() - print(i, mse_loss.item()) - if mse_loss.item() / loss0 < 5e-3: + if mse_loss.item() / loss0 < 1e-2: solved = True break assert solved -def test_backward_gauss_newton(): - for use_learnable_error in [True, False]: - for linear_solver_cls in [th.CholeskyDenseSolver, th.LUDenseSolver]: - for cost_weight_model in ["softmax", "mlp"]: - _run_optimizer_test( - th.GaussNewton, - linear_solver_cls, - {}, - cost_weight_model, - use_learnable_error=use_learnable_error, - force_vectorization=True, - ) - - -def test_backward_gauss_newton_choleskysparse(): - for use_learnable_error in [True, False]: - for cost_weight_model in ["softmax", "mlp"]: - _run_optimizer_test( - th.GaussNewton, - th.CholmodSparseSolver, - {}, - cost_weight_model, - use_learnable_error=use_learnable_error, - ) - - -def test_backward_levenberg_marquardt(): - for use_learnable_error in [True, False]: - for linear_solver_cls in [th.CholeskyDenseSolver, th.LUDenseSolver]: - for cost_weight_model in ["softmax", "mlp"]: - _run_optimizer_test( - th.LevenbergMarquardt, - linear_solver_cls, - {"damping": 0.01}, - cost_weight_model, - use_learnable_error=use_learnable_error, - ) - - -def test_backward_levenberg_marquardt_choleskysparse(): - for use_learnable_error in [True, False]: - for cost_weight_model in ["softmax", "mlp"]: - _run_optimizer_test( - th.LevenbergMarquardt, - th.CholmodSparseSolver, - {"damping": 0.01, "ellipsoidal_damping": False}, - cost_weight_model, - use_learnable_error=use_learnable_error, - force_vectorization=True, - ) - - -def test_backward_gauss_newton_leo(): - for use_learnable_error in [True, False]: - for linear_solver_cls in [th.CholeskyDenseSolver, th.LUDenseSolver]: - for cost_weight_model in ["mlp"]: - _run_optimizer_test( - th.GaussNewton, - linear_solver_cls, - {}, - cost_weight_model, - use_learnable_error=use_learnable_error, - learning_method="leo", - ) - - -def test_backward_levenberg_marquardt_leo(): - for use_learnable_error in [True, False]: - for linear_solver_cls in [th.CholeskyDenseSolver, th.LUDenseSolver]: - for cost_weight_model in ["mlp"]: - _run_optimizer_test( - th.LevenbergMarquardt, - linear_solver_cls, - {"damping": 0.01}, - cost_weight_model, - use_learnable_error=use_learnable_error, - learning_method="leo", - ) +@pytest.mark.parametrize("nonlinear_optim_cls", [th.GaussNewton, th.LevenbergMarquardt]) +@pytest.mark.parametrize( + "lin_solver_cls", + [th.CholeskyDenseSolver, th.LUDenseSolver, th.CholmodSparseSolver], +) +@pytest.mark.parametrize("use_learnable_error", [True, False]) +@pytest.mark.parametrize("cost_weight_model", ["softmax", "mlp"]) +@pytest.mark.parametrize("learning_method", ["default", "leo"]) +def test_backward( + nonlinear_optim_cls, + lin_solver_cls, + use_learnable_error, + cost_weight_model, + learning_method, +): + optim_kwargs = {} if nonlinear_optim_cls == th.GaussNewton else {"damping": 0.01} + if learning_method == "leo": + # CholmodSparseSolver doesn't support sampling from system's covariance + if lin_solver_cls == th.CholmodSparseSolver: + return + # LEO fails to work in this case, not sure why + if cost_weight_model == "softmax": + return + # test both vectorization on/off + force_vectorization = torch.rand(1).item() > 0.5 + _run_optimizer_test( + nonlinear_optim_cls, + lin_solver_cls, + optim_kwargs, + cost_weight_model, + use_learnable_error=use_learnable_error, + force_vectorization=force_vectorization, + learning_method=learning_method, + ) def test_send_to_device(): From 0fa526bcb3a47d8187ac0e1d94ff677d3e13b590 Mon Sep 17 00:00:00 2001 From: Mustafa Mukadam Date: Wed, 28 Sep 2022 10:10:59 -0400 Subject: [PATCH 38/38] update readme and bump version (#309) --- CITATION.cff | 6 +++--- README.md | 12 +++++++----- docs/source/img/theseuslayer.png | Bin 122347 -> 146528 bytes examples/simple_example.py | 2 +- theseus/__init__.py | 2 +- 5 files changed, 12 insertions(+), 10 deletions(-) diff --git a/CITATION.cff b/CITATION.cff index 6f0c32d17..ec98ad281 100644 --- a/CITATION.cff +++ b/CITATION.cff @@ -12,7 +12,7 @@ authors: - family-names: "Sodhi" given-names: "Paloma" - family-names: "Chen" - given-names: "Ricky" + given-names: "Ricky T. Q." - family-names: "Ortiz" given-names: "Joseph" - family-names: "DeTone" @@ -31,7 +31,7 @@ title: "Theseus: A Library for Differentiable Nonlinear Optimization" url: "https://github.com/facebookresearch/theseus" preferred-citation: type: article - journal: arXiv preprint arXiv:2207.09442 + journal: Advances in Neural Information Processing Systems title: "Theseus: A Library for Differentiable Nonlinear Optimization" url: "https://arxiv.org/abs/2207.09442" year: 2022 @@ -47,7 +47,7 @@ preferred-citation: - family-names: "Sodhi" given-names: "Paloma" - family-names: "Chen" - given-names: "Ricky" + given-names: "Ricky T. Q." - family-names: "Ortiz" given-names: "Joseph" - family-names: "DeTone" diff --git a/README.md b/README.md index 4b0322677..7838a0f31 100644 --- a/README.md +++ b/README.md @@ -63,7 +63,7 @@ Our implementation provides an easy to use interface to build custom optimizatio - Gauss-Newton, Levenberg–Marquardt - [Linear solvers](https://github.com/facebookresearch/theseus/tree/main/theseus/optimizer/linear) - Dense: Cholesky, LU; Sparse: CHOLMOD, LU -- [Commonly used costs](https://github.com/facebookresearch/theseus/tree/main/theseus/embodied), [AutoDiffCostFunction](https://github.com/facebookresearch/theseus/blob/main/theseus/core/cost_function.py) +- [Commonly used costs](https://github.com/facebookresearch/theseus/tree/main/theseus/embodied), [AutoDiffCostFunction](https://github.com/facebookresearch/theseus/blob/main/theseus/core/cost_function.py), [RobustCostFunction](https://github.com/facebookresearch/theseus/blob/main/theseus/core/robust_cost_function.py) - [Lie groups](https://github.com/facebookresearch/theseus/tree/main/theseus/geometry) - [Robot kinematics](https://github.com/facebookresearch/theseus/blob/main/theseus/embodied/kinematics/kinematics_model.py) @@ -72,7 +72,8 @@ We support several features that improve computation times and memory consumptio - [Sparse linear solvers](https://github.com/facebookresearch/theseus/tree/main/theseus/optimizer/linear) - Batching and GPU acceleration - [Automatic vectorization](https://github.com/facebookresearch/theseus/blob/main/theseus/core/vectorizer.py) -- [Backward modes](https://github.com/facebookresearch/theseus/blob/main/theseus/optimizer/nonlinear/nonlinear_optimizer.py): Implicit, Truncated, Direct Loss Minimization ([DLM](https://github.com/facebookresearch/theseus/blob/main/theseus/theseus_layer.py)), Sampling ([LEO](https://github.com/facebookresearch/theseus/blob/main/examples/state_estimation_2d.py)) +- [Backward modes](https://github.com/facebookresearch/theseus/blob/main/theseus/optimizer/nonlinear/nonlinear_optimizer.py) + - Implicit, Truncated, Direct Loss Minimization ([DLM](https://github.com/facebookresearch/theseus/blob/main/theseus/theseus_layer.py)), Sampling ([LEO](https://github.com/facebookresearch/theseus/blob/main/examples/state_estimation_2d.py)) ## Getting Started @@ -86,6 +87,7 @@ We support several features that improve computation times and memory consumptio - `conda install -c conda-forge suitesparse` (Mac). ### Installing + #### **pypi** ```bash pip install theseus-ai @@ -137,7 +139,7 @@ objective.add(cost_function) layer = th.TheseusLayer(th.GaussNewton(objective, max_iterations=10)) phi = torch.nn.Parameter(x_true + 0.1 * torch.ones_like(x_true)) -outer_optimizer = torch.optim.RMSprop([phi], lr=0.001) +outer_optimizer = torch.optim.Adam([phi], lr=0.001) for epoch in range(10): solution, info = layer.forward( input_tensors={"x": phi.clone(), "v": torch.ones(1, 1)}, @@ -157,8 +159,8 @@ If you use Theseus in your work, please cite the [paper](https://arxiv.org/abs/2 ```bibtex @article{pineda2022theseus, title = {{Theseus: A Library for Differentiable Nonlinear Optimization}}, - author = {Luis Pineda and Taosha Fan and Maurizio Monge and Shobha Venkataraman and Paloma Sodhi and Ricky Chen and Joseph Ortiz and Daniel DeTone and Austin Wang and Stuart Anderson and Jing Dong and Brandon Amos and Mustafa Mukadam}, - journal = {arXiv preprint arXiv:2207.09442}, + author = {Luis Pineda and Taosha Fan and Maurizio Monge and Shobha Venkataraman and Paloma Sodhi and Ricky TQ Chen and Joseph Ortiz and Daniel DeTone and Austin Wang and Stuart Anderson and Jing Dong and Brandon Amos and Mustafa Mukadam}, + journal = {Advances in Neural Information Processing Systems}, year = {2022} } ``` diff --git a/docs/source/img/theseuslayer.png b/docs/source/img/theseuslayer.png index 1b8833964e8cad88c955a9c0461d36fe64886ac8..e894d509f6a9a9361ac23129ba165a303dbc1e95 100644 GIT binary patch literal 146528 zcmeGEby!vFy9ErdMT2yANtd8>H%PaH(j}6Dh=4TGDcyo}EgA*sl13Ei7Ad8>-eYEDUlC2n2$4Ur|;I0zm_Z2mxpa z;79*Z#X0x^b=6XkhExnwZh-#@veLhAt*Q!P1IK6(WGFra5q=8z7Xl@RApbgsK$M^q zzmK(`EdMzNd}hdF2-1JfF$6#1|5SiK;BWuuCt?otpHIv|`1@=$NDkuP#|Q!Nzjk{r z9e!nWXGH^72!y-?{s)?wbhZb9NJ8$*O6hn&w=>b3byu!$b_V%I#&yY67!%*b+v47* z%MFq)==Y!)lqE={yH|{9)kjGdk21!S1I|mmXT!?O-@5tbvcT0q!(rJf3W*W>oUwQp}_dQO5`klw#a)}y4#GZOO|BuF% z=u(r`>z0e3A|AVo>f&b%5z_hb!7~D;ZGOi;W@x;3+dp_7dG35TQOYONW&7j4Xc2U? z!1vWTtMr5XzAqg!1hDD0zGwShZ@yHmtG6qM8I}&(u2%EIi#9RG@juYt|7YFz*pKQK**b zxn0#eQD$&((t7jqotu1A_@Bcm$;d>DD9PCJjy&z}L6)S$J3afJtq@Ha#zmd){dQri zykTCR!XfBYty-pV6oml%3!W#pUNYX9{sf{0{5Fm2?1(tEY_i2)R=itFQ`{0J`Y)3K z#bePxxCWq3H?&?Y;V@!+KOMN! z%3)C5ReMuAuyJ{I5V7rd_xGs%J|M*K$48F}zN>ho{m&G#iTiVO=2Sj>_p~pTuH3NB zu+f>0?E*h~EBofM@M~KOJe)0W#)%y3}H+_9`W#7Elv;GbJ z;-FXJdMxC zREK9L!jtjuHKCD@z8HCPJmW+WK;v_|1a7!%!T0iX&-MH8x6hwi&(_j!aW(phJ-Rt8 zq_lCXt)6jg61&{()Gkmt+bGQDM!|hpq~!W_@%Nbi=Z6Ay;D$9;x?s;yhXY`Q44o;^o1}&EdFu2sYKGY?kL{u{|aPtZH@&lwFd_n~VpT z`guD0VDLj)y+f6BI-)|08BC~LnHWW3T$<=*9Wdpo2U~m^NaBpL2``)S6J9S(QjIup z7&ix*h|1ff8*7+3ioHQW=?D=~#=7KWG=EWf9J14THMiq4R5yJ?Y}u~i65;fIqoA8J z_wvthMFh_TM7sq=%Ky9@8`m~vlPzXH$?cYtWC3QVjNc$wg*Aw1#w}MQ8~%^ak@i&@q^0w2_vT; zRJR7!+%ZFZueMBbayUKv#4(J8Sp6_AWC$|i6_Y1pQ(J!2j;qz#eVH~5#9HU}Vj!GC z-L!N;;q*D4vMJRoKL=4`^scrH2oL@;jI~*|nv#`RP;HghoYf0~4az5rBRPt1B(^GB zeasyuuso%M-TbDjH<}xkQF#@NF25PKUi@tGenE;xa}m!?%yu%khltWG5VY)VHvi%~ zmD<+l;?73}_eMj%k0f+B7lq(7tX-Wfn1HAgS`?BcNt@fn92_l&Ura{s=C=e3Ij*)E zSVzpPxA75Czu%RV zM-aI_mWp{SG&(3>P3?QRN5HJc;1VNt>~VGU^=ri=uP?d}=Dc=3uoQ59w@!C(htJ=O z)wqn@HSwQ~D`38a61ry`8s;XeEO3NYV-kO)z`@;KJTig%|fUgTh6RaIQKx{%=TCgv-k1C&fHbHXFcdQQZpj%b@8L2 zW(>jZNm^d1zQ!bJYB`?pv(1FZwi7(zru?L0p1e}2uzo>$HYtmit%@dohv~!B*XoX= zIa0DzIA`D*XDJrZXXjg$8<KtZ{!`UnREJZ1Ls8wX2&pji# zy_{wI;#;Da*Kwqc^8Ggl37Py3K~9)+vs?53O3w#YaRBR9bzm z&JQ;NKZ#Z-=c5bD;C-&Fl@1QNC%s3d7uxT$@hSfW4}@F3j69O6GmsB&Ofav~h6*uR z@#b_TW@CmE+*~i!^OVhn@KN2Alx5O}y<2yhNA+}qUaqCs*LFA#+ODdK&{!|Bt#sgb zqGE|(@LQ<0G2qhYYHl%SE*-083iCNaXh(A8BIZ4}IGYSUzY?a1P}YyB8~C6PGle1v z<{Op@ZEKzLygUWd4eQF`?NucBh>5F$aPWPk@HGhtEN?=n$r~bae)b*)EG^O8oT7G~ zkdLk%bgy*I6FqwGhF*7;#Vne`oKlT~Mc!4^d13y7G$)FOL;Bm+M7b*>gmXV?bFN8X zfj7D{gR({`5a)y>UFzogs#Ld>IE{clmAzvlv7z-LKfm96=JN`)6p+L%ClTdiEsk^V>z>@OMlT51 znTVgdH4P_pBgwqNY_ISeaDU4jr%g<-n6fkNyF;qWXg7JgJ3>?rs`~BCarPeAm{nB5 zZi*brp%iXiq!5*X!Szs00_-TfB@N$BEP<4LF)ehpZwWu9>q?*8kfC)iS;YBL;#s5o z?0fM&Go+^VL5D8FG;Z=ot#!a0S~ zJ!^lQj+wX)@fBPZdPN2ZDmKn|+0$27sRj7M5*R+|)*d&^xl{0+-bK6UAjOE@=-i&F zVU2i0|3N~Z+`c<-jzmvw6w993o1Ps9Q;_WRl@Y;b6=s7dm(!(?1GJRmg_Z`)Ao50$ z3E`=qEf@4gQUC^#!ejc8#oTBNqC|n=wIWZ>o?HDU zhaI=&BO5_x&`xX9@w+2R6p!j)4?xN!zMs-4USWdLPKk+}K_tQzNZGxEreU@>P0zO6 zL2ymK>U2H#Kk0Sbi*!7hdv0R@v7qzD3Z!S|_aia(So*B3&Un~Nvg+sGy5G+ph>BBy zudHw%%g+0t80ni}#rZ7~F4=eX@4a-6Uo)%w?6#v$4YZ>U^k5F9@ddus4b9DV2Z*1F zzpEc2Zidm-C<0>m^AyEKicfQ{zF@@jD9m0RS~wnd;z$e*e=6YVjg)d`c3Z~`sl-LW z(LKdkN__mW;`Lm*pfb(*rx z#MMf1UX0lb)YqNG-cRYziXyfRs1%4xfEDQDRWE&wS?b!~ea7gBuS`seCvZyyRhe?p zKGRGU5gGwQ+|yOrNvZfZUN*yvh33G1CVR5~4SoQE%b8=U4sY`B%mwv=96lZHW!+a} z+_$AKOje_IeYC=3uO^uX zGXlj>f<;_>Kqk2}(usjXECX9^*SRdaMJI@F!hNq|)c4ie?tR(s(bU-*7kY?uGOX%u zOw#BtGQ&`V&^z?4#M-f?XlW6SaEll2)}TX0jAp^M^>$EPYU+wdIDWcYvW_nL&gvCH zo%oMx5(E_HN`EXmZb!2b*oCyiBq?`lqgl_BasNN^gdZ9q7c>~cHtSWG^&3&>&>^t! zj@`}k>v5P0i84IM3B=wX??U7qv*kzEu&`5A({!~VKnNw~A%fkn)Q#YO_wwR6M*Q5i z=;}MZow-hFQ0w!$;xk8P_a1_ek>?adoNN!G&lZ{CbyzY35-ycI-F%(`j?SkEjjGz4 zqQ#we->Jv1wKKjzSX#(Pe7@;X3?D_1+&QLmZlj`8!4jb`q8CyZ`bKC^2SS{($d6hA zYYJjUZWXoiZ2JNG{L={6bFQZCk~j|)XX}}qxqgp=x0t+!;(*@ zZ}IMv>P)gvR_rHV7#feWFH?y1rQ4G_^pfaaOJGI? zZ)R6kd}-6~^Il7}d4Ig1Wadk6o9LU}e$hpsPWXHvsB4&A^N;i`iNuBtC4;aHf6!3> zCvz;`5J*0MOhdWrg3c_C8U3SZ;L%b9c7o!$t;daT>Li}j%+xb}?d=Qw@q7y7sJZe%Q3r|;b6`Zco z=BavE#!-(HajE@wN8-Kx!_Nva)KLZE_Q`Hq-rDAVjdnBDc;jnTz0?PO{I$hVrBxpEL%}&;F!ku{MvihC}5(Q6!=jD>OOV<`Ey6uGPDQ#WWy;>bz7!n)_>;ZnP+kE{=gqqavq zc=bS8z}v*6GQZCA%vbo&ZPhDB|!W%Zkg+n=#)Eoau+f9_3GK;S@;sPIL1FV zUM%N}B0JnY*AU4s0W~O}!}RA$d2DV>w~bHT1U!a~4;q=zq2w=w)eni(S(l)Vp^7q% z)E)2ib=ND^g*O?GxMo;C=hH zGS{q-I8sqxOBN_*rjdf*(48}(*ymypWiJuF1tw=qjz=W zE@=*TeCqlTw^h73D3E!=ofoQ5yCjM}Kc6&19YB9U%reO{?fbm5*InAXBy{|P)or|p zxJnOLSD(pZBNz1wfmoR3VuFbD0!QY${u`;_(HqAUsqT?w%!(dVX^e)!ax}=H*4|nI z{og_PSG5|fDCq?uTz;gT{kuG7lklIav0=u>@8!=T;2F$L7c7S5R~j@@FATdtS!`KE`(Z zCD^igNFF5Pgsas{FcNF<2QvEdPvIZrn92#*B^MO}@+NFb6p`F$#19I2WEU>o%s_RZ zcj>qG@IswF%^dezcbi{_7%yZ|?q|O_wuWTWfT;0VDkk-W`Z)ngi$WdNymL3?fdLY? zSqIYoJxX_y9Q2ihe3E zzMOmZ_1$#?L)6`huEl$w!;I(WZiJ%NPgbJh>1r8sY>!D#lBO^r?keA1yiDG^u@++X zCYyh*c$D5KZ11zRM*QHs=HxCr#2yNr>wzqKt@elzs4w|^E4c32H(R630M(Ay=)K9^ zf-WN!^~V!sslIuOgN}o*nN)K_Bs&-VkF&oq(N-&w^V;H8@Sg(C#`WUdOd9gYv)4`c zUx6JX0`QcC6IWVJzc)__60|n9VwNKrn%92P_H)8t#nX9*TJACh(RB!0TWKfdRESE% zz3Vyk7w+<$+thq^gi2-{jAxJRaIv9SEnZEphdJ4+%W?5~mst5=MD2h+Reno;4>M;w zOXT@afd2iVZ32+CJ6Sl_J6-DyKioCX@0he?1URDSu+=WvLl!X(VKb@GWNID*yLAdL zO;%NzWdOfve`CWz|K`Hm(k*p*C}FtGK&oS1B~ij@UbI7Ax6(NCjTuf``vNDH^Tox& zP4wfg(q*klVWx0<6+Br+^U6hYWYvA*XTRC4Uk5}jfa;Hq>( zcvcdEsI*P+euW#c`^o2`xRe@R{4qTOQPij#Ig&?~(KkWS?=JTT0B<5={>>eB#aS)j^e+)+ngj_0U(*6agPYG?%DqGGsiwm=qSdF5j6e(+OPOtM8 ztsnIPI#7k53y(HbGo7(*y89|yy%~p@Z(aHG-HdF+|j8ysUxP9jno(3iWCOt!s~iy)@H2~nO+-aU+0<}!m~T^*L- z7r{4ON2VQcg;n!W_JA$5dnE+gkSq|*}!a!GZV9-}K+JCZP?Aa(}&#FSLJc+#x- zrvsdTIXAx#U0~Fcb5`f^a#oVkI?cJNG-_}JB*7$6s$+=NkBQiJJqFY89F#!{Gis{e zkn&efCZYpGInlc@@`8T?1Yr#1{2_fs&cg!IirG6Yr}PyQEXD*+q=ZBqrg>X~h*PS4 z4Ea&lD^am28!bQL&wNPYsxm>?f&j8;&7Qt(b@aZ@?&*pVjOlPraGM5To>bhWF$v#m z?5RNR(4eLB%MCJMSt&ckXbkkufG6w1;f0Fy4Efw?&WRAfT(bs_PK^{`t~QV zdi17uWTv^?#2Aq@C#s;B_=xq>MeP^M{csk7D z42SOoTVtq1Cb%?lk=?C+Fbtp7tG4X*P#9pC4xiel(!5y3%Y|gVSW7((^cwc2 zN+D?_gN!B(r`|)Qxs**5=yy!`IwF2i#uxR?5BEOH`E4TlJ%i&{19u1yg*02^wTDUv zM^^B*Af^gyNPR-hc(#bMaC73my8F@cA!{{TlZ%|SHp)LtJg$E=UF>$JF26%5(Vy>P zC_}DT+jSqtsHmiXT5{^THcmY6qUC79Xl&9@c=`vBN|@sd?bXHzYp8zaNCnPb`gNXu zd0-M{*TS0+Uo?=;_hc;;?W-#&+!grMtrvqTrKVKv>7N((lxEf;gsC{^7OFKNX%QPY z17RU!IXwp2_NY(3bXIb=rnt|`=)BGOpOC8qZ-Ly4CT~ve>{Zw1t~{f z&GMz3!j1^e>m@)-nfnIBil$Z#J@nkjACb5bT_d|gDwLyn=Ll#SHLnmE#i0rMnSRgw zaTa96Yoo&#W-o8^Z38Ye=&DL~f?)R9*GGUX-xI!_xHD%L z;aV5{?3J?Zc36v+A5P}Ip8uSEH~HgRF=P$ZkQrlieJoFvFLJr@`OZAh?<}!3T|SA( zVP@yWh^INAXk5J}_`=@^={|l(i-3$_b>7B?VNNgxEye2QW%J3{B4F<=@@u#N{PHWk zwB@xwWLgNioJjtsjV`d+qIV>C}ao5uph#Rur}_J*~>WF%{-lsBBK!{h1_SO={)S38&8 zdQwvL9P$@2{1T2#=w98@1h0CC(X4&i+&e<@fsug2SIBzAtOQwkr6=mF-%PM-=k1sA z5?yxTgTZ?vq-}uWkD+KMNwgzFqp2RF5zpyV+5=n;P{!z47 zjt?R`4^hgC(EnVT=6I)-s|7Lt1V0cJyU<|`o85q?oPJ!GN}bfY(i_8kckudRX8~p= zlZ1wwv~1m%JO8s9uNyBwjd6Zhf8K z!NBHEgPlHJ6nrmt4v4n*ENSi##}#WA*4t0vYmlNasbwg#+F74kD=Ti3QlMu%?Pp#6 zzCs2gv%E{eYxf!Lo=lVb5AR?ki+0RFtjg8u?Ef|Vsv{5n27-+cGaxF&ExYv1=$x()`R6ELZ!S-yYpxj?pN z$rWf)3e)o6!cT-fkAXrU%awS=8a)qKzBVzM6JJASG)x)VpO?WT#wjL8KY^??S7o8# zy<{_-@pyRcl95*;`?SbKQz1&to8fR{uQbbC(@z=^@>1Srs2-XXf~d3UJ!;~rElTx6 zLj2Una2B!N@#p9pL<-g#ld5vIw(;z`TP@ynT66+p@dyW?gsNdP2R!V~cILsJ z6O4wJ2$XwrcWsw+MZ|$XSw*~<=oA+qiHbx~e8rcSVAZ2BR{G!$J#y6*;*;APc%_mJ zj&q<$4c0~RLJ8Z;(pS4kU$`T$UlaWsZo&zL97=Rs9KWYQl?Cv(b1uP+IcqIC*q$g?}W|B1cPwPXDdSj~cU_JB?>HWkI?_BilBfHO9;rS`NFQg97 zx$5n~tsK{)e;JWsNX@(ReEx+E5Um^p!*n%c@sR09M>*RGv}_S$<7pYDHTt|60b z_EB%`__KAIsX|+r9{75=Ajn&T}niCz_r7s1~})E zQxeHefa;1ik#vl?Q=`0FUs1$6jLw5&Ac>R!;?rNVuIzVi%| z6luoH?Xda&Yo^Hu^k-*TuoV{oU(owyjWWz}a&ns56!u+}wq`j#W9bYC2abB+S{HCO zZ-gb?bKll~)p-ZG^9>q}u#60^lu_5M0Ow{49T7mn=90eo#=I`Uj?SXU+TYt?81E>&MkX&eiR`}I9ZN9=Q_aIppqq;YSCYv<>w?m+kvL2 zK=q7}F0$go@$}>If-y4bt4V#^Xq-nK!%$v&lDO9vJAr@u5OQ?TcU=ct1cAEWz8!^} zmd)l4yYq!u7eoiiM8@5PsOFOGMLuWXZ3(#Thu@xjdAlL+^|Di3o~fOcA?d33b7anH z9iopg&m+48PkW7z9-3V_ds26_<$5a2!X=Rz{HPCr3M{`8=1AD>;wUED8n%|uz-YH; z|9NQj5+vv95%txieC6ca^a3xIxUr5Egltu(4|Jc)-f)RGm}y~Hab5hpYb>8uEWP$# zLoRqo9Wo`I_?*A{aj*%l9qqB0r}zBp%fq+NQ?A9_lC|u?a$b5(oX1B+i5upEGzn*=#l=RjF7iez(C! zY;|}WL`O*zpsg;($JqKyy_OtC>UXP7cfF&l0WYR${nl&;Q+T$8L;L+Un6mt2HQNw* z=1?SyL0y-j*dLm=Zt@C;#<=Hc%g;=B0?^O!~UJ1l8y)Y`ciuDeskJOdQV@S zA98EG+6W4~388ma3o>MKNjxqEek$=xL0XTvU{)(^}p8p24p#bAr$CE1wO zefu%wDVS7Oybn#lX4qpOc+_{~=n-w({yR~G!|gd>%Rf5Q*|Y6d^|j{$@Rd1ch5MAGJ{ z+(d(Ed=XYi?nDPDUbM-xK}nN(^8^5Oo6c|P1jA9Hh7!``+y|$H77nz7bAv)TBz~2W zNkmber;?JQ2z6E4gP+2__i*uT3>(FfyZt4~#gYIY!YXne8y+w#-9lIzj+&reLep4} zp#hNcIv(s%NigMDQ(>=4pDB`4|7B z!w2_7)QME=g-cr9-kr3F`2ZLN*{Vu=#Bq=Re2bhCd{YZEz0=fE)+N99?ms-+ps2Nu zb7_3ODX7j&-H4`ZgQ?nuYF01(q@;Hi@)TmG>z+LDwgx5uGZ&G^Gbn@&3BP<8lEwHQ z08*i0bg6NM!wgF@;Niv(Eg=Jxa*Q@b7mF$^M#2e|&sWL1)t%>mmLH?*sga zyyd^}e7+K`1*~4nK{pW&`X$lPgQ{+SAI`j3&x^4x;T}w7jrsH&69Bn^{tV_jGNwQ? zB>uYb*lRT#7Q%oJiGBGBo@6^Ta)JOB&FsJwCjP})uwWs)@i>}(QYm(Qx*~CPsBJD| zHr$1&MEKWlDG&^y8vGew!ohX30K;zje1XRIa%}U*LaQ$@GQrJU9`}HY>4_*$I^puI z1GDMy@Hg}-#$;$sRQt)pZ#io6M^^W;nAudT$y)Z|JOTU;gz$@izAmD|W!wzpU>c^+ zBLL#|uC*P8EC~8ck6t*nULD(B;s~$j07G4sjilUZK9|BnJ41NL=#PX{KICVrA~NLl zJo@qg%+?Y^k4PJZNLGq!zi&4;y7^SB7Bzf4`=Y@FO}S`sfpmZ&@5j;>Liw~0F!vT$ zhE?X>KY)Fu9hoGdIh~Yf*KDaXt8<%O@$;P6@nm3YBiV9LO707j2FFa+^^ak!^y4jE zgH|6O-!t52_?aeGhUh+J-lOtLm47Noil@^$uN<&OF6htufCa z7hVE=7gTX{;`=~o^tVR3LYo4>^8>f*N7mxMt6dgE1pAu-8$goU-n5=B-@16oFpMJ+ z%-Y&#HOj+B2WM4vlOQ4$HLL>w@Om&KLf<_8T%-xO4mx}V^iw#mGzU5n ztx-=e5kNX6+5VHyXW{XQLLd?NRatBhRCa(Y zcefc~?!kpPssK&Zc?4{Kvup65NVE<^s{bt1kT zdRs8M_S=-(-}EI>DunB%D1+@O&KCjr8Y!Yj!tELs`c9b(18i#(|0;!3^Byp_*iam2 zSYf?o2&y!4e1|NBnGG~{?AOT>)(|AI2{ML~?T=w^J16$s?8j9Fq13vH>J+Q~z!@d_AM!+2J?@mT*cg0@W4BS<5T%l&+9$;C-2(6Ls=bS5O-A4QL zT3uYoW|(rexnphgqVugus}Hc%P+ptu)prd3+Nb_nj5%TuC8A0;FcU1CVDMAaGQoZp zk2~KVxD$4x?CGd#u4u|^mT<~pZgspi?Q7RbK;wjM{cQc)l(WZ|65Tx}+hkp|q~Q$w zC~wgiUAa~If-uT^Lsn{GA<7KQ8yMpclCM>D$-Jwr9zlMmS-^DvDPOVWTGj*kQ!KBg5nNaAvtnj;v zFr)@+ZzwG=LvNYCC2)yu^|nn8MuVfpwI~hT&Z+EOH_M!E9*Z8+jP)<2Bux_vwKtY+ zqJAu>EW|3!z-D+;u0sQ#Wfo?TEfNSk_<$!t<1PaK!Pa;o4xM8&leH9iA);4%AF1e94rZZjb94#5|n_p?Ih++vp=5v#Y8K_Gyj2fnLq>(+-|e z)Lmb*Pak#SGjVu)^iiyrI0WbHO3Oo|V1Pclc$@KpZJxI?1jhzV$W2D>KWXW2bFVA} zfhqLOSEkt_5er}%{t1Xn$r3g$`tV2^32HHsTY2Sz$}OR_fwZq=18pr-M_H<=f1Z^- zs8p+k5;n})?-Q63ll4D+Pus(~Oy|4t@!j{V2+j7pv<2^I^AAXT%apm^$p)k# zjsZ^qu#9P-odDV^J(We==+K5jyp%7XCkN|4y2msxjvx-9ymuFcXA z{grEed*F-ukyLPH4o&&^-`ouC(MUzgK~kU^0VKDum9sBSc6P2+PPw10kG|0@)eDmD z-Ux3jgWLL+V;+xuAITnJa#r+ZTyUaISHqw9QvGIB0oS6><8Woesk~+oYuG1KlS>b?PEmx>SAFx2T6 zCfXkzbxsFr`tM$-aXV4mwM1)LGsF{Bbv|G=jsDsuTmGoYoi}JRTh=-oZjLI|NJaC^ z(h`$w9VzJj`p{Jsh%vUIx>aR9R%($n7)-d$7AaQvOzXhA3jAhzldlQX1eZVV5WgKvjLLbE!0U`}M#eFiKz5vIW!ua2{Wv9}Rbu$V%5 z^pox^QuY)enAN$(=g433NkuA8B3eSw@HX@Tx4?nUf}~;aNzVxE@iS)0GU{WieIa^m z)}Su*JYM1{1|CWpk45OfE2Yd>5#Z%;TmJF6SUconk=*Au=owp6k4pN|4if$EGmDsy zu`^|Q4~}Q!N**RT1nq5Q0|zF5Wax4Bgn#F?j%qr8T^4sIQ<7DSXTIm}UDF@mHho9W z_v);~{OX>UG3?P^OgXo;XMdTIWoNvXi?#R2pmIAt z^NU8FeAFA6km|c_YAzKv0&zGuSAPzaq}cR>3oGX_IAZDSWre6&3xivf!#skFiYs1?`oWabxG`L zX)2e&c{?hNimaXp)1;=S^&@yUg8!%6K)~6k(j5ZxYb6W8c`1F<0PM3NG(IpUAkg#~ zYR+U9_o;E1w9FpB{jo2yW)MX)5%uaPN*|11LMUq-Bt7a9qIpEOTW_vyGN0)UAJwoV zl1k}igjI*U8GI-G&qimlKoDf{DC;oi8%mSoL|`H2u>x?Eg&2xd6#---K-gQY@Ujbf zpE^HG9$mB19tkI6f0!5(p6xJ*kIYjdjeDCOC>^+69P1kVstFA0fYL=TFpMXc#@;5= zh%eF6gCj*HX}}%Ek7^r$dkdF_EO^hV>r2{EnP(Tp-Bwr@bW-LU_quOAvI~$PzR4%` zPDG|W4#7G?>x^x5N@LD^i-)HA!fESh1Ws|?H6EkfoNJvbX*hQ!nXfNyYUAMj64BQJHj?q@hc}?f8GwijqhrXwc7BWv@ZwN@7%U z$|>;DPFW>C3McGBQ{T+(zuo$>n(kG~N`CdnY}YJ$WF9;DMe`ZNTztIEkbHDSGw;cX zNok5iRS8$>91LKU(4m6YYnfig)S&Zt)dmK~qw*2yPAz0OX`gJRpZ#OI_)jgtgwXV(o+AAunv|zQk9s9F z2+I`UQGkF;OJz{cR1$l~@wz@ei6&vqCp^Ca6_fGHqc6bR#h%ZkQx302R)ay6@S?p) z39J}4B&fIgq~a!kEp_v71qMKvY1_OgE#Y2_q1{b@;j5NjQM_W^vnWWXu!l*3UYzCR ze!=eA8xUXKFNd>x({7u!;ZBPBt>3sMimG(gUA9I#MWy|#^UA;ES1X7waLUZTJbC2W z^M0r0Vs~i2yboWf@zVSOn4kl<_MvLJl?-4q2fanc=9yNhp|Q^Zzg=ULjuX^E7rIAc zFsO&KXxDS@SG}DGkAt}WvS5T6%r$dCzLLT>4WFtskr;&3Pdo*LP#L6gv!qlDrL#pv zWz74Nymj*ft^FBBbE#@MT?V7|koeA$07ZwXjJq2E(lKw;9Az7<@z2=Td^Pr>a-TGd zd;&N-OKeqjCiScgY`XON1ciS&A;8GtquYaN0Ks$~uJFHc!tHW=zrkc)%Vb^O1wMi< z5;kJpG1v4QM;m`Y4_7L(h0Zb)^o(#R(tB5FyMRivM7OjasCWQ<_pGM!Jt5Y|N6r0J z6|*SAu^Xd99h_9zMDje|7VKcrROzR_1oKsZ)DGZ8Cx1t3ns-p4sM3LbJ$Cd7h7=}x-zF=C zRHS$$rO>AjEx2?}U@(R=MM45dUreTR&Kv!T6aa#;m^*!}-ibAYBOd>FT+^{{-;zy! zzV}$O+(yYTHUolzSm%sWYv$eiNA`P&1)hSQ`oescX`5F7^>Js)lxQv z-%9oxx9QJjrIH#9&QS@_fB#yqAnjiM_!ltgLzVc@4ba1PAnx)07xkJGfC~(F0kde& zWIzsdLV6DzbB!(*l|NH$vi4TG5c$jZ4?(4a|L&7|jRfr__LecHgyA(<$*)`Emfvz$ zTD>k(^mHs#5q?nd@MAnOdvwhp=&vQH47b0z{4TMwp#+Cqf4=-h@dejXEPzxh@pVHz zjhFRNVe0@_lYW`^xukXdr=cOTTT+8t_X)d3uUmn3xj`2e-n|4o(U-um^Fa|XD3_Bs zqyvD^xzhR7SgR3@WC>wWIE8ZvIXY>Wal2+A+!j5U#P>rIHE?O}xO>V--cn9n6(sB`Vy1qMRu$)nNx@&nP+nB_D}Y6S z0Cq-S3`a_AxX^-lP{oW?%YZUT=U{C}>;QD+z$I)3%CMnd%Q>a zZZ%$+ewbCoeb3$HndsQr1+Yiq+{$-u>lF(M;82yM+QCZP_4^P3>W-fx#G}ig_*RxV zOcLU1a(W4jV;})h-g~r6o(SXo#S#2#3hB{l_3NH|9ll*%@Lj?3$yhG((QP!=zu#{lGYaAWfR7c1b>Xts@TMo5;okiKhx#d$9h`t$ODG+TPoLtR zzx8137CQyKpYVXLmU=fhKt%v_te$E6Uf5T46W4|wC?_F>&s6-Yx$74nMi0%%FHp;T z5BQ_5QZxDh(uxP5y|J$CDpV05n{)vu>YopT9+w-`FliA{t8u)Q&yE(f7S}(us9NxA zGS*xIWM33*kJ1x@>ey{=X}AKH2u*mo9LBuQ6*2U`GJp;` z*%Axp#Ab-5oq>H>s2r-a=`TiCM}z)b`={hF(&p#lalqS9I5t8}PGLF^{g&-OW>o{O zaF8r)K;SOAxNkGvBUTd*dN~x)`WPspDPvbacq&?`Hw%JNVg& zxA@VPNnBV2P`x?nomvQQzMNs^81{(6{ov;3qXiDIsGpkXuiHWX)D z@x|e^+(f_*y0xG46>A0k;3fX8+{RXbuR$Z-^L@*b3~b!D@nQwoqPuO*9}9IGLH`oo zamX2avNw83L+}c`Uv;6}NC4sJ^pn4{Y}V^QZZU0}KKTe>C)flu3Wy>@F8YYQgqCd0 zAbgpC0@fK;YBrR$K#=&#}_933!5PI^RON z@gm6i?Manb&BEU`VjClK!CcsPGtYuyeIM_>iuaprhL|B6iQ_XMc*al)J+1t3yx#?T<6-XU zx>x-xPWx}eJHn6451Eoc+{$&|TK4Cje*!=5a zMNs$dVzj#kDPGB@c4-IJwSxo5DBH~{_L#`-F4 zub_H}R;k;-q?84!SOykcE@lqfI!#;?7V(kW$RbE_TpRbuy_4cRul5kFKf>wI8uf?v z`n8fFVV)lqAIAj@#u(7I*?WC@d!Hk#n?p(?Pmxh2^l>yJ0&lM+IlCM~pxSTN93!m_ z<}>9OsWaNC^Buga6a%Spi|tkkjDZn6s8&d0V%Pu-z+SJkG|yg;^UY6WqK|{D=Hz(K zoIlcQNthE-Ab?b_g&9v(r5@K&gu20GjMy>V=8qUx(-TS7NpDZmwQdJ+SQQp-Wug|E zI59R_c6lSMJj&e~7RrxkE>3`OixeO%ptYk5rIV;;N;fkcnna8((Vub#Slt4VmN*tU zj4@YJKWWAM0+o>}r(y;!;aVa2_<;dQ1d|lGGpimI~#??l;XBFq>O63Lp z220n2GW|VZJ8^|gS*P;^TV02o(ZzF)vsUWq1>(Cr{nnqT!j*c)^Yw7BYg39!{U#Nu zmrA}*-sz)X9OSCS>0qmy0Eb%#SNJvdz1FwG=SN%j6rRi0_Ic_Tq_{E7(;ry4_vWIc zDf7fK)R+FHWx#_lhO*z8q&}9H^PeBvcGy^{&Q!ap7dHAb>NIY)mK1A&y`Z5_zTyL1D@FFooEkflC zFw7IA-DPkub~|x47?f#jKYJit)!!dYXfG;TEK&Rx@i0}2m*VgMgz}W%VU^Z{0 z`AgsabI3GUkbD4GC1Tf0p{*a2rvP$DDX(XA*$Lp8=t8eH)P1J`wP9PtYsi`}ym3r( zO&hbMm0M~jmqQ6((%7S4-oh8mC6L3wqdew83;W31*kWCfP(gGLWTb7i1a{?gsX!C} zP_{rbdNFu73E$U;zhwQ4CmNB4WJEuE&_PpkH}~bi5A?!w#sEckZ;lbk>_OkKp77Plu7X z-isk}N83yRwZE``fB?iB^wYCHs92rrx=1@21NbRH-1IM!FI*Cm91besMc_)T9R^&U zH_)WO5N03D2oyNFt_{8bwy|Pj3kVY`8Dw8szwV!B4*XRX6Z^xP0ryuwPJBncMI1>X zz_k-VnmCdnG>*g*4fG;C9xO;`e$nS7u1CU7^UXlNqfhbyZL{z~&w#;ypXSSro{>Xv zjUkvxaskI?z*;*3vfPkNLw~{jNDnDe(u@MK`}mucm}wh?(5N}xgB_@mN)5j#z5hCt ze}zn10_f$HX0aH+fMxz|@A%`f6lU)DT$oaOfGVc}WIWIp=MIdPV1_ubLoJ6dSlQP! z4_^X4<#Tg83dQ1%5qT-^{`?P^bn_l9ro0MM8G;!hvOtitpfHyk0cY$vaTi5Qor zDMOpZ)A|Y~&{@!K_fAec4+{oI2n|P;oxn8Y#0a%J^u>AtSBR4uCHG%zeSr0sH zB=!!7W2+ICXP;$ccYu?lLr;!qU8KsptyuSe&QV3?NTVyQz|R3xgt?bP11(_sil!YD zkm^y}z9qy`#E9;r`J#(MnejDcut1{@Sh1A`HP*%Pd7P!$N2opzOE}jWp1vO{%n6A# zp)D!*M!$UHo&I2pks*gf2_0I}_}{|+ucfVnjKC5HuSG@2WfpFL8!cjpud;bxsd@XQ zgyjU1JuoHo0`mj>sRw`yas(w^Pe`L=8Ditr@ysnvRudw}svZ`EFc6FtyZ+*?{wpl_ zm7t46ku(<6GXz~gQOnOzd--hhGZ|2l*si;z@V~5rHEf&~S_w*;P0$a9)X7?!{+jG=v?DCi{A z;fHDt@3Hg}m0{9zo{)M{@t13N9$CrYi!;*2%AkU#gr`hxHETF`Odg$RgzEGKeryi9 zBNW3h;<0MSUwCY*jcAO|+Z8P)B*BDqoi`%t2$XS``|~)5LAw#6&Gr{kzNhI!lGP)f zb{gmRoeYrrXUZ64hFdiMD>N!P1qwT^{At8nKku%EF7b5Q9+L!43Wr)v^Q=SJ{!h38 zq|4}7iLw?lPGPrW+_a^oBC*FAkyK>4&tE^6!tCZvOs9PnWE4+VSR+Sq4S&uB^{%no zm>l3`_7b`RK@q+daEmJiwDkhlfILc84G!6fRhTI2Gyw^*FS~p@%7R3Z}o;-mijH;LQlwJ z>%cZN>L80t)jl2ozFnNDZ=^pY?4a_RApQdqd&9~1!f2W5?RQ{W;m7Cs@`*i7akf6W zpX?e$_Rf>ng*hP3>DY=%=@bg_Uw=!OAS=$lmjQfSbD#bnzWzKO%JzRB$7jZ1>|@^< z`;wjP%h>mjJ(4YCClwN7-`6b39!XN6g-Z4{Vibk!Tasn0*?muS->>(5-;dAl_jt@7 zq?x&{>wKQ)b32aXsq26M=zJ~(kxUIa`}04aBb;?n10PC-Y=mEUDrTP%eGap6LmS&v zy-DRkgCV$Yt{_ln*}94HXMBWxCi>hhS0ijgxplfv@+^d#s3V5wO{W7Cv^p zYbfnN(Dq#6b64i<&3H?ADgy=6gv%87L7P;H9C8Ar(@%qD6RKJyA>kaR%xw9M0;#`yjedQe|DV%1TFrj6_NtEh z655y^$wI&?-b&v}Nkz77Rz_vU*^L6SK@vnHx*ua=P%$Hp5e&f$^9b(q65p;2WVb@o z+wsMnsihcnLJ*GpA(Z9F53)J}YdHqU(r;#Q?hNs@K+MC_C(*s*#;ZcP1xRi`T-;fn zyZqNwSdsS%fFN`S#Ob)DDT-at;}OU~ZW}Z@RqF&*#8b9cu)Ge)+Hm0tEFWTjqj7z_ zK<@gYmHaJu{CYQ6YLc_QV)T(;7pn}QI^9bPzpdodnFN#vRBHhni@&xamjhq~LIETr z`D@JHJ`gvmUBoa)HIg`-W?9;)()O>0g4)l>_YB^pO0Ob)KLgnJ{OjZy&&@T{fiTf2 zs370mBVA6C>^~D(0YJnQIhXCFL4Gp8o{9!2W|~(DvkkOTTj;~x)!W-k;TJ@`TONFm zQhXrya~M=OK|X%F^Kf9~th6OLpm>)p;vr~7fvU~x=Q3AgDcDo4MRBAhr(fC-FfF%N zF1dX(;WZ9GXUj9;tFm?vGpWM$ydl#;bMf~<(|2Hh^7i`2pYiO%lQ7R){T{vSnxO;L zD>dJG07k7-KcUZW{3v*%6R6hk-fYFAP)u8G2--1~G~d|Wrl%fIykDuWmZ>GZPzN|U>(c7}O1{%NWU8VhdS@|_fIAZ+V>_Orp5A)=}G(^Pze(zW|C{h(fK z@cnW7)KTAO13FW(hAFV8zrnT=udG~1k#q)HPxsWG8ooAGp(0*Z?@){i4p@;pv`w-}b z=kCRjZLBzrsIN{wHsvd%DKFV&F0!J<{~<|D{>4%vxjDV1c0*QjM-c=vxeOa-yxGaz zj&9ChT90Cy6c-z)h4AiDx#SOZCar>^zs|Z**#(t{MOL!t56nP}pm0W*k~~-L3zU!r z@-l^0;e-4V_J6RaKRY7p9t7%ubjEhhQfX8%(C{uH*P2d4w~3w|*zZ*s19zQpafF-l zh{j}&^EE2PiQZ5KV3RCth6dd5}FL;V2w0t7_@6$9f zsi1!hG`?!DP_1ptw`VkdGiyEys5RTK9Tqlb3nSEifVQKCv<6bWB*}I$2Pw!%AHlHf za&VWEAvk>xy6hA11>tC5^AYrS)f+s$1rXii8tlqUzG*JkOlK@O z@hO<4`p)J8Su&$YDtU;M2M;Jw|&p-H;!srdRIa1VdyB}t|jpO zmBV?CJZ8w=r7?4IWZU3ijSqD8>66}u%R~5}_@tiK6+;N{Hz^e>dy|flHFksQeL9nl zfoRuy_koD3P8z!f8pWNCnX>T43n2|`T4W#vWQil!%R}?XKyb*-K)iIk!ZSFOL(6Rt zZU)(^*DB5nna*lP`X|>xh+p92rc~Bx?<|t_ zQz*85mjP)+aHuXJC+Kc?E~5$e$QFqJ{LtnMhQZdXlS3zB+x;?$kJSj;_}x=WqaT-( zb(EhGtC{HR6wURFJzZ}lQx|WG+T7;TDsQtz7r#giogc(Z?+3 z?_AcV*dK6jMl4>Vj?IV1U}kiFwCfEfEwN9wO`pY7a*Ivb;Dfbr`1`cjx_VP1I|;=@ zfYYOWF|Tu+FLAAHsr6?{G|A!03nRtIi~kAW1sS2v$h(flG)M$=^%Q84QIc`CX;i$~ zn@vm~6KOi~AEG(K_D~sXbcCa{%5p#ph|~{Hm6WhtBOG6tSnu1D=Z(Q2vZsV5Xz8jF zwGp-u4s3vj!V_$B=~vpbUX};&f#{3A2`}?SwPw zV`l9KG^`+77$u zn2zKuPP1tLcoU6)CF?KQ_sCe~NtDyRP)4OcK7OYmZ-JzL|AR<5q7j9vN{CpR-Ba`T z(Bb3L=ijp@^377Z(`lWi2s&-T(wOSNp44lJjiboD&8-^wnpgHi;stC1Nr<2KLss<2 zZO=O!6=yI*)R0FHirL$vi!|&$HVEzE<_~QklFh(@e^kJ~d*j2oBzj^!ExXSRDNh9_ zHH6&fzDIq%%lI~k_JNo42J~$=NH3x$`1i#{$wSYtMn`CU3X3tFjBf~FkW~pUKknN8 z_$~(jDrxpF)Wl+4vf@!^`$s&U^=fy}q@=cY>4{)|65B16&59Al=$mjO2^1gYV!JlKl!(m8Orb zMnjoGlHB77B!%c2I0K8UJ{~<3l#l!j&%&|?w-Vzi7jkSsRu$LN01abuk*uNKs;ccp zs&zVFjw}0Z0`r*!370+wm$%zRIqHt)@$vREhUWuu_McBA4JJwZmIHgNjvJ6mcwNo_ zyOmx-_0QUkMllt2^Bi+a*F4I$gEB={%Mo~eRZ=Cq#4^frzExVj5d5I-_}XYsgmoF} zMOt#8YLt@dm$+$83X>m{?Pj7V(8d-NL!g0vy!YqH-eqc;H-rFdp$SmX+k)X8Jz2c)8Dhbw0x8>D+eo*|R^_Awc zH9ETq-!>;wvaD;ThFJAqWGu_B4aLQ6XkPVDGRXFqcW~#{g~My2t9A{;ZUaa@`-xPk z{HXd_2d!DE;mzcZD$RV{9=(K}*RFsfiO`t62|}r*JURk&J32OAb=+*V9ISLKdume` z6SjN)+#^J08k$xDf;)G0EG)oP@l^44)#)rDW`urkYcm1L6NI2{Pee_ScBdv>JFTI{ zy`7I%LsC)gv(84|RyN;I`wr>d0?@M@#|zyvCmU-o7`&ufQlT7oRvyVL6vSoYKwK)x z%I+iM*$vPET@o!M=~?h3dQI*a57MklVVP~LCg~C=`?0XYhkWgHDn(T?+-T%olS9>o zUs)AlU#NK_`t+?PdLEd$To6+2FpnatxO|mYd#_+mUXKm#VsGFm#C#CUW@jr`k?@G1 ziK1LjwroURyHI&kGVv;p@jTR3BK&KE$7ya~$;C&4i*x`J`Q?Mvz14j)32LRzj>9PX zE7{Z}>^{saQgIKuSrTv2Po6W73G(kjm)6JnCL9t8yHrYM^!H_*e=SY;AhcWnD1^%Y zlxI|Uu5o?Wp->~*ppon9jel#JaT@<1Lg|WY!Ntd)rd4Af6zdl#-;qzCxoZlL$O`L< za~M=iSxjZP(q&33>`UWu7;_r*7EddA>CHH_)A=pXRiGRfVtoiFKhaTo8J#E5e zgst^8mM#eSI4vV?ZF<@4IZ~5sgW-tgx%SKNff5|(8HSWeyxeCxs!6j#-lzwW3mQz0 z#z4ujTrj@}dxT<^phMil#o2d%@QF!#kBWH+XC|=uGD!CjkrE}Q?-~43-pY^xmHs5& zUX`#mX<$zMf(klGQ^h-|-WpLk`YZRMl_`#4i#N^6M0a5jf-y*Voe+(Z3eVKryCMm} z8X0JhGOIDrOp$pKoN)!Gc$m4UL@4pamKmUHTv67pMGUa^E~|08wXcIscla5exv9F2 z0Q3smgISA;-{k}IZis!iu@ftxx(O+%vuhJKu`3=mJQf$e&s0z+JUIJ_3}Qj6qOY;{ z20$kFJw$0%2!&!eJF4pWSxo33Xv~=md?hPodzl)n$|gPx`X zeyLT#qoZAi4EIO(j`uZM*Ks(Bw(F}ZpP5#6tA05XEV4RfYaMBSK_bo5G!{7xL~0&7 zz_t}x#A=#5?FAYb?*&M#PInciq<3eMbSOr_ihf*v(ebg#XcD;H0FOC0dh-YO% zA{dycZpv%2w4G0Icz{Mh1eOtH%Cg4dfe5qkgJh63@cFbOV^=8v}{j z2!tbG&7xy!O}8JdVB!{OZuywLu#)c|(@}Sue5yHn$Q7qqsdir-dA&=t;Xam$`c8MA zdQJZUgtMxg#Ia)HS}$DulJ;R35ORrDSg6GlUi+pKL`NE{_%czf!>;SgH_lTS{8YG? z;9{qm29v@=sy;qXVN3!+Z1s`*T`XqC+J}t8iOyqR_92Rq3BnNlqp_+rVT*oM<#2aq zlHPmIfOA%OO4ni}kD8<4dvDqmJak8RabX-f3f<~mm(G&)gC^@3&`MH1Kf5--$kfE& zuxUJ6N?4cvU`}1ha=t=b!|4KdD{H6MskNgQ)W*;8c$b~QEU^8nNbT!S{mnj=v8G+{ zR#==)BKPcWqD?^P$KG@cz=4vZp3Zel(F_#%dSXhurQdpRh^Ir`Ri9u#0MozUutTKn6hiCr@+_^*Z&FmJn&OsCth)1vPAJvJuhvfVcuDuejC@YW+t18Vi8gYYM|4;+V;i%F836+8 zS53aK0u{ihd9qihUx?SLLsXP*A`7}Egx6V(qdASmiOe|gAopdrPpmS6OtrlU-U`$F z%I-ebck?)9p2+AiF`lfnL%wrcKuV2xv3xt@)F*M)cT;}cuGWQ{bE;icnx0f{d=vLC zXHOX0aHdH@)mEvE&#isyHxn9{izPLH&#f)@S&QQZ{`6D9&-OhiyBmuimfgKOVUg|1 z?n8ftzwIb~Pt7h(kp&d-2D8ik6TT8jIu${06I#(Vzl)Q5`ACEO-k?NeS?H%4M*Eje ztPb21kG2V~M~JEx-)OirJ1X%oidxoX0L~u}mS&)t`48Qsvoy{41_E_hd|)r3Rtt4(XMG1Da`BGK;t>YO-ubLJLfVTZmeD8|j^GA4 zxOh9iLWgWPvxP0PjY(BS{g$}s8X=oYE{)^s>A{7ZRy=uX;sCY)j=sA;0Hz3eFme}l z$3(3>7%0cth&-XIt6KPlPj{1vFW=@>kWh50Pge>nwWSk=l^G%~RwdUcJOWYkQ%;>Q zHs>@RL>v`aUf29-8+zF0Lp1Y(dJ4vHBVNSyD4R{c&Haj1Vyq-Jc;$IiT0^kF4I{O@AM)|Mt4+JZcBWA;_IbX z#?e?Ova+?Hy19chP0t5)3O%i2;#DZ-sp#Ot9EA_PGF073IhV@&<{wpJf5>hY6r*mg z$Fc=?f2!fJ$HN_e;L7b?%#6N#%;xr)8KOy8OI`pa!1uf8#4}s*g8j?iPSX$}=D$d%q8`S&seRx8r^>BMU7uC#_rDF^t806GV!&jH`tQ-{6 z$&1rCAn$d{fp9cW1cSKGS(_1{8cLNp4Geh;H^yp>X0)c+-2HANA$R5$ggnrbqQK-ZBcFC zbEGK|oLpS+fK1cpEck240U48+{oPMI*<+L=DZ@sxhSZCBzFNdv1q;F!uZcBLNdmc_ zYBFV0kLH~oZq+{f_$w2K`5N7|$60XguE&wwRoDy(tecTSfx#lnzproPr^EdY@3xRL zIPc=S_B}y~JXZ{n4*}gkt$2>1QjiMnlKnc=)&-FiBaT_XFS#?+yZj%VL9rk;{~J^c zE&>&!bCrQ;DSA`&eUAOu|M}b|^bYw%5To+!P0h9H176rZXWFj!M@wdW6AGX3ke$1hf*v0lq(jrN zL_93pSS<(2hVxZ|b~W-#WJpeK83^>L;X1lG0vJ+n`Wce*|B5ALY;CpcV{6RMwxru_ zJvly{3zu*o;*Wq`U9S8;UhSX4MI~=I4beGxMh2PryC*9G5uObMavoPd%1{!o1p0krteUr6ei!nH2uc8sqJX$N87nsu@5v$$^EKTCJ*UI7NbCFF902M z{;3Y)enU_&a)IB2M|o*pXw$#Rl1uqkGuc&TRypm(M(VGay56KHR_%m<{P#(n&fOG&UQ5A=*x$S|Ju61olV0z zGc4zaUhJ##swRO)Rq|F^G=gDxRyTKz-Q|ut_X^Oe{w0}**Dhmrig5JA#tFrsv;tVa z5#I~9XJS+g#5DwM0o0mw?Nw6;>7cX|@Qq?Yo6fy`DUE>gsR00^F9b+Foy`yce5MzD zq>QQ(js256)>@RK;<9-bdI}U%ca5)TFI9FQ@0@UvYd88loRAq7g+0^*(4eEah4T&` z^;PbZ)s$Ipn~VcFvNuSgX|H?UicHUaa@YE z6p<+d{Sv!rb`V1OC^eI919RJ#t#+e&kFCKhg1C@B_jRHyZA^Of#pNX12N$w0O3>F3 zQ4@xp9!|Z;HFo^Yb-nDh=LJ6%xt$?XB0?$9^tULSJuy-=%)28&H%Z&Th%*|@<6yq` z;Xl;MG%{$mXlx4u7W2+H+e(piQ=I@Vo@0z`ADQX1bfUj?+r}p)8EcE=+5jbYE#u86 zx#ZZGN1oa_k7<5ns$qYQ)XV`?0-{|W&`n{IR#ui~!%JSc_SV$TvAGw`rE^A9!@aVV z_zw8{C;;frVAOv=a!w_oq}AMt=1eQ`$}7BsA25MM7BwSniM?wF$-ADR#^XnJV*cnp z8;#5QWpzT1h`I1BukB%mq#C%`w0L#0;{ zbCx1DuZ6BwGeBC?WDO`oD0v><+uz6QNa9nfviN}48}NZF_GKJLI2+ymMvsNwsi}zg zp@WmJ9SP{7%+Su*u#T9CE?mvJ_~;)475?C4(40^+o^Dhqk*3}OCj>4Y#Wj$MTHM7m z`{n>I0r-)?*L$i7;GFERfZIha3~K5*ICmQ!u0KU)75aVzGcA7J0lnx?x_ocA~p)IrB=~7L=TWvzBt#<0iAwV@LULRe*?)HAMzrf>R{nujLb7Xwn7TY?# zPlJIAccu&IP5U+c&`J1J6yS!7cg8+OWb%MwwSURSCxl%=bs<`n&0aS_u`|2-2^`OV zPc6OyxwWSz@I@hgZG#zfKlEF}fCkv8ok0UxQ2HA=DG8ARAg;jEZ2H6QC@H-lr!QK? zub~eQm;OuNYA>+!II~ibSVfe0@nWtW&Cp%PYsG9=e)MQKY|M7VOEUP#q!Jng?@rvh za&$Z(J4aeni{u+zy&vSMZ~h-diJ3J_M=7fR`*TWrx!P!f3-E|eJk`Dq&WHh2+?!@K zO1SuQ;@AV=za5!MJgM@k+p#S_0dojPXPPj-KvnP@%o(b7XhVFPo^zxTaCGwf_VCh? zD%hv%_~{|n(u=VIOg9hE^X%LjG(Rnn!~38=VqE8a`FR&P_D+xnE8MPf!G{|FV&ZzZ zv{RDGv@iUqJggfG2b%op5kgC#&2|Ll>deWI-=TL9L&SM$rY#U{(9m@qPaWUtG00rm zt3%xGJL9Z@wox=bb*i}DMvZ<*&0{g~JSxp%&ojzAi7VUX*L?-&JuHqcH-Af3vcZ0_ ze&3)BG#^u|lemO;|T*9^((ll(hVcZJOj_Nl=Lx5jL*v++a z0b1xrXds^(ssu#oZ+;k%d+RT?SeUGR4H(_8zCc|uAX^pM{A3O^0Ud-Nfi$EwI8ZRR z=}a9jUGZUX0$+bTU*XagEy1&Wy~i-ig@2vZ#`r{_Mb$M-8CY8C(o+`S>6%~B@hnOe znFxQTirlI+-gt4>I-jrKJZh9tIVA8X<5846izij%>Qh(#VLUqOfc41N$R(_A{{F-&Ex75+^5(HKDQkOw~=$wdy>KbX)n!XPoj8 z0QkK~$G0XrBX*AfFJaBTjq%BR9_c#0&F(k(O_RSfI!AN{G*(_%Lowmu!yFbWuc?)XkkXHwD1Xz5 z=GDGsV(4vsq0b|6v^}?>ci5p)NBAvYw%SLCzQr{m^*7bxNBF3x;*UaV?ZVmRcDJ_K z_1CFHwK;Fs2j#9s>*Eyj$Tf=nsn0knA)~xo831|~F2F@NQxSw4y-)O1$rP&Z8Z>R~ zT0pxvLnOc1&9(0lzh^ogIG3EBm1=P1o_6i1)(3ZH-Vgv|aOkw(5&K?xnO8SmWYnB0 zh?3H~qTAYR#5|_$K-T{mfKH-5PW3n;K%rdly-}v5}gm9nNyX9-24c`2w~=}{@XvlrZRlhdB@+* zKtpo8fAeFZ(zn`;ryc;%eTD+0AzUHE0`$?kN?q0hCA!!|uw-JeRQrlw2kj7J_J@GJ zMw(}KrGlA|fNzb$RTUWBquYg#1s^7&dx+eqr&$;un16STx10w!xIUZ6B0@Xy21={0 zc4c7;fhH}6hi9aV*AAi@7Tlwy-l8-&FY|q1_F>%iyQePBf%7NTzbao&l=Pqh-ebSs z4w@@Cc`chR0Uv|DA4|UgD#BYj2UO&}0PbB!HQn{?h0xQ$txt@%Z(Jl+s3v6V8LIfC zS-eRp3*;%R+LkCpC&?6P&IaXpQ8Wt?K2=KPlZ@dj3~Y@V*gAtMMp7utmZ@^49zA=v zmLQxKAn0Jp^JNq;u%d&QW1w`T65km>oOBlS(Iv5%QuHH23PUz^pTwSzX^;X+<+ip| zz6R560$V2XG0ZSYBC~zPuMJA$N65#L{vXc$+~{I&0##E0Eckdtp+e6VR>{Mhtu`qL z9UHW^NC({DSc&{z=?);Orm)3H;hbw$XN%G%cjg=uyiN@yy? zc_IJ_Fp=j+aTXUZE&Wos$zs3lB*euTr$-qLxrkpz9sHbwgM+9nee(9eY0TWM`f)8P zf1Az8mcGXCYqh)A*W`Y!y!v9-ix++e&E|m?lB^MI*JmLi2hr%v ze0(Zn%J4_tIf6{3B{vgoXh~n!mrU0Y{vsdAcA%gM)A!YmyufZ#R~Cv_<{kIJhabBp z@P-2>CioM`tMAOFV2$_P5)NlncYLD#6V=iLnG`Y0IjCBwosFz0)EbdvB)Iv|#)? zh(sDLBtf-?Q9AApg z(P};JEoD`(J$IV9Et)Senjz$U$4EDBsSu4o8BrI z^2TT3g@dSH)xrN7CWNgce(YDKcQ0^^5^TVkJ)R`MCJYtd}fn?b+Rf7`A(MO&53 zg*c2R<`|P1&=e?#xK4M*eujE6pCrU5cASV)R&9VYEn(+*pfNvM+Q(-du-HKWX2(FE z=)Jc~w01|0HN>d}ItCGXK-+^FijshSZqI>dOe5smscdYo&K0|1sg}1yi7GN7WRM#z zi6m??LgRYH9+4;H_az#*6KiEpyFcZ{W7om#OZnSSBIWU?VhT#mK+Z&X)^UU ziYlQ}@j((bok*N%yX`6kOWnV&e$!MB9U@U~x`}*gJ}jvyLrJjD@Nj z83z03e4DxOLwjd-Fs|pVB?1dE;_ND0ZgDnn!RZph*YJk+5A_t&bm58gx2b5o@G;;# z!dvl-{z3i?Z-yWGc-lT9XC&1bdZ)E9?%myaRi3Nc6sF<6u9&B=)WX1?FJ0<<%apmmgwhw`OT`c)zG5WsN@_wJ3B6HCYm1Uts@43uqtOPQxiJCBShF-iN$Z! z(9xZn=1SuHMS_tx{sLSvGkJ*E42q-L_aN%E8=@EbTGsv$fBS~jo5VW__*Ra^beIPe z-xfA_+KH%CS_LA#$v)Oh#@-;#qY_hKY1g+1eHn4ezWW$W<+fW~+g4|?LQJ|*psK!s zAmJ`{hn+X4eS9fJ{+DP_$7~n6lHE3{zBM|MU*96TDn6C%%8Ow^e->@)!KWH-(YMLg z5Wc&yUUavlbf2(}&6^#U|CeDv`fM5dC2*Y@;(t(kx0YASO z?kiEs$XZoy^g_e^KBqSv6BRV8VODQoH{Js%e_>%^Z7B{xE{JB%VJ0N>@yn`(9h0mWXo&SX~<8x~0&{unQX18G%jll`9~ib)VE1lKsmqce82c5loWo_|&y zb)a_MfrGbBW;^wsij|!M*+aMC$P3f&qdJ)Atg)B*KaJR1!>6u?y!Dwqx_#%qC~ZgCLw)DS^90UF~qIVvP=Jer{_LR2wxZseixPny)8gm&)zV%l4 zA3?*BMoyP^etZ@qi64whkA25%W@lwxYO_r+VFnJEa)VshT?&ihJ(9Z=1g$I^mN##r zi4O@6!pYFG_}G$C_PAtZqt(4$=@!a-<9ykQJ<3d?{^t>tuwy6AH1=K_{)L(aHE$ah zI352s2LGb!93gc?F=O*4Bk`Sl+3D6os+A)Mb-uFfOiNkG5|e5JQlnUH(P8B!<`tf& z3H4=%J7kQ`O_B*^vwl>8p|H1Jkml%Q4=PKVXPo2eGbZOW;k3RcL^f^JL^|m=nJrP? z@VF*kw{JBCgs){EKjWTypxhau${<6dvDA5)YEhM?9bNz0fr3RjL>5-0E1fQwD5D`| z>95{0gv*P1tlFD;@=%^~lC!d4^EM~S-hHGcDv#Ho%2?ZRi^h9t3Au|m{uFZ+Ogu$0 z)JeWk$Dx2(LPYFBG&h)2_0jP#CQHIXL7Zo-d!UpFw;&q~mlVyXRxe!~Kki=7kGoFZ zbO`v(GuH6bqAHw5u^<<0btY5&h!G zDj0*>GF#lDeeJc+y!F!4esCGiamJ`eMl=1GcbuDUhWWCTWDB#is#GZGKVIQ6+K@{Z zsv?VBT4rI(mKC-O{glgrOXsRTQ3B_BrTZy?inmaEbvuR}c*!@z)t6c-`NYJK`y?|- z_^Cc_murx1j!1nr1Zq#HwTCK^#w=SQ%@^sx?zUPJ8nsI|M&ZB_bD{X4*_~1Virj~s zuL+JA;kS?Ge-%Te5SsyqIeEn~Xjq95d8jX4#3I36ML9RGU}?=nY76);4XA}`_)pee zCAnF|g(8(2vSNsk=1o+F65nU!uP@>6a@KS(GsBEjOHD^F2y%yOF+U=zbkFCFgUaIK zo=27=1kZC5ccwu357H?he6Y)^JKXN8#nh1*#D3?+kaS;bx1;tW#8}L~f6OC%#oUg^ zxipR?IuRs{i0LjOWGsFhODcPHPY)HC`9SoAnU58$%^2QwMTcC0EC7MQ_|@Fes30=u z?nhZ*Wv_|}^B-K8m2JG?E2Tk!JBoCHWHe)-x>!AT<3=8678SN@r}Pta2rC!L;Cs9E zY7)uC-8%R!SKDjG*{X)+^DsO@+qb^eniOLCY972ia%<=7ACdGl`aKW7#w4gXq&BG0TYQW#n$v^oJ~e&m0z-E1_m>c+_kXnLii&&NUARyU!|!jz&I^@J7VF zk6cZwzgeBZ+D znk(d$I(LdKcepP_a5|8(D)t5UVI?!4kC_f7bb)i0Nf9b^u{gJb3HrfMNS;POrpC8f z4UdG{tgTgph;EyJOf*x{c#MD9uvX4O31N?+CFX9Sq9CDm^YM7{s`-G#nz;t4?qdaM zjlvA)%M#Pb?jgcBE*jD~E|EPE)4}f`xrY`My03AgdgQ5d3GYwqp%$r{`SvmDRPtJH$zE^L%oU=fMYiSm9FhGW`x6&{|h9u>+IsUn? zz|Y~XRK?Kg+&HW7-yv-=2W2s|n4`e3UsDr4A2oV$P-i9k-@)!b1K&SCqrKp65MyR{ zat#Skt1&Z_2{IIOA20pifzm(YrXgl%**&_?yv$5Y z2@Ao@7}j*m8nxJ`V}Xim1UlxTbdR|%ip``_gJ&>RG>IwdH$M<=S z?dYwF770kpJFf1s|-xzaNZH`7kh`9R>stYO1R%9;J+u5lOMYh9ZZy zZ7*HA1e6d|WMt?GAd-@jBY5s(89RS64Jp;)>S`QlJ%N;yk&$t9bd-mOCy?dkt5?yn zh@^VqOE0GvjSchZQgr`&yE|GCN`>O`wkMOp&f47AX#^HxoM=jHo?cq&B+OJT_}kJk zV?@mcd0AOEPLB4^#>qF{IRsM#e*E}>kB>hBhx`ij@bI9grw4}fqW1(Ot_2312VB`PW^ zAVAbIzPmPY8x*l$zI+L|S}knF1TC`gzc=E)Euo?aWCzQx{gi*=95XdY$|*qd6B855 z-`@4SaDiOv1n7z9fl;=g5Y^Do(D(5pB|Q}ZhFQk@jHCI;sA#g_zYf9y`@N`Lnd48bTbFKjFJrp4;jY7(jJ91|%a2cIB#yie_yhBBJ>Ccqxd^MaSI# z*G?^NL4qyalCO6m>g>-<0^utwE60bw03VK5TAB{g*VhNcQ{I4L5e5Sh;Or)9a2;T4 z(LseoO+W&5&F5_X-w(!(0c?6VhVSVw&el9!OAm4_bf8Fu;!&vT;q&LurvOy~48$Cs zn!1v$V_-lUa>|pcASb8v`B(*5HWydhr%zN_$w_&SYMv$3)Fuym+C$6c)7;%Y%N+Ax$WC?URP$+S(c$1H%Z&1UKT$pvO~S z3xn?8h!hsAGLW_BD8-nu0#Enn>kKI?`jS3Bsmx${Unyp@TWrR<;dO(8;FG=@9-(Lr zjO3q3+1m@~gKI`#zpL;6u{S1)@T#gRP`UveJ=p!=J|?{|QPJms&C+ahMFd`PsGZDo z1E}@R&N^CJegzfBwo9mMRB7%!+;k_Pm?oa~=8fDgalq=>aC^H(CDT;KALGVoAR&on9s^RK5i0nR9lcae&o z(b>aF&W61?eD_(3p`|M`rmPuz!d$oPVefq|DD7Xje);Ts zpB1To_;c%-Xn%i++0)FdETSzLDXDE7ZV8OqP?~KP2?v!3uICU^2!Ii!b*9Az`+*`S%X#*-0l8}(#;YEI5%V7O$o1>Me14Eh7uXd+m8&7va>_%As z?_hHyIy(U7HH=ArKhN+>$nK9Hqj%X&FzwQaub+YJc>RwJUB&Z zOw+4Vi{1MLFzvse+Sw-hxbtc;#2uAZRK!k6 z$svb??F1|j>24x=|1x%LAY$kv0jlKqtB+!p?Aei6fGXx8F{qwpGUaO&qsf5lpoyS& zqRty{imRMGxNs(_>Q}Em_VheuF+$?*Ef%2Ozk0k<~{;cXQdq7SF%yC5Yk{p|Uq`>+uA#CByisu7y|lx$Vd-^p6e|VL}{2cs)}gn8Ex>bf|1@c zd6*cq;@S1xs_SsOdtxo)69zPXGC|U;FnLH{M`CA!1nhe8iu<&;uY^+8Fmdn2JUBw9!e%6CXWA1{O3=_ zT6VBFAI~lUjSOg?mpOkC2(%)}w5R87<)UW_IZu2Wn?iScQC_3D+Z$KDCpf{8vJ zRuvT$<3B-bd$_#3;RB`pZh) z(lGwakXNTnisxDG|DTr`GAjN;fSHkkRGbQ3`yQvzR0>5a43IwL1VuKq-W&z~9RQGU zKfe(b6$PAF8-W;LV$|=K3J)EFAR~JH6v#)p3>1>xI0ZUz)U2$@A$WWj@|S>m7NCc_ zpNF6O<8;$7lA3V0pfpWdwZNNei|)GPA-=K;~Fu% zL+t107bgGSc>!SMHXhEll&p1I1v@0pUn&l+>e?*9H0Apc}O{4OH2q@YOB zHDxGPT3R|hJRHOg`}_NQh_NvKrH9M>!Fk!)ufZw-(Fc2K$j~uxa24^@Dxm&R`{D(N zWo*%COk-o{%3KbXC<8kEutJ^f>or(}Kl@-2kS0Sd9s9xgiU=SD%1>zufeCX@&p4Z2 zx^(bq`of_|%!$I1nX{voxp~%}00}qN9)Va6b&!9s%x;v#KQ~A|aF-tu#@v@FNBP%n zRB%8mCEXDT!+-2^+uz@Rs0i5zIy$ukkQK<%NDY@K#C4#sBfjV3$M@I2Ur<#I-xNDG z4np_51IrE62vDynf(w=JysfK~@jnF|tQ`H(O;U_uq@kE=@Vs(vE?eAg)fx*GV zH({YfOr%h^eV`k`C3p;G(e2?%UU-=1d-sV~=QX7dPW5o$ZqB!>9uN?axvb@bsw&!v z%Xr%P?&=qb-dAoT0pB==PGnwxo^o5v%gHOs$>TGS5#^(xi0v_nPo1UmV+jsxu!l6C zm@wdJ+(wr=w8j59-lcBBq##neK9KLf9m*>n`^S%D9>4ZlHe(k#j-{0exPJXMkX)jy zWhZH9ZB^62HHGYNf;n?-T3^yR0t+0U0iy!+QCkj> zO7_uFh{Kce? zob1}=@%xOx35|a490c}Xn2IhboD>tC`u;QWsV@2n5&Ezw&-A@G&GQBp2E5Jd*SDyt zsZ1^;83kvi1)K)AgKfQ0Mu>;8Ct?t@$Ka;1dAS0iZ{O5J{et^N<>mc92E}x07B8a1K#}U+ZSo(&Ok}e7|vgkya+7q>>K3A`v z2Pmbo{nal|^Ne|<>O-t_zW zJ|shBW;E3W^T>XK?Dsp+>f9hzQ&)VFPkr{g6by#z_8zTW0Pwcyrm#KSOhbd>Q8bS| z&~e8t1M^j5VCOzePDoID$?i#mjw;&R^w%I$%V!_j*x8}I+~5FV0P|N3@FNx=msJl_ zV~X88J;wnpcLc%&9gG1z%;7LyYZLU>l(x>DTN}QspW3D-K4(oHlkJaR_x|HilM69V zVo6SJ43o5rglqft%s8Zf6&Y`yy8Q06IR>rBL+k=+N4RfSApT_1#SS1FFLo%j>`(X| ztK&g6)_-72+5kEzRrUnv>yZ%=$ptJS1Ad7?WMyU16RCa8h|QF7NMK?C6ii5KhEWjT zSz$|C;96sji;F|^xkbyfv9bA{#>%O_R!&`lL#>BZY){_p5|>S0;k&>d4V>!P$rc{W zjS+^0u5Jv}*$gz_E;0EkVyEJ_*H>``QV1BGmo>Z-ZJ!zvikX>3| zPc_7Q;DxT`?Hx0+2hBb{qr&z|wwe>Xw>KFMXEWFC$eZjuKjurJ`a4M0BSPGUjlJBu zHt~%1CZ6q^z&Rj?8oe9_1RH^mc|?YOh#QsrZ4Q_NBCuyd7g^GOyN69^YXUS%7$}TIgoUF`pt+DV z>U!meu2(8KP_idrq^_cb1XbnfzLU$X)#1nb1L)E&xlnUS-rIj?7gSgtm>8Y`&bP%I zBSNoGpct~a9PI(p_COj9cYYNW6%Nx(k&m&pf8P}h96J1vwzfZJBd-ZLxZ}3JLAAYe zBb(J4^d``IsBO&4X5Z7g>S{FOwQ!JbCJ#@y$5R)*NiOa$ec|vPiP;SU;t$>XNxr8# zTMD6{x}UvQFx|N#>N!gE*M5=`gGDeF8`?~rdk>>nS2}4MV;8yn7C;M!D7mzJ&!O=Y zzUHS$BQd#T%-%0msXRHm%Gtfrq9oEVOlKi5K{rdp?wt1g^j=4<>csyv+DLmzl!W0<2J^Fb=TE+j@B}nnFY~u$AZveAyW?X1!S{m zj|=$te=1p6sc=v(sHotte~3ncWTyTU1UjWj2CXvQW=PVPq>%LKO0n~)xwrh1Oj{=G_6un|Js zX2auqRrYvjJq$=+NZ2@%qacrTVeTktr&(hEek8>+NTequ#gKIupS4*TGdnvA1f8%1SlOgM+4I7YoYG`StFw2k+o~AonshYBV;f8W- zQe5~PyF zrZYv@3^bQTZR?RtOrY47&@l<1$u)=HKsC$z9NUl(wB;B3*lFG56F3YG{rx+Dy8?8yRB`M>os^)m2I^lU1cih5*gYaJ702vy z4omd{rOC{lm3C2eXtF z%$84P#I!g5>~~Bj(caPzVT(lMPVEdjZD?eqet*vL>Q$bUW(X$d5^syDyCI63+qolw z7Iz%G8#eRFl7(e8u-2U{o$Rk11Oum`7OQjn6y{r0e^2{c=xF>Mhz{L(z_1>J(BRGS z{aN)f9Si})OYvN0{Mqs`5kU8}@t0N%7&Pn-jV6FdsOD;urT(o#iB*-WnQ4Eoa0*yq z(F@F$CU!MWTWeqvFxMitbkg#;5Wm>(jevIIwa4D$8+h}-1z6&T!cW0&FzU7V_+2zt zeYGj2P$S{*(?njix#sb4rZx5L?VmU27I(mqWKB(nUjkSDTqAd}Bv>76uBoQ#|1tSs=3#sw`o*q50S0^;Q+! z^MtHXCdi5ZDuZ*M9YD;?iP%#wg_qJ&^KD6pnBRu+`$Nqsah_|+o-3#qyu7Nas-SFF z$rN+^*ZGgWLp^=}O=Enm%I^()W>}o_osGt_P?dV0RmO6`}pVRcveeTp-bDX z|9zAoHwKNqPXDp`*2@K62<=6euYdluV+c-_1KtlO|1$PG<~XkMMa}-N+{w=i`E{C+kufMr`slF9QRnD) zS@P^F(B|+y;rmHUG9#@YKuo;=+{-^7(eYVp;>4dPH((mMp?+Ke3fa zd=eudB>dW7{?xrc=%~`1+T!;{rgCeB!+(X*e|34r)}M4Tg)x$Pr1h5>j2WOu;J)7v zE<58Dp7+QGRY__6|BtS>fU2tN+J+C^-QA(2A|TxYf^;_`A>AE^?gnWA1!)QCE@_k3KhJM+f&{`)InNwqI0bo41MSOw8d2zhf3H0*FC2~vf`<=Uv}!1#fRY>+g^tah z$NCbO7fAibu+SqJAP9f__`8u?&*aSK-Dmiye@-FoQL=C*)WT3keE_2{KvanTaTCDJ z&dP$N!By9L3S9pzpRYNzp`jrFW1k&c{O;O@+`ajCkC;J0Q6VcBt4g@Kx_Wyz<4cKS z{d3=f0JgR6u%h_SyFl$z+5R5QJvlj%)8!*3CNhs!N%(h1WsP8CegP2?69Z`o6CYp0 zi2ZWs)1#?;BoJnOq8O?E@w(2?>>w2t6%8%To!wn-XZ&=be>amerZ6sL_cwHQ(E9qi zS+ID*Qy2t>U4INl&~eHCVu(=K!_T4H(ZPy1!6YOWiZ|3HqT>GmUSQa9S&$;wa^I>J zMtESFhxEzFSs~ft>1w|({*!CcW&sF}yZh2ql@Zm>b2WXS5GY@j!hyWSd?FxmLLP(! z0?;h4IadxS@Xd;Y_`i=p0u~c4KUe-VWLPQ(>ge*arm|8+CH|3{{Bx}Q9}OR+C;HPG z9R+|Au4+Cv7Rex`mC9!d>K1*f;v^g|bWr=w25k#rV`V*9s$u}p1_Gsvf4MUSHdr7Q zAqLSxy{Y)({yQe)?@|dj0Rd3fVr+%jpAX|(k8?CKrmb^1S!L#?A&&vM8byMxtE&T$ zds$Ex4nw%;Klbh`_43R-85bCc+@?X6R#qev^E{eQH>6AT2-|Gz&5BYg%iH|^ z@d4}o34hV2^r3P)ULdf$5jsn6K-VMhI+a|`mcX*3={?` z3u%Htqlse@JdeN5ihWGbVn4ge{fSg|gj;83cwWD*rAJ$VuX6m&afvjZ!!St&B@h5A zEH19Bs2(1hVnF|Qq5k6=04xIDX|q@({&A6r`Jj}Q#{hbd+Zj2%WflpM59E30iHcSS zBfNjcL;3Gcd=E`NAW()x`LdW70lcd9ukCy#4MzF+ZggwMkxPr!%vy!e}5fz2htw1`)6Ok|NCP9^&15b;19xWAe0e_!uk?@sAE`}p`T`ltUn%Kz7`RDK2wg_chk zvshuX##&U9oGt%7pikGy(uD;eHJ9B<7C?B}+A3^hWVDYRHTv{n86Sg!_gsJXOxAZ; zXlQ6Ze}9V!;=a&a8H;AaEH$qm|3EK)?@xFE2^XM!0Wlg-_haYaFb51o2S#V?ED~rx zo#gx^;I4Nz21XvAUzQzaS$X+yVDRT!GLz|lGtpY_vMMWI2?m@I|F50+AI}<$jFgj?2aKe>2YQ?U>}VNOa$4H$&CO#7 z1Tf1cCMH$H)3dW$h_^<7YcViTD5@@&{j-s?G#_``C!zl$O8#RzxYOGL`l%ry2tPA3 zGdFilaWQJs?(VLT=he~b&+vE#dA;)Yff*SY^Hef#-}?FaQPa>UKF)G`^JXH9=FZ8{ zF(Ned<7{QYI+q`SF9Tg|X8<(;K&I2v)7$f{i#)CC0Jhl`FmLM19orIFiDoZpQ#EWD zvi-<90AMWC+8J5RO_m9gn*p<$8;O^_;G3(Kv8}$bp-OSjlQJ3oSdv+U`k2j#jJ%bM3VEB?~eYf zM}KEIUA6+W$a)Lh)yHhF+Y7Iov)D?sUl;u}PZuVp8a_e;0R~+2WArQNB!58$-@WeA ztvzu?hu55pHzEIcng2NbQo;nlTo1@-t_;BVCnYArT@x^C906_os2telPqnMe0o95S z1}d;=w!T7#Gv;^Mvn!&M%_`y zCMKf0e!dEt1a^uhkI&Q$6_&UeO89j+*TtaCy@iL->#yl+97vWA7bVlbw1I@|3ux{4DCWqz&je-(jh_MXjicdiW@Z)^eV_YtU_Z5kVq#;VAYRF^A7G%+ z$oUDQAZc7yexHOG7`A{;|Jm8u)2v`z=ra7*JUrRK=etwE!NDjqU;%#q7s~s850=j_Ut|0~wm3Kn8_Xa`efu~Z;%KQG_wN2a z`~LFm47U=}o&zvdzy^$uk7r_H!XV>414erE5Q8i&Ez5!p0L(?<{ww!7s_-Tls8lC> z;bXuvU2R2zjbh{jS_J5~dtmsm=vzY#xb-(Uql$63f7}-_p>NlFkeNYV+=C{Div;M!pZ$mveBVoSJSN{LU zQvES&y-1WgLqI!Jw2WrVSc>{vVAuooL5n35Kp#^b2ysE_)Y(fQuF+_tNn)NNJo8zZ zjZRg0v=?EHQnL^0g5*O@u^=HL_$I$t_h&e^a1PencWcD8J_*Vl$Pj^ z^i~)Ji5)fu|1)mb|DlQEq%QNgw1zz+5IxIk1LO%>)t1j{ubFHx(nLOfEKni)fc@qb zRSsfTo)k2y45%H->*0Fq7c4L|Z20!}>Z(|~hLws6N*dZg^a_~!RK8*`@-wAvvilp<1K?=ie28Oy zOfQ7JFv04AI_DAsg8XNR4G>dfM8QXs@GrLY=i?A_`i`!~>5BL) zHexHO(q%X+xzyFx^3wu%k| zZL4T#3X>DSTau3(KI;W^BcBDT0K!wM`L9cgp#x1QiFg}|c>C^2)_c&>^Ir7MSkTa; z0x9}}KxjfbY-J2+^z@B{M5x}KZU19;x5jh4P-G_|RM2~`7gpd8Uazlcg4uU8G&DkV zsji~SV1(I0i06hM!BAO%omaSLs^OKo82Wn(Qy-ynlV#GVf6~vV)eecm(Fm*f;zBCY;DBP^`f ztKngXFNYfqM2&+F?7GkK!itI`U6CYo9fz{X>>|=O$dDWC@9(dmpp-)K1mBtAJ>KAsqXOX{-?j(aes=b)AW)=P>&*(~lXY~W z8D4A|NJwHRh8%9LcjDFwh)eRnc32ffS=y9)N4Bn(f9XG*DLN7j=>^02)JmGXlTI~B$xA%#O`Nn zxL&9df+WwO3!MT02aj`bw;F@^bM4^ZyG}Nn1&EzJKUNxh1^hS)0U)&>afhBBY0`wh z7}@@#kmn+k=Ix)zI5Gru7aK=1;>e@=6g*wSmLVDJq0mqtNRZ7t(F)1Sy#z6iUBcea z)Rzp!D8dY|r2ab0)r%%3+$JGxm7hE+H#rW4Un(g0T2pGeB+~RYOlEZKuWwUj*geYBL=t=5U}cB|Xd;Yrk{7mlV8js?9JSM%zX zgxSA`o3h%>)iSM5Hl3Wj>^6y#8;q*ssZ04iQwEzupVuuAA#|Z`d-$;MZ75~_n;4UB zih9O|xVU%zT6lQ)Px70K{i6AM3Qiz?)vX}|)mj*OhyY5IckkZC(hC1ykHHUgk_dn_ z1#X4F=s)GtkiRE1D+o4KfV7K$n`DDfu8k41|Ok0Yd(6q z={wnX$3wldql+VhKk9C;o&nOkFD_PdK0Dhy8gR69Lwy5$jfYo#rSBwzV0zY=;{hEu zWsIuZM>jpz6AcxS;PAuGiIG)1LCT6liFk?K=ovQ~w=AK@(itA`vZ*}T?;6y)zI9C} z_~Vl0MWx>w?LJ&3!xAE)AMkuiPv$y|)LgiARE%ZU8r?r$>&A-GkJ!X0$jY!86;Bbt zb@MU=#Y8M)=zDMQ!P7FJObF@4NoqXV!C@pIUf=Hg_$B6X-wz)lQKoNS9j{IB%hyQ{ zjWfdp)BK506vSI6I*b=rHAAkB*`L3$CVTzT=D}``k7CB7>L^BAWB|bswbdE+?#I6I z+SG{6YUK-U?^*ASJEtDYu7(=2WPXRn(9pyCi z`bU5H${x7mS0`+sygyjbtSIO$&H?@8r+5*bM~^Mche)|8H$@ILVSaW#H>$+(A<&O| zw=SOGe)d|n(W_~?FwQ^j-=CixuCzzswjDJs{BVM_W_y_d zvzOBNzfeO5!NVge2KqeT(VtkLXZY6D%`dusBV$^sHKQ?@%KcNFJ{YQU+6&&X!AoGh zw5gj?-r8Ajd*8$EMYNWyN1+yffE32_= z7NzsB?y4Nn57?7fR>gB@rVU$GZbS@f_9{ED&{QSU}#LGQ!FTy5> zcDM{Nhc2%TMUbACmFF2J-3vMnfw|eqohJDu_u@WfF4g=a!1+E5gi)-%$NsRZs`^`E zKK#b3cQP{%aZQHih5r3X9>@^raAP=k5jW{(hD`rIt{LC zx2i(g8k)s-7h)FL+FnE*2#((}n{VN&-`$<+%V<}fZ#2pH>-(qg%`f@P*xmPL_;{A( zm-vvNz5U|3ogWgs1ThuB)@-@kQ3337FVobz^7d{t`Rh8LE&Yu8>z3mKe#`Ax^TZ_W zGMjE7{Paga-{mlzHPhzPE%M)=spaO3;0su?&clYt5>;i>ZZIp^>}}2Y$%Xh^o4R+E`^!L6+%h`R1mvDd zcr@Z1ei&O<*IJb#(@j*&Thpg7SUB%7)Edi+ZvPjL&-ZU#wDS3WYwchxu^}(ARtMdinM88uua)%dG0fUdwacq9TnnI~Qf~b&nNiomI zfA$c?;_>5Ug>jK;f;uUmEwXnT&bO%Q@~TfIS;sU->u@_6l$R)`VcCFQ@zmGD|!6+H<}FD6y5F_9aT3o8um1~hmF3sJT97h0m0 zt8*00XJ!wLbyYtq><1C_o4xL>jaBI?FIW#oFY3nE$LF{Y7VGh$wGC<(Gw_H&I`ip< zqTz_)0r}{17lW+tA|p^G%IQ#kp(ttUQIWn7r-PfIly^3{@c$JI2Nzftxq|L+H%z3g zY_wD@$RU{Jah(OTAPND9scnH=z4sJzM#Vnp$+!k{y^K zw7~^K*K|zt6lai817Qey26Ncke-Kaw0%!#U6%SH|Z=4QxXJ_^t1zrh9d^HET^m$aS z+}Nn@)nHNa=EZE*_Hv+>0~iP72DjV1;JRA6d^XBo4j~mZ*@Fhjs4}&0S-GxXFr7^<`Fc}>;gT53SGiTdgG5>s(Elj`cP@J|%q2SUa zAC!UoTPeNk5p{wg9gY{ApMMyb1cR%c$a8CJY3ZNiKX>AGAz(azG-n-I|$-z zX|sgit*Q%jYlte*Pk!;;w8i=@tl7$#=gOQzi&pbyf9UBn-^oRAX^r{X*PI6qA-}I) zawc5O0Y4?^;I0EJ&g~k@vIy~PzcMByt&5qh&UJYlv=ed>)oGE58EqFFPmH0zq`k8 zx_{dMuI}p6Dr66hhyaqkgvRf&P_;m%2vC?)5%ZJg@^C45L)bI?9Sl1OB^uZ@;3=;3 z4SFjq<1%`IH zzdJiGT(d|f{PWI^NtWUaYYCShKuv=QxO~4-5PkjT9JXv}qi^WJW2Im9b#h0k z=ctSm&w|2+zJQO{;e|gSE4y~Po)(1JsEQ9?>pT61PQoX}g^Kh(K$$~X0>AlcT3j3nhgV$2w8rF$ zp+;=4(Kos!kdFGc&S`Jld%Tkh;oh?})1{W9sgIucc zc^Ve;OSUpV-Af6W{-K=C*dsZ>T1kY@Zp{JPk_4JoYb$35H=s7B8jTaRb z*E`%FP_*oeU3uh^eLN8hc$WFYwmze2;OkXRLrurZZL##n*VVm<>l>RkdNup=J>gez z7=*JP4{1MGn9U7cgLG=mm6SP}HJdl@Yd&T0+tUkfVzrO)y`B}5CUa)G+r_gu;$V2* zK)2<)Ub9rJ0i%CK~Xqonlq~9R?e$I>jLWBL*uE1X&BfBkg%-p|2-h5-@G;?>aUoU}i_te+dPgcn-lx~(d1LPGd z(hkc2V9LT=$vYaGbI1JT_V_UXgvyoN-SUZ`dqhGaVdE(1d~OyAsJO+jh&qZxXKo?x z9?QdmzXS-KAZ>i5Uf^Odf-~8%^@9D53{Ir6DC6GD#a2+2c3)pF`hmbhG={zn#WXta zTk(USCD!pIXLM&qgL_Zg%UJzp2n)|MIDu9ctd-CzELdanEZDa)y>jH}i}iNuqI)#1 z!!`TU?wd@?4VSSLIAZ>&tQk$t_a`hmc7CW{2Z)a*l6nl~A@UPq!&g+fcdIb|}3xJTY5G`@|NAt3V@U}1s9BcZlIB^tr-ImSA9fTQ3GzDrRed*|V{ z+DP{!+o~WxUmQ1ZV7Hp}^Cd)qNXz^7o3rhm{_9hUZuIm*H4C*Jr+uQUpF8qt_n8&K zg-k$s9v)Umlq(??J{;ZGVWH;zk=Pf&=t|G$#O2lt-{`+lhlLDJ&P??DtV-GYoK}B6 z-=90fBxB-Mb*3`TPbGMK3%QF+i!aLe>x!mvM?kF;GGWl(GchlbO-m8}FwDrw(O}h8oqVPHGgQqVEah8afNcz0}J+dR@jmSIo zUwdgL3~_HK*^S zd#@h3tO@B4A}#>yOm{G~euy zCcD?#cM7$;%Xq!}`u6jauH3mIL492%9a0>k+a)&dh$wfk@kMP9jnC}E66AhGU+fK9 zzJHhqX%yUJHs5*DCDapiMUR3k*yB&kmZUBmf9*n#R*Rj+>9+IUll(X)o~BGDSem1Y ziZyKB`#IBdc?y9Vms_Z3TV{2MZZWVsv7iXOEjisr*8}1kN85_b)0_U;H=5G&0~*&O z+*I5hS>Gj^Z;q8EF^DJCRiwXa-@#v39^*$K|CIO{qC)emB|BEp!DeX12tJFLRd~JQ zwZ{qcbAu%$E^5c$M2wo6ibO4GpSaX?J)GZk8O-aoi_w%1NGTc*ke3$cBMQ1(?*<8B zmQql)!=oKuc6pS-JD+lM70A>Y*;ZFpVt&S9FCC4;o|k>aCsOxyYkfUr)>8#2<_ffj z5mr#ZObyYEq!4NbI%wE)NQFE74OPsfV0TWwPRDEx)jh4#HY-%EARYmM5!8H+^nS&T zfJ3haJB{q~Prc`hryRj1fm>8%KDTXS-GeLIzH)n{miitJ)rpabDz0cuOeiGUB$l{f ztrGwk*f8F3m-q2HimWJm)!njUgm6JVOmktlSJUTH>vYe$LzCd3DR==Wds=I+B`4=Y2S!WH$EA9QOOW(Nfrc;84h+t>zmnOK%s&+U0OEDy;&AC$GQk)^ zTxq)dP(<*(BPVhTGaBFehkhFU)kF9_WfcDC3ZTd_j7FipoB#e0Scts`HLW(<{juuAv&Ag!zJOG`fW~4amOkWGacsOp4 z>$x#;`XKK^3chZ6-+0T2Z+p$-1Vxespw2BevqVPhe%6AyhB+(Z)>3J~d{g}P(1z)o zt+>pCs0&-Vod`KMH#gnvU2SbGP~wIpFPV>_0L21$#Hs06-$ zTD5#%kP9du>SgfL>B^Uf*1%qB@^Aq-F`#_O98eY}vFe)iCzso;z3FNF7S`o2$Vf{I ztEg}|U*}(8$w`Pe_*sC@VzL-Oz|J7Rh_eqLRM^t4N4=qs%R_gkEJYN&MaE|U@ReB1 zOg@LUw3;x5CQS5vR#1Rt%}}Lyo!-5tH|XZZ#d>k!u4A%n_%_Z7{gAKOVy;>8IJ6=| zhRZYsRz)()H1oTE@Hq#hr7^+zqB;a&RIsdM=S^|&XF8YFaWR((T|m{=d~;J=y{|1| z$WS8_zy@*Om|f3Nv7_;uH|LjvK9|VK$^xd=cPL_Ej8H{%8qr4=POt?oTeKK=0K;QM zFg{Iw`k|MyI^M6S#_wn`nZrwsc{ir4q_p-hL>jV-+C3s(Mr6RzRu`WXkjdWtE$SZr zay-5wtk0Rn4z@gq*Xh(|WsX!G)0;KcUEKUIR$LbicLmyK_2@U?)X`f=pd5ZhxWzBJ zUaDrQEe?IXhjVHbI?DGZ z@l(@Z`Xn7#EVDaY1<;>N{;7`kvDh~Zj|pfB2&+zCe4jPsb+imsc`>}lrd=&7&9AJ1 z=nc$dtFoB-g5%mFrAOHRDps-up3AKXkpg;aqJt1>0m-}M+H7M z*m0x5tR}0f45DV{JpD6)(IoRwx8aSNbc*C(1Ea*GHpjNsh-{(iX4HLL;rJ#9rys zX7NH_LA{lc6NA>{PdD(KcY0On+y@r}v(C#XLX(t%snN4)f)l}7}kZsrmz5|I#Ug%R0DXVDUx-;$F zY-op+l{O~23;rxQywY!L@q}o1Hc7c)Oc9;ZN2jxoPfl)Lk3|$oK5UWxY-vr$IaT<>qb_R`u!mY^jQC$jJ{h+HUrqV6=D} zpTsrJ^OuX^O9`XF7Q%q1XB~GY?RJVo$F^j5#%VxQ-~cZcb3)ysAfP&9Z=z+cR=NWq zQ`eD$=Gxl?fDsz}nmV+mQ%Upm!1_DUfDfmy$C6eYqc=BgA(^lHrF_Y>tRaDc62TXw zP2ShlM+Je2KRZ7fG2;>@V8-DxVz@PiAY<>g>^xPCHM*WjSq_=9PVvE|)L zjcTS30TywA_whJ8wKFIL9%Kf=6F3sa=D&X zaK7O8Y+Zq&bN54m&PL}#z{R~I6N5*vgPrs%X6D)5sqgo-QW48)taLn;7lCv0L4cCn z_8-9sW(pgOW)s$9#RlDxjdC;a$upyj>b~}ZV~x-EuffTSzFwIsjqxh4_(IBJUr|Ap zPO6tGbbdRaPu)g2kKs^Z-!9s|MlPr{&_B(D#7GMU;T=J&-j8(7e+eyD{JJ=9@!tI9 z`33>z{Cs~gFLl@+il)+(_kG{JhhlARpLZ_}t%5#mR-2GBC1K06Y1Pfu&4_zL&O@RW z>6zb}kEE&x>0Nj0aO+r~*Y>t=m^*k>h^_R-1)1%NiE^?<0Uz?E<1C?)qr2$*d>Fl< zzOEGnehIxn#$$UTlvx@T9ZJB&^o)?0u-2^})svr~vdM#n`GugOv=^tRik=!&{Gxo3 zj~C`~*;1C?q302A9L}p3Hq=D(jC9ZTyC(QnsDPf`Cln|XlzDH1ZSCx^&_Gh!bmz1* z=xCRai6V8HhiF^aSPlYK9WxsnHZ_C4ErDVmwTH3kW^#X&s*az9Jw5LLp&Th08Bl~` z;d&2PrLO*dR1|V%57-QJ{8pfAj1&f?OCdW(>t#!RzSI@&%&3m8ZZ7FJ1B|2db1NWn z`hZc!$oTTPl$w#IKWr4l>7wmE_zD{FB`O8q^rA@itL_1EmIUVanv7=@v)w;) zKLT97{&&rbK?ECDHxKH#mv{Ha#(e_=!Tt>&&{loj(!e+q9-hO+!&I?7Ktw8Py z=v)LKeU|%{`no3-HY5}hZb8cNV=bEH@B|gSxvLtHVIbM|7bE2^)+#~)!bAd=XP{H! zyg3P+JNAs%o?KKHHVgH2Zt+xKZ)o}gb%L&%I&4xNdymB2v-npCuD>xG{fetnR#o$R zo&%JG)Y}tUFvqoD?|Go*uJta1WSBim8=>;&Ate`7x{#Lyp$d&p_Pvn%Q72nbP3KSg zh*b8oflC4)q8S_?7k`_a)0xnDMJr>0!lZ3c5KY`Q2e>Q^jk}B?AZdEhRyw{1s1D2G zRi}@TOCf;7Yr3ybX6LthA<|#P&nqeD(eOoh9%;EhrK3{9Q%D9|FVimpRP?bm=7(*G zRsFU@q{SPcw0(6iYe`-<;V?NUU&J+(TnT7qr~w^{_Ol)6&Ac^~dAPU7Ox^~Rvae#{ zSB8O_Nm^{?S&8P2)&r>CUQ{y(yv2V9mn>x{f~7(n$07RqJkn$8q0#6(YvtaO>>-LF zCJN}hop|+-lb5r`#$Ouy&hFp~kw`GN=jj;1@VL}PDp(P6j&Wnu7WZ+ z14*1vg5=&RRhj6!uI%atELG&`*Ui+qh*860AOV^c*WM0(H6^7B%9E7^l58MDlVU$| zLUR?!wbf@_6Wn<0|}>fHdHV$=2mWY(e- zm^zQR$U%&s(edQi%>0DEF0vIPEtCE^MpA%=w=78HK%dzLkl_MZ9aEvp%1LyY(EDhh zjZjon)T(w5bT#@i9r?$Zirj>}mZR8`l6|JqM!ywcun|qCjKs9dNcUUILB9*k*KSv` zR||}aA6J*^nrdtuH1(wvm-BBiFnL5gEzmID_2fe#7QMF|FHVWq5Mj(=$Q8Mdw%0P} zZHz!8_fXK#NL|ZRdH2{C2TK@Mj)+CVna95bP*x>oUdDoQIV zzF?f;n>Ccoa_>|=WklrQ{O~L0hw0EKL9VX(W-pQzFU)x*T$pZP63Bi`3}zcUJ5YoN z^!0D;k-j;8Q#|z4^i8+}&`Aq-2)3mEY0>fu7FuJlZGhsp4;d*bAXpA=G;J@oC4G31 zvZj~A?sW%Rq8^uMfS*$wK!B32cC6R3oHmQ3RNzkJIJjiYHxYz(03}Wf+hvEU9&b<( zL(9yJ`pplhgPxt9mU8}8@fPXs__ld8j-gHf%R$pNMERAOIN>T-h7h!8MLU5Irj??Z z`g>Q^!yz>}S2-S$9=X2{zJ;V>`Q0L<(O6O@#tiu1m9t$%esOBU^kxmQ?t| zj=#wVx|?H^11MaL1^rON?CWES870c=nVm#dOrxC>^)?HTCl?^GzqfYRf{!zIJ|KE+ zJu3Bs-pMYYIKMdHhn2KqXksMYmmwMS09|T{WL59-M9%l8LW-SIld;TVWnbFk8XI+h zP6Oumx*5&d>}H0tUNA5YD5t5ODcRyoznEI5h`42GjKrkfo0qT5&A-g?Irej)PQ?yGG@F?7n@_Q!p*xOk?4o(OIo&_iw)}mgMP)KKyX2Pw6XKbF zv4MF>xM8!2t>1aUpD92ibA*MtGF~91)mUbc7~vSLWQC@D95aaudK2_ZEGMO6@O?Dsgfd4Yt}9I^2kOrn^`)MAZQ ztSsaZ)D z)?+0J)@Mh#KV7>VBS54OAj$X~7dP7M zP~_I&#c+O-^x`x8B=utW#UuQ?pD%ma+}hRgl8*u06n+wwEhlkLxz zpV6X7@b1p1>*P5{w9@o@g6sR(62|%52qp)IDQ}!Ax?!SeG!O=`b`x z(4LdJP5fGP4p}&xW8*U{K0mU*9jf0LXc9>+!(+Hn^dlWOG1&8H+I8(IIwys0-uU z{_zRlVWiBm3@pwc&y$PL zArv??T;fNWKnKHc8)KATuPAe%T3MkQ6WCHlM@P}g`9pN4+v#_K<|nI&XrKxeRlD`| z*fE8M5P=4ddiN^Zq+2q~orJ_s0l|`QgFt>^;@8)B#JmkWEw?@IU6V+JqH36;rpr*S zdEEMhZg$pJezcRLlz!3^ENKEmr>Gq2U_?g0159~~E4@H|`Y z;pk>vHc#~QeO!IfRr(W$EY>3o z)qHb3t)FN2JDbYAx}utujmaJ&e4Z@%0kb1-R0 zKNyFpG0kuk{OO0AjB(hnySw)AywbfZtJ0$ktiWLYz`&n?YNgC7V7|6tQ%H#B)b!ce z)y>T&zDeQ@{E^I0A;SFcdbP(}6h2MYi+6(pMH6oM6y)v{P{l);&9J+0JKQfg{4cGo zh_TZ}4=m8O{t}ObPxlUhyL+Wxai-h>z>AVBF)b<+*GT?>e0M<`zLKGt~qw zkn2omD-+1;X_meIL!4$zz z8a{Gc$aEz_&8jh%cWSie=EiFFRyLF4<34u_Ej?`?a_Db>X%{dX`_2-q#s6WMq~au?W3Tm7A3&_1+|cs@+~&kH^gQLCn*Yvpuw+VLu1|IpwkDS zqz9;5f@x!4LHl9Q<_F+ohSc5B6q4eUAA0-<`hfXWpICKo`Xx1W(*=#6be;KlQ0Mn1 zQ*W97mR3_j#e%DLb&jI^evg~O(6a=+4#NR7y??MKuDyT#&@K7+S+ zyKLGvy7j@X*S<8jk!igBzdEJhHL6fi><0U8J@=M>cihT>KS5PuBRJprv(IsAf1*;S z&Ex!FY@GUfrp5IR8xbANUU2}t3Cfu(GrwKf#Q>P|Z-Z&WojuN*wSh-al%Mct=;bLI zUfGJAi{lAc~?@coKV77eYH^#yB63yiRYDp7W?RLa%$>DKC(ut=H&SRId2y{r4` z)#&M8uW=l{zK9R1GGA){)d`AQYIOB5n2HsK7_7s2?cRFN1$kL;vsG7=zacX3I0ovP zUfZuOJL{E1%A!$i0k;5|^FoE-)2LmF4eQUL|K9$sFo%+SA+D!jq%3yi0$@zkUsBwV zKZEwXufD%|`*ujUd%6?x_!lCg@l8{{iSU>lMT7kZ2-5USQ`K%3*1eAQt3VlM1||eK zvRZ*vBW!zzuE9QCFUlVF8DBm)zB+KY!o}NJjtXP@eag`6^Kd~xs-@x1 zPnfKo@-Bm;S+`rQ(7ce4_nF}D4V0D+pA4{r#qW827f8d*WVSQEHk>}n{SpT$D2nUs zjESYJ0%6JhEjNsRN<%P{ki4^@;jcWY&8kQiN&0Vlp6`mcs2$bn)FQ7$H2;iQ%*##rN7H{q?eCE5x#$JARM7qo8f0IVio%Wl(GIJBn&CS48$#t0nBPdX-tvb+9b0ei`a&Q1a7K)3Qe( zG1mMZPK_K(x6&yaW;fJoN!3n}@xvUOrWO=R{B}@L|2`U@` zl`w$pZC`M?E_c^^XS!)2oT0RU45R{cMI{PNqg_*K3u-k5Tf&m4-=`$UpxP28UzHuh zY_Xya$c71iaH~;A;n(Fh3O1H7ODRO9PsIL-6 zd@^!YDV(-jXk=q8hr^!%saErlKE;d=wk)v)1D?`FTVbSm|;M6rD#u#xu z)V#(lFQz!sL=wH9IvthFj%Yd)wCoeIY?1Z-Zf^XiCZYLF`Y~J6Qc!S!0~*nr{_{^x ze9qbs!;eN(h)5c`jL(!_#>#GtESQ!}eD~pYue3pGLBvNtdu9vDI@;Xe+e2(q4^lSO zSzN^M{O!&m!z$!sS)-xjQT{?Y((=lxIU5dHuT^)qMaKVFx>8ETvUy1eW zJCtX7y`yHcmnz0Z0Nr`FJCMTI3GOOD!BzC$^J z1i}YN1WAqzERR^ubY%#xGlOn0uAFJwHEWF{BhIT@F5{G%Y^}tIJ!@{>xGVis8m(a7 z;ga)(o@8WVN=YT@fC67!!P9lpA&)_Uthw)y^37Seijw$}mv7eGVQPkAX(WY1L*)Ug z7`MxzASp>5=*rt>pc#)xpo2CVrvd)+5ufqtGV2%!B+o;`@KqXrO?d^bGgTCC* zuf$y!Rtw>MsMakxnUC&zELt1-qeAXcT`4*dzIYz5(+%U-%ix$ITpz|~jpmsb9Zh8h z3um>7S6axtRObP@E7ey^n(<8i@Kg8WhM8v*_8!@YEM3|=4zH$|ZG9hkb>SPEsH)1} zP<^C={nI|TEg zD?6oV?+ox~i(T&|F_I-VHD{eJ1}2W(A+%elVweGh6F7#>^uRGF`;m9-2~F|$7(()k zjqV7~v7#aEw|Mz?!M|Y!^#pCm zCSLMTZH%U*DZotMr?T`-aH?t^1Xo~eqGU=MX&0eq%z<4yXGe(-D?G)Z8+rTYY7~u-KX*o_YU5-%}ud*@)@3)#m15 zpxc>D+hG=JnKL64!PIWXwmRjN!yd`fW&a#7!Qpka)wF?|CS-(LFuA(yA2KY)P;b&pp44LygP5 zd;2vwrVLv4?NV`BaeploR{FEusFE+EK$Aszd3o2VEUE;AOcFurd=|yfzXv6&nOWEy zZ>R6%gU)-XKQG@MZP4NVix)4vy}c6<8$ZH)yF5BteqLU9CxnTOh2^XFi(ww9u5VPc z!|N-C3OMpqaR_v(U11f*!5FFLN@(pPgUqL`#Vk(sIbHq z7t$`2y5aX(P_VGxs0GF6L6HW1UM8lD^{ezlU${Ah>O_>~Cap}36rAhek0+AX?qrw7+ZbDK4TcQRlG zjNb^K=TC#;@&mTAO4KdDQ;sl&AkRjlnv2_N@^*UAIOW5A>mZFS2$U*m;C&lKu9Qpn za=F7KT-GGM{WYv#PzgNz8@wZK=r3Y|fuJf14yS-`pNQuIgMDLsDl}!(d!azmzd!y? z8Tt|9=(3k!_=|oZw<*em%fLl-R3vwSg)dQpR_;S6-09vu-k z`_d1$w(4p>{gEx{eUqPp^kpc_DeyamkVX=Dnh*0wv|mi)t5uk!q9~E0zOB^c;H8R_ zg^pY>cb_@qL(WTz53K0@ZKx%u%7)W@EbFbvjY+K#wHcRB1nXv5lXEW(3}u?T+4IPG z96c;76n+OZzu`~gT>Fjba@qCWio^KXgW-8!{x%5@MJZ}*!wpRsuTfe*cS~pDXt5?W zARl^V(fQp?@lU<918rki_SQm@=*-Yi8M8u*?O}1)Mx7?pFe*-bwP3x&6AgollXgNQdW!YGt>ZOy#=0{YHA=;0}YsZbZMxI z@fC0Q%Nr3NpEd#dK>}(iH8n|j4O9B}^fz(lP# zQ5<_10&)Q=7H)2&RC-4H?ZPJdcOSWrUF1=VpS`?V8eI0#=DOL69f|`DW;KxO$rp)v z#Gr=3HeON-G=_B5x04>s=A1za7KOFj2_8O<76BrMbYbv-#AYUfN*KlLTcUDj6G5BP zMX`AJN?v|UMef4hZ05ffbGeP;szDiL_0L!nSR`r3S2;Ln&|WdPotNhylRvb^DnzfQ zV03?0d>6a>*V_|q0{bUorFTxlN1-`h*MABpw5fJ|voV9=ytT$8Tce^zT!>Ev6f;_= zrf&zRO8|rp_xlKITT|67g}gRSbd>jl{z~t*A&2K06{hrB)aAp=8<3b2J6$qO;@`GqUaGXbE|IL*x zsfWHJjtvLT7R@s=vt0w^tsxaqA2|m3Jz~OQwG;-`qH6B4NXhay=Vb||tFEf5wDS<7 zmHe8t5R%)f_e&Y4WPfBu7I_OTvh@fx={Uj>!~X9HGJ$LZINyH`)Azys|EIy~Kh+c< ze|h>912W(<#7t#Cq#^>MqQL95-*;bH00j#R2~lM-Q`pWf_(FADJtYCL9>6)??c;iz z-D!SOt7(`1H~dg`U|DiQj3x?>Yks<)!ZHr}Ml+8XD8$pkrWrn4c#IHRwjRR$6-lD1 z@^$BkKp#%G){$L7&By~qsz4w>yv>Z1)xVuD()|k)slo^Zx;G?u5US&+wj=lsGpxVu z>hj(dEl=Tum=uG88|1+dof8vy@cJlyh(JubL;n4mud1v{l9B^mtkv$coE{lChGJk(5L3-I18fD@wYz&z+w(a&8sum?Im57G2hm5N*%|o+F|gI1()d>J zw6j$wi~8-Qf*4Kl=(oVC$ptvWbC(AdSd-Qy9j!9~g?{i-EK(QMNEq)(}xjl6CDe znufn=4j|~uXsO|`2VAqjyQe~1vdL4=s1T$kvqLsIpC|$E_qf}pZCB@gwvx$aW~SwK z%vtMxN^{V5lAJdEY2H@!IzXtuq978B-ie43nBhQkm)W~aiQqdQnzC$V`Gq*bxLU(Q z^>1WkPy6*U{6u6#SV;>!l!62iHjtvHIYrE_{K+hzUTn-~y$P@R6*KXb>_#cmGkPd8 z=6h-n)}Jl;xzZI$S6AP@wa{S|Ad7dgwf6$-6Jv_hE~J&g*beZG&#e#eHZfQyq{vkR z^>=vHTVl5;f*lx+D*j9RO@@t-;k{BjN2A5(vrs<+{?L{ke;bAHa_^^8?hegyT|PbT z(y$A^yHl20{i(koLzPoY7S}R>gH!v{%xsZ#+x|v`{xkXrcPT;UyJxMQ0gaV7BZ8*! zp=wKg>9E5Cn#%Ih&69;rH*$GJ*1;<$kTJM49nX$yE~^5s`1s{&Lh%7&U{WzSNi^qX z0s>rN+Eh`D26g%Rk!&)>HEHWDCg%1&eE(7LjUs80r#wF@$2&n%1;Mkx$depr-xx?A}-%?1s4mZ>g znf*LAb}43piHWJDr3D7+EAf=+AEt`BW2iQPM8ve-?nIs0=@DPR!vW3hH|=>O0S`-8!di-Sx);-Q14U8D_?BSLg4fx z3yud%@oxzkU0wMG8dsu4G9I+4nG{4ZXPER9ch@%9&v4kAMwrddLkWEs+DY$e-K8u} zoNqDY(+S5CWIs95t=lv5RYjK4{mrJ^*2k!B(FTq9xF}= z?fqZ4$A--d`pf5T5u}N@oP)$V-p_04*Tk#v zj*J%Y!cBdoz)pzMM>>6oSlou)JBZ5ryb$?@g(_tiW}C1ne{%btP0NVy+E-)62?(tTqghn-Gb{=bYdy5AT8Q}zh&6FsNn4AJ}KfTZaw5Z^0 z_0wsOl>Q^ko1d9s9sikBe&_TM()k!? z7nZm~eUyB6vf|lD!sDB5gKm+pLHK>Vf5==)!N`eWCTRBe{*v)?C|!eGFbies?u4`Op!S@HBR0TJ~j}hf$;7U_jcrfMY=+%LA(d5 zd3JY!c!4{IqXdc3Qq{CxUY#DEgXp~8+{>*t@;8diI0j3ilZY#9yj;! zzuyjdj0x=;%8a#je0d#~2ti3BB1QPcG|2_%zZKz`?i)+_ir;m>zvKdI$3OgYmcH!B zQ|5}<^D@pHl^P}RDBYb|Xdc4B@mQ(KgPP6zrL3f1GW(^~Q|=R0v7Gl>$_Ae~Z+TDW zgR+pBssDQrvs|7KV=4$$(<`O+TT|Ns)Q(B9H`RSS`4xGg^*V622SRJNDAnfi9vJ$*x z5!Tl3*KcmFj@$7;P-|#nu#MV^n5=?wWbzLv1^P;g@2%5ix3KIcUq+2le2o=jJCmHJ(ml-!@ zlO`a*cnx7rBW+|h+2b*{!&&XOm#TNzS#8eenxLX|Flk7!>T~?GNa(Bf6&;Vz?Vv_2 zG;s0*LgG6{-2anGanK!g!F`d>PQvK$3NRU79EgV6>o4+sn?*KKN%agRUbQBSl0v1q@QIpJ@F?WIYK;*|{IVVj# znj4d!CKDULUJ9$=L>ZCcM`fbFZkE1V8?@01bImXn`95+xU|$X93`qz z-8+%x{pz%n3P7y`Y02n;9ecDUnvKcqI3G{!(~uQT%bOOg=yllpJ@W$*A8jR(5E2i5 z{;EnlCdHEgg}Bt=z+{?5*7wGbUH)(G0aGn?mCXXAwf4gmI~?mgw$GEDP`>-}F*LQj zJg`}^BFG)?!b3Ig8?g(Qoj~JuqMQHA)Epmr+jKITcTKI4}aVByEK^Kd*J*rYQU$?J+ChLw#o1qluc!a)YoHBJt3sy4>lcL%Pc?>0rko@6!U zVfw#EFo>3A9iu|d=KyptQQyS6A$&2}QoV^HB@h1$oW@jzeEu}`zDf2%U=%sJx6;NXK{isETQ%F9qUztABnN@LzX&s&-XsGwE_!ipDbI9 zwT(hv-W;}pvugc!xUYyZ`{jVCcn3H@&i!ayqH;}FfQdc+t79Uw;q{hhL}j1b(l%zFWoTu3f;;3~2olaHRj)yx`uUI4Bmg=DeMhN6B4x1tt3 z5;UE=H59U2*N*o4yX(vSxpBeKKO5}uNT+8rET#V|D2VB0^D)V5YAAfD>}DsMA)rEB zhUw<=aFzEM&~|5t(54-6Q6f^R0>m@buRzoCkDDcs$;+clm%6HI;iutZ45ZSOBn> z1;R~0Bj}b=*8qwsZK19?XxcW@INduqWtHL1^}`kyQC@~X#mr-C9KS89@N|BC5|`2S zm_eDXx82!4oe#p~Ajq4;{azY&kL^xa?X%dPtOsv^poe8&(7Fg?(CCQO3f= z_J)Z?O+}lCm_W@A88C9{at)Y75lBf%XEqRa7+!5aG-P*=+hBV6`;HZxlsAll77WD< zJ-=jgGH!uV))tTFrK35#YNa$fmDF<23_dBdP+L8OnFt@p_0g}0V#6ylIXyI(ulmW+ z-ElFapOdBhc*`P^U(tIHIp*l$e0*?4>(4YTqk164Q)^VZh{Wf-_$aK8R`I&5%=GTg zRW#)tX6gI3{H;gf4SFfs5m#$+C>eUt9h2lfW5u-ap_xgA$XEllCAEu!4|W1?y&x_ij|fX zK~(I(knz8lB5IsHjg0SYF0y`VXY~_)nVf(5EZ{><3@r)8B)lo)+*brPvg0FO4Xv8i z9B&9__Iq|n-67dQXw^o-66Z>?9xMVIf2q7RjQ^>hK}O@SPg9{E>{BN3DH?;u7F~TS zT4Av??&3cik+qTkcGT_mtQ_JALEn-dJX3`ALVRxgZdiO2f=7APl;}u=s<1Aqi8@B# z2|O94l*pBi6y0weq0jQKfkF7+%8H5wST$Jy<*y;9=nDk3DUf`bCFBtRdjWBefjVJ| zBv@M%U{@2h@nhS!6LU+;urv@dO%2PkE&($4?FBEVBR?840Q)8eBhf>f` zzy~w#)FqJpcZgQ%W6=5Pd$h1hAJ3Pi2ui=v@d^KTz>kn%S!D{2ZxaaI-(GKuTqUEF z0mo-)+6ARw4kIEi$A!~w4p&frjS=xOaX$R{EIZDuxa{6IKy4XrOk>jY(lPk3g-#}+ zjLuY-r8Oxzv64nFe}CBoG>h+=<`)Z*vDz!z^0KYfo%tmzeeON(D)4+beq$%R1{!Ke zNYK;B(_S3sL?YD@(32*?Wt{s53JUwt-=t?yn%A0Bs9ClSa~@2d+}JbKI<5I@Oqa4} zpOUQ1LGLEyCK_u7O^*KHT#TjL?gX- zIUYsPX7L+kHlItx24kh}g4CQle z{d>ddO5qDg*kmngsg+gtL2j6q=5YRObSn4uIlk^9hVuFBBf;s)2VEQfa>q@P0K;?3jdr6TtsBgrh{lG)UO=TF z7eZoU=}k}V>gwuUi#r7$E-SwKhq~))4Z`d;2{AF%NK_t1-1nM!=tR^wc*~{a$xloH3X&-Ye~UUs4_?xqqLIn&-fP)w zui6+9YBFkNCJ}fCr8Pd@-;H{8DktFU!=pNdiz>eKuMf|!_Hc1>p7f>z@1?p!AsyM7 zPi;@I9R$3(Wz(0clI!?&%AA_gopKt$sIB5joBD!2^AAC}& zY2V{}$sSIRSBz;sHcpN81pUoaZn9Dd))IN`;lu7U$!h1JNJ*S{q*gheez{@f_HvEq z{snj4-ee=}yk8Tj(o%QFK93&KF7YVNHe&ZkbgT+Vt3{EJlIjc{4kTjhn z75$e5B4JFLZc8NYt1eu&Y`EJ!2?3{4_ELH2=WvEF-JIV{AF>zduqgrv@gpE0+}_=RNOb6Fvfot-mFw#^o<0bb ztAY$Z_%bcR(MiJ~*$ugpvOS2j)pLD?Uyc@5dp3(ynkc-1e|EIl7@+n2Y^BNX>JZlj z^wYP1q)OOUFL*~zEd_b2XR9rEFC0wb7k_qkezyw>TAa6g-MF4D2U`Sm2O`H1vBQZV znX{E*_`!>r-cpF+NSTqNprcDpY>s^-Xu@#CpmM0*KCh{36M12r2n_stsQtp@;N}>f z;=EfTud?L)bf3?<2PX!LCC()wn`f>W!+KF#TCu_6rBV)6%*+_jdLZ3!Q(Viyz&QDu zuC5|>xIZVz$uZKh982u}Z@(b=Z1Yp)G;0#c@`wD^POm%v`N7&aMEy5c)OA30=5QHO zP=ZHNo%h3tu)6D?gpk8{-DTX|4fG4vzXPw&cDq61L`|w|)-~dvoY>D+07zVArV=~5netrt-T>Un$8r)LTT0;k;9%nC z3OK;Cw4`?}+oV+sHh1`)3KFDQQv!Q3v`s*;d6`sN6PcsJQDIdAu&O6_@hc=#71p9;T! z*P0F5IA_*7GRlE`F{5X&2>fI;na%%H`KQ3^bwm;!^Ge_v6D083gKb-kjEw5==C`8T zC~3S7tYhQ1AJ>jcnR`S47CS}HRCS!tA(Y9yDsu{HzMM!+jH8 zfdtrF)8v=>?3GEBOfrx)wtAgGYFku`j7)>%-iR`?T~VUQi!_<8mD?dGduuY^j<mRo-MT8 z-o;~QSWSjGl+=AXI&O38V)jR>hXh-jXav(*ZAl_@|DF~-^f8VlWq7-E0STpX%!!!rltlo@b}30#lrvgy|OR^ zrRjUvMkhTnlk#N1FZ}63Dnw%lYJ-^kr!PZa$D(fmT4#UKa%?e0#R{+mlj;SG3mZZ= z-ypq!OBU!iK3QpE)4q+%C-i~?LEf+N@xh=tyVXoSSlpR?0osE%|AxW?!C(PtPb72% ze5Z}|016bbr%v~aZKaGY^?cG?a+fOt9kK>EO(FGH-L?BJ4@00F=$)`)O>hp}; z1|JE%kszyATE){Tm`?uxN8>m^7iNe6SU z{xxHpyh->G85j*O_@eyj%XC1ALZC=67V(_lR%r`tq9^s{wvx9p)#kwd!U-6X8zo97 z9grDR+u7EH+I{hMF%k?WUCV2m&Y^a%RBxD;{Jgg|3~ z9|9U}r+2Y^sdFXK!E70~K#;@NobQV;Zvf>vUBpMg^{%cxa?1(^Ixwl8>9Bwt1Ao)^ zpfcbu&;(pSW?RBfzCw{s;DIS@R$rA{yOqW>aI=H%Fwj%}8Mu`mME1G|jj5qo-r3iZ zAs7&TFq`@K6|5cz3PNyv@p-((WvOu%quW%17K0!Wqc-T~Mb8j2fD9l7;DAGzpcjRY zNJiJ_y0kt3v_(8cjP81Tbb@Jb9|HLQ37536>i9#9{#J*ZhmeEIc4_Dp?$v6&3Gdf4 zG6jW&*fE4h{x3Ok^&GMDef|D}&uE%V?@fHrjJhv=iIi)f=ss;KBxj`P!v2-Lqyq^h zcD&3(h9T9>v!yvUk|`NvmYgFwoQ}nx5=a`To2@yZ*UvTfMStpeuhxvlcE7-f{1Ydc zD@C;iDpC!#Nz(T-cvro~K9H~5zF)j{I=?mJqIjQ+eUN;09IW@p;Eva+R5cJsu-yDhYDz$6u@EvgE6dc!67_w?qM*#Fj6hBdyjl$kDwi*{gV=39dY`VN(69?lv{L?yo9WRjEVEr78J~UgT*Dy zSEt?ajc!?XA!MPZ$UvyP9AXVrN*5}WCBIwio30-C4+3@V1SM#>Mf4s@2L}h(V}3!w z7fEPH2vW}lcnd=kqf7^k-XR$0A+3sl2!p;5QKK91bk&94g@~|8Q8YF_zV&Xi?`_9Y z%2VedI@n+f6ywDL{0XxD?IosUk(t@A-zU8-F~$OpPNZ_H!#3@3N`*?Wp@(qC9~4-5ou%0{ORi3|G!e`y{Ma@N zIGZ@+73I-k*aEJwt03aM4$5S*@L0rZdC3n55*FC!0?sERK0sfBmB0-wL&$=eDJBdh z^@F-PI}dwQctl=3WDlLK!9c`oTqt;qR8@7=!6o!rATup3WVRzP00tP*=ed=p8m(%6*nIju@x^rpyi|}I-p(f@jANIrE6=jfS zuhh3+q5lojrLOMl^O~E4fw=uZz_8d$4)!d{9sYM#X5K*l8)lSxu~H}{q2R+n$E1!j zBJ6t*VrUc0(Zr_L1BHV!U%9Ie8L1!Nxvs?#+04R>a``L1p7s=Zwb#Rho#($3)sq_y zr8PdAYs7)c)kDVaOV+Krlu}|uYM|JZA{T}pa+GZm=`_vpw5%C{XLR>wFq!~)=*#H z)rswx_3v8$x;v8n*#8v=#3vz+8W@L}#Lxp=GMwJU=3_|#%tX%U;65QB{4>}~qP(rm z3vBLI8So8&!5oJiW{czEUnwuD$5KmGMu*)2V%Tf-sdU2&A3fg#C zH{d%Fj=S+Y%||)7S-u6_)aZo&#Yw8_;INKXpM`vCA({*7#a17Zd zp2;F)P*7(i8>$ARAy@KogS(0i?pgSPH?Bs9kn1QvPkBF$R9CP z1Rh6XVoi~co8xF7E+a;6pZ)!1Ssod)Pj6z6@0<2^R6--W3Rn)RBA5AlY8$3uSHPs(L zOw&%LWTJ3e{SLm|!e&#OhL;;U)8E4(BK4$C_d-oh#eEQ{%`@nBy|xn#Qa`}@?pnsn z*3EL5w^7u*h(Ok8yF!-hIBwYKo~{a?SO3pi5qqR4JDdK`V!1pBJ*}p?QcD5NNkU#k zL`Q;L4e0KaVSmg&e&o-?6~;+9tjcIdZKRp)I@p?D{x+O;=Ztpg0-y8RF>qLJTrNzx zCk*DAl0tm3bWP1w5yXz;VP8BuvP)j4iWmL`9y~hLSr!=9qML}qtf*9rKGeNZK<7`9 zqgz9E1g9Lq=!64VMzTYT*2`c|nUT(zS%^O=JD-ih^JT zqlZYIV)rL{jEntZylJ#@TX{{mB4^BbWI%26by~#L0T;R+CXV0Z%);X!Ma|2tN({cE zXct6`0pREcbJyg7mD)AAV8Q9wbmZ^c$lp4A!P?&LYmyN?h7x|#xI@U$g43yjvlBvx z$VhZB#|e?+Z(aQTJp;B0v+Fz`W|7SGSF>Gin4j%QDWt)Tq$_5l>tve7fgVI zLfIbO%r;@`azR6dud?gwWZ6WT|Dhz{3wSPTgW&F$f9QXBqirkv-5wqg1H^~chrci3 zHhXBR(0>lBCxd_!b3~NHf;M2@VQK#9YC2Nv(AoKtV$I|7bnB~3&|CBhhF({vXsUaC z5?WH|+w=yPGvRC-yo1Zrje4$b^u^B!I6vg_eu(|WGkz6;9%<@f`uX|30iacPndKLP zpgIl1C}GPXaEt6L{LxA}{<9+&-g_1ndxZu0U+}Hbh>25&n!79nHeHpK$FmKCIM~%c zkm%z(-Z`En{`mPLK0`@R2)y#toWL0%^htfSV@pdEQ8qkVcA;Y7j#izV9dq9c2`<#k zhQlk;LHXV26M6;nJ(P^Tz1oT_kFr&?!z_eD$uMklf8+B-rN~~tgY%?_Va%Le5RXA;nqQ}Zfhu=f(>rS|6RPNy^WP8V65>*`Pantd05uuj6w3t37i{1FCR#YWM zaPIDfH6~LiA-M^AV>K+cc+Kze={A#>?8~@b>tmx2-8Ee{#ZgZMiB43eP>?EohP2k? zTK+)Ks^HD-c~OQU^1aF@@#+5YIDw$YO{#e$IB^jbqGxPAz;QAvQYkDv%B*G}(Z^BQ z{pR?o!!Fc_IEb510GvG3e$;D1E5SneB-X_nd5H?v>pl&5EFLO7*wl5Th4Yk5FZ@Kzv{$&c!JX$VUK_MTfx92WSpRx-SM?sBi z1oa@?W6 z#Mpv_VbfK7g!UrM$V(;fb}Tvn<{!5iUFHs@$B?f|B#uvFUBnXK7v&0vxNAR>{b4P8rJk z6Qbj-Pf)zDC1`ubySyZYcEoYLBoz+WaOYAL|LjQb2+2i z-?DpM^l9)@e$Frb+x#}rd#e*G9o||O`}3fYsV-QoGIf@yA0{^HjqjlXI+EDY!|A`C z)XwGx$GPc++IkL$`58o*kEx}4S7;Yo*55Zh#+jnm5EQv@{?lDLqBh&xns%!${~A80 z33gY+r^b;VQsPtM#i(acK8kesZpn_y(*EoIEGv4Cn5LJ;~zeOS935>b|E&O}V5J zLm@;?hGYH5w5+TOoq48|Jvr=;!?yHxr*?BR(@PL(i09wADU}zq-!y`; zsVmPdopF=9Q7Eb`EX+UH-!%~UYBG^)Wf_v*o42COQ@#udp`pT$J}viMYwTGZ3)@>P zkHNn6>ygYWj*GMDo-c_XC-|3>M-(H!J=W)b;a<$D1h5x&JpU$cJ|I+nsnkoP^ zI?8ZYmggh=yy8{rXr>EWDXD1=1`o=NiFaQ_v5^S^C;(_WKOdey|qzWJX`2bpT zhGD7Wb+~Na#8^_F|HuN13f+zE>cn3p)>f3rWMZTG=|q4WeVg#`aQ9Mx8%c(flM}?j zrFMugkyEN-bVHz?`3PNw60VWOl zhJ&-#=*5*>*w=u&C@z}r^}=um&2CCMB9ztN;OOSeCW%d3@(uv9sG~eryNKJ7ztuSy zzhn7K@(SPg<~T6F51%Wu$#x&+6sQ_MgY`!=E+aM|)UMeeY0RMak~|?{J3);T`MvRr z+iuSfuSxBylzuuC8?)~jiHSZh_j$5SS#S&S$yzYW1@DI(#WAD|GigM`$bmia+6)VR zn{3o;rcLae@lSCz3JYV%F+3KW6KUmRWGX*Fn>FeLZBpKr*9RA)Lq}(!=D$)h9|l@l zcIJIL36c}m+wWjtYEyqDFnE9Zr-d@*eYP-9x$R;D+TuoUn=31~98vq~P>tY4V59vTr;6NMo@TBn*XHfd zP@V~*CpB9aGFFAGcWi^08T^13H0lb>ZsD3y;*wzgVAW~Meu1qw-#j}^e)@>^@Tm|Z zozrCus9xGk-~V%SL^5@~D)h!AaNKL&n3P~49Nya^_mNOZzuQcvflR2>uRx9$>X`la zZ_>v>^D3JIhpmAAq~PJ+eRo&8$nqW%U6Sdo>E}Q2q8$(Tl<6oc6ncT4n5QCE`$VHM z=4faUT(MYHMQOTs3hV(lRhjMLC6JGu8?gq7rQ!@2R*c8TSW1nsdT~74o9-uZwMb!n z=x?mWC}VSb0k3JUe7Y{JXE2FAWM^XiW%p+0rTgsNP#b!Y1h{*Hx{A4}F?}{iM&9hN zx5In7aiJU4mRxz5Gp%E^C5M z`{j5UF-ELIV5y^>UsA%pQzQ=`dIM>lopN=ntX>tY;<@61Gw;_NG4KKI{-Baj~SJ5(6qEn z;o@o!kpzAMenO%~tgYH7d2uC8ER0u+0?=z{$26U2C$QB7O}#ygYIcW(ymWZmNbxZd zypFUnwLUyumeSEkg~RF|4&IdOgC`O`1rQz`m&0ujlv zgfPE{huQ000>BT%qx7g+mBjbZ6zj#tIMR5d<%niW=95h=Ec8CqMwK(qb(FV|;rxxy zH73XtVd87frplV@$j+8ikcFH<$Ui8I(wB5q`C}`HBwuI!WoOb~L@^2VUL=!Ot09KV zS=wyuiGaozeB>$^OXg@+`=Ee+rcu*EISwS&_AxOU3BwG69MB}9a?nq*9^q^!#4t56 z{Za&tvv7$DvQeDz5t*rC)uIe|e&_a7A>J8w8dt%eek9eLMN@G)Nb2-|oDqrA5mh`} zUBk;~&n+xPIX1C3^F3TW2Sc-66O8(lMn$N1_z|}I&9ROpHYb*>dM{rW)(ub!vKky2 zof*6CZk`)NGa!S{ZfW1X)m-mYpZB&SyS{krkqN_p7B@Oc$WI8p`Nd$fxTx3GDu`-K zEH^(jqu=1<6w~n&WNXGe@h-LjyeZ{m9R%eo=&XP@SHrBJtAnWPh~w!?msZq54BYZN zI$BjypQ(ZQoKL^aHK1UpaYBs=fCX57XG5`t%M=hd_xF;Xgsg!*Q*L%k*srR0LY2A? z1~2&t2u&m>%d?8WOggSTAU;MvE}Rp9vb1T+XAFs}0j0yRG1b{%nm%L|Ld^oRN=J8@Bq@5#?v#}K+gF6lk7t!#om5@? zF80_c)~`%{%yP}eeo~th(-V)A9zmG$nAko7y}uGI%*RO$%o}LTs}wJ6=#MOkto;*Q z=LuJqAr@{%aijYc@W@!pfea4^hUQ)_mZ&7TwZZ1$J)!a1x{WJ64A=szD+2_Ok5 zv0`Q4u=8++phrJ%gP4-UuT2b9uhY8S6z)jw+;S$iNrJzke|o7{Zhe!?Mh4tQMt&c( zlaDW{}InhI&xFt^Z5?ipFOX85cxk+ z{quBR&=W%j?n}$cu*l|$DzwUEZ+?lRBRLfN{1{+8SFAW=)<{U$gzlEqt0?X6@A_O~ z!yyvOz{6{YDp5G1pqiO-gc0dNf0;yV9GG7Jj!df6z~k zMc(TBj4juA46tOJPe;; z5O0)Z-Rm3P;L_WTtJ;K>+t+_qnj8{aL5_pNVs*}k&!x+YeSHYwep~Qz^70-x=j54; zIGWx!=WD-y2?=>n&5QN)zF2vMM_`L#3DLrbUNaiUF;mm(>mn(;{t`FU^-(RJg?mpc zG9S$XeUnU3mph>F0k@PDafGPr%65tfi<@gUt;zoFTrGYxJCujy7G9!A`?|zMN(2)s z@UEYZC99KQiUMY-hW_L1Wo41*QAx-drkaaWURsbh*EdX{PVsUo>)9y*XZl)0ywkUNGDSBnib$}y8UItn z%zMLBVre)FWd(V^=Uwh3)DP5OokttT?-uY6rv{Td@0^X)hV9x=tv6AZDH zD*335H%s7~gQ1n%jMy(`*x`g4&NNjFdjok-_q6Nuv4{3kZ9B#`cjEm5!L6{7x8|(3 z+06n+SLgkPcXhOXQ)rrFa;AYmtFHRp=6T*E<((0{YylQfDr}Epb`x~`NCIU>c@9Y# z(hdvIt1(%)rV^AOevs=5xjLVF=+1k%a09YyO4F>XoiRxJNT1wZh!Qb#59sAK<-2zT=McG{GPr;m-QkInuwPcsy8N$mHyn*=U(kTA$ z3hYgAVkP8r?_zJy%1w-Le70EA+taf>p3Vy*aq~``2-vvY^%mym%|Et5UYGrKpM{P| z7Jgu!!uijSMC+M&vVaWWP?Akg%&U?XYORbg6T`Va<4`x80!-SArC7@QzMQL{^yTx8Lg~6 zMa}n03eCAK)eV1T@k0CaS8>?~(TN2sOiA-6pS=7`&XkpV{jN9HLN7L{x7w`F#WWg96%zZKS{ zyDlL?9kJ6qNpl<($xBu?a{nypqT+&wb^UMd($vyWdg*(J^T2;uX2xt`ijCy96(uiY zWl3Npel5>1TaNp-th7+w485BEY}ARV%X`Q~-wZWB5JiuQ^{wyVfKQf4!aF}T%})j` zU!3qPygc}w)n09xF{!Z}O5zmIa3KA5e908W+SC*EUKQJ-br73bn~KR%fp4t&=aNkCO9SEawoO?SN-w z1O#TCT3Tvqe_bA_owKF7!SQiS3{lzdWS|kBVdyD^NdSaNB9T603#xZGq**clSLcpZ zM<3E_8$H&2b!AAiprxzyX}z_jyind}91BXiNl5*OJAZSpYaGR7al}|;p*Z#8sSg)U zNy6U3a~)k`RV(+{zM=VTksFXuw&q)e;O%jIDQk*|6DglMXIdG+9jK z{x-qqm`J5iF?9S9KaVBbL`CUm=qiP}W=v#JrGcOya>D&iQB2{JtII`xlkY zoOXoC&Jjaj@}G$Pik2!wGbi(L-t4bd3PRr%*tximC4S}g)2sQnVCDxsvN_0!-dx9> zkiua(oGV}%U}Ryy#13zEzZaNYtaVNPo;jb?ZWCv1;K(hOAZj(Qt?%2+;gi)a^A_lS zh)`Fkevu89HRN}L-_U=fmgoP*^Y;<4)Q3r3t&sk66f}j)5<2u)zB*lwe7UeMIWMkf z_(Np{a^*5COrO3#mxU|xw1Kzk``cUaQ&0^_0n45(Zm&M@g#Q5*o-r_r8+B#Vatf5_HRoBkWCgqDNqbKCOM3f5Y#p3nB zHGF}b0*+1&0-%V2!o}^Wl(QX_pgKLQ7p|Pg0<@7t%+o(^)I}^&Lde*LPA1GY=)IpRoG0wKr18IU^}+j zSxolc2ntSEeQI9by!LNua&vKUX^{N#3J(u7QokZ4)%#)gmLIS-7M@Ag7CU7ToARqM zlvu~3IuvzSiRElChXgz?q%nk3L70Id-}}dKdDLO$b5UeL&g4%qxwebZ&X+`78+ z6;gqO9F!sKd$GTVyrjc?WvKZ1+x8ece8^47tK4@`*L+k$^c206fXJ*5lxaB0n>Uv~ zrQdwT>~5ZI3ER;OmOBH1NQH$74#-a5+%h@bekDdD5`AvwCQNMgdlsM|{Ru7p3X0Bf zY&}>zg)wA2_FbV(Sv0+Q;}su2r}3BAl%g(ijFd8}S;UZXJE6Fu_sb0GXs7djv&t>Z z(Z%GRozn>YPI-HJG1?W=O`X;A{n_U-l=5BVNdLPO3J(uM?{>rWR&UDjt;rN2i}GC6 z|3}qVKt;8+e-AKpcXx?WinPGcAP6WO(nurSFhfZQ5`v_(ba!_nCEckY4N?*_-$C!a z|My#K)~rF#oY`mZr{nib^Oa)=d{U_O{=NS~&j!^txUi7$$;m`Az`K-$JgM63HI)fGv}2Xst)ZO1OJ?m_Ap zev+H613Be_qz|%qMqys_biRKiqRzb2zEdKLG69Z0@5_6)S6}`Nx^ddMEKi_8O+{0A zaM=nN^@r1?t-#Q^wBC$}h$o)KNP_b6z3r#|cSHT<6`2^+!4~EgREv6CIs(m6+Sp#G zUEb`G#d$CKwGu}SR8`FFr$CG8X`R+e)ey}#@xm&dyeW%=^uOUX|iozxMa z(5iD#MN2N1*}Xfcdn}^?nO$r9koIXUzs)dJm(GL;wX~!p9h8n%uf}GPhV$1GhUlW| zN>9wbFsulyE8ETK=S2-NO=vd8FJ34|Y1>`>&MzERkDDB&X`U(xsg@7@)bft3)|*!y z)ei?4Z6WlHT~9A{EJ<);WkPN$z69IPx!Prnrk#ZRb-F4MC9R%^Rbh8`rvW*ZLY(qx z9*1JF;y6@M??qi>80|IwE)=v88yl2HuFdm`6Yo!RqNGYiR?%BmZ1$rIrHHLZQ68`pFCc5j45OXKJxM2ntfKSbr}K4m&^L zZ1OU854-Jqg!EpowWbC`bzZiYN^e)J+5P84z3s1=(T7D3&rgxZGe3o=b7pn}wcu>5 zdAV%WOlLvJf%PSejjjj2qVl4gB+Dh1oBNJLUW;ij7BH@liXel}QUx#$ z6B349CV+8niCmXFO+Y2Lg}FHc63CFm#^GrvD`fDqsK=ARuw%Seth5YBhq&HV6jW&i zfsZ<7;)FnRI8u1P-Ut8Pd%pjF?_nuxgS5F{wFEx#kttJ2m}!{nkXT70ub{K_<-@kv z*+ug!3KZn^Cp!ipV+vyfI;&knB^HZ6QuI=sPpiP!znYyxPxL3}$SKEP##_%if znxoAX*2MjvBJw-T}E~2IlMy zjRJmIn~jGDAXstG8>Z#3Qh${@>qy$jFEbNtDDoV`Su&(vc#6T*&-Qd z@{ub$+phawl@piyuKa-hrlO>(wZA(IYKF@`eHxZ(utc-y=8#ib%F#gQ_{&bOwR`r4 zRL6B3o97LK&e25s`*(RMYf{0hL`NT?C5wKCJzs8lO0*}%gPI-{e?l+ORHYP_2}m&c zSVFGnz`(j&xcjiRTuYVm+xueF7#!oP2FZbUttQ_y=vUAuQA+m%#v;(Pmo~7ha`x6@u%UQ|$^x#`I%GXNM z@OED#_9pp|i6g9_jClW1bM=>_OR}AvN_vf0sz!E1!B7e^vUkT&DgyZ-qw&q8K&mXpoo%eTr#V+{NK?GcX7R)(`Cp#zYoZmz)A{j3+`0 z$AD^JA|fIH&&BF8EK|M9Q zoC^oWFOIILwwUvGgSRo3PxAPaEFNEzCO*8@Be*KyT}mvJ7y{o}@`V-9KAiK}P@SsT z_<~>VgCU9V(v6%V2HKX7YhX1`=f?EwT`o`j{myT>GV;sgh}EmBomZ~fx>vm{zTC0b zHP^d;pTD~y4naj-gsxuRRvyikmq1?o#?;oXjvMM}Ix(uzhWzH4GHmxJwAA5x#-*uRsl6XFvRp0()VQj2EF+6pG52ya^@QViV)g9o8m{!IdFK*Z8>0LXqcoecjLq$30nnUH|O zzt+8KhhOgj31RSH^WMP$t`ws=Mc!SfU3Oql5MetH0B$srr=0A3dH8zN69K^D>g(%k zKMan8`J&m0tP$uF%SF?T=o(q$I)Q+&=Qo%R#2E-^46;~q3BLhEG~UOUh=qEPB*Jzz zPll-y5>yF_k!e8E@lsP#GBexAVcwin|5o+H#TD0;YEc){=H0h%K|UXr8{rIs?9sd5 z8uMq93cEYcSqg%$twLo`7iW&VF6I&!sz9WAHBNkw1@l(*iu0!$3YjBc;MBO*lv3$C zjugVunrsm|c+Wr5`H8&uw+Y^*l;regOthO_`JD2!*5~H5RbNTc?{!xORhlf2ZLdE> zjP!gRAFNd@eE`~?{F;$h^K<;$Lf>P`Ob_O(XCDhcq zdmUfmc06B|o~;A{G`z>hlL+kl1O2O3;bA`TPoe5a6W6H%_8YnQrtYr5WE*p8q$XI> z4iH41yB^$ENmvI_@V!w6!d%ahEj^|HKS#Sd=J|bzH5N9(S$h{5kv7v#dkx+|By74Wxon%ROCtF_NdDY1!r~Fi{JvNPwLYtG2{|@wxvy)1273OaX)S1X*VSf?7hBESDVvBFVh^O)}pn8nu_b~O@rE-KCWi6d=z}4sOJy}SNdjCH6p7# z0aaT+nyU=TyL57K0g^V9FYZ)F9y2ioCUcS}08J`JRp#M9(Qhi@9A2dxNF{KyKf2n@ z()L|9FeN+d1n@q7cV7b42f~hPpo3!LkH7Zk`N}>Zz2Sostw|XRkhLhggD@N(0icwS z$a~8cD3y4q{<>=%;gR(U+g)40l5U%Cc$}2?%x!lnT%P!FdhIk-$cgFFCAaP?GWd?2 z92o#VgS6_e%`<06LupmRUgSOvz+MLcN9<|sI=Hw4GkAl#{~9nX4T-ZG zfmWM4K|a1;0O@J&?tcHS`Q-w)^syv@dLiQDZzAllOw>SRDR;Xia!RrnKl2K|R9c-I zSk~uZl#p@Q6HcG^Z7-iIc^til0+1jhXm{#G?mw3a#bGurjp0+u;ZObocvXPBCgXF5 z0s4=tNwISwR6nDy)@k+TXS%f-ry1}E;+HWCiS~hPY-}19061?zR=v%11irHBIjRxC zDV9OAdlcCy8!_d(&5ezuF=wEc#dqTphhGhki|Zs70szLLA4dsQg75#ux@D ziu}`;kjHqEh`p|%Fs1H%v-y1PE$j#Cz7x=`b5vnfLqo40`B~DTAE@{vYz=@GoV%Ch z#l?HOyLudFs`Cf+z@V3-c7)I`w9S&j!k+-%&*i~lVoXejD}IM%$9s;Qjo$Zb7}uxY zv6~(}dL&&H6oe97Aq;XPJ8lKQ>+?}y>c~|zE+QZXMt=STA&@cp={-6_K?OwES$-UW z^>IoH)8iO$D4EuATAFJa%9@y1DDFZPYo>BV1d7Y7i@qJb9C4@CuqY_16$1d0&COZD z!jB!*YSU{MQZf;>HY!Y!0AN<82-(2!;N9lz>$kqEcloj zhpp8yafPE683zEcCQM4BdVUtVPv7c zE0^z%7#N2joB}lYKT4K9Qaxm>b$G?3M#BYz9LD#=Qc12N71Twl(=khJe6@L_M(9-=9~aBK z10B(dQ+nIudVGK-n&SOwDkvJd4bQG^SeOPZRD$S+E7UP1wriQo^j?Ksw&}eo&L!Si0qo4s zW2kvTVXpP(^iS&X^_L}+gki_tHL#2f`a{Nn1NCSTV=HI;LZh3H6S6(Xjg5e%?cZ`V z28D=4$JhfUzR&Ip%==f5CIN6*w>|Y*-%X|`94D_fkKup9c7xnXr|=i&s`PlR(AkQ1$4m4{`%Fi7am2@(N@eBB5w? zHy8FQO$Y$8q5}1tSpw-BGCMoF*@FU)t$|peOKQ>{=xqrK3Q9(4Y-kv_S#k3 zK!*XSU#SRKKj(ZgP?f$6l+o#Az9Y+|8?LIVvUw2dO3shHb_fNWuQtD%h!j()8Fr4> zMU%*q{W5Y!r-gB-FnG`fIzE!-t}NBP;XD5Esp>0cg? z53GKA>vynuIa?=6z+5#8>H=mhZfXGS9 z2SE6RK)Vj-My;MVmu1XOk1^c@gO6D+cV=Z}HFd8x;|T8&-FlXhAqXTsAU73$BNGM( zRAO!X+AvHG(Rmvbb`G>SJ^pFL;<-^P%Fp&YIwArK`J!0fyIZpu@Tb=dhYZO5{O$nE zo5>vs@8w1p^i}n`!-3|-YD?9W0Yd!?bQ}s8lo5-B(5@1pVFW(nqr6@3?r;xys2CO= zZc>DFDwr$zW(LEM4G+|5FRMp{tzim;TD46XD#cz%WUtqK=xH|&?B)&`ms?Ui#7b4ai#fAfB;pjM)R9@$Rhj9+cfTF$r1CGbu99hmit8{b>1 z?MS!+xh@-XTYGcU7>bPhJRdjP%G8n!iR-6lv_QKN)01aO@BF0_Y$b zYQVaff*?OPb^+PVRY+=U*LwrNwy@p#s52%q<9bj+4YB?c)%0h=P`EGA=S~M;Yu<=w zuWQpd3hdnWxC`*VqLHu*GcAb2_z`WDARk~W+9 zl+Q1X>92pOO!k8ikit7I}Aa$^VdVF!e`>xlEzMcpl2Ig*kO zsB`1cM~{kk6&U^g;Ij-OSH?Oa=&pFgxd~4J*h+a-sy;S~UpiYX*72GGG%wCsc-11bn2gjJ#NKhi~u7~Nur)t`Te+ylH(jMt5J|5YA#;&4Nhux8E#x{ zUid7$z2xG5g?o#m@39{SR)B$l$@7Oq(*qLY@NW5FQJEk|+%aO^7aXDX-yJzObH007 z1>S~~U#yBT28VSTIS^2yRM7jm(kT$?ngHOl==gLpG`?4j-Klle)x`cM>4v{5&^r)M zczAg7x08gNvgdtYW|2I`x<1o51Z<2srJEx|(Xo%BM=ivoHwqUw1I*Da2>4Cdhs@o> zm)n3#gMkZv)P>E{vbMqmqDI-TbvP$<#%a0UEnZ(=FTkgy^E-R_^*T_D;pn~oJ77Z1 z-OVaOYXoNpX}HGyKu;qRsUs?korQM;tZ^VAKC^y|cXuIO~^yPx#>zUd12Nb&GNxe+Qs{*Fs^vrd$gi zJHO8LU$Tooc9>6iPyCU%Wmoj|=%ETW7OlIyt!?V8W*ZCA-!auDjF~H}rk0IGciXRL zD%4toKSNM`m)&L?YY`5LS5`me2y@wiA4?)E+rY>!fBZ6=+4LzbUfO3;+xnn(w|XQt-qaIW;bM_ zAdJ7NK*}69eVLB>EZSqm3q9i-FbCwRGKu3NbS(fKnEjxsgn~mcz?+ty{vm7q9D3Ax z*|ooJ9jtb9a*&mqE7KZ`Asc3p>yMpzz*WD5TpYB$gCe|*2MbU$r6t-)gz4YlZ>A?+ zAj+B#vAE4T(CK|MsaS44ALul#$=~4PG&E&xW00|gaj2p|K-{0`4xN zxkG_eb*G6}1yDI6ayM#wROqqAVLfQ;p!f4ptJA=Ev~}JA}Zd~m`fuU)vxalhJd@BVQGq zV}2Jmn93rTnlZB5KgLPM=D)rlG=2J#_y-eu7w6iXckE|_irE}O+vz@s z>=M5f)zyi2&D6%=H~W%Y!L=xL0Syg8zFN1x$DnfCHh3s3C=d*W+EIxAB#4*bd5JW# zAMx=NeDmY-UL6{MHYA8W^~yH|Tx6BQMXu&)Kjx|gYvI;5^s*pWb~N*#kPc}|UQ~@pMiQPWn9t8B@4mam#1jyKUVpr9+0TO@BqWO++iYpqg9l&TVKa>ZtCan zpSnNW;<^j-8x?>5>gnz_UjE?gV}^Rs9F$EsOh zY513-yZ)zu@HqT^I`J)vNkR423h|iv+3LC^PgveN!CeJv5CC!*5uYqQ3BQSxA)%!i z6Tjg+;{!b2AOV^_7*H0-{Hpz}g@@v+S47`H4bw(CY~?q!El4l(Ok7KnRDshTi@ICAxGHTz3 z3Z%p4e;h;)Xy`kBfsSx$Ppz=~AxuJt$7ltZ&D`j+&BnsAHt9K%!hhVX zje?sc7<|)TXDo3lakUoIrhP&QFNfY?H~EAGc#6Y)AO=pWbjB+XGE?P|%QyrP73lWY zx+c+15DYjqdR!fnXW%LQ8u1`Lv@wd zr6cLfyxq_sH90Z)rl{FI(E|y?tWSIAO$A90Rz)}&|Ispx1jprf^irXA&eoV}H&E-} z(Mvny@J(wxZ^qRI1hb%3#U)PtHIPz0|EVkCtZr*<{X2UbHYQG{#1CRH=>QaMYHF(H zk&h1B5*iARqOmX}Pq}CJcbf~TsP3W~xC#>zyn zUFhO=^Hky9nTY2l$)Wg~Qg&Wd-IiLi9vzv(=+NkKY4^X9pMn#(DY_D8$6hl%m(!T) zDgtCwA{m}!#AQ*sv24$l?-)6+20cf6vGb4Pq^@Lpa6AV?S&+tb_YogJ8%7d8Qu{a+gKmJtSGNG4*u57e$(54fxV=J(AS`f#zc z_p8G?(*bRwV_G8N4v-4{f-U|g7n=fl)VSeyB~ek|cgE!fyEkL0y-LkwG@rpO7($=R z7IxJ~EcK>N8?NRkUGluAJBJS)lzvx6^u1$CV@7ebGjP>X$$QKH>92Z->F5A%Ea9lt z`RZfzr_QQZ(lNwEP|x_yK|J)0u1yLlcC(`JUeozXGjyq6KBH96q2NyW$Q#-BWQ-MU zDW8atPN=D*&m7q^wkTi;r!8O%D2u4uD%2YG=*JGtkN$b#69l zZy%3Cw_@e}&x?&hLPLFOPyNCjZ$&*0Wyp~BNg)pySFse3Z|M;y^p3ZJ6gX|#FP%H- zV)`la@&LPYGMXcMEZq;=8gy*YMFemt$YD69s{kmC`|&k-e2Fnohdx1vp~gH$v?jn;&XY)jjhjt20DEf?dwfEkef=&%g07WLPX%`5?4sBhlYV( zwdcO!QP>J^VWl8?zca#M4G$CsM}kvy5DD;ZBLKD=WrqIRCYx z1Bg5L*l1omLBr%#9`t%bg&bXx^oa#;V_x{xEY(;OFApQTe|g82WP{R?!FAg|f$}MJ zfl-3xBpFQxDCmxghzNW~Yxw(6=*nNOktccN%|21b$=wl@UMsk&>dDStR^@z)mkYo? zP{ttR*PiFo+Q7KkyW&&rGn&K7cfNt8I6~tsm6e1SnES#MCEf7eOGn9dYfu9NlNLjO zA+iHCtf(aim*H%M@{qc=xV+69$V=29;mi`z3zg}@uOOnf2Q*eA#wFX7IKzX(7oQ8e*Pm(nU7PEoa))ONa51}G+)}np|EKJNm_R6?-AzTX zK9Zvpbw}n7s-4AU4(rme6$-|j1yz-C5iV%N8ifKwTIQznaZCz)4+0Fp636pZ$!3#s z?I?qxum!}$5y=p|N+l;Dc?PI)&m}tURWHOVFT)qg%4fd9!N1-gWwlFMgLa~Eh7~jM zk!z67kXUOXmIQ5pXW8tM%13xj@LrHFy>7Gz`SxKShUA`Q$%4v6?70qh(<)vHvWm@n z_zw_N`1oWsL4~;)9VWiJoWE z$I{j^JdE@xAAF8l$#Y!Y-I?q=lKCtN{LxLIXtjgJG9fr=qkyrMR-4JvDG3vRt?A^y zk0BDY340Z)d{TpC0PbDMt7z?Bw@|xd02dWe(rXm26_o(v?sDa+A&y)$UvN#3t2lMJ z1l$6>gT%SZqLn3HM2(2H%|(d>W)2QKZ@&06&4^_OJEPB#-Cs472i*lqfbsd!@OcJ<^bhVRLI-75SPS~Og|xv^@(Iu`Xs0Qs$qf|FXvAA#rehh;nuNYb+KWxjo3k zJ^ood#yE)JdGTOlBpnh$0F-+K!8@7w_#<0>cXzjGM_j51r3bn*h6cMmzak5@XUJvy zI%t4}?4N!TV+D@J3bXd)*xE>9;U&Xlkg}38rFnyQiAbX8C0cV!D=S4DAE>HfK#!d^ zs~sBbqqI@ma43;g5r=Q5zw^hjWLVpY_+~z3<(juLFUgP5HB<=(BY%cv+;l_8KcAkf zcG#mFFPM(X55tpDCrKp)V8$tE7PxKz3`g)amWw~LTt_snF%Ti1T8g5$dbv9X{1wl# z#%l%xWt{YNFu6o@N`lZ}4Z%7C5mr2bT6?UnKKk1qxSHQz(8+kcaqrWnYZ4U^SSZFb zdWVJtl-utbeSWV}9&}-p4^;cxq@iNQKq?51nH>LQW zC|{}&0Q&+F%96Za$9$EAj-N-!coL5#VIKDgD1mFgF#{)75VMMk zih}b7Ibt9%VqS`Kb?iKdLTLB=%nTB3#Ujp{YZKmq#Mx4YVc&Gp+|KlDxlWypB1|=O z12-9zedoI=YV>>Z2>zo&v>m7mU{f6nb+Q_0tz^9S;BcZ~+jopadMlorQ4Z7{<09t8 z5C+(GzqtCy$;1-^t?dm9$KtEyN*H&W>IDS3TLFd!GYK9n>tjMvr3Ov8kIytFcwm!r z%gCKpVz37P*tbPV67_Jv7>QQL#6V6T^CZ9!fWZjfOT~2PFlA2uJZ1Z#oc3gWC$_5Y zN1b}D+s|Zc5J>y@WB(B1ta&?yIyH)IGmzDV&UdS=68wg9)NQ(U_=Jzla#R=?+YKf{ zy1Zk|9`36AI*A6ud6lmEIe>-Vq7j5t&RgwU(*i0tZr-;*acsw_^HN(GXMvzVtjZo) z@~4281VDC!Jq^2w*H%~^m2&a0L|o&8g<5728d3UG@Y0y4jf!zkCPgZZkS$R|Fu1F0 zM0?ed6$gZS9z{KC{~H)m-m_|AZ*lMo>i?zTn70Noti=ugSq@!GrN1H?`kJNq$5)d| zf_X#3Ql;y08G_kGc7$7fPi|^$lu={J>4P~(_sTV!HN=+?>JV-fSl&= z)1Zdf+S)?iE3Km`cKnjF2fT{8#m579I-kMZ${oOyMw7^SwDLZgVF)l`C7`2oA6}k4 znya$Btn=f!JFmT{!>gXZ8bqg#MH6_&v|qHR<%?injSLqh-+8NpZfW_~KVlh2M_Qua zm>|kB)1U@9_g%aUmz9)-MSqg4HIOEpvHv3wCeqPhSrGG7LIwy*2L{9<(JT%`;(m@Cbvh({O?ZfgzJ@L01kcd@L`h-lcNq1#UyxxXfyqGb@gr; z0dMzlCxL&*9}7Yy>QMPC{5$qYykUQ+_pk(HmO{u5h*7|C<81;@9b^I9;IDweB+<0# zQnSw9AwRrsNo6eNJr6=w7Kz}K!yE_k%8{o}(qSSuFsj>w&d<-8CnRoKYQWFlPH~sA z(1-lsX+r!GVq&_?Ygo|)>}noG zSsUh>Qc`yAh5|SejN~C9eiaq&y%9oxK@Y6+hAM3X+1s` zga*qrl2T#F1VlQ4+VJE3u7E64ACP!(saj@sWUN8_4F$5?{L8fdzz9QDjq3(Zr>c>2Zo+b3L6mDw4w^I{2kIr$aG#c8%`4%htA zndYP#x>m?Q0arSdk+DrRu5Xcmsk`DcF} zy#ISQCc&7qs}nTRTb!Og?_j>{V|}n#YV%MvAtBvSBu!}StK#e)`d#KzEK?VZ`@m*q zG36@CUtSGjj7RAF5s_kTvl>V9+m5oQBnpBUiRFr=2C&OvvatO+F~$4eM>%p z#DAx~-+v>3fRz^mr2`lSFNYzeufK?K{?*~HWDJajoG6Y=OVHqU7E{TYk$jN+^Ron2 zU^ZncMExvc=abF$Ol!XF9^i$u4r}v-hrc(8cp*rW{+E3IzJvJ#Bq>0F-svRie>MaN zR$A5S$)p7t!QmfsSa>!TDRJJtq>AkR=W;qE#kkq_S!x8jk+k;fdM3_ioX0)6GXDs~ zKVc&Pu^ZqioDizTzu$=@2%zM96KT-X2sa-c8rnS~8vaMNr$g?3UN4Jc5u#%7jiko& zSzNQc0pb0Y-3I@?;C{1>_X#qQjQ30UEuY^%pCp7qM8tcGX%w~dmV@a}z_g=)SO?LW zH~N9wZH|Ao9Opgn=F(4B;eGd3$@0mQaO9r7haTzR*sVAHe~eb1Ik>&$;dESxGs{g%LOvi7)C=tp)Hv-uG zfA=+#5?R*geetlZ0XO*@-`)fzqPWf4K$u;}+qScdGW#2<-LZn?fPNf&mH7W5M24w* ztI_7s(C`1f7w{P;2C|-RT0HV$D3HOx?arD1?yXyIpv*Ef^HnApGX7_P{Q){5B=q=tgy!BH&wrFGFO@U4%R zf<1k`E54WK>xAn8;=qijKh*i}&HMq`w?>Z7^Z)JTANk6v&3V1Hy2thDFeO6$sO|iu zaCdTVWs!i+0X~)wH#1Pl(^9%bjKB67jr_lj>qA3&2cn|h`>Olj4RO+7oWt&+b{;n7 zUTaZ0AA$3w!2D{ccKjJ}KHgLKyNXlnQi7+{=W-Iz8vwCOycu~k{&R3P` z;`lL%q*zIHJW`49qZw+BB(oL2NU144f%iTV-W6Qw`7OQfw+D)#YhI#AxA-)PKaU4d zAm~U;+mG8<3C--h%xb&z;bqC|Q~d9c3xG3P6Ak#6$c#$}D&8)0X~DMR{LPJ+uXb~?wsL~1RqL?Aibc`6p#jCXq=ipN^^eRi2B+a!>JAQGu3V3s zKk@sX)oiw5*7p!|H1(gmO961+AjamJG>U(B9wrztqtbIhXs%n=Y~CO`^g87o+4i8` z$PW~6$-Sw8rW()XEhp|~_1(Gwy_b{otRA}jXoQSGU@&$U9At;4=7H(yF*5tlc@X%5 zcU1*jZtJ0Kh$GdiD!#nYw3^+N@126^&z1k>%e6#c4gM#`e}yWr;gA7>7*=Viq(`Hi zx^{7|!;f>eP~=LWtOL<~S#a^`tpYI=E{W%{Oqsuadf<5dTyWxOssX>S%N1aI750Ik zE0XH9Di#tLZ}(9MWB{}&^Y{Fv(qY5jcMt25mHV!G=9XIaV={Qy75-U+Sq!iQGsg*G zi+`w$!Ut?VucJwsZXbcE_ zpaN?mr{0R6)RGn_eoZlgy#Psykz@TerU4=zX9oo7bx)Vnf21G7lzFhjOGawLn#wj~ z7k2PDW#i^3j!d&0d82Filk|(vnx$0v!)ZiFJkb2<^{S?=PXgNNsTz9rvAt#8^pyVzm5?6`c~8UQ%a*jPNs#SG?Q3f;#G{f2ZlTQK3Ni79gmeVnk)|8 zKSwz(fz)c4DB<E(SQ8b`2uhv*9;|||F>#KAR1#QuJ)krsdW31u5S1a{;J=D z!Sn5i+U&aJDIDCUt@sVBxUN?@s4r0-1q}a)Z=$Kg%Wv)8u&G}ZJ@_yxP*{oD3=USs zKF?kow{qQlbvEhJ%Q4^N^|2PyY3J6UUEH#&yU>Z_2FJGyrwlT_2M%WWX0=a$RMS$m zqPrO8@|cV9HnpB2ag5HusN}`JRQ9g|U?I@E_vTB_x9t8C489l`pMe>S-t$iB7pwVN zZv)~8Kq6i&7#%VlNN3w&7W0@hqLfq=4i{7 zSr>9W?d{^_&UiVmA}v?_2Xr;^e%Adqpi~avr2aJaZ6x^t#o1glLuXe2!n@~4(S|pv zOegUV8#1t9tm$`rciwoUJZ|F_rZ%hXDdIaQOn^1EE;T3mxnP#sRj*Wl<;~GsqM=I` z2L1svEb-QCcTrB|X6+_33nM9FuLP{R9KSxL2vKq0sY3cJvO3qD|;5 zpHy9HK_1Sga@l3Zfqmopo2K4-mIP#gU4Ku+=tw%S11(!0C3&Zb^>^2NKosC(-Vaum zzHl+>-X#~Ly4y`DWxHdlYAiJ9X)-+6!x{d(><- zOq&jmP$#Bl(2~-!c0sy={*_Xn0rt#l>q?{l=iwr~ko$hfMJ;32Um<;jh=Y3f=+R*5 zTHDkhUvEO$2@#V(`&}Gu*OHP}h=qqOt8%**HgQn1IR-mXBryuDBgS&|->@ZQoB;Nr z8Ln~XqS}78lDZeqgD&aVXdq1N+;-kw&eQDt*d3*SFTkWZujry2>g#lQ;ivS8i$E5b z!+mNq*qPJrcTHaD^jMN_5eYlu_d-b>t!$^0xn87-M{uKXx{RE2BrM!Emqu)3x4 znZPgn21~7fBj3i11UhJ-=31Y*&M29TZf+LQfBpwh(*Sy-lAzRY91T@}m7`T+>>Vjn zNhf0^l}Z&Z$G#pMm2lAONEI0{qD@|H66H(>9ZW&0HgC%uxPTKf^rh{_nB&hrbx<%G zR|{VpEFtzX;8`0ontE?`yH|fdcQyFBASiKr`;iNJ)6Vn#!`RT!$g7t%bv4kIi^;oY zeBYz~Xl}ixwa>Gwi?{PLP3q_Uc!^vMzJ_7zffop6>0i`5t#?0$k6hi{c^XaEYwHb` z7Zxr?ZRza{5VBIQ44j{vnmYT2jigNelf^{hLB4zD;yq23kT^aiakGaW>i2*JX!sMK z{}Z>m*L)COLdS;S&a3%LA^4-`ZV&LdTkJc`YskOGW#^#f-^ur_Eon@W@_lb}20f4q z31ZJp;fpI->a$WOI@_GAi8X2ay53(ftRl;6wyN|`@|1!ZOfZ62g9l0Y-%5-)C`9hf2BZ%Uh4jwT(Q7e>$!>&${7@UwoOWG2a@l)VI_8K20q#|HS0< zO8=-aHUJjr;>W@N_aq>g;0Pp!XU}K=IEe%t4ab@Pv&sSjh+;_X;gCm{J!opSkLF=_ z{L)w;{ZUU#-}dmQSL*(%|6Yw4SvoKg_Q38FqX* z$F$}wRNmsv@oMR5y2H{*ui=+BQg-mI76LPjL`1!z*X4-zj9wGxqcTJ9y;eb~n`mJh z*~gE7mI~23wU>%c>+8d1I`Qd)Z|4Z~eN{sLEMx5%GLi`>EG$f?-eK9x8F%&l=;$cF z?F^0)bU*wbhE`yh!`PAOMdn?T1}4(%I%f2&=YM`+MKj0|H?fsJI?g>v6p7y&3i|na z+c2H$2jZ`~G5ZW^%U(N2+#s%9++?E$?F=e+Pc>(`Jft5dzxYWRG1Qz>nzJ?jm;&S~ z^7!rP)lHkz?5%9|%LeGGq&domsOaQ+D|Z=<;ARtyG=;btlVvinq>a6U^w8?`tdX$w zF8H!#VLq%vMXs#&|WbZeU_ZhgUxoNib=4V-{&%|pf)7#m$bBi(mlT7=kkJxrUT#SC} z?thwMd+xoQ%Rzh`G*(qKw7`{N-#?wZ70fzJ?j=AI?(%(-m_F}Nbpqb6)~4?bfL0hB zNBHg!oQ#PtXn0lWO$cxrHCX-h9TV^llEn4W(094kIJX{CddB|O9|#y{1~wEn-aSP5 z*WAX50iD_4g`ybhc|M!`=^9bwP=kjPk;MozET5I46p4_Io*@xd;X&efh!yd=^i8I9 zfcF{k6W9K@?w|eUFu`K;i18idD~BOg#Zua`DjWF;%%3_5Q!62ggKu)U1((%$CDT6T zM7`gi^$ut!D1KpMmGD7J6z{X6){J#i$rWGhd3H>SaauCF$|%_+F=}o*R<%P<+_G`-AWe{r zEw@U|?s7$KqzdZ1OAH!Aj~Zd*uWcN%Nt1t=_C5b;DQ(1Sg+~J>COcY!9Qt3!#=rDg zN6PgQb^Otga${HkRaV1G_LXSGOS&C zVzriF#P752vHG_wQHhPjRhFZV!os6YDK(O<^_8frm~IS!`8t37mtc|rkiR)D$7mYP zpMQbSgO8u;7#hNV=4X5Y+H*)qN^~ljfV$aeZ)P>~N}Y)J?*$!}<|Za83$_&$6et3m z<}4rt6<_i~=|zhwMbVg|Hh7>~{8^smH=&qOaZ|m)r@JZdH zK@r~Q8zL8UwIz!ddQZAt_eh($zK*R=K@VRF)H%e-vJ3NbCbh&=xu zO|yt+<`#Tq#rz{_+2g6g{JJacvk7?hcD%S-wu7nG)LVMOjWH_F+STgH!2`}(zlQEM zL{gur`aTj}sNc3pXTjumixlmVNv;f5w!SmTZ#m+s_dx<$OLt!HfeomQz3K=Z5X+yuKfwjrQH=XsszZ5{()$Zjw1)FPDy#Vh&=W;foen zew6&Y`Rm(HXZM;qdd`QxH>wYO>W+#_3Y^v#&5iquY|A{)Zj7YgtpsRZ7O@^Jdl@fo zi5Q!0=;{lhDK`ya=Ez#IH5JyGhda~k1aGB73< za@`q6!GETvp#gpzCAaA|`}#5(dW#ZnA}6^E)ctKHw%=OF%A)o~eE8shI>=5By>qW>X`(CQ|*_&$B3>Xnl=wj_yUg+naPl{CyTen%(I!N_-RmYplzXhhvyX^4jSL$kC#jYmbRXs0uQ+gke z`@x}q2Ich_bgjs?YgOFF>jij(CAHf>mxh`a=XSNqN-gg&utr&8-CcyiD+`aW% z)m_^@xC!YF0Ria{kWjio5CKUE>5`C^?k;H&0cip0?(UFoq`SKt_AK&F&0{@>G=DkAm|#u_T1gN@e>8sLbYt0r~-$L z=i1987Bbvp$)OBsn`L!nn{Y%4N0v^2!P(2CnhY6=z zn}gnt*nk%$IT?6u)@MH+eLljc zW90Izd``i`Z0r_eCFIM{Vto5~s+Wwx@iqA>w08FDm zwX}<n|L8VW1*?gE2vgwoFGXlXPn>wkxC7luTz zh@IsWD!!Oqo_R^hFiWaPb|EAq(@!6`MsB5V>FO%6GyvBXkqn4q4uXQ7q%Ab?GNaWY zqGCdqR6Uue--QwvgzlCTTWQ&L#aaarH9wyWN+zFyIVZ{9hfZ3vI$yUZB2NiY^%y_V zh##PLr3$4@=jn4}+lSIcd~5bl6dj4Gh72NXtsja?4}MpxnQ6L0Nl)-&(WDI+t@cbW$+<7~y7E z%8rwm&0ON=Tqm2VIs3y5i(U`w zKq+ZrQayFHE~kxewWnegKD4bFVIhyp-c=wgXcbxE6=S!o7n2r@9B}KuZ%C~g=zt=^ z31{Jd@r+K6BU(xOlN*}!bl z$sgIi#q~0Sotq`}*Z1n!#VH_%AY6DN=^*+oA??QzqpiKN`+lE3-eLt*wAI7_?G(bULl9 zJv#qd5g%?zsAO(99?*tAef4!5gJVtr8UK+;D2ha>j+NvO#fZ=Bg>ePFWPt)OwX>)5 zD8=>cRcVZ>f#O8-x~z{wx#r7H6VG)D0=@c?hXV}Dv^b3OQ+9nGiJF=?kmRsxa(HG_ zq}4xCQX$SEt+kNircd=dfcTE!sQJT$ljAy#&Xu_SbWE8x;#~%RAPE7x?C@Qiq0GD(W8fry0Cr zMzXI}&aWgbU6|PuEwlN?Qzwv7Uk3W?L`P1ZdRb9&$6hW-^V*ad4gTZYT8n^EmL?W9 z8#npRdGLu8FtU$ z`(q;c_M7kw4x$d8t4!anf`pLh#O5F-yL>4j&llFFX!5bd?1%l1lHsq`D&@|DO1?bV z^um%sf=N1p`^LNNAGmewYR7E+N~BjdHm`I**$vkElU5Mg=(_Q?&8VA%D*M65qwB4e zy_Ee=6!_kA&p0Y;rfb`mY?@W0?|ISFlo;(k)^UZbdegNPg2^d##O%;5ATFjTtuJyQ3_J+Rywi%pLGGVby+4*&6F-cR2vcUTH9-dX~d>O=}J1m7_Gza`t( z-s3FRpw4L+v>YptMRn--(H-mEzN0Nf2E7Ol;ccb*V7xQ_S?_+VC&31hnVRTfZY{xdsl67nG=#TVMFHmZBaD!&ope+GiM7 zzj%Q)Wh##ou4%}_EBYoBAMI|}%o|06C3oftUP!=rxL>W0Nu)Yo5-D&--UPfKMpp2d zqOV{O!KueweH@M^@!|GqmaAIvbh%b=w-`u(S1aAMGj-h?So3|G=BrznHJPy=Vs#Am zP>fL&dhr%l@39`Hmoh@~*;5zWshrKDBn|=X@75Wi5syc4D5A1zI-Unac{FFlrnRyc zBn9!Unp?)2ZF97JfXMe@Dj2yNmA0kg?qYn9t|W-zl}jEO{54MHq~H*YMeq}uOP|Fb zVd^tB!KS$zb(ItULyj4MQFygC`PX4&D_F9kw8FUG?i)9@ad1`aFTBeKcocqXZwWV) z5pQzRR`d^7lm*LU?X$LpoLt=m;Z zLi%Myjk6w4>&0f+^P;WMtyaG`{*X!y!F!8vnVXWNr~_pT4xS%+9i#;jaunBDm}Rag z&#NPb&p@2i3COQ>=h%N{`(_}0%_O^C-s>#Rxcm)qk)1=p*$VYs0Ud}zg}BE{1coYd#axBF{_mR-p>8^b+<_zca= z<5j1!5WbhSwOUyT_M-vMJ|iuP`F+g#&}K)CpQ6+XBUzePBXjT8WMPZVelMzD&iqmm zaK4vC**kB=g=2lhAUTm6JU%3Ns0rgV6XdJ^)HIjNpy5g(>c{N6c}2nLwmq$j5P zHZ|s)d^pspB&WsFX^`+N36BPxf6^R#|EPrk6e zJZe+q6LC+>-na~dhrAI=H4ziQ2%VXmL*Ij@+@I3P_&jtjqquT%_dyU>^J@nP~xGopon(N&$FN!sM!-@d>R za&k(|yQ4gIEm9=Tg~_jw9>&fN{J<*p@niUyQi~BjAD^8}zrIC9VTs6oB_U%kDG`xR zHG7boiu5K2sL%qsJ4<33-5f>Y4A1~^w5}!3JnW~mX9V(He^z8 zIf_Wn;_*%`X<_GMbO&jA{KMZ=RC-=x3Tq5`r6Ihl2+hfmQT(#g*nX_E@$69?eXN{0 zk*0%O%VMQh5w`O>Yget=orpi*R@PCc91?7(K3!#W3xE4-XtqHLi;E{b(QZl0TMosL zTCKA#tx_S^Vr-X}G7fz@RIDwr`weXVD|gFBgw#eVAn!p43zIOX;8Ok8BIxq0YQfP~ z-6&X9Xs>{DMsOi#A2PIM|G68vJ4aI6KH!Mv7@b5w2{==n&g%C)W-;gngTC9j`*sHI zTItgtj!!>>Oc_0I=M1aPJB6E$&b>)`FH_K2Nh3h?Iz%LFS&ir-xJydb!TuqF@Tc(N z?>_unetBplg@8s<5xocZg?tlPSUkX(BKsF8t5-X)e5-YJ(bCcq7Z=CJ#|Kd;0Myw& z0R4~$p3s|5pEktxJARV#Igmdps(W&s!euoNGG$(00Xzl?pMyDQi4Pj|MKMYE{+$Q# zkpG=n6gJy^I_&P_BnWsmatjKS5tZx2pDxZ=);*_O*4(el%*+HsvLZLo7DO@F>t~#x?ERKjdTG{Tc8FRR>rl=cb9%`C0or4p9^Md5U$19916*>kOgqBps%Oui)Wl60B2ZpXiMEWl}f`<|Sn;T8Rz zsq3q~n{b!P3`e{7pW2hhV2yiO?mhcnhoikxfnyVBIp5OmTBppZ={GFvjYFEpQH)5% zBKYjnYnqXZkh82b`P*_xrkjUsxdXNJ>BEMBveo73*7jyTzgj_zsPkP#*M7(m^2)n+ z_PMuC{-zM&q^T2>XeK5q2Rlax)o9hWk;s_j#DtWW`YV?^gpH(O_Qvsp<*7K03meRd zSKk_sv36%m5o=JC;DiS*Kk+zE-Oc4+6YuU;qzCr$PV-sA@nn;T8*7|+{%bsF9*hT$ z3C5pB)gLkt7uJOSiP_oNp&@x~ZOfAPsr_VJmYQyE^+oT5DG>;9U5Z&TCqaj0Hw7T)C&a@3l`Jm$oKc$@-P}OfJ@~F4FR$2>S{K*;hW)6 zx#v(9w&P(9J6pPs>8<#4C0!JbcISQ&#bD};HhYsf;V`BA@9gC3m`Ir&=C3QH!|0BU5M9)~+ zH}5bmFJnY)29g}r!K{&A+Cgi88{V5^VZL>5S41n=>DIOe%YN@N8=r>z9v3T~S2QIl zEo`$bbfW?XcKLmmc!*>}Wm}nOs!9aUkFHM(V2CExX3%LvJB9DvHQQ!KBKyhjLaw>e zF$FhRA^Fp~fpY0$IyE*_zBIUJYUKG2pz5?E#N~HaR9CLBu^Y5;y-f6wM?k}c*-gpk z8}|yW+r;GJSK}c92o;*3@+hRKnHx@&Lda!xl&|-s>A(`pEW4rx9pfzLdyX~CR^13v ztV6kdIeV3U8-1sDKNSa62Nx>a{#`DEX&$584~$0RPPxABgg9F^n{Q7U%&ZRla3v9r zA%EQD2d_w&224$)7NV_DKKyTy!Yk{U$tsum4p13>_gQNh&jTRy@j7#p>ZTkgDs@2}r?ymr#ZF+iIS67}<7p?_hWnotEO}Cm` zZzMVDZ*T-m*4pprK(BuT?7|gz=3A3Gn>DE-!LLzKnX*Z_@r=B@(S&Q-_+zmjKYl#f zxOiRMaSlsD-&Lls0)`yn@3&a(onj8%CXpAlPN&U^8jgQ+6~3>4#|ZG7Z zHm0~2+1THD(o%c!^Pj$uAkTT_87PgzYAHkpyZ<`an}VXVS|7vX1GTHU`Ip?CBs$q= zLNxdTxx5_+USch49M@VBp?NMsT(kYoe`es@-av>fXF#_(2Kwu})tsxwBq|eq0OzIb zjLy7;ex3gbwAj2oEZ_{K3EG~V8vglvE7Dw-u#Qwo^>N7fbU{XXmv`~~Gk1UfR`d^R z-MKH(WwL!YC9l5PjJ{NKRYyCDjfX(^AoZ4Zfs>>O|MWXH|H49=HXi%Z(xUx0q(P8| zYzjEE*=cl7XoPZS@bH12! zTsk|L*sWu%mRr<`2!kEEhn}QB-9V~!2>wai^73*D^mc;~V+N`5{;a63tnkMRQHTJT zw4e0x3PWN=VA85pnj=}n>{n6hnFf`qhkHC@RB zEvbFoNEe2vJSGeah(r+n*6(yC3W!MtnDdxwl==mg+C-&YH>6VtF_PE|67v!`B#CjE zH_@LoJQmS{=SX>O2NmG)C^_AjuiKwWL!}Q_o?}~HJ*{u>9ly{?!b5{#FX=0B-%Fgo z5wYQ6*lEvo(HdC%Mimt4+xIoqhO?!pm2NgaB`)WC+{a=*UAUpf6aTdai#Md9AK(T$ zF@A5+Y8jPA;ypK_t_xSCI)jxW36v#Vmwl4>2v+*%OB1TTp2XtUvULbGFwtiYMYB`5 zNK+&G-0$~g1KiGAr=TVEvRS&0rmb)H*L_6jGU=8jxIA-br}rm6W!$XECE{n{z0-Hi zQc`fNWc#P^L*Z4I3dV;j%yvJM2(kTkB$Tc)9IO-_ucKt9Z~$`z9U{{M?l-48Y53x{ zaoAHDyTyyzX>Fz@dUV;mPNIsUqKahLSF+JDvEP#AlY~Gke~J)?j_W;hvq-n)R%!H8 zo^TfI%Q|bs=G38*7k`R+&Gfk3R)aV65&cVlTj_j~Amz}*ia@w~kYM-Pcw4>HhEr@j z_!O`4bVS+-xqlw;Lt@z=7G5`g^%rbN-8gJmRmLGDZE!l$_nVgB!SkKug?w#xznHsd zIB*{XI2ANyQ)mYscAste;gbQ!f+TExt)dRVx}ubW2wdFw;l}v`P!t+{(%sow0?Pp3 zZ&;11*SBwJgbFkwX3|MwmMR*`GVU;~9PV#6ik} znl{)XPd3I5)|Z%heq*ScvkK~KOhP}W%?Hkkl12EeDj3<~Nj6H^8C7*ZBE2-l)pxOh zO*Q7;t&-XkbP!}eDCZ9D0XenK9LEi(Fm9;UT=*PK4407jspoRSp-E6LTfx!SUomLNXpX)4v7Byt|6x+rXdp?jKsQP? zNu=TSFzF18c@RO3<%iyX|J(f&g|&#`CGC^s`;bEyrpFS-&=y?(D2)#-rDmgil;ivHH5IxT47gysQGe1kFlWv5<6Y7F-Vm#9-9x%?0xX zpWa9!P$#k4`WQLpbk6T^Y+3qR3&k^s+$|z^wS3)t$NA(@gNknhtbml>E<$mAt+w#A zUY4}i(vRNt?cJE#f+5mgW^>d?SAl0y`jnnG*&ZX@j#VNqltJoqx6d+1PgezzVfJ#3RYXF=m)}U2?*ugC40yewVeh{-JJ7c z++KmqG-A=Xn1qRa?flbXftIbIatCe)(h~d>b{)^}9;St_Jvmp|E1!Hv*H_F}!P8_` zbKu^kGwq0Qh_`Cg9NKYp6}AhNO|XRy@BbG3TKl|l+p~kGJbk7lul@MAt1#ekPD#Jr z!MMJr-|H-)*jPeN6hAoAJ% zl{7Xjjp}GcdE+$ax~+r8G-eU`tIY;eB0eeZnzFGx%fq3n{`XMf;H1JV;h5PfW9{`o8GlC5BE??s&0!Iu+6y&vb&Ba!W3JL%w%AUZ*EF7l$0*`9| z!g0g48mt888O>=E(p>~vTe9l7Z5+HVoctj6W>XWAkg2~n<{lrG^y}}Cw}Pg4sUT@w z)acNm`x1r_h4y`0Sm8NF|JD8SHdCsU0{i_X<}jSg3gW5e7aEZ5DEeM|*1@gNKvE&I zCzVKa$)D^V;=+L(AN%GuA;C0`0~Boh@^bLMWO8(L)z#*A=DOUCk;vF(=wi_%yt3T4 z{uZObMP^N!hoiW>_{*x^<1;5MtmU!%&WzCfc!fjRuC=KYBOmm(vd}5uqe>$uk2)>} zev?XN9Xn}K;j3@q1>#TYa6Nt1le81?(q)wI6Caf+B*q)4^NwCmJ#G2CN1)Q%DSCN8 ztkS2f$U$C=8L(MS4&T&pm~AgzqFaJ$tnOa~(leR6#PXQ$N&Qxxo;{Q0c1H-$wsFtf zOW*U6EJ}%_5sRlmnwVYUwi~(MdTMOgfTQ!Kb)-(UA`27#8L#3;cZ-Id_hHhJfa!LI z@kt+}(MM1o8eZBYlcAnumE}@%Bq=}O_dAD;5#&_t+nbr4WF&$gWaK3nnXlpcQ1oWcVug8t&J}d$N`{ zpS}?>=QZ<3$HYWcHE2otDkA8%Xd-!}fY*HIc@D6Brrr%|k=zokK+%$kH2x;*HD5gB z?q8ge#674hpI9(cEnE^EnQhnKm1%OPPU}i-^%xd-l_>16L9nOm304>uxL|UVy7RT9{qs^UcF2aA z>)n7Yxw3e5xuZHZjM3>CsfQt1kGQ$x(DP(VkOy%qRz4a9>GV=lWBUe9HkHr_Jh7w? zj@4M`IVC^2wiVn_@s9LmOU~`vxa+)rrkTe!b-=jHgR7EhQ8DVa{Q4P-?+kNkB>v*~deP zrtXoG-m9<>ObY4IsUn|@Q2EG(7ku^Ir{wp|)8u=7*;3~#^WG*-efI99NV(+g>l1Z0 z0g-k=xWHa-dbzWHpSEXWfoAWPHQz|MO(dy&_c@m9T*silHf+H7oK&*$YFa0_y+hrc zDJX1+0Re)Jk`(sb=3O1mE-dcL1S}&dF4txG)H3ux0aBb-_IPLe`E|k0(Ps-*C(aIp ztnJ|Gy@YRx3trGFbZ zn>QaujO@5=@g72Pq-U^5`OrY2+ocee#^(IPX#YsQh3knbU~bH!4u69=LPbuYGNt0le&(p^gd|%l70oh46PS$MdUzl zV#g?yYpz7|L@w~o3H|g;N-AI-<2E~i%SGme&+(FPduxE?RDl0Gc=(M^WSd+RubV#9 zuDq$SJM=3>hCGfBXU-{?mLcMhi(Pp?3E?R&+mqr~t#$^3oJfO>PO=X<@HQEUHuMPj(U;~vo6FY0WTBPLncvkcVW-GZ`^;Ju)h1S-KxaLR;LY@f$FWTHYQ$-3 z@*Sf#^b7XTLEeYMsfeOy6|niW{s8u2p9#Kj@-j~OH&a5Lb*Ax5OLE&CG#y}KY;PJ} zFSMi?xc}|ml@?7+F>aEkL`D2NLWqO_>y+!a4ecP%QSujOPquPfA>P_@zl?3UK#6y$ zc!CB2dAc?ZAwuHoP+E4)yRwvKYAP*ewIa(@=l%~N&}5;w!lJ5r?gRzn}DWJIgg zkY1ioKA*jI&R&0%A;al@R(p7(5~3zKjYPAF&P4xYGwv|`_s8MKpB)US&>vkXM9i7r zA3tHcHzzclghUyHITi-H+^VdcYFfO_h=MdP4r|h-F&0Qhyw{peWFOt@?RV7q>2KE5 z^&<@JC36DN`J_dr_$X_zS2X0Qz$qtY#E=nfyy_sA=Y_*v>qjYSvcb00-*QA&9*gRJ zcf$dJIsM->F}63CXxRjY-Nt>2C9GN-vECs45{*;qwoRpFfTUP|^;n8NJeaqvb@66q zQ-SfvZwY|l`?QKE5e9s>J1XfEf7eDp2*2Ft5f=p`T3GY*)fSEF-N zpO~w{06I=J^svi}OBgv>=;N&b=B$yRD={Zdl+)Q~r)%rHlrmivW8>fJ=ra=yP1uso z4cnocy_=KSq50)O^lJmSTzQ-k!-MRc7E{G1Z;ljvMVidl40~0y!cD|qJw})YUF@zA z`_NYizXJZ|^3&y-XEbb2X%>V2{$E54!mI?6vQ4*ZEJwPJN`5R44uW<&Z^Y|F*xAv@ z0@a4G;b8?uMIRN47)OE{EYM(P6x@FhEc7A*oAwakn%=H+H4#nILN<;2e>3mhJ0%Pa z(efqv#4}>`xN`el5aPOM^|JZjo1->-G;g5${1#FepfY7j;BtyF9~*e8E<~r}d)e{k zjNZ%+%(7*lD6P6Xg?jWBGGG|o5D7vA1kI?(Mi@Vsy=g6M@5`G7zK8=w85X}m$HV#^q;PGiC`x0Xc2)|92uZB|tS4HImzI6M zO)UCRkW2hd$0jQ~S6^~=!V6jM8;X^=KuP1cB$oSKkD1Q9!j*AFSFUrIX4%x2#Qq>f zf7=ZvwjwK46XJCn?Q@oCf}LqPD3!hH$Re?AU$!>6*WGVFDr}$`$VHHGjqP2Rw?PoD z%N!NGVWIBaHeTJ{kef&j`?X{_@TUQvkODTyzRbG&w!+G7(XKj|QLdw%A*IdQsi-j9 zsgj!F*?wWstU9aXH4^fWPL0oN?aMH>_OR2n znaA*&sI0b%1Bkdq)DvdZ<7fKyq_&?;QV8BHp2+MpHA~#hc9dDwu1xP9HQc-lsD2{QiHlEt?2e+-8TEJ*4P@}KkpYJ)LkF$oE(%V(6w7d&K} zkAIMFvTx}1YBw)&!j&N#$|z{Yk+!$ImQ2I=^SSGot&sBCYcS)(Yh;GMwGYsC~rzGRJXE z?E4YcbiH->{!soYQ{{Z5xyNhnu_VWb%ZcOSt`Pz(-Kq=UtrlG>Y>3dt`lwulK;j zS6w>2z{|53*Fw+3FE=i5@nN}|J-XOmmQ)v@#k+NI%j5w?pB?)7hx(EW1mf5#}%f`mUPwX2fV6fN1cHEM}N z&(aq}3@lMz_G|F(EFB1X(ci*t>$fxb`+rx_Y+!#buy#hUFn!-K-+BGg^R~YXbesuc zkt3ZW`_a94B4ZiinxeRgUJE)~Su|g8Q8J_rqIjTe^s!W*NOJ+a0xg~0srxHt1-jSb z67y%@G%TAgGW&J~aa69hdM={kZ>sL?+CW{0({h%30p&lCpv@0hNV1Hl-MP+@73=g--PAcyjMw@3Re z+-}7NhDb5=gr-i%z8{lbo=LbwC(6!?mm1MES6p% z2-^=0MOzqF`xg|}TT(aQgt54#DZPS?^|zN|*bA80GCIE_`iP#TH{_Sd&38~T=p~}f zRW9ITbEVe<)LjS0Mnj>1g1nYd*cIce*UitH_7k3=lUc16_vOZ5+>4r<+#7fe^w|xM z+#liK=k~dw6KVzq6k<}WCL}(><{x!+8WkT>@hiE>Ssu7P3=9ke5)R!mkooT~R}#3a zJXU~BJKG}@@DszE4PYDToBC(MUl`jf*?r=c=n|PeXSNljr>9VjC>fi-2fW0m%QMTB z9akDl%*}D6pbA-N(`DCe)E}-+{9!ivE8RvEn*2-mQ0;6fb2gT zn5JeuM_P1#Xl7FEC(hYo9v>o!g=fb1F42cR5q3XoPR}vG3@9?4z_JJ2sYCdf+bB9jX&Ak*50RQF$4%{6!atbw$ z3TCR-9A%S4NxIZo4SS;B|I}`9>2?yqOPxybxJH%~h+ZO7y$vM)a(c8bTU)FUiaO=K zKU-5mUCQ^^|3mi>d56AlJGnlZ)Beg2xsFZhr%y6CPy!Jo56OIx?oNqA{55V3-)Is- zHhnCxQatakXcNpu1$kCF!x9ADc^y9?hOEh~dPB~$P?@V2N2FOg5Qa*}UsvDgeH%uI zL_Bt&fI)sE42$zC8B#}|kY9-c?QN8Ti6Ob$NA!K_mN*3MB6ZXRRrV{EPFRwRS5d;) z*ozBhsydEZ7U+ar71P_(9yIbA@KOs9uW(;xxCNc{w*}98&NbxWV>BvZpc+1qA#I#U z;R*Q2tq0V%j06Pe@s#sM(o6PcPgT8_Z|;BNi`b;WKw8|7SG%hRSK9BE0?7g#KxK?q zw;7^e2e4jyK;I}TC#3eZb=FR-w#!!8pdczu)7|-u#8YQ@QqP~?RF+TY00Tlv6~q88 z__pq#kx#!pNIoF48sAzE2g>zn@SU>uw8b~|lai%AM0hv`@(#jBy{-LoJ&nGD5)GM3?k;dcXPEk*=F$8 zF%rAsWu38P1Wrn4abJ_0e>^q5`XE@5);8vcjElj$nF?T(DV=7iGFLPK4(`Im_V`W@ zW05(ifCG@=Hd?sc2!QnyA#kn>DWTrxKlcI*67!(=J&9b{c)bnk4*JC0TNz&iFv$kA zq(;b*DbHtJb_zhfvPr$%6= zTkO$dOEmAXmIY^!tS2|psMn5;vM3wmqayIqAHxd#4j{H9oE4u{Dn7|oPPr$*O* zo+@#@Mk!+!2QT`&yUBIGhE5y$o^(R)3|NA@k(bBIrX{(_0i?^h|U+ zlDW{HbNcqJ9A-7JzTrU;G zkAm+R;*P44k^cJ!NUgp?f=3RNC>bXx=n!~^&=U9TpfOpKq)FJ|+r<{&l`b^ow4GvP z@>ky0X1?g0%@s|p`goHYMT`ki-7kLK0gS*IhZ&2{fKHl;&7CQb988-$WTlHz1`wCMd_5ASkb(QGM9)?f&REoLXCllqJA&+H7@te0{5oDHM$_h50feS< zNLJ#{!cj*e!tS!)=}pXP6z<(j4^`b)PA(MItj7af-t`|kb^jc&F)SE#2nYOx(Zh*} zMuN$3v%5W7>FT;7_rX0f0ua?~bOJ4z-g<2T&o!%A=P5gvLC*(?P<*7YB{DoQL_$zE zf4ZuTB6eZOHZXke$@8Xs4H%o=sfmA9nB@uO+S0 zuER-5;Ea1m(WSzquEtIxOMwl{ehibA7XcXGa9s=-e_gXc?K=|9adsg?kVtg;UZw94 zPA`wU>rd?Lf&4mlMn%5i0N&<%SAO-#@iZhibS(I<+<5bflf&ONLC^1n?k;UX>yu^u z(Q7K`SPo)y_rqQ2m0_Pir0floVjmu07ONQ&iQ|((3PC64>>J{pfK7t~i1sWo6jFi; zzTCZB>v567=-Av>t6x775jQs@KBeG z260cx&Y;yR;e0#!W&CGV@G29}{v2rtJb+6l{PUwQE$lNeE`EFVTc^qOVxMRmi^F7h zvIKyDdNSe8LSx_Se~vQ{h2@YS??5OP1D!GgYt~h;V?M?-vqr!xMN8Z zx6A&sV)7K;9Slr*f6Z=o8T=%=z^CQ*tCI~0SZU^()d>wNQlXgdaRRRAK#`JJ{irIe zoHhk?8(}=O5662F;^g9bw%w78-v@E6;M>$uT{v1J&>2iRF*tr3!XMhs{2!TQheah| zN<6yDmmqUX>pBv+S>SW3F^pZQU%;k%O=8=}mJ9W-d>{T-baEw|Ng?C#CiV~V`tvOW zu31&b{ad2m-St`3q<+W;Sr-?;NSR1Xa&jdx1`_)78IoTgHp-dGi^wbFt9P3v1Os8w zda;-oG8%0Rw`xJL`{u7q$|J#xHj`o8kP6uB!Z~6j9=3FmSd0UbIDmTm`@{oP&zr>e z&kl{jKZvEsIOkun^cK3mgmb*-{@(FeBecxzw}w>%uztFA&EU?oa>*oC9G0_Az&!~i zlX*i9g-;{$a=+U}Kr(_1AaHN~Vs3vlf)feFFOm4;-$V)vBE!#-6+v^}HPS2&4rS>i zT;1i9-vN4~usEUDw}TrtlMjLcgS`43=qi4=D!zxm>k#wuWCH#NV|X?2+K4U6u{R)H ziKp=UP!QclTuq`~B7Q@Jh>_Epet{T4TsAb#IN|-uV4l|Re6f^pK#%c4K#$cn&7pZF zZ`Dn+J+5IhEN=EG!{Pbg-H#NmKsqEVX}ar#dg>HgFSTBwW_jH0Ne?#iI*eTsjT%$j z*=FNwL#3eOqUMHw-h=)rkm6wD0+O5uDXzzTGX+!Jjw7uL`NfJNn&)}a&-K8mz|?ls zM9OQYyCB@hM&Yeajb#ooPW<#538nq2`8_NvvM%yuhVqFFry` z@z1w|lfcU9>xgu*fY(b!Kt5#2258ou7?UtVrG~wiph8lg3V?y{M&*RitA-RmXS)2N z2+W9Omw>I1CWn9Y1WdcfLF*=WU)+v=3ElqQ6>xvphIy2_h#p_m^*Uynw4mW1b4MMC z?hRJwSV$`EEHF#O(b}||VoTs1V@dM)E@r1*XQ@wFU zg*baKyefWc^Lf0LTfBz?53kd07V0=<7~5xz(B29}%o8@@)}GYk5=^6q!Vos-Q-%g= z!44BfLb0d+DiUxkrf}aoCY`C9-;!D3E8SZ^no6-d4}1T26{zL)f!c|l^x-9a*s&UF zFEB_h%|fcto-WiTlmf;J<5=}pe?c$hZ50T&nxtcym(o3H7V_{un>zBZY*_zMx9Sg;VRI(y#YA!Vz8a%Vf1hRd?L&Mg9pV| zc~7x^{KX{q$l!%{$SIIFZI7$9$nK9Y1sYYH*Pb|EKK>P||GreDF*uvYXtRI30z6!A zyjZ9>f!1k+&^^5^Y$E3-n_rPI_;9d?w=bA0 zpYKljBA`>kV_hkMmcRa^F0vGU0q&pmWDnZuKi7ppR(jLysjCw7>(4tdP=nnO6?+U` zhe0IuV9wFj+?ivk47fL`+&+ z;B7Aei0TNQb;3S`?iZQ==e=UQpw0PAY`qVH@CKX&@}$o^;A|@+nU{9c0)1(qY`UI3 zV3c4HlOAKf?uj&3q|;>375*^T3+!7Bpu_;&q|1wB($?n(fn**|Yu{7{;yFU#;3l*j z=WyltO8|2~i5K$!d_VB2-)Q7_pv@ne?}^Jw^NgH7sy(~(Z>94W14}rMyS=Ow@0Mdc@_T0Qe z7jPv&0`b^&5O8aI02L^7F>6bI|6IMCdo$HnmT#~86c={;F_SUle{I}9dx#PM&Y6!I z3L@phz2uQ~8IpPJw?T+{0hGhQ_m^3~+Q2{3=V}JAPFp1e4?0nxaj`iJl27NrSD`_% z#|fAI@2CGO6=OU=8n$Pn`1BrDQ<)s-V8FCT3qJ(1B^!e&gICRBi0VLSAFL}#d44PN z%p1yA{?~Z_w>+4J3j>sHu#p8dpC(J;kKgJxoK2VwrHUl;Rq!F>@p%KSY7hL@bcu-j z^BF7T>!xYbyieq;EuL=(ZpKKO{;0$Mab_QWq!)nw#tOk&`f<8`5W3Ce4dQ0vrP2Y} zh0p(L+5bN0;BRQ;bdPq8xsCb=QHmzU$T6p0mVKbWi94E$Mcsh%Tg}&tk|Y{L{kKy1 z9~X(Fdbp$CQ_L+7i}2b?BIGd)Z*TX(lowlV(_1sz|HoPXACJ2lBK#8_l2->uu485( z#37bCuNZJ&L{ZN9zi#Nm65?UOL|8DTc39K@FPh~)SN7J#20k`pR3+8_b};_k3VL#| zktil?B*FjNGXA?!OjyVNvRbCe%>Yt` z&G~p0P_cb|Z_`Z!EX_o*UR(UZxu?q|VBK!KJ?;f_%ie52pL!Y0T=y`CV2j!2_{_lH2!PPA+YZ<-+l*Oe<)13 zhQJ~cbC{NIriDml?qj_#))gtzZqNo&o$TEiMhr$JfxG44oP3|iV+&&IY2VjXxLcAbXB39giT1}UdQ z{vHK#Y4BL3@P=&v_fvU`Qp>|Km-`1*NEzrqw}yW`n!%~K7;jcsGo~o5ob%I7X?v#X z09df~{)E7V3z}HX(yphjc*iCuA{pUlEi1fkmxqAdF4S2rfpZVIdHqc=5UTbdY^qkm z%jLK6?9Z$aAeE#brN;=8fyfD%4^{_|m=}ROl(G~2`e2F>2!$R zpvb5__-_wO>HUOq5z`jkyF%@MJhB^Bwm8AG+uNe->*gQ#*E>aIJT|Lf79%(=$kjgN z@pBXhgize2D9}uelf-L30+BBcS!=eD_CiNYe;vlVQ?^quGF+4|angZTx>I1#&ak>Ra38BQF>@uqliT1t9n&wyOU$QSqGqAC)Bx z+D#zxA5hn=|DPIroT8c5O9on-I~rvF?{Dc*9`2_9oh0M`yxXd8GYdG(AZKZ-xNp<@ z{5Qzdf;hx#?M#aG4!Dlx^>tfUQ?bTqFOB+i(LmGDC7_e61G4z_jTNf^-Bbq<+oP2T zp^*Ww-#wZtnx8rVN&8PF$r!nsZ^uVKKvG^BV@M#fG@OonFUe3k{f`3=0**XrK=vHP zblrbHl=n1cqzHvfQw4C9K=6`Q%L%fwU)Z&*3alT~H~q?g*ub>sr7UR{oINa5Ki16K zO~jT!fSTW`_rZkKeFCr!N*EeVWcTIemr5aY)VF$=l|WA70h{+j!#+4MpoQBp=z#vf zuS*R`C)bR58Q>ay5sn@J$Oi6D28AMM2ez?ZH32`2D0?7@@8U<`(|C}`M{W0cYBwap zSX6Ig{``CD8fyUHqKkx&fLU@O>;wWT8RxNl&Q!A+)qTt+)7=FY23#u(6@|=xOraf+ z4~(lWIB$@yw|;42k^w?-4hUc?Ce%aJ-*W?2&YJG8bYHa%!Z<(dagzO{C?w^B-sr!l4v!pIt4G!J7?S_D8w8?1@{%8V zKSpri;XYULixkvj1O13)Xfa>!yjkYdN;ynO+h9=~{HAmoRGiXoe&%tC7%Mv;)f3%0nm#XmZ_d_NrJV z{N@Z}wd8dr{n)?`jgq+?!jM3mK<-!=N8BDLpv_h#JvC=eud?mjJjy7`igA@Gej_0N zX)^6969fXWozAsRVrnKzX9ZRBPqsKoIoj%ge{S3#-;plP64Xmyw$(w%Ir;-NStI#- zI4R$Y+!xzv}1`twl96K|Nv>oW@Kl1c&L5S;H8VXFEkrg1}ocJ^Cq} zYt%C)%C-PpbN!B1Ir6oaUnBtU7+6pPP@2kV5HkP{G z7dWhF(tRbhhO)Se{P>{!@k|cs(f`HXTfarQwf(~b3^??_kTSr~A;Qo@$Iu|HA|TSD zB2pqC(%mH?-H51^3W(B;vssOcJ?=Z*C z&zce4KEh|MfHq*T<$XP*#Hl(bj&5m+PH zDV<=hDS*}{&67PiJ}bBsm2hW(e($X1*_i?k=-ZKyz$ILB25!OJ0ro3I1dw4C`X2f@ zQ*gV9?!>Ic>Itqcr{3_5h^Hrmto-C{49|100zDBkyQ$a3!Fe28k&w|9lKE!5NISLf zq^^5QV*qwHItOoNASy|Sh|E^r-Ky=1ZRf?;WB9C7TlEyb!(V$I&VA`)*np|^wpOM# zpTlQztia2kCAm-@Uq^MIs&@ov3viDq77`X(Ova>B*>st|saU_J-5PGTNj_=62|+=C)_qfYEDt3t;B`v$(SSrbUAloy<_>p&&lr(RmUz= z^ZLvOR_J<7@iSc2m0C;|IY*|sz7?}1cw=J2xG=RXa}PKlH%&bOZIf@y8pYOz)A!28 z(6oX(>YDYVpzHDXq_K~HIRVVU?Cr84<@7W!2pmWrcTl$4VzlbhOX)1z0S`9`c1D9o z;(%>w%R~QEHX$ySP}__DIU3G`qaoxq`yY()pS^iN2mq1 zX&Z>*dxiDdc{D+M(y-hrgYSrjXIGYkg+?o8mAf~$KA&jL^(`n3el%?N+eMba!X>AD zL{GkU`C)Ewq~6>cxRjzUreg32RA9nvXd>(9P~ljgqd;PXDlj;3o<5o+M}8lztI`VE z-+ZC@*U^U2`V6#cL~(3*1dy0D@P5>&Rd!p1RV+%943!(o%^6=x*y-b2-B!vXwQgp zkbtC7?-WZbB5K_aERW>~$-6q^SkIuq)LVzBN!43LP2D^> z(HhJTqlxz}3Ux)3+~J;Sz4Y^SBzkj_yV&x+Opa258?{>Ke%gn~+uzRR(eL z*QIfRU86|fET~$;nC(_GpRC&UQnm;9C$%b>gNxze*v46*NVknmN>*a;q=pO~oCc)^ z?iy(Nfgbwme4do8>n{MOt&KiKFkMQdB^7195-BIw9NqbzE*tv(5Y!l~lnOS*5TXWf zW!wU+aM(o;AxC?L$XdeRfa&5$u71jH=OIfwIrjm+g+1i!vw56*5_AV(8e=Y<%wF*f z1Q(*bBBHFL1C|3Imx8xSo|*`ADV50b*otUasL$@;^NXx)&CwLqG^uB^JIWdy-@Hlu zP=9Q=xztm{Yo^lCYKNpFVrTU)6sL~?-7!tSDTeyLDt9D8Q9^a40qBo5vM9HBtM~#c zK3{)uy}`ktm8u=CQx`&^OGZay=rlXP(%F2G6Yc&Ymy#W?z|UotI4UtpEgBO(s_lie zcNyRj=>v>J?2Gee8hV4bijLf*F+sf5>~^R`n&1|mlEaJ z38{ApBhoFW!*?f@5$1l!yXp9DN_qAk4!BzEIp@dqS`fBs7FOip!GD;4}p>)&| z4R%}g_JUB1GuKpno-FqNTWMlJZ2Rk9aVO4#~zP2{8H+PK-neOzPo^My@=d636h z1+W!fQ<(CD8n_y@yogMF2X_LynvLFE9f_T1ON3K0@~#N;sGofdZ(lK8HgC2X*{ug( z@6-EXHRoDqj&v9DZQBDcZGW`fhDx9TWrNJd*R0b@ z-o*FKGWED=-$~2rTE5>&&q#2&O2_M#ck@1#q~L}riex;5-lB^DAz&iwxb|dDn1jgJ zQ~dGg?g>NelE-jd@c$s2RhIpayzn5GbX`#z0hqXX zv~DnB$IiT$5j|fbsKv$3Va?_HJ~_|X@!Zo?n1;czdO;yap`yy|+jud8E4)vII_p)F zEst_h`to|J6~9z=6&PJh`WP$O!6a0yquqVwLKKVCex^$YqciErp-CQZYY>eYWFIu^ z9TKteL7Cn_AHkt$lND*FQSk~tE9(_S@OZb9(b^SaW&?j`G1yzr>2n2yltg)}NkowB zyPWgMge^~x=AwjjD;e^BhpIWGyd*xyz^R^?*ukqjBk%&(l$-TE=?ucc0Wvd^$P}53T`ks9`jh{j7#_z!Q3n zVOPY~{0$4O=zwY{TD48*eaR?0qTh5AQE1oSRdEFupMnlAt}?x^p*MHN>rCo+ACVDPa?#WRwiu8bXBu{N$(J{%A%rOM2Ab{KV54(8 z*OYg;F20}Ng6YCf_%RWy*}_&INKSoccv9DO7nk=zGV|i?`gy2UjRq70RU%`k{m%Yn zj$WrCp%4#3mGX|%5e2Jf^B`@r%M47S<`gB5JqixDvfOtnxIg!!*QXUDeASs$Mt#3) zhgczSBW#B;8tN&QwA5y>X9yk5vvoNpM3qS^O`^i(`|WeMpuVm%+@zEa?F0JI!(hYqm6iixzsKjm`hK?Lb*o*z2`o+ zReigA|3u)zgMup7dTcLuDb1B4j6HWOAumPTiZI_&0Jy`d)t<`(U2W3gbx-|-!|?;S z@+bZ1n;o5Z7d>~H5#XMuQ~3X8N~u$Mt-+f!IcvNbVjiSq4`&1LD1>=PIVlC9A?mWM3D#8A%B3-bLUZ(q2LN6Q9E_NF7&!wUXhfG&8594fYV>cDKMY-fP zjZeFkUM|>vaqE{l7o?J0XtQgrxlw8kPT10qO0nuvgq}SvZx=rh_QJoo7#>q{E#s(1{2I>{MiGREYWI^(;hZG7>b`nYTYXXz-UAnxZ&_yK_SLSrpzq&_ z`eL6St^IijLvudQ+VEwkKh?STY(=V$r3A3-jG+l+$lxLN_Ko-{Q#~Rds;SB^B`@2Bq>FwPXudeJF=?M>obvUW&R?933qZ?i zn_p`G1CA&@r&5ekpC%LG-IC<7${#I>BeJ4+B{`*hMLWVSu0*ubeE7J^#%MB9sWsu6 zk@3EX0QVsIg~gnxDjjprK1#k-^eWTIAzPDVOo6s5SNoNk!<7MDIAvzr=2%Q?I5AW{ z8o5a~f0IY0A&NHOf{%)c%9_oFiGVe5LMr>qZ*_4P5G4I>PvpiQ20e4sERVx0rQ@5@ z1`{7-sWRUSqbiZ#+D+b;ewlw9rb|bd{kon_o7G zuUhw3iK2YUt%o*_va8*79TA> zOin~7h%_uLW%vDLB-vJrOvxV8*dt~Mf_p{tcmFc;Cf(rsnRiLZ@h>p{N;xP5t(>^v!|+3v zwDXBB0$6F^1xx>Am~tfpF*4v8hYWW{kJ}SkoxSi4=0`u0eqYw8zQys4HET3>{8qxK z^SE7NI*Z`%Zv3>niO*f4JoQaP0tfY0yvj*y1Cj>vXk>?*HwFR9Bm3!A6Cy(iz$hY@#3iX!5>A z#jyK%g>xvr!?C8iV#le<#wU?)ENQbk^8yZ7v9+i*`#qAl7@Dhr zQEldd8!eUKYwJ}hBJZl;QV^9t zS4id@mWy3zb7`4ETuEmTH&!vXPlaGfo>M&yO$xK=eSFC_?Y>$$Ps9tD0C~fd$HE| zi~5BUju*Udc`hum#b|V1wpS-(qD`xO?DeKW$CM*eZfYeDf{0e5a79ZvKfe0LbK9Wl z7ZA{vmd?@OSOw~aqN*K!Rmk$@!j~e_1HR{0p_=mcCf11``JyM|GQ4P}ZD>$rS7)RA zAu)#vrV8qx)gHJ?kV9|WoBU`Khony+^I_e-REV%l>I9Vo!gH&s;^PuHM(3kML0?-- z5HVa}*Av(}9yU9so^B>L#r zjB<9IO_E{=)c0uikfhh-tfUXH=JA&}ziYk}m=?0a7`J-yo=14ezWPs~46KB_cnRGF zbe3d)gA#?BH%B0e`p>zln7uGmtgkd+e*i$!VHy(Ov@65+374pqdD$$lj1L!*^U%Dc?$ty$sS^^&E9@~7YpaZfV@+c8i>4NPA60>)5Z6;R9F3m`Z* z$HlB7*hc^m{F@-sA%1)8f`4RWf9%6GjyPFE2O`KCYc%}6NLTYpI}U6Hm?vY&6?^=< z35=?Cj6bMvSf1o77_zt|J?o2X&jwT7ds*bXQB^j*R?pLa;!^g=Ar9rPm-;C1QadBU zc)H#r8JKqFwhj(vf+*)==~#?oLt}eso~;3dli^uQ*?v!mGHJqLtrbW$V`;T!? z)38(nO=BDKFF{6w3OGHPC~j$H_F71wO{w&UMusSctlw)Fq3ZmLPkBM(pE-Y|B!UF% z%9f81mT#?g_>e(@^(lJ8k6f|{+z&tPu9dU$-imYwWmZlbv6)b619GvP^ zBNj+SNGOWrCd1BUq+TTyM+cF*dA%axVSRbmXZB_7T%=+&-!#zDGw1^THEmKm;ThgG z?D@OBFE@NPRXytmqs9aErwp1jPW6B~e$qE!u3=c~0vBrwnjiT)L*i~^ub)X2fXmZW zKXrOW!F4UYl zsNy&~9&U#~OnIcasdQJE6&xmABODU)%k5YgdiWA0*{||;_$kcfWL)Bn>-(_uLr_Fm z!XI^0lr&aIt>syHN(@anEgJ&_ql%p99Hsg**)ekAG1d$kbr%=lzYod6cahSzVMU9teb zgnoY0K7!F>ta203M)A02$OVXn;;I!B-|v076SOjLm1C@1IS5nzx%7e8K}D2Y*j4h` z$0i?U3I`r?-<}gdEDKgF=C?>$S2x=?ZFlspg7+YHU8|hx!xR9`W~G|*o1#jAo{v_- zBnuzf-eSH3AWad5FS9?IQv-7^>xhc=V%u#zfH!aF=XB0j;*Z~Y>;H4T1ZV*%AJ@}w zLu3Dgm338xu+e^{8@P5}g@}vyob{a|>x>!anAahPcNwV3ix1(sJ+m9Vm6dhpJt!uu z2%t}xrJ3)})x{|`j_AtFTAM!=jBl(9{3YD1*c8qd01@d{YXZ&V0Kh~kA8Lv;t_-K? z0D6FiJ$qh;Rm^?QZ)W__x1v;Kk+1XbpCEAX_W@tP73bn5<%RZ1*FmLoTreHSxb_I1t-mPH+L!7lc68CPTkcyt7Rss zOM~%HZZI~g)H`1Z%^iB?JlBu9Pj0{e5I9FsUu>coToG8>h=eHZ*kHdbMp z>y(`vaBsq=QEnLG0@g*@t%T)+y&p_{WR9v#|zBRjMUQ2#nEW8zRa`LOOpnuszt-K%D{i4=ccf7qDK-8R6n7=T5fjJ0a z&jgmI1$u`b*~AF3CtzvWxrvD;_jAkayrz|WY!YI&MmFOWJFhdI^!;G2C{p#$ ze4nyR+Es|~8%!|Pcu7o4O(xOe%7Ss~w>ytS5Nq`_c-YNlyqSr%r}IAT;gjv>slo+} z^OWeq#~K!&`=(#KdNC;hM^iUY2Q5Z?kRu=>YYOjr%^#{&A&@Qno>>POMPsM6>mFY= zRGsqgs^{jyfbA2H^tK7Wqt5m^s4hQp`aA0tI*JL5ialXZBy#$yQiGZCC(!SRaA{_& zTgeWeFP(z=62Jd}=_+^-HiGXEu>aMZCYO+mI1RBM?i7_0soPnZqjIfT;Q?TjKO*m5 zGFFFmK$S}$yp|u7$5X?M(LK1ghgb2Iew-qLQ9$Ei@P1QbfLBmDi)$C#q}{rehM2M= zVpK6$!SG_r)LQea zc^k}X6Bn=1lPP?C`+z6eNTe}zSXN{0dQ*1uFS#*&VIwQbnMgTnR<0Bpp*}!hnGqH35ele;dH^4n>^L^1M|v6Ih_ z#b$=hMYriFGC;MsX~`g-PtJ)FQS`3F84#+Cx5a|uid1QS-XsL5C*4*C^Y&%J;9TfJ z7x}=z%))su-J3}z9nLS;KRsu<05*AXD2bl4N33eQJ2V~{8zcezWwORL_+`PK-`7el zg$S=|3CZ?>YG)ak1a&P_`fO04l%2$!j~}IkCY031RMQfrx_S7v#a1A|5huTCbBia< z@#qQ92w(LQ-8A8gCecEpp5Qo@LpBn42igL~7RJ@vm((HLVvq*CGg_cdX@LP^E=DDYj6o5SQNj3R z#G-6eA3ae|b@8@Z-S?T8g#UOe;}zL(L>TPZ48vLVhhxiwAw4wBRlua^qdaX%q?m@C zR);S0S1TA_wB0O?G9bDfOCaUaZs!MKO>oc*c6VUoeV}qlsWK)(y2r8Miip&~W0WY_ z!;P6{&r~;e9)5+TcuOixR%&+c>@GeMn`-+H@xLp4PzT$orbl*fAy*yo@H2C@$=m~j z+l&x%U-5NNCu&91SdGZS*cC63u7HTlT2Zr-&P>x8Pi{D zBA^ULcRrH`%371h6}fGzY)U5ld#uh9Kdr);>CVL)a{sObsmg7?I#&_D$l<49j9k6( z9X45>O2{d=E-^PxTeKEm%2AibT&JzHeJIq(zKWKAiSO0cQG!xcn-5iPu;GntGdW7) zd>>%06z+?+C(xJf#(W2s?c_17W=NB1waFS?4_fG;y?`}|laf|jN1Z3jotlWn<70)7 zPcH+LTorThMNG!s*VjTnIYfR7#xi?GR3gW|1D6OC|j1Eis#YD+- zkFxJ!!)3IFvj${nIGmw_g0{Xxx#{q=@^|AU123FU?H|S26BKBPxl6wk|K}D_%!Z-5 zRV6JJ%60~MyONbGRrAyu)ebsKWMBm@;bMV4p^&h)(4_lSRMB`)V=1s=Sma(|o8AMB z05KqAcu@sPI;jWU(Si3Ib5w>qCDL_MG>en$1`X>HAJ{wrr-M+L`O1^VO(zZ1k34>A zY2-`i7QD(KHqR$KQA02@c2rX=UM$0}11Nat;-E5|o|c|{U3mA?R6{;ug$svq z8f1Ujnx>J!VN-5I#k}4ne|kujqPaVXZMMa2m#Dld!9~phK1+i=VQ;FD2y(_9ZH_g3 z%^Vbm)O@t4zGG`YWj3CQvw$Msb1sD~RC8p&CbLydw;2E)RrLG17t-;Rx10hB@dB}r z&<>l9JdL}2919LBz?O`vU1%-Qxj=EbspUJ@`Z;_VimfpMLsM-B1$wGP#G|D^Iq*#i{f5UGJl2Q2On$ zZ89v6os(+oXyOkOp+O1I`tbIZ|IS$JsyX{IU+G#7CHozX9{3~w)7677zKX}+Lv25K z<(Jk1o$(r&S*k8n`EyfG{R+0@iTE8lR=^E9VIN>;T3IEKevxD6Rj0-%M1^yJbDeEX4>Y-LziuR0_!-kSI z`x{5Qx%8dg`2WL+^Y2QJs^YH{D)p)*=xEg}Rw}Nm;4LdpkP|`7uT{Gks^OJz@NcEY zRxonjA#6un%9I$n1S2C7f355{v5;otWjwQ$8Ot}YlTP)HLlB#*T$FYVbmZ13u2GPF>D^!C$7ezeCKU;_Y{5%qFd3CTUfFS5#po1RYqmlr1?#Gwl zv(Ke2l>jX1M>Pk6|NWEtSBc@$s! zzw4ia3`pXs@N{QTI|^YCQTxeLDaN;VKEGfArOt&F{XaikbjfmaI6J#K>3_TnxGQTE ziPygZ22sWgVCKpCX_vd!0ebWnocH3Nvo8L%3j}CUZNO)=W~(ax_h)O&_`!~TFXya5 zEH5YmMfP1~6D_mBL){ol87 z7Lxz}v8ew)v04?L&-a{`|9b=SKEls=v^Nfbs*PhYQmvf znN0u=eR3*xq`zj{*q}4}Rh4em z59pHzwC{N&M&QnC2{7G4hwJvt6o|*T+~|9J-l5hc11B8*jsMBaHUY6E62wY>4eB-x zwArbtQ@0Bdk{3V1t}y+v5RT&fm9L;vPG^S?c>Yy}09v|hoC*}bS3WR68b|_~a49_? z_Cz)g`YedZ-+f7Y;X5hjScpLJ08*9{bon00Issu9hd?-+0>V9jo>HK?PbBJM%3;v) zWR3B0dllgyJoNvjCeuo9nx?x}Xl1b!R#JU60Iv9={g=<@W4-J3R`N&9Ip6%gz9gle z*|0#32$fn1Jb5WJ(=d4{qbL)&t3gAujZ+OV%j^NUG%#NT%ZlqHJ9OwnOJ1~7T)6n>8Smo`6$-h( zXc;PCnA86NHyaU%MpGKQbbu_p2Uyl3hmD_9-@ig#YK5P1x7w`W@s;PZx+fz?+d)n( zkod6Jwfth@nfX&-l21#HM1- zi)-;2EyneVncnK9xL#&1cNppBx6eYLxVL!mFXCB*dp;ULV7faia8*G@u)?ijPTj{U z@M!=QfJlYz#DFb8UVzk)C7|T>0R)7z%rRIIIsp?!AL1pA+6bUDVfCB|kXfrBNHpr! z8IRCFQ9@J7rYlZ{rMCO~F_x2)?;^7yFQ-qA4=K-!In1?10E5I0_aRkaD&M7GmKMAF zCAkjJ02wn1=a9}#S{I)0fRAeUHT4i=;(P-W6@K5%*ZTb8`Y#|S&P>At*xu%m>>F(X z18Ic<)zb~Bf8QZqRj~23TrOuNot^aJnlqsD>wx$_vL4Kr#5p&Qd9~lIkY2T;bJp|;;{PllfdVOa6wO0oK6T>9~ z0^Wyx8o2SFtH-h6qGUqU52;b%BEWmHX$o9UK%qSep0y!giq;Y!K7i(tzY@F}-SZbf zO@@HOh^r!8SLx5r2F~0NNPpp)J!U!6ZOUi+Qo|*Kgbf~mzTY91OrTacKZKk8(q5VD zRKd7G6%lED`P)b7e~$HyMyTgY>Wy>r-@zGy^%oZ?-#>X--7npca{9)yE{As<@J+z9 z;o44nb)m^0n4^|JX|ueR^8Llz*i6@FUf8pDOIi`E8ncOQ$sg+sIH-}&v>lj_1|yts zCa9NHJ^XF?-S%rBT|y~wX%v?Nf!Oto5&u-`80@|9^Qlouexq~451?lE-?Dwdcnd+DyKNl4p4!rt7>_4e#P-a zfP2+pTdRW0bHw#de%;p`Lf`dOb+g9l6w7&Sc6l zBck+!__4p3UfLlcDcy_;qay?aK!}6Xdp6@`fAdjBGBV>#@jF+LWO*APp_)~JT67s$ zU-d{<+&6(PeUQ+VY_j0!fwt!^H=x&@nMpLK@=<)tbw#&$+rbKgxjRH zFB_e7GQG%d`*AtV&M- z$v{b<%{Tu~{00}+Kc_nF^`@@tyGU;d^qQfMGhyd5Q;mISi3fbMjOH733&M1PyOW zGwUgMrxqqno$|yxkK$2bM0NIkX-W<#*$X&_q3!)hHl6u~I2-vxO2e{ks&^SFb%VbQ zwyBJGSzqk5ER@_##L9<#=jK@Ej2a?rombB4uEv8{WgXK2JD;TBo|VR$1}+bWm?;Zs zrQ=3V%Mxuus(%_Gv^n5+l2jdN6Oar&B3^V~tL${m<+=s4Ea4j=N-`AoQ6YT`PT|U) z4XUkh>o8^ylb&>_-4!t-++8q4HIqt#*auejNJU(%)|*=++&o5>qR7S!oQLNoB$`^ns2rbPkujlzKE1r$^yC*R{jsRLe#@_r>UON01dn@)R(|$!M99 zERXZb9=2gSdK)>VCvWafq^wASR4pY0E;0jlL50I%XN?T@10EeN(pHog0<3llktaCs zO|y@6b>U_#B`d4f0#$wZLsFa@3DhS{GSDnv05f94D6%jv>|DaeZL7aE(VQ)eRu5rc z*{XsBTO;1LsaVq!)}Ml+BLF^dzP(Gsjw0>y!yhlBYUyY!139b2Ac`5x5P=&G>0C|0 z2>SZI^*-Dks^0+h#BOOf$MpjH=Rk`1)SJ2|+Tfz`szd})7)c+#1I}!c@-t_4WGvWJ z`DP;L1pZVJRQNbfwa3@^l-S1yq_yQ`&l5&iM3WqWES}vT6ZC8>Op03#=J;ImeGIBr zDhT%9a9ex8v=%UkkdVm4C~PzlDESxj?HO=j zwl$XsnPNaKx7leMhL@LwU195|ZZdDaUIuDQK?Y9c>vKyyHWzGcKn{p=)Q0>}`+Ja8 zRBJ{3DP1s41gmW5_j@t*n>9!}BVF9ymMq-{!FXD0vBLA#lpqx+5puqmii{I>8Q#%D zEnJ+e<4d+tDOe8ftj8pBN{=nwiJw~$gfFGo9{!Uk0q#m)iha2jt47em0~mTXdVh0n zcOnmat{=~ylzz#1?YorYbn)5A&P#{uFYJntCI6OLxrH$J-ZHSPU~f}aD`OkMUjTa) zPjg@(C^7Bh=I(RUeD#{$W0bU8*(~#eNvf}_#Dh4q$V^7goTaXpE1CfMBhBPUrJ)XZ zXose;ab&2{-#)k#z+kpudJ!x~lwsT}NZ2DX>Xo5nHjHodS`L!an`C_>??ZB98(*YU zn^lvGyl)}tYZ-JixLRHw%x2qEk8=(#Ml{fL8-+Yo%5AC7joJ~R4;=vaSl1|e$}$ZH z)dx{=xjlDIz1(5iM4V!UfNX#U&1?SDHmG0Z-&c`761%oJxO_3}jqiS4_pHE}TgOD2 zC}jWJ!c{#2MT+q+$$wTL9B10iZ+HDS(g{@gY>MWdG!~g})2S0X0T~?j@{yql4{Od2 z&QExeq0^0K8|~G0C-5jZa>4!Q)H`72-q#I%yD8+Gd^6{f#5=ea%LCUQT&)jghFK(6 z*f_G54f+l*%8CW9_t7$yD+k)!Jg=oiEybfO;8#U>C~qmRB4&6!g2krm@83anX0GzU zH!E|^AO3jd*lwwyV)w}Os=14*hqkjn8e;GgP0@ad_9JV?MO*>Oiv*!DExH)r_SauM zCNe3b?JLD>sFo$enITg5riuPu@&C)Vn>z}FPw{kYG;gxzDQInXKec8GXWPZf(_$SN z<*AQuzI?Z*b@ddhY0m6Y+OVAcu!S44M(!{z>_d*{Cl40Cg4kaq+6vsny;BBqQe9ia z$RANRZq{m(c^kZ&NEvLZOF1QK(G1@9A1^15yxI z@csH$#mutm`%;||-9IP*x2h4eT9dwAFMu@gznx&%f7A9KX;}|vlZ@2L)|eemE+W#) zDeCnw4B;?_61Qyf2PHB0&y@6HSqUP6_4AOP1)Dz&ey$*nPolpvF7-#1K@!yjf&mg| zU0_s*`JXpgc&R&pJq|$*X-gegtAF22#Kig0r<`K{aTtGQ^C76X3qnUsK~0E1 z(hE$CnMoaY|1ER)RsC~_UKelLs}(c?e!c2xZ!uovCX-h5TSwm#-nb#=R(@u?k@t3g z4;49F?{@D})}P$W+(BYXNI1K^4cCrRilL{oP4o!IppW5n+;3r}nR#2hg}9X?U5#LH zQ62=63M!^j2K_#H8O2Nl{>}en9~?$+f#AOgsSP*l=WhP?UJ{^{ppB8SY6;e7(bExB z7Owd1&k>@BnGFWfqIM(3FM7~M(eO&~3LBMK_)MD72j~wFS`f2Mi;AQ76E~}_$8E4- z?j|9cdo%D-o{Vafed2k--g}I+Qp(&JLATMFHUzkshWoz#S`TS6ajAabI>}wY1>^kY z@(BF1&jLC8S*SuhiPSS6EW|mgr5kVX-N2j^YUhG4aSX!vq)H+0+9Zsq-Id(4Ks$a4wj97s2m8`Ru>phaAe1SbbQI(ykloU$hm5n<%W(x& zE)=#wO_AalTT=&G7ye8twJSPZN6rEO@VJ@nWe*f({N*k8$knTGGpYc-P*zbv`1kA6 z#C?6P*Rsw|#9ZQ;nzZBwBMGQ2gEU2)rcpD_pf1K)cvZzskFM#W+%@KHMbO@j`whOj z^BJdV+E)Ou2=QAy=M)v&X4xjS0Gn7T?p~PcH-cQ!{*$}Ih22W$n8n;z^y?YGbWdJ2 zdR$0{Fe}VMPd0z2UOWMjsbUNG;{t=#dbM}bxY^b)ts70&YJ^5w%$VtH?Q?A4vhws zZ}b(@TSX+KW`D7gM9%mO(RD5An54hy4WTepIFB8L@jQIAwq^aw_4^+SjT8(HlMZ~n zcNYTiCRGKAhcyKvqh5Qsa$ zl@$!uI8-L{&Aq>3R~kZGd0DALVfb$gqi+a>l~sd|RXvOOs*B2kqkVXAz$VIj6OqqT zy*LB5a0KDtd#Sq^k0)!fMC0cwz7=Q8mG}W?{eHt=fdE1>vr3xg&cG0LMOm>OuoxVUauov`w@|ty&^U% zShfQ&(W~~|X?1-fy}0l#fG9?v8yogK7@LEXnv5UgxhoBZ0#t_c3H!<%P~*kglny~d zW580S&kW_!r@4JmN|7^UV2gM}hD$5(0U9bDRa~?EE=|*656sR8M$^$pwoA6OP*eYNFy0G%a^)56dz+YT3$YpAw3mth@cme%23T2zc_U5gt0AR^Aa3GWa*&Zw z$v(8asj27ET4D?8Ga-=s?7-ykshp8STUNnxtisCk0GD5l;L+8YRzy3`D7K7uCcsCy zy}yU)#IlDID86iV6QzqK&J<+islqg;+Su#Jg3+BWckt84kqZppuZRZF1`|+*7plng z0ek;9lN%y6#5!xdI9)Cwy?K*v2)V?Ve={zj0nNq^XM*|1$rXTJNi6V?-x|S$uVKT% z)<~kngYga!CF++ybktSH0NPy_+-CwDDt2ihZ*bo{4L6?h#1D{ojHC^^NEalTFyboS z5Aw^bY8T&xZr`Jj-Dolwzwy3gOJPr_&$}BzW!S zO$ZM(mwBG_H$YeBkC`dDxOg1ap(1KDY9^=PaGLSok0rM}+TX+!BCJ>`)pco5>$3Ng zVt|>}S~)SHfvaZ&dIYorxUmFn%Kjp;DKWWmP0Z&@Wb27(3np1jnqI$JP5~s~EG@`Gf+nkPipe69@mQ+`$}E5y(~v@!h2=rk>wcGdYb$8?^nPPr zKhagBP9mxS7mhO-XJ2yCLq-$ePc$lySkuitRSF`aO0!<-OAkNn+W`|+c?c*n(Ef@# z#2y5wopbXfS_q?7bd$gso&Q2IkmxRsdUArqjOPw0wmJ9}lDLqv8$iI@SFDkh+4S>HeO?ENFYx$lL@1dNyv-ehe6GO7S}oN_@L>8io503 zIgobYY{#R@;ZFb2uMAsW6=Pz7LpDHA{MFFy+3_cPKy7Pj*xuFi@RjuZGVQ_6h#pQ9 z-C!U*vcZ6;@bIYC-eQtwi|7o-azvI_p7ZhX_^h-q!~=_Q>0GsCmDNQA;o0)8HhH zSL5m=N94&emMbKWTSr|4P_U5s{I_IeA>9iTxv`7j2$XqE6YL%;_yTm-u>&#pw^Lx= z2qZ2^c@2TtcVmEr@t@<%xokO4n8c0|hw2x9d3{&Az7IBL9 z(zR$4yVw3rvK2+r_$kAe?SxIis(_f_hF_TC>>Egdmnx?7H(daPZ2R5hV{sE{rkr!? zbq~gg8PhjTm#TkH+Fp4jY<3nb7;yf78}b&Z6}M0u6l`$`c@a$54dl^gQqhnAPKbLd z&$d<2gCuc|;#I_ju>jOO%v$9BsybE7!`@@zX$*Vmn5ztr^vB;F?)1-kTg zp2`&o4xfTt_|ClMwwIkT;Ge7pZx|(F1|MoQECJ#pMbn@daALTl5e$z+%qj51sOF*>z$@f4a-D3t_j96l&ixq#9iDB_hj)?9W(lHvA zt`qr)y89hIUx=uWEd*+39l+a4L3|~B)0X$=KU7+~F60?cqdU^a6#!qG$`n)qV?3Rd zc16XZ9~rT0z+w)x%&Z)J%O>R)CNzq?YyK(@{J8*;P9)|e^_#42 zkO{N?hSZn@k_c`+IbW%pyCD9_grGhBMemxV01;vQE$5hJ6rL`PqFeJq1<2NM*|;~@ z^E65rA_{RzQyI0ojj<7tos|7-dgo%jqE$(hNLcEdUA5eE^z_nHCHr%dk<)VNWZ8}3 zKgXGPO1lE^%JG9r1la^yDw}*3=t$dqsx#^5zfHUm;*qn2lh{1Fu62!K!Wwt)m0=+T zj({xl`o6a^6m)}5#b>S}3+RcDY;8vbQXEzMtlwHqEYZhQ-v)_l-S)56Zp@GGSTmk+ zJCOxi9`0z1cZaSAO#pJt)-?1~jm-8G0czid=)i0~NOaa>1fwQ;XVKVJp zE&N!jh5i=HZm`Y^I8ljm8v{cvn!z$GSFlWy_9@GS#FMz%_bnvu%?)LPs*YvFi0I5` z((mA>IQ6D|tXNBn%Zf5OxZ>hWvXL&Mybq?+z?!1Fm{h~MrCFpcNl`jNEMqkV*TL%- zLeZRIY4;l>q!dEsY%_)3Mh(;}Z3J5R-Z${$CP4rz3^gMq6XcV7e`X{2PAgi99kVYO z3Q(B+Tfd?LZd337Y&3W_9{=$S--uTfCq^ONF6U9%T2FqgE7O1T#&v}m3t0L>|J6Y0H@SJ<5+Vn@;`ki?y=Uqn>CeuK}P4kVIm1wnr5QG_aeSoWu5 z&x>JI$gWj<^VNgt?I*OW%_>FZR>f=f15f}rPhj4M*6+G;K#Ol2-vgiV z(N|BKpr9IjkN?zeC{4f_C5HZWP=l*S3!xb44Kh52vP&bJ$1#x zEr&rI|JN6^xE~&s!>|3pF+JZhU?7IsMU3R2T)U1z5z*csV@1o^c3B26VeyAvAF75T z(e8zy=((dzgsT=Dokl`Uf3YBMp6!5Cup?ZDJkN+MP*tOt0BD4Pu_dbn&%ti&+2$I$ z@Ds#7Yr|(Re0AGcg7YHI-wnZUKodKIELJo25-TE4fRA8oL*{JcT2zZ6O|{ovX=uJ6lM?u~-`T$Jy|RDEGkQOFZ{d&q0UJP?W7 zPSn(HmYVcYO0WpjLY(21p-;t^h5d>j9gh=8<|Kr5`${e*$?jOw|LNJKwZT`Ab={li zPq;gH5?7G67nu~FkdGnu_oM;D8W^Yi?icWX=%%6b0Ei0Ck|36+b$E9#sA^lzjY)2a z?oIohUQ}Qn*PeoH1md2+3iBHk*` z>hbgQy>u;X6MFgiladZ^EELi*bra&T*M%9Gxeb}TzAFIo@W$z$YcDP>e<#&Y7kAk# z{*WR3xI($1`;Ijo;}_ckY$!}YEf@lkq19ATGJZStx8Lmn&t%M)^_K_)YjdK2=VJi; z@t?tlibBzLW%-!fr`y4FDnXV$yJ-X;JgvHm{oYcDssU!i_4W>qOnG$R&XNWwZyPKw zx4GKObmLJ6!THYRE?2-v1*@@5(Ug>cKI8zZr#BVTew%9usPl+2mtXwGUn=Rub*;c& z0pt)1a8qkP5Y;Jg$Sd~kyM}EB;I;rb9D+F z>syoJ51F?n3%>qYh|e$!TsR!kuy3T%&Ul348PRe7NM08lV+w4&%4wJ-Z`&q zf%TfwQm^%zmi7J5or8JUaSjpdHrRrVZv0ZZ(mqF^REBE&PfE-Tgk4?Sajc@R*c+6g zjedS>I%%n3s(^>C95VoLKq0&d2xEkAWC;aR6A0pa1Y*!p?5X2{=^uHT*yRD802sdo z9OMJ~#;WiI%li=d&`ex#GB8lu+!Aqj2kxeZ{W(ADUT2>!kSlnPF81*|0J$#pXZ3D3 zsgL@_!aIEu^AgtX33mZ)i|pan|I^lY$5Z{j{~sKCkL*3NcZ7@+vO{H-kWng?QT94E z*Mv-@Wd2_hy2sN?kBwG(cN;@F4Xw+0SA`p6uO18xF<)6|pl zaXntqqI7x3G|zK2f;OQK+|Q3eNpMb{KgE$Zc^i_u^>scB!X1Hwid*iI1Qej5^ar9W zggC`StbV0>zv)P8J3#cs7peN4>vRGiS{{7@3@NM(n95x8HnM$W_P8~ULw}{1Z$_Go zulJcS|Avkgv^SZoz0O%`6zOsHoH2c9nnz`HZG`uiiG8}+{t3xlC1rT0Myi)nCHvpY zq$~18FFLips$Y1s6?i_zA`nEcUjUZT?Ddj&S#521GbpmBWsVksK#NY~A#NcEAT5w? zWduSAp5S)aKAhVywS z#yhJoEM^lrl&pbEL_kdC@cC49X%4qQp%T{)zF9=}f4Z2LkP_WzgT3zW3xU%V9fZ0U z2->e8%cz(?F7*irQ7*l+FrK2-9$>XDO-<8!;bk!4rRdbp?NS2z;gnnK-X^~%ifIz zil~B^UL2s+T0e6J>_D`zjOH8HHUI6GOG1K&dV#@z2(r)Gmp8Y84W`XcLdP3YQz-*efn}t#%{KVNXF}uT`Es9b<3eYO@YJOG zZm$M)slF{lyW@=d_xtWV_xusiDO_lKqA?*zzP?-O8;#3@y55zJ+WVr%Q15r4=dJlO z@X_N+Rw-K)v3S1bnOca77H01bA5sOudBe4OP^^_*Yf(BmQj-1_w!}+sqAq< z_fsSLyBbca4o`_i=LNO>Axt=?$Qx+q!SZN?kEL_Hdg0#s1G<%W?(Gho1rh-Dk$I_! zjxmaE?eZCbT3IHKh9}NL6PA7BW*B#S?`(Tf>q8t%r0Is)=nH?>*YR(WDHLaM;je0* zphA2dpc}e(!YK~4!$Y)}Z>1sbP$UuzgMpnTaiQ~V38$>RSN>VSGQqJx6UUy;q<{7a z)PDt}e%niJ=r5#iUEa2><#_ElR+fEo>$)*NBu%uKq2enqF%?Q6@=R*si!-aO8dlFW z!_O^K7hO2S{W1`#V+^?5lSqTtxj^+)`T`&(Vs_i<*|vnZjh?{!Y@z-7xBpR;F(!ng z^bqw%2v8pNG2!T~oA|u+fqGEimk-wSwB6%=*@~gmU~<4!AcRw~#ZF(6gWn zMgB#Qjcb1AG3pQQmTmEKQ846m_nLyt`Mj);1=+&wiLxgZ-L6NYea0VY7apH+bw^zN^ zYNmpo(27O31-FuM*)Hq`{ea`b?(=*Ftxx}1Hg9k+;EtF2zCTF$XQ!=m;a4w8o~=D( zM$4h<>t>GM&d&zQu!kMPP|^OUE&9+d<2cA`Cxt9r?G)|tL=DTbjSV}Vrv9@{$dJUA z=i-sQ$-qCLy53FH*FXbYS10Y-vxxb&2WkLlz{MvRZg7!D^u^l%(5>yz6^M7@|7Nc! zK<%!Kqh+&zAo+U<;5P^{!v#jD@g4Ke7oZbT#0Qd$kn#6bM3iyZHZN9QFQ8&C^+kTUu@3AeGTo1*`yccBFHfT*H#ACi zX9sa`Wefb=xz6a+rW@f}K8d(E)Mv%psrwG`Bx;Zy8Iq#4(Bwc_Oe6{t!L@(_FEJY?t2JHP z9+nq+TBN1f#|=72*(ELiT@8c+M;J6u^Uvqe37y5y4~;!B3HXf?(0%jc1Cz)j2*Bdv z7rd_sy}>|U62~5vgu2hm(R>LEOKp&zg9S!e>n3mkk&cR21+W(`7nf>nU;2+(r<2lj2%JQ;C zG!=||Dog-L`C~&M4muyg@A%1KTFR(jxfklBDbs(~jSvBb8XGwb_X@h-+p^#o>bn;Z zY9ed=fHn9T7%m{$ybA6(k;kBBJ}cc2vcf+pfom2gufR6EF|EQf^kSL z^b&;U*oT?{Gg=0Mc3dU)jr_-XAdtm){?F1XV@=7_^7;NZ02gTFLi-32TL!wFwC^ux zvsm1EdmJ4yB2okq1Vwy1Z*;h`9aMkXfaSRly8klHdCa^j)8J4F7%U*xSf}%$rer^L=sf z-xumbffCRapdBHO-vyGbM|YMY$&S}%9`}lF2D4>gkJ2}>@)_`4Oy50BX!te&UWdd6 z8&Hocfhl+}-*vY~lFN`F-vH@XJcsL%T4|R1m&$aK&A-9KpphL#NVMScKU@76esh8% zXvlK<%<|mpxK=xNAJKIu3zK_q^$Zvn)Bt~HT*w|SwtQx4)-m=-GZSchp=`<1DNnX* zgGq{^;6NNY%vS&edk?AL>WPxkv7b1QxV^FP$s5G44X@E$T9c9$Y0Dqu&Wf5@;piZiGx&h@Knz=#2Sy$O2cW5-7 zAYxZ%O`bM1Jk9E>$K51sfmKigD**xNz;(#UeuVRJz_F4zh(&O?&tjf7LkL%N#hzOY z9Tkjp?}CqyVE=|I%mYN7`O=XEpMRE&-}omQ$ysSI;rP6&8K~YJQg)k#*LJD4D+Fm> zmyR8_{UJrPc#gX=#E5b7c&EdVwqM_nkE(Fm_CFIc3EB`Emq`Ym{Qa!|g7JTms6`!f z?WWx@>6iTh*#F-T(Y5nIxbhCYX#Vdz{O_0i`CF_VPl;ZsL9_S2E1Mfm=LMI~*6Q4; zu@;W4uENF;rL4b~0`e=2O^}oE)o&m<_P7%L<$u3&f)V2Pwi39zl5^$olN)b4Hs&jf zUvP4s`8FFtA!*siMKJ(Kdh=z4)pgo)qnM#{Q3FFg*{MV&%H;hTZ&m z>AMY0;daNhFM-RyEY9J>@V8C5(}}QaPlsZm&PP<*MLe#>){(O{vNk-HtG>p=SmmVq zc;Wq^UGo9yArNs%6|-E1?S}Z={RHyanW_bl5~}al^X~rsNY)fx zH~CLgOJT%*sJQ&N%#A0t?&Np%mysZys>n_koZ~#*Y1pwh)P*Gjwyg2F>m&Oi1#^RUv8rL`%2a#ey5SS3 zH4#bMu2k{9;|~Y$vmU|ARw3oiUsjwcfAsB1#Z^2rsj+a`2HaW|A#>3tL@lr)f)5dmM=%uN+H(l-paIth%HtYcAkO^&WcLyM1#{6;7WE4s-gr8l z1;v0m&ylRdZq65F_qT)y!s{l?_1-hmz~FBP28Av`Gm75BcIW4NL^U{YC3AGjGX_HI z@oZ%lyaI@`#2nXq!Hg&$kGmoC`*FzL)olkJdpsB|aZM%Ks4egB+@+Va5qngY({l5- z2^0)NNIq==6d;?)45qn1R9zdb^LD>~0~m_5xG&Hsy!@$p3E@NsY_CJ{dI1cp0Ew!H zI1veP?Lpzp@otsF!+-CHeZ`>CT0t>r8HW0{ z;D(5Fj3Jmr#yPDfmAh4dr$#~$YS?Yx;~{`t@>cjH55oFRcHN1hjLt&+cmVhJ7F7L+ z#Q-=Q1U?1Bh_;>OVF*;g7uj2K1dK;u_racOBTreuv*?9p_e*HyIm4v@69Eu`FX47~ z5Vj7lP4U3~EsOMeBgF!mGzFKh#E~sYCG{;|S5ojn@LV&bXm$c^cPn(V|b7p|1#p zYwrTOt*gLQcxoAH^>=Kt>o~X3IBA-%)wTaZQUe`#Gal#W(h)svX=3zPeiIC71VXz5 z23l4>UW={ZSbG!vI}Dj*p$Z3Frf`#7I2|djLpzWq(AHgr{Wn8{Vc6;V%3+TIjo334 zm*kv!b72A+r2##%x*#5;Z72MV@!Njb7NW(^MhPXxdSvXqs(S~KBoncGag7E>+VSPf z#ga))T)T@AAhtw%15dOC++KlMKgOG3v3Y0_)uP70BfN9c@sh<6MK%~oe&Z(hpfhHo z9{F{85vZQGkfYIbWXHVVe*}~mh25^L)m91&=N&aDvzQ4Y^VfjdyaETAKM@0N33?Iv zqWeWDcUX`h>SWNm={~|P!X1P+hKvnBTN>e}!>k7~6_;4LT%iK=|E-rZD08~2TGjgr#J;5YOkvg32a*;edw zml%!~bWnIhZZ^)f+3+TC=NG(r#HbC5YsHhaMCky8IYA?0>*um$X(4IgV8vx~1MYOP z^_zOf2IpX|#=~cx%*`dY~c`fCSP~K z7pbdp=g4SeB9o=SC!?P&0CFV7C(@Jskx51=Q{%59j51`x5>#0}PCas)>o0&|AR_yt zGXO^N>)OBYq1p+mg~Y#@$3Gw&e9p$Vq7Th8k^Z-<6F*g9( zE^V=F=4SeT&t%asngY+{+1mTJztdpM936Kyrt0eFg!ZKm$nCr+H29AWh)#e51H`3%KzH$=qy^KP@6LzTMRT8dP&cC#6{%MVHT?zyvsg~~eOwY1M5(wpRxJUyRL4`i5Gf?>WXH5pZ2S%k zY_%!7bO@wLk)0=Eyv5F1pm0{2=d{YN@E9W0RqePRU?alUe`Y?~dl$m}m=H?XB`Wn4 zOw)Q@1YtDIc2eQMdFZ#5hCeUys{_zA-6834f6%xE17jp4HKf>s zBPUDo`++~mf-j4jNkyTLU3^z;S*lT##8oXufEtJt-*_+&O@O7#Lbj+zrKV^Et@aZB zY)CI@THHuI2F)Qmaf9p}-h-*&7;RcC`U7d)7;mFV`ogD~ClA-SEMHyz1QUeqGj71h zH@Ks8tLiP#P^`BxS$Fpn=nVl|lHBd(^22-iLMcsS2FC#fk=@YF4XCXL1lM3!=aFbv za8SF(;d9sBukwSzCz|IPJKaZqWF_S+BD`DRK1E4|K*Ma;ot)!j$9L$7o&jDoGjDz1 z_JF;Bh-cITj^%Eu^J7pxs$qduj(T;!tGFXPFQQBFRL0)Ni}OUUgY~mO^&8+~Ma&wN`11DWPTdR2yH1nISp~Wh zg%q^D`jRE+i7Baw+`D{6^!(V}J~@}F-=jc7d3|;OJ=AP2o%WwiC7_p1lO*S< zcUZR2n9uNU(_|=oSxTDT{79IvY1xH=fP2s$H3TDnr&#j?r_(fW+sw169|zc)S!YmF zQ$(dqeV7B8zi}92S&~JsW}?@5@dGAv*!Ln0TKR!gcr;d#?=`i)`A$ca5bxhW(OGZ< z@s4uuPsbO5w!B&0Gunzdd`eaU*0ZWDcv;(3x&$b3QV*l{+YC2UFO43;9Cw0Ne18H) z;Z6cu&?Bb>h4=ItTz6SGSWXbU&8(I#%n49Bah=9pnl9nS7_%IS)DMT{mP zlTi}+1#+1fZu^56Z`kO0fpzn`6f_QY2NCyhp5VzwPL6TeIQ4u&^co^ zyWiuxor59{QL#J+XcTR{x2dO7_r6yvb{gb@ZEIYH_h-=VkStOMocuuNubTfvpjL$z zl|+OB2^@42Ew)-J-{I@2rqy`1!xF8pj&8R^s9gF67|3&Ai-ufQzB86N`p8^zaD0g8 zl4QWD`Pmx>&IfUyoJ@_Ay0gWD>ZZ{=kXiRaXt%F}qYoYLw!FhD8WGl;enNpg;ly0r zGu{yC6EmfW%{0H#@n~jCBNHAnVY5@4o8u?TMi}yRX31nVS~p$fSgwty+sEm0X4=jO zeFoT&`JP{vM%KtOW66Tlh4OV|qEx?qFI! zA^c=o;Vv-&s#7808$S`ohbpLu)G|1^&X_E+C`8nb0xw<}%fJb<9wWN7IC>G{C0?N! zr;7GX;nolZdcP4}FSdK*_Fml4hKzH{iUOZ-_AYk`s1&%*O0)^&tP}A>KU!S1sDxeoG#XvNtbItZ9*@T*YjT=0E1Gj3In??BKag{?jI{DSf2^ zY7_zXM|TR7TKl}{Kjt&6A3zH3(E~go>l}8=x}!@eXMO`txwq-YNMo*KYYW`}2KB(q z3o`5b`BXECRtw_SyE79#DZi9xHpDrlEjnnzv z3y)(@-r|>~YU?9DNg1IJC9Xyw!WEINEOrq1Jh8=9CAKPmeYV%B(KZl(cJ{PX_BgpD zdqp}8{%FO3wcSvGE$s>U}5V0{1)2@aWR_F!1+~Wtgd3R@-_2!%dYri1_uJW{I^rzhWy;W zqD(F$$j{GTis0ppG-5DN_t1l~RXCehZ(EsD)jjV0OGUwH>#ncZobGA^Y~b!{OqX0P^MJfS`3sePyY667v@13_H&?0d<7t~>2-AXNT&II?Oo)74%m6`Taj5y|F;0M!gnImDc8icMP;{YMhgyNs>xMY zzwG4B)Aw*(@c~}WOH@#G<6XRMvJjG+D%`EOVIW{8E#QP`VVE=a>M~@(Jncr7Zi)|G zNglsKGplI*6!tuzpr~~s+m8TUt4qoo2q1w3^sQDkyzV({#oS4g(_pnn=~zE@*c_Ja zR+vOu=nO{bL}p~_)U;__-|qtn2r=^RPf2opc;E^Di&O151L}Fc;iSG%*H?ywL8 zbH=i~orF13kK7RW=7lsBMRrU+3-|4#%qa~;ICE=n$8_@iFp@X%qC|*7nFagoy@kJeg3xB0Nn>$Y z#GG~!uORv$OMonUce|@uUud$uZzfXC2@&Fh)}UT#TU)WXx0M35_sCE7>{rgcFm0v$ z%lR)-ZNh|{pDsg1qrLM(NXi}AR=q9M1mp&?TD7G>JABj!8WvQ;kMz$>PjM~^D1D5O zl(Ka+;&%AbVZx+$6*#)0UE;Z(36~H1E)O{fu6O-_#Cco+|8y&4uOVtjj&2{hK3f7a z-SoX&qQ{)#8(rU;niKwLcc3=4Xf0lbR2=adhPkZhfyOA#hYsQkeR;&GL7%8KnmIeg zVVLfU6sl1q;5ei4iVgUTS4TM?uOUTM6A}>lPweLO6(!7%{=q>Ucp60y*o(Z_u44$N z=E^Q`Y>{xCr%o1cTleZ(`C4otID!CwzvD#3L8uKb)%zPF6mO)oP{ljszq$iL72#uQ z%qSse5CRxP6QCAGim0~*ENEh*28{~QVQnYww2SxAVI0A?@|20MCU_YsL;>!V3mRn8 zTKt$F+&%_}brWplyUmWudcuc?A_@Y|#?%@&E0J4FuX3p_Ny^%) zY>nhV>i)Jj;eqttgvT#pFDfuZVr0l@tiOcfdqK6j!G^y@vs?g(!|WgoB#OJ@LW~ac z{8Z${D07M7N!LqV; z#i-ko)rfA@h(!o#gi4aQ{Q|8Y?52U?BmjnYyxlCY&6U+vlSdl>4Sx@&3X5O0EW9Mh z?@|Wb@k5yM52pZUL;&}3ttmHkHNjJaQ$y!0-;B{qoYAT`;3F24{YT1?eSwLhA8YCK#l9Z~ z@TEC#86;4rZlp3DRF3f8UKW};)?u$G>Hh&K4}YJIw}`C3r7B0my>z(b6S{ZJbw&F= z^|*iJXmG?tLHj{hx%}Sd@LR+N|Aq^L(z?29_1t2HLASx z%k8ppvSJ*~?Y~M2SDJDl zCFPV7v6WB)Ijj=-vp~m$w(&s{I>tB^fcIV~m1m{y3GVdZ?&{#tf zN5q3zMw&`giY19s%Dpqp1eZZXn|v>95&+q!Ltoq5(z86Yu5CvDe0{ckbIJOCbmBpX zfW609hfMikWl}3YoTU;H+`*o7|{iK`sxL$7r;qHB(eIq75C+7zp8^2 zqFBk2t1~FN<3JHl#8ID2viJOJDTXqquNG-{8lApuVWN3Q^-yf72L+2vC>Mc)H~hF^MEyL&uiFTsUz)pjW?6<4}KwAn~D7!aXsWO z)>RDrdkqCqEA*K|O^RL3vC@I1u-oSPdcv7@6S?UUxD+b+52F;F^FI0(7Y0=X=}4Zs zZ$Nra&2R$fB|UJL135d;nG_ilez*hTJBBFU{B!tCx!Sped5ibtF3d{}D>~kr&H~jH z#7`vBB*dvZB9F-67B!_h_DMqi(u20?ZRprEmn7Z(towB2D-4d31 z<#nV<9px}lNM9Dnf~!m{-m zn0}!(vJA)%v%JZOT< zQM2R(jlfGzh~d!?u>R%fo#=i8WFUAw@J^7^tZhV}R0HB?zRRX|UoKHg4z-($$&C#? z|2QrN8V2_m;*RIWk2dnxr2N)hw6r~2w;R#@Y$h-6L$!g{CX=VTA6kzNA+{gK@4?p~ zBGe)+51PwXP+(UvYY#2-Qr;K+L37^RD9*y8V{4OlF z2cJc0_Wj)+s8(C1$gJ#Cu|(&SK=Ud9-<_N>h0K7jOPqh~3i!Y{HGaBR!|UAzCoojs zUm3ijIpih#l|WC^gO;&i3oba$BOYR%M>YerTCll`F*+&f&{d(868yzQ#;zH85U7WxI;@dUmd+_RK!jt zn&mYShf2=?D;lqdSjRI z0_b~1`%vqFC;@ETVhA1fmeR>(Gnn zh3l4#=2r);@1gEW=Famq^efa`DpA(9&~kP#U-M+|h#H9_;9KK;aTxR;SMX+8XKCAC z&aEZIGInHtyl5n0cRF0&f!qto3q@Zp0~L{0?xY>#iJt2APZZked}d5nH7m8WkUtxLFJUTQ& zYe_KdRiZX0DVNfP5EAy6=F3`8p)5l8(hr)amSWmuvr;TpLR|*T43ot7`AAAI@AP$w z_%p=T)U(|Q(0miu)z_z|yzHS7woOMWm0P+-Rna6g}D``8dl{@R#~8x`MTYONDftQQ@+QBfcJMeWyzim&fZ%hb_a zPT$gfd|vzg1P?;%GxJjB%&xQa@&v_yrOC&g-(rlUm{+`}`Z_~6$nkp4aIX7#`K)9K zIv9fp$EyOecur2s%&QfbpXvut(wmQubk@7BCS+<;)(mT#)#N(w(c6lc@!U}+F`1tG zaZ3Pi(2qaLt#_AA5KKr^x1%oN(dk$cJ#8W3#(Y-VU3ICojLdi;otMZpX<;jK9B7ABo*tD&Hd{BV14S2~)4tY+#sS7r4igr z(4dMcjiQMuSxdM)4wlAz3uqQ51>q)LswS;-RgG&6aKCjC(ug+E8!6LXeThntzS8J+ z!^s}GO$u~T`lt(CUaHBLBeX@S-Kmn7#!2HJv!0T;@S&f&bvo>A6ZM4=pNrx7lHPO5 z!yQaFacqO_&|dxXK1Cxjy0}MPgwhpf_V1?UW2hYe;6<82h4rL0Fa>IJ$xpaWtxZKX zw#Z43OS%SPzV((b4w}Vo;^7OemqRz|)5T`%n!#%|MaM^e&W3@*b#JrtoC31;hpu~L0E zNZuK_d6Y1U82b22nPElTvQ@CA{ zRsSw@X5h=IXQnA&V}$VIu5HJ2R8`RUoxy0w8c>o{@mb}*b|v+^^=VhMLc|h)o`jbv<&#LnQuYMdBE~ngM~k&iKx-Kjne9*BU#1gF?V0 z%78~WIpY6*kK0(piPkxGFAXA3aIeh8B;1}%Y(mEgais}f(5o}`M zLyuF^{fLp);O1L&Q#(M>eG6feSRq10?S-_E=9$B2u^!8wqo1 zG#KZB`Qc}ZsaO^SfO2pZ${tqw-|-5-jWaRd^9jzrv3~eypOuE-gD7kmITPKA1JHE5 zK68Qw@({rSj8Xs@DR>#QNp#4qf)o}0)A2{L6*zjp7YtJS+pB%`tsKoWa(v=o7ub)6R^YiPoUHVrTO z1H*)T{>mW#`M;pY4-^Suzmb1t8}{P*-g6;KDP)K*df-cW)?aYv?+3#_{`YgYc%U;S zvs$+=)v$*M{`r1?Ur9c~+nZ}u*we%Q-+$fzY>Xou?jj16ANyRg|M{T(&twpWuYIgm z+VFoyCHDXI?nT_Evl%)nk-ZU2AoKhdA(G(lwiJ9}5G l_m9^9eG|xYViM`r)ryW*{wh92{}Tm&bdMQoK2f&~{(rKUzYYKZ literal 122347 zcmeFZbySsG+cmy7-O}9+(juY6rlmWiLpmgt?vMsakwzL62~p`zNku_HLQ3iG{af2} z^mv}{eV>1S;~V313^02n1L0j;t00f&m^PrC=Z- zeklZXgI`b&Ed^=F^AYNG@Q1gxfufD7Dufd}#(ODaz6C$SA*yBk$$}z1Co#Y>oHOa;%$Vl+quCnOxHVi zJs=P&bHopHulMKz0)askWuVyxw$r*DpbTsRI*uV%L-ww@29*iKcAKiq5?@fY|Sw|lQ`tl#mO&|2{H$C@#cgr{EUL|1j)- zJ{k?uhWx)z4>NrT&m9;tjLg4GP4T}>BQs)p{@bwc{9iIX`Ar1g-;x!2?Gn}70x#cE zIjmm)9X7WJz>MasS%~WVw;6?1qx3#+$Y1_vivNn5d@G_%kC3@0T*@y(R{nn9#yrrR z=Y#^LWB&;%*bs&t#EwGPQSqOU^&~)|^WTBK)HV&e^eQanYCTyDI6um2k(>GvBJ8+csu?>E?O-^Vp zv3Zm5JnfIrgelPHL-U!$Q2YLwi0`oZD7rv$5!ZR-YhpV;UbN{sxGYAq^{V<+R=+az zcz2U6&wo#;Co3)S!$QeZ7vCS%jT+4Yk+Hn3-j|0Tw~f()ZQgzC{EuyP3p<4W_7IGw z^p6GhLh6dT#zyZ)vMKpNbIgjN9a8h{vGSbPM-xf-g~y?gj-6N^ZSLNcOX7xwE@ z$4o&=t0(jMV;$mIVA*-`LNkxFeTtr{OI{un#`4^PU+hbsZ`7qm;|8ljz^s3Cs(VM; zW0*uPXg9VHMR%1Lbb;*G1r~lXl(dTR_rCmlg1p$wG4kIsHAwy5onum%D&V8b){nn< zjINhF<%tAaK)7{((2g2x^>{1Cq2EKv?;;?# zisL`}8U$a?Fr(GK6nq_YwVy{#b1|td>Gk^ME&AVI`*&Q~(LiM&4GDP-EWZK`X3G>@ zc_od_eX!GYt>{eMst*D?$i*N%7`*<%^|DT3`u#M#*kqp0DpTcfZ<;FY9SngLKq><2TG#ix)d-5Z%(Os<-CA!ZcD+r7&X(@A~R!$_4e*lwq zIecSu$KPV)*$UX+6PDlnLEcJ~ygKPmW(oqk%4g+C)MIXul@OTe|@^br_hSI|4!JCFlpczv09Ok zeP6Jpz$g?F>T<0P*jhi8V~r+AjR;PvM3BC&`uI%A$fYj3Q2|ffc5J13J>jcFde6$M zV2Z~XFb~JOroU6;o%}Z-k_9s|m;YJQQnujShlSCs(#csiq2GymT!z1Qf=gYDxjy06 z!JZ(hlG!c=Cj54f76tLKUA*RNUXa2$qC8Lw2P3ImygM=3T%W@PGug(TnR$KCwap7S z0`vcPRe`d2N9eOt-A7YD3!6v7V!L4HQG31D%obHyNw~fBXyOR$cG0D{8+?+oFAHR% z3PV?2zSXmajGTel?!8JzVhKsOaqVdK;a9slK4!rlL>z%S5S2^0Bum_MG~-C|p`!A+ zZ#RL$!Pe~Uy&=}tt20MhS!`IryS9Z$DsPnXY3mG=qkg7DYCdzAJ?|$r`sngtBb<%- zuxk<jDcT8z-ps~E1N*a)ff_dOV#9UT7<1+Q<_Ed#uyO-&%cA~gneF|;icypJ9 zH+{nHGsOUZANBr5-RR207jIT5hYcO88%UQ%_pcZGB#eq5f8i+2cJHHkXkJ>b!?kD8 zNwnI%(XSZ&R;6OBB;)rs1befL7wpZ$WqZfpPv#ThxARj++{Yo_p8XOcT>fU#|ASo}$#zpocWh#XW&a=mM8TL8`od-W<6EPnlV1bRH^EkmjwG|@ad0GVI-N~T zAh-g1(>BLzYQ7_^4SsdrOx`f4H$3z{vo{F-UR%AV7e8l2@=Uvo_Ms+w-orT`>gtPe z1v-*JSIq3D?bfF(`4;=byBKACq)zDsUh$0_=F2(M$T^y}VgW?_GTdlx6o~qhyfsN0*+dYg->H zUToeELcYCqs@bYlNLc2xnv($&7kQ(d98XZTJw4i?7u`&QG@lP0J+{z@Q!j@GTN+4( zLgM!ao>t`c&Ubiz5+Ll+C{n-qK}TDKAGHZu!zVYiA=lnSH>3)XT%oHH-=s2c3vqQo z>u8Ziq;e>BnhmKt#K>OkYy6QGkO^UK>fzMHFYKLUKj%5Wn&zZ{Xb`boayd*Nel(+V7Lk}i z*=GHAtKi5nkH++KH^yKCT=rzzZ@UE(Dd8s4%>$71d-RYO-zYqFA~x@XJugTwN`@Wg z)x+)XM|&ooopckafBS+o(e0jS$*qiklDmlt>VwbsPi!9e z^csW=D{g^o-KuyLHwE*gNq96}iJYU`58NtI^RaH7J)2HM(+*|pMDOwaRYwsP4#KXc*H3c5UoMT5f-Ds!B1ykoboSL_R9qpByu$*5;@f$zwvX1Y8xvQo zBj@4V69$WxlgYd*V$~0hTI2bcf0j+bgy7o{%D$=ef6}W0Gt8XAvz%ZoDE+QYhj8=T zz0}NY01qi+wmTQf8q^c#x8IB&0`w5WN@L<`7pQqjR1!I9jG3cuM`!4W9Ej zd(voZdld~LL~3qQcI7N8R`_eYp5cQ0gH^T~EIEy|VQsmnnj~Q*2lZORJ<>Y?s%Lb<)tdt6txDNM;=L9s|n9~I=L1! zcq-zsOZYGyX6ek8*#Ac;q6PQ9Y_R_Qgv&P>nsj9c9JbK%D zFrl0hHc>YS(;R$JH*zZiV^4Q5V~(*bz|Q1NthQtxKsWjCY>8l7m1^(v#auP)x!*U$ zC5ea@HyWnPw9_?@yM0IuzERff`0KiL zA8yZCSDKSyPGV@50u1o;+$t21zf>Z?IZOJ93DHVd!`@i=jqH{1qiiA|~svD*JE+I4#5Ze!X){J`^RN=9gy7q`koVKo z(1>e(F&|P2F$*3kc+ezl+QCnssaf3N%l@`H0wRKIGP|dZJNaM^de83 zZg)e(I-^}S?R%{*|~_h$IuKLJQ_KUX>!ty-ixplGm}WBC`f0F zLOBZKV=&(*x6O9jYx z0FrOJnvyY$3y~Fcz-6yrW&aVcuxUQJEGt8PxYziUF#Mp5?NNceU|dI`s1@bA=N)yq7x$qr zt8d+q<*HSQHR`a~o% zYfA}0G~$N730y;=tZFr5W|QH4^E`XCe+o;&=ZTVi>ka=!p0I1kkgvEBZk2B^OGeo~ zP>Q-Uca&p@r&1Y;ya@Hc?&J%;lDw9r+oyQ*;kWcZJLLb9jtNOn%eNiPUE{%g8~QlI zb+!Ax)Q6!cZwUh9V%(Kro|}vCF`BE7s^1&NZz|xBB0+cU!`#w07pIKwvs4U+pwoWJ zV#3Gb*55Pb&Ag@I(MU*q<}0!GdJ>{VO#l8XN{7OEo)F!$elhCGAu=Wk$m0n*RpBMs zbGnY>(;0I$^B{SPTWLJeF5Pj4M;q=-=-mFG(FYBa)%QnrD2Dr+Cijx%KtC6)Ko^jz zNH&cFI3)x(HT}6FW??rgaY3C0Cf^ls)556#9_~BZ!j}(G1r5LZw0m z7KMd#ezWnbgcG6H#`7^9yqGePY7{y1033+jh1*3bQ~l{D2q@$fi#z$t>L#P2pkxg5 zqxUjMxY|I-(bxwLra2x{L9(deQRsbatdEw1Y1qoPnM$=n13wzw7e`CS;(I3MAgMyH zUG9={y1~`K*LyFe0r^HdcabDc+B%t`DQGH$=De3K$OL`WyfSrCmg;|JC`7;TT@DPg z<<3mP??EQPD3CU!`)7OIUh`!88yTV}Za)eSBYmoF{{(G0e_3HQR^b9rQMp1q`B-fr z(eI|3S;gO^d~fgYpmscOt?=N{{A-eERw)Yz%qr10(J2&`>IB#8j?&MM45q!xbPYV$LOdAp$;vc5vHF3$zJ1Cf?2C zFXha>@Nw2)_(g_$&7%1oI~Qu^k}kG}c8$|#o*r;EVl7#j#n|!12WuI@cOHHXc(`{E zMgEy-&l$_!+)1ik&u!N0V|DZ1V6hCyHA+T83jbhh7*ag_JYKN8MuY0_QcNELCj?p1 z#A6R7Xm5b+{AjajCCgDSrYwx;meO}V2pHWE4a9z|tg~_Ufl22$1@vvPx{%96Ng9kDW4^@vi?ScJARIEz|naCPsdQ`GSZ)6+@N9Tmy zCHxD=g?J)_3KoN!TJq`3iDWtHe*!zQ)3%- z_n87F2j_bBc0qgS7Atg3;>6tlA{w>3qm3@`gdrWWh{uwG`SophaecC{YDK-Z$Dcgk z7zUE{)Vuh#UZFo0_$@aS2O24}Db4M^Yi?O^Vk6^|VNJ7CnwMTFOv5ItPZ$Mtr`G0469kjXG z&O8HH8?%~N*GFy}`i~xnaL)sNbdkRYWl2xT^^D&sWfxf+I!fHsSz9C-@mQA!q#aHZ z&qAa7iPXL$`R|N`%&Sz>s<>2zUSI4D5e=3PSd#uBcLWDB1Yc18(S8Z0Lz2IiKC#JK zL+<$sdL~^x<=C(zKpv#v*%gZ!+6xA-mlU}?W!XXh>e_`njUIgN|NUTyx2+jqLNG0_ zdgCn$#`Emjc=8`B`#BJ;fF4^i=EUoL&XTzKgK$(XyFfbc`H;}3k}}pAy?`&HHp`tr^C>BCL+b&M%k5xX!HRO> zbwuZGTd@~YscA|Kn(7~exRYOi@&!7k(fsE=-H`;{sUY5=_hf0iM7O&rU~e%#Ao`|o zTj5MsQOT7|D;LlKj1jyLJexE{(Y(A5{z5^L-p^c`~RZDzxUU6#JHNL-L7{F>x=&26qxr(Lg^v=vdqY_SBy952_7LP0={$%6;{D~N zxr4iC5jOkEPUM1AP1G2*-N*6QtZQ)bi(`z$JQJ$&$?*DMr)9tC}BdeVbu z%&$=@?6VDN^|Z&B5K}$b@2x#H4m6N8JN53}-!ldzD04sz$-cM*#M-kr0e~C?e^M)b zW=S^)HGsh{Rwc);5X3Qxee^(4qC7mY^``rbgw(bZ5{xEs$mcuFM{gwP%bOu^Dt_7$ z9QI+H^4+O0Mm-5Mi1B%JcFMIA$q_hw^(t?VqYFLFxAuXoMMWe1m3qa9C&s$$TEREV zMBHExVwdJ!`H>LVz(@!dxgW;RKAC zKMFdUw&hh}kb@5180ZLug=dS^-L=nM=^-;4p1c;UTQNz1%(S9jfWr{?YTAbCK|KDG zQrGJ|)9F%=7$iRNG1euSU+VyR8}Up~zf;2py*TG{fPDP--vP>Y^As$1^KS2uBM7@{ zP7Ciljo$^zo5?2sST;gCeCR`nAV$?YghB>n-$x_-_xkbu8Qd^HX7k#uWv-Pa%P!S^ z3@c@Ui3J4a%E~h2Vk)UL7Z@EeEsyCRRF~7tFwZhSrmW-ws5|?;65m7VFLC7jp(jE< z^%TCcEG;0!2z}aOhD06QBotXLqsH@Cqx4%~DY%Q2iCLLDvSg;-40s#m4aRwM_ptdP z(!)2tk&BTm>E*(31E%iUR@Zc5RYOT|C$M)tyzPlZqf}aH*<1aNHtx>cw#I1d;^=6* z*i)`hlT(t{E{--_Nl=5QYO680<3V;?;ef*+mzg7mVO%Ea1pwJ)MOkY~r~PACQ#R{6 z#kNF=Gxpn%LeyTENeo+38SBm1-VPC zU2`;vjZ3#;NP+|hGR&C8sF|U-jGL8?z;_`$iot2fQD1fz?qC1Gf>*ua+A8&8hRTQgMEURu}6(G})7Q z#)H|KaY#O^3v8xxQ#=`d)a&!8K@5+N&^FIo2?)3xeEfF{CKX6R0h{ed!u0K)4I`yR zl1)+^ep3%u-Eb#lB8eP_&V{7c1IT`Ol!A}&;lxbuCkPa%JKVa{0-2nMMZT96X?1fx zU^eG8$Cg%klVo@K3=8+w#$K`l?Lz(L3hlttgb&Ux)qFsVc|+K?j)0^`&4tAIMi<2mXEC%U(DT0)g^CL|oszY$D+6I4R@upr!XBAPr35Wh z6E0USWZn&RyRU#LXQ4(ZOQEUAG=`e|L5wApL-W;qGsP(@Sg#`%4ObtRX>)I=`z^=1 z@2~Q)2CY+T{Ifm~M66?9-ppIktI}!hMH}a}!sGaSC!YIR$9`k9`t*ZAn^)vI1vl## z{IQ-CXBe<%-R`sz$Kz8IKGUA@iWiN;mm$bgTE6}+bu#kwnc+pXEjr}db1kMS^pj^z z7Xw3Zq;x&|%V$cT1rZ1n_LN|rB#MKK0?UJyS8xi_ZB)4zse)WYx`ouQ@yU4lO^;tg zLQvLcr!D76%_{|2{tD;J&p@wFA{v7vP4WS*&C?f21bLCTcRc9j^TkgvX*Hrw@&Ku{ z^@Rwj8q{G(>Rq5@@xGo9EicKcQ1ZF|OV=NZ#=!Sxa1Op>bp`0*X&g=a3jjP_pyiNK z?45F**G0=qOl`;QZ*I+$Q757>k6B>S3%{hgM)CdW{Z_@WZsnXEJL(`UlLB>WNy`_w zv|^ct8@-<`qG;4^Z`R}8Rz+t;5Y@Md%1ZElj2LG(flpAxtf_mPgj8^8OX^)q?Z4B( zrCvG89?_s^eP>mI^22ps{l5`+NP;>ffYjm#qwA!$y13WZfa8T-!&~n4aDbC90l3)( z;HbDMo6~sNd|`rg7$G5m(bNQG>08>tDMU%NM=lu;?xxgXP++ZdOsG!P{?&ff^MktO zjPqp+tbH$Gzb<@ylDqMXw2pDcGidkUZD>9fVZV%;8(s&{iRwVlQwQHhNSQ!v7fBDU ziBk9XWWw&J@?fZwAj08MPZPNe0~d!S}2c<0GK zbUy!?amUb5aG>wek~XD*wi|>5;Da%6Cp;4UawX%2@+&9TqeBmtu2^uYr1|( zR8I+qNa*%TYhdGH%>iN4K`j5ZlJ*?J-!t|GqlOJafu&zDa??rSFONtuKy?~}-PB<2 zu?gw%$KDBljVt?#y1Me)$x{~6UO%bUG%9iK1R9gFtl_O}A$IX=;A*IbRi?_&7At=3! z8#C--W|c=OVr&tZi?ktI(nX*CltfL0XX zS5c|T1vtf)xvvyX^g_ywZC z0y#-lPGs%=e0#|LsHCLwXRI`b!IEWRP=G=0Wvj)vMRS)YJqwj1z55JMHW!irP^TZV ztEftzeoOhpe06o)rY<-x3#ONcq>s|EsQ7?W@Hzo_rG~)c0Nbcz zFGlbL%)J0kFB~WwntQ+w1G_S`D~KRR6mqp&y!Q9s%-zg0i!PnwG9OOZCom$I9+plCNBQFj0k~HgfM-MWfiE| zvekLt19yAKz-;lMg(^`09AAL!Dr_x%kl)DV6T0E-xA&F&Sf2viZ=n=M%Yj0 z`;p^sZ@pduLUIXgU1+YpTN238pBP>O=Zw10^gZjSdnNynJBV=B#iSQ7r``nI31?;1 zUSr#3ynP|NEz==_eClV2s`s9{L-!LaX8<6=dmlwKLitPLj{L3d=KUR`!EO07Kzhu8 zB?e9_8TTY@a>CNO?pd*9r9jZs^)gIXfmL@A92o$=dzAS$rzK^M~e0%1X^{K z#Lz1lCjSXg%xinJYz`m0Wpw5RU5V220F#)j9b6lG;k>O2?=~=*uyWNZH^BKJ)cyu< z7BRxC83q2;pu&)5!y$xNN)PUpjak<YBgrnGHLdZn_0HJ~>uLCI5ROVl~z+vbWzU)hyn-G<<8>YZbAJzjQL^x6Q(?F~@3^ z3p`1W;My1l;Z#F_DCoMHZm#*4(sL(&hzJ&GNd$3I-NlL-NT9rlMZwAAsO}H?OzO9R z7rUU{P`f_jn)gi)w*xQFUJ6;)uJddnJQaXg>>NTfqwO7y6JZT0BG_Z$(tK=C)#%Nq zhsgB5j7h;Lw|Jq9C0li)60fm}Iq+NIfW=`XcBr!npMbwv&1DKytB4SZJSP~xJAES_ z5=tJims5?_&sz>z#5}M5tb!vYfrZYo5gkJjKQQkHj!F`f_<^@G@nPLgA0 zL}5RYp@$F}c>!MuE^8b$KPS)6m|GJ;5kt;j62n#ic~CG05+(bRjtGAF?eVA*9$PA+ z#SbfR*e3LnRQ{lo%T)8cn1q=LN|Tu6wWwGfx-}MealG)5>k)>VD$|meym0F9E(T3)TB({{v>AnsuA- zKTKdbsSv81)htII#_hZZGxqjaC?ax^Z@1q5aL6No9w!$}&{|V=Ut0&JDCUho2dI=) zmVF7sEqu{#4HhDPTsU+64v=f@He2dz?>&ypBrEMB$?6o~2ed)mXR4r}VdU(Cr`QS@ z#zWkV)HfLOkYmbYJCH~DzH!{^lGZjww1jqMp!&^Zw6y?{#aT9Z(#=iC2h8szQff-h zR`dP{z!(0&##LsGlBys|OUt-+wtL9VK5ZYxG7kz`h%?G6MBY>H#pt4Pu@3I3L5?WZD(}Ji zyTtVAxhGeRpT6D$lQhbWUS+(0C+C#b?yZVMD|afSRI!QC~5Na;QrQC-42 z>I)&^=aN|mz`If6gWt?x^=` zBqK5uNk+VKev>V-uoT>A5_OfFNxtWmJqmkw*_5E22_ikk(*q0TUrc*G6Jh)AH(>T+ zm9U!W9>hnWIMA!)l_jLrpYr39z9{HplaL^}i`zFV)}fRUUzyysn3nyePQvAbaL8Rt zU~6;IdkRQ@oiO0^OI@mX{9KYwRP|P4 z2$z9(u2;1EJqt}?A(D=Vg(2|m*-;_3P-I;T7#vL~>}zWPW^zy$t}y=N$IybSmALYv zM2W1HJl!b=_C5gWE)6~;uUu48u1=0$tlh2k$b{PJiUVS??8-{(rdprnuf+hL2DZd8 zLz3k|o$eZFr7foJ$U8l2oe#wZjyp4+%6<*If#j!z?BNMy3PBDFQ_!3>iV5KBa|hPM zuK*vsXx>vYlJ}{O$oy&V6;y1;hp93mdZn>qjQRFZDrJ>*kT@+chaU5|D-mVKo&)b| zSoLmkW7aT(i;WY8bFFI;w()~$YjNL$`86xO=Rj1jNST4BtG*eps|ol`r~b4oy~9x9 z?;-Bja4J<3UtI7Umm^!2I4@?hsN@ga&89N;tsJ061UzeO!(FIlFD+2yfP3c{xH1*L z++a18^VSJ=s9UvE07I_Bc#WKY_ca&S&(;^^Vj4Jffh)V2cnj^_6@Udj5>uRW*PXE6 zZM!RxxY1gn8b@GI>5Hai>_=6m+SeJ`!9_b`?IfM2ifDedEPvIYoE!-MncpE$PUWdg z0C*Zkr4ioR0V^tmwQH<2SgIIEYluD`&HeEWm7b}HI#GIQ5d129W%R~p{`ez=F;5%- zlNmRh2M7a9{vpC|oLj&R)+r~h9WWOj0MsMQ4+Bz5pnsSJzQ0|qa>01OU7uYGIzg`d zq(gh{Y$@Tk3us^?!XVa`fgc1ssYY#OY?Y%d$L9>@PQ+@^VY&ZE4cAMqFC^Rdl24NS) ze}@t_QF~4vxyYky{0fW<^fJpXS8mr?lE9ACqFl$MsL;qiQf4N;SEfUY`0MCxHOJ{v zq9mhyL>DP5E?x>q+@FQMxOSnE8S{y1GRWwLjAhMLBf97O1h8c92})E!SmZ>u1Gg04 zM`Mp3!}!b-Ci%EBLZTpmI&qQP9bdFeQNAD|O&I5m{iyT`1+7c5=j9hCmT8NwNI8rV zRgelNRfTf^k#00y^5GBh3}k8-X>&w-0i1>7zNM#y)NQ~T^cDQ2G^yY#9jWvXkytp> zoCN5=wR4il_*Pg#+8eMbDhALTxq?C3Ps6HyM zWAZ2%>s_pRuWC!KT$z2&)=Mk7NOw&!!R5Y?iNq<_dVNOijttR@s*io8f!ZQ@``&sP z&pEOLqDPiE=il)O z`C#cdPNPa5Mx*KUcL)rq!3$F4ce#lN2+~2`9Q4z`!EI1>SeY2u9t?dmB({py=xt2_ zJzh^rTjv~dl?h+yGV0^!%#uc7ha`6!pFw!Rj<7Xn~%bURE{_VRhp&&NV z&@$r0z#^UrNV0SR2bwO(Cs*gdi0U^Yy4o!YEf08zEEroC@n?vQHDIa$|7pKQ!!SXz zEkX(e$1$`mbiN^k4m2vKU}h~tnuaUTs*kueJ(5loKQbtQs4~dNtpIW@ek3OV!h!x~ zB~9NHkygPOj2QOGGn9_Y1Q2%hNwN?FV)HEFlQ%8l z^duvK#m))|h`?Rk%Yd8U(VfglKos$n`7emxcGedx;MwtZ+aPCU4T&d^H4r#TbGi-% z;h~Sjqd5b$S2J#yM9;ti^gW|SRs>?ep&JCM)_`|#Z=M&Q>Nwt$pvxa-1LaLC0Sggi zfk6J9EUQtkdi%WstR@{5eJe031NPtqP<7^}*1{7jOu~Pf5<%gxMIut+gBHpH1}+zT zJ*()vV+2lwzbpnlmK8E=i@xFtWI$1bk^=ns7)st_iPWNd9e^fSFV09(5U~%QjLa}{ zdDHCnrA80v1Zu?IAj}6!$!CJTamfqxQG2-JK?C(8R6qC}l9o1H^)>X+}&Ybq(EoV%ln>h^iwxwJT)8 z(w)qz^^UF6&9Vve=?;C4ZEi#=ah3rl4*Hq4YLR;zTt@WsgG^+F`jj!T^mYiD&wvq5Yp-rf>< zu%XBC3Q#u|bC1H3D^m~B|LiWAfeVFx1wUz3J?KnZA^=hA#Mp{=*MNCx=|#(t;l-u$ zcKS+91SLg<)7A5)twDlr>mI>DrhLuhmRak{3?Tz$yc;II>%|1gt_u}9xzHOGfPrk( zg8nomdZHky{;0Xt$xai70OXXID&W8q*Lwr_LVif=ZKSXIV$|8!4X@6pw*|>>YE^5ydB2{#>2_c7zy_+vm+SfY&hGyu~D%y?nJB| z^CQo<$*sM=09Wi<_*r0x%L8;#9r5ah`J=s16Lqb{#)ijA~{+`B^5_Mt9iH z6J=vcNZI#>1c+&bqrMV0zU-aCU{REtO6J-#82+FYYl~viu{+ch>9K6E9NdQ6(JSvy-MW8z_{p_!X$Ev#{aT zSOx;T^}2_VWHTs{R@`#%pnu-Jt_qrOEuNmx0a$kgCPfb4M8CCUBy1X)JB9C$fi=hob0Mad+n-st!QrvKNY4IMVpfHM0+l ztV-WY7cLA#3NbY!?o?+xle*Jc(yU_fk%wp1o(06AplqoxJAUk8V$+IECekGtkKV+~ z{viZ7%4hr@Wc)E|Z*(0X`6`}+^T}F{+2uV5uH}6!01Lj!^)$b(^$!B(_d^&uqXvJ{ zU3AJKnSah_{HyW!o4Cn;g79DxW%m48g8o9&f4n>=1bpYnPAYZLzc%E5yzc*f*00(5 z|7E^&~>95VhJjMsmAZ6rKseeTpg~yJIscnQ z_`@}ZcsLe_XaVW`{Qm2g3&yp7!gZYfYq0rvDDuEP;q<8n(My965kU95c}skJ)Mw%Ool!2ZfBt@2ozO- zC0#%dD3@7ro)iQ!YoC13)!~aERR9+O9J~T}Pw&{&32~$d_5-u*i@msv(a&MPkeUGF z2-@32@Un?MK=OJ5+DIML?D)0qZz<}nprbPAnK(g6PRqpFD&vn5oV5SFz_29@a5jVN zsmogqXY(?xX+? zfQIygbDz^M%-W`kUZNsKOB2$LIA#r)6Y+Qy^z=I)1Dt$@JPnVJ{yZFom=qWlKCB)y zI#SS5C+yayrvR~md;;|;;uI|G9Jq+uz}drB0br2t5l2YH_J=3if`SNfEv@UoTW=Gt zF`@;7!*zbZvWAH;FWtKT{I%e}=ll26hioYZn-CzD4X{;kaF|+;F_=Fe9Mb_HZWJ82 z{FL8bm-bf33;<>J5FU37KIlhx6%IZ5+{u6mgIDm=(V!K*wXGWuZ8`t7p1(dHA4P;< z0bH?}YX_>j*lsuHOweGFiXZ6pqI2Ij-ZvA%lErpTS)=@3^_)NUmCxeQL^{gbN6>uk zWUp_npgAQ{+s+1ub zKmgYrilWO?IV z>Kum)$5Wl!S`Z0=ckk$*TPpne(x1CGZYXag(*OL0Eo#Kv;m}d3~F;X z=gx#OZ%;LlpWVUMYXLU}sG*Q80fK7&4ZSk6j8RlktKjPM~LSapwE2sq0Ux)E)r;{2Ow@um!sXOu{y?UA}l3l z!QBUZQnWHj5lV;xXk9_e#0A0J8&6 zfN?n=w+E#kr(zv2CR%Zx0&UWwlO^w{?dL zMZLZV62)rqE(ozPt{Yol+a!5$)toD|J{tY86@R87*pU>p6a6k`OCQjD;@*#9 z&^L>>3v;okdf6*|x49GRIzAFD1sff=G%1#)WoN!WtkwW{Co%xDR-A6=06467vAT*k zAPMPmq)aR4pzT*RBT^G#;Kb-=m+039_|`P-yBl`LDiGo2@{4HXZ-U_BeY;i&?)hQj zKEQ%qXr@#C80O*&{9Z|J^gCegAW_NmGP_c@99!b{yRJ#*dlz7b-yGvNC)O5h1qw04 zS%azk^&HBWb7062+behr%o7Zo@@mB>Z_8!yM8g%bv36$XeV`QdJ|rj(;k$rG+ocz| z6Z}aEu!+v5^b_DrQeT%6%jsZ2rqV+KHceZpr}t?dX|XP^2Rv3}jV3)IeEw!73!Ff` zJ7{qyTctfJ1|i^91f$^FpPl`9!A4h1&63>rWE=1wHNyf!I*eZu>K;u$0VRO|X8!?I z0>LJDm^SMwv-OyTvhRaCHSB&zBpa-tVJ+wtQVuxlQ_L-^Hb=Z#xN{`BSwA^;qHykG z2_`^Zioy#U^U5?bbQ>H~|5mNfj-PQM$7Qq!w6V(F7Xr^aE3@X-E8-qZ0tD|&u z&jM{cj|+jd8GZRNu%AaCYb}uJ&v5ZF>gjW-D)kM&PmsLwW{qG84k<WxATOX5Ery9=nN=PqjJQ^pFt0Brnj{ILp;$1`I=H5u+oV z`hY})t0bCfCf~UaQvgdADPRi_P~*&W_vmo0)l-mQWBSTUg)CX6sPeCXSZ~%4H(8Xu z>AhqAr8%iz3om8~EL*A8Q*vgFcS|>QU)`){$z;I~9n?c-b+@i~G)JALX3zhPm-;=Y z{hWOs2hoGJdP_%ljiq4zJOV=gT%((>qVZ#HvQ!kgEz*Zbn><^oIWrHCV$%a_k{b6y z)s%1#=-JW-S}ao4;DqFLN)-Wj&cvKx6TEDyxD8`HjwsJ&(1Yn}4K^%sS>9r09uq=& ztBFA$+>4FcL#lKEBAZ%H_nv&{!)2gLya9PgL5(3hb&K`Ip?tLc9YlF0b1B#>?m&aqieHzzv*cVzM^nH^A6 z!b{&1wu7e0?r=uhebwnEn_rsjU+8yJ zjXoS(2kNc7sbr%JS z%BQs*Fx2JKWVJ`^uAuySfYfo zb%sgoU1woWlri{Hd=rf#gQKI7z4gvFzGUf;*Tb>PEah4zTO&s7{h8yem^cuB+oYT! z&Smlo;6`c%_O6W0*zf*@MMAl92aeK6&anKFJ7ms$2|`;)FD_X95Jsre{a(LkzKRFI zst%K%_t*LPx)I= zPH*J3;TF|kVtNW9{X7=VU@>?L5IVbI2!9+_Wt4P}GS3?nI_Ol1HO&QJe?9@=`y@}k zKyRI;GOF!jnU_m}r{zGac^ezmK%(|E*(4<`b-i57jS8D&$aK-ky_dpv9*f}N>C3ue zGW`Id>)kUMc{he!vgz5)&d+!o2C_2cbg$la#fE2~5%~Zx#^3(z1EEz}ty9dxlYcic zGZ~OprKe7{ifR1x67(Y*uRgnM++bCaPJ7(1U_gLhgn?^lh=bb&5Mppb@qwN_o{Lt$ z@j;u7o$*0 zfz$jNiQUUKD_1elx)kGsA3=9gX>+xUcB9`HQsEqc6&2&POF6(&`D+qL0n6pt$=l zZgHO1#_|~gt1kAQk<+Q{(CF>(>KwtIDgC(6U6~?BOQMA|v+wPl>W}#@-yG4E;+WEq zuewfs0;b!&DXN{j-ZoA{Z?jJ73dB)sbRz{9#2x}j>&v3H}kngf8a@Zl9*;8ubhdQCO3M9sF zroBww>IZk0iGbTSaMCQ2F?h6q8=J_Q!I%en-rCg&c9dx(_X!~pb9Cb|T5^6aiGG;) ztV<0kjubDdRTp*l%(M5i_r33Z$8}#@Eq+i`lJ)HQ8nE&$8~w7a z;mU8^hQ9+G1yQTTVD==<6VH#MQ?|s7jRvWuN@q$eor$TQ6!+A_C&i2CW)~VwoGFwu zO}r^M4r4Ci!3(2$&SqGuTAI82;?}=KHAq+qMO( z)DZjbaP=ZZrI^U=EP2-n567t{+E#!HV_VRBf&uB0C=PgjRdjZp>`7nN^WHs}5 zJjy5#ZUu2ml3S9lWcR&g??u8tEOg7X4sK{#Z$|(AoXCpF7v{U6<#anJ^6JgI#u=7f z0r^@aD%aFwGKjk*K&ax>DLT|$p5ZZL%zQG1G$GT%oTWUo9Yd*%rkfXVTNf+~iKb|@ zoifvPm#87(p`!S?oJ}xQSkpxGH5nQ)?92MSbm% zE79@D4@fwSWHfJCmES}gdE$q|&D-`JQhk;|r3i6zdkpO>4d>C$&AeB9U!5u>k;Gca zcYS5Na|~KGeiHHdDOAkcOo?*KX~s*PlOM2p&7vBJwqumi4H`Mh@O1Q+mQc)JN;YLV z$y6|!OY_}Um29Fv@H^w@HPr`ZAHd9BaRP9woz)S+eb^+RHxfPNJf|rZH9eK{_TIT# z>ou4d)A)pp@ChFFA=;L5y_m1IX?xSxRQJu<)-TbYIWhJVKt+hSYWsW+x76uei%sDe zhEMD;MO`3c`U)8ydA^*p`xM=C!kQk+#A;7uu9S*=?^dX&2304JwM!K9 zK$M)en#pvLNErDET?tl)HvvEB4qs7W#$1{5zr%oZ5fA~~(Z`0pt`8W|NSi|aXkMc% z4sKD0axxH4WxrTJ_{fEaqOf4ehQ^ozOfM(tW3&awS4C1fiig3sNJ>nH2cbsQYvKoF_L_G&@l)funL3rXywabyJ94rHkpQAxNdAo4Of?RebC*z;l#wH$WNEU&T)JVV5*qL7svs#H5aJTM{yBYNVXN{03=_y#>l z8JUx1Kf@v6V;A9`e|R_+i`hR*9!~0LjG+5!?}o){v`y*QQa@aZrhf#KUogKdiDAQkbKhLA*W%sTI zS)#k%k4%3e^9LMvVTjR1L%tj%%fCXHoBW03<7(w84t;|;?jT|L3)gd5P{_=+l<}cB z0OzQ{Aj}{uLqNwU+ic0mKOd+0J;s;_Ajs13GziVL4Ew;9hO#Jncz3xPcFFAV)Zu6< zjIx=uWXz&p7OW<|vo5i^Nz31{AHDiC!QPm)Z%QUmG4X|LbXqd2kIYRT`8f;-o34(T z_9wj>)HH!~7WJ3Oc2YSL-k;V5xRmA4!ny3Er?GDBs{au%Hy`}aXNbI{Bhl`~J&_Vp|@F+dpFHLDiDalW$r`)IO z;JQws(BEnBrHpd(D!|cY>Z;EVFn4CDe>QP9&c*9JvCsmj1FHA$7lmjPu=ljShncE! zw*_f&7(Qu>v#@}EVM}P0mbWWrwO{i1S#$DFfLQ-F!*!+kn)6+Xm%Fn^iW5CIz^(RK7xR+WDOZof?j>F2rtRGfMHY*^+)hg%V&Rf((@_1LCIje}f za7P)M5!brCbwF>%q#Bd2_15?> zZGw^5p!?;3$GTt;KO2p`4s*oS4pgb;REdmgxpk7W8!j)TV#RCJhyBqiseI4Hy5EF# z=EZ-lm%mh%DGJRJE-+JF=*HeS>Td<)4gJZ3%eslfRPA2Tu6mij$o- zSfu&#IRJ{AHd>IQ12we)501XgCNb7P5+uxoTcec%yB$9moC_%+mU}*6b`%dP<*wXJ z&jmrL`P0uHw#suEGv#?8_`{4sO|Ea6^s;JAP{c(l+XOkz?IDeg8R)dSx;4fA%>kIt z%pGrX7TEnolzkXR+rCEfC(dmS}|oSqCCYA zAZr<8t9Y&gd2>C;9XKO%%B5V9Z?s4Awd}^wJUN#yDJiNPSQ#thl{^*I zW3`98GE{{9064cq1K>}x`{eK?3>HXSdJa1#p4#wQHO{Y*y{Dkq_Q7~97dwz~q+{@<@tA;Xzg$wUH#9ysqm?i$@@ut<`0y zXsO%qp>z+_#?DY=`xk(aT}7;XrhCWVJR<;oEedU7YRaLyN6sJm+zb-D&FM=*eV#T< z3Wtz0I^(d;lC*Km3^2fe0^upyJ0yT}5uB-KYM=&;dXa_ zM2`ahkxd%`9{oxAY-D3j(!$qc(mS^#srb{$oy(ma7h1!T{vF7zB!{}KJk9|!#`cJu z0Tz%!?k78{3lZuozbA7-o6Pkz%Yw(_dJbg3y~I!{o^Rg&zL>Ud9%J-?;s84vu2D`F-2>U;ar2mY zqry5iOkG$+`y*v?Ctcy9IVkVo7QG%{&{_weKHch0mK!?l$eJAI!-ZhcD^LK~U=Q8p zXbTsODFVgmuVSkK^@5!D3aPRah~z28#98BatEM-nPv;g{VgyQ9L*$sX#N0I_IzQem zGQ8JStG*_D`8XaZA&^dVT0P`MIpn;NNmnLIs5`13aUI}M%Ylmy>U$TFgr?S)K^2Ya zNdTJ%J+Xx7TCCZ^gAN*lk1xPpA~+sb zLu55-ZP?F6K-mo(PyzGd^ovRAV#RIPzxaLvN74r-<_23zn<)EhLe;8EJnr0Hg7ZVB zwjTn6BFkVgS=1ZhjtVh1y8JPCQ1q;zB(c>dLX3^ZMh#_F&QsfC=P+p?;PTDwD>%1z zHBfkvU~3APoh-R~&OGr9600d?c}C*z_!?g)&6AhRZin@_;^5^qmpS={#|v2xRJ}kr z${>8H*ZS<^g=C^s zBJ&hAJ1d*Xkd<=)C};vu5m#1b#Xh@_f}r{{L7C)%
qKryu}gc{nN-NVO_Cq(T_ z2j%KYk%8l&LheOBVe(VsQPK8Q&`f)kmb+M_7(X~E6#*c2#qkZ)bV892(6;Yh-+W5UTJp9&22RVV_HdB9gGQRWpQ2xi=LZWnbM{UIt zn4JVD20H`Era7&n@$C+0QHLyzd?Csote~=J>I#w4E5PRRhB=-K-@YlBcr`m@l0fN` z+E>j0dU3lCT8WS&?c|0-ze(@RYp6V%Iw1*qii00=KlZ&ai0)Rh05*v!x7`(ljekLw z!>w?N@Nurc{ERE!KEeBMyIPLY^^G-~jn+=JdjL_0> zdgPOWCNF~&bz6yN+iF)okz1WbqkD3Gvu z@ykK+7|&>ZsmLGwET|B8fJ29FyzJi@QuWwRrOjR^lJwaR1I`EtIf3$GuzE95SZ#^! ztV>TGZv~(j27D*WeoJIsckR4}UQi=*l-8JxG1f)WUcs+EV8`tu6GLNUGgt4Jfz=uL zMIO;A^*a7)E_&mpcbEXnFij00%4vSwa9AL9y6~m2JkP1lTiV3X?~7!WkKt8>uxzYn6RZNryyU0lZ$sm$+7Z$O%tV z%*UyU?y4wjx26#8Im%H^hcy7|%uRpBoNr8C>TR!x7*Swv92VTslGtPLQF5Yi9u_v3e2+xG|0S)UoC$^O!yUYog6>vv%Yk~2+u|pi zjmS(WSNH^V%a0T5@xCl1+E8PGy(s}CU9XLXy!(NMw5R9zxSBXhhGR4n(NK)YYdtEl zs6)|06D!?lBAo7RfpSgC%l3;t(Z+!OYu-?SJU|mA^Cw!h-evlApl%Qa_ca#jc*BRP zvq&r?rz?v&?Wm|XgRQpWTmhqbMpvHJ2O;_@Vm6#x(>P@>y6~@!Zz2nEJ;SeZ%u^V9 zOjqkpJUH%RqK~)17V-m9enV}3z8vs9ZI`j1KSS~&ZxYPllhDz+^+?7m8CO2WShv}-94wM(4&Z|eI1+^W>gq^LP$Xj|Ij*6Cx(1q)Rk36PQn zb%yeDnpfz};wL__0yrK5R2hKOnR@+fX>1t2f?b(*++t??i0G09iv$nwD+JaeW zYyHr(SeM2Y-_w+GnYp*O2b%yqb>1fXbpkpVa`v+@OX z7torZ;w5w~HPdeX!&7=cf@b@`?3dSOhl*6c5P) z5b9I9QY4+sc0=zTCK^Th!~&_DCNk)deu~A30nI~5nKkmqEUH_+3FS~A(&*t0>O+;m zsh7V7@b~r4Fc%^cvto2~44q|4rk5x_VtVpl10-OE!D0GB#~^J75YN5H;1NigQydPE z=7az^GLE~%6pl`wt5q_{w3y6gxa4}bJMPxBPso&Z$~w49H5tW8(Tay}Bl)kd*o#g9 z+PhBy8%rQZNgD+ZrJb&G#jX%eW~zUoZY4wTV_vV2kYT=ufz8(!6|?Vd97t=%1l-^z zH-$K{WjV%m59q}tv2Xg$Dm?_5y5=c`LLT^%w9(}wFln!cn7*Zf_|VHlKnCqwv@&K` z<`9vH%UcC1!9nfF(83)WpCBZFz@ry#34Uz^xRMkPL5h|JO*6ykD5F^i(6tyu)ZVu4 z>B0D*7b5SFS;{p}WFEXviHd;Wr&CBvBAKesk9UhR9f8Fm zTY3$EF^fAxC7zxXg*TcVy!3s-AO1Q1NZ15fI&0ShAU3qZPm+0kD|AIayfZ&%ThJ_O zs^6z?G;l03Fx$!2VpLu9R3uU45N=+61NhlJ$_uwGzC8xFcH#C3(qaTPdYH(9B*5ct z%+=UUXV464mmBJ+$iqaud%?Wy0X{1K3Z}=d(QV~S)_3ARf91*QFo=|)nxL=lJV^bl zmtN$=LPo;RWD(28i$A!Z`NQD@F7CfIf>9JCW|25U?R|DGqt4WB@MqLqXw)i_tNPJ{ zrkwGmOU3noBAkZU#SdEp&%7T%{xt{;G69_h$_Wjz4<8;w!PJ75$UB!3B5dF>2L#9M zu=g`@NHoF}1i&ultaarBiLIsi_bH~3&lrLb)uS9k#i+&zksoMZr30n-ny!&qalW}# zGOd*gpa$1nUpUXaQccoA=TTX@_hV2$;XY2Z)d^s}_bjP%4+4cW#ElTKbaZn(>!9d+ zoSH-u&H}TA<{yjYzTNWGhD4AC38^J|E;G68tqc)HP@phB7hrN&4e91iP|0X*XTCq% z-%WwvujeTiZHE0&NsCD}|BAsi%bDwPi}oGl;i0@3RSJa|&Ee4+y`i zRCFCt!s!B_&<2Kqw{Nz+qr=vZ z!$bktiUR=2Y7*cGzgPaLm}y$m{U|P*?`=X~71e~(QLETiZyKp+@Ezk99A@@jnfKyh zu>4Bhx*~$_?5WEiOwB(vvp?Xv({hQSJOBCpEy@k(iAf~LT`2~Pd~VXH$p=0s*Y|%% z7LDQ|HIj<~>N?0OGMmUnRwouI!LDq#!MGOoZGg??{S;vC55pCe2-vvQZYM%2{UsM? z^q$m7@jT6IZyRP#%xiLc*D@j)XQbNAv~s>9K?;i6t?!M(rJjTujSf@gwT9;`5znh7 z-(4zeE+dlRkDjUxpf{Mn8f6Tpf2_(FQ83TzbNB^RRq3>L^A>%DM8lP0+ALVf+zqqP z0!dS3ZhdI@<`#nO{{X9-Ddf{F+*{_edT@@9FB1z=1P%odQ!|?S7)3Pox1>j_VRA2J z#6`Z6`_*n-xk`07Kn%VT8;W6n29c3YIH9+!+Y+4 zv4+Br0R4hhC5m}bB2DV{yU^rFfjg`tsoI(MY>BEk@~(XhAy?e~Jn8mTB^AIqPUeoJ zsINZ$nr0=J**cl+w@n}{788KApkhk&x%(wIIYVvVr352;|Jf-*P#?pq*?`YlX1M+# z39{j>j2mEX<6-~NypgO5Gw%hfBD*t-&82OrR1;tm`Yq{{g%kivsggMr?W@`DZ8y4) zQ$6zGwn!&BE?j?A#_|E@0!FbyalT7x8Kx4wF|q$;bN;*fSvYsnPl-nGT70Au;^#YV z;@GtSEKp~wg*>1)`fI!PC6IwP-}>Sm=|3TwL-oaa2yK?X8)Ik9lB=TeEMDuR zTr4fKneer|D94sk08RgjKem)!xZHK%X9c><0u|hVp4UU^&;@95TCZ5&Eu?P}YLg4+ z8e(wF1jE2Wa36x!@j;(KfSTRRy^z9GJeTY+n~x7N(;Z5XH^nGt7aYy;ngNE$_Mn)% zd(_@b=IlM(q3)5dHI1v;JlA+FC>Dbcm+>t{U`qk0m&RDr$*sA{J3@RvCaR?bBzjH5 z$w;$^Rmz-SqETABCn6p^_@XsvkdQ=joMK>)o975YKyKFN#m!~XTh$`o%vK)=>G@?5 z(>_~9Tb{NIa(*$SQY=dJF}(bty_p45&QcN80+)v>*3^3}QnScvw6`T45G<^&LH0HGU76aFHJ(&iV{Oq(FT*P%nL8*z)8U6P8iJ2^hH z4;o4=_tGV&BaG)l?3COQY-D!cyW51nbYO zA6OG{hAiS*msz|Dmryl)E6`c()vx#}Aj~r;PVQyDRME3_Dr|n$B-nQd0}`w_Ef2T$O*(mA__j&rE96|=GX0G}*CQfYcF9oifr8uk8C4mE^c)%0rc zK)h_qLfOcbZB-Q|1U{A<9V+ZnUFcPCW`F1o3wBzm#ap(PO z@&3-x_VWlC{T3)d6)}uc#sG9AW5@8S>6L{ zlfMZ@|5i#+Y-Q1De~$S;{7ZXCAO-*?dmZh>gn$4)i!VR&{3teDy?=R+KfCg`=-QCY zhD&sH;6_zVwW}nS{8j%9Ys3QdQU7lN^uetBf4;Ke-$VazBOITZ&%IIqquIY=Bw*+l z^U=J|eO6y%8V=0ww-6_NNQ9%RNfM2dx^9TICnY88jrO;ItAM>?vq4naeuE*jG>XhYHD;lE!nY-k`v10|^JpN}rSgWbiZqPkRBB5Zpd zroEEAXQIt=od7!;^6M3s3c-iWTQw*APrFKJT2`otJ(I+gOYh?UG!uc<13}2XlvMwp zc0OU{G+@BiYM-oeW->xa7=FHbSW$!^i+zr+1^>OjnmUShF;wl?M18{k&OcAh#R5Zx zdZEc>_-Tpl{16rn8j~cb5m=%21mC23&uCe|<8z zX6)~AiiTs5df21FPaZ>q+6~c5&n=nEQU7Wgib5_3VSvlww>EJKCBqaIL*wJ)WqExY z{<*`?TeY&QiC==0o^LM|CHx*#IGXJ%$Zg1gsEexn|8!glk*^EuKeJn(&~W+F-WszS zKOw~IH0+FEK%B@>eE{22sK7{7=gC0JG}eDc+ExWtL=RfD{p3s*`MXKjK2{GZY=7?+ zH{0*2x|lEqUl4&^z=W;&kf(jPiM@#B8yt+~|3W7y@#V{xk$ejR3UD;HB$(wbfSI8j zQvIj9F4%^(-gF^OPIhafr3b}2qq5bk1^1GW4VJ*+@kwoSHET7m`N`}moOvAwpIcsA z|CEltGDFhu3l9kidH?=BLx`G)h{*c4sxsYN0x1oQUk|J11Lid6{Ia?f@`D~N6j3$i z42*)Lc>kcFs>;g24#QV6E!bGeUe+g%)<#*a&mYoaB?5s$*r90%x{A<#3e>Lcd4HPE zI`&{ZY(N;r@WC!|Yg^lO?~`)TGY}bR`cPWB`|7%@H6f9&wRL@cz1iUh%TiWPDJf7u zQfq8b>}rf`_vh;w#lr$`{g@D!gpiw%daaxmK6$6CN3|19q;=vr;%^v z`*Q?B>P%+Y?Y_E{C+M?BzkK;<))vknYwVbE9&eCS;kll79uJ}VR(mjmJ53P|1?5qU zVyL!WwHz1H2OlLtKw%DLfqpUI19$?_=GU*TdAXU&{a?f0=2nPCIg$_&9M8hiohD3r z4x%nglt@}w*&aUp5i^wsrVGqKUI@IXh!}5qX6oA$32aRN*)aF7?nl*qTiP~)@*YywCrMQow% z2z#R&{#j%YY%O*u+DVd#1C1L_&)MzW^MRQ=IuA}Cb`F}zMbOKx`8@Pn82%;TY9df7 zR8tJmN5?%Y8=W3o@gaWHb)P?D)E~94cToJg2!V>W2t}a2>|lNVyA`caxX_@4*7=6d z7F*QGT^yF1$YBL9*e(f?C(0B)+>eMRcmgt@^eW?G^;#2vqkM&|-g9vN9t)TXF=DwE zK+P`y7E@|yFCLsY009feii?eHB&+AT-QjzoB!!~E>b9B6Qor|mWPO)e;7;d1sS_Tq z5XqYE_?s!|czv;!7-)NG@k?XCxv+yJef@)B^2E0QZLutx2CI4GgPT#vCu9-a1QiLB7Qhq|9*A} zR-jo2I=W150#U>ivA@Z@~~#KHzE*!)Eho$)v2kep$k(^ zzbET68WoCs#I>OGUo!&1?#F^!pJ%JQ3@koZjac?6Js`C`xAVWj{%eQvrD0+KcUrIQ z{@UX8<9ny7swy99f6w@2~RfYKZIlDOyV!L~Li*E6Z z$Z})Dj%)3Pt~Q;f-m;Kt{H&^9A$#?YRRIeG%!oXCr)#TA^fN<{lL>in?kv6WbGRZF z85tR^gtsByBjwri3Gg@Vl+j4H5ZEfn`N@x`t zv0%p%K4+e2=X%8s)XeAB!{5~nf5}V^4fFt7ebDY-Q7jJ9^b9AE?;S~+rCY-<(d1#` zP}+{8+Q&cUCf}avpH%D*Gz1Jt5CYkJ$PUbf$_=9VpM(32aWg3;#X+S&M_U|In3Z=y zogb=x48)N3&gav+{6++Fzou9OlmWu z?l`oi#K&tJXae=G#*LKk0e3YjWM6x1P$r%{5vK5Omd{pLIhx4~@j1p@wzRQ%w<2Bc z{p)FZ#83(WreZD3zs~2~ra`$=+Qw|+y4h6d#iW;{!fW<;W4Qk;JYc~>sURAfnn?$D z{rqKq-$e!m3vK7g(hc9c8uMGOrzB9!H&fMTgZQ^L ze6$XHe&0hK^rZUadsvG2daI89*)5G5IALEdcKse@@L<;8Yt(IjUCiLCNDPNULVTQ0 zY9*N$6!Gg+e=Q6cioOg?9!r@WQZTA@^#4E9B?%#iabV7k=;{KDD5qeXkR!NBvR$#S3>?^ebRhTCyV|49Ef%_kCWPVtn0t^ zwKXHO9-D!cH2?#`Gj4P>1bLxb3i#QLb1b6Y7cF8yrw=4t&zC>@r!XMd)m+y}%)E z{n93N3|8$WDy>=9(nlM{f`Y|3*q=ZD>MsNBd8(*aNkIH{n?Lq>G|UFYkF;)FFSQR9 zAw)ZP@rCtOUt6ty9TdgI0^In;=Bu_cQ#(sv2e|G?N=lYScGq9@rz8sQbTawY@<*i6 zn1OyD1mShFgZ!6fh2vm>Cv;ZFE`%N&9p#y-5&Sl@E|DQ9N%HxF0MxQ5|F4nC ziG<&vfsB8u%5n6iRd|ZExH2@5((J@~@mpbeSn&Ce!zg+o`&F%HUtPFAMVNgC@uYJp9w_s1z*x{F$KF=m)lU&wfuJLLUpjeyve+C~9ag<{cpd z=3VVl|8@31dw3^_=}BtxeCNpTS=Yp_!|18>`qJO8B@ONC7glrp)stvo3BgdF{a%+0 z&;n*BKmrsO7iW$NCl`a1I6kUi_;szCFqGLMLxj##ON^`KLgzF1>NA5_L_yj@)1Ph& z!(e<6k0YV7dsqmXx=zmDeQ3nSx(vaCzL_4A-@2GaMXVePk|~lU-QT+kIvT~|5-Vr9 zc8YDin4P1S7ZCxg@uL1MGoT+i0^1AwC4{-USUJ}J+nD3|DFUw-xgH}&ultL zG>+sQPASMQE`Z^op}Ssa87#lLriKlaf))x*)rF|_i~GXFK9zGR`ARHv-N1-^rd@(N zHpB$96;WfE10_AKQkXv3v%egr-zzd2Rsco~p;PFpaWOIjL0DRm8GO; z>OFhA?49&hZ9tkf==aovn;|H$u^z+APAZB?CelkeM6!Q7ITc`wiVh3-r69PN;ksg; zF)#;WkLRd$K%m>JKi-?F{xe1Yyiqd%Kg{9TewB!9r6d)yJ)a{QA2q`o)Ldc!e?+FPzkQ}1xBENh2 zjg?^zQYT3f2!Do8eO#6p9FV&3^}=Rj{a~0uRZG(%vhCz29I8RybeK=I`--5esWS0XQKb3 z|8y1kV}uSC3p=|HKvRTK@U(Y!lB1WO90ZgnBiX~je%XAqO}0E(urfF2pTN-%I0|kV z4ga!io?&TaFlpm+`cG6M0yWg%;1G*?9k~UJ-Ywx*)zAVO@IPT4vG$r5G@}-#E0G)$;a%1vV5kvb8razJPs)}^>wob|EVccw-ZpI zGA#zbFKWR~1EHm(3y74Fk+I$bOa-a89=o*1aVjNVjlapjeesn2sc=VXi2td_Y*@r{ zEq`3$ckF!KgV3paYCkkxW&b<$U@@ynG4S$k0CWxT0;F5Lh3t9|_0L(AK1b4VyDbeD zS$KGe&Y&>HN!UX`@pD;eX*@N4oA;epqRwY0kNc5lNK-j%%`}58FZKxp3j+=&uheb` z9ITM7prBw~ZP5}rQf&3q!=n|iRq3Mj2nIwL2ISF$`z1rcLB&}C{X_2!zG}LN{~vwh z2m?p2MAZz zor6qHhPc`n4V2So!~!{Pm(nl>0SSojefmgrz-hO)y-i{uwR?`_)~Iw_0%yI00C(Ug z$?E2doe3U@3~AlI7HR%}EF=iFwIH-<4ut4L8%}YKHtg^U-geEnfhex|B78Vx0pL===6=K;Qt&dCAfBPoJ!C~DPh+l|b zVmn|vn6Ee65>@u`W5P|cU+Y-N59$3BsgPaBh=s$JmKIE5J}w49zHxM^+qW}s7b#yv5G9d?+?;rk+nx8*2uS zMDmAUy?mK1kI~fqcz!K6gB|bd`z|MHwKYkr#8mJv(FA_JyQQ=?B)Q$sVh z?>TAg>@59f*=9ylV%447+3)2|D|QKINC-|{&Fc!qv51+B*6HSwyN zIXa5Fuj+1TI5Ki`<1RnlN(c$TPR9sID8NIKBZG*N zl3iaT{U}ger60r=fzmS4^y98t zy*p~J&#M-KtE^&GjmEfbHDhP^>4=*M@L-|uW2fT><6nA&KW<^(ynof zmCHU-R#GykaIw69KdTU@Y3q@@dmx2zTRPDuX0Dg7mVInuB6}NpbIw~@c`9Nobgta< z>}Z|mT*!93t|BHjT|`*t{d<#^zIK!+CoOp=R=BufB$rtXMIRnEO}j3r8q44LqQ;`& zx%#Z}IO;0|5lp!9R-WPJO{?xfpM=xGWizRCx17Rgr)ihoyI(LO7H>K)yNWyL%U`ng zqE_^j-qtH~d|j>~J>@%iIqhjvavyrmF)Au*=5Eh!;{%v}Mh;#W1Ip>_RU9b+hzyV3 zFPA9vAi>-C_Z9KfYzWPOghh7!9?8i{uUBQD`x9_fCo{UhBkeX4Hi(%on8jCWd4 zlj4&~8z1oIs})ZqiO&y&U>Uqex8v<5aoRiwr(pKE)$l<$B+jDD%pm0tR}w_U(@%$o zhl3N_ajmaNA4oR&@L!GIzFK_|??n7Z8+<@Zx$&LlY3$H1<)FrchKG+IcnkGrsrU%l({Hqndk1HOtN4`2; z&Y(x@hKS}~Id*0Zhra)G?4r#!fB;XmI$EkkMwLLw&CM-6Lu@xk5xsGZfdN*H{w1`a zpui)y8nPzQaQbLs7Y^J3_c6K_&) zczDDS{`%6);9_U4t3}4F^EE-{mG{C12BkkFDIAkNk3Pa43Oe53NEI{KZuV=H=sA0t zoUlbLjbZ9@PIAdO;1(qGl#fQl6YQ#`QS5i6e=2kc2tI7`U#Q6*d6b%((Q`_KtRr5) zPk-k%V^5w#SW6ouJ#F!B$zpK}uaG-W7n-S+$wWqZXkgy@lUL1`#qT>UyjvSOsd4@~ z>fmRE>K4-*!=D|Qa!EA(!9(1-t%v>)DW!r#2j-F!qo;0H3Qj2*VD$JKNz@NiPF*G* zN#UPBMDjPkf>Syp&%yq9CpqiVmd}&j=fbhAw|IijpUs|+jEtCz`5l&5RfQ#9x!4C6 z1)yF=#<%{?h+YU?JX?>IX;h2_=Iw{?tkJBu&PE=4Oh)?PZsU@bs;54Y)_r8Jc3wbu zzw3OO+2EMHw=paOLMOVFlOyjn_l6}|36dJTcw8i(;wvg~zJ60=eq<GrzI)Qi4H zPIq|e38$}$OO~PDeujE`PGm4kkqY9zF~MU*+;z6U{>?yNvl6d%nEUQK`IYHwJ@1Te z+Tee==++G-_+`kAs$E0Tf7?Z{c&ryMXb7J=I^FZw>FPX=9@1LZZByWU`th=pv)%Ah z7-0o|e?ebI^+dEfYJo%k*?#Z7Ge4n=>klbEsnhopwqr%{l_83cg(4w4XTH}Qam^{o z$R-G|CaS$#UPT$lRuNfPF#DfYc&&u=(Tl)03+3-@u(LrcjD$Xsh+lJdb_Ps>@mJA` zygojdyjs9%l%Q}4jv)kz%WC?W=kL)2^0Bx&=sNvtNrSK>jDeSZL;bZ}V4&>Lk*M7l zO5lpEk-{g$ZwS!nIXRb$-VhME!6hQXb@dwiqrNY*R$VE!HkP@DO&Afch_E=gn7;Q_ zWV^Zd8B1P!_UOU&p5aon;_oV%yS4@(AH6y_wjV|>eq_FWtq|JOh;4e#A5R4_y`p!r z`{76S)hODV))R>v?X1xUe1{vmV?$>}xfY2ZP0kLA3Z7NU-FaSx&n|)X?m!IrVHyDLAhau(GhzoNVi=Qo+3?Q!rNM zW~)}~_Eb1ul4){f==~S0gjcVS{B>WnxN4>GGJ(|z_G_*OpR0aND>5WcH)4JDpK$sf z_N$wZx2kv(q{qXOulaQKEMO$P9D3`O1X#Hj`FyL#Pc99id^{~Z-s$}zn$61!?aWAn zKDQo>*Wu!NwBvBid=-&%%wI^$Ve5L*V?zbGU%i_ikQtCJVypeY+PWuAY3w?Et@!zA z0M@AY;mPic98ukyc^vmN%(pX(?|#+z>i7+-OSzk`n2%S?R9}&XmO$XE;D($uGqW=# z4Mb5eZ-je0e zOVLx%#4z1bw?5xX72#35lcpog2QjR2FIZ;UI`A2wc0ofray@Lw%*Izo7oI z$>BRRvsHC`_xe*rQLaK})OxCzGZfP%Ed>j=0`nUMK4jp70f-m3%Q4hRST}dCs9qL- znVQPG16#b*bZJQ#@pQ#~LT%7sOn;ip;W5TD4VSt??|o+TLEimmEAa8F2U8p0ybFsA zo>{R+a%3Axu8Rumg)ppcqIx{sD`Ca;X?ZjhbJ}9;xqHZk1LwGEW3xo{27zD@WLA0y zMIZ|KxS8LUt9VO3c_K@0b#Fh9RBielH8r*Sro*+vdFQIK%X}jIe)}B4(ODUKs`s(v;#wi>e5}>TdERr&=81pNjgtMvw#MvZ{PokW z^H1N$3-jFb`!wI?WtBkdMn)ckC{98`yI~B-K7rsx@cncuHa0f8o9<-1dcX9rGjh=# zpw`X*G4(i@A>Zn|I-f?-i@$sx7cR;uS~=X&=rC%>yR$s0qA+?#hB^5K6>ey4dPBP0 zlkLU;?&U8}z{HS~hW>39s?PD~p3Ok)air_Q6GzB!0w9S#Y9X!6>=jDy$h|SOX$gGlotww!P^x zV8EJbDgq7;4*dPmmI|KiF5}bP(9&-dxCp3SCFK~3p)kT|D*ZEDAjBt~qq{TkVMOrz z+Hf`R^&;KlD9Wx)4D|8C&4_NF7w4|ZZq+UVSoRMyJ2EF?^c>%QPva%A*Wc@E%X%rG*BYf=!twAB{ou`bxx11sv$yp}``Lkx zViY~0P1OCQl-HE+4@S%6*v*J^Cm&2!3htM7e<*hCC!(v4X=rHZ>+6#qaf+^0UXzfz zT#q`nJ^#g=mzg<(fbIq#6prQp3qe8yIl#Nv9g%^fK3?tP4}I(v6%>U<_)~7! z^+je}iZYxCa2noyz1sU^#iXk2y!28Mm*rFOnn02B^Y5M`1@j2%*@;T`LyQtCDZx1w zA%Uxd$IK;I4GdWESZ`0aR?)=_2)&+;V(vFE1t^{=p)B8lKzE`p-#Q#D*_Ye*nvURf z-FG~vyf3&*d6Qf4xT&`|u{&ORWPKugrFHA}+NyT6%}0axR~uUhbi}oWUvHZD7$(JJ z@y9qs-zoJ<{1|IYGy8o#dD|@uZFka9F{c7epil7Zte7P$q9Sv|Ki7h*^3{!pJImLc zq`7Q*UEn2+`%(>$j@Akm)r5O4>qUa7KqhH?3j~twD`?fl;2u5P+tFb^Cm-P~NYZ@& zr<*8`I6@|;yzH-Eh!AqLWJzFe&UnRjJx=>nr0GAFmL;8^%01|KJv}|pUnF_D^#0EB z#Mn?t3Ma)!vw=xQNk%o+IAaz9o*5_p=S0Rg9_{Y7Z4{iIzJJp+bCTZt{UN`|QB;8KDoE;p{$RS>JHQPu7QPvu{6`Z2o#& z8&xw_xV;g+qx_ImTlO+b{3kC#s#M3c8Z(Q93DnBR9>TFUIu%MR1eb5v)=l-E5|`iZ z#S)!+x;7ILuQbGMiwNAszjWQJeCqY&*+~%zjjpgEfsBR^3f7S8(eR-K<{g~$1{JG= z;%AlnTLu1e@?#bbR;MTZ3r#h8dLu!5bfmlk*$`BihQ@QP%X8a2f^k0X?t4WRcX(PF z8q5zir~90BFH$Ex|Es8O$<&>?`4F>=c}IwAg)TTx0#u>n9$VB zrDm))yadl1A2i-(p015j9Ll;%5VFv|@bWYT(Ql%9l__zdQ@iQQdoPPZfaC{dqSRyVZ z#_TZ&3jP2QW+qxue7CjHf!?A6O7fat=^_{d3>A|4bC%4t{lz!(08TIPNXLxdL(?7`|NnT zzJ%|f86;DWNjbXmEKQg>fQQ6O4>G(_uMW386K z%vSMhZexz3N#Ysa?< zpJ-`$UanQzC%7$3Si+r2UGn~cm4k(L**o!m%$WUk_9hAGo|L|pJqJ2_6OYFy{+!(@ z5?+>H0$=k%-mqmm8h(<29SzN*0Pd8ve%tXk>Yp(8OFn$);T$#0&mx5}k%$SpCE3+n6czn9KIPm4npD=nnW_sV1oe!@KQggCoVG+w^BQhV^tw_?N zhH{X5G%q)aTj8_CDtL4_P4B(;vEE0|mFp7+3o6mAO@HD|DA_Dr`-yV=qqr>y9Ey+$ zqiDBkYi%8_C}z<_(O@le7;^`dMD0(vu3l_i?}!nY@ONvXLw|6{45@WT^WMJK{L<>0 z9BBJ|yhn#WJL1oalokqI^Pp{~r}3XMU<@VmTnxJ(jP~K)fK;uI&i?WwK09?Y^ro9l zmFL$PZ697bVKb`Ib0!K3p#Zp2tSpv3I&*^7)aQ5jTM2`U_9IPA9tW<^Fz{BGpULB( zMPgBQ86LVePxdJ$D8Lf2Zw31tG><=s)r<2rv)2beR|s^!XK@wY*pgXcKVx08Im3ul;#+pnakd1>vyqYf_9miyH4oE zlXtt^UiVq9tgHY4ZrB(hD!jP3*h8-p1Tb&9ufp+R??R;FSD&pKJ-`# zGy*$mvOM0W+c+4?-oB}ceGlAd z?|eOQl*Cco7!vx1Hy`KYgyC~9K*F#!(?>Ra`fBUyn=zXK_ZMbzyH;&q5`sJABF#8zk!EetTWcw9Mct& zK*0)L_Fbe1zOD+E(Y7Ldy$x&~k}BccVVwC>Tx_#9Eiizb-f%f1mecLbWXH!clTur> z#ha(W60Z4hV=eHg`;NZ|HOa)!u6K5UH}Em}xqr1P?~^&aQ6WI27DGXZi1_cXpZ8`G zELKD@)`JV2p@WjHJehBogeVja(32YalBBZ1XGQ`Q=$(G~&Oa$2Dkv4p-=bVEy)Rx- zmc4;in9#F@VWUn`{3R)A#3rG?f)Ksoom6;0*V1+LLmqJ29A`C@_ zbU0tJ0&sVj^(K7(cAkolNfittTg(4PhB^cZj=n7#fHS4tlIiG{`eqF`ZHxxMQ%Dl; zVk%nVZZNT+kgx@)z^Vt29I6Xss|i?^}y{88RPgVkz5KC*R; z&kuCeIxtb^O{YC2!*H;@W#T|w*6LyHJ&edAnqQJPh`{^ z%yk;8{Tnbq5qZ2f*ppH!tN+xPuPs(p&FaiNS```mV9w!7ab8I}fNVB5E-}Qsqfcm| z-TAg(FGz0b5(Zrt-jyfecExl>G^TCyK1=>O>0xjl4t{y&BQ@BW9vK}O>BPW6NFvQA zV)Rrs|ApGOF*YWr`Ek{MdS;LEvvB1my+#8t#LAgkSX%O#jN>aPDAX|i?_tS^$-D4D z-*M^w|2To=3u_Bc`7ujK)5~@#*wF8^aNFppr#FDij6r9{jiLZ$b%}d%JWYUd(=A&; zg9xRnP@j1#ez)%RRUb-F`a8nx=U_xbT~ki4;aURE7425^&8apidm-~D~7iLnmyu383 z@zvz87HY5Zqm|Rc#adKIsH20EjiWhTV}z6PmvDuVMEZ>M^zH3X0s>u-U_5wQrnkmF zIXO8H5gVZq0A^bqj;?`dge0qf`B8M>a|U%${`iv2@6h12onv+AkB$5>wL=+68FPY^fAtxw6e}C|pKZ_W`AY&pfK&V^wz^%xYBd zdYzMo&^rd0BxSC<3hrmODxH?VLmbE5F|QO01F-vyESms2`z#D-D!2n6V(qv1T_}j-f z_(sVsqWB-U#=sy5FmmR>3%}82p%N@-S&SeXJ3E=^g#b#cLqos<3Y1m5@5ar zDz500mAqO2tFXh5+4?pJLEKPN$I9`Q?t)Rdq@NJf-_lt(>mVjAXlsbYngRMFLPa&TN+VN#r2NSZvX`b}&$B@uqp=mU+oz1kZ%Z{D(3f`c|MDI`P-z0$Y z3xn1L;gmd$_H;1(bb`vmLTbJ@edj`}1NmvSQV!RwJq{lU^!D{PI7aCEk;Yjw)N_5ai{tB9Q*kY~hqE0@crVYxe#}w>y;eN}P}Eql7)r5m-%)>2Q&SfZS7rNK zudoxSBhVA^(MSg?AT<#>aFDfC>S;}25z?!(H`df9Mgo*c#(R6~gFndjWOlFwLJ#`lpT@OVURc?Zbw zouFXTd%;iL_6Or*89b_LskOB%bPyTbj?;Y!-;MwCdHALRjxa&F>3z+AN`E#jG=+RR z4iS;gP1)VejlF|I`I9SG-f#3Kn`dU>tKc3DwN!T(b`d(r8gVO(qW0~_NHdQT-n8v!}k|U2M4_gtm;0`=oZRJ}@8u;56xmB&dvbbz6%HF#+>rHNm zf0}z%pe&&aoW$LXyY5!JE7tXmEay7x&CPV0jnX5uZe9Rf0t_ra%P6v@b{m(KZolB4}nPojaD1qf5CJm2i+5a?VC3;vcKY>H5+pmisS>+nB^e0;Rs_S^mBN8N~F>_QVTpu6h;v$B2SndkQg6 zz5W5~hr`Q{!M_PdYz3FBo#d)iPf8tOmS5#beFqN!9ZiX}w+ zgp=N@kG;d*C+f82%98g&^U)GEj~b0vbj%wh1rS{_H{NykyU;un7$LNxk&GAiJ%iZ< z3?0BVjN!8jj19A)j2-}x3a|6{^o2wmIUM0F==SxxNFh9Y#E2eapu_=!D7_53>f+fQ zTw-u=rA5Z_v123iXzA+dXs4BTM*GcQ!pO+zY{{uQciEfn=Lri4aV3;UY7pY9^*XQV z6B;ByBRc?2KVZ=f^LY=UkB$SdQjp#d#tP6x0lz^yL!=z|{%g=wOa-cQK}z+1bz#}1 zKoJuFG&$eqzR|1;P!^pIo?;Ru@YThEw>E#nqSEl6^7$loMGk&~sdM zTb+#BQ1uJtT#R?88*(v`{FIc~+z->s-d9)sX3uXtA4!IxKaPkbtd_gR0TRQ*L7d_# zlA&vz`8hV$QU|4zKm(h925YIz!7QOZo? zT&?!VM6lZ{>6bPz$V;@;XyZO82+U&eb5f`zQ#&oNSH0RDbu(#Mg(;6G0ZrtPZ_x2H z9Z+T7P!L*;@vfc+N%W$@65WgGFuLbIm`(Ce7O!7NlPbb}Uh!Eo{Zwpz5ATd~~ z2O}$X6&XAX(WFu`3T&|ZPEW!pfIF?3yQnFgltRUc-%l9?R$Z#d^ZTBGCdVbz5eOWfj_?VIRnH-l4?Q(5m!A(K8p z&q)P)Qz3Ja*9}m=XLw&|J-kquKJhqO3hbOwYh@l0@88C~pm>$l(}G;b9>gfAmy6C0_Xb-G-6AkIQ`4iL<-^uE+Ao-Gu`3 z&2Mg>Z>UEB?ZTpbm)vX+Pha+mFqkw7`R1xWG6@@Hr7 zdUxf9E?26~#Sd+lJRW%!SWU!N&!J@{iSf`pJ?M1Ws3vFc*~J{i4bs%fkDYuWA>Yr3;~S@KmsXp z?}-#0_2FqJ>y)q+Q`lG~c-%!Z!Qa3oPv|IUT%gE@Rj_!+v zG_zGVGJkV?eE%yp(7mBww877WfYE?ND~!C~AFAzPe-;M7# zRh^p$EALuwalTs3EMV|8EI04LF0d+6+F~id%mC6FW~ajRb5JWe~A zz2SW3sPAg3p#}(RIEIAk@_!7vlu@*Y5-dnjZYS;NE%4`c<4#VyP2`UMfCqwnKV7N? z<|Q%~7K|q^07&C>I8+3bIF8ZL%>M;~O;P{x{F>HM(fkKn`G=DE1t)0h%1HMemjR|l zxtJf#LHh|BfGWk`ztVci4q`C%7>C3f$N+pG$`xvcU%1khsC<7m_a1qfcpb>cihuzT9PEmC$Qkd zJSMhQYz6eepRv)bKYM}~ohB>3wAh)vm~wopsFI?kZ`k{mD>ZYIQ&2s<=L6ycIs4Ch zY1Nk5HA?=^IH)oweA({eZdkDo+p8_gvv%<(#2MCLy>>r;;XV*CMg{&p3~g<%9u7#n{I zBJ^wiFcqPgsQ2Y8co#v^9N&Qy=c%sXPI`E6^Pa22JLQjU>th;(@BoY)oqE8fq1ej&^inZS|S?t=?gz(GW+5QFWPXZW>@+ZB} zR0|+b5_Y~{P?FDA;!IX|33rdfzNSbY98W_nlnvrc#mVQ~8< zT|&yw-+R}c4fXfl9z6A4ucd78|MSZEH2h;V({PGC`7b#G{H5Z6=#xs~8jPw0pVIKZ zXy#xu%L+%)*%wy}lg4*4^@*UXi?#GzM=3QYcJ0j#E2+SMOjil}D1&3kC<}=L#9qcN zvoo=110jV6ZciVO!inHC7-t1ZVJeEzp?oHh^q%SIMn6Ca+9s#YIvhT<-rbA6tK|sU zTRRsI=7|12gJnb3!rh#nJ}wdI0KjkGJwekb@0^-`TZ^mjbej-9$E&UNMY_PE8bC@d zHui`uk%v6HRIxl%DRZik3CSF}P2Ygzjt>v3_Wbc&Mg4`5)!uR$2j!q7PXP(!>?iyU z1+qGfc)^b|UKXPL5=$h5*aLMvbDfZREI$bc!?n7AZI61STr&8~e{|8NnhH>B!SvY? zr>)0O_DYBeHc(2hT#r&U`2NDVT8(KCD(*fq8;la!(D%os-3)eX9ky6NxN0T-H1 z16U)=03$Ibdn_02ue_1FrJr11iC{EQeoc=$UWZ=|R?%d&0REn$m{u#JlBT!Z`kU+qL-A&Dsex9aNeLLbwxnkZ-pJdFL+XrqUI4{ z8hIQ7E=GWKDIA}}a6df>>+Nc8(gapo!X-Hx?gsS793erGa4WpcTnXC@uZE74EEm2T zN0A%FcdiF#7K8;egd5Jw6zV2np}RuG&3Fd5B4867pOEW%*-q^ zMi}stE3`BQ3V`weio9eJ6!pV@J6l2F1I)Ks)xEoU_C%?Uz*&5$u`(}RncG(i;w}?n0`bBIuE!_ zSYp<{jZ7VJ{gE_u#GXuc31Q3LYDK#4E>_!v(@KUWCL4$mpEA$`U^sUpUv~@eYGE|? zXIgf7Fgl@5*Po-ljG)^7>!wZohd4{Lq)Ph#!2s;O)kS=uY?W85B|kv;9I~v}EK>e% z*&8Y69+RZfc5-yafPtglR&d=@mlBtGv_{Up4-AVI(KJLlQ$Eknj`S5{d>Srl%keQJ zKd0adPR>p(&+sh@xNt^CkEs#Z{L>Q~VwLL@*S_R(TyH1Z{%W1o{*uc#{wNb@HaYkd zc(jwxHqD$nwn;y~IoSdLce!dzml1-=?saJLup%V^9l-+;9-wWw1O~xQ>WGCXTW*0F z2-qhX`m2)9s0u@ii#QU4f$FdlFXL<6tamn^rBgH5!q_z*J<;eT+TwMJWXOMPk zR;#!m-H0KlXCr+~oCWD_?d?>;5uAF6NIXbXbMm@>rQwujR-ronKIPU_M11nN^)?U~ z374{WzGN|fTEd)_MCp8YJc#pjDK^{E-dHoFG+!S&oLzCIhkLYKi)az?wNx)6SP0gB z(|0W>C>%GtLT10^U&j2OOrl`Fe>o;%hzw$%*Q~9an3NRqfgm*X{2Gm3W&?`80bbO( z65>FpoC=;twS)u?H5J*M^sC8^i@O5=bE`(0@IXf2@K=zn6+1{LYEn@%6h|l3$U@q)6QtUUWYQP$S_A z3c89uC^}`ZYZ8POjhl#|#4uC-XxdSe^VrwIZnnEUuT~f_YILRN1uQB=SyWfv>mz1~ z86_WuKt+L%Gdeb6sKJ+{0`5}8?QSGRFDOB6EBaJ^gDp}AkRFx2lmaa@y>kYCs6 z)RAfK9NuqhM_FTU;vO!B&_0FeTrBTuf9?S##lqA=Qgc~tk_}#q;~RVK#^OTb$<%=A zu21;t;QkjF*WM!Z4fY7>y*n{?USaqvc;QfM%^vjAP1A+NikN>YewvY)<=OT;Dhys< zY0nMmO!lpjwzgMSy@t8hMtpMgVwp~(SruQED36Y!S}-f6izsmIoLRgeoz72+u~XMf zcFm5?_SV8P>%nyo*z~mLS+7u6@iRIxY86NG7POi>Ak!5Nj$8w(xA&oRFuYlp-nh== zl74cQ`~5}XluX{`|EerdVsSykqJ1#`S9R6JK*xlpAR^2J!)eR)9s&u`1V;2{%|4Nd zg!B%HQ8!o#*y4bA=iRkw=+)Ggwx{kg$vF3|TTH5oXQboE@@nY@&^QEKJsB=26!87G z7vEM(|FSu*-G+BT!znbh&%rN$aS$a)IU-KTRz^QYL_o0R*D8#VW*|6T;o{~Q=0l?+ zAX;W<>%&d|@%vh)EnY+LW*hwO-W>%|1+FZ;0^i@Ak>EYjWQiDyMeVdCsqzLysCVkm zte=6u5S4#LoGoM=PxdK?8m6r9Z7nSPtL5h4X8ZRsK?bbMN+3K(#N#sDns6{^D}q@+ zRsWox&Rcw;2Pf)eiY;Zq0DZyj4p@nx#>FpDP#Ft8C?a=Yewp8-g+tp)NK->?NBF^q z1G5&kI$UtH*$&-t9f zpZLqxD>Q($?g~H`F)}`MZ?-qrtl_>$f*GOn&Gl16Uh|y|Nsk0SHOWy?RU*93f=zSs z!~AQ=%wKsg*Yb+?ihYKN*#A*rK6U^BNOjQrKh-O6YRlrpu zjpeP+tSy@qWQ{N*5>ZXIQNg8W%rMm;N4=Y#Q z5c3-o$Xo`yX?awwWOC3cV+tnbcCy9q;_Iqz0imBP?d}_~Y=AZ=qh^j2(FvILZ?iC9 z!K}d#rqoWXReVLI@)eng3@|~y- z9Ojls*SnqinsOlC8w+AijEn>J?0QS-t09_5W$1O>+&+HQ3I?HG2=OqT z--hLCVBR6L+!OO*QBS^6$%9adnLuhOjV|2M$#pe~3=L6pB~V4=eX}$-FGL$Sa2v|w z7ITmHg6A6|FOgw!Uph2j&x5Q|6opF|n>0c&&BKR(vj8w-C5AY0JrQ-- zCKQMc_RpX1z;9HX-d%NVuLo@2RU1>@ri?)AEQtw~8G2o2e!EP~`!Dqjw5>_bS?2$m zf3?Vbl(Lv5YSEzjR@=e>{iG@s>QCX_4|6uOec+lusODfwrpQ_op6*{ zu9)C@vjUlFZf+ISpi@FLGL z*K8v;UU9XLnuv?4gJ1xi1YLaS-Sszu3R4OJ_#{%LA<5I&#Hbz|0#FMk_HXV=`E zU7yCNEqUq!PC`a2mfHg~Mrp0(n(@#XpsA8*M*%eiFnNl*mw)}vnZwoSEX)8cf zkeBvthZTwokPi3=VBZC~tMJ$8pg{#pV)>Z3v^3O*$(-#-;qNx)+MvH!4G6szf~lcT4&n0T&Ox+r4|CibhsD&&Shu zcYz*;Bfe=FDfy)qTkLhUz&!gm$CacZWV`}u^ZbAPnZzPKFrd%GZU1K+owS3T>?d|; zYLYb9pe+viMDC24y0^azD44|0f7Ylwp=L5Lc*xa<#C(!W%tcYeGH zmwnh)(BjXyvi;M$`(Pq-D+#O;IX-ie95B|EdXaPZKSZCj1LLUX>@Kt#sA zo0@0;F_y|vQ>CLXpve49%zAEWz`GwdhW57Sn{&OVW*E7WBNe>`hnny_z{PIXCrohA8fs0p?w3gdaqwMgSA2gISouww}px^4M7f)Z)lA z-tXU7y;0)K5$({|HJh8y3Uyiv3AJh(RRtm;3 zgYT=PHxz6mcj1rYaKXP&pc>O*q++|f?TE)F*y%cmx1c*G2Rp?BqhA3QoRzI6C%$s# zjavY)@KupuxiiB z`4t)~wdwFtK=s}8^>Qi6SPqxp81;Mee49n6F)K&aLc2~QQ=BmP-Cp8|UGjakMQa3G zCqwZW%N!a~GWUh}UTAWRr-%Gh8g6!`12ETlNK=9?Ew(CoAwa7>JtCyhcx@rA<|p^- zc0maxbv5;=x6^8E|FjqOc6KqT?_Q#HYA8|Uj6}{dv@$i~d9ls2PSK;Ibe(J( zNpE%PvaOb;ri+zIWm^V8btj9{B{@puUTVc>`m_{kLRQ*+j(NsfH1lBzZEh2<3c3V^Y&KbeR=s{m5aqzkGefNeH)MX9~7`r4=+?D7hP~5y5R`E2qL} zP^E{kXiBIzYK^S8BIIzr?Z^OIskgJeT9Fz1b{`FZ={-@wHUJPZcU)Yh1T_G!l!@Ht z%CqSf9S_4x=AqvBxEa=%T%;T-Rv1oY3D6CqVE9w7w0r*0j&&mp5I~34TQIO>kCOZK z!>%L!){rv5HYpAJ0#EYZ~{6d0PjUH5v~i9ZJro* zklqa-4XC%?=uj$>cXe@*&E#zcJleQTB`TOHFg~T|hTi|k7yH>kuWk}}KEKa(n)`nv zXS?K?K~Zrqv6pj0EP?`xRAHZD{!$F*{@O&X0ncfeQJZ}Mz-6Z&CHE5e zKP7;az>CE?lPAU#TYL>QX8kmWi!&bk@mqER<nyIXAnm2G#qF}W)7;Q+u&rk@fKysGT`Fzf?l07sgx*%)9K~aR*^5O<|1r|D# zp|PQ*cH`RcU%Tl#CP(DiJ?k$4PQRAhhRUoJ+`)GfeLF*&le24Q8DRH{kk&MW6w?jG z;CaV0yDJppt-vwMnH(~KOYb>__b6ykBa~miG$O5i)t}sFT@M^OJyp{=`FI2;z)& zb!{#k1c@9Stxnb)@02+O00fRpn86qKKEPWBsA+cBmPf|dxhZG}x%+kpq#&cqvSk`0 zS=Ljhb7V9`W3XDQvnilAm6&zah>AUd!%}y-NA*1hC@Da}Qe*V%3t69!H~PmS8H@xD zJF`oGRf=&I^$bu}kP6LvhE7b+Yy9&AN2D`5`zsU4w{V)@S#Z_RV3WDH&Zf4u*Tca> z9w9x+i=5@j*JKobQg>emedr=TD|Pi=J52a4@i3$n+N4VCfo=tG6_&T~Stpz*)g%lt zl;{eB85B@!R9Xl#8XL{lpQonC(e9zO@i?sVAq0=|deeZOR9(V{9aORM{RwgU z6JFPU$hYexMdOM|+wHy(3JT1~;q8ASn~I%&4KOE_?*p(IjINa#iQJR9fq_x6T2+L9 z3SjxWCuSFd=GPz9JrFNNdMA!7Z@WAg9@Ahym6q~~jsD?kkg&n$c)Loe(+Obi`NyO? z)vsILkpPr|6kIJ3XCkX8awhP{OPlM$`!3g8Vxs{t@Phx=_;S?IA$k96|`^(~oFr5ISPHMzF5XmP*N;yYS3=D75qI0VnOG{jjLWwb% z)N~M;-fM1-W^39xQNjC_b;q$YFp7@9fAK+Df_}C0m14;US%QG2Eh|7q1-0V~*4BEP zs}kLbye}cBrFKD+8h(&c5YNYhL0z>Bjos(Q*9|RU;_7Fc$-zWcRo^_|omI}oZjF}` z1WHa~;=W`N^{};}zNV_qmg^bdG}=H6`=qer!Wd@PIY@ox&! zBYChX$La2V`FI|9Rn*2z!b``@NyU1t{V7)}Ib}hF;Sj5WkB>Kvi84SsS@nU~YE08} z*(HfE;tDzjN}K+HEIV4Q&gHaE@YfEs zd;!U=c3028G1IIy5l3YwL_MB-dtdkj&VIs57)kBuQGR7&!wO<%XR5p~WYqpqpvdJ~ z%AB`+KQ=)Nhx`$vUqt&+8!8!DWtT)F8(A@^`jqm=Z^Cm^!VKqT^q`; zhTTy_)OHerCLZmJ3yf2bJ7#rtrPW-u)x}h#Y%DyqO0tTYX0D&;74uH?{(3z=zG$j_ zV3!=i$ep59Nw}E#3*QcV*Ck zbQh2h@Ifqt>b$}NKl}5NYPQ@ieZQ<_|5L~EdO!3Ht{FmimpRW z$>6R7t99KGizcETXL*~+jejC`*x!_@En+_@HaqNlPm39 zdIOe6W49~UGh8nqy}`)%(?FOD{>?#7m_{!ymd}g|EX3hV0fk`k2Q;(}Zi>>$WX|Xg zyQ3^1aRAdzXz)HmW8&?Wo+V8ElA|vc2Ujmqkz-u1{-b=ur4SEMku`Csxw zybHB9zOtOvWA8eN7R1!VhPybRA|Z z*k^MKK-I{dt^P32!hyl~Gg=0?3YyjGielM8XG`3NGSyFIy#zMaw!z}(G6Wu;07 zDBXM~=f|N5>5QsydDHSQ#dG=p5V0(M+qy59CW7ORJZs=%+39T+e;}ND)RO| z4KcAOs|}>z2N0_gyzOf-;Ox-rU{Z6(oX8yConOzKQEEk~#?9K#^`SV8$5y{NZ8t4=$H!?D)qs*m$hYSzVU zm%$Sh3z^e@Y4Z^g3qh-=@+mF+!H6fA!F|SEciZWK0ij(jm=FC)YAO!X<@H10H9H0H<o}Do_S0C07l*D?69wK7Pe4c1*|-ilppce8?p4?1ln=R z^LWi&S4#|s6rxCogsuj^{Ctv=p2LdL`2N&H*UZp-qg>Jym9ODyC;}cB8zy`$Nnzdk zLQlW5dERU81(x|VUy(AhLezGAbVf2?4PdCEQ?@o#T%u9-4?_sw3wIC?tOna<4k|+o zdODJ0(<#Kq(M|$|fuZQHiUu;$v0LN)>3U?t}1f zafJJ*;NlQQ2&Rfz!A`h4PH8Zm!*_)fw!(%jk@%InSp1lqEA07J)G@#7G_VBD#_L8D z(D>xC)8L=C7F;8Onnzdj>v}Ll5|OrSDI3w#ZG1_f-UrVTWXJK%{9ZK*_#W}-D(J)= zzN_bS8&xzwcmQiTHoRUc9GnXkvNDsB8ufZ%%=UJN;^r>tf|YxI(aeAp<#f5|;7w_O zlE~_KKtsi03BrW_yH7)${e#`7fk5LYxLxNfXcZn|Omd{UwlRj`x^HVHcoCHGkp}G< z?EhpB=$7+ErRdK_{-8r5<8egOOy*#Rg#r_Qu-WkzO(XWKo_ixfAEDGmVL^UTVLpiz zMXtxTsim=aqNgX1d&oITgdR?p#%V%QSW;W9wLYTj2Oe0B07@XC=$pQ<|Ap7{xoW3J zV_QrZ%eJE+6YN@ymzHN9*yMs2lvnzPpPxR06&-yVjtw5w?LsRQAs8W4i_YA-wbD~{ z;ceB?c};7fzAD%6gR){MT<&e810*!Mq$K1~`>5gaLsr`*4n^D$S&Hm>+LM5U9T2sZ z>3)78Kb&rV!PU_LM@+bRak0^j@{>FdAmzy)j#DN{$!3jWG)l|R=3lNgEeeelY-I@C z=G5-~to~Sl4&p>`{YLqd7NKtlM{~Pk&5!tpNB+P79i^SJF83kTy`7zSa-<_;NWeLo z$9~f%Ao|o0Tl!Zn`3qA_pi|qoqMjxadxQEaF^fDw9eyvi6v$aO)!zEhf&t{T8 z_I-6_lrTYRJrCHJ@uy223egxiIFt1yyG)PYSk8{6{GdS82;&)io!$#Mz_b{ax=7zO z<`X^-ex31V+}-`MJLR`h*?Ggkk!N&rSHpu(+nxyW1QB-J-a@!MLh5kwq1-`uyj~3e z8)w7slyyAsRAyO6AKZaG>}ni0nal*B_1gJ#YIsf=AAXRD)KD9NCx}@`@MkF_0g>Rf z4}Xo80pL8=+vaupT2NQFy8N2%^}Gse?Um}vfEcfL{B|aTqR{b6Q_!cAE=NZ82>1`X zVSUCb^d*VZs@%x$0{UmTnf$XI&7_tdM!XmQ*qVU5hpHO^`3O3eH?OoDmw)f)5Kp%+ zlqSzdNQOpT9Sf7yBP4BTP2kg%(bqOe+xx*in_I=<*>Q}yW8*##LDn<=A$WLCH+|9I zp2Nkhuq3L68ev7r$w4L&t0u?u%PA4m)w~+x@mYh(TCjA3X8*!!j#>8 zt_<`TJQ@Ak2jhm2*liU05podY$+c#mKbs{*;S0fiG141hX`ozT#j>giAv&8V&^hkni{8k<7U>?VPDSVa>UY3(aVF; zK_~63dVI1s-H74P_LPxi^M&vF?f%xo#j(yT;T30Q9Wh6PiJqX4!ld_hoRuT<^XJoh zMo_iu2E`O@E`7z*y~OE!<2<(Q-}$O{qv_i#_WQT%Kf{h?>|U?q-|->SJa@{OFeKC; z&_`?-jE(knJHb9AZxjkdQEndQy9ayL8+8(<81vK?yG?rf?yZ5B@&rZWsZE|U3|n0@ z{pqW08VJ;%hO$bKmTG)8lUpdH7m>A}C?;!4k!{e-%(?s{(RW%$Rp}}dCIhW5$P2+-r&S2yXgcoaJkZ9(sXh7`|vKM za8<)yEVl7a)7`j~dUJbCH**FN*LM z57k8m8+DwhGy-lWM}LXfDR0j{FEcqD4hmruMt0|zEmGBRCo-g9Psj*cx7-~slk*#2kHWvf-UW8W=1!lbITP_k1F;j(s5h^4} z&e;C=YQ`Ek()E5f1r=Szpt8zLhmAaEs? z1O_EDMETpjL|>JUUo~#$%U=n+A7DsC+-sKJS+Co!s~rh>eG*ixopp(eWbYG47=J=a zmhr3+zh00Q>KQKMCtch$9`G@syCzunHr!brt2W|bH&}e!6hPI4GqqonTR_5Pua<%Z zeF@pIfRM*w9f2S|1QAVFR=iv@>%=#JBVn>MYH5o49}5px2<4ZlKnE zHY=Lg3Vc=?PzVYP`l52QP5}GEqj|Zozy-0Fe7j&16CZt+iC5VMq)ScDqQ0do&TS}# ziC*xLh^3D?@BB*bN@b(Gw&o=aDo2-(R8&rATk`}7W1gN|ZCp|SJij5(_Y+Hqqc0Yh zPp>bIkvF^`CcEK}B7EUx%uZ0}nG_n5`uG_()C4#vf70h30NHdo0uo+xEDy0e-1( z+`8|bXi?FrTIqb*44x8+dnOl*yD_PaBIJ&=_UNwnA(iIbuo>aIIoM$4=%PtzDZ53( zH1LHM1uAzi6>lx@N}5!flh$6t5eWj}7OTznGBWgp&RgnrrZLg*n*~YQJu@{4@R19q8X;C*&$>Sj8<9}SAI?jx9(J1OtV^fNU`0fNU{ zF?SjbTWnWlGh;+E5QrnOzpAHUsuw;_Ld*yWv}1(8iW=oB`V3svK6I`&7x0TBtrtKA z-MjDa4OrZ}$q1>q9{I5D%v5D8S4gP#ojpAb&~q9GBr9_=k&fpYs2#QiE^G&NqLzSt zDX~b%N2kH`8=WV_UYxHjFR0r32FVLVF2|W%9OE_=pQ{!T0g34;x6@^SBGkiHK*>&D zQ6!>EtwP%`i%#G6B+rKJvi^<41eMJ`ByINg%U->~V2A~6ftylu3KE%!F{QMX`9lNJ z&_*)Qf4Ykmp!r16*`zI^v?l^Ny%}71|0><{sI~#(hR=XBW2eXOYts;$DkEb*_K<3(5)a{Jx)fv>?0G?07MhS3*v1 z1Q!uITZDbe$YjejhJeL*(Qk@!R-=R`0g-ui``gD7P&9JLi%Nu@_VZi-x z3Iskxdj&5-*;f@4IBjp-T%N&Q#ket7G4Xe#rEthjHmO(ud?MDCYGJmvsbI|;mE>a9Sy_;PX4k(!j|Z8NbIM{N>{7*u4y2GQ{#^kY!ObmNdEka*yiAyht3?6jc+FSoFpg7lak&Df z-o*qz2PG7~Thw<b6P5i zw}MS55QivAmiLNd=*n*JB!up z5;1$Lwic6++JE=0D9$`-+}WOUC!nfnhvKCwb5;jQf8dOth%NGz?m%>LZxHU zjM5A8qvsSDy@2a#{3$0YGy8@>?n0_q z*EZDG~P5qpv#e$Xo$qr_NAtp|J;tZrooe%-eYjGX;UQ4rpfUXucs9eSMbXv$~% zLisedW~q}-HVDxMq4~*HLbc?{)*{8Mn9Pvmi+M}6dtu1Iz-o`7|Hsx_fJM1QZNtOR zAT137Qc4I)cS#5$2uOEJ85OOGC&c*de zOsr?`wO8EhzTcxRRwXc$N%JDPDC=gcAh(!#au%aC75K|Lu_J%})F%~N{s~DX?!kz7 zaKvQX(|7rND{r5=cF%h%&VT&i`B<+;eG0CwH^k=nv!^=YPf6%5S{qJVKP}EDe#uA6 z<7o|jwx#S(Qrm99o|@?%C2|`CN?d)q%f;orCqG?P0@&Vr2pDUR2caNY{k)wjfXg2V zM}0~m-%!xZ5KyBqP)UN%?;_)U2P8M{E#f{EpeEkkk}@JE zFhbBCjKzu_#7|;1eJ_2{A~1rA@1cj5v9{h*ZL>OR&gORzQbES~2c)u$<&C^n4=)sz ziVP@bf3adTnI&VM22A^w3VjGrd>5X^KPtrtA>--cF+Llq)X6wM-zb~-91A|{i=Q(h z+6H88`B<%H6Lp7o;^v(&##<|&dNfz zv(N138h zV%_hvs}1LC=JV?A>F3dohPySz@kxiSbm|-RuaqZZ6Z3xfhMaIPJX(Lh)Nw|X+p{cc z_4OpkxABu6uC)Xt09y^M$S}&l#dOEaECNSc(DP06BQW>wg8WLaggaa#athJ!Rkk~; zekr@+7lX`5@A;Y z0*6wZP=C<{)-(|fG9fZ)?MWU=7-t|%#?79N_;gDp5@)(|w)jSnJu~$CcYzN!RR=Y1 zdX9;9RW@d;6wQg^I5`U==#_i>ns{H2XYOel#E@oM;i;%*Bn-T5W>JD8V7T|*b3V&D zoR8;cKO%E~a>F!cAPEObs5JTH&l^HY6P7pDG^qP$kU$3$&_cDjhI!RiWg z8Ul7&94}-?L(4!m!K#pS+Pj<|N&iHK1q`ictX0B$cP87<2$V_E#1_9B;yTPzU_==| zv+^k=d9Fd8fSTSGeaX1muht^sI~nr~ny8%n_}2LGheQT>EQgPQs5e+>!ua_38G zW#-a}|cu`uDaE>g@;yT^%2BvcSNvO^DTPl8YTH{kj^* zCt5VAP&fp6~dg5XszK)Jc{`Zo_g*$~wgM z28XXC%fWVtj{e4vtd1pTNfXx<(>`!AzpT7x-j#8_@4Tq&Q0#0l4)#)QQuh9X=m1tu zW&?*Z?V=9R8s65>J71>pz~?%7KX$eQic!zsfb}GI4ur99gFQXUf3t4x4N~HGhI!8E zN2L`Y%v>tbmDYv>6j1mr3H{>dm5`uzzy+bHp;2zeP!MQgZtfBYAzheqt}Js!$GE6y zkrx5Ff`C|GFkW@8;o6w0S=Q+P8WX%ID?WF@^U*V&g4N6igg6+O*mJMDo09Fe-t*`@ zd#3&KC&dM_#vS&foIc)yJ)97ipmLg$f$B-dW0dbH5lDUF+$*GQ$6)I7*clC87jf1M zCpBUioCa!;0=+%bRXP!ui{UGaOYCELOU8;(R?MbXEyfKm4=0c=U!{pB^I@Zo$M=#R zyvkBpX;j4-H7~nzGkWp#`OeC_idcmPM?(?9xXJv9(6YeVa_RkuvsR$)@eoC+^AV6F@3f*?JVIqVXIeYPf*5=!J&~|Sk8mI0HGv^99;xrX&z0IXLL$w?v<- z+i$xv!uDc$O)F`QBY4`8N=ZNcV`!+Xx}IMQX+C(0&wIo)<>mUUhPNOyD$~BSaURgN9Vc9p+H4`SJwt0gMXyMOuqw{l!i7!}-~=3dUn30iGf6`@yKz*9z%dy;Di z`F(a(hMkV5GmM3`+OVZxcd68Te0&<&U#r|2o+j|`bH@o+kTBmI9@0S(*|1d(+MJ)C zvL2}_ZA_DyF}4Y$#7FP1dzl1hFH;RSrIe97PZws6eqwH@iQlb_vVWi} zDK^hzL)%|dUZUUQIxM&O)8>i_yx!IJT;?0uylp<6{yCSXg7e`oAj@rL|#=R@pq*eVN%58Oc`Q-0^)s zPc22DK&4JMC)IU0DRM>)!Zs436E5bvGOlJXgqtxyT>L0|MEqddD+c@MMTjJE<6h8! ziBCfoW7(Aji$=$s_b~xTOS6r#hHI@g^gf96Cwd3D`-1xAUaZ316JNKtY!Sra>Ac?6 z=JjNbvm+1f&gv}&6TeE+1b#dCmIy=X)StZ*H8IH`Sq?IKHG80l)?UMerVV2ud_g`4H*7prAGgJx{cliR3w>v&qZz9 z6d$mHNa-X-tmS%Xt=BAs z7+;QmJ#ZLbnDZg?_V&S1ufzbIo_bV8Bk>2D{lKlaM5g;{)6q8;61>(-1nkYbcM<7F z)6I@3oeXbI(f1b@mrhNtgW+}GWMnEIZ*piynH*eJ)_B$KbdLr1JXy|ZEwMKGo5g&Hws^%Y1ba`IG;GWNRjQlT`1vjHGL~Jx#USZ!!abum zKhxZ&#;0cz5)y9rM5{~3+@a;h&|v!gCCP-f)f=n2W;8) zT5>pDz!L_;vZz^GWU|snNmw#9`_fEGkLMcD8Bcs`Y;qoV5d1Kp6xJtk_1g<}u%2;p zp2)ECVc6%ePO2l#A2%mmc)xE9cDa%^6cm1I#@%#BvNuG6tTD*##`Eo&Cv-p>U{46} z>5z+>_oHfrzSW4F z%^T}0p}y7fyjaHwb*hky^-el|brw!HhGnJQ-@U@BAol{*Dp1x%j(6& zse^;p6$E%=`D&=`#+}q3<*h)i1}H!=9kjY0f9-Rhb=B#Ppr=pTvA44Wq$00YdZNFw zWL^OZK|&TBdL!0u1p-ls1AI3DqbV8$LdKOFPE}W4xN1+vsKL4wlM8WNQE4-8&Dk@l zMFw$Yf}?Es5Z|WEuy!pdUTW32oKB`+JTV|~sYu`sPZKgQD5Hg^Ni%6*^V?w4Zr4&- z-Q`P>-R%|XW#>j48HYrwp8-lASqJ5sP;2a*t%lrp$bL{yql{vEXbj4u6#(#)s=ZQH zmIr&cCS70(19W9K^=X0xrm-!!-&-XTNA(xRC&aa!tk^f!ZiC;*@?||#X*iAWtXg}F zf5VLf?(gbe#(f=}sHh=ZL6IYOz4ymi+1R>M;}$@!K{l^c61di9KJVv#HoAH*9nnF6 z2jsZ9ULGw?AXdA>;{cWQYmoiju7oiUZE5Yye6G5`FEJPo*neQahO%{lbtOM9Pw?i8 z#g2f$c!a?9%GA6whBh39Yp>MSh%*c#6r?J$HIb`2=Q`xeN$~Fj!~&D7!zDHsnmpnc z!_GSc;wi2ksFAV!QIh)B>YQ&5{H(0(SXi#*)BR3XFP^UJWR&Q(ZrHHUlhfRw6~IBD z=6XZird6s&i`6aD`hCyCi6(sNo(>ZSQDrS>DTGlkkp@^SWx3p1YMaZ}F_LI6i;jh* z-R`vcmj0gJ1s&@c`7`UwjeAe$>;rnNzDLzt0UlDEV+JZJ;t2sZLCHK7Z?1^n2Ufo~ ztXtflUplk#eiq0-G;!iY$oi~0Tz1Eyc7vqoB=lkFq;;*R%bkjv`Frm{Rp>b=2m&wZ zwOP>}c;m&!Q2hSSA+ho+pl2-(7(hTcNCTbTiiEof>k#6nKz3^GI(_5ObG^Z4d|=(GS2Q`>zs z7_4=!7uQ3?X>H-TY7NEtYU{aO_!AvYewAOd%Lp$g8Uf!Ve`5`=chwZF7xkx|bqT56 z_k&e*bn_#!yNT?->B0))t4u&P(l)zP@9N^RFoUVHyjoA4(GU(d)F!yqcz&yyjHfPo zugA~!^0>#US^Ta(il@ppmej5In!p6%XFp|`#1_yubJps0ybZhB&sgFzn?bdr&ZYJc zdA!-%l?AU|@T;y_CTOd=cy!Ab(%k1f*FM-d6r+eIKl)$#FcC>z?CO~Ku!d1lQr3Y~ z>*U0v9*ss6as$gBy~~ibdz+Y}v8EUd`0QeV-B)+Wu}moyQ&)X>N3}2iu=UZy^l`{j zl9b10D}kq@XFFIubZ-Gcq9{ff*78(5Z32&8NKW=!?Wgyn>$vn?zJDhpSvMAaBRZT@ ztBpdY%c;#B�(1TRUDVCgOZSedsu7C0y7e!L5fwBn1|#{P8hro?w)qN|q;VokNPt z-Xc&6i9G^DrkAL(jH?4sCuvkL49)GCIU@=K(u$-*nzxfti6*}5kF^-s{mks8%=d&G zZk$U3p(bRRy}f(_f$5C1F0RcGHiI|gc=wktZD;dUHfl3KucX;*8DQY}i*MQ) zvgY4EeGTDP2s~sNX2T#Rx#6pF|Gi#H*kY=>J}PZ_{I~WA{#Cq=@m)?%`_DK!2RVoH z##f6!Vmz9IIQhbbEDC-&>m5&)6c!$YYJr+F`}$zm{z*07-d~HQHFK5fQ=BW~Z@x zKX;ueV_2~61%VfAV=?r?|@DBiRODr*nh zp}5r|Xczn+1neoYVrov6R0&Kgu7bKblj_Uws&o6^qer%i@+*AQsPnkJd50M~T5(k* z_U^9th2^`5!fR4vX?vW_Y1duQs!bL7a1Up1@9?wlVhz4iYpGli91-k@Y{BvebvXOZ z`zU*G2QzP{;(L8;BI7F{W$5V>NR7a z3z{D&7`N(Q3|!4(W9ljAzC@%xuj6XCFMfLlbJU2t!%|QuUMEfT#oEGLr&#T#$QxeF z_E0(^QW9#(h&>n`-x6p5W1@|S&frns+bGm1>OB3?F3-yo5rb=D(bjcQC2{5>ow!Qf;8@EPk+}Y}^)V3hEANUE`!6VxA`(titrz9%ty?^ZYMpl5 z2hW~qk*`r2HAT5Ii3y1@pBtW?9*j|o=uzHy;~%S!8H7P_OEOc_lAV3JiW;n%DjcOA z(HXAhACn?bLzADvy)E&!mx`axR{Il~8;dvd$9>5>)^ih!{ZZZrBZ@%h{hk)~51)$m zd3{q^S*W&Z_0{so(N-d=w94u9WH~al?pltKj{NPN%>%_57_u29TNUW%3DhI4p1xIg ziKnBjaC2UVlwa#HFDL^a*BFymZ54t*S@kDK?0q5g^gOJ9=avZ6#0sH}oJH2nvuAj} zTb7Rq{@>FWg)5?I31F1OFd2!)AN zmpiafjP1`qZzXzZ);dnJ^-<#Cv@p=n*cp9@jkWOMjEkP2Y!80-V32r$y>|B}Lov#r z*5T3P#}1QSY(u*s%KbTz!YUWp+pi zRV|nQJtTH}s<|IsZIKhWV{wlZR#uT(C1 zzeOtHuwr`p#4kA(Zi%aF5CqcH^Q0uI-a_RreQ7vy8fyD;)7;{cLCV)#PwxXA`)G@3 zXN<9)9`0-Rd7rvoOVYS@HF@M?$h{F_LHBo%N(#*VO9G)8QzQS%S)Wuj$~;g1#U+pQOCv z3Mi_Lj9K@bM!|JRho9GQw(6hniDmpW?!m_+Y}!bERJCRpAM5j?i?V1aRT*`Wy~@NS zqiOwQS6NWwL-mNQex2R&Z#A8Sn~BQu`GUjDO`4OS>*#%nlv}E8$GQ0kYOLJ$RaE@V z!LPvR+f6sa6(6S{ktF?-2P`z8UMwkGA7Zq)RKkTv6OKiAL+BG8=LOjKu#-h>hbYDB zjIgjU(2xjRzKsWK^}TFx-t7sRNnMHT}=eY8HTkE=KA}?qbsHeECT$%Ut#zzeCtix&)}*#isX#+r2Z< z_bwAuR#YaU(?t<6NOE1(FtNtde#iU~^{d%7j*!8F8qI;-NV+d~}MxmFH)G zrErn)B3ALU)g3}vsPV(hkFL6@;+r9rd^Ah`{`McfLHuo_qITnV7#JA# zqWLh9H(O-A8l_rx7snN7C=MdTwxylm9UZbMiXGffcp0UM4QYCG;phZPMDT2*4rUBb zgGM*U`4*oS23lILfovVKR@|XJ^~UqN^|>${wbw>Df(aMZln-MvB&JeaQXk@AMHN92y8 z4I4WLYTmVJF{#B;88*hNw=tB0wSJkCAU$WRw-Js2)|74YbEU!{c9(Tikn?tF>&E8M zYhlY@_e3IZWxK?h<|2qm!XW=}0kruYGTe&=+fPN+tov-C2^yvqFSpE{B0U_r?UFFSjgOkFJQx9~{E)De`C8FTgSk%dO@`X7)EB)ZVSpJsQEty~Qt{}Ug z8*{nq@{@P*L5B?aDPa1bz=kH02AB~9Lm<5^ot6N%S;YD^7~PEHMP_S$}q zJ{Zc)IQD>$L@zG0O=MUepY*d~Xjp12W5|n^_k@pa*faV_Lt`5C1tXcH)XX`?)iMsv+nc%0AO|~ab zalMjH(8*vwnfK1KBPH!(S#>uj4MofqyD>!}bo+}S*bxK;KAVB$00xE02Sjx_H6wIP z-xpRp%SNs79VZBt48tTswhG@q#J)D|SC?I7tsRANSxbqKcMP+yvPj7FKw+o+3Y};! z_V?R&Lk$LXPVtF@;|Um3!EFU`WA-`@N-8xE!)b-9=i@$*nfcY+DzebEwe<*AN2fjb z!S}&G@UY6Mtqp&b(?x(Ap4<${Np6iuLJ%sg-Lf!uT7dHVE(XY z&^DNe@Z@BnT?J8G;5m2J(0*rztAq6U=HwX<32Sa17MCdynD1CSuGQSUINe7THI`EY za$lLTJXJDt4A+hEUTbw>+=yEe9NI012m_GI!UCG0Cm)UgjVcUOtClp8P!{0&XmKG6 z4#F-A5NpfJYO_=K)^mEvjgBNNe5Nd_5Rx}9@XWx96qw(w6$~c`5snd&lXf`;+O^XNXW4y@e83Q zm{Jm`BRN(JyT$Gb-|9b$3SUlm2~$S4&gev)#lq2{=Wg^fpRLMdoJE+0Oi*RFK1x`42tV$E=tb?!apyKR}Ut3X`85eTUZ4Wz)Q>+9f67yd<% zu+%=`UEmNI42uxtV4to4Au!zHy3n<@{7CKj<#EpUxPC+1%fx==r)s3OXnrwEqY~3F z37-c9J{8@t-C#8IpvjOeO-&p%Ea5-P_yi7#BeG@d&jS37ZTHeb}xv`CRk4PiUJ= z@RXEOYPM-)&%JWr%QG}|EM50%145vPUSZxPw$rry6O7n;fwGQRwJPi1F~$I!G!j-7 z-CK)Zg8B=__ypM+Mj2Tc3n#WCIXkILttt+FBV-CNeVxir4)E;TWw zNufQuFMV~pJ`L0`_SkXeTpg?VWJhs6(cyZC`hnJV0XtVa%;og-ob_m%dcHZ-#eU!U zsmu#AnF@94;dUv;w)s3X=Rcw^EV2-TKp}@oclK&;Tll<|bd})+fs50f)eL)BY0&FG^&Wtf?vE zVfCn@MbgH95AV|i=S0Je(Rlj0}jw?kQMZvo*sCW8PH?{asA3) z3BQZsSG5z+4YnUl6#@1q*pz2iOMiF{hr_{gUt&jrHcG@6DuNY94HTgFbYDY+*E;iA zhWXJhpdPF7I=d;5InxWLHs|2H^YVZjxC=z?mJS(0&gl!d@YW!NF7>_aZ(4z~4D68Y zmUE|eGPt`D5Wck%#4ZF9Rtr(mc6}el$!y-S88v)$+af8`o}Qn|aKA6LW9~ORD%Hjy z2?=_88g;#2l`>~>+LB+*x=sKo76(w(#UVpegKR2qZA=ITGFSICpAiEeiJECWhmAd!iNf?TxBc5ZQhcTl>(SiN@8dTkiz(f@}X8jgWGtiaVS|Kg*vp$TP2 zT+5v^2uqEE3-{yV#!T{<8_a=2r~5xSIXFPNHIlE!P@~U%*O4{r20esS52ujH3m{s1 zd~ws#!5G$)Y;(Cpl1!pDt2=jtF>)R*ECn>pq>4YyZeWx;U2?R*WMEJQt?FQ<{I~A~ z+1?%gVS;mFl%}nqWvp8!Hk@~Rw{!Jz9o*^2`-C65>4+5!MX==NOX{tl~YOHyoxSH;{C!!)b)%u2KbX~U1zidX%{P45%| zw6*(-JX2-iY{DPEMjCY!Z7LX)y6@=(B9Sk1G$h#*W0Bss=?nzo+|fGg=#MtIyp z6NQL7tBL@V0#vxysQb>O>KP=8b5h2b=9mLHZu@%_QE=DOFq_Q>(nB7`qVgcQuBken zM7NLwABuCCkztTIwt?Xoi+$9xx_$bn7ndNOhlg{hw~w42GW+I>JCb_7oceD)v7ASl zk7(~-5q8^PKj)ZF()RRBR4W%id{xx-6i3TpmtDL-5v>#b2$>32}ByLUIa+zI{889!vWn ztBpZ-4&f!|Z_Dt1kR1D$c_<4vz#sb!XIgYe+@q@~k?&QRuFaDaTi+qpF%CQ>113O|M~J-&W#ZG1SwwImi1w(uds-^mVI zH~B^<%90dIdBQuweWXN>(BRW+11YpfAd72D34INz#&;v!IK`klf$aVQ=Skj&?-p|y z5k3$A5I`aZe5Gw7nc70?GvF2sZGhxLgkyHKg*evePL4JhJ|Q&AgPH=_r?n!`u)A~eDEr_1ofVD zqvP;;C1G>j&S!iITJDj%k zRO4up5HCJn28q{8Cm+c=vPmq0B4~tUb2X;ydqsI}s~Z$a)gSL#gr+yU9{Dg_oRg*1 zN+!fnGA(F5k{-mcWlq@N5GWCwsC%w(Yy2%h$Ll{P%D|I@c%DFCz1e!wCQ3p4yNxRR ztD8;;UNs3?imtRc_OL?g)_bFq!lfAMf$dj1+H2&E8v2}8KfXYhMBv)LE!|07*wI2q zP#P^YnG4d5gz){Jm63G9#u|orU83@Vk+-C{KDw*9bM#iQC_#c`o@5B`caWhHedb81 z3UfYH8` zq4z5-49GIkGfQwaC2{XOWN3?^7Yhc=nUg0Faj(jld8#Da8}?)q%Og8oi*ZRRH{-C-p)-upgPoz z;?VNemr=f4hb_3)`mvE zHgP6VCi!miEO~XxY&V%0fW3zl^@(^2`++d#-JFE!*idgn@SS_IsSGa$!AVPtaG0ub zWw5)QecSYsLBuKPBo5P=EmONF2K&JC;xl&LMRl{+kQ2UB2JM8vV2Yp1HVdOYw3?*< z&1te$I&zxjwwfK|8RWWEt(HvrbBP)w31gBE5nUC9jdlVdUK|-3Qv371h`k{(Q!I1u zf0P%Ado&;C#3hrFD)O`&GSEbvVLZZ)4^12Pf=}#P*dysu3~z7m($>?dtc#8^DU%w{&ZD<89asM6c^SRJ z)jLYA&r|{2NNlIkbFSkDK!CdX6$o9kTMDZ}1kHWjT#^$mXkPlP)>(s4OFUFsg$}ZF z5i(LNjx=if@kcb^&(~^fv@gf4`+f$h*89i(6ZA9g7(BKkptdnZYklv{E@JL7Ca&*D zJ=Ee~0n$Hz=Yi*!APgDRIC|4}AVTyf>HYhwts1lk{bHs_jVb56*COA(y5Xd>0-V|( z>E)iEIS)OH-k7wm`eFH?;JaM`hf?!(Jp0dsMKRNp5I&G1RJVQulu1YPe&0>~pPybk zY6ZyA%q`s6y_jV4amCvh)dCIZ=Y+7U)>VM>`c(L7W0c$N>*n*i86O`@t(=GaIW&I` zlRsZ$Sck>2+W<=fs~8!F!e4PE(CPZ;aZ4eyvhvMkVK@K}wc5MZ&@hCzoA!Wlzg{mu z1@mI7oj<9B{^kal8k;8E`l{p=gU_1pueD_)a(UT;pNg}OQ!O_&A)+uC?DI>2OuC*=?@b_Oh}-g^r_FOziG9CwmmA~^sC3O zlrE<7zxEN2hR{RO>kCuK{xSdGHz5_*mVW~f7A&$p$>J@uMe>LROg|x6T+R<0KRF3j z)BEEF{`uO7K?Usr;L`uIeWKu6IOB*7KA^x1hT$^REw%D-HM<|liva)dKPF-{1Hl#u z&_4mfseeDuUl(_724Hpp-3~#TaQFyQxm+t+^KxT1$<@d;E_;7|BLbf%dhlaEpS!+yRv#SUX$2*!Dj!EDf!^4em{GLTKN=Z(J!AK4RO)c|XVc!@kNl ztbSu7ty z)pP%^5gN~_R1t=M7b3WzB*{c?lV`m9M+mKr8{?bx{s%rA0ER5z8sSDazOQs1;Tyow z6wQGaTZ+)qvi^3LpCW#s*@k-l3n+V-srk3u;1-tT^*C{{K%}JD&e?3^o_q>ktSl}+mt?^52Pfw_X<24UYfR!t~wX| z7Zru5i!Lng1s5Z?z$KUpm6crpv-e^3(ky>;kN$C(Zs0DOQsQ&|o!%&B*47G&iP0ip zPx(?I8#<(5zy=?09n8(h|YI)s{^#-?#e)|-(B9P;$DXxzM;d6$_%`Y45f`R zpd^d=ij*=oHTob9ZU?MC@kfKS3_n-bjv29|{LZ)83&M?!7ov8*`t#KHU z6+P!qKE%>2={2-hAKqI|uUWjqvM_={e8di-+9uxqKO+Z+6H*t*-gA@5I%L~$w0}C7 zIshCI5;PEY#s6&BVGd~Gz?~A(&cVO$&M@Fv1O-Y<$Y5VzhdRj9jLJ=AOifLvi43G< zUn$m!lr0EKh^W(&3_DF08C->aF4m`~EnS~hD4AtqX0<6XSREp``R9Gz;Kb!ytyrR9H?h%|Hn zY-s5!mx}v;R;U+glAxo$vT~mvI`%aRn2`QGY_>r4m10mK4&BNV0uk+LQl+8$6!Fyk zMThdaeHJ$H^A1n##tVaqU5}|$%_&tinmB5!3N4~4K6Pm23Q#|0lTd?HZ@pC)#q}UU z`xmOdbFvt#_p|Eq@&a`BSPr)eG(N9Wr5oGdMUN zlixJuD&U>?^|)*GYn2E`jRpx#@$UXpj`({zAyBYNo8C*SyDa>|?NsCp^!i>bqW2%C z;ipXsQjU1YkAEE1CeR<>7*Ch*dM%okW>Xx)jF#IWC8$fykj0}xQ*`)MALC3YIV^z+ zr5rGt$-f+$rEf3l{xpeh!#*-M<@fvXMf!LWrsT;def3JNb$3(~@5pzX=AQL^l6i?C zoAzhR{EtV3W2{JnL_?&Q)b+25F=-UJ-~0FPZPGpS%FETY^)>YrF)l_2PcVPQF=vGZ z;-sSUcAl8n^V<;w+BJXFC@UNOuD!t>ftH3AfyQ*mLx}c^@Att6PdtaKpsx8Loz=+&=%rg-VXMu4*@YRgv{ew?(i{ znLHEs*Lb@nZ-<=e@Wz0Ez6xkuzwA8q?rPUk8o3*vN9en;JtBG8V2{OWi*=w8xa0!I zdU;bYBw$uy&{ivHp_O+cfK!7*OF1B!p#Bq{cCMd{6(2JND)sTzCGXzPw-Ad2;Q`0$~HotVg31CZ1y z(GP&}7}lFU`0(&~S?kpsfEU%$W;4p+`5Fvz3d-qnMk}ZPqQdgG~4q>dN z#3xAS@Q3nJe4V)T&b02Lkb6`68Iiehlg4G41@&WD%dFj8=N~rle-CJ|9Oc1s^emzL z<8Xp zi6^&F!)pLQ5IhX-eYLmL1^PuEKyNy@pU6Obvuc+v^;09F)aZOMh~c`i34q{rFW7M^ z)95b2sAG`HqOvQO`!&Ovs+E#b&$kbJ0DRScd%)nC=La>JmP!R=+#BUkxi)i;x+X5l z-x#`^TXwl@ZHgod%S8ue{WR+AH@FGdvfE7&$v0{g;^%Vk@rrOm`H=%`CB^~Af)DV= zMQ&~qItsf#ZCux3mc2pEHIGS9eC8(hLpv)`!}%ahV$R)?LEa@(-lp03X{fXU7T=c+ z*Y?o=1TlY%1&S`eAW{1pPu;J5NfZ;><_rwr&P)eDkB#*EP;sMnnek-?>f$HDzv`MJz>3Qxhw1bfXnj2Ut`G~p+V=wO7=}v4&bQbLbKvo^k!%!pHii^)rmKjhU zpw92QIZ49wW`SF}{3<3U28_60H%g^Y7kq>mx+?aFUjW$Jv5xVvAAoe@6BDuRIh>q9 zLQcn1E`ml(Njc%dh){}xt39dBs+1jZN%XO3FdqnaHTaFG23O_l7lRUQ*vGrv_~dib z_q}vYp=d=NM?skh%ag3OjWYfs5?J?$6-NnwjwMw@F6ZkrmEUwV&YRS3SDZnI+Ek+9ir*M5X@lP>PsY)x^HjuUZ!m78=U8WS(RP?I+8V&Q%)An;hzLx_cb&)61G1e#4IiK zZK=GY%OK^LtNw6divYNb6LNgp|ij zg_&z;klwg-8^iCUWjezpZZ~;MJA7l^K^dxz!R2)oAO~4$)mC#1wTmyc;gQp=&kBK~ zYA;>Nwr`DnY^2Xf7#>g6aq!I@)_u2$X&n$bW%DqDuiqof*%cX_JOL@8tZf82sQgG{+=RrLgmBgnx2!a$uIe zA)jd*WTerQ`C;|d^!R=P#s)}(DUeNDZ0BG1OwVCyWNk5cnFYks9Py*X^cF|^&W48g z8HS<(E(MJvS!6u_361_Xlru9U_g~eMW=AyPYfcT)T@NTv^MM999(yf&wP@(*ED zyMO?JRDmqW>G?Tx6OlvSWC-l{%A<#yGIvmc+y?3vTSm4r?rwY5Pz4hyhWJ9gwO36+ z$Z4^`p&~8W`umywvfM$bj}z%=%u^ZpT8vWqoV`!eEM|=|{iWpx;vl67BO}dEaA)q2 z>*R>mi>F@3uyXTVJox4Kw0)Gm%MI7(wI12iu{AZt&Axv`TmMa+`IUh^;R@eZ(Eofm zPg33HHv%tF@25|%Sz^9?dD!^TgSQn9hfJblPTwU&3!@i9JR^j(*D$KR8*fO%rSg9} zP7|(?|4N%EDPe$3Hy+@e9LnjiZO7Y+wUVLGo02goi^m4`J$Hv0q-?}}wO>>W8x{%K zkM{*fY^>aB@hAH(VIJp8Nbg$n#=^H?Q7dmzx8XjY+SBYB@7QHS`F!GxmRaw!V-5FE z4Ge4!+WoglVR@Bynr?oJmVsAVc_OV3KaMfyR>%hpE+(&ROExzaE@f+d^a~Gq`XHsq zUiGtlAm5L#vDAUZhE}X+joNlOSYsYFpV7mNjV6pcrtD3I$ zg`NEEDLwiS57opJ-S}^L7Y{77OAGWv1#|*13YVFmnYH7w*irB_vD#JVg?63s=|Ri~ zIn=eD8QjWJ?Ph#dCOqFV`@MN7E=@LG(yoFG|Nk!HVH#)*>f4Xx-ip8Uoui~1N!t{z zq^|ZN0WS0{MVhE$~#w>$(~P^(t+Yw#}!SO&WJ^ z-02zaa}?4z!Bjdztew!w-qlU~ZDU3;PZ){`{|<22qyVjtC#g$#^EM}<8G0J zNkStwUvZwF<{b9 zyVBC$;yHJnj!gdj9%+i;geL@l!{{vxR-b=?epz~}1SDsR%NAa2Xm>xn!n3QRLpVvA zJ|4Pn&#l+e^{jmlZ8p+NK*GW&pI|@jffhaOivTDaSrcJ{8jL?xJg5r0uO6qhvGgcI zK);~UCQT^Co+zXAbOrmB!o4qcXYR+J9rJd6`6jYk@h0E9x#31Pa_QaXAvj$upgUIn z*k+%}D6`dCng?aCV6SlWEC5U8yyOKY$K1b5{Lh6_0;pZZ7}5NxaaOYLZWNW}<>unH z!+1Y{a94(~s!-9;aGYBm9pF-BWvSA4 z3RqcLH+Q+sd$#Y4c=)}Tfn9#Z8RKtSnz;@97|<^ zF_uPUU08>2ko8U+R+V0En+guk>*uH8Y;xA6+vkoACWJI9eI@g(OD+^vg?3?Hk+g%x zyBU0g&V$0PKg-z^Zi-cb(B^+X!ihoZNWxpp_Lrx$rS}8TY?*FFR$-wsu|F{i3^P(* zIX*5lE-Nc7rPwkT7GiuuNQ1mR_C^>o=dm0P=83qBn>-fU{2rtQP!^PEBO6?GC@2e* z%h6{MZyoy4c1)@IxJlq~yh5EV+%36|28gW-o#*yiZ|L>)jyhE~HIh{WCD$<`s#ovyQl4?yF;2)Qd(N1 zq!9%H=}wVGI+qYZT98obP*S>6kd_pX?nWA<+3&3Jyw4lo??0B^z4yN7oHKFF%r#5Q zFP`ML1xKD>elpY4>CiM$YHG!`skcx(l9L(9(?2l7h#PV^csvxIF5&da^6Z1|`eTz< z6=syh#en+HlU(D3Nb2Lx|;mv3mnu5ebV9KZ21O|uPqJJh_v3;rL$Uj-)sfhH5Ua}Xf1 z|94_U(~gpoQv1e0nuLUi$mHjrFx#^b0!iEGGUEvn8*OL+IU$9p$KGoOc{O$Albu8g zVpEBSkK#;iyqQi{S3yFbbh2)IA77*;G+b*2O^J)6*Ol4%f_4vI>-{6^AI?HlWK`W( ziZAz0yku)vyaihZ93BV4N6ma*GO`7tMC8tSKB<5H{ti1qC$h2l_e4#zxF)u$Z!40L zmd>M7>@FB8@40-{*@I9nEu((EzeBw5_J%D!163+&6aYXf19zSscd@5SxEfY&m+FWe+WF0Z}W{G=J4ZQmv?z3Hi5#FQLG z92FKul{C0@mZ(AXGllp1owXdO!z$3&Tvu*d!Z=f=E8L+AD!KS@SX;L(@1loKU4GcN zCqy3q-CnG4gYsh-mit~@&$X^dp}-cN+%k`Fg8eH~)UD=dU0RY2iD#h$+4tX__FK~9 z@$+X}j$KzYyUi(@$&!6Y=cno;8~u<^<;p_?!OuCo`5R`UCLG+bj;0fhVpPkLkG4nI z2TcdR505<)v{vQ4eTox$2Y6^a*3p8C2k}h{$zDr55<7o-gg54C1 z>Jjl=&GD-BsZ=(K@YK1-H-F>43j@Dn(Q8#MbMyR*jYZwS@=a4Y)2obcb$u8|7G&ge{&L&jnnU21x5cy0 z3j$G4Df5xKBxs6uhzbl!Wns5a#38l=AuQ4%|<(cTDA2* z@w|J}PKJHOgpt~<-{|9PCn&i4UEt&xtH$-iKnY_`TAvCehq<6iJTQMC5S%W)&JWa}Sy(x6ErL%0~2 zxNFZ}2Wp#0;=+Pe2DF=PI?p2%$cx~Ctf=Grv}2thgTPk6YrgW<#yavNZzN^yCs#<) zv7EC8-T^@yQ}*y_t_XTwtCWlew@T0VPKV9M7M;ejp7E9nnPp~}C)Y+V+lc>r94V=U zr5zacC-wsQ3}R4hARRl^)AK-ewZZcc*<{YeBSqLLv+C#b)PcP{$9fhBw5mVf`gL$J z68I4Mw|&+SV`l5xK@+)jhwN21u302Ldk`Pe zW~xDqfh5`R-p3dqh0F%9Bv(vsLa6%A_eu&)+NwD!A{g`P-waAPUem*nW+28y9Ir&f|8%ub8=|50wk1 z_WZDgChGTVb*w_e#=7k6FJ5klfNgl(ZV7^kgF{mNRr-mlDiQAa_`PN@_DXvIZ9#!| zx)}ybn!M+}!_mXd$|@ODQBeUpGDk+VO<_yt*B86;kyNAA4s)RPMT%D+$KwSbc4)`p z#>cdTc%9+ri)`H7@b#={!XnHajIN`@Lz2xDdIK=*+yP7$0ytfZiT?rUU5303y&2Aj zlsgS-co~gcM>QyxpKJ?ocM|88k;p58p_<6Si1%RP= zL{+#+6UBNki4-(CN#&~hZg_F%&QhfL4q(*cIz3Iexq9GzW zj8E}I+`>Ql{@Q!@&n(=alGsFWTnZT4_z%7yDSBvOr%=R+EsAn`GtMLIgAyKkH~h2J9qvINjg zWO19AvxO-4iR+#`x2twZX$h&^;p7{aB_r`s+?{O+*W7`Y)SgftCo3g=+8XQ^+9HV^ zJcg|Nsr6Q48w-+;WnbiZx3dO0bu12>Z54}K+jeWoykxt)`l_3vsAuz)Q}9M2dsb_q zUgd`f65RZ~$MbC_R5QwXhxKKQ93gt1^5fb7y4Zp-fqxbv=3_|6~BO z0`^k8UXd^?E>*eV_=+~Wh14Fz3*JJPsEmuG%oi}cRZ)xOX zkIEe>PXMrjId)_tZhkJRRH7t+6mt+XC?b7CrXl7ziKgU3zvu$MP2e{OpyQZs2|!sO zAe<^6ltZ0|NQz^nl+KbZ|6rx6gkN@dym78GQZd=B{Ry+-k9&D)B-R5E+WaOIWL)&L zOHnhcq)+lHX12*#8OdCBL0WG#*pEtl^&;lT^_o>paKm}zUyS{Hq)CDM?tphL+16D# zD!-7F8cwDVV{<3@y+EbNTr!85La5FI)ePf!O}9O*+?0EqVU*MlUB9VPlpREBOp07I zBY%!{xxL0O$G1Fw*D$D@#PSec?oPL-5x+)1fbWfo9g2%areD*J)n6xXlT!ILT0UdMt*BD3Mt;WbCg!8|&T2E!)BfBnl{+Yx2!xEzUA?$Of7;4yLDS zgM-fses<9draJ~zV!y<1c_EpbnH(iM$26KNqNN(!n-uYK-SEldv*UwdtZ&c5u$!ME zhmwCGCij!=n8`;$W!EI;&AmKCTQTD5S4u;Ieym|_hUYU`bHdmcN==C8aR*%$ zuoNVbiLLCB9}x6Cnm%KMB4Jh7A@f;&^#DD9OAoGcRkJqn+@dceq&)TM9||K$w$MDs zTyl*3D8Vc8fLwM#e#*i(Y=d+C|^)PpOoy#Cjt-@-PZglGS*HzUe>-RRAy-?y; zR_>zu6e|<^S46JEXY>pnKdySfeZ7otBmo<0ZLM|2S?%k7FChUhDDLg;4Vz7SQe~YM zJE}F%UEDV#Ucc^BPE|-Z`Z8*l8^6eJww2XQLg>NWdBvc#_OM;YQ}(A{&$yb#Prg&*=?U2Ji~2Sjrk0B;9#UOx70riA!42E%?cSE# zw)gDE^)%~JJ<=7h@bp}{ludr#<-HU{mK>{HPj3ADNs9Lu}q1=LpEmw8+?OOyz*I#U6->9dFnZ#s8iG*oO@;&We_CfhT zbS?B8@Id?knJXSn#)=c(ZB${T7HVOT6%#V_vpGh(0x7T9P14$087rN$18)uFqq2C+ zv)Z&i?)s(fGJ>b>A|7j(#~5p42_sa+@cg~~QBVJZ2qY#8fwnO%Q>^tyYn|fRTIuio zMrAd|vum<^;yV>q_uDJFEl`OzXS3pao8mS0LHh{&CrX_|`0=HX8oZ!J0~Y#Ky`gti zVU0b_Bg_1?19DNfDtI{oIlTr?hc6&xS5mazBzVFA)!r_;q#{2rIhzoQF zrn5WCBt52cz0%OH&T^waO>44LUDipJ9qGvyuQN`aYd`1Z4vn-1Kl~OKiNfe`A_Ll4 z%Dt5vWPaYFe%+}VM1td7RR*9Uw%mb{x zz7ICC3D_+MSk~@Omwc}3S@WsA-1+E?jdSnPF=Sd7^vC0L!5;t>6(h-vDMRV6NaMPh z_tDbSr}GVBuOngc^C96u`f#T=eyJ`CWRUAp##}Md)Rgo0yCz^et9rFdF9adH3&>B! z>$+J&R%b}D9PxurmGJse^u@eBi=c$diV8mXYTf8SNqa7)6a$WI!!@0)yDM4Dp=0v4FBH zULh9u$k|%jX2o=aV@CRS+>%+gx2G#iQ5vS?3C75bD}G>dUuQ zj#Yc)>1prEm{~`q)t7jru0xhl$O?;iuo{=|G0q3NXYcE)j){b^Q0{-Poq{ZYv=Og;&&!<>tCHy}5?| z+}ovldxqiZ!uNQJn@P6aRg^S_A zqF3mm;y;iIT-YbQP_AQ$>W+fmvhR3Vw}-bb=uN%K|R-)Kla{@(M7_M<}5h|(`> z*@cR9{n@ei*qyj`hy?PsWh?2ope|9H6dlGdN$zF+l4pe&G70m;+-DH0FM>i7=5bX- z@Q*~^)k>3CGS48wFL_rQ^OUIUQCO#~tQK^y4#L8h&Rydx8qGHjFpMtG^Xox*x^cI< zL&Csm1KYgH-HoTsWTAJl{F&yb3U;@{AC@m;7&etX5HP$H(6O^|_}M64w0eu+1a|#o zZIG*=Q2V+ie1#tNGg3AC{`;0{Fxw<&*H`~~;!^iw#cf;0at8mNz4Bmcm%Uo4qhfnv zxF6IwkWg?<>&dn(yK_3ioEC&pYA9{~-nHTpg- zxQpQ|pTo-Wk9Sk$)T&Q=EC)J+>ho#OHM65y{&E2ve{|LoJy28rh+oTOQJa%f+pE-* zP@Jn@mr0}kxo5biENuFKS9i6zNq5ccq=$Z-Mcku+>&8xr(?-NVuSD8F-m9|Pd|Kic zZk@9;&gaM1tI0Ax4(v(~Bu=vr!e!6eFo-DD>hHZcdMgH7LE%nNPSUJ7MsN3ac;Bo$ zu)Fh8&Cp) zd4cb+bwO08LSn?()6%rhflG>TR~;@c7i>DpNng;#%Ute0xr}VQNucZLRIYAidHCBKZO9Uej+~%Yx9gic__JbgfKD68|$b{m#xqul2zUK!E$GY#Wr!=#*Oy2~~VH zZo%@;%+yT55cts{MNVYpLYf|k_i|NYUnFDAInW(us~4Y>Bbkn?jU?R*rH8*Tu);V2mi`VmP^j<#MP#iNdg|888r#0`i926&N zrBq15;B&nc1|ruUA1?(ie1#NbWzRaDwWi^%VNYkj?haKhz4j*EtERw_Wu@NV%a`)if86^3cu!%4>toI)GM@^g;t95N^q0OfuSv^hqYS-Osl2E1H9=Le(L5@3)AbpgX zpZ)i!c=iXOI8Q|OrQckI#pc(X<#?>0tm`%$u6j1sY4|lZ{Akn3p@+$->0`cuRob>M z6@T(Mn`w2$xDi32=1K|``gpKKw({+1eAC@p+x|o%jiaMhzs3VEw{X(SR=g0GanHk^ zi9@BQ{Y;z6?U^~K3~Zj;L4lDWcJ}0HW^ZER8_xQZvsgv?8NW93MGJT5ee+OEV1RF^k&MMe;egUy zlG^pckFZVAwq&s``r&5BnSi@!*Lqh|9~WSVwK7kYB!!2R1jxY$L~Wn`HpQz9^YAD9 z^fpgp5zb;2*4LDKH*(mUI-lS|KoQ7~GK=2D#-9^U>G2>=(1dSN^Y2+D-NhQ_?t2T2 zK>WGgROeE2Xv3Tz*o4DVUmmZl8l$ilblpBTG=9sEJN;ambhk`)WjeU``j8(ht`rHv z<-QXb7Gf0E#6Z|pdTye8)*&357+z&aCP|OqShwP~po`<3H{k?LD% z+^g?k8(dwn?Vjcbp=pG$1>R@omMC`o=6YC7k)ZeFwC@AX0Zui=%M)LO`s+K-jCJ@} z_FQUD>uai(p@3w(1~V0-wUMhRLn5KFMSPA$ZSdSR&RyOt`>d}GuT)~ASffvS zPrf0$W`c66qGNX1W;~B=MQkp8crX2Uwa0tBLyY6zE5E`FtGsK@Usj3o7GW*i4AM1t ziqHP*AH-Hf$aB}bkHR1BWdFACFEKgvYk2G-EkUl|9tjl*y^%oo2Ml5uxY93iDest~ zZtzG)qG4qROOg;EEk{$lI~g14$?2u`!h}|~YsKaY($Cbg7QuN6qJ-Z}A~!wL$O)I< zaB0p{_(}ibN3K|8{(uOh;Ev;-GKku>{ic?3==(o$6kw-4$ytUqlaYgVi}v6)bn@*x zWmZ#>j_~59wD;B4(NQv}x|N;S&oP@%oZ5TTmi^?Q>4PU2xw_K!CVoS!ZTINPls10$apkL{@nSX&h7T(bM1Y@DRO)M<$K4? z`KnwxNMR=wI^wYXuuelJJcveNI-9F>EX=kp%RhULjZtjqGQTcmikfrcYm6-MOQw&70_Lw_ zpV4l3Ag9|a&%Q=@^#Nn@&?0!+#Cg?j7~)_kK9}; zH3Z|Zr=K?eXx+tUk7mFq$J=C1BR_D8l#JYE>y4UE#$s!O;f!;$t|3{^2l+&r=fh*P zLE;2LXLJT{1L-dUxl)|N&a_re5{@wekK@aJjx3ayV zlj`iG4WV1JytAF+8@ti^&ZCv z<*MxOFoerH#D1@S`UXk3KYH6`+<7Z-AxJ4Tt%Y6<=gFHVv{Jc0X9kKMluu>he8daW zS?jP_`!rm{29sQ55prm;PKlagfjv%JA&4kW5-6U;R<%INoovmY!I8Icuq+6ECMTIoBt~^1W(rlO@j=T)H_*L-_Aq z#%*kfDVB%D1~E}|eygSkqQNT(Gb>u{U!H<)l0UjXxgSKC8?0A)AEAOU5|7X6o)^iP z_|c$rHXbIbFqh-FNr>ylFhoc2s1h3Bh4n%ja&mR?y03b+V(Q%H`_xK3x~!~$@}-HP z>gO;3p=ckG5j(~U>T%9>Bu@r?F3=1)-9=a8xbubOFw`$D@tfGbrdhGG*7n3k*%H-c zy+`MxvpCb@X(V5fNU@yMjZK^nCC16PGe7$jFg>OxhV(cscuPj61K|8QkEEbn7a#@JO0CdJ19m^5Z zA6`n&XZg?!AF1S1gQ)rWWmVD0Q^ICxrQgwR*=tEhxYpG`N9WQzgjcJO-i@lzxGMka zXBlJAkwLzTiPDlH7tCwu#)BYeR$`fyq%HuPdZIK+cm0bFa>hX`WE$j_W`~39JQ`%} zvgIwgXfyd=G0iWe4QT{!Q+&C``F(Dp(c2vlVmBX9hxY63Tt(=H^H((`4!=B%xqTeU5H;@d?a@{rWeiVfBC!<>5-tP;wG=}3 z`V1&Y0`{8Tihodp7z@-@Sn2$Cmei1QggUo^bd`lHJ^v+BpuQ)wkc`j0i$6rBq5S$r zOEn_Cn;(I1r+k6Oa?W>9JK*la&QEq>{dd=neoXL{rhF&vq6jE8E0~6tA|-oIG9~J} z?vxyV?;n4H|2vEXn_ZB&Y_#eH+qrz-8wK2u^RB?SUbMB98MdjOanQ+|vtF zw~_jhL@$1nldvc^9KWnr7QK3Ug>hu}5jtJ<%hgs$zaqlSfWOksJDS$^8VwM2ZS&U%(#hS*?}lG+ z!m3L-0xY2=`yJGCK?dFsDhAcdye4Tv(~fPR7o^_j?D^(hN8hcY zYJ6%z4#iLNFLn$cKoNMczbZC$3)x!qRU4YwQ<#X*wz_coZ~00h>qtS4;cq)rB@R(Z z;FjGePL#iYmj-oG3p0Hcx=Dk0J$Wa9)@?k)VXg^KurhsyDbxoJ(yMG=3@dR*Qu0{> z0s+F!u_EeCxaE60O`BMMw}`=_Y6y}oG zb5bCHj9oL?eIb}LIDIUsg0qrhEnX6bcn~rexR;`f(6@RFl2qG#VD2?YUFek)dJ)@A2o;u(FgPC62lRqL&!ME ze-jq;dg4Cv2Gk!_Vx#e7_)e@DSlURIbfonCA3tvYT4(_*8o$$prOxQidKj2L1K3f2 zf*7v4gUY4>a2J9+ojxg%)kv-?DD6K+r?ySsg+1~btAGa7;29ryf8(m%oHp4io(bG? zvi_^0hGmVfZ{Ya3esy4Jy8DXo4T8p42lfqZ%!x7P1;o#o23ut~eZroMl+{m=+Lon9 z4fz_^d?Uz72O%=u+eqeDHlJ!=c1gfbVDM`5Zer1^Hn}>NjpyJbC;J?90}YB7PtF)4 zhFXFYL!Q(O3I;vqKS_vfWvZWuSryyQ)R_-p8@&3v;CQzP1FzlJ2Ted``rcMy`4c!b z>R<=46+e>s3FvVUs;j4Ef(Gz|C5Vwr!e{y=6Ae@VJAA5H3*Cb-aMsn&acav;{`Mn>b%1F-VY zK)?gc(t${fZ~8l{)SLhO=v)rQXi5LJO3;8wOv1yp4R9zH_P*KIUiWwH!(s3X`llDx zHa01LZq|Ts4^^_>e-*3Gno+pIRPoqBt5k3fCOwjlEC8a4R4S&BsXp0(i-3d;( z1l$X!+b{BT&UQRS;n#a*X~4nw0h9am`0u628Cp~!t91NUghTW! z)(rkT@P56x(6g)~BWk*>Up7Dz`7Ra22kXz@;M|Cz@}TT3&`1VS8XpUs;{ngTuX>^a zc<#rz3wD2(VOSn||0Eh+a2j?FxflEE$tq}(sUVa6K-Ev;0C9+IH5%nuOw?FIeOpc%t~zXc|VOayR~ zCak|#RY*qycQ|++h{H86DQS)sDuu#?d&f4&wa$wJiWHXk`*Q&=NhFV=d#{Edq1Rnk zAPc5-;vlT*{o9whxCIWbub6}TpLjAxvJMkf34$Wm;g3ba%%NMsdhQLJhK+Y!PJiVR zN(#HC6R;*7hPm7(|0{(}CU6}?ncwNXUt8svFf;;bU+y&})X)s@hJ$km93wfx$6F4l z{Plml31sj%NWs574a5gx1d%~*-)XYrIrQ&^|Nd%>WESSKKz?G%KmYixlKx!j?|-|j zf#}Q5_iKdz*9HFddC4V^KCq$@`o}f+W1xQBwK zJ!w$$cb)%P;oq){E+r6D(T{*yeXI&KWKaSD+O2dFIGRAhNT-ZA@wdnQKfVK`{gnu4 zpu1I3z!&k6H?H5Vy4Y#`y+i+p)PBj{6Pc4T;@)AsGx~oN-95xgr-*x0|Ar*~*RTE( zlHGg%oBoqO4_)2=ulJ!_m|$nEH{fvF=2^riBvg%z{PF#asqt;vdAFKxg`9q}}a+F$D4nA5f%=&LWbnA^!R{@ZN5~VBP;PDs>VyTV z|Ibzcy8^&5hPrZ2g#YUn|FvhqehfqGM=u&Kx&O2uW9YyM7;YO<{r~?QSbZH?5Uyy7 z;oo5RKR5NCovJ_p_T9$9I_v-MaS`_yPzZDgw16%o{J-qP|MB_k5ODWLjxMDC=^-UG z5nEOxx~={H*rES*e1@gL-Fpd(g#CZc%dba=7Jx(EmEXBw`X42+aTDCV7!9rLe-x?) zqBLQ2$??wr@nrwpYQPa8xO=*&s9XO@s9kIb6}9P9L-8La;RWtqfk0mVKMK{HEFiE@ zH}e0Gd<7md7_s9C$nXteSI2-S0(8YA`kk*XP8?nrSqwaQS91mWE`?@2%vxVyK|wv% zE?_^Nt+e^h9QDlo_nk>jfjWS6I|(CqmjCuZ{Okc>Sp6T&)caXPMvI@>-AN zYG~@@=xEKG>qyT7FGmD8nas+`U12fTpn4s_NJ*|^kWh#^DlQ?>d>a)sEQd=2RTifr zZW04}(hc1vELf5qrPR?YihnO_dLP1>S*0(f{*y>Y2wLG4B#gMJ4iqDH_w~)#miM`h zn_#$3y=k$i83L0Z9Me_$t?g;$8`&<#Sl~XYSv&Kkv z%6hrpRL{6gt-foxbNIzVvuD4z1NSLCR>gBGys+Xuo!zq#H4&u3e?=MarDL+o!6OLTrb*J$=^0XDrn2?}@Fb zQ4=`zu^opMjAGbX)pt9klF3bZ4W@}O|T(GK`G9tFj*0wNJpM+ehDj4tVz1Yk?mP0-#Y)7rB%@SD?jBUJk-+ z&~AUepRj)bAe@e9did&l2jXvO z000yvC%`dxMMThMkphcm9laG9D*y))@;oqK1<7m_rAdrnC;U7_((%)BcmGc)s@FOY?EHpqaj-aHt#1cBg>u_C=b zONDOS3vew0+4m+BL%;~z2xg(*yeI;+wfpTiurQ*@L9}`gF=s=y_v?1!SUf+>!oq?{ z>Wuz+F9i6DueU?cL{H~~-YhtRKK1K$c?s-eQb4JFQQdsC4LV&z+3rBn%fZkD(OG80 zR9=f7(2hUgEyYwkcBhl(@T0`l?OEs>M8q))ga?$R=;?$Mzu7EHaKl1ej82U+@a0Ocbug||XN7Wg30QJV* z51w~W*l^zW-cke~;FGKJSOJRB3kV5}u-$}RF432wesR!2U@{2fmTm|v!=|h`%D)dJ zBQYyCw|uVDfK<;Hi5s4z8l+^dOPd7!MZv+ruY8+eSAecE6MidbaV3l@Jiqq}ut4*4 zfttveQLsWsS9Eg*h`w2V4J?Q7| zoWy3rpatmd9vB#qKb0o(Th9pjppq7~v}avV^s*t;rI(6gq5f=>OXJBCKwyATNo2GN zb}<37nAefyWAruvA&o0H(onoN1YiU1T`3*L@J=i$fn;A$2F`)?qV7igw!4Sk^+94Y z)JiJ4@>V?pR6-EIXSuTE7AQ3GWbcCxY!E3mGQEzFe*buW0U>49lH9foUbgg~YLaX1 z8kb@0pXT%0srL-`%~e3XMQ$ucm>dj1knK}47OAu|4z(-fTuzK@w3fkuts!rM_#Tq! zKHx&GX)o_k6{CRgmY%%BvC5;eW$aoMm5&*#Lr=vw_iu^A#xo9WrQ<5aK+H{ZrG%XB zBkk7jHc?lubv^}sY#9!$d)h|c+X6Cf*ZA@K$aBgdoSnO)esz7)Tzq`fv^#Xt?DOL2 z;?SXHr~Evv!s!Hoffae<+5S&ercR;~?S`XaC9LYqUXT*SokGXJU#yDL)dR@HA4{7I zoFiep-hb<=+%$*?DKb}TISx5TXmu3-G?=78@AQQTFsNASSK;(M{>=R7-3v30R(86w z3~|z(x-BmAE6{CpCDeR|rzE@+wk`nVV({&hcG8`$@p|VLS3*JnYO-3l^+{=-@L7-JX}5}B z;2RzG5GzR+$*%-}lIaeS#G?8%(2e6Pp(M|NuhFqJB}u6XAZWfi>p@A-xt%gULX)jV z3Nx+M2U?0k%X-GUDAq|z=?8mF%o2JOC3HcvMn<*0`#gw1To^zpQDQ&Gp)&`h9`)J_ zV0gf@2(F0sTuqdg)?l1AY4fXwF#R!H&9>eS8xm4$X4A_OTTz6B6lN}Vs>8yNV}&64&tEAKApI8cofErfA&7#!AuZDBF z-%5!i$Pvg;r;uVFx+b z8`2_Sj+}+-i~M`xVkD7~-Uu|Pt17&bd7bVRlJG+E49wFBpl5&Q{dlp}V5EQ^e%d)s zV66eqvc#;!JO^kH|4k#Q&KFV?l-ve#1seh3;z>}Vms}Ciw=TiNw>K?|PRA1O0xhFO z54sdtQjS_s2pAtyH8YO8htY)ICHb;*iphb((3AHumFmUPsR6m%^4l~((2+#)_~ufz zuEX1qYw!|d>A^VBqzD0(SoPQ=rwZiCMy_LtO=86k*V^aK50?|0FPWGV7&l=_RB^*- zH}qSc1wEDyNZ-R8RK<(sl7AQzy@bbFPHTQuUCeA5yns+`)Gb z;(93dfPL|Xh%PaK*Spsb-ZU?LHmO;bwu-7lwvchs&9rpAdSu1$m0)>~M#ROcPf#0E zIFRs03IqOn5^F;`W|#!cQTCok(7Tn6?Z#DM9ksSIx&zkq*pNMaz^H%oX1NDRrWtt)BQM1O zshF6qGoZimv>y6QWi71e?^J3D<~w*a@wa9%qB!zUkJPzqN~QC(UJ=lV3R_D;a)Fl{ z`5kvgBLA~_d)6FqU2JG?J~=>X0@)j4f!t5yG8q;IXiZn^bUVa~xO${xpL1VI%7HRt z+Bt<63auPO?|$cTfs%xhA*VtVf@AIe&@Etd>BTt_)P4udhjUR77Wmp38-Fd!o`ooIQLJTR=1Grm3bI~4KMj$D>3MsLgu$v z^_fW_z0unMkR~00=OT?^`r&r>5gM45AmT`2i`YRiziyH*sV~4N=}n0bI8AJAiZ|45 z(0~x^{#Ep<>E{qSFV?3FT{mgcX8v(4j{yw+nEMv>zg^4pFo^D@S+p4W*=g3q0!w(d z5`={2ZEd)iKY#w0UOBmFj|G2~3VROJAto3@ZRX<5(yL9aW~qGXFs4ayWOi&SdStgW zrw&SxSrA;b9YK>Npye6IZ50;48S>gYX12O^fL-X_!d$5Cofpu1Nwxfa?rO&!)4Ilc zX+x!Oulf48IMn{WQTVM$=;=!?RU~|wyMqx* zw&*72bB$~hI(?U!Y;v!CE-4F(?9oy zgcrpWv0r)(nGj@8{o$?sy+^S;vj z)RS0=H`SZJBn8~%sR$W(El)?uB^}_P+hkVyESQFDA>ki1HWm>Rphi{y`^4?x1%My~ z>Juj{R0n1+Y!CGXrP;Q~)X)XG5^CPdzZs)UsFru%Th@eS2iw%$ptQCdPN~*vYAfl0 z2Q*j03*>jS_~qHOQT1dj6^b=q#{DOiQx`n;oLcSEr8=a;)35elofLI1qzB>OlJji9 zvluadiB01V2^(AmezVjSfqi=teaQ#LFPOSu9>}W<8T~h7_9!iW(ql%KS#3@sBct#U zCNt7A)b1pOtMLM4=f&=MNm{NYG)6yu{V22-J)n=!5uZW7%ow>rCNX#5Mf$7e(IlY~ zvUahttb~TUSWnS%v3B4M6%C&hpDca&Ayz0_fNi|of+r8N{uJhb?nm5q_Wqqp9KH7R zSpfNQWG1A&b0M23I^r9(s>SmYnB0<0{_1zFkwn*nD{}OwcT{aNACqt!KZ9Bm&PnX| zyi7Qw#M&kBUe@DJ4TFkPk;_NO{opcu_ScsPSO%dr3VYy{!#L zOmEcvznT!Gs(N5+Q!Vz0s|eP>88AYUuC<9~K?GWJ78dmx;y>G$WYWQ-#maB7YZ9aR zq-CC{&< znL|97o`8Nc`a!mc_=0^S+K3Q;WsCxZ1UZedaj&TpLt>}&eYTSe&MWfmcpdAiFN~53 zxA<$;$?xb9<3c1MvMxe*F`)jp9ulqjv(i*31;!BWq%o#tSTsobKi_F(G@JWmk0a_H1DHg zQ;kgiY4`aZgIJ}Z5{jM4c(Yui6K%dSQ)kCE&Hf^7$>8&?)G{V{F!AU5k1o&LoFN^g zMUTgnRE+K~WrO9DAI&o3#y>!+q(u@c6PYikpZ=NEG)mF54KFT==zB0$PBfZ>HGXX8E%Hl-t959yyuOQ949^Q3v zyYEChRGB33K{*e^f7|+Cx%>59j5H@@EJB}`>ng92{DoeKwnTKy+lqdHXE2!Y{Z)CXr?@0_(EhTB+ z24}LgHel@<7I>?1{VtzljIl$-MS5eW^5ytnw%nW+sdYYGhvZ`>5qq1N5bC$kI)VSLHZK>Q)vZQ}Rx6$-82zFRn0 z^>CGCbMu}6s}f>QU4+p_kTJzwGmjkD@YE$3YZsT;r;+bqI_R6w3gHVjT^7|0h2DqD z1?#-LkjJaOfO1AC^Fg3|snK*bmIi&J>_dQgq?rO}zmtduU4}F35LI=eS)IjyCiDqj zhOYt|jS$4KB5;@dp?HQ41NLRi%W)&zcyezIgWh?K1tq9<5D&UBdwxOb@!!CXKhU2A zLWR`F_4gk@2HW8fQ!9M}SzIP<>`aYD(ohfS2>delmkGIW5L+w&lSO5%t9p}@X7IyM zR@$e@AL&hw58&Bo0}T#6oK2O{~q=gpp~<~d}HC7`-2 zx<(QQ@p+Fc6-5^PRh;P=s8nW<)2XC3YLUooCeZKlK$D~QTDDH=uYJ;e0h!GM*bgfQ zN5pillXJ(bdttV->Bl~MpD{eHI!9sp`LLrb`h`&?ezG_Bd=~aY8UYN_O+szH-}Scc zK8Z!{9YF$_*%l;DVlz4EyMwf;HDsV7C)V{=c*r*hrLJ2qe(z8SLXPb}5y%zI;gApl zAjK0LHwFyUeS?#sC~clNbmVmB50R|DEG|0}39v4EfhI*|&KHKNq|oP7>TPmX5dz_@ z0LoFqqv8@oae?(Db$0R6;zIZt9PwcC()&jf^{)&WsPL}tiJ&@y-t?i@X(0&y19&;>#9^V)B1~HYNfVmMDxZu23B_0MrNdD@)pwMM4vS^DCg`3T;^?>8= z;dsm)&_MzD(0tM-F|$cKgZ{6LgFxj6)y`zt*meeds7krBhZQ(;xXZ+cC6GmS7O{Yu)P_iMVf{b!uXy4)1t@X z_XjV7U-#dgZdIgTlBvNBUMFk;=#&CpsjqM^FDMvZ=W;+}k;>#9xIqt#5|`-?P?Uez zw6!h?!Q;6J6_e+@s?R_TE%|Z>2mhul7MUd&?fHft{nb~Lg|bh`x9HZ5buDoQpr$}Fh#Z{EpX^6Nd?ZTyAzPd)+USx>YE)<`Xnn^enu@Wx^Rs#BLa< zFU*em1PK{J8E7$RT?oMCMnk%DF&5wPpS zG}Mp)JIu2`QyPQaV+-dlJ$JC@Lr*rGy|LNOyND9ReyUA}A_|q_iL*3WCzoAl>nvH;QZR zcR$B-d_TS)-;eLtUV9y`={@gxU1yAQjB%>mv6V(J)x4YacWX;^p50}(86H|A3(G|X zN3}kX5tLLB{t8{YPGY_v{>)nMbvamH%lB?77mHXrj!9a0LaPiGZx@8eQ0XX2hJGND zI@=;{T^`&C9Ib(s%b;i6JU?71v$y*B004UB$29!d%RG+VYMiF^>K~(s{!DDGu3#_s zf4Tjm@OPc`n|(p6V)A1~dur#qQwMVjPU_hnPHv`>hRp9>zW6sYI~iK&Hf9b01!l%T zD+Hdbww1(v1I%X5xu4%Gv)Pla1JZqiMq_<URyc?#KDS6K|0gDDEA@=TK z#osdSv~ufea;7ci;LipLGrqGZ^7}T;DYvCYo!z?zup}-YWyveviaEjCju+(DjUfGn-|OOjB#o#daQEmbp_d7&_1cf zl8;O}+J^b?k~G={sZbyep~7V% zdc0Fuxb&g100yVghaJS+q;g~$kr(I3&>WXma0dlgT)yL4gU~6)Ev_w$u-oN7?;|9R z8WEm~q18`Bl~_dLs6^$Y`g^rYF)F@{qPElmPTf*ec}t_rKeK`E*VX*q1Q>*j_8cs- zDj58#aq$7FNtzMIh&3NrfSc3#U8Cz_^jhe5!l<7=qBD@yK7ar{;@HN6R zzXVoRwr62DlkFq7)~_FIU-9C--0%R~M?Y6wZ|U0oLk$VM(t=1B1iWk3Mv5RQu?V0==cQzB$-g@n zui_rc%(|QaYpCNbP{3!rsC8VO{4v`}IU89%>iDGG2W}^^Z`ZBXJ)RgYJs2VORZUq- zd#gbBYYPgQi=R<(Bw1E^&I-q%Zc@)VK-0w60n^8Z&uTZ& zpMs-kghIr3mMp55Vw7w~n|47sNHk=$RFTSMzV(4u6_pEf)&;;dp4=s<;&exFa5?i+ zJt&`&J|2@n#ajJd=96P_N<})fab$ zy+L=z+Ng~Ga%Ul@4w7!6J_iGvo?WT-&Zy>5`gE9#v%-|}BZZP-t^OS-V98dc=Y`0w zWNz-HToX5_laFQ_BftGK!|9U*Odb`3a<9^@TtvHE?hlHS7tTw-P3z3sumFNJydDwV zp`iPAn=gxt<1CurA8dAABznSUb33(S5uYdVS|I-yrj5K$p^S{0n5yd{p@bs(*Eg*r zzHdqF*5)x+;9Qp-$7t-56*k8>an3MjXm>*F?sMiftzc6{szG|$_xvN5-=itG>%Dy> zH`C949y$53QQ84S47)JK8~-R&*Bn#u;#T~F7k_~xVbmtk-@}Vwx0f)32CGIw=p3TX zWnV3|(p|niWys~M=)Ad3><1Px^eP4>ZpHp9R^3CBQX4_&rEP3i67tDo^aAr(P@mn{7gN{*z> z(@JW&H@>6E@-NJAix~+vp2-Lok5VXP#@r{_WS6WX;|Y19YmV^oKe6{vZgE!moa}I? z8tsS^OQAHw$&m_`iz^>%=Tb2UTbkww72-)v`b@m}oKraR`XldOOSRYX+Xf<&WvsK8 zj31(!p$=Y_>#aMy^FJxpU?8Owe0vm-C!r@TU7@O({}&I#OEJgzhp0^`#knbl47(QH@G;SDW5e?g3GYxk z`sk=4183GGPP{zqJGk6qY|SsFoI9-c9G?gq zB?z=~J9?_3YARaG$>U&GEjf3#2g}n$f2Q)`bku$F6RKYdGv2qKXr{ZcGSVH)*?=R! z!_VqudK$f7v?bVt+fhF_HuhGPrZ$Z)NbeEO`3N2fC&fo3EFtGUumr5E)P20~butSt zJ4jU8gT%XdXw~u%8M{R2019wn>h9(i9y*jrhrU_4Q4hj3|ZE zF&)lId-XUZBCJzdr3u5&=za}`J$y9CZj)+Q9m5xLr{2GE*eFIgJSJ5V_Z=%so(ii~ zK)^SFR6k5p+AXQHu!hBv%Mmx9rzW5PdQwx8*Xv+6bvIVei6$MU=zLFz8wr3KKKJJJw(X0+{=GNJx5P- zSVd4{VA_F!m*N9$m?NpFk@52U4HW*^Kz<SZj*=$^J{vn))HWeB(M8JU%ZuxBWGJ@z5v`+d z*)N5Wh1Z=|Mf4t z3B>5;|NmwEfA(b&T(!7-D5d)6V9{y~KT5w%3yQnE3bA)%P#7*k`l@2+%@i@ga)7&6#7=<{2I)_8g}@2S z<>cgi-cJ84lJPiL?Rl0CvjJAG*H-)O=DzpTHI4{>{U``NcEiknRG)`Y>kGEJx;iv( z&wzIXVkhQjR5PP&pj&XB>#>{ixF*t3=agOpcYX85%EOd^b4pPz3G`qHDQI;`rJ1z71)W6ZO9<$JmoTA=L(8#Lg4m^U6BwN$Vx|EVLz2W6zXKS z2d!sb07yWbm+AUz@RT>Qv;>qjNV^TqknQ`WM$RlZmg^HQD%blV#=rC0T7I165%CHW zsJrziiou4mbY$qp{H&eBp+u6cQyI~00IS08ucGuh_9xjL+wYv!yUQPe;0UMa0D!e$ zAhLPG`$k~a1IFfuY`49!HO6hQk0RBj)j%=Q4qI+VUf&%}x_I8&+>?0cHFD;ecJL9I zFajL6iw(71*t%C*i$k|~#u|}^^}b*f0ctSh_+Cz}w9<*RTMV9aB|RqZID|W)XqHdr zzW9iwjB%v~xqCo@ywiAQXJeM&PdJ`Wgh;=>_5H`|qx-_6Y%|Lx`KHJlPBrikd$ROo%mJ@Ye zYF_xg*5^u+rr*Ae7TBjxpC0s><=NfH_T6`{iohji@B$>B5oTH~pLa*6V+DqxpLxLU z@*M#rRwg^Dp)KIIJ^-}C7`$8)wWei`Zt&GGc<7Uuze@k6(;Pcew~18C&IDkUhZWU- z(%B^qCz71XVUY1qqHB1VglML)dVIakw+L+w9qha2MT>4jtJ(KPwTuq=R0A#8hDz44 zM}A%$dBtq6e|?hr<+b+Z3VAlq+PRJS0YC&h*l}xsM%Bvg4}fvHjzS;S=7hF4$+e^C z)G3XHvo1I=2T`5;LL0L;Tb9gZZpnjvSI>(v;&Z9xgKAeFxlG2 zgyxR7kni&{4prjKTRu+Ka{yNP^d3_Wyo|&UhPKjGstdtgM%6hW0LN%lmqC3Q$vlHycC6mNmV~bM`E~paq@*$=2|P!B>{r7kW8p z{I7-e1FY@~{YlCxo^)zFHU%XT=9xX{?3?j)U6XDL4*BeFO&WsCG;}p$COiXOzbos# zt(1&yrYy!;cSmbl`kq0qeA<@%d)b54$8zy~Oliq}`^Xka&?;OY{{fvoae>=SlQ-W$ z@h~3yB=zl>GxEdq^JDmYCf&tN&3Z8e5XUw`HYGumZvdfa*4Vl09GjajydnGdOUfba zI~wFor4>h4%9;&gcr^bh^`n<_lYJ4=9_fuN;Ses`rSMVsYdcOldN&{pul5k(>tnd>@ z*Q$Xei?B-XJ~=3D$~*v10fiWqPbQ^7q-9=nB~3m6Y7P1x?BUP&TG33O)h$a0S_hle z&;tVn3?q)JJe>9fe!WM05=|uM;$uelg?<2u{=C=0V5MiTq=?7G?`Z)C+!4|e{nzvDB=m)QB|>D|;HrabkWOg>+S?-)F2PEbIre zY8cI=lLdrsc}?;8k%#;!7`8w%o3y1Dod6L_tgyuN502XJAST}p8LGxM9xMBD`dMMZ zAUEg%f2TA5Mi9Dnir-%UBUe$)xq&yV6Z?iCV48KBrRo5%wG-~n_-A5K{`O-Cn~iKT zfm~d?=hY|-Ibw>}Os9i#wqTQ97zLSx0@3q*lGg{W)jOv=ye$;aFAsoiT=M1eHPS#? zXEsj+BK*_glmvm%ntxC93N9+CuXC?XF? zH{^oWRJ`OSQp^Lk885$qBO(je^jGBugF3GK-CU15EiBi3K}ONVp0*4Hi|3sWA;!8G zEh!#72T0zgmeotJOmRZ7t+AKM_k=X>Gp}k%TWNc7nVqfYqtm^eWk6fP|Bh*at^RV| zYq<;~tM4fyo}{{IY#7qFrPbVdMd;XGfE}jR;+=-Edp9!}YJ$wkhR5sQgUS?sY1mBY z0ZBk0AVDkhgJo*pO<0e)nf7yvu9^|wG&!7`{zyy&a%X;AG;7YcBWlf$g?qlJM+0JR_2vrN{h*@IG43lSN{LRF1Nj5AY$Zg=OF>8jM+=8;lHR_oK=ue@G8_i|hR(t2DZ#-d-BA&J^ z*TCuTOxAd3ZUVzQM_E5=C3;#WFJBMEHnEPgA{)l`gfqV4s-z+~9L5jVTx|Do=+#ws z%7Z3`f)D#bD;5j|)KX>ixeQegYzK`S!sj12QpePbQkS>bC8|@A&6}9i^g*(vG<@@? z3=>AAcdPloP3=tmQf1J^cHeF! z?@qWm4D;1YAdGAwM**{_&ZF4;I(6OZMsHEE-4-%URnX9!ba99@9oUch73YWZt| zuz0P!Y+<>4@I>lEd5s8KMKatDw$9iLTmhG zfvc!vET2}&XP!Reh5Cc6kBp>z@HM+N978q(^z*k4tkHBR{-C%bRC32vIW+itI zD9qF@r>3WC5DX#k;utLsqzwQ1vZfKCIemHpix~Dty%27aFS4RD0sk&i?aqOpz z@%1YbgDF+`0Y2@<`c!pM`j`q5HfrspD)jPmJHTWZ0l0$Y^m(scXq)Jv++xEKhoNkO z1#N+ZwSv}4TLQmzWpchG-Xl`l#O0E3ml&(Y8z1j8i(>F#$5ufYH1&kylhL_T9)EY% zD4+1~)G?8Soj~no<)Wpt^%TBnWy|h?q>Zo9=qzrYax{S=J2%O3A}N__nO8z*G!yQ5 z{y~-@tx{ta5Xu?8{d3E#ZeaudK(4)&J{+3m^>&JCsVZm+f5dNQW)p}fL89X2y{D54 zUw^%d)a5|0Le}%<9yDoFc5Z-^4152b-5v!aC-xWiSq2F&n0>@BII^;yFgD0qEbH2&2p2yO8s5+=FlMM4Nmjg7m;yv-#cF7e)CDogPU5w zQrZ*kkzu@d0JWGARGxq(oDdf}=JTl6(21}y0d#@HLa469GCG-A>o3`9AB%r$<1et) zyeQ@ZBk5zuk@|tcQ>1{#besPhuffY8CzM5qz0P&Iqnr~b0l>3h)7SVT@KROIAEcef zRD5<9sCcd>ZPTw3vg{*6C6ZE3Q+l&al07DB>I6DeZk0aOI`D*`H;Bwb$&+MD-aVbB zS~ooM5}XGIRh1q%=2@yyKbTI&=k}$u2sd@n+lPKSn5oC@!5vH#9yHSU_Y;VL#xM-@ zlDXm!iwr+o%w)rfv{7-p9a`7lutGv5vwDlYxfXiqF1Xi1OD!?>&C@{9kNYDF`FT${9W?nr))jwB7EL+L~#de97-*{fR8Tyl1!-c)?XyFkcb73lr4 z0iE4G{PPDRCGt;9h7UdpqzP)&=~!1QmBr?&@h>A*M!PE=oF(-^-++@hmc2X9300>(-png-#6p-QgFuKX zj?Yncj7%g4HkCxQyO%VrtgZ?X{UUx~zHv>}9bm>HozA5_yg;5^E5=Cdyp7l%K9Da>g=;tm zJ%EZgkxMYN+SO~Ek}BQ*L6P2d#JZJM$($#HZ&4c8n)Pk3_=w=rCpAZwTc z!zesaKYrHsG;s~DM$M$~u2|iC*sI$$EWVb<#hx0*iaDH1b)WJCofMq#dsmFZDKX6P znf?02!(&up=)(g~2QFIGkQq?8ea#Tnx364FIAPq&Gr`hSGqk@h)_pu1ywQBOK3-3G zSJe0wxv^FQ*u}~#6}Dg>wHx9Apr?fEy`sH@uRj6NsV_XA!#r08T4~q+Y`=1HrWM8i zc3)&xqL`5F04WU6~~U zA~0Q{-<8lu$1xTjQ>9itSSr{n=$4ugpK^XG&&Hw8shXA{MUY&A&S&;yCcNkM7j#{e%6MDp^*-+ zt|femTgeq)EU1Ok!v1z=44!H`=S&@WIPVyzDy?u@^x;u+!Q9Q=g>ml^kSCVuLY-%K zx5xC+pT*8CT=$_{)*vyTM_|&RAxtgCA=0Cw%8CH0EUgEY*N@KNRXW6+tRq6un5rvlN6*kFG zSLV{S`XT=MjTd*-b4d`|1U_Ja8ynpG}@|BM#z!gj8 z13AQ^hR|BoU!_HkJ5mlXeERe^0ZHPM82imtseXXP4D7?QpC;n17~1_$_=mFU5|OaR ziQ1fh59L&z0Xb<_^<&LcGKEDI9vb@N7^&u6h2*&#N`&H<9Dt~hXpz#qoKM5F?pQ|= zR4czd6S@WnPq4?N5 zTUk?@DFV%R+fMRlFP<$9$Y&r8Akm~o<$f96>A?3>evzTmoqo`Kgq;t> zVqJ<!x7}9V}hCDEFfuH z{KNkQ$g&-5`$}DmTy6U*Q%oGF9SS$rTcchMe!8U>Xt61`Kr*_aNPtUrV)!|;fZ#US zoM^M}r@4{lvS`)=hC|^;&MMyGv<1}<0MLtf5+9%96L0a9XejwnV%}scmu_)!(luqh zbbONbteb@+U0m~z-I<3Q31uvYv5|`gQxc^V-}PKFQ;b^F(txrZoBodHcjf zC})5EE62R^`zy~|9y$`=Bw=dUgEZy^h*}iAL_)pj9FEB?+Vl<>bafUPNv*El=QU~- zmD5(e#g4`3RdquiaqW>5RaMxcr$AU$EGniGx$$&K8H7j;;K+t2sk>Eap-oo zVsJm~VN|-eX@;mJNsMSoHiSf*PNEGZ>MZK`8_SsX_@&%^- z58zyf^_wnmb`Yu<62)M|xJ8Vg+UZs;bprd32kBI^e|a1_Likgtg4B)%gQK5?$^Rwm z;>bJJvvj(TECppi;T%%NJanP z>nu^>L73JM?0>R7z6rA+H!!rg&v)tyum4%>%V#}3TQ^4xcu$sXf4K3BqD-aYnHo0U zq@3lC5|{a_7rr|U-#3D7>I?pGT~m1s5MA=<9sFQp6kIC2MFyA>_$Eod z`T9hD8RSc5(8L#zk*Q-@0=84<6%(Z6l1~{IElE z_H3?}??%N?CDbtT{%JB8Fz0a0mi5+4JMZh}B-(Ff>tXk$hyT8c7Hemz^=BmQ!qNF! zXt0F){2VJwrqCPx&sz7UxxbbLpR$Cn`TV|EDj{L8QCQ`l-_V8w;}l9{rCj{XQR-*Y ziNT)v@~jso31k}JbOS}P+z|NU&gdpq$&cenxEf$7(#2090rL+S7ITR(ObxyDIncwG~>21om)@{cg) zs-U59+Ti{cqy>vZyOTAq#SSmCjXpg(b;xN=MxFGH-Y;jYg`sO|g*>Iv^CCwlKHSu0 zsB=y*%4S5f(p)nWUjXXRIVvNiX0JvZJ=yg>^AslNDwSxcDBgYtd=Giz?uQyZY`Df+DI#9~;#PpC;OUM|hNE-IB@RF4F%_H8qs)YS$AYVv z)T6f^@l@F)XFl10*}*hKWZ1{bV)`Ss=-_e8<`Oi901-PSgL^I5=D@~|%+>q#J5B1{ z=R5Zi7`ahj&7V$aFx}R?JOLXS&%iqBT&xf}rfXMjeJzB6gi2qkBMh|GXTIEm0!+i6 zhLMX8X94^DF}3SN^Ih~G-ON3%Z1pCsXGQHw^!;@Nr9B6yKH7u+{C}F>H7D1ArVf8V zh3jUem&C`<58tJv(q-TL&y2bM|-Bg2&oX{N59MsBKF&rRcypaZO-0&nL1>BKi6 z;+B@O29`;!^z)#O(Z~)He^|N&wQ#d|!iDK4zvCyo6)qVhj{i!1_dBe^kB+>=Bw38J z)iByrZf56w4UH9NrgJxt^J5p}CU)SSGmWi)KZlZa4!BwTgfjTtZe|i{sc2O}c#oBS zsK}@SCcY$_2QaVo0tCA~T}<2FUP~SinUllDx(t3(g*ifIj%D6BIxnbx!5>z(LPiz8 z=2H|GA;lm@{_eHcHk7~AxxIi3P`j<&EVo5B6+KQ;fK>^T2V8mww7U7<*cgYNChf$~ z@#yHG{2PrSc;u|&n;dUUW4vb!LK#IiH?Z2uQzv#ABswKY51^J}C=q+9GzmVDA5f1i zEB#2)5UmVp>Nfxzdk6Y(?s58|55PRSq&KvPR>Y9}i~afa0WS63eHw681NTb;mrTkz_&IRe|8Bl-@&p2@Su598{A z&@#6h`}9dSUfp(UNEuUul~RMrR(r&(%Z7_naf|NYzjj;%mO5s@&=`vRICJ&-{a2xW z?}@G+IO#0^^~ijv4u|iFtU>SZ2z>Nt?0)ZwPxCsuW4k)lf40C#u7T0Z512&pU#_ZL z2zyL(9NhGpP+I4EqpmzZEA9`|NzGJ2c9(%N$1#xbux4=_*I!8&wTs}rSZD~L3)UZx zT6_4f1NDR1Q>mNJ;2%#$^(;RkzXacU-XmMv!_fawdHBO!6@ALCJ?H}+h|Kq3%}QXu zXB7M7S0EdWGbx0iEPj$^v~)FU1hX$f?N$jm*@F&Pa|nS|G_WtkZ4v#?4ZwvP&^p3hq5L=UBR7D;KOf7lt*AWM1I)xUSX$}8 zW|zcdZ*rYpd@9bXuAqI~YV2VhnW`kJc_aPWGthL)`b{k}H`zNg**u+%Ej(WB_g2RvV=V5{y% zMs+Oz{P-a!|9WFpwkKxLf$!|KAp$!GhWC(b;1B&?LvVO|c_94V*qQoIvsD{*jO8k` zTEuUyZq5;i}DEZq;gH3$xw zpnE6p(cJ3rkg+THb^ZdTPZhXdo60bHuj&dfSY9)IN!Y(shI;wBv}zN(FWWzcyhHdz zC1~8h9d9BF=c&9JF3LUK>FvhTe~!>KIRXF^8OK^mGE@M(h=2dP2fRrL;Z%jnV zwE7dcwwDBPgT9#U#crA3n%&m8J*cz56fMlNQn)X8|c)2AvJob=Vn5HP|2Wz z2pReqmn4dRuOnN|7g$l>CRUJ9YE>pR2uKMbzqvbq(vfP;NfN7X zFWJ{e5kIhU7F=J@up&NoXD%12e%goo18_qP{F3{C;)QOTe?8SAdjA$ChEl4e>q68u zPR$UbL)H%f9S8=-@puC)a1PerR?iPr`|5f11Njay^0NKw;(YiVCZET{|MM}>n6Cp+ zM5v_EaB|{T4XbkC`Bx3o8|*+}zGOk^?hTCbI2;xXwBaY$s+Cg{;T8~^}p14#*DWb+m<>-doTgY3`95Spe3c&`47zWKjjN-&&X3Z|?h z)(P^W;9>mGKqNqHMDb(ccn0Hn2K*5=h)6X|7HU`vT@nhKVS zuCrfx-YygKViWZ{@!1H`myjQCU_(5WS(bcZD3=F?EHS}(0bi`oHOY!^`~dG|c$h=q zDwl5ehK3iLb_LCiEL?9e3^4y&GWgS;GZ`DNj=j~>mJ#*$UjNS1yZB5PN}u{5uH6Op z&fS@wCs$rDkpAr3dkZd;UXlh-tdv`plWN0H2*Zx&p`_x{f)4;u^C2 z)%v%z_w2E*Y}?3&ma)yP`&yC@253uY-@hevV3$9u1QR&LmlQ9U4Zqk!F#tQB$HylYB+hV)aFZs9U3NL(gQ?r{1V?^ZCSp2&HnR#S=PNdwvGY0 zYkNykxb_{dO4|SY=&v*3i}&wiXIB6Fg(592MFw}%W8)jQe4yuotPRpIqw8De+~ee!FRB14c_`ZzR24q>TEiD<*cU)F4{D{KmG7ido1A4+AM!| zynXcJ_fTNMP-Ph*J{nj+d)qWv0%O-J!6y{744$vRPijN#e~Na_qcfh9(z1$?*K;zJ zbAjiRe#`}7Oo-)(ytxR>54Kh&L*=1>y*9UFH}K{MxTW?UxmliVX%_s6d2k;39e3G@DX@?Hdy}ibY2x!j-OX1+rMJy&>2S%v^fG@7___F zE7=EaGHzuMNWuKq({;N022i*jO(0&ba7wPb|GYQRp1v{jC6ZS5wJO#RShD_o87Q-f zar7HC;JWD4F4EfrO*$slz>%cJ-wgT#eJqKXzrR(%X@sF|3n{O^9ztt1bb3SZK>@L= z$P7ppUeT=no8L)*tRNbD^FGqI0&rfFR1G27eAJS>2Fy!4VESjW*HOkrKVM2O?!ffu z0B{kTrcL z|Msgxk~5$c$MA+l7zHh0+sRgk$J$IL7^T@__Mwa_fWn!ihwQexR2A6L^_h>}uiqa#_i-?L4#`dA8&w(;h{_3&Y4Z4niVPykPqd?m7 z)pQeS2qB$In?O?rKxv3+=vFE+By{7ZSoA`Sp#yP=v*dhb4Y-z0#+8pCMXb8eZ!92Z z7~4T1_LS89>&w5qCZz!1v4-O4j2yN^5c~z#?_j!pcP>k_OC+pTMd08$k{CCqLj&$gK5T zl%Vj>0xf{1229?0`TGbK0hcL)txLz+knyO){mj0fF(?WTZPF z;edTV(AhKJmRqdBQsb;40dnnWx#i%QZ-1qU1#ECc?qN^O9~}|Z9A`X|bYCE5$pT-I zYlS3VTio*FeIBSMTdxbAEI$9n09lzeExH%xhu*ii41tR_|FH%7dKl{<*}HQT&0$?^ zez>L-0MCxb?B7GWtP;OGkuA1BcL^0hB$s$DKpXSBs(M9F@SAefx72`QgsW50TvZd zTtw<^plFSFzEzMHGg{=FC#0C;=I5TqjCWq?GtLrCHvmL9NeFLM8iF0$o%f>=XP{K4h}w7Fti@#{>7nt! zVIm(6x1bN}yHM1qp{g*Z5%%~&XYRS(LU%;w7_CjBK(u?l*R>$eT937CX9XcgQ<2;?iS};H4WX zsEPxTUc*3trb7C2$>6)ti+G_(;*AfhZHKaFYETz~o+hY;`a#O-eSl(FU-GAXEbn=J z>q^@!_nW(C_mLH3_g9l@7CR|%ZYy+ExcySusT-GgJd)Je-ca*a(Rokp{6zIle!Z z-3r#YA#Z#N@q>pKRWGkke-6E`rh793Tbk5NwB#e_wF^QJFzZ$f`1Bm{*0XkACo)sW(ZpL6+6OI3WXH*D>N}-+4NvJrZNmyXfo8UK zVR(Jw;swgQzQ;#FjFKfzB%w&5vhR;Q7+`kH#R%&-j)8SlH;{Q-YHS9;zH;hWtzB7{ znf#}o?}LY3+ZJr8@I>kZIp^O8`6L>h+*t$QEUs(2!zij7h6z2Bp9!ZPXiJ8FIOpW` z5{G98AjnV}WhbZiX(fK%*{oyir%O1lgAfCeH%Q@khmI-FEyK{ak%Ga~WXqk1uqeN7 zAHw^h*RWyu<+VObt{~?a#4O|DjM#9}j}rweSTI${61O%ZrtVC9Dhow`Q|o?6Ujpu_ z>-eYfS2`wM)$Z1lho9tn&#{UB@-E%Z3oCyvJ!86V-F=uJF+E;F^ifeStj<-uu7o#% z%*ob7-)ty-oNl?IaaBbWt!4w;MnLv>cqu7TM@z+I+7 zasviToX@OPq_(M2uDrgiF$g)H=J_+Ly0h2bob8{QmVUw@1hzwnlSN;vd0-B+UzL{N zos4G%pGokv75c@^vX0T8P-5jE{EYYct=+)MrR*qmdFM!c)_3S`73Pd=)=(nZx5Xo< zXWrNeAFQ&veSwgedy0M*ziW^Br#W5c1FfJ|l2gj5Oi4}&vVnbN3df{rn0FZkYqS$; z@%I*a`FZ#~~3@ zm18In_k9oV<#5SbbW*4zJyYWn+p41~giePeh#Sn9e>cGsFX5FspSdEV#2q%QV2zah zC6)}J-pHpgOxD-wpc z5||TUHxvCKau(dcCK4Y;wGHW)22Rr)m*ohg2z0w}zfZdb?nOW7yP_Y^^eU(J|%MJ3OgQPh&uO} zI55|Le=|N;35+#FLV5P1a~KY3grwYdSFG9PLHaxADal#LN|j&4uC0eE={ia z=a>=N*5A#YmS5O(=Yg0PLk7+V;q_Z57StLJ#=~mDJbAE?=F9oGUMVdEz?Ls-XIT zIah2qx`kmenBVLt);B4E9x<$3R~>$H#&Psi@p{)9~MI0>^)2~ zz4zr%-@e3;-yck%9b_?S+#tDrOr`OD2^k^Fx>L|aS|RpCl#2LCq`KAP_TO|edYIQ& zev~I>*@ubz)>vL1d5_ZLlT1Yqo>$##RrYDyvppWRZrJ0GCr$iPLQPVB{;~DvM{VW!*-^wpm8{_9!zh+;>r&M^!A!3!@jAku}>X0ZGY_NC9hYb{YH~-425Qq>#;np zYU%97@IXtJ!_zq^Y!6p=o4z>q)k8n@W+&an=ufe$<x~((NuE^VKht*gT)`2t8loZFVdsR$x%U`u=RtLEwCnRO)mX9b4={MK z;FcR|vtOULM86+&=s^+!^`4{rQeAOyFmpGf!Q2o64MNcKqe{(|H+=6E`HeWa!%Wwo z4*piqm~AdWccv=)HtuQY3;c@K(Mj3tile9(hyH?0?C#pm|1kyDiNr6)%7KAR(1%bF zlWzzfnfH^*7v1(mqefhLB}ear?;?5W`LpiAuSQXLA)ec{hIE?5540B|M&{vEP&M8T z3KwGeAenKZv}q5`=BCLOw{%}WJVIB`J3QD;gd)X`9DyJ3oB;Y!4m98?0;NmlEzFai=u`?SNY3 z&aa`8*fMQz#NgZpthwn*LWfwz)JqYKuPdkOCnK)O+a*0uMaBhQBjj3)`oY*SrJ`u~Nu5M`DRz9~V z%`NR_Y1sT;<4w;+!OzZi!&k?rV+h0V1`VA`isFR}azy^zK|RMzQ}q@Aop!%^-<+8H z*mt%~oB;bk$3!)&i&u*_R-x8LOb^-`+c;1?5vsZlK$jZBX>M|PHOPENc-UIdtnV0E znt;a}3oL1hZcZh8T>osVGo-Jw^L%-izDq2Mc8R-wbh{^($eQ(gy^_B){-Rx7jJA1| z&aT;5b;n90frxqUsdUt$09*AYBsIndFm}fND8BCM zf<@9F8%6A5n%kvVD8}r=g>RzHq#9>faW*UN0QSHNiK85Fg4Ad5BRH`fzAK_R#ZkFo zBtJ=6mB(9P5MzkxE~*^MmG&STn5V$sD9-lVEnQlNWPd`)wT&Fz>21q6pjY7ME_vIp z`OPF#2T{Dy_EM~`W{;d#9gmwV@cGYo<2i)~eF$T{WEA!j<{wnRNjOCvH-4-chm(Dm z@#o%JgxuooPPvg?et7F~oRaB>U^AKk<9nmL3eld-_w`F7s9|$S=s7Zm+#|^DPdALzVf~VXbj`tgimEpxVC`i1U8hYQVRIi+x5A0KGx1Ia1NT! z@+Q7V%pa@fypmx7Hgtv#wIJJVSxuiKuf|O0@5A*=ya_v=bk(?3R0C11Z4=V>GC7Xs@yE1^5-kakYn-4l3 zCz++;^<+!ohOPPE1z+blAbkFV(xRU;`&BYL^c40A@Rkrq!THl9_{z05_{Q!UX62Kp zN2V?(96kcf5gAAH$uDI>?A!rvq*r&YmU+~%E!6??5}*k0J5+Z4j2HAI(uw9wwd;%Y z6RusGB{C#!Sw%hA^TWW3JNL7t*oy1eqypGr<; zEW&tnMac`*Vy@b)xalhxl9Oxn?azK!CVxya2!804Ke!PYmk4HGCj1grZcAn-Lkt)* zUH21ZQ&FfrM%$&`$NK;>M#szGO%I<&uuVTozn~gjG)Du5pHWst@$FD8fV^A~bSHY> zrxu^gT=qt5k_DS5HOo0AJo|c>F?oD7u>7JKc+3J}3GeUiB;NKnI-V0_vjd1)C3q|> zMly9Wis|byn8)3XXjQGB9_wj&BZetP98Qp;Mx7iQX&~nsfqA{d8YVW7<&3yhi?;^a&Tj+Q8Kl?P+B#gj863zAOP(l zt(5F7j@Vn@u}PAAH|f{{%OZGCq;%cH9MdGB)OPhjlPZxeFSUMtMCjqgOrZttJqO=x z;=a3+Y+F(yW*D%q?jj{aSSug%dJRXoaV0W`iKIuVv5GGc*3$#5Kzr?S6~FKPZc1h9 zpacJSpDB85>U55PajwPv;HbpfP=5{lSWM4jomQ=VAy*E)E-$kMrGxSy22=|>V8T&< zr9Lqt=3$iBpM^&>_`{qNPT#A%J>Sg6V}|yK)1=#>*=0>eu{KkdZ&_>o>djIi@HMp9+j-FZ!VpMlQkG%3q%R@A zLD5{8u64lKDQ||y?JMjq-Vi`f5PU2&l{y@&yRDn&tJB;>%I0KSs$ztKC|9wo|4)^nhYXQjwixRm(SlG%mdeOd z9HBajq!@&bPNFh0ndh35InVNXUe6!!_|=%#%B*W_> zbf2ha3@{mj3g2S=4o`GMfQ*}YU7oVd;uY8H%v@hhZ?>+DRe-ASVwoSi;F~Xk^(e7N zpeLh#3=>QBCJ`L$5YiXJZAjfN-)xminPYNx&!&(fobS(d_d+*sVT45EcQ!-Sv{Mc_ zDlC+c=%y4M!W?!?N3SH~{J1xoigr|{=5w4=N|!zB_C=*nDMSL@vLYkiClD;pZ-T@w zn!jL*IbX4@MMv8;ST-J?vc6~M8~80`r*~G)nEWRf^>G)1TCxcX&mWORvQ_P+aXy^4 z2BF6B0s^?aH$|GzH+g8k5tw(^h>G|@Gp+~?!!=?hk^yOr3ILNFe9tmm)tveiTI47= zcY$OyoYg%Yq#7*MdqxH?;cLCNTV#j3l&gL|=+pdgY zi25To6q)a+*^R!Df_cC!#f6!^GS%4V@U>4RjANKvh&JN7KWIVYc5>wzRhIdGi(RTv z*F%9lWl{uA!FH91h;i8J*RWp)r#&=J-i`s)VmLmX)#1 zuhgE9`EFO^};c1L_hZ0<2}<+vr`|iwx%{iN`@;vAoEa4;A#bA!W%XFk|W( z-u|aHp#;0cd!>&}>-V`=JCL6&p1$QgSfxJXWJ5i#yTz;mWxcoD(S|9LXFt0Pc8gv8 z)QqycF%Ga)Fg~1&-aU1wVRTS_tc+Ve99j7#C&gL3|ENLw_DAUb`WSviBZcz$=Hkr< zx(=jYN4px(Eat6BRlIpCP8S%S*bgw^u%(+=-8~_aRD^07+SV8|4>C@k^lOo))dSrr zfFE7T7p+Q?GqZ|ivRHC(`Cr&kB!jD*aUZ)rOUROvZZfi(QX7%cV*uYN{xvZ!qVG== zhBzR=$syLA~Bdm4|w6!?%gj1_M%L5{M{ zf4(za;<9|LWW~BLUz%DpHt8_#99)E@uV_A{d30QO@nnV)onGoxB7nrcNLo|vHGh>p zSv`1HaU9oa*097%&_PnPwaUY{R zMeCuOu*hcDk=C;(<1U9d;K^p)fd|PzHUO{OFMpo+!Bu2T#W6359zCKndx-L1OYjnX|-Dyb(a@a7o37I^;1qg zLb7G4cR3Es8CAaAy6-EAu8Py|FBbbeX`d!d#+`e{(W-83Y{xsDGw84t4n5J^wQ{G_0q4=- zNe(HmxF+(6*DHJ?{u=Xn&p!X+%bKDbTHL8$jAbyY{EZbL87TY_Jy=5H!mjG?I@K9S zJfo(pCx!Lv%&hs*QlK{(>GwUq+om>sjI#BQz&lFkw5yE!ow<9zPP|)|Vun5LbqGc} z={Ao};QP;v-6VclYx4MOpsrc5IP>y^={@V1!;t0pFK<`nlYauDdcUl>2fvFfa-hp+ z6(}SX`wzbhO&50rME9G_lzu)1xT$CiIaTSBugXTr9AN=l;SL)^Ywc|7Txz$m$_v80 z$;H#OSt$XcjNK^bMYYi3H?T|?YdWRf8pO|8`rj-Y1;DZpvy8RRe#TdLIvCM$lvSQb ztot>u;;P6`pJI9?3n_1!2nJO}r+6zPQ$GUu+n&1i+rhQ0{K@-?XnVT+J75eL%8r{{p#l#eB26p8M`Sxv?Ef}eg} zaa>?B1)00FlBzlqHO>;vx-?=H;#d6c1^hTI-w7O91c1*Rf^{MDrbi;-B+ipY51uri zF)E@s<$R|fp3z>tKdeF$m1w6dxJ@q?fpLPicl$sT2b!IyR7z)QUX-tTA6zU;@ z;~Ym0wOP0$<;-DGyiT}nq|wc7&=&amu6OZ=JM7|hY+>cBW4mo)h%gq&Hl8%SV)6h#NshvRULXy_L3=4=F8;O z6(pq7WKwcGvC8PDShVZE3eK)(uP3+!^be*7c`C z;On{D$^ua!Khk-0_y;9B^mjcY7oOjJtv%6>Df{^n6ZwN9nVHiZ1=2KOLC!ZU{d}E9 zsJ7RH2|%b$TD&c|1Fyh`;cQ}Ezvg;r6tV(jIcAyT8!-D&!8~yUvV8Pyeqou;hme6C ze;!?>k)6a(Kv`Ni=T3Pkmx>50`>2KR==Asnnyw)&G-?7$v;dWhM4s7j=&^wGca1Ue zuVSkL@|d0F!dSu#x2w5usceYYpchnN=n3Ra%}UlsNUc6#yv1-&*q6zAy5L=D1;=Z5 zgrMK`e0xpwOLWS|v|5HMK+%=-Ie}cm{X1nr6D6g+@d0<@ba+a`X`jEuhErG)NpM4y z$i%{KhsHCFC+fFr5hoaNi(b^`QP8Z4+Is}u|J52}!dfee{3qy~Y?kwNxN zw@Eg?J?abOJ!f142Qn%AMnd0&)<*`0#+W`b-__o&9XTNDN1DkiqC}jZuyGpbZ{+=snQ0pyu<$Y2? zZ(7v$eR#t*ddZiepfiNH)BW4eO0(1?T)~nT7LHf z{C%8_ti57}PyRG}Y2fx!>Jyz_3zx0j_--CHWUKB5CkfjxJuO=6n_aUg-aYX?hO84C zVII4oLY)o@6{UoLv|4O4RPUNp#{9njZct6b4*T$!y0y@_{8GjR4s6^~8zBB5R{Ky; zvAZjd*Ydd51qjVBZ< zEXnfUn03*8?zoBnFuN*UfCn_eKAg9o%~Qr~Q6yEE+ic9!KIrffI?oy}_34=c)(5*N zn&E7Me~z3E&w7zAVtN>0to;kY&=v)5bYQiW2n$UDayhZhM6g=^UZphG#Sp3`l? z2O5lDv(CHvLYy06E~$s2VcjdNb^b^#SCQeD_pFf8v~!!&eg?*)4VGr+V-LR`JIOvE z?1V8>;{6dv0dpZoItEDO2?YC6tKds@ntt1Iwdtv9(MMEPIZ|ZEJ+nI`z3hGtf#k>G zCyZ&aQ`gNzuoX;|9r`br;Hg_;H8}|5sd(+VSQY4hJ=ehfWz$f@aDjz-e#cFfAnCc9 z0>LV2|3v5WgTn!`Z_C(|CWFcZNNSupzOa*RO>j{H)jDOOBjI3hI~QEK!uS>j>Z#CW zT_ld|tg8OV%ln2B+OK5iv_)9|l@TxrTXRqwNuUck7U(AxfIX=oHOEaqg8!qq<-JC_ z^jd1N&UU^}-S!eOp=*}2Sv{1?f8_zNpbK?rKpU(q*}xW**EwQ<{g?q;NiiJsAZy^~ z7<*(c8y|V-ZPfCIp__XFn|0%Km~r(oFs(6tIO}=Kv~CRw`=@~hhr4(X&_{qCJ9&kM z9$-zyInJ=23cY%^w59>#yatl?ma#kR=^ZvoM^Wc%WMNA24Vb6?p93|NS=I+x>(^9t5 z0Ob-Z3`8raDRZ(yE$$Bcq<|>ZaQcEDvT2Um_#c1Xn*$q;Zq$O7=lVZ(z2vg~31ReM z3~URjs#ouu?N$44zhvJ))g57~_AWKI2K;!u|Lqq;DR?AR VUJ}!Zu0!C*#>!!5E#Xk?KL8=3-}V3i diff --git a/examples/simple_example.py b/examples/simple_example.py index b8ec5f689..c7a7a9f38 100644 --- a/examples/simple_example.py +++ b/examples/simple_example.py @@ -45,7 +45,7 @@ def error_fn(optim_vars, aux_vars): # returns y - v * exp(x) layer = th.TheseusLayer(th.GaussNewton(objective, max_iterations=10)) phi = torch.nn.Parameter(x_true + 0.1 * torch.ones_like(x_true)) -outer_optimizer = torch.optim.RMSprop([phi], lr=0.001) +outer_optimizer = torch.optim.Adam([phi], lr=0.001) for epoch in range(20): solution, info = layer.forward( input_tensors={"x": phi.clone(), "v": torch.ones(1, 1)}, diff --git a/theseus/__init__.py b/theseus/__init__.py index 51ad5f164..f0c6ddea2 100644 --- a/theseus/__init__.py +++ b/theseus/__init__.py @@ -3,7 +3,7 @@ # This source code is licensed under the MIT license found in the # LICENSE file in the root directory of this source tree. -__version__ = "0.1.0" +__version__ = "0.1.1" from .core import ( CostFunction,