From ab01d0485d9584eb547047bc02a7b503fe9c6114 Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 27 Apr 2026 13:39:42 -0400 Subject: [PATCH 1/7] add urdf_to_dh_params --- CMakeLists.txt | 3 + conanfile.py | 1 + src/viam/sdk/CMakeLists.txt | 3 + .../private/urdf_to_dh_internals.hpp | 95 ++++ .../sdk/referenceframe/urdf_to_dh_params.cpp | 414 ++++++++++++++++ .../sdk/referenceframe/urdf_to_dh_params.hpp | 49 ++ src/viam/sdk/tests/CMakeLists.txt | 9 + src/viam/sdk/tests/test_urdf_to_dh_params.cpp | 461 ++++++++++++++++++ src/viam/sdk/tests/testfiles/gp12.urdf | 115 +++++ src/viam/sdk/tests/testfiles/ur5e-real.urdf | 270 ++++++++++ 10 files changed, 1420 insertions(+) create mode 100644 src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp create mode 100644 src/viam/sdk/referenceframe/urdf_to_dh_params.cpp create mode 100644 src/viam/sdk/referenceframe/urdf_to_dh_params.hpp create mode 100644 src/viam/sdk/tests/test_urdf_to_dh_params.cpp create mode 100644 src/viam/sdk/tests/testfiles/gp12.urdf create mode 100644 src/viam/sdk/tests/testfiles/ur5e-real.urdf diff --git a/CMakeLists.txt b/CMakeLists.txt index 8184f848e..71050ebd0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -361,6 +361,7 @@ set(VIAMCPPSDK_GRPC_VERSION_MINIMUM 1.30.2) set(VIAMCPPSDK_PROTOBUF_VERSION_MINIMUM 3.12.4) set(VIAMCPPSDK_XTL_VERSION_MINIMUM 0.7.2) set(VIAMCPPSDK_XTENSOR_VERSION_MINIMUM 0.24.3) +set(VIAMCPPSDK_EIGEN_VERSION_MINIMUM 3.3) # Time to find `BOOST`. if (VIAMCPPSDK_BUILD_TESTS) @@ -503,6 +504,8 @@ FetchContent_Declare( FetchContent_MakeAvailable(xtl xtensor) +find_package(Eigen3 ${VIAMCPPSDK_EIGEN_VERSION_MINIMUM} CONFIG REQUIRED) + # Pull in our subdirectories add_subdirectory(src/viam) diff --git a/conanfile.py b/conanfile.py index 0c6d91015..0acfcfb8f 100644 --- a/conanfile.py +++ b/conanfile.py @@ -67,6 +67,7 @@ def requirements(self): self.requires(self._grpc_requires()) self.requires('protobuf/[>=3.17.1 <6.30.0]') self.requires(self._xtensor_requires(), transitive_headers=True) + self.requires('eigen/[>=3.3.0]') def build_requirements(self): if self.options.offline_proto_generation: diff --git a/src/viam/sdk/CMakeLists.txt b/src/viam/sdk/CMakeLists.txt index b5b129449..97bc7fb82 100644 --- a/src/viam/sdk/CMakeLists.txt +++ b/src/viam/sdk/CMakeLists.txt @@ -136,6 +136,7 @@ target_sources(viamsdk module/service.cpp module/private/data_consumer_query.cpp referenceframe/frame.cpp + referenceframe/urdf_to_dh_params.cpp registry/registry.cpp resource/reconfigurable.cpp resource/resource.cpp @@ -217,6 +218,7 @@ target_sources(viamsdk ../../viam/sdk/module/service.hpp ../../viam/sdk/module/signal_manager.hpp ../../viam/sdk/referenceframe/frame.hpp + ../../viam/sdk/referenceframe/urdf_to_dh_params.hpp ../../viam/sdk/registry/registry.hpp ../../viam/sdk/resource/reconfigurable.hpp ../../viam/sdk/resource/resource.hpp @@ -306,6 +308,7 @@ target_link_libraries(viamsdk PRIVATE ${VIAMCPPSDK_GRPC_LIBRARIES} PRIVATE ${VIAMCPPSDK_PROTOBUF_LIBRARIES} PRIVATE Threads::Threads + PRIVATE Eigen3::Eigen ) # if the `viam_rust_utils` target exists then we should use it. If not then diff --git a/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp b/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp new file mode 100644 index 000000000..f46776f7e --- /dev/null +++ b/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp @@ -0,0 +1,95 @@ +/// @file referenceframe/private/urdf_to_dh_internals.hpp +/// @brief Internal helpers for urdf_to_dh_params. Exposed only to the +/// test suite; not part of the installed public API. +#pragma once + +#include +#include + +#include +#include +#include + +#include +#include + +namespace viam { +namespace sdk { +namespace urdf_to_dh_internals { + +constexpr double k_axis_parallel_epsilon = 1e-9; +constexpr double k_dh_compat_epsilon = 1e-6; + +/// @brief Parsed joint element from a URDF (subset needed for DH extraction). +struct Joint { + std::string name; + std::string type; // "revolute", "continuous", "fixed", ... + std::string parent_link; + std::string child_link; + boost::optional origin; // none == identity + boost::optional axis; // none == URDF default (1,0,0) +}; + +/// @brief Result of walking joint axes at rest along a chain. +struct JointAxesAtRest { + std::vector axes; // revolute joint axes in world + std::vector origins; // revolute joint origins in world + Eigen::Isometry3d end_pose; // final link pose in world +}; + +/// @brief Result of build_dh_frames: frames 0..N, each length N+1. +struct DHFrames { + std::vector zs; + std::vector xs; + std::vector pts; +}; + +/// @brief Result of common_normal: direction, feet on each line, and +/// whether the two axes are (anti-)parallel. +struct CommonNormalResult { + Eigen::Vector3d x_dir; // zero vector if the two lines are coincident + Eigen::Vector3d foot0; + Eigen::Vector3d foot1; + bool parallel; +}; + +std::vector parse_urdf(const KinematicsDataURDF& urdf); + +std::vector walk_urdf_chain(const std::vector& joints); + +Eigen::Isometry3d pose_in_meters(const boost::optional& origin); + +Eigen::Vector3d axis_unit(const boost::optional& axis); + +JointAxesAtRest joint_axes_at_rest(const std::vector& joints); + +CommonNormalResult common_normal(const Eigen::Vector3d& z0, + const Eigen::Vector3d& p0, + const Eigen::Vector3d& z1, + const Eigen::Vector3d& p1); + +DHFrames build_dh_frames(const std::vector& axes, + const std::vector& origins, + const Eigen::Isometry3d& end_pose); + +void extract_dh_row(const Eigen::Vector3d& z_prev, + const Eigen::Vector3d& x_prev, + const Eigen::Vector3d& p_prev, + const Eigen::Vector3d& z_curr, + const Eigen::Vector3d& x_curr, + const Eigen::Vector3d& p_curr, + double& d, + double& theta, + double& a, + double& alpha); + +void validate_end_effector_dh(const Eigen::Vector3d& z_prev, + const Eigen::Vector3d& x_end, + const Eigen::Vector3d& origin_prev, + const Eigen::Vector3d& p_end); + +Eigen::Vector3d pick_base_x(const Eigen::Vector3d& z); + +} // namespace urdf_to_dh_internals +} // namespace sdk +} // namespace viam diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp new file mode 100644 index 000000000..972a350ae --- /dev/null +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp @@ -0,0 +1,414 @@ +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace viam { +namespace sdk { +namespace urdf_to_dh_internals { + +namespace { + +// Parse "x y z" (space-delimited) to Vector3d. Throws if fewer than 3 tokens. +Eigen::Vector3d parse_triple(const std::string& s) { + std::istringstream iss(s); + double x = 0, y = 0, z = 0; + if (!(iss >> x >> y >> z)) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: failed to parse space-delimited triple: '" + s + "'"); + } + return Eigen::Vector3d(x, y, z); +} + +// URDF RPY -> rotation matrix (R = Rz(yaw) * Ry(pitch) * Rx(roll)). +Eigen::Matrix3d rpy_to_rotation(double roll, double pitch, double yaw) { + return (Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) * + Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) * + Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX())) + .toRotationMatrix(); +} + +} // namespace + +std::vector parse_urdf(const KinematicsDataURDF& urdf) { + namespace pt = boost::property_tree; + pt::ptree tree; + + std::string text(reinterpret_cast(urdf.bytes.data()), urdf.bytes.size()); + std::istringstream iss(text); + try { + pt::read_xml(iss, tree); + } catch (const pt::xml_parser_error& e) { + throw Exception(ErrorCondition::k_general, + std::string("URDFToDHParams: failed to parse URDF XML: ") + e.what()); + } + + const auto robot_it = tree.find("robot"); + if (robot_it == tree.not_found()) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: no root element in URDF"); + } + const pt::ptree& robot = robot_it->second; + + std::vector joints; + for (const auto& child : robot) { + if (child.first != "joint") { + continue; + } + const pt::ptree& jnode = child.second; + + Joint j; + j.name = jnode.get(".name", ""); + j.type = jnode.get(".type", ""); + j.parent_link = jnode.get("parent..link", ""); + j.child_link = jnode.get("child..link", ""); + + const auto origin_child = jnode.get_child_optional("origin"); + if (origin_child) { + const std::string xyz = origin_child->get(".xyz", "0 0 0"); + const std::string rpy = origin_child->get(".rpy", "0 0 0"); + const Eigen::Vector3d t = parse_triple(xyz); + const Eigen::Vector3d r = parse_triple(rpy); + Eigen::Isometry3d iso = Eigen::Isometry3d::Identity(); + iso.linear() = rpy_to_rotation(r.x(), r.y(), r.z()); + iso.translation() = t; + j.origin = iso; + } + + const auto axis_child = jnode.get_child_optional("axis"); + if (axis_child) { + const std::string xyz = axis_child->get(".xyz", "1 0 0"); + j.axis = parse_triple(xyz); + } + joints.push_back(std::move(j)); + } + return joints; +} + +std::vector walk_urdf_chain(const std::vector& joints) { + // Index joints by parent-link name. + std::map> by_parent; + std::set all_parents; + std::set all_children; + for (const auto& j : joints) { + by_parent[j.parent_link].push_back(&j); + all_parents.insert(j.parent_link); + all_children.insert(j.child_link); + } + + // A root link is any parent that is never a child. + std::vector roots; + for (const auto& p : all_parents) { + if (all_children.find(p) == all_children.end()) { + roots.push_back(p); + } + } + if (roots.size() != 1) { + std::string list; + for (const auto& r : roots) { + list += "'" + r + "' "; + } + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: expected exactly one root link, found " + + std::to_string(roots.size()) + ": " + list); + } + + std::vector ordered; + ordered.reserve(joints.size()); + std::string current = roots[0]; + while (true) { + auto it = by_parent.find(current); + if (it == by_parent.end() || it->second.empty()) { + break; // reached leaf + } + if (it->second.size() > 1) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: branching topology at link '" + current + "' (has " + + std::to_string(it->second.size()) + " outgoing joints)"); + } + const Joint* j = it->second.front(); + ordered.push_back(*j); + current = j->child_link; + } + if (ordered.size() != joints.size()) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: chain walk visited " + std::to_string(ordered.size()) + + " of " + std::to_string(joints.size()) + + " joints; URDF may be disconnected"); + } + return ordered; +} + +Eigen::Isometry3d pose_in_meters(const boost::optional& origin) { + return origin ? *origin : Eigen::Isometry3d::Identity(); +} + +Eigen::Vector3d axis_unit(const boost::optional& axis) { + if (!axis) { + return Eigen::Vector3d(1.0, 0.0, 0.0); // URDF default + } + const double norm = axis->norm(); + if (norm < k_axis_parallel_epsilon) { + throw Exception(ErrorCondition::k_general, "URDFToDHParams: joint axis has zero magnitude"); + } + return *axis / norm; +} + +CommonNormalResult common_normal(const Eigen::Vector3d& z0, + const Eigen::Vector3d& p0, + const Eigen::Vector3d& z1, + const Eigen::Vector3d& p1) { + CommonNormalResult r{}; + const Eigen::Vector3d cross = z0.cross(z1); + + if (cross.norm() < k_axis_parallel_epsilon) { + r.parallel = true; + // Perpendicular from line0 to line1: project (p1-p0) onto plane perp. to z0. + const Eigen::Vector3d d = p1 - p0; + const Eigen::Vector3d perp = d - z0 * d.dot(z0); + const double perp_norm = perp.norm(); + if (perp_norm < k_axis_parallel_epsilon) { + // Coincident lines. + r.x_dir = Eigen::Vector3d::Zero(); + r.foot0 = p0; + r.foot1 = p0; + return r; + } + r.x_dir = perp / perp_norm; + r.foot0 = p0; + r.foot1 = r.foot0 + r.x_dir * perp_norm; + return r; + } + + // Non-parallel lines: skew-line closest-point formula. + const Eigen::Vector3d d = p1 - p0; + const double a = z0.dot(z0); // = 1 (unit) + const double b = z0.dot(z1); + const double c = z1.dot(z1); // = 1 + const double det = a * c - b * b; // = |cross|^2 > 0 + const double t0 = (d.dot(z0) * c - d.dot(z1) * b) / det; + const double t1 = (d.dot(z0) * b - d.dot(z1) * a) / det; + + r.foot0 = p0 + z0 * t0; + r.foot1 = p1 + z1 * t1; + const Eigen::Vector3d diff = r.foot1 - r.foot0; + const double diff_norm = diff.norm(); + if (diff_norm < k_axis_parallel_epsilon) { + // Lines intersect; use cross as the common-normal direction. + r.x_dir = cross / cross.norm(); + } else { + r.x_dir = diff / diff_norm; + } + r.parallel = false; + return r; +} + +void extract_dh_row(const Eigen::Vector3d& z_prev, + const Eigen::Vector3d& x_prev, + const Eigen::Vector3d& p_prev, + const Eigen::Vector3d& z_curr, + const Eigen::Vector3d& x_curr, + const Eigen::Vector3d& p_curr, + double& d, + double& theta, + double& a, + double& alpha) { + const Eigen::Vector3d delta = p_curr - p_prev; + d = delta.dot(z_prev); + a = delta.dot(x_curr); + theta = std::atan2(x_prev.cross(x_curr).dot(z_prev), x_prev.dot(x_curr)); + alpha = std::atan2(z_prev.cross(z_curr).dot(x_curr), z_prev.dot(z_curr)); +} + +void validate_end_effector_dh(const Eigen::Vector3d& z_prev, + const Eigen::Vector3d& x_end, + const Eigen::Vector3d& origin_prev, + const Eigen::Vector3d& p_end) { + const double perp_dot = x_end.dot(z_prev); + if (std::abs(perp_dot) > k_dh_compat_epsilon) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: end-effector X-axis not perpendicular to last joint axis " + "(residual dot = " + + std::to_string(perp_dot) + ")"); + } + const Eigen::Vector3d delta = p_end - origin_prev; + const Eigen::Vector3d y_dir = z_prev.cross(x_end); + const double plane_residual = delta.dot(y_dir); + if (std::abs(plane_residual) > k_dh_compat_epsilon) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: end-effector origin out of DH plane (residual along y = " + + std::to_string(plane_residual) + ")"); + } +} + +JointAxesAtRest joint_axes_at_rest(const std::vector& joints) { + JointAxesAtRest out; + Eigen::Isometry3d cumulative = Eigen::Isometry3d::Identity(); + + for (const auto& j : joints) { + cumulative = cumulative * pose_in_meters(j.origin); + + if (j.type == "fixed") { + // Accumulated only; no joint frame. + } else if (j.type == "revolute" || j.type == "continuous") { + try { + const Eigen::Vector3d local_axis = axis_unit(j.axis); + const Eigen::Vector3d world_axis = cumulative.linear() * local_axis; + out.axes.push_back(world_axis); + out.origins.push_back(cumulative.translation()); + } catch (const Exception& e) { + throw Exception(ErrorCondition::k_general, + "URDFToDHParams: joint '" + j.name + "': " + e.what()); + } + } else { + throw Exception(ErrorCondition::k_not_supported, + "URDFToDHParams: joint '" + j.name + "' has unsupported type '" + + j.type + "' (only revolute, continuous, and fixed are supported)"); + } + } + + if (out.axes.empty()) { + throw Exception(ErrorCondition::k_general, "URDFToDHParams: no revolute joints in chain"); + } + out.end_pose = cumulative; + return out; +} + +DHFrames build_dh_frames(const std::vector& axes, + const std::vector& origins, + const Eigen::Isometry3d& end_pose) { + const std::size_t n = axes.size(); + + const Eigen::Vector3d end_z = end_pose.linear() * Eigen::Vector3d(0, 0, 1); + const Eigen::Vector3d end_x = end_pose.linear() * Eigen::Vector3d(1, 0, 0); + const Eigen::Vector3d end_p = end_pose.translation(); + + std::vector all_z(axes.begin(), axes.end()); + all_z.push_back(end_z); + std::vector all_p(origins.begin(), origins.end()); + all_p.push_back(end_p); + + DHFrames out; + out.zs.resize(n + 1); + out.xs.resize(n + 1); + out.pts.resize(n + 1); + + // Frame 0: Z = joint-1 axis; origin = point on axis closest to world origin. + out.zs[0] = axes[0]; + const Eigen::Vector3d& p0 = origins[0]; + const double t = -p0.dot(axes[0]); + out.pts[0] = p0 + axes[0] * t; + out.xs[0] = pick_base_x(axes[0]); + + // Frames 1..N via common normal with previous Z. + for (std::size_t i = 1; i <= n; ++i) { + const Eigen::Vector3d& z_prev = out.zs[i - 1]; + const Eigen::Vector3d& z_curr = all_z[i]; + const Eigen::Vector3d& p_prev = out.pts[i - 1]; + const Eigen::Vector3d& p_curr = all_p[i]; + + const auto cn = common_normal(z_prev, p_prev, z_curr, p_curr); + + if (cn.x_dir.isZero(k_axis_parallel_epsilon)) { + // Coincident axes: keep previous X direction. + out.xs[i] = out.xs[i - 1]; + out.pts[i] = p_curr; + out.zs[i] = z_curr; + continue; + } + + Eigen::Vector3d x_dir = cn.x_dir; + if (x_dir.dot(out.xs[i - 1]) < 0) { + x_dir = -x_dir; + } + out.xs[i] = x_dir; + out.pts[i] = cn.foot1; + out.zs[i] = z_curr; + } + + // Final frame N overwrites the loop's canonical placement so that frame N + // coincides with the URDF's end-effector frame. Consistency is validated + // separately in validate_end_effector_dh. + out.pts[n] = end_p; + out.zs[n] = end_z; + out.xs[n] = end_x; + + return out; +} + +Eigen::Vector3d pick_base_x(const Eigen::Vector3d& z) { + const Eigen::Vector3d world_x(1, 0, 0); + Eigen::Vector3d proj = world_x - z * z.dot(world_x); + if (proj.norm() < k_axis_parallel_epsilon) { + const Eigen::Vector3d world_y(0, 1, 0); + proj = world_y - z * z.dot(world_y); + } + return proj.normalized(); +} + +} // namespace urdf_to_dh_internals + +std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf) { + using namespace urdf_to_dh_internals; + + auto chain = walk_urdf_chain(parse_urdf(urdf)); + auto axes_origins = joint_axes_at_rest(chain); + const std::size_t n = axes_origins.axes.size(); + + auto frames = build_dh_frames(axes_origins.axes, axes_origins.origins, axes_origins.end_pose); + + validate_end_effector_dh(frames.zs[n - 1], frames.xs[n], frames.pts[n - 1], frames.pts[n]); + + // Revolute joint names in chain order (matches joint_axes_at_rest filter). + std::vector revolute_names; + revolute_names.reserve(n); + for (const auto& j : chain) { + if (j.type == "revolute" || j.type == "continuous") { + revolute_names.push_back(j.name); + } + } + + std::vector result(n); + for (std::size_t i = 0; i < n; ++i) { + double d, theta, a, alpha; + extract_dh_row(frames.zs[i], + frames.xs[i], + frames.pts[i], + frames.zs[i + 1], + frames.xs[i + 1], + frames.pts[i + 1], + d, + theta, + a, + alpha); + result[i] = DHParam{revolute_names[i], d, theta, a, alpha}; + } + return result; +} + +std::vector urdf_to_dh_params(Arm& arm) { + KinematicsData kin = arm.get_kinematics(); + const KinematicsDataURDF* urdf = boost::get(&kin); + if (urdf == nullptr) { + throw Exception(ErrorCondition::k_not_supported, + "urdf_to_dh_params(Arm&): kinematics format is not URDF"); + } + return urdf_to_dh_params(*urdf); +} + +} // namespace sdk +} // namespace viam diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp new file mode 100644 index 000000000..52931d78e --- /dev/null +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp @@ -0,0 +1,49 @@ +/// @file referenceframe/urdf_to_dh_params.hpp +/// @brief Convert a revolute-only URDF serial chain to Denavit-Hartenberg +/// parameters. +#pragma once + +#include +#include + +#include + +namespace viam { +namespace sdk { + +class Arm; + +/// @brief One Denavit-Hartenberg row for a single revolute joint. +/// +/// Units: meters for `d` and `a`, radians for `theta` and `alpha`. +/// `theta` is the joint's angle at the URDF's zero configuration +/// (typically 0). The runtime joint angle is `theta + input`. +struct DHParam { + std::string name; ///< joint name copied from the URDF + double d; ///< translation along Z_{i-1} + double theta; ///< rotation about Z_{i-1} at zero config + double a; ///< translation along X_i + double alpha; ///< rotation about X_i +}; + +/// @brief Convert a revolute-only URDF serial chain to DH parameters. +/// +/// Returns one `DHParam` per revolute or continuous joint in chain order. +/// Fixed joints are folded into the cumulative transform. +/// +/// @throws viam::sdk::Exception if the URDF is not a serial revolute chain, +/// has an unsupported joint type, has a zero-magnitude axis, has an +/// end-effector frame that is not DH-compatible (X-axis not +/// perpendicular to the last joint axis, or origin out of the DH +/// plane), or fails to parse as XML. +std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf); + +/// @brief Convenience overload: fetches `arm.get_kinematics()`, requires +/// URDF format, and forwards to the byte-based overload. +/// +/// @throws viam::sdk::Exception if the arm's kinematics are not in URDF +/// format, or for any reason the byte-based overload would throw. +std::vector urdf_to_dh_params(Arm& arm); + +} // namespace sdk +} // namespace viam diff --git a/src/viam/sdk/tests/CMakeLists.txt b/src/viam/sdk/tests/CMakeLists.txt index fd0f27006..65a1432d8 100644 --- a/src/viam/sdk/tests/CMakeLists.txt +++ b/src/viam/sdk/tests/CMakeLists.txt @@ -56,6 +56,9 @@ target_link_libraries(viamsdk_test viamcppsdk_link_viam_api(viamsdk_test PUBLIC) +# Path to the urdf fixtures used by test_urdf_to_dh_params +set(VIAMCPPSDK_TEST_TESTFILES_DIR "${CMAKE_CURRENT_SOURCE_DIR}/testfiles") + viamcppsdk_add_boost_test(test_arm.cpp) viamcppsdk_add_boost_test(test_audio_in.cpp) viamcppsdk_add_boost_test(test_audio_out.cpp) @@ -84,4 +87,10 @@ viamcppsdk_add_boost_test(test_resource.cpp) viamcppsdk_add_boost_test(test_sensor.cpp) viamcppsdk_add_boost_test(test_servo.cpp) viamcppsdk_add_boost_test(test_switch.cpp) +viamcppsdk_add_boost_test(test_urdf_to_dh_params.cpp) viamcppsdk_add_boost_test(test_robot.cpp) + +target_compile_definitions(test_urdf_to_dh_params + PRIVATE VIAMCPPSDK_TEST_TESTFILES_DIR="${VIAMCPPSDK_TEST_TESTFILES_DIR}") + +target_link_libraries(test_urdf_to_dh_params Eigen3::Eigen) diff --git a/src/viam/sdk/tests/test_urdf_to_dh_params.cpp b/src/viam/sdk/tests/test_urdf_to_dh_params.cpp new file mode 100644 index 000000000..2cdd44b2f --- /dev/null +++ b/src/viam/sdk/tests/test_urdf_to_dh_params.cpp @@ -0,0 +1,461 @@ +#define BOOST_TEST_MODULE test module test_urdf_to_dh_params + +#include +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace viam::sdk::urdf_to_dh_internals; + +namespace { + +viam::sdk::KinematicsDataURDF kinematics_from_string(const std::string& xml) { + std::vector bytes(xml.begin(), xml.end()); + return viam::sdk::KinematicsDataURDF(std::move(bytes)); +} + +viam::sdk::KinematicsDataURDF load_urdf(const std::string& filename) { + std::ifstream f(std::string(VIAMCPPSDK_TEST_TESTFILES_DIR) + "/" + filename, std::ios::binary); + if (!f) { + throw std::runtime_error("failed to open " + filename); + } + std::ostringstream buf; + buf << f.rdbuf(); + return kinematics_from_string(buf.str()); +} + +} // namespace + +namespace viam { +namespace sdktests { + +using namespace viam::sdk; + +BOOST_AUTO_TEST_CASE(test_pose_in_meters) { + Eigen::Isometry3d origin = Eigen::Isometry3d::Identity(); + origin.translation() = Eigen::Vector3d(0.5, 0.0, 0.0); + auto got = pose_in_meters(origin); + BOOST_CHECK_SMALL(got.translation().x() - 0.5, 1e-12); + BOOST_CHECK_SMALL(got.translation().y() - 0.0, 1e-12); + BOOST_CHECK_SMALL(got.translation().z() - 0.0, 1e-12); + + // None -> identity + auto identity = pose_in_meters(boost::none); + BOOST_CHECK(identity.isApprox(Eigen::Isometry3d::Identity())); +} + +BOOST_AUTO_TEST_CASE(test_common_normal_perpendicular) { + // Z-axis through origin + Y-axis through (0, 0, 1): perpendicular intersecting lines. + Eigen::Vector3d z0(0, 0, 1), p0(0, 0, 0); + Eigen::Vector3d z1(0, 1, 0), p1(0, 0, 1); + auto r = common_normal(z0, p0, z1, p1); + BOOST_CHECK(!r.parallel); + // z0 x z1 = (0,0,1) x (0,1,0) = (-1, 0, 0) + BOOST_CHECK_SMALL(r.x_dir.x() - (-1.0), 1e-9); + BOOST_CHECK_SMALL(r.x_dir.y(), 1e-9); + BOOST_CHECK_SMALL(r.x_dir.z(), 1e-9); + BOOST_CHECK_SMALL(r.foot0.z() - 1.0, 1e-9); + BOOST_CHECK_SMALL(r.foot1.z() - 1.0, 1e-9); +} + +BOOST_AUTO_TEST_CASE(test_common_normal_parallel) { + // Two parallel Z-axes separated by 0.5 in X. + Eigen::Vector3d z0(0, 0, 1), p0(0, 0, 0); + Eigen::Vector3d z1(0, 0, 1), p1(0.5, 0, 2); + auto r = common_normal(z0, p0, z1, p1); + BOOST_CHECK(r.parallel); + // Perpendicular projected off Z: (0.5, 0, 0) normalized -> (1, 0, 0) + BOOST_CHECK_SMALL(r.x_dir.x() - 1.0, 1e-9); + BOOST_CHECK_SMALL(r.x_dir.y(), 1e-9); + BOOST_CHECK_SMALL(r.x_dir.z(), 1e-9); +} + +BOOST_AUTO_TEST_CASE(test_extract_dh_row_ur5e_row1) { + // Frame 0: origin (0,0,0), Z=(0,0,1), X=(1,0,0). + // Frame 1: origin (0,0,0.1625), Z=(0,-1,0), X=(1,0,0). + // Expected: d=0.1625, a=0, alpha=pi/2, theta=0. + Eigen::Vector3d z_prev(0, 0, 1), x_prev(1, 0, 0), p_prev(0, 0, 0); + Eigen::Vector3d z_curr(0, -1, 0), x_curr(1, 0, 0), p_curr(0, 0, 0.1625); + + double d, theta, a, alpha; + extract_dh_row(z_prev, x_prev, p_prev, z_curr, x_curr, p_curr, d, theta, a, alpha); + + BOOST_CHECK_SMALL(d - 0.1625, 1e-9); + BOOST_CHECK_SMALL(theta, 1e-9); + BOOST_CHECK_SMALL(a, 1e-9); + BOOST_CHECK_SMALL(alpha - M_PI / 2.0, 1e-9); +} + +BOOST_AUTO_TEST_CASE(test_validate_end_effector_dh_compatible) { + BOOST_CHECK_NO_THROW(validate_end_effector_dh(Eigen::Vector3d(0, 0, 1), + Eigen::Vector3d(1, 0, 0), + Eigen::Vector3d(0, 0, 0), + Eigen::Vector3d(0, 0, 1))); +} + +BOOST_AUTO_TEST_CASE(test_validate_end_effector_dh_x_not_perpendicular) { + auto substring_match = [](const Exception& e) { + return std::string(e.what()).find("not perpendicular") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(validate_end_effector_dh(Eigen::Vector3d(0, 0, 1), + Eigen::Vector3d(1, 0, 0.5), + Eigen::Vector3d(0, 0, 0), + Eigen::Vector3d(0, 0, 1)), + Exception, + substring_match); +} + +BOOST_AUTO_TEST_CASE(test_validate_end_effector_dh_origin_out_of_plane) { + auto substring_match = [](const Exception& e) { + return std::string(e.what()).find("out of DH plane") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(validate_end_effector_dh(Eigen::Vector3d(0, 0, 1), + Eigen::Vector3d(1, 0, 0), + Eigen::Vector3d(0, 0, 0), + Eigen::Vector3d(0.5, 0.5, 1)), + Exception, + substring_match); +} + +BOOST_AUTO_TEST_CASE(test_walk_urdf_chain_ur5e) { + auto parsed = parse_urdf(load_urdf("ur5e-real.urdf")); + auto ordered = walk_urdf_chain(parsed); + const std::vector expected = { + "base_joint", + "base_link-base_link_inertia", + "shoulder_pan_joint", + "shoulder_lift_joint", + "elbow_joint", + "wrist_1_joint", + "wrist_2_joint", + "wrist_3_joint", + "wrist_3_link-ft_frame", + }; + BOOST_REQUIRE_EQUAL(ordered.size(), expected.size()); + for (std::size_t i = 0; i < expected.size(); ++i) { + BOOST_CHECK_EQUAL(ordered[i].name, expected[i]); + } +} + +BOOST_AUTO_TEST_CASE(test_walk_urdf_chain_branching) { + const std::string xml = R"( + + + + + + + + + + + + + + + + + +)"; + auto substring_match = [](const Exception& e) { + return std::string(e.what()).find("branching") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION( + walk_urdf_chain(parse_urdf(kinematics_from_string(xml))), Exception, substring_match); +} + +BOOST_AUTO_TEST_CASE(test_joint_axes_at_rest_ur5e) { + auto chain = walk_urdf_chain(parse_urdf(load_urdf("ur5e-real.urdf"))); + auto r = joint_axes_at_rest(chain); + BOOST_REQUIRE_EQUAL(r.axes.size(), 6u); + BOOST_REQUIRE_EQUAL(r.origins.size(), 6u); + + // Joint 1 (shoulder_pan): axis = world Z, origin = (0, 0, 0.1625). + BOOST_CHECK_SMALL(r.axes[0].x(), 1e-9); + BOOST_CHECK_SMALL(r.axes[0].y(), 1e-9); + BOOST_CHECK_SMALL(r.axes[0].z() - 1.0, 1e-9); + BOOST_CHECK_SMALL(r.origins[0].x(), 1e-9); + BOOST_CHECK_SMALL(r.origins[0].y(), 1e-9); + BOOST_CHECK_SMALL(r.origins[0].z() - 0.1625, 1e-9); + + // Joint 2 (shoulder_lift): axis in world = (0, -1, 0), origin = (0, 0, 0.1625). + BOOST_CHECK_SMALL(r.origins[1].x(), 1e-9); + BOOST_CHECK_SMALL(r.origins[1].y(), 1e-9); + BOOST_CHECK_SMALL(r.origins[1].z() - 0.1625, 1e-9); + BOOST_CHECK_SMALL(r.axes[1].x(), 1e-9); + BOOST_CHECK_SMALL(r.axes[1].y() - (-1.0), 1e-9); + BOOST_CHECK_SMALL(r.axes[1].z(), 1e-9); +} + +BOOST_AUTO_TEST_CASE(test_build_dh_frames_ur5e) { + auto chain = walk_urdf_chain(parse_urdf(load_urdf("ur5e-real.urdf"))); + auto axes_origins = joint_axes_at_rest(chain); + auto frames = build_dh_frames(axes_origins.axes, axes_origins.origins, axes_origins.end_pose); + + // 7 frames: base + 6 per joint. + BOOST_REQUIRE_EQUAL(frames.zs.size(), 7u); + BOOST_REQUIRE_EQUAL(frames.xs.size(), 7u); + BOOST_REQUIRE_EQUAL(frames.pts.size(), 7u); + + // Frame 0: world. + BOOST_CHECK_SMALL(frames.zs[0].z() - 1.0, 1e-9); + BOOST_CHECK_SMALL(frames.xs[0].x() - 1.0, 1e-9); + BOOST_CHECK_SMALL(frames.pts[0].x(), 1e-9); + + // Frame 1: Z along -Y, X along world X, origin at z=0.1625. + BOOST_CHECK_SMALL(frames.zs[1].y() - (-1.0), 1e-9); + BOOST_CHECK_SMALL(frames.xs[1].x() - 1.0, 1e-9); + BOOST_CHECK_SMALL(frames.pts[1].z() - 0.1625, 1e-9); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_ur5e) { + struct Row { + const char* name; + double d, theta, a, alpha; + }; + const std::vector expected = { + {"shoulder_pan_joint", 0.1625, 0, 0, M_PI / 2}, + {"shoulder_lift_joint", 0, 0, -0.425, 0}, + {"elbow_joint", 0, 0, -0.3922, 0}, + {"wrist_1_joint", 0.1333, 0, 0, M_PI / 2}, + {"wrist_2_joint", 0.0997, 0, 0, -M_PI / 2}, + {"wrist_3_joint", 0.0996, 0, 0, 0}, + }; + auto got = urdf_to_dh_params(load_urdf("ur5e-real.urdf")); + BOOST_REQUIRE_EQUAL(got.size(), expected.size()); + const double tol = 1e-6; + for (std::size_t i = 0; i < expected.size(); ++i) { + BOOST_CHECK_EQUAL(got[i].name, expected[i].name); + BOOST_CHECK_SMALL(got[i].d - expected[i].d, tol); + BOOST_CHECK_SMALL(got[i].theta - expected[i].theta, tol); + BOOST_CHECK_SMALL(got[i].a - expected[i].a, tol); + BOOST_CHECK_SMALL(got[i].alpha - expected[i].alpha, tol); + } +} + +BOOST_AUTO_TEST_CASE(test_parse_urdf_inline) { + const std::string xml = R"( + + + + + + + +)"; + auto joints = parse_urdf(kinematics_from_string(xml)); + BOOST_REQUIRE_EQUAL(joints.size(), 1u); + BOOST_CHECK_EQUAL(joints[0].name, "j1"); + BOOST_CHECK_EQUAL(joints[0].type, "fixed"); + BOOST_CHECK_EQUAL(joints[0].parent_link, "a"); + BOOST_CHECK_EQUAL(joints[0].child_link, "b"); + BOOST_REQUIRE(joints[0].origin.has_value()); + BOOST_CHECK_SMALL(joints[0].origin->translation().x() - 1.0, 1e-12); + BOOST_CHECK_SMALL(joints[0].origin->translation().y() - 2.0, 1e-12); + BOOST_CHECK_SMALL(joints[0].origin->translation().z() - 3.0, 1e-12); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_no_revolute_joints) { + const std::string xml = R"( + + + + + + + +)"; + auto match = [](const Exception& e) { + return std::string(e.what()).find("no revolute joints") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(urdf_to_dh_params(kinematics_from_string(xml)), Exception, match); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_unsupported_prismatic) { + const std::string xml = R"( + + + + + + + + + +)"; + auto match = [](const Exception& e) { + return std::string(e.what()).find("unsupported type") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(urdf_to_dh_params(kinematics_from_string(xml)), Exception, match); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_branching) { + const std::string xml = R"( + + + + + + + + + + + + + + + + + + + + + + + +)"; + auto match = [](const Exception& e) { + return std::string(e.what()).find("branching") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(urdf_to_dh_params(kinematics_from_string(xml)), Exception, match); +} + +namespace { + +// Forward-kinematics helper: compose each DH row as +// Rz(theta) * Tz(d) * Tx(a) * Rx(alpha). Matches the Go test helper. +Eigen::Isometry3d dh_forward_kinematics(const std::vector& params) { + Eigen::Isometry3d cumulative = Eigen::Isometry3d::Identity(); + for (const auto& p : params) { + Eigen::Isometry3d step = Eigen::Isometry3d::Identity(); + step.linear() = Eigen::AngleAxisd(p.theta, Eigen::Vector3d::UnitZ()).toRotationMatrix(); + cumulative = cumulative * step; + + step = Eigen::Isometry3d::Identity(); + step.translation() = Eigen::Vector3d(0, 0, p.d); + cumulative = cumulative * step; + + step = Eigen::Isometry3d::Identity(); + step.translation() = Eigen::Vector3d(p.a, 0, 0); + cumulative = cumulative * step; + + step = Eigen::Isometry3d::Identity(); + step.linear() = Eigen::AngleAxisd(p.alpha, Eigen::Vector3d::UnitX()).toRotationMatrix(); + cumulative = cumulative * step; + } + return cumulative; +} + +// End-effector pose at zero configuration, computed by direct URDF composition. +Eigen::Isometry3d urdf_end_pose_at_rest(const viam::sdk::KinematicsDataURDF& urdf) { + using namespace viam::sdk::urdf_to_dh_internals; + auto chain = walk_urdf_chain(parse_urdf(urdf)); + Eigen::Isometry3d cumulative = Eigen::Isometry3d::Identity(); + for (const auto& j : chain) { + cumulative = cumulative * pose_in_meters(j.origin); + } + return cumulative; +} + +void check_fk_roundtrip(const std::string& fixture) { + auto urdf = load_urdf(fixture); + auto params = urdf_to_dh_params(urdf); + auto dh = dh_forward_kinematics(params); + auto ref = urdf_end_pose_at_rest(urdf); + + const double tol = 1e-6; + BOOST_CHECK_SMALL(dh.translation().x() - ref.translation().x(), tol); + BOOST_CHECK_SMALL(dh.translation().y() - ref.translation().y(), tol); + BOOST_CHECK_SMALL(dh.translation().z() - ref.translation().z(), tol); + + // Compare rotation matrices element-wise. + for (int r = 0; r < 3; ++r) { + for (int c = 0; c < 3; ++c) { + BOOST_CHECK_SMALL(dh.linear()(r, c) - ref.linear()(r, c), tol); + } + } +} + +} // namespace + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_ur5e_fk_round_trip) { + check_fk_roundtrip("ur5e-real.urdf"); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_gp12_fk_round_trip) { + auto params = urdf_to_dh_params(load_urdf("gp12.urdf")); + BOOST_CHECK_EQUAL(params.size(), 6u); + check_fk_roundtrip("gp12.urdf"); +} + +namespace { + +// Subclass of MockArm that returns a caller-supplied KinematicsData. +class ArmWithKinematics : public viam::sdktests::arm::MockArm { + public: + ArmWithKinematics(std::string name, viam::sdk::KinematicsData k) + : MockArm(std::move(name)), kinematics_(std::move(k)) {} + + viam::sdk::KinematicsData get_kinematics(const viam::sdk::ProtoStruct&) override { + return kinematics_; + } + + private: + viam::sdk::KinematicsData kinematics_; +}; + +} // namespace + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_arm_overload_urdf) { + auto urdf = load_urdf("ur5e-real.urdf"); + ArmWithKinematics arm("test-arm", urdf); + auto params = urdf_to_dh_params(arm); + BOOST_CHECK_EQUAL(params.size(), 6u); + BOOST_CHECK_EQUAL(params[0].name, "shoulder_pan_joint"); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_arm_overload_rejects_non_urdf) { + viam::sdk::KinematicsDataSVA sva{}; // wrong format + ArmWithKinematics arm("test-arm", sva); + auto match = [](const Exception& e) { + return std::string(e.what()).find("kinematics format is not URDF") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(urdf_to_dh_params(arm), Exception, match); +} + +BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_non_dh_compatible_end) { + const std::string xml = R"( + + + + + + + + + + + + + + +)"; + auto match = [](const Exception& e) { + return std::string(e.what()).find("not perpendicular") != std::string::npos; + }; + BOOST_CHECK_EXCEPTION(urdf_to_dh_params(kinematics_from_string(xml)), Exception, match); +} + +} // namespace sdktests +} // namespace viam diff --git a/src/viam/sdk/tests/testfiles/gp12.urdf b/src/viam/sdk/tests/testfiles/gp12.urdf new file mode 100644 index 000000000..a8f2bbd36 --- /dev/null +++ b/src/viam/sdk/tests/testfiles/gp12.urdf @@ -0,0 +1,115 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/viam/sdk/tests/testfiles/ur5e-real.urdf b/src/viam/sdk/tests/testfiles/ur5e-real.urdf new file mode 100644 index 000000000..9f71d808f --- /dev/null +++ b/src/viam/sdk/tests/testfiles/ur5e-real.urdf @@ -0,0 +1,270 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 288e9c6753e5649ff1ecd53d793b4669f98a6cdb Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 11 May 2026 13:15:09 -0400 Subject: [PATCH 2/7] add latex folder with pdf + add annotations to joint_axes_at_rest --- src/viam/sdk/referenceframe/latex/dh.tex | 538 ++++++++++++++++++ .../sdk/referenceframe/latex/dh_params.pdf | Bin 0 -> 210976 bytes .../sdk/referenceframe/urdf_to_dh_params.cpp | 12 + 3 files changed, 550 insertions(+) create mode 100644 src/viam/sdk/referenceframe/latex/dh.tex create mode 100644 src/viam/sdk/referenceframe/latex/dh_params.pdf diff --git a/src/viam/sdk/referenceframe/latex/dh.tex b/src/viam/sdk/referenceframe/latex/dh.tex new file mode 100644 index 000000000..944d9fc4d --- /dev/null +++ b/src/viam/sdk/referenceframe/latex/dh.tex @@ -0,0 +1,538 @@ +\documentclass[11pt]{article} + +\usepackage[margin=1in]{geometry} +\usepackage{amsmath, amssymb} +\usepackage{bm} +\usepackage{xcolor} +\usepackage{hyperref} +\usepackage{mdframed} +\usepackage{booktabs} + +\hypersetup{ + colorlinks=true, + linkcolor=blue!60!black, + urlcolor=blue!60!black, +} + +\newcommand{\vect}[1]{\bm{#1}} +\newcommand{\unit}[1]{\hat{\bm{#1}}} +\newcommand{\norm}[1]{\left\|#1\right\|} +\newcommand{\atantwo}{\operatorname{atan2}} + +\newmdenv[ + linecolor=blue!50!black, + linewidth=0.5pt, + backgroundcolor=blue!3, + roundcorner=4pt, + skipabove=8pt, + skipbelow=8pt, +]{keybox} + +\newmdenv[ + linecolor=orange!70!black, + linewidth=0.5pt, + backgroundcolor=orange!5, + roundcorner=4pt, + skipabove=8pt, + skipbelow=8pt, +]{warnbox} + +\title{Computing Classical DH Parameters from a URDF} +\author{} +\date{} + +\begin{document} +\maketitle + +\section{Overview} + +This document describes how to compute the classical (Spong) Denavit--Hartenberg +parameters $(a_i, \alpha_i, d_i, \theta_i)$ for each joint $i$ of a serial +manipulator, starting from a URDF file. + +Each joint's DH row describes the homogeneous transform from frame $i{-}1$ to +frame $i$: +\[ + T_i^{i-1} = R_z(\theta_i)\,T_z(d_i)\,T_x(a_i)\,R_x(\alpha_i). +\] + +The four parameters are: +\begin{itemize} + \item $a_i$: link length --- distance between consecutive joint axes along the + common normal. + \item $\alpha_i$: link twist --- signed angle between consecutive joint + axes, measured about $\unit{x}_i$. + \item $d_i$: joint offset --- signed distance along $\unit{z}_{i-1}$ from the + previous frame origin to frame $i$'s origin. + \item $\theta_i$: joint angle offset --- signed rotation about + $\unit{z}_{i-1}$ that aligns $\unit{x}_{i-1}$ with $\unit{x}_i$. For + revolute joints, the runtime angle is $\theta_i + q_i$. +\end{itemize} + +\begin{warnbox} +\textbf{Notation convention.} To avoid a common source of confusion, we use +two distinct symbols throughout this document: +\begin{itemize} + \item $\unit{a}_i$ denotes the direction of joint $i$'s axis as extracted + from the URDF (in the base frame). + \item $\unit{z}_i$ denotes the $z$-axis of DH frame $i$. +\end{itemize} +In classical DH, frame $i$ has its $z$-axis along \emph{joint $i{+}1$'s} axis, +so $\unit{z}_i = \unit{a}_{i+1}$. To compute joint $i$'s DH row, we need the +geometry between axes $i$ and $i{+}1$ --- this is the single most common +source of derivation errors. +\end{warnbox} + +\section{Step 1: Extract Axis Data from the URDF} + +To compute the DH row for joint $i$, we need four values, all expressed in +the base frame: $\vect{p}_i$, $\unit{a}_i$, $\vect{p}_{i+1}$, $\unit{a}_{i+1}$. + +As we walk the kinematic chain, we maintain two running quantities: +\begin{itemize} + \item $R_{\mathrm{cum}}$ --- cumulative rotation from base to the current + link's frame. + \item $\vect{p}_{\mathrm{cum}}$ --- cumulative position of the current + link's origin, in the base frame. +\end{itemize} +Initial values (at the base): $R_{\mathrm{cum}} = I$, +$\vect{p}_{\mathrm{cum}} = (0, 0, 0)$. + +Suppose the URDF gives us, for each joint $i$: +\begin{itemize} + \item \texttt{rpy} $= (r_i, \beta_i, \gamma_i)$ --- roll, pitch, yaw angles + (URDF uses fixed-axis / extrinsic convention: + $R = R_z(\gamma)\,R_y(\beta)\,R_x(r)$). + \item \texttt{xyz} $= \vect{t}_i$ --- translation of the joint's origin in + the parent link's frame. + \item \texttt{axis} $= \unit{a}_i^{\mathrm{local}}$ --- unit direction of + the joint's rotation axis, expressed in the child link's frame. +\end{itemize} + +\paragraph{Computing $\vect{p}_1$ and $\unit{a}_1$.} Process joint 1 in +three substeps, in order: + +\textbf{(a)} Update the position: rotate the joint's translation by the +\emph{current} $R_{\mathrm{cum}}$ (i.e., the parent's rotation), then add: +\[ + \vect{p}_1 = \vect{p}_{\mathrm{cum}} + R_{\mathrm{cum}} \cdot \vect{t}_1 + = (0, 0, 0) + I \cdot \vect{t}_1 = \vect{t}_1. +\] + +\textbf{(b)} Update the cumulative rotation: +\[ + R_{\mathrm{cum}} \leftarrow R_{\mathrm{cum}} \cdot R(r_1, \beta_1, \gamma_1) + = I \cdot R(r_1, \beta_1, \gamma_1) + = R(r_1, \beta_1, \gamma_1). +\] + +\textbf{(c)} Compute the joint axis direction, using the \emph{updated} +$R_{\mathrm{cum}}$: +\[ + \unit{a}_1 = R_{\mathrm{cum}} \cdot \unit{a}_1^{\mathrm{local}}. +\] + +\paragraph{Computing $\vect{p}_2$ and $\unit{a}_2$.} After processing joint 1, +the running state is: +\[ + R_{\mathrm{cum}} = R(r_1, \beta_1, \gamma_1), \qquad + \vect{p}_{\mathrm{cum}} = \vect{t}_1. +\] +Apply the same three substeps to joint 2. + +\textbf{(a)} Update the position: rotate joint 2's translation by the +\emph{current} $R_{\mathrm{cum}}$ (i.e., joint 1's rotation, since joint 1's +child link is the parent of joint 2), then add: +\[ + \vect{p}_2 = \vect{p}_{\mathrm{cum}} + R_{\mathrm{cum}} \cdot \vect{t}_2 + = \vect{t}_1 + R(r_1, \beta_1, \gamma_1) \cdot \vect{t}_2. +\] +Unlike joint 1, this rotation is not guaranteed to be the identity, so the +components of $\vect{t}_2$ may mix into $\vect{p}_2$. + +\textbf{(b)} Update the cumulative rotation: +\[ + R_{\mathrm{cum}} \leftarrow R_{\mathrm{cum}} \cdot R(r_2, \beta_2, \gamma_2) + = R(r_1, \beta_1, \gamma_1) \cdot R(r_2, \beta_2, \gamma_2). +\] + +\textbf{(c)} Compute the joint axis direction, using the \emph{updated} +$R_{\mathrm{cum}}$: +\[ + \unit{a}_2 = R_{\mathrm{cum}} \cdot \unit{a}_2^{\mathrm{local}}. +\] + +\paragraph{Iterating.} Continue this three-substep process for each subsequent +joint along the kinematic chain. The output of Step 1 is a list of +$(\vect{p}_i, \unit{a}_i)$ pairs, one per joint, all in the base frame. + +\begin{keybox} +\textbf{The key rule.} At each joint, the translation $\vect{t}_i$ is rotated +by the \emph{parent's} cumulative rotation (because $\vect{t}_i$ is expressed +in the parent's frame), while the axis $\unit{a}_i^{\mathrm{local}}$ is +rotated by the \emph{child's} cumulative rotation (because the axis is +expressed in the child's frame, which includes the joint's own rpy). +\end{keybox} + +\section{Step 2: Choose Frame 0} + +Before computing any DH row, we establish frame 0 --- the base frame of the +DH chain. Frame 0 has two constraints and one free choice: +\begin{itemize} + \item $\unit{z}_0 = \unit{a}_1$ (required --- frame 0's $z$-axis must lie + along joint 1's axis). + \item $\vect{o}_0$ must lie on joint 1's axis. Standard choice: + $\vect{o}_0 = (0, 0, 0)$ if the URDF's base is already at the origin. + \item $\unit{x}_0$ is free, as long as it is perpendicular to $\unit{z}_0$. + Standard choice: project world $+x$ onto the plane perpendicular to + $\unit{z}_0$, then normalize. If $\unit{z}_0 = (0, 0, 1)$, this gives + $\unit{x}_0 = (1, 0, 0)$. +\end{itemize} +Complete the right-handed triad with $\unit{y}_0 = \unit{z}_0 \times \unit{x}_0$. + +\section{Step 3: Build Frame $i$ from the Common Normal} + +Frame $i$ is constructed from the common normal between axis $i$ and axis +$i{+}1$. We describe the process for joint 1 below; the procedure is +identical for each subsequent joint with indices shifted. + +\paragraph{Step 3a: Classify the axis pair.} Compute +\[ + \vect{c} = \unit{a}_1 \times \unit{a}_2, + \qquad \vect{d}_{\mathrm{pp}} = \vect{p}_2 - \vect{p}_1. +\] +\begin{itemize} + \item If $\norm{\vect{c}} > \epsilon$: axes are skew or intersecting + (Case~A / Case~B). + \item If $\norm{\vect{c}} \le \epsilon$: axes are parallel (Case~C). +\end{itemize} +Use $\epsilon \approx 10^{-6}$ in practice. + +\paragraph{Step 3b: Find the feet of the common normal.} + +\textbf{Cases A and B (non-parallel).} We require the connecting vector +$\vect{f}_2 - \vect{f}_1$ to be perpendicular to both axes. Writing +$\vect{f}_1 = \vect{p}_1 + s\,\unit{a}_1$ and +$\vect{f}_2 = \vect{p}_2 + t\,\unit{a}_2$, the two perpendicularity conditions +\[ + (\vect{f}_2 - \vect{f}_1) \cdot \unit{a}_1 = 0, \qquad + (\vect{f}_2 - \vect{f}_1) \cdot \unit{a}_2 = 0 +\] +give the $2 \times 2$ system: +\[ + \begin{bmatrix} 1 & -\unit{a}_1 \cdot \unit{a}_2 \\ + \unit{a}_1 \cdot \unit{a}_2 & -1 \end{bmatrix} + \begin{bmatrix} s \\ t \end{bmatrix} + = \begin{bmatrix} \vect{d}_{\mathrm{pp}} \cdot \unit{a}_1 \\ + \vect{d}_{\mathrm{pp}} \cdot \unit{a}_2 \end{bmatrix}. +\] +Solve for $s, t$, then +\[ + \vect{f}_1 = \vect{p}_1 + s\,\unit{a}_1, \qquad + \vect{f}_2 = \vect{p}_2 + t\,\unit{a}_2. +\] + +\textbf{Case C (parallel).} The common normal is non-unique. By convention, +project $\vect{p}_2$ onto axis 1: +\[ + \vect{f}_1 = \vect{p}_1 + (\vect{d}_{\mathrm{pp}} \cdot \unit{a}_1)\,\unit{a}_1, + \qquad \vect{f}_2 = \vect{p}_2. +\] + +\paragraph{Step 3c: Determine $\unit{x}_1$.} + +\textbf{Case A (skew, $\norm{\vect{f}_2 - \vect{f}_1} > \epsilon$):} +\[ + \unit{x}_1 = \frac{\vect{f}_2 - \vect{f}_1}{\norm{\vect{f}_2 - \vect{f}_1}}. +\] + +\textbf{Case B (intersecting, feet coincide):} +\[ + \unit{x}_1 = \frac{\unit{a}_1 \times \unit{a}_2}{\norm{\unit{a}_1 \times \unit{a}_2}}. +\] +There is still a sign ambiguity; choose the sign so +$\unit{x}_1 \cdot \unit{x}_0 \ge 0$ (this tends to keep $\theta_1$ near zero). + +\textbf{Case C (parallel):} +\[ + \unit{x}_1 = \frac{\vect{p}_2 - \vect{f}_1}{\norm{\vect{p}_2 - \vect{f}_1}}. +\] +If $\vect{p}_2 = \vect{f}_1$ (the axes are coincident, not merely parallel), +this formula is degenerate. Fall back to $\unit{x}_0$ projected into the +plane perpendicular to $\unit{a}_2$, then normalized. + +\paragraph{Step 3d: Assemble frame 1.} +\[ + \vect{o}_1 = \vect{f}_1, \qquad + \unit{z}_1 = \unit{a}_2, \qquad + \unit{x}_1 = \text{as computed above}, \qquad + \unit{y}_1 = \unit{z}_1 \times \unit{x}_1. +\] +From this point forward, $\unit{z}_1$ refers to the DH frame axis (which +equals $\unit{a}_2$), not the joint 1 axis. + +\section{Step 4: Compute the DH Parameters for Joint 1} + +With frame 0 (Step 2) and frame 1 (Step 3) both fully defined, apply the +four formulas: +\begin{align} + a_1 &= (\vect{f}_2 - \vect{f}_1) \cdot \unit{x}_1 \\[4pt] + \alpha_1 &= \atantwo\!\Bigl(\bigl(\unit{z}_0 \times \unit{z}_1\bigr) \cdot \unit{x}_1,\;\; + \unit{z}_0 \cdot \unit{z}_1\Bigr) \\[4pt] + d_1 &= (\vect{o}_1 - \vect{o}_0) \cdot \unit{z}_0 \\[4pt] + \theta_1 &= \atantwo\!\Bigl(\bigl(\unit{x}_0 \times \unit{x}_1\bigr) \cdot \unit{z}_0,\;\; + \unit{x}_0 \cdot \unit{x}_1\Bigr) +\end{align} +For a revolute joint, $\theta_1$ is a constant offset; the runtime joint +angle is $\theta_1 + q_1$, where $q_1$ is the commanded joint variable. For +a prismatic joint, $d_1$ is the constant offset and the runtime distance is +$d_1 + q_1$. + +\subsection*{Validation} + +Before trusting the result, check: +\begin{itemize} + \item $a_1 \ge 0$ in Cases A and B (by construction, if $\unit{x}_1$ was + chosen as the foot-to-foot direction). + \item Compose $T_1^0 \, T_2^1 \cdots T_n^{n-1}$ at the zero configuration + and confirm the resulting end-effector pose matches the URDF forward + kinematics. Any mismatch signals a sign error somewhere in the chain. +\end{itemize} + +\section{Step 5: Iterate to the Next Joint} + +To compute joint 2's DH row, repeat Steps 3 and 4: +\begin{itemize} + \item Use frame 1 (just built) in place of frame 0. + \item Build frame 2 from the common normal between axis 2 ($\unit{a}_2$) + and axis 3 ($\unit{a}_3$). + \item Apply the four DH formulas with the indices shifted by one. +\end{itemize} +Continue until all $n$ joints have been processed. + +\begin{warnbox} +\textbf{The last joint.} For joint $n$, there is no axis $n{+}1$. The +$z$-axis of frame $n$ is still constrained to lie along joint $n$'s axis +($\unit{z}_n = \unit{a}_n$), but the origin placement along that axis and +the direction of $\unit{x}_n$ are free. Standard practice is to place +$\vect{o}_n$ at the tool center point and choose $\unit{x}_n$ to match the +tool frame's $x$-axis, both supplied by the URDF's \texttt{tool0} fixed +joint. +\end{warnbox} + +\section{Worked Example: Joint 1 of the Motoman GP12} + +This example illustrates \textbf{Case A (skew axes)}. + +The URDF declares: +\begin{verbatim} + + + + + + + + +\end{verbatim} + +\paragraph{Step 1 (axis data).} All \texttt{rpy} values are zero, so +$R_{\mathrm{cum}} = I$ throughout and axis directions pass through unchanged. +Cumulative positions simplify to the sum of \texttt{xyz} translations: +\begin{align*} + \vect{p}_1 &= (0, 0, 0.450), & \unit{a}_1 &= (0, 0, 1) \\ + \vect{p}_2 &= (0.155, 0, 0.450), & \unit{a}_2 &= (0, 1, 0) +\end{align*} + +\paragraph{Step 2 (frame 0).} +\[ + \vect{o}_0 = (0, 0, 0), \quad + \unit{z}_0 = (0, 0, 1), \quad + \unit{x}_0 = (1, 0, 0), \quad + \unit{y}_0 = (0, 1, 0). +\] + +\paragraph{Step 3a (classification).} +$\vect{c} = \unit{a}_1 \times \unit{a}_2 = (0,0,1) \times (0,1,0) = (-1, 0, 0)$, +with $\norm{\vect{c}} = 1 > \epsilon$. Case A (skew). + +\paragraph{Step 3b (feet of the common normal).} +$\vect{d}_{\mathrm{pp}} = (0.155, 0, 0)$, $\unit{a}_1 \cdot \unit{a}_2 = 0$, +so the system becomes: +\[ + \begin{bmatrix} 1 & 0 \\ 0 & -1 \end{bmatrix} + \begin{bmatrix} s \\ t \end{bmatrix} + = \begin{bmatrix} 0 \\ 0 \end{bmatrix} + \quad\Longrightarrow\quad s = 0,\; t = 0. +\] +\[ + \vect{f}_1 = (0, 0, 0.450), \qquad \vect{f}_2 = (0.155, 0, 0.450). +\] + +\paragraph{Step 3c ($\unit{x}_1$).} +$\unit{x}_1 = (0.155, 0, 0) / 0.155 = (1, 0, 0)$. + +\paragraph{Step 3d (assemble frame 1).} +\[ + \vect{o}_1 = (0, 0, 0.450), \quad + \unit{z}_1 = \unit{a}_2 = (0, 1, 0), \quad + \unit{x}_1 = (1, 0, 0), \quad + \unit{y}_1 = (0, 0, -1). +\] + +\paragraph{Step 4 (DH parameters).} +\begin{align*} + a_1 &= (\vect{f}_2 - \vect{f}_1) \cdot \unit{x}_1 + = (0.155, 0, 0) \cdot (1, 0, 0) = 0.155 \\[4pt] + \alpha_1 &= \atantwo\bigl((\unit{z}_0 \times \unit{z}_1) \cdot \unit{x}_1,\; + \unit{z}_0 \cdot \unit{z}_1\bigr) \\ + &= \atantwo\bigl((-1, 0, 0) \cdot (1, 0, 0),\; 0\bigr) + = \atantwo(-1,\, 0) = -\tfrac{\pi}{2} \\[4pt] + d_1 &= (\vect{o}_1 - \vect{o}_0) \cdot \unit{z}_0 + = (0, 0, 0.450) \cdot (0, 0, 1) = 0.450 \\[4pt] + \theta_1 &= \atantwo\bigl((\unit{x}_0 \times \unit{x}_1) \cdot \unit{z}_0,\; + \unit{x}_0 \cdot \unit{x}_1\bigr) + = \atantwo(0,\, 1) = 0 +\end{align*} + +\begin{keybox} +\textbf{Result for joint 1:} +\[ + a_1 = 0.155\,\text{m}, \quad + \alpha_1 = -\tfrac{\pi}{2}, \quad + d_1 = 0.450\,\text{m}, \quad + \theta_1 = 0. +\] +\end{keybox} + +\section{Worked Example: Joint 2 of the Motoman GP12} + +This example illustrates \textbf{Case C (parallel axes)} and reuses frame 1 +as computed in the previous example. + +The URDF declares: +\begin{verbatim} + + + + + + + + +\end{verbatim} + +\paragraph{Step 1 (axis data).} Continuing the cumulative sum: +\begin{align*} + \vect{p}_2 &= (0.155, 0, 0.450), & \unit{a}_2 &= (0, 1, 0) \\ + \vect{p}_3 &= (0.155, 0, 1.064), & \unit{a}_3 &= (0, -1, 0) +\end{align*} + +Note that $\unit{a}_3 = -\unit{a}_2$. The URDF deliberately assigns opposite +signs to the shoulder and elbow axis directions --- physically this doesn't +change anything (an axis line is symmetric under sign flip), but it does +affect the DH table. A positive $\unit{a}_3$ would produce $\alpha_2 = 0$ +instead of $\alpha_2 = \pi$; the final forward kinematics would still match. + +\paragraph{Frame 1 (from the previous example).} +\[ + \vect{o}_1 = (0, 0, 0.450), \quad + \unit{z}_1 = (0, 1, 0), \quad + \unit{x}_1 = (1, 0, 0), \quad + \unit{y}_1 = (0, 0, -1). +\] + +\paragraph{Step 3a (classification).} +\[ + \vect{c} = \unit{a}_2 \times \unit{a}_3 = (0,1,0) \times (0,-1,0) = (0,0,0), + \qquad \norm{\vect{c}} = 0. +\] +Case C (parallel). The axes are antiparallel but that is still ``parallel'' +for classification: lines in 3D have no inherent direction, so the common +normal is non-unique regardless of the sign of $\unit{a}_3$. + +\paragraph{Step 3b (feet of the common normal, parallel convention).} Set +$\vect{f}_3 = \vect{p}_3$ and project $\vect{p}_3$ onto axis 2: +\[ + \vect{d}_{\mathrm{pp}} = \vect{p}_3 - \vect{p}_2 = (0, 0, 0.614), + \qquad \vect{d}_{\mathrm{pp}} \cdot \unit{a}_2 = 0. +\] +\[ + \vect{f}_2 = \vect{p}_2 + 0 \cdot \unit{a}_2 = (0.155, 0, 0.450), + \qquad \vect{f}_3 = (0.155, 0, 1.064). +\] + +\paragraph{Step 3c ($\unit{x}_2$, parallel convention).} +\[ + \unit{x}_2 = \frac{\vect{p}_3 - \vect{f}_2}{\norm{\vect{p}_3 - \vect{f}_2}} + = \frac{(0, 0, 0.614)}{0.614} = (0, 0, 1). +\] + +\paragraph{Step 3d (assemble frame 2).} +\[ + \vect{o}_2 = (0.155, 0, 0.450), \quad + \unit{z}_2 = \unit{a}_3 = (0, -1, 0), \quad + \unit{x}_2 = (0, 0, 1), \quad + \unit{y}_2 = \unit{z}_2 \times \unit{x}_2 = (-1, 0, 0). +\] + +\paragraph{Step 4 (DH parameters).} +\begin{align*} + a_2 &= (\vect{f}_3 - \vect{f}_2) \cdot \unit{x}_2 + = (0, 0, 0.614) \cdot (0, 0, 1) = 0.614 \\[4pt] + \alpha_2 &= \atantwo\bigl((\unit{z}_1 \times \unit{z}_2) \cdot \unit{x}_2,\; + \unit{z}_1 \cdot \unit{z}_2\bigr) \\ + &= \atantwo\bigl(\,\vect{0} \cdot (0,0,1),\; -1\,\bigr) + = \atantwo(0,\, -1) = \pi \\[4pt] + d_2 &= (\vect{o}_2 - \vect{o}_1) \cdot \unit{z}_1 + = (0.155, 0, 0) \cdot (0, 1, 0) = 0 \\[4pt] + \theta_2 &= \atantwo\bigl((\unit{x}_1 \times \unit{x}_2) \cdot \unit{z}_1,\; + \unit{x}_1 \cdot \unit{x}_2\bigr) \\ + &= \atantwo\bigl((0, -1, 0) \cdot (0, 1, 0),\; 0\bigr) + = \atantwo(-1,\, 0) = -\tfrac{\pi}{2} +\end{align*} + +\begin{keybox} +\textbf{Result for joint 2:} +\[ + a_2 = 0.614\,\text{m}, \quad + \alpha_2 = \pi, \quad + d_2 = 0, \quad + \theta_2 = -\tfrac{\pi}{2}. +\] +\end{keybox} + +\paragraph{Interpretation of $\theta_2 = -\pi/2$.} The URDF's zero +configuration places joint 2 ``straight up'' (link 2 oriented along world +$+z$), but the DH frame convention puts $\unit{x}_2$ along the common +normal --- which also points along world $+z$. The $-\pi/2$ offset rotates +$\unit{x}_1$ (world $+x$) to $\unit{x}_2$ (world $+z$) about $\unit{z}_1$ +(world $+y$). At runtime, the commanded angle $q_2$ is added to this +offset: $\theta_2^{\mathrm{runtime}} = -\pi/2 + q_2$. + +This offset is \emph{not} a bug --- it is an artifact of the URDF and DH +conventions disagreeing about what the zero pose looks like. Published DH +tables for the GP12 typically bake this offset into the joint angle +definition, so the ``canonical'' and ``URDF'' zero poses differ by exactly +this quarter turn. + +\section{Sign-Convention Pitfalls} + +The most common errors in DH derivations come from sign ambiguities. Three +rules prevent most of them: + +\begin{enumerate} + \item \textbf{The four DH parameters are not independent scalars --- they + are the components of a rigid transform.} Flipping the sign of + $\unit{x}_i$ flips both $a_i$ and $\alpha_i$, and shifts $\theta_i$ by + $\pi$. You cannot flip one in isolation. + \item \textbf{Commit to a convention for $\unit{x}_i$ before computing.} + The ``common normal points from axis $i$ to axis $i{+}1$'' convention + (used above) gives $a_i \ge 0$ and tends to produce clean tables. + \item \textbf{Validate by composing the transforms.} At the zero + configuration, the product $T_1^0 \cdots T_n^{n-1}$ must match the + end-effector pose computed directly from the URDF. If it doesn't, there + is a sign error, and it is almost always in $\alpha_i$ or $\theta_i$. +\end{enumerate} + +\end{document} diff --git a/src/viam/sdk/referenceframe/latex/dh_params.pdf b/src/viam/sdk/referenceframe/latex/dh_params.pdf new file mode 100644 index 0000000000000000000000000000000000000000..6e55ef2f4d731222bc38f05b2e2093acadd62d78 GIT binary patch literal 210976 zcmeFZRd6ItlO-x_F}1MOf)clwnVA{8#mvmi%+z9LW@ct)W@cv9)i?jl-I?97Yx}e> zceAW2BO=4RGLJ|4@$?8!5;-9eYI+)GSdy-%+)r2rMgSeaTF(rYiwi(2Wol)pYiH_a zXaJ!9ssR}2>DXCW0JLHNbpSm(Jsp6NfeoMupp^wMumWg>0rV_%Y%ELwS{VQvfL7_B z?#wLg03IG#Lo0)SWCH%rZLkbX|LH=MTx|>iv}y{5Mqigx6u ze~Cv(48R#3a8yK;%va#y1(9_eiGq5rkFzM47@o*U! z=^N4;(6Jk^>eA`cef7|1V`HYHXVNv)XJpr7X5i8MM+x>0c80o^urBHPdImb%#yWaB zI&3h6D`xD>&+2SIQrqCq}xc zxc&HuBB)J-y!~xb&|4^!=YIyozn{+k`JwSYqx^sC{}+M(i@^WS5Pqw&bP#lq^?bnS(h_|Uh7DS}!HA7zOheqOV*($j@;*SH;21#pNX*@H3-_BF zMwnbrG@k0vQ*f|2@|;#tX7nv#<69B%w2RSNzNfk|4$+em-2{y0GGb`&YbeJEUkV7% zq7XKoqjF0N6LsN|Yb+x&_3v{guQ>^!jWa(JLhoYea6m#s{7Amk0G(yvD+j?CG5(?$ zIZXJOX)k(5e_yq8Fz}?5nFcrc@o=Jc(r0Q*j_%d&1A^I{5@atO&po$8wnZ2X%5}VS z$<2hjxE&ZpbS8k*k7PXxtnM7*Mi7vGV;zk3%^!^w1CAC@oDW@TsihpNBW{i`S7%bEEXH5=MnJKE|0GX@y{k@&^d|I*w)+WgOI z`$zEqr`rBQQOsX*{xj!JV2?Siu{d2-ZCB2V_iu~)oSft;4oSBqr;uhQ&anq4>ZB-! zDv6CcalSln!ufnB_m3kavo|90gRt>^^9mIT4-w+kiXocn($sEm{Z5rjp{o>j{K}Fm zMZz(b%ajO1#?YE6%6fyeVAf$8ZbzSD*Sm}V*L4o9&f`RjcB}P>my9a%jzc?TaUQ`d z@5WNIV%_2r59sFX%KY;1dZelvCZa^Fkq!A^Va zq(ic*^O+zX5fiax3@wD`6F+R!+(Nf$_o2QsV=&~%v{Wff@6LY6l4dLm-#Smfk-VbN zxZc)Uh0UVM{M{c3bUA{m!~J}I^%cAIvh-Cx0NX5n^D-U9(cQ$n@ZLIfJgeN6t-!RJ zaTBHEgQw5oitR-O;deKy;pt`NlM#hNFCkX!_X>mz0D&QwqjLlao3_fdLAYP5c*QtQ zr(lb`MOI5SDV&7jMABB~fjWfhRRgj3mWMo@)64~W>N3b4ZC!>9Mac33-{N@011zFw ze-B93WrdJ!t!XP$haz##{;7zm;=DaaK^y*Hl+vX9G3#mi2N}J{%mu%Qx0=!!zx;C< z#YU1!T5rH;)G>~p11*!48x10tE{9$xXZJB}(6>4jZmP9+3hB~NoBcWs-4kbBxy(#g zLeUZ%sF0(Zq-Pk z1e*=~8!J*RcIN9KKC8~u%@0p%0zwL1mQSACAq3~jXH+7SFb!yxqG&pAqkEJ(dDax$ zs}(X_B@Yh1Ha-T#{vyfUEVcc~R2smA?(ZLEl5=XRi%d5Ej4b#|5+X?(tth5uwB70> z8d(BLlshOY4o3386grXv))QOg+#$kGFPJ7XD@fk0bUCtx{Lye_J|%qTlYC5#kl+vY zYWSqUrpnJNfyECs=m~F2s&32Yhf|4oPy?GVunXimmLAP0`PwGatoyhax+H?Q@4N8M z&)5Q}1iOavpOj+|wD~ zF6U7WXI!k~Xv-$=EHx4Pb;?Q|?nu~DJyLKA3BgZ{X5;0(Fn$aP!IjrZO-(0}C0JO- zz|^0ipc4A&$)~oEiL|J>jdvh9xw|Q$gO{EXC@W``@)WA2w6DxxLI7&_R2ph#r26NW z2vQ=%1V|j0KATjbxU(sbG2JLMhJsSL9O9Iq^rwjgoC8X@z)crVsVcvLPop`oaVxTi zoQBg$ifiQTGkx1K2(lOu9a6!$x`#~SWEVYEEQnLe5b}sfazFco*MUq=UMNkjNGxQT%TP(JFx9M9u&LJtG&6!hP1?I&0m7jQhEya1{iTNM=l>CL5Jytq8-fng$ z9tMWsVD;(vV)bCa%@~GtH}woOZ5_5gj$&0e53U+dZE(qH?=?d*kffSOE~Af^rjyg&xfl*ICnZc zzt13}?Y#F@iqW(Vv~m=-jvlqk7D({-Uv!820q^9}5H2a3r7h%T7>d}11<^4&bhKuS z_JqDw!}uO}~}TLQpE7p>=@No^fA7$h1vu-JPD1y1bMAljg~)_U%F>F^sCncC~#zP z)n6a9Rjts2&67MLHacf1p&zA!+-^`$yOcf#Av(1>g$y!?Rd-iU;l7g|=+J4x!aMmN&-G5qoKJ>k zKV1YJwpz1x+W#PsoMqyk2pTb7uGYwd9&`oKrFi}sdpIZ0J<-51B1H^J| zYjali=Zg)*p_HboW1V%^6LzhQafDgnGOoNVpjCVUU$oWRi+z5 zR~fT?#|+l?thX5i2cEEqP957eoJr0VShVIk-#q&3HbGP?hEJkSRwZG%&MFhbX)E)f z{PnrHxJT*GS|Tol5LMh_>#kWpK|~J@1`{_JhGYLqvg+e4HJGMa!EvYx8M)gYX;3rO z&sPb)dNBs-uxLRkX+UQh7%!}A{UMk|ZZOi`+QgY`()u=qR$_y@kr@*#<}=W)vvDRx zc?6vY05b%31uY-k%wtG>LwnsE!bR$cYeV1kSV_!j+kL$fHdWF2Vbr;3^>fg5rxs#n z?0dEH#n@PjIq}o!isqmW93yjFJF>?Uw?9u1#EZ6MU9f2SSP^nLb;#5SmI zCdj%bS=nvab=rS}$-Gnt)|3q+tleuRx@VkPA{aK7n9p6g>!@d&52z3Ds(>$r8r{3V zcx+jLcrFsW77JbLnqU6%R7&RI3xmP##`Sy$>Za<6=F`CQL;@;D&km}8J*5iZrU*yd zps0z74cvQKz^fjAT7i=O;XviSIUpCmb-MZk{qrtuI}1|74G)dAr`t6Q^&nF0hWH+i z_0Ahs6rT>YK7}>&U6yv3z<&C5{cWWU&>_-VyA@O=KF9RAj!Qwh_Wr#x&DNU3o%Hg< zXhS@C1vT;#pMg;8`7zn}vG8VgAGqJ=?|m!3=Y9J_dLqb(S`SOaw^ZjipZx4|Y*G8} z@O77V;_Wx)f8(LD|L?hs^k31luVC4~d-@CjcD65X_1|m%#N__t5#Z|~h3%i%)BgzP zL^eXoX{=z-NZG*1*qE;8*g7v|_hfv-J{crwZsUXq=7YZM@e`ch{;nYa*0X`1lETUO z^y$6ezMxz*)#P#UP@x(8S3x>nx%aynVqBnr#&7mzA3qRsbOb~m5ai*3ZxD95v$JNt zniu@uq4K6%KIxj>av|GY@cHTdMwL?xri@F*oanzGvX70Bwzt7-u3_!2VZeMrWB_v8 zyg_ot{66(5oXg*{d%wvA2=LJq*DJ`0(i&GcM4s8F0^7l`sIWkBz`#7Hyqm#^arh>6 z;25F#2F4e@?O&(Q^p4|Y!!&^SYjk{4LikrlmX+lJINO4Qq0&0{toUetCYTFUXmF3G^ZOY4axa5H*t$O2_^bJ) zgHDZrroxW;EJXo^vj#`Kv8zEoIevmb{T$lb`Mmwag@%9WTN&>KJKZ+NUS-5)gi*|D*@BuXRE$hU$N#)qxCB`}1Md zJ3A4p`4h~^4xC&JXn0E{@F8l1U*VaiU%?b19Dqmtqa7}8XH5o502YwdTs&N zwiYcW>OO6OiJ@JFy?+lrz0f;E1Z(DK^Y!QeRytG;Tz^GiKZ=Yqb+q{*q$dteMwx{&6WKVb@+knj8L0wM%DA!vx zN;y;ckf2zfJIw?!P$oC;+t1!culO`TZwMgn0dVjJNG-NFvH6L_+=u@Pj9wiFwYYjn z>R~kA(8zkJ0`uGi8wRGH`h2ecMvoy`p4jnjfUPu|atDCcGy>nSdT45OWMc}jmlt{u zWozHbmp(fT9(AC_5Kh59JQTBH{9>?F6 zU(o_tuvwb&K08uXVJOt($r%U-R8HFvZ|m<^u6VTW)zJr?^bC=fI=z-~RcrehZq&-Q><`1_ArDe zoj9Fxg4elx=pkr3*nM%^V8I`Zea-Wj`~FNKz$qg(%)%OV>|=FPr%c9J>KZ0o<%25l z1yFlJu~z*Toe<`Vn#KQsy2LLCB%+y4|7G2ChDZ|HG|5QnR+$gnKC@xvIc|_Zx%Rro zUxN=ZkN4zWgqze>I64#p{<~F|aRYqvc#QPm>(Yr*-;ULzO@8WFC33pIqow0pn{OY9 z?2n1(@q{~?EdlH^2-`B*(iq5ybLqOL03TT@H|{I89A;m-`isGhJto++&IZAkRpoP+ z!0L;otqSK6&UvpHeofL`^>;AYJfTf5y4>Ob^^^u)NhTaV_g~^N_fc^_Td|{Bd(dpP z4bVUQXncYhU848Mz8q^y-$YX;qkOS;5w`D3GXTHd$W-szZBU*}vLsR3j^W*Y)eA({ zwwRiF4%p}@3I~GmlteAz!GTnrherk(W$OXS6+6H{KJ>L%Okd26wm13m4H48ruv+z) z%gaLGxjHIj^!pBE8OTlB)fwn#;!}O^$qmOsEv|?zEHmoS2Qh2=a{SC54PF8&`E3AO zRSJYsP*JgtIovvltv*fZE343t3W+&@Nax@9o7gzXhyLv$L@_+oQJl*53OR|0vY#aZ zW+8=FWfyWlq`-i|0oqlY_LsQ{6EX^^1T!g&7UGx*KUos@>UP~ z$aPkSXBF~%25~OOq~l*MkNbbKhenMF!jJdo#?e}q7~&Ohxc%WS1Mg7>4X#Wm;$hrl z5gZqjqKZd?150jY(c;4Ypl&vithTI06jOPz_^stG6U?ejWo*(STu?2&1a|SauI8QM z!Y}Jm;6N|BLMdU#BF>Gzhp2R+5k5KYTl_X>dH&_Oc8MKp-RT_Eu>GNrxvsxwUS=Ua z_=oL6oSgE9SEHK)ByRT8>0$Qz_*>s}0{*Ya=C}q`dHtNYW^AFTc@|5`kYz0QEY?J+ z#a>#TvUF{lR})Fm3L~%dNF!`col|YD%S?qkhvV@IThcA}29ycjo=VPg;rp;EK_a2J z4TP(Lp#~b`?Zm9f>$KxPeCE|RiIGe$SM@n>jK{cvf8|noq6wp9Zda&b0%Z!mYdA*5 zr*b|o0PY%DF>Qz#bs{7427N`la${#Ko3VV!%-p^U_01k4wO~n_MD4kwhlX)+;hQ5@ zZ1vudK>QgSQ5BIAqlXxzmf50a4ydic7>27tC5T4R6}fE^r>vwoO{1NE8=G+X-dZFMTOs=ddU9PFfApiXoA|T%<0%KDmJ|{|gpUQD>^X`^{m10g zz0mKQ$!hRZGQ%)b0nXza9RH?x>cb1BVr!x+x?&C_dd3&&K0~ zkkFYDuGmi0fPJ%i;#AkuS{nRRRx%|uIZTeduizwQX>voO9H&cYNa5n3R2aF>auUqW zPlW8M9$4*12hbAlhoGIJZ%A^c+NUW{OZh6FL66^xaA@A^fx|JqGy~>Ea2?z81EYp> za`ol}5hGOYyUr;dB<-Z>6oecQ4icYCJlaPmzt;va#*l<{H%;dSG+%1uqk0k=qoBvv zCbCwx)dS7#IYSqoKtW z`~H}$H;*k2EN4>bnN&PhHWL=S^oQT55@CQ!pw5j!)BDSuP1S41cL^&BXM+8G*AiKY z_Ac`%i%6rVaXC^jo3SPKZ;q##y$U=9&ja44hPZZ^Ii!ihDkU2VWKfO#*=pzihf74%z9xS z2Krd^1#Wf1RHI&|?GsBnwWmOV^PyF>b+34R$4dL;6FUBs=G2geCOg(i0el>yOoUq& z{lqXI411QIp`zCt;}9jM(9n_FA-wqJnkkd34-v&Wjj~|(SA;8^LMEmJ=*V?lL}*e% z)xus}q|Pjw(Qoy!rTx(f??p-93;F22wuwO6HqC)4q_^m=`|@$U$U zV7OoPJ(7g7m|8!oB}ueacH1%Xa>j#pSyY^RI9=vcWV=E}kFEqwdxvl|I=# zp+5$4_2N@!bhm=f9LAWBDvEH1reeJU+TOD%8d;wMHw7ZbAu3077I8lYdj%y;&MPjG zt%OjQQ^gUpcIlp#?~ueCDD@zk8$Q_jDizxJHM-biz`T&5()|`jS5h62RWFto*Uy)m zHDcNIQ!~Um)mmu5cuVRVW(Y&=|0==oqsg75eP%kU>4h>Z4Vk}>;dn#c3pN#wOKu0f zZiJ8EBgTdhJEAj40ODI`JxXBttntj5!6SG(_HWH_SeQh4StcUgqNWZul}nmJepvnb zF!GUq^pQvQeW#&T^`M6xt0N^&WZ9GK3f{n4vBEtpLo#P0FW4c+xK>V-4mq+J{*I9A zS$9&5T?Ol3_Z|envD=r=w5HT*rcUbwDe#xh3jp{vx>vA=APtK;*0Ffl*idd!)wB;J zly228ZUnuw`W$W`Pp(`{;K~2fo#X{MX8KXn-ldQiRkXPI6`@Vcy&^pPC1l}b-f7zw;%8>e+OKARW<=fatz#O$(i)ATLzSswuF|3IuL6Im?pRg*hwNK8%rGki_F9qhg`ivZl74q1lYq6aCsl5RsV~Y8o}kJi z71UFcwZsok*7tBSPx)(-Pdfin=)PsRXy;8jdYrink5=pE zOP0BIp~cByj$JsTtBr?vL#;l7MiH-?O_v53j9XrtmyPilE?r#(03!tO%qwbU7?_6PBUqLfY#56)5|G8qO_u zApOj3mcI(k4$6Yj=dmX^NS!%GZ~*%jo|LB9b2@6A2mSYMHVdRh4?V~XdQ3cXOXsFO z)*l7CB^$w(f{u1h*Y5EL2pNwxaWVFe{3E(ndW~Gx)R(m{uj`^k5N(h)P&eg*ZOIU{ zKc9$t(pbBHFaB}1?aOZEF4ri0G{q2ZIJXQfeS-R6W<@vK^{tOwzph-L+0!MI-3XH^ zXVzb#4S5;KyUHpU_jOjAkNsop!#T9M-RLG(QuqlDqr1aF^#d((r2MFeZKCNMe2oe3 z3r~tLLc1+Z ze5*ql{@i1Sd^<%wKEGubD8Fi&TAK-U*e`>gUmPR^4%<|DCuBcsBi1;`L_0O=dOUVL z6kP|xjey4f+q$;-FTsyFCuV)J;l;wEMjCviA2Z#xk%vDMOLzR? zmyM16L-aM>W|m(phdJ|VsQ^5W775z$_VhqjB7VtH&1z<*8FRUA9|M_iK#-zoNpOMT zUfm6cC0!z<{VDb*yvPgwqdH_VnNw^%i$3E~lk`9#mgzoH`wPA+s<<&gLDbV+ z^O=;J9DF?gflw7Y5=jgZ;==Vz&CysKNB%B*6!xxk+jOfPO)Skqt=(^|&v^#CDeO-- zoFSX}aL8nOD%xjQ>DwQfnvSw1IB|Y~1URF6uJU2>B7yp6#X(_uDnGqSI^N`ydGv4&F?+$u z2h1M7e9?m9wz*SrpZn7=qtx1P5J$+i>h#oloM~`D-zcdXYGusHFki{}sV#g}h6#Nb zsI*zch*1KFGhrjyLIFpVm5HT7#Gi(jgv3TsDQijo1q>z++kXg@k!=OcJBcGN`5pYW@W7Z$!`Lg0 zLi%@<>!}EM*B&I`af1WZupC)H4d-j~q4h3a_PP&qQF{73nz!lvaCr9{`B%ve?eTB4 z3ZR=jL_U&o*%w_@5^Gc*9rnhw)XV0ovX!}0!)FoQq67`id{Crx?HfJAgj{jY4jlH? ztS0BLX@18T_u%?^kkP{l7$WJS>D!|AX=VDh%47?y7{dgAdvvSgocwV@EILOPgEc3g z4Ii`J0$dn7-4-2yOz&^PJL6!n?!7a^&L91mM_;1Mpxx%laZ>zK}j#nwN>k}PCk zHy=zLSIl+EPgxpZ4V+@gMP3WG>?B3f*$_N+Ca-HLYYDOc=)rPak5xG3DtSBZpZ4SD zFD@Q9`8nk@?=m;4W-vkMjJz|W_do7j<5?`K^H8Iplh^Y4Po|?Xse|mOddm-76$DLl zJGuLb?=?sI7|n5Pt0YKyLU+z*?u<#m()8D=ru;@={gWV@{bInoO{`g$=*JR685jUH zx@mI6e27aKmPpzjTWI2>L_sQ6r3WU=V$vkAV6J0079*lfgp1?JyzSr7P~%mTV(YC@ z6ncqkGXJ-hK1iQ}Zl2gyCWlJqHa69gYag?AMaz7L6K-@CGiwJf%J<-|{v`7~^qKv~ zew6W-L#_mcWRn`!EE7NJQg!E2!xxEdUvXf z9u1a_yOQjt<6Ce!$IJLUHA8ZUD&n`h{hGnzI(-zy`X}99Y>@($gxg&xnlRL?q5M}G zUPXsq`y>x{DJRP2*c96~xnyGPWOX;;9JI#}H#8@@%zG5-as+SU{35Jz|4fHUuG3e` zun*?XrElCg$wlQ?=~{-X>%){FULO`kUWh%sJd}#$JLcCD;9cr|bm0hchUw0RmV6|< zuVxhcCyxdNn7Px7b5iEYk3d%=%f6DwYDM_%s5d-VwT699;&g-0Y9XbvviM_ z`o}AI{qoR-IWMuL?AhJI%y#_84SvJd2y-~}Xl5N;+h0(#? z_UAqG`&&a&25{zKn_M$f;bmMryN*-@-dQ`H^j2tWU^*aUBhqc)daUiQXpA~0LoZBa<5+t~$ID}jd4EssB z9M-Vk45l+igP7@`E9U61l<%+%`{0=3Ltt$7xs4rpamh1zJf#wqanl;KxC|)gOKv;h zM4k5bt26iP%B_u|fwj$xGB4Aszu*e8AZ@Cy^0;vGVk%!G;@dZpuMBn(8#R3&e$Q2N z^iQfyif3dfsMO|R&KVIoSDi^JQK6%3hyVSX+Dq6m-c}Cx*HNm^!R5!rtr(sadN1G? zEUPAQLCPn47xN_vpKDZFF=U-UI#wTYLvj)=x5>Tz0<05oJXUI+r)j)bXnb={e}SGA zHW;dRDh4S|n%sy$DwWBaKw*^wM$=-|*9IxM?>k0XCmuW%&&L_kle&%Ssxd9KqgvQm zK@BEPM+}#ETJi4_3kgnzm)-Gl;?}6e1&&8ea$5qT4#a_^P?Xm1;dV_4I!6Z7V8+vv zZ-KOz$sC411@PYz*U8ziGv8;um{xY6mlv>2KiI}4=rO-0)fYn^>$0@Oy;Y<6uuwmb z#1-~V0--auDP~J^C32zy>?>ssKVka81sH7QeN{?H36n34<`Mc&`wpPn8tPZ5R}fkd zO1(_uWpKcj$W3GP^AmA)53Rw>N8Gu`*}_HtqS(y-ovNy~NIrqwWjuXN5v#8PFMKCP z`|K7oMb=lxw@POTe(h`Ar)rgpw=(jUsz1EfM-;u<#;9ErZ%-m6JKSr@>1ra}0s~$W zK<)?**fAlMYG8U>xa^)YnI4Dy2jETyhsLmT6OYzmeC zTlFgys1>teXErXrd=_TC$92uJo5I9qmro(5px{Mq)|(k&J6qRTu1$SCIf4XNWMAbj zDQV=-^7(tXo>)MT{zUK_nJCtqy8a|?1|MjM9SK&6305sOieBbqVp_aH;GZ(_>QIB5 z=EkNN@Da{{aWHb%YKgucT$rG_8OKb2_7V~hYsH*D2cs|~q_4U%wn3PmYr)thj+F6| z*0YA_lXiN5@Kwy(QLV88mdcL#+S6NA$fH=f2M~pxA1(3KOqU63NP{&{TR}Do1;OGS z={yx+O?>nUDI%nhu@^|olS8s33-;8)UC&L)Z?}fpOG8)F-Z*wOTJTt^&1U`JQb9_w z7NSQ`Ss8ZNTZ48Pourp_w$nr?GA^tTaUhbjVi}DtL_~t|>Nk2B}9!>-o!T0RgyF z&1nv&uHC=L+gF@~oEdqSfh7EIivtcq=6oKm1ELio@=V?Pk$r*kyn6-bi8bru46boU ze*6j5Uf<(L+Fjx#za6&=BmTn8;UnT8I@&V~wm;|=o3q6ts(sjX_|a;Yq@hWIt;59< z_BK=Cz?xkc8r>~xST^~%j#UAR461IAYaxf1)yF|H1NBl`FOgHU+eIafdavvZVU4!4ssqQPJfZfs|r|?!78#o^t9cT!o z)()k%P-ix59txm@Yocv1JbTb9=B(NMlW)_>pes*BY`ZZXsM)sSx-FZqt4?*~`2>Vo-xj4(*&_m7;X6_LGmCc7* z^Ob@(p48n%Al7N=j%6}70+92p4U7rnZ__+Kb~S$%Y-lRjX_xzn7h!)Y>+-UjO^L>C zE-I&-Yq|}QDrdJBJhJ!JK$BLUwBQ_(_>dFBOHRlpy?K0Rxtyily$PM|+)<}Tuo>2c z+gdK2ooZl{Vzzu^v~VHOC=@TgdUYHhR>f&#r(3MA<7Yg>nq1Lp{DY8#kY58c@kLFk zUiTlkxiIry2?jzb{WwPo1)T3}xP6;k)LIHjEkPLYW9;LcPC8S)B6xB_Y(J2Vqs%(H zJLLtM!YuCm1{aeXG*ks;nh@%`QI#0+aGbVM%s)Q;4K3XoduL9HI)g58OXj?Ua(Cuy zp6|I!<9XQ4KHgU`46ROzrN{WbIh&GOh$4zz<2Z=4-853QBiiBBxR@w&~nW4KW z6sdb^3vNT^iyi;mw3JndrErU#;oEUe`W=X1`d5IgWF{${02A(SGVZVHX%#J0JR$Ce zL$`1;&6xuxtM`0o?Zagm?5V3Or7pb|tMug=sB$CU;S`8I(dWPd_;@;@XJv{xD;zF39}pc1&NQ96x9v#dIiC-jhw%}DM;W9)XG6^7$E3H zpt?}VigaXriziPOD`#gfTgL|S=_M+9zqatP1z2AV=nPTTU%E&Vr!1m?!*q%lCPT{4 zKu_>`u-S1>Qb8+a!J=Xpdn^QzcZM$o*U52n^|i{*+ulBB!E^zAqPYsnYopjC>ERs>OxW%ueDPF7ZLM++}$$**P@oWi61KKpBd(bYdG)EipHS z#T}u*NcXEU(#?2?2Ul=gSOPyvl~43#x$B!5SaUXhfr&k@g+RSkwc@in{&CEC)DgZ*8`v(~J`A_xv zlJ!{Q1Jo46)l7_qD*&X)ld2xO8-026h$s zRbEY70k+pbpBvG6yQoGN?-mQP6 z@+=@vOcv`-z7;AdMpu&=hR3_b7Rc9IG)_RXDfdn*7+p2VUWtym*H@8xD#sZHMcK_l z=zDy!I|PSFzr7T+NEaoFYxcHfQ`jOWUwpqd5h4VmmubK@RK^!%EaJ$EP?6VS>n})6 zHBgAfbit3PZNDuj`xz;!?^60=bUbh~69})_q!?$m*Hq1l;U6(GHdIkn3;0o;X~>vW z^aO7^t~^(@Q}18iiD$VC(D!`ji+y2|EB`G@N*isQ_&MJnIo#X1 z*d`QnNPzVwiQ4t+x0EBY-P!Ro1pfO)Uxftzw+L5?&i!^sdU_euVhYD|?BCM+N6h`) zLESii85>*`%0p`cZhlD>R18-#qm6CmU%ma{Nf|XC!c$upCCnNVO}b%Sylo~e4(gyj zbbW9|Q9!kwZ{n05_Icg z&ZAD#JU;Xr!>Zqf_a$D4=&hYt5g%*I#kv9&j%QuJtE%&^1&NbG^gu~}g*{EtguRE~ zM$RxXk`o0k-+qetLfD$_qh4O3cHNk9Yc@inH^4sbV&UixeL2?goKNq)kEDZ565ZAL z_A^3kqHLXU7qn`-HN#4` z{!+=$`nC#0oQFm1xR-4HK#cLCWBp*x?r*+W2AE88u(k^9sGK?KpX2MI@x5S4rCrHM z2oIUR^C;6a@cOBHgLDgs%OzXYX>CD&gWp{|J~wmWR#@tb&woGvE+Pr)2-oe5qV%qh zG1*^KqYj7y)aVLfoi8Jpn}!ByP;U3e9wRV}iXZaq(}m;+l9n2L(${-?o#x)pM!T|~ zk5dWap$A>Z|E7H}9}EmZ$6U=2SM(WQB4ySP;C)pSOywsmdcKht&?}X3Lokpp;*HDBD6If+l-daXoagnkFXSIQj} z?eR9Zf@Fj>dVGHA(bdUpoFcfzob*6VY@y&a&Or0$6z=FZ zXT;qsFKE7AQth?s7YFUoQ%g-61VS}?vM>FwYhD@u$+r66Nt0q_qWdpPSuK@&taj

oZVjIcIo)?&pHC(KCHjb)FZ}76+ zmXbdmjUtv`i4S%zNoVWeI{}S=UwIK^^Cs?`!X{Bu;y6R%#0S3yNk4dpW8l+3QYL^e&(+k~& z^Hmcb<2_YY*V8tns%rvlUgyM%)5DC7tzY(xXLmQvO>#Xh^=j3lml}dcA4`WiE6<$% zs-tT|GYls~eoBd!hO$G_rft%9R(b44a4fW8!Uk!lUF^b?jcvZAIEk`1=w}8f6Ncy2 zQu5n~ZD6GOf`KKJ{egWj=r~b_B{piN+BR&dlv1Vek46vMEPYp+vqT!CR`Zt(M10ah3E?Dgis3g_+pt$!>$& z{SG4E+~Oo5Y)D~jzuUx-yaWd21GJA*>~;nHM@tYp3B96t!W>@P=F=T^xf-BbW*GKG zh6q^QzT4%+$NbC)S~o$r%X1u#EG#!Up257z%nIf@nR@AdR%F?px?bb@al0n=len zWMS9A2poIra%h)!5v{7ya=qku0=y0_@;bQeo(^hl?diMsQvh#}Uap&bXY5fvz}xJL z?f;vb<)7CB{BPVW^j|Ltp#RDU{a1z|!`E_g2KN7VS@?fhA-c=b1v909^lLjPDdBK+UB;_=7xb0TrDNV^-~an{RXT*a-)14 z1U3TXcMSLRk4yph{p}M2L*0{GuSst_(D_0p5DYv#npf{YaG`S_8I{7pM-WJTOv&tx zx6s1DMiAzh67=bTJ8uQKJN4FPwrd9ZmbNxV>@{{qzjP`H(__#}6`H>w%Gr$5BM2tn zo+TOhW|k43txY4Y(Lfv}DUZ5v%>ee8&iZ74?F}7sL)dy}FC^OrR&Wl`O_C#c z#z0>Gq=0V$yWKf|wt<4u$W-!aUwLzUV)oQkgN&C;X@ZdQ!BM(D^R8@7@ZELYynS%~ zb_Kal-WrOA?0#RG^3HmQ${Iz`achM2X29`>p=8dp!Fzl^cKi*3~VA4S5;s0eklQxz5|~lFUl>rffFuS z8mdW8)N&vlSAHMB0y9vcmZp46#R~9Yq#3L0$}glN@WOk|4tUdHom4XMcGmaeNeVmw>!h6m;*slG!!o>?kEv~0 zFE5XbETevY#BHHKb*CM8;!gPB0aNurQ1iHl54a(&X(lms5bgYcXCmzEAX0?hDW4+g zAfz+AA#mNqk5IPY$^F3a=44Q*IB#T1AMsZtJ#e~_cm6BeFre`ImDB?7aYo4_R1J9Y zJTUv|4-+ulWz(Gg(|^-G^_`y!gmex_80DNrKK$5`1FWg80~*%Uy`chCi&DlvL4Sit zb@RqNaD$i_8=YIcAdR~390If3iOP75KOy-mWq{dTly%Qg9#hX`Ki=HusJU^ed>?^2 z?Q7+qpj!*-K=977rWYuWC6hO#=S`3{-fPddl+W0g56?b`SNliKr;qS^q$l?aMDO*h z8pJDnNO$$@mN9(Fv91bl>pSm>D`AfIE4pL+3IkWw*Jz&V_A$FpD39o8RNyCvj$Mrd z*k{S1=Xi?7IzJHF1@rP1>6vEz0{>bw;*FQ)fO~Zh|C+nwC`)fku){~j`{*+Zm%-7| zE$Q&Ks%ibr?*j^WRtE{;1|q$agvnRv(X;5-bMe$b_*qk3%vDnlt+XzZ6h>y) z{1a*~3SBWA{&PFqtBF^muLbB;Lcy@3!-0s(@%cV(DzZCPc>Q2OT# z4j{L4oeX_VrEN~Spvuw>M-fH&>L-ryl4Q3{^2S@7$rb_@vXneomidSYGw#rZ@_Z++ zIOx%}R67OujrqZ=#H7TDF=oUV%D6wUWn+;cO#Swb`zFpnai7^NeOzc!>-46N(@}RzV-@<$;4Dr18Mf3LKlQgcaB}%({7~?^^m~7gMPurvh)+2Rp=&akX zEVB}%fzR#Zs!HgUS%V2p<{by3>4wTq!qF{sIsHv9^B?7sFn`>Unm%3S_5WL`%P>)Y z<)(pH%&l<^Pfagl$_#7GvE2@I^;~yO(w-yz0bX?tmrwnxIL02V$tEIbLVS2U4;byj z8Mg|GcoI?Uj}nQNZK%Bv+?pdX+$_yf2p%4*E>>pSrw*poe!?n9#Ail+BgDUu-LP6^ zv`j*)jRhqVT8O#{pvO;XOgD1l-Msi`(trz*1(lE_Rjlt5Nkw8KPFnGc5>ns3G5^9l zALTz3cY3xQYxDg#tyFwMEaB27`w^F%>jOSIn9ZQXE4@D|LF~I|%8iTB7B^+EC^U1V zLU(1ZeH=nqm|rz_W6b4NJgOOxSQ$)2>CI+1@_0sz;!1BfaX`iXQDBCBV#HnNOlY_+ zA;f-NH}k}?Vr^1H=6-`&V{2yrRxGo1%AahvaD8?1$S4&JrnrZ?O_sNdzxjz(nz+Y| zP4%kcpL(k;B1gA^y;~z^(@k#KfP~CPrIMbl`7oLZnK-tUxa63lhVY^xfH&^Jw_CKp zW22u}dMra=yjW3rPt=Use#)n&sFc2`dVJ+y!Ke@g2YbXPxUXq@ao9fIWXgKnY+l)uNLk0K4KV-8VU%4z^D2xW$+qIZSz=^lyQF|?m7vS_%f^Ft z>kBiwoB6Md{&(|U1bq0yebYi{m>TT{IgC;iJqn+dY!a%cX1j=)Daw9}ApSV$dvGP~ z-Hz@Y{pAYsJW_-u^uVRVTM9KyFML3_%3&(vzjd0c4y*;O1qFR~mYl+uT*x0k&LlL+ z3~uR5U@HzQMQ*4$75Q(g;=c-5MupcG+o!d&byvwpb7CBRZt+3CymMHy1aF4-9nB;G zHJk2hh`LXEe3~SB&_VdD$q}i=;RWDYE;tzYuU*V89Ug6ihN(k3BpcE$SKBA+XrEbO z42*zg$ne*oc4LPL#y=y#Bc@K>oBJb)wKrC#lDv$q!jA~+qgcN8lv_{3-gdSiaW&0b z-f8m+gA5G3R>g8M+B#mLk5T=yeo`2~i)DIN?VRSGuB7~TQJKV_?SzsDGsI``4_Vu3 zFgkMV$exvvlI$6R{z>t4Cn3|)n9dh>#B1RiOc~2_xJ|7Y!ML9WNrr_&%>XB@zR zE*sRHouj0=N!xFbJ#^sZJNeahiQqGk{jOyWWaWHf)*c05#T59;>vTf53@H4{L5NTi zM9Q_c*)-tW?uWlsxl8KJ#DR!<63-8sx0-WCwmU`Jed05Tw_KUss#L_+u`506#LFqG zd^QP*yX7edH$D8TC+NTI`$o`x5py40Dbpf{!+458(95iVsk`O!@aZO1ZtpzCv={NP zh3?-S@){=I6%dGrsb{|uy%Aw_YdR2(Hos8UdEEM=1K=-P!rgq?A@KOBjHx2EpmlHM za?y12YCFTMq~|Z9G`4*K%h=Tg?TXADg%Ny$r9wJ-OMVwPgfQwU9~DRHL&NX~D{p9X z{hsFU7@&spGD4Jju1yw344t_!&*Ofa^@6sIeqFDP0=l1)ku0puC#8t)E7Kvc*`8@z>x-2+?`E9saQfEvv{Q*D8L(6-Y~;<2q-rw0B5NU z6{K>EJ|#wPIs3fy!?Tfu-Kilf!2d9e_2GxkmwcfGT|Xz4`ol(1a!7>n7rB;W+E$^% zl%f}!kBdsb-9NI4M@=#;;trna%1g9G;MJzBrDT(JF=rLqiY#gsutU9FrwI+-M>J<# z7p|XAI*za|EXC;=P2n@WgQWvUHeA&~bF?q(p3IxxKDkaRr_dC004d~dOxCM1qZ>NG zW_HT9+h9MCfdR9MENx`IU%a2E@`=)bfs@{4S^?+zg@5d~eYxYbtPgcb2k8O-)xBva zhpp}EEsWbB-3L^rTiBL_x`Z@umhif z8}$u8K7VE}tYOSKqu*wmFH*a4$fSJz)V5oyo!Xsz`w5X+gdn~V);?e%7;a$d=4X_0 zCdm=(s#`_)r@mB*$*C~68U^X)8O_TD6E^)q773tWEXqmiN!!3ZZJH+m73{t1SSPt( zo?g3(^@NuGGjbj_^ofhFn;up8G}?8@dBE1k#eEtqph?>#c0p`w2on_$tb9gptlDAd zsjRh&^QM6s_V8M1&Q{$0pr_~y!EM-WO8+Sgt!6_>XD}?GM=d&Gp5j9p9$80<{m6M0 zNGX`M?ZQInShr%Yw?sP4t!*WLp!!NbXre!TXm2C_X?$#3|=4yFGt-v z(cGG56MGnd*}dTnI$bM??yaEzB1;=$fIzDVu^{~V0`rIC8rR>YO~SdokW zXC#Xy($1qoX^tFQG8BlM$4P{&V#oVM^LRQXl6wYJ3PzgF@+IAS;QoH>+Ft%;i|>RZ z_LeN7b*O1xsOnMu-5?3x0G9lR>r38YfoGB!wMVP_2hQI0lnBrIWaMo-iR@AuQoV!F zm_Z2wpO+YeXT&@W%$X9Hi&Z+=H~q!*jX#_d(JY21?qEXufY{vC<_WJh8tTBG77Ku6 zP{HiyD{^fn!%2J+v8E>aGt%<)QM`g3cCO6&j)o>>b0W7NMbgDl>T{40zxYFa{2z1` zl>IoFw&h2KpAI&f0gHc9$5T{sQ4WosEu_y8ndh5w5BO!cR3!m?T#|H2e!f-FTF7Ue zmz-Yb_f2JyhRT*}caz1?9NKxHF@E8sRg0{-qh2cc$7_SZcpz`_%rze-{Rnd&HNDbj z8PW&w92v9zsHKLgF&4@^_yKfqCrBy;f{On;#^g%4NezgOzE6*;I1bAD!IltyDE%|U zB%A3}8c#-j5n(h&A#xjsjoDF#(Ad1%*QD3yQ`mczE`bHYiS+0iHrp=Cgj+D$;*@uh zN;FkWr&AD=)%}>gg6Lm6n06`|M!pIO)l#fS>-f(mh9G`=j&VD_gv6LE4{Vpbv*U_& zrYa_$SJDC|3E|)^{tDTCgwwb~x<_|keT^pHu}#f_R*cwZP~k94n5+I=yyT&w^e09i zsNX?3)a#Jks*|{ZbTgq}a;j?INTC0m|66tgQbIS%hT2nN8^3V)wFjrS>7^3kFgrL4 zL9{t_-r^)U8a@N>2Dc6JA245f(17q640_!2L(1=ae4uhg?DFYd%?)-%G@-7U3>o^7 zpBD=&JOkPdsi%!N{k2kxfec)fATJ8VWXQCS>MdO)xWqwa&w*kGoH%&|c?LXh-yM{G z<3h$j&tVi9H84~LrtFlGd#$94yK%@TF*JMvkbl3IC*8)}Voz_v8lam0-qfj~%pI6( zt@TEr*%G}$x+e6X455;*B~X(ad@oYF$K%Ih-+xJJ9hfv9!tiO3m){$BVVdbZuHX2trN`p6SDP$f5Y-%HyQ`X9aEMf4-p;%bRX)ot&z(Z8*AddE~cEo z3DnZH2@{eOUo9zWkpFBUfPB)`sO4zOT|qfW_rO{~jzTq!xfrM9czl(Fay3@_#lpVr zooAE;zixh5QS*rz%qR&aoh3q)zwvu$*)=|P-=uUm3o^F$#PPSU6v^tkqBep8$3nd{ z*-}D4wz`@>XE2mYiUp!b;Dt&meK@oaY=Slt*}Ep%dX?0FX|bV_TFpNLj?@{kX&U$L z_s@=dQ`>^bF?X~ktv8LqAeXS5+t=mql_6No3DNVb{UjKY(_4H?+}P+pvxf{FW+bN78p)CNSUtNsFwfqnYi?0#tv_B!s^+Qxw{(|lHHmINZqoN#H! zBl6C4{TxGicaV^RT%Y=$Bf9xq^AAg3_Pumw4TgY6qSMl&akfe|GvDmraWfJ_LgDt)Mu_V zy<1ze4qQ!F(>{;;Qn6OLz}WXZ)FiOTY-Yum!SkX3>L*-Dr&Z)(S=(lZRNMLq)(=Ig z2gAEQ7?|Ut-ylT}WJ4Hgs6{0MV~;mukkspIQmP9&b+4$@*!~1~__IwHJXFl(CHPDF zS{*%mN9*QS+|U}f3v=UDNJlaNvU)Fe(wMz=ASZnE8^1CnKfkrNGK*;;UT&P!r%JDu zaz1^$+W~|qKX&q;TRCA@Gq;(%MomT9LTbzYLhWf&=JX?{AG_Oqp`K0;}V{K*f7Xk?a-C4L?asw&D+TmI8l@Z$FJWg^lc`W>GZ z?7{_U&+Q7ZV~wB~S}2@JUlA&slwN!0W}@bvaoeU1k;fjMN7m~QVHgf`pwPta;t(F6 zzzT^Xvd;p2`7pA5v9U#DDh7fWBZGNQpR!Ep}84 zY@jKIF!`@tyRHU?nZvW}<}@(EcARM~~I$gBWF{itPmuL?<)`_XCH zI*2%X3s$M&ZEpaWAutpn)JTM7*Y8+cKWsvkHJ5Pr47pf}<_g>3RsvUv!H$z;D3_ZF z&48v>vsZC~WwWoI@mj$@rRSSri`B2c7FkzD#Q#p|4%RiMd1{cAl||X*!a!x-v&awc z!gK(6)pXz?l7(flB4y~nLB->d92=3|55`*X8PVat(DD7lG@%)(RP1-p<^m>|RvB>t z+Z)QuqqZuqA+}7HO4`<~+jbwBvd52PJ5q5ZT~eE^PgH_5O@5mKkn1+sZ40fp-wI9` zW<H=U-LfG*ddhE{U^SmCu$hy+K;n*rZ!sJJWhCvdm~M0Ez-e$DiU4C--f$W!rN7 zkJkIVg7crIJlK7TKq@$U=H?040?*4w)vs+dQUsu$Qg&ryffd$s#%3jhJfP7UciL|f zBh^0?w2}bFhlt{x9P~qJjJyg^j&b{QN`xANR~?I&UPi0XV~1a}gIo*i)5|KWT4knU zW1jQ28qjr&>naD!KIonsAIodtt{k zQ7p$m8ktkIr+3g>62m20aQP*O-)OzA756wjPN`PknaX2m7oI7c@M%k-U z2}?|9w5coOntrb?KUlP0)lL=-%-LUGmviZ^RTSS=GUQ8KP~P(*YA&mwu6_%NhH6_ftf?5=3nbUp(QJz%MXe3fH94RZ0i*x zq2iEzyc!i}l7~v^2L$^dbX}3NH@Xm-R(XB0y`%jmlP=n4Xb3KINRBNK=9ZksO@!^s zp!u!2+0elcF5dBdANS^Q?&i|!f2uq`u@zbgQIADZxmtS=!q-b?|FEQ0A*PGfagv{t zn7b$1|BKTiwg&pc?bAIIQUp`CAzXg!W-Qj>!ul0JEiwqu2qN#XWuie>ZOio}0x|`* z2r2dNj$uC;xN;>cfwA3BZGfAs^Tw^{QWgU$soQpq_{M@10H4<-rFj*{9LBJ8ZnKwT_C6@}o=U_j$rF zcVwfg9w}Zk$K71ryeAjH{O1GolYzQ=u(dJa8xu0rcAD@s6H9g{k|3GwDi6|NaPdzE1^OH^e%mpF?c;r(!)tncg zK5#9O=!93BlM!YdBul5Ev_Q8>QnpYiD@_Z86brPo`k9OpNTqmNkOqUqSXl+PK95wp z-qwoQu$dehxV8K+{i18ebr|{O`RXeADp-h}Q!%s}JwImKgo>BvN4w)8TnD%R?3{z{I(ZB}mlr4*`|CpxH{$@IQx}nKpSkc7GeCMFtv#x0WK=c-SLw(0(=u0a9Lxk8=y7iQnVEZre{MO8i-`L3h(7e=m8}SS zffaL_Qrl^{J2Ns_?YQi`$Emb1^xb`v6jwmPxcc5%RMhz6F-)m4w)W|)@&ui!_V&%( zYNOi8;^WNfWV0zPd5Ty?Buk=e6H@>zb`P=n!slO`Q3&pD4$m*+r#j!XY34P$g_#UJ zqDDA&OE{9oTS?tZ3we$`P~qINfzXVdU58=NwPB0i8a|gO+@?Zuh!hZOlBKUK6L4G_ zhBz-f2nGyd)k&Oea1ohCVnj+`F)D{5>%5uacT7c2e;3tc)`zu3hEiNL8;N5*Z=!G< z%GLa3a$qrezP3uFv9F$q*OA~#%B=SJ}> zw2KTthso93lrZpH#QPW5=xJDpJX04|fDbBGO+IS&wUv@I87omkwM7tDNF(O?=TLQ- zi5{YW4vH|BHwr7TvzVI=3g|gho-a;X}$sR&L<=&%}(< zlLPlo`?2}kn(QuelengF`Xq?SJ|~YVkHkL$m=1et3b;Cfdqv>60}my~K6qiCkf7Kl zFUovowfoGErjQ3Gc^ zqvj?Q|EgCvSC*&+4$~_8u4^n7Zxm9r>5GcaOeC<9{lvqBqZ4vmlO>3zIee@*N%=^X zqC5G>!Fgc?8tdJ`1%k?4^L{@NPSXh?#mleu5$vLr8IbAjpFMbwESrszQU{3$892(T z-!3k;KB*0<`b;OONRR+Z2x%%>8m%teS?i0nqWPXZJA;O7a1nVya(*HVO)uu}{SsJ!aK{z}8DIjssyTW%W(BNQ&w(!i{Xtm>G@wT8}Ds73T9tNYx-# ztQ)RZSaFT8TGKYmkJ4?gBt&(9Mq1wgvx2!YhSy=K5KGSlYE34q6z12SjtcpU7+Q90 zray01x(W}SJTmoTwj0)g>Wb?eB&eFwA7^VEg;=zY{!CkJALzkZ0xwV>g6K>)5zrw_ z2?GjOVTznW=CI;|J$X4+ywf=hxtMUKX3`A(dU8gVOz7Pc<` z_dxA;H-NNNn7G^xpb)Jhdk&r>g?7-BeMuVCf0(3y*G7d-o0?3yQt&}ig5FEvh;gZ+ zA48_@(5a%N$ICC=u=$0IU)23jas1rWjp4DVtXQ76P?X-lE@Qhr#Z{7badqB@I`#a9 z+;I;bpbbAqf7Z)<;v*wjc2bV*=brh2w|x9DS<>Ignqob{m|^j0GH6mak}!Oj&UO`C z#d~*rkj$rO5-A^$jcJHSRYY-=i|aFrsJdVtKT8I~Kprr8fXES)ABw)XaU(!w%Q)u- z5019EmNZ;NPDM`$$US=m*4|WCo%L2^g_l?AR-NJWZx4=Qj!IuF+wWrfKmmK6Ft;u?0m`nv zsjGNiA{KY@XR{3?<_)C#U->2hgGJ5!iQEnimS4#5o^SY+Ini`QoS)83@x}bVi-lOs*I&?*y=4+&SIRqvsE3x&~Kq zXzEOU@6`mbQ&<%SyJd49&F#76n#x6^P>k8uL2VDegj8`6tqx-WtEy2XLEvplo{)j% zkKb508y$!w7A&CTa}Ka7e_uNYrQ5ae=Q1)io{G^RZb%jM9%;f06C5iZsf-=j-1p7* z!NpI=NA90n;rYH3?eq|AkYMt@ESN-Fs(Y-Mf-Gp_<^U4ik#prc$I zAY!;wT~6D@Op_VQrC@i^XO4Xg+;j}UW5OO1x7(|XrKBoQzn!br(KkWcXbx-N; z$eel#o>>jH0GEH8?3j=>&u3R3+Aq)OfmQV;|7pt^Z=H*sz}DE+LFcp}V{S<#0Nx?o zuJt`t(97C(ZGPmP7=|{J*uzGBNTY3lV`Us_(hS!%d-&v4!6a6`i@+{MVKDh4E6Vil zhllNVu9+PU&#nk%cnML*uX`z7}?I#pq*s9{$kD46Y78k6G3_ke z_$&L`a#1VqQSKl@$A*VEPL&n47S)@zz22J5ji&#E-oG_#5w?J6XHEzlZV+iIc~*3< z?7cQ9c@(t-KQ)8VpRjRLi4OZ({DUEhcd!CrfPjHPZOSe!a6f44LCMYb-(=_c97Vlc?QxD3)OC6)t;5saG{^)&t zr2~Sc@*|QVDb5@)*f=6hm(NdGYQ{57S#3K?(@xxB!-~}2Wlh{iIEmo$?AixtH~j}9lFTiR=S0?hYTCb^xU-xqaS^$#?^xZaGJTFby2?)t z;ce%*lzWPxw%MEh*94`{I4RKmgFM~~65&-BY5jP5;u+%gEm5gr5oN{6j0VKkZ-}P$ zC@pTnkHKmiB?J*!FdV&l+1C<2oMezhUPv;JVkptbMH4jlX-b($PiV4})J0Qj&q`fI z_tXlt)lOO!29R!meK(tivC;nB`b3lGEFG&2vRHx{$HW8Xyp*azryR$+#Aq{b?Gpk2 zXxz8X&v(0Qu_;d?lBAh{@i@>}uF7VN5$nLvMkbUqlOtvVM%*zOt0sXdoAgbbx52`d zC{jPM8p2#okIcAt(iasfRfkWPJl)FYc}odEWR8QO#%6-QC=sK1Aj(_~$3}?Y-FB(C z863-aO-H!pvVOC8B3JB%S+4m6J2k5F8!l`pXIitCHWc0DI1E*3GcP#@qfSZ4T=$v26FVj6Y9#YZ9G01#<*De z|A#DdK!TnPRTxUUI1m0zodfIDyv13Z$JjNE;&Kvg+)EYy>njdz)mt$EgK!%h4AFWG zhsWEOmhz4uPQqkhIIOgDRRqMS^l|~D_NLamgfW=i*emfSe1ywcTf$a1S@-`tOx=rH;#4a=5bUR*XA_?@ca83 z!^Mx_Fthumbq{DMg*s6!vUC2oz&_L|odr8pjAU6{&_k}%mHy(|oAUG}sJ+6&L}-*k zXCR7y_2#_m7F)r)HJCUnzp$M+Z;9pFh(jqqOjwU=>rLT2}QyB%g5BaR`$#Z$~Rj)LP zwO3}P7<}}g-f&Z;YkoITQw9&O9HiDiUW}1>q)BKXE2m|`d&}oZFstLHBLOBefzKk@ zdDTMqZ$uk8*F@W94)a+VcxgqX*O@Pr>b9xamEXm(U(AJu^9q2{uk8q7XkUi37#?HqUHKI6llCo=%+J9j! z@>%1|TpHtkZ7Yy976A8oXx-1yP-j)|5Ivl^%uGp*+i+_czV-l**i##iXw(8uu$S`% zw!CM@Vw0)vGGAUe_;%JD*r-#>mC#c#VoCAn!;7j?=KRhg_iH(gK|XA3Kfis{I~Gp0 z<0Mx2cei&Dvh0v4G5df9zq(wqb~0WM#QsPI$oZY>0En03zWJknrbg|GT@5vekfF9? zHSsNlDbxwyY?~2c$?Ts7xk6*ET#>^Ih0_Xw*k zDx$p^riT!eTTMN>$2Y+X+T{`riMTX;S^r@xn%4A|&7?|Fn%MrhrkF;vI?s5!N#N4( zP+5Do2<@@<_x6e^Z;ih5(uo5NWfx|#AXfYzA4$~}8gEbR-wgYLDaAhA$D*7L^ZUrv@z7mp_kKip4ABz4lI+1jQJ=49K%5}l45pFlt)%bKwV!XS8>s#2l(NSJ)8MQuzc|ER%VP2_FBNJemJg2PGyKh) zuiLjiwI_FwP1iNK@AK9%Gl$wFtbaR>jm%6zz{B{}1T)M>$OosCj=k@(r+?7z4?iGf z(B99JBRB1?5%%WWF8pw_9jvzgvMlrzBs*apnCC?@%q!Lx)phh?A3pw_L@T1w_Lp$eSZ>zi(kvA@reb$*cpAH?!uI_huONd%Af5~ zSl}>w8uDWbi6;JM-g(g)aYT(Y<%<^+4e7nP>a0(rD8gc7Vy>^OTh#u|m513xEve1u z7N+1~r?qgYwgEfIBdo~Xt#%!?c%lspG{b+=DfSzmyi+V$G8eYBmgCvr1f@RPRfAv{vK8i^J^5dpbyX}PXrqoL{pJ;7~oW_P#+ zWA_)y+k*Wdgf*9rxhtJNiTa$9K4WYj_>UEr9ztPckzCTo2J5vS3|}UoveV+<#?^v& zX&a7qgdkA@1TfaY@NSx9N z<=4I09j}Tqcm2GYVU!fW*1ydN!ba7R=$@s0W68MmkdFO|rlOHZ_JYDKEdi$AY{az) zaVA3;MF@QDK;{>zO0fL{(sj3nE7yiv1yr-4i&c?JDH5Z686+2IhjqcpeWuGPxDcp_ zYERmp^ztHAk{A>25PwdIRs(~ufRBb7b0-q0r4uw7((ycKdMbr&xrxJ7`4Tp)9xAA2 z2Yel%ce^5q+IF#ruEINdk+7xKqwWU`%+*9yf}aZ{bxWUczjJUCf{ic4^(6tXUDAbM zvBs>a(Z-HL?^NPY{}uFc7zfRB(*H@g4~?K7@#k99O5GcifH$p~zt+ z?P%P@JK@BO-Z}I}Qh^NFpn`~ZO;#9gs?)xGs$wM@)c~!EE^*bmAV{R`V)y!LKd2O= zZhzV8i4~zkf0sgcG_B2ddflea$j`NdtV+%yI4~5`T=HYoq*?(zX$&He5WPg3i(kZs zHLLn|GP=FLie^WHeoCay@W>5KimzzI1fCJX*+(%b1v~^C9aZ*-ncxQKrO}+cAUh z`cCacV+qgeBNr+-ITK5&D3ySvgW2mVYItiLQsk`worYn)FygksT#j*obAE;LosB==b|#2NM(yjKr@r@Sd}-WY^}f z^oCjZ)Xn2qBpc|*+HTqVSJc&M!X^;TJ%WdAs7_eGQIWa5dtrB17Tf<^eGrb}yqA5K z%22FFUy}QlsAqMg-_547*91)tMe|Bgt*mcheutOT)9bgB0~XoeG7MC#+))13B7sxZ zti!W|QdV*aPH+_Q{y=RbsdPeC!h2!mrD$s#S*u7+wjN((ICJAgC9M0V?x-dhvCeYE zW!a(y0pJJ<1q7!v({Y(Xu3}5cP-)gTu?|CyJ|JSBkG*k0LIFXYyhvNoGx;L{EB?42 znw$Ub7zuF^h`z0=>6g=Tq(j37whLJ~k<{u93TlhCkH3txz~o1m*0nEVdvw`|naz$x_8lx_v*USD=HhR5kb5m9QO6G3VWJIv=y&r2!y zs(!{(Xh-Qvh!h-vxr6+@O#F7N?%@{B6l`@0fLo~BNJhCQNa&d;A90($ymzzrWTI#c zwzlcAAAx55&atR96Zv#Ne6lgFAb=>F6*25~2YUJ^vDRB!ui5?{U)!XB%m+wdd2PFg z&+AuBcU#Ylz2j2b4hDP7*Gy}{b^u_^?iu*}Za|nh%L{>_x9Ac}W%6CGfyB9c8NACv zqD&XEeaEny!`#ldi!!dV&NxrBmaEN)*J6q(<2G(w?^&9MaGWgh%6``(sAqoz8e*b2 z5H5S3m^282g!?@bJHUO<>yeVtgUz{Hmr4NFjmS;XKTAM=#=(7I=e?ODe<5YTWst{BB4lc_9sj;>4dkrNPPVnyZ z?GxNaB=(vvzNyC*&@H(L~&%3l|8AVf~32y03Ksc;VG~03zMs9Cln}`pnP!SEqzi8Cb38vUe3A2+f zTG2b3NjoM#RBz+j%rC}uu4)c8Cc8w}YRO{E;e4?%XdkAawl~G`c2QiY1eYXN^?Qir ziBkACavP0OhaY9Rl~*<)LT%1^jV_gvCT||2kNsQM2>D+exIYp(@MSg%iq&c=Y%Xy? z{jQz<}`xWzaN~jHI}XaJgB*5$N1r6qgcu@q%@PXJ9c@G5>lkI zqXKtJqcZ(tJ_RacO=lz5rdXckd!|q~KU@I&(ve@j)dMs}h3jt@;d>pb8k0MIRJ)?3 z!X-r1=nwo&8=|=B<`kaA*)`L>5ubPpsRyb#fQD@WqDMDeTrx+uW?Uq|R}P_%E^qWu^E+H3_qZYt*!6{|AU zE`EvM8PFNGVUgeN62tDH5YKk^ce^ttE{_1T^AR7Z0taC@O6Q`GhPu{;m(~vYz%*1Z zr4M9|#2mpthOs3%3Pd*`$Lr=@OpIQq=ONCjo z(C>9&{WbfR+yRQ$vn_g)Rvs60Ye%*@rN9be7ex6)BYbpp%BLS?gjE_$B>{vHH&l^f z@OkogVhTu_$-=|&`QA=!ejNZ5qzMBvMt2BYIgcu!3V9q7u=X(RxPGEdLdT0|muzd4 zeqL}h=0`0jiAjVf%CG9ICpJ0ut6?%tw1)$#P=S2aGe*<5psF<;B&8yaWEDg3FR>O! zi`Lcgo7*UV5W@iaJFF=og=itTs^HNRV+bfvcEe^Z{CBn7@Im2E0cA4`* zgub{#FwE1ody$eDg*G@<&de0%^WB0PnG7{dxyO6FYs_#ki`|!koXF2$f`qm zb-iy8`Doi3-qLELpRXh7U_*`er-Ysw1Vpti&lKX+1-AOh9j(*xze=q79ErS&?V3JI z6s>ER^X~Apv%bsC{w*^L6U+s_}1$N1mRF-!c2Wz z=5;LWU>AftNoVH-=_R_VxKQzszVY}pQ%)O_d~dl}ELU$nk%$@W{y}~^HgX$UvKXU& zMG#AVhoGF`qhRfUVUVn|%ABx0M0WXOfS`k^L6D0bKY`Af4;DmGE zxRjbUYu|4DxyQ|=*PbpBohGL8FDlO~mfCM0N;mr3V>r@C_KhuSU|HDf^?X+7V0f(dD)Hp*$CkU<>wHW3y&{k;9%|&00EK7;a2wkR955y+nugFJ=4g5j=V%tzgiB2Oh2xLbXJH|piy4a=(Fcbv_GQ3`8jw&vpgXw znb3iOQkK!UYD+RU5l@)61TK&fo_=*AgSBd$ z4J?%Bsw>_BJ6p#3drOrDU!KTQLqV`YIBAFN>M6lW7HbHzGH|FA`+TcDq?3~f`Ztbl zi+}IoHA@?j?2qfu8&oJwEK|yz?G3r12KlQ|EV6fS2B6VPcrF{J$cTCvRs~iI)I`3 z0TG@2sg-X5_p*wADLG-l_M&WY+=(IBFN|VuAM6XT0=ln?Gu?EVow*{4)6ER{OY%40}3|Ft+e^}D0=mi<)G^vK4b+>niw(RJ4QictD(P8rcS-C6f6pgd%G z1II(`^^28b$#2N~dUU%RuKCTObDg58HS^iOJp{KFurc*g4{R|w2c`tHgyNYAdl ztztE)SDr9pJhSCu|2s~fxw3Pc+o7;6|I&3iHG*OT~aey{VSdSUIJ4 z@l)FVNDeX?jh7+_fX@&8?(*qZov-vqUwW+nG@-hAY53cS9h)ELj~OURn>>m`}r3nOmP1B&;@Ys39ZiOlFcf6Dz)wQo%1H)L?SQY=~j4!@u_ z$UPOB4Z9I*%9-jA$B%k*8Cy%kt5eLpQtFogM|f#}G4qrVBTUt<>~}kE>1s9*47K?* zMQW|KPrfdx(_pTjoIDU0Mgz6lQoCeH>F^0wTOg^Z;vrUEN&R+WczD1J;^Wy2iyK)$ zp%D0?00L9nmRxh3p!DRPv|mFV&Z_b#xGVrx`Vc9x4EfiY)u~GOwxH$RQfw-}n6x0f z_=1&8Qh*_=cO0E!+ibYDL9f`d9^Pd>t(3kmh9L-}l9n4zo1^eq9gOMLYSQ5+3v8bT z`9&vOtv;?vWvTi4rl}LCU>1QQ%Nk=@aCQ-C$(pgxibK>!;`rJ&0~y?YNnT2otH$s` zEfsLCb%-i0diQB((h}DEdDXG;thu9M3go&$HKcl{_E2r#VdhPZPO1?DC|sAo9ntz- zF=?9Ykr3+RULL7|!+r4>RE@LP8uS;q#>yWwql>{NCP&;!6j3=7;>(bTT}{+A10EfT ztX=VX>$J4f2dgeK7u{IikPC?oRu3g0pXmO(3b-1d7K^@$L1{+sL5CMTkF!>$ z7-=8&ncetTIqx@p(SI4 zvV>7d6nitQiI>!DfjHGDz_Vp`H}Gdna7v-s_!)7Y%7WIhFoV z;_VXufzo=7UOq;B==c-{{)I#id=%Sf!f|-Jj2nLUJh!WPipmen9g+!#VY;?Ur|4yLy{IrlS zV&wdGL=>vf;7a8buv6wsFzTngFr56xXF= zL#sQ>RbP!)No(iAMi`tEI+(|}B6U}%RDoIM-m2lDT_!>N9+V0j3sG@?fJUdh!{WWr z1xme#h~{0)V&@9Prq14H$seqHSi6?bzqs*nS~r4hjOOTFFA-Mg5D$yPl`$1ng|chg z1nZkJg;Ni5mkQM#36ycdy4R*QLOeYPBk+aRTuELLs-SkMKrBbbs{BTInkHwo6jGQv z%oNhal&SMst>C!SJ-$h*5*;a|mk?j$p}XoSAa1^3pgeeAXBHNl;R$V*bAfwxQ2*rv zPy?_0)C|4EiJ~Jkbk@I%!K{`z+uKvVbGDL}jW80cJUmLEn)~yh=oKK#9je+pWRH|< z_Fl+2fo#KJEFD9j>7FoCZ7+?c6cz%voy58qQEbzlQkIz95DuiDgLU6@K6XR<$QvV4 z1w%0Fr@9tu>8JL#DDF=)E|$E%?Q9*o8N*(H|9e`4p749Vtop0k@C;nra^hKx#RWUN zYuG~r6R>z%juMoTj?laQCYjW(JbDLZZvC<`CKVSAoIe3Lag$PET$|(I^G`^`X<90Y zCO7@rqA$T1X{djZVT~XXEQGuH%3-2C5SvDn9~u)U|0v3*fSh^d^;(+ybf97v`VPn| z^i~Sz1k>I-iH}7pi1|6J3rs5@MmTQ2*&5(6*zJHt0LJZZTCZ~9aURKI>?`Ikh!seT z6VYm$!AXTr3C#>X>bB4uM66+mpmW_EPR)T;Pd8>m(f+Z2dZ~AFBe;oXsz*PnntwRk zXZ(*9frq)Jgh@K)#N_KUVT1@q7vbVzJ6)=gtgF_{6TtIYn6^fD`K}9BWnQuaQ~6=m zDHD$%P&Bp~VpesC+C)S!1TQA|N-naS!fAuYP?+D zOkFu+3npJ9ih>f#Bq6Yt&-(HW8^J&MJ2&O7eujv2V*=bTS=d1cN6K5-IjR-)p8n3i z5Q0Wpa|V3*hY@s4GNAxgKEO90J{N}eD-*Y#t|G;J6q=Zh5YJL0r7~p1Yf-hXDUJu;yjGB_Xu$56a!}we9*eD zsa?Ti`R`(&&p5Fj5NEo9wA|@xe;yocLbk~O)$k$2CN@KA;n^MiLlpWEG$sB%x?RfQ zQWFYV-5@=S#Mv%*bEzX1bnRkjK7u!Q3u+t+`}`Q>{4-oQ+P_coYl(`i)=&w<<*S|tb|qn|6!vr{r}r2ER6q~ zjl#;r$^5?_{|_65jg|fXx;^t1Q~^h84HWA5?v4fRf7&RJcCp$H?%@T4yFuOEVD9i} zBpuzu$8))vJD-33SG`45m#yzxO>>*yETEA|RJ{$Ay^IP&dvlq2nSqhu1XT1zqccDT zMnWMb@qs@_P_h0WvtV3bEq4sPxT2BxmgPDYGP zF2)V+ENF#gz#W=gS^z2m@`7UO|NgVnO#*@vX&?5NFb*gHtkC`k0FXd$zm`saJ5=q> zoZXBZfq)N#jim|D&gmn>#m*Gy2>7TDP?eSgC^`V`{wB-)O`rq(`)~lv49x#c_wVSx z5?R{)E7-`y#NO7y$j-yk&KzK7X#)f(O2{!dyF1eXjOKtfm0+bf}H|N6y_s3=qbOx|9F)?v+ za07r}06=#W3&y_+sChU5|K()<%lx6i$IHRq0buqa1L$LE2K@L3=jCMN3IsSix&VE= z{^|H%1joz_Fts#s1{ed)E$!g`WdAS&&Hlz8_wQ)w4$xux7(ZqJ(_er8{igRZVW#$W zHXeWI|GHvEH5mmJMOoT^Oa8A@M8w`5;6=~Q3ZQ3UX9h4cvvLDC*_i-7|C>k2$nxKP zF#U;@wllK_aR1%z$2t9{W!Hbt0M)-2gc|U_xfJX_CKm{x`ZMUdOzcc1A0N#BpU3@Q zA^-oT{I4wkuY>-7JCbm*vH6#u>TkmTkKf4F(#GT8jE~86asJo>dHauDu=~GMP2k_F zD`IbB`hR`W&PE@*AZ%xD^WS5%bds=i2bwBbI-6MhJuZLS)&E*F8%sN&lD(7VUr!5w zo|%d1|M)((%f$NQ`EdG}$$z`njLG8T3YfRUr4kp~>p$0)I|vje=C zKi1I{=>D%M1~4+%**kxP06xU|0L<(i;r_Z&4t4;e@L#6C5eI-#$pm1O_=A`MjFNv43xHAT4`Kx{O8-G@07jWV=%b$eAM{aA;Sc(#r}$sQ z^-)jh5BjK}@&|oXQ2m2G^r`qE{={LKQRA#{66;XKloq2 zWx=6u4XDVz1L62PM0Sn=p^du%)noccfv^{ zeJE=?;#9XnE5xr}$E^*}VQq=Z?a$sX2JtF0yX|nx(^!L3g~!76KL}w7=+%VwykEa~ zYXn$>w}N)dP~?7b;X+c%M}Ke|kaVyAQMNiBy11*nSIr>{|57$f|5ZI&H=uZ)BF{K$ z0f!XInVt}a2JONfdH(ip4lQTuomeKG7S8A7D{GOL_9jcrbHVz^9 zE!z0ZCohqMWEt!wuafVvGNDo5%?R}un*}2oNnp-kAxF zHBsKC5E(hNQO)VXLCdY@ES`O3HYk8|QtsM+#qx}*oX>O&5*)O4K2>4~OY2XtAqu{w z5`^kH2s=n#;#kJbAN;}XJ4@M+@a`uRzszEs=d9D~W#o={+6Bh>aOpEOC20qft#hOH z`BXq{8iZhk%xIL^f+U9*%J4K>b9k@{?cG`c6uEYt z+*RfQTNr_ECq`P_nqc@ggK6U4R)$sJijz`?N0lCk#;45}$+4WyF1tFPUJp7)>-mBz z*_p=#O5Nk<__-o6l4q$JW5gsM6iWoLG>=nSV|4a!GL8 zBziu?z|Yz4^cQl63-m;iX;Q+qYwr4J6#ze{_LWa*=31N{?Xf2?1V;l}Cv6lK56ZTY zzKiD9PR}OWcMS5M-!#Ou>8q1_tJ3B*S7ehN8mke`@>`nneAQg;i!K%wkL#H+<10uW z0|&$Oip=3<)FtLU>l%WuPRcE>8Y*lV5w zoZt0@!%v%)T@${WZzj2DOY(-WC7TiGBxc+O0!l~KJ}?r6rFWGAkjs0i=t)hf(7P~f zi5-Moouy zjyC-GZ;#yHUHL7RkQFNE*^|bOZaN3fI8mcm0e%jEq%#Y*qd?sk57a(vL;k-*~k!yQy7+TiO z9uoDfAF{c9ysd~tYd1|}E}Ykzk1NHbqyR}z-i8w3MkmM(P3<(9h=X!6&=s3Nwk{P5;sDwhzR%5nE ztLUI*5bo>?U{BVGRnaErv&a?Qa7*nZzIn#-`Dw) z(Oe9}khLhvmD){UN&maU$Aqex)3wJ?>RtO_V3OQQ+aAs$if z3}G-rFVp#L2;P`*vLLMBTH7@CqSPWRIj$}$c0j;g;j}b=!(k`Z3H*CjtE8O&PsJh& zf$N+(`>!{1$GIh0cs(F1GQ1Zuw7Rx%lf(ovxX&CoqkY!6=rN170o}W;g0uUXWlu%1l^hj(!j2QP`qiZ;&#pW5XNh6AZ_cT_MYsUbG` zkDJs&m$RJ22T=sPc!=rBH=wF=OD$h0f9+Vvax}Yd^0$=rBzS#iMoqMUWsj+DzwQB?Vwmd+ zwiabsFY2HC6Cfd)VjZRe?e=)UqZRE8ho4D!mcjHuWFe&lxp(7O?}|Gz2S`$mZrQI$ za>PnnW4}C&k-q0>hnmdZ`@9F7Qd3~dEz6oIvLLTl1#E8us1)WK)Z?n@8-VYfj($1O zS1t%D<*gpkYSuPb0&SF=byBBu2pilpf%M;~AG@DjYTp zg(YG=sL4R-@IY3$PU5|U>_rP|MkqW)$z#&AA=W5BTArWDnO&Pn%rh1X!WV#yf3ruK z95*nUAjw@r+!i@<*1Po#)a}I1fUMZ~rox!!$X0lKaEvAYRFaIf0FtpJ;pR7d4rHf{ z(Yx|%(C$&1AaWQ6jagc1`tDdQIII+B6g+}FDVIn|503u>Zps7`wJd7wo>kJPNDUNs zpE7+VFV?PyY*=3aEOs_`kusM)qXoi$!+%ZUq03EPQ7x`o%tAanAC}ZZT(u7$_dOdFIp1~$pc^=eiM1sO9r$ng% zj`^(J)0kzXs#eo~L!Q=FwmGA$ZikxokN)Eu+O3gLq&qSCP!@%!7Gj`|5NG(`LB>TKc2B0i*CI8_uE+c zcdMR#=#m_SW&9J0I0-Opjo|l{aLMgq*XBSdK|@uZ&0`)Jpo7Zbc+&{-gWooHMmb1y z?$|ot=X)Ky;gqJzo1qP`m}3}>xy`Pv#UQRD@~3VxQXtGUKiYydAw1!w*@jtgUUF=7 z&KP_ZT4`Vdf|47)cq4c5?G(8}d+-Wh{%gs5IH{EuWV@CV_^Z4l-tv)nb;C*4g4_$~ z0m%uC84hg*38=boMEuk!7y_LjD_YNvJ7@AG2N{0%yAjECB!Bo0*)aO^EBr{(h)WT6 zlyQCwW8yE#?)o({fRxg`ZmF)J@z%})`JE$w7xjc-9OHMqd+r#%4107Db(EvypPW?; zx$LDoI3i6uD$;d&S2UUsA1;_>)6VqUizJ%pIX$t2@@E zbk3{Ne@hsFx2d`c%@$Z5Ho5K3dXT-EroV&rjh%<0P&keL^3Bi%2R=qT%;{0ZoUg#~ z>|PnMv=s`@ps%fYh2-w;NaieN!wA*!4CdKXJpFJo+T%L-*(KRFs}X6|ej|h0k+;@$ zTr@5X%4gVm7DF$1cB{ure|?MvCF!F|PGsbbaKB}bu+(JjLV50%f%00N;t>EMag-Xo z;n3f}LWI$pIN&2qv(bPpB044DA(*acFaiqM!Ipyd!n2)JYb?H>tDzUn+%&6k@n}pJ zL>eY*FTrGL9A|{rc7pppp0i=bCaFJOVVywbwckI%vjzu~*7&xeM-P-~UN*){8Z!x4 z5X7v_c^S7Dxp$&Po6Pr%d>S-pbjrvcRIS6#Iv}JoaxU?(1g*WC8FzeZrD(X4V8wkg zM=8oF+KBp;FYmLwS~AR=NZ5sdkL-)rqJou{QM#Fou(vzf%hm6ElUilxtU@|o>38E^fEhE7QOT-Hy!PP8D6^cUEXo5KP0IJXKR1WnTfk? zk2X^(ux~!~@0OpV)u*IOMLOd!U|iMovRIxNIUiw+m`Ohxx7x2)^_hJ;l?n5NpK%I} zTxj|oxwUA84O_BN@9UW%=k-Nc7er;&f}A>v$5TO7MsD4Mz)C-R;M-6FVIyeVAOR8e ztlG5iw5&F`Fy@mI6J%^4l#CLVFO`5V_x7j$q7B#HZT)vrm>|e5>dr7N_I-SQ3vh+m zKqCc|<+@Ueugs9!i>^@2Yv!(k`~GYk^_&4xckx)qByZP^3OBF4R{7hCY=kA97(cs= z*WY&wTfc%j=Sf_7T_qujd)}hsolu5|{(gH`@x+MgEzGG`g_sdG&PTWiy z!4|$mMUt>u9ip<~Gg38IU;2YW2zE)qdzLIpBoDscK%odp*$-?5L4O&{$n$;5C1Hj; z>mDyYrQyC5!Ci7jOjim5A@St&~*s9PMmF0aLRqAfHilpL8&whl{7gxvp z60!Y!gT%SWGdiRp?o1dUs5`IlX}8*5UV&fxZ#IY-f^iT|xyFVlo3vpYdM6BwD9lX} zecS!wjCT%XHRsEZ)pI>VuR!neqed07Li6wFqyf{wGfUWgFdKoUm;K5ulbwRl9!Oe7 z8c)8pzn-AA-cZj7oK_c$>-Xicm~Pb0{Y!WW^DZDIF4b5sc=D z?$!)MQL#ap7fq3nUPfPx#Kn=;*hss-^XVLoRQN!0`g2k&x25g-TQjmqH(5teRu;Q~ z8}p5eB%$4T5AlB9j)$-6w&{`ZS}vo*yvy7x;)X+~q!S3TIVLF3{_;hr#tldygP?KjgJsY`EdDkhPEUc#lnYaBSo) zu}MAF6wO;ZUiwN0gNVlz+1|`wrn^=~R2$Rv>7=`t1qN&lqkIk#YEIpBB#^^y?xB1l zW*y@(EE47vjrG-{HP}n-QX!N4Evzx%tQRS^VT#z*KmxnS`bS!(rHa3117 zkvt`)h+c+Gwa(%iF>Yg8 zwZwfuYBNtmLiT`~Xzd0EIW{)RrRW^5P?q*3!2t;peD!g7tn+Cv+Td^N+X@s|8_H1n zZj(6cK~eo)8K1-}qj~bJ`2olghxnK21R^E1&C=dQNpLy73o9AbX0oN0*6u}s*fY;w z+r}0E{2c4k&w5|mQ)@Vt0{SAq<{ig&soGbG$}dSWrRzfC2wUI&*8~^MG0d_ z8n%6M5qJC{xgdwoq^t1t{<_+3B0c9}06+GfOnZR&RQVkG zvr!H98;Bgf0(ZTnFF&o(WT#OcYRJ6t#T=-j&_cbP@Y)bJkRc7a{zECsx* zFW=gjd+N4}hmiu=rLqY&*R2w+*v~2G4!u}J za=w~kwBAmmrkau*RdpWB(8lE$&{}MevXVu0WCLfMGyALy^p034DDiBhc8HV0$uieJ z(eR;?wumu#8GJ!w#bg&i$JXovwZBjE7PuL^Uw0g11(Cc2_h~ZPCiRVW58|hYZ+0*{ zpJQQ&V!P_Wu|~-+T+r%s+%HevTV(&}B56?dlirk5Yx#~H_{8E7NN)jy4qY~1%}@^! zu4i23>d4!<#U61}yWQp)8;9R^sQ5dxvDFr(WBQmi=L;3BA|VTW$xU={+R_d6afTko zbA%IOauj;giAFetNe1}dKU(;)G9Qg?&0Ty_@kSyA=k0yp^PVBTEOsFt z_<|7(tzAhjtPoH<>xt_qh8cHEar5(CTLVmQEvhImkC3OV=S~f``a}%}fk`e>rh=4qX?eR>iqdPoK!{!>?1L<4UV%Q+u_^p`)}<%X*vLFfuyB zZ#C;W2mV4s-Ji%LxGZ;I^|>>e_!6T*gWYDJfwXz_#Wu~IB6+5n8LsH(0>4E{q2pK_ zwup2{v9Ydktd@)ht5fS%rhrb?L2qnKQ0SF{fyg(NhD%HK*#&4b@pAeLz=$-|P7Pc`L+1NnGCR=9*V0ZpHaEB79@2r~#GWrx8}0)?l`0gqv33;1KV!Q*nqxo-zd%KA zI;ZFnEbJpf5Ps%iWOGZoe)E%u3{8dD3AUxl5%fUkR!9#H1M8N^AZMRiU|^TDTYpaL zT&I3`@4c|x)>$c#YTZZj=UL>JEdKp?dm)7#Rb-xgI3Vo$K0H&vu#IKC(a=Z=eGX<4 zqVQf;_F`TD6;P%WJA^&jz&tf^|L!JR1xpq0HITemR_2!RWvV5}p8!471U16PbI|+X z0We!TQu{fIg}&%)QqU{srhs_%aT>MsP>2!I8Q->j$`7?cyaX=-2XTMc7H#B$h&H?Y zZEDtGj3d*lsm8GBU#PPVhIlo^ zJ5acTzPO%3LzM0oU_MMTGd@^&YIN2$#GqBQA960YAPjzqSlSbb7c zkG(ZhSRwCFINul+>wYQBsiqq~as62^Eo+vbL(Xe=5px|m1~S>Ea9Vfyv~mNoB{KWt zdDlZJDwFJP1cypNa4dQc;ylvKR39tG*MPbhE9P5Xx-9{=zu{b_HQ#omsI*LyYn&#fDl=_GZa>X(RFH6KTx9WX`j1dq(`O^*}Y+8@r}C z2xAG3Mq12?d5p&`IPM5rFA=11!_Te1?9UBdhKWW1yIF=$e0?Jgz{Ar<*|z(#GJFIe zJL}6}vBAy#xe?z8`ZgsE_aXT+|tnALy*wVuksQXda3^8Dc5=gf=W>d7qS& zL1~3D-M3w~*E>QWHp6HF`KTVA7Od{jQd0*-zUSN>w&J&Q23QQj$g>h5zcy$2f_nb| zm)b@`TaEfc_bBFJX8yPJVJJNm$SX?J1x=f8x9K)``8c-|=UKqVuZabcJBW2LGx-Zy zP}*j)wX8+u)uF5!0%BEsIN?v`na|2;v*s`0IT_(GKf=erdx}d!vTLhqe83$m8*u~Y z-_fV*8aTdQwm?b=o^T$JrV>Vq4R{hNGW-xiKrH1Us=*|Tpe*QFr>smj6q2OGd|N2W zFDjpCM_*vTj8YyrDph$v87b*$Rdnbf84bmO08IiV1uVw;kYm^=$$fQ<8PZ7S;}#H> z{Kb;swqT&#c|dqS>b6Z5F@N(3m`cIF9mzy?Ud8?-;%tbWq>$PiB$`vLH$x^5CTm(J zq`s4mb2oI!)-}fx52S{F1Ca@pz0x}1lTg|e&~VG{E)@-h#Xfl*;Y`)8?13sM@qU3D zlmMe%j>0CV)@3t(vCoSm3%Ny-Y+M2LY@6CR^YW5Qy910U&iOCv?;z6TSYyq1cxCs= z3vijLw+K#jBJeff-mfA-u|IZOL4;dz4}ex(W*vc+XnLj9Y#+doRX^dOz-8FeQ_yzl z;wd?%o4@+L1Wy8xAybulDi}l_!DT%08U)bbPuW(@4$Pld=FK!TaOgyNPdIv)z=rzj zvx!9Yvmz_KB44V|9!s28%lkaL#wbWw%edD-mTf~YjWlv;wCnIU%9&Zv6BOCjom;g& z+nL4;*+g!@2b;VTF>m#rc4aK9LX6e_^^i&+Om3H4L4?NZyZMvtt9TC2PZ;cLe~|>KJv?NebsdjO5AxC zX>TcSH-S9ue?S?I0Io$J{W_`M@Bp6RaP^~>) zi0f!qMMDV2-`mmge&vFX3!26O@7K+hIfRV`c zXi`%QzXAEGk@6TvUtD<%PIsqkT*!|)?3JDj;1PsM;Uow$vL%Sui=IAvqsXgo$QnC3 zPup#w$1*dTe8Qo-Ty;(|$uK>vC70=iyLIQpFAhRl*b3>fs>e$*inR0L9~$FTu)NNN zYL|HQ=#iXRo~fogq|!?LlOx#32eLG9gVHBynH(Md1NREdXIx2-1RSGe95dXeAin5n zQMWf%2Kjd|s-_N^ip@H$nxZ*MG#zDhc|@P|&MU%(QD&v z#GkkL@~I9F8uUp)u*o?(F8wtCaOU={@QJ$_4zdo7{zn^i=Y>^G>F386lpMy81ZA04 zKmPbl!pyf3@jajeW%Vm@t0l|RMgzOnf-BN6=%mZ^aM!CMletahvSH)V$zWj5l0{~pX$IT{aZTQ zVw7Gtt$n$iOYB5;Edc52qK+C9``Kxpy=blo!PF(G0(X!RL9j#pD9*Fr_J>Z7g(~+N zuLrVAi|Zz9v7qxFY2BYt@$J*sw?eP2+DGLT?i-OD4M7Jf z$=ckCJ~fQ{m{ZkI;<-g!2&&X@OLVegN@R6&#(_meD*StuVUaNWPFXXf&j!)VYzZh8k zM&R1-O~qWd5u2cG4ri+VYsc={#Ifbbwsm_aFR$+Kj!mAeEBM zy34pOu9%b5-MYwQM2M@t)SpgK$19HE-gebI(gc?*Z^-4jMxh+pSlC+b`dJ8mec#1; z3y1SY-MVhYst$V1guauK<4}R_OQ|Wis1NnsfP+Mm63npk)YrBFL@^3q~HE}CY z+5I94$thcs5*5}uEugBGb6qV<9Y2^*ZLei5u{)ry-d<~dcI-MT)J=Ud(Jecno;Jp8J)zQ1q=+QgoOFSJV{Wl~E%?3DAlhpH(HKbdz3!T&i+w^}bJ4Vn6(L}smOCMJ_M2j`?maRPeVFVik+`JirAg?TR#~pLqw>b$i|A5onvsYnZb`_WWMF_vhgy}_tu4h9sHxkz|b25|_uj(^4_BZNP z`Hnb+g_A_&3M0};KAzku8q~oqw2Ua}yK%#f7ODvtq%%2N1a~+Q(_x+EjO`GiA|o`z zdSQ(nv3uMm6=ndfW5r9$`+bHpi#h)EH?E>S{>=jO<8#Bwk@^?PmTO)M6WXa-B}&`&bsfW8w&jmXv_sN5a?k-QrV3I_}D3%}crR zNbCXc=fxCZnWJV*v6l)R`OtE*%i;X}!UX#^OtU0(rf~6F$Q%B&GF2j%!xNy(`sxE9JS)rPkgnr@EAD@_i*j zE4oAmC~Q0L-Q6|N6znrPx=BuP_5CZ5Ck=t{?{YhR1Jr2Tw!W7K6*|_yx0Uyyd=e?Y ze9zMnWJO#t{RoA7Yt8S|Kx-jTb}E?B(sYnhSr`tjN|LUAzeBo0+WMdIkBXmLDk-w) zfjTM;(-2=g8XTfV%EXk##|CbjNECO@P~}S3xrk%m$CF6?rGsC55r%8{7t=y}gR6D~n>`le*dYfil3R71tYdfjQW+?SWeIdB!Fon^(pPNxxLqbL{Q6lKOfwoV!I zzQ`+27V4qBR<1!^&K|ONzxJh9I2=D-kx@yLR_PIb0!L(SDWpxSnw4%&r?izeb|+-K z!oa2GcO_|DuLR4X^8Ov-FN> z3EwZ9)~pY5{5og?yVy9(WhgP4B+r@+;^Vy8lnltJ%}3yOEAi+Uy!dS`WC@AqhWbz( zc1S4J1Peltcs-LEy&a$`=P@wdJcxM69lBWN@_WwgC7G8RJLmYaho-S9Y*TuVt&4>Q z_@-1mqHR#3T(;{24ck;j&@aCUQy6bfZ?$p0^l1l*ts;E&7y?gx#|f%Il_V-wR#V45 z@(w#?!dF*UODfe!JrJM%^hv)~a5%ZtDHH?FeM;uOuZYJtsTl5;ZhF$b0#_|^mx9p& zqWI6G_TQ?Ss%16~x>GZy&4Y3EEQl1x$tWSqxf3xwpM|W#X~#62f9c2im)Fb$z+;yV zO}4ae45|vcHsVRJwi+r`QuLnixGrl|Ir`orXE%ZLNO~#GT~{3y6BdeuP4-~(M2L4l z1Z#^JPofedQZ{@Ivq}?Rp53mqa4b?crgV4$yF}C>9v@X(^cCw`RT0Mk)TR%6x`g1w zvZ@}d9kxz2Kl`1yo%K+B_x+hl2<8$(=pF~}!{#8tAL3(^u$gU!pXTqTfpZIXeJJ0z zarlX5+;1W;9kfCkDvVCCCTWqjBjYsj5qjEjGS&TV{Uw*OX%C;j=ZT~n!xO?tGT3)W z)4-w~jF!midJ`}EqUCvDiOq}N9EJkZ4EybJe{Az+qNu{KB1w(Hh$1OYtnw>AbH>tbwtq!vFOh`Tc=j}& zqo7p;7F>S>BDuiCH!lI!%skQbD(7f5PN<5~D7$TarJt1zRBJ}E6!HqMU0~35J?fkZ z_Z5=r6+CpZZ&1>LGk22H1tmE@t>7}?5O`F=!|_j|6A%@6JR>gBTfrjj9+#SpHnP=Z zJk!Ba-rhNwH@q&@QkE$aIAb7Wd!rqwdN1bQJk)#bAhH9 zD{j(eKiAtz>77!y_`{^Im+jKkz2vEn@KCH$s*NwuDWzFW-QuTD$CSslkHk?V0otoy zcZPz^72=46gTqIo)eJUiGVpLlQD#=ZXCYJ8|MUww>_UN2zbRoVY`QyJDHw0gQqSmua@HcoC_Qr!B1gn5 zqe0?ymni$&4O{5g6=;2lYnA2iC;=)(64@wtIc1%+Q_{-~6mjJP?c93NaBYEz+wBHJ zo7lUeAm(G!E0T8ZT0fQhmSx*xzU|L_Hb1)6wQ(3TeYQ}LZjICEZL{#EUrX3Z#yXNW zk){<&nqbRG>idVjsmyR-*D9>kyz2KpZq$WC^___7=#7A-;2)`y(<^9FhtU;G9^KzU3`irKS) zBZW6iEBNle1NlJ1tT$LBK#LKJPcKV*nq30vEqjM#o)WW^O=l!VuQNK|Z{|1FmK47o zcM#kPxtSEc8ALR4spYl)xyi7dGny~4|vXDWD)cXgH=mQ3$J z7*?zjnj4>fur&;A9e8=hJtC@Bf$0)kogr>^4$PN?Nck<8WpJFhnJiyblx2B1xy<7{ z#d~V3^cBq7&9Nd;L>3*Df?~}j06|q~&hY`r>v`pR_1mLpfGLxeC~U^KbWyQ9?j`A< zc?PG3%1$^Ecg7wLv9KoI16*c&G7VZkIGa(-9^pK;c7&AD?U4TP#7-Cj0)h;cRS;(% z%eDcY$xA0fvbqusM7jIk*OQci9En$AQvaJAhE@j97Pucj@=JNj(e$$JX=hS5wmzibS#=u(LZwvqlF5Ut zoho~j7(yDN)5<%&uq80JAEpYHOguh*nT`sI1)XR{AX51y9N^cvJl$U)PK*JGSdog- zc09h44>ypwQNbti9Yc*XVI+Juxw_jdYMQ%M&&PCI-fgP|Y|K@fq-swO{APmgXZkLJ zs5R~)O0hvg;w3_}bgZwuLrwffUkdC|b%^4*8gb{(hKAp%INO7|BE@q0qMq)bh;K60 ziO`1g5rn%8$-_`-i5qY+z0t}{tW%;k#vEW;^Jtdn_kQYusfeD0bvvmJ9gBGm7s^_l znu)AI6<03~e`Q32k3d~@c<6iBuo<2lfQ5FuFE*^CvylVlf)a=5_GynJYxu5Y(zTBM z=9u&4Tt6(D3&=A9Lu^hdX5geT8V^iun8`gC8OY!TN&>Tc3z}gIP3N!Qs1x8Up7rfVP&yyQ19ceTSp)17k1&c81qd z9b{@14VU+mGi1{oY*Cpvel~UDuxa$X-2!ss;USVnK3OIHoo83Vd(6scXz%&}sCHZG zV?5Tmd?MPsplpoGbgJI2KQA8)L>SB=SUQmiC*lL zU5~+sM9RU3<&<|lTW~lxtFtp_yIecQw^lu_%NPOThl9nOp@q}z7;$roOI69*7k!B( z$8%e*s4$Zs$j=sgHC^Dc1?|tBJk85DhxTYIOc|MUsFrufx0xPQMr~sA3D&AM+6OY9 z#vwo;Q(f`WXqk+bi0DewKoLNqNYj@#Lwvsdq=VF0U6fv@z~oHZ&aNh|QlE}Q z;Yz%6Ktx%0&~o{?Rct1}=NZxv!YuM++n^;VQy1NCj&7><3*WBDZp)$E)-~$OGj>NF zo0(YR8qXM!f2|!^4W>~_`13We*xC-@j=p~d5_x^_0FFHzZbyxK|gQsSMUX&VM-G`!WwjZ^KFtK$TmGY=c-=3l;2oVN1&{s@p&Y zp5S}Ei3{`=J)tR8L^C0d_rX~k8gl9~tlwj8z?FAHQMRl?sHSluW+$)XyEM&Vxux!F zDU}X1=<28+uYZ32T|z*wrtXo|W``Yqg}ml=>+OZ+x&f0@JV(>BLmh-=b7owqZ^cp-i( zfwcftc(+SMcV!Wjw9!kj6tdsrz#R*OC&txzL@Z5#L)zP(Q|j(%0#!cZ6C2hx7Kmes zgNwxT+}rnCm-yCA?*7eOOeIhT@{BmjM=tjW%HM}va)$0Cb#xvEvx!kKWn!~O(kv1Y zD-0CQh0qX|ET&lzYp=xLcuSpdrOX;k5^W9q+qK+YX07LK3F0eK0Ltt!9-N2p3N7{2Ow2C~xY;BI5)BIR1q*ReNhq(Ntd2 zmhFK$dNUeg8F$!=^FS|zp>m%Ta;$w*+1`sgNQT%VNX~U$VlzE(k!WrL_q2;u!=RgD z<{Je^%NrAY2W{%8>aYINGOSQy8v(S#8PYRrPVp+FY}!WfDE%6B5S3rpFr4OcXj{!w zs3$zpkY#p>rk-jsFD>=OZ%%QxZ!lMou}UiGqws-vw+F=8e(1RVG7~V3s97k){j>)C zS7fD}p5=ymUpjcwVPW!)0OX;D3@2M z67p>J^BdPrmX4fl8&j2T^3eieFl&MnpwJN}uv~jvMLBMkl3CutEUv_9c&>EPx(-nm z3t{ZMjM*^Mgbu!W{;qY1k0wCZ+ciz+CS1Zk@$01jyT5bZS6@!%t`)`^3)jmoe;v*8 z2it$q0ec>$FMtT;e2~n zSi?SA!hn+e5GXW+x)zv6967@|vAv zt9gdi;|w2uMLPM4(6l8rAiDEw#A)lf2^tC()~y%Cq9Tpmm!j&~B8Bt6zt5I`zd5mhEyY4r9Xb`uRd!behe03si>k zQcMe1+$Vo6r1x(6(MI=`*uumpY%cK;1cJ>IkVFhBUc3{p*^=3#3V- z8&O+cPbu9toD2B#cK}{RPZ-1P<`BqlI(wfW1cszS$xTy!QWo;luuNSn^W9&mrv{OT zHAf)9SKi-n%p0=UzUCDjID3UUW=tKnN7C-h zZVrfK#L%}$K8V$hrLbgl1l0ANtyt)RL@jYu-&o19X=utNFyN~C_ROEZWcK)Q%*N{L z&gkCV_r%6)2JI2XRzeR!eesC)WA&x+c`mkK;)IR}N4C03-=x+3-V>;s$272MqoP%p zrbyKxPp7q{c+i!r?!vuOyauKa;V*k0Q$oPh4lvCt9yrtS%>D(Z;fu0;Jso6LmO7ku z!#yuF(80Trhhe4~tUc#M#!LK-lbw=(@)VJI>Qq=kXhnPd#0y(DzGb*G^Lmn|{=Jw|qr-(o}%z>iP)^HI{Ar_r-szwF5q@hQ27>N61Ket7)mH733OAxvLAwkt_snz0zYZ} zu9;)6D`wCbQr~hpWkh9T zZ)9a4FHB`_XLM*WATc*KHy|%eWo~D5Xfhx%Ff%bRATLa1ZfA68GaxV^FHB`_XLM*F zF)=hWHy}Pf3UhRFWnpa!c$|&51yq!47dA|HN=XkXJ#=?>cL)OvFw_7uGzdtElynM6 zgLDc~(gK2n(%m5-DWLF;C*E`3_y5=WzBOyjJlF1h?`z-d85Raz18zBcs4Z9->JI1T zSMc9*92R4+7YqV*7mS@#lPF!3ZOgW8+qP}n zwr$%sPuaF@+qPYGzo#3~5&h6F`yb@W%)RCu<1all2pt1Nd>lp4A*2v(8Mol}25KJ} z;2tviDKg^e5$N61bL5vT#48dQMUW4{I{*z{0QV9u?4X`PfcLwHAWqIfB(D!2(8lc= zfRB+8v6g=u(83WfmgelGz%0|22z z=z8FeAq2X;yLUZ0Kq9U|K^f%y13=fGW%WlnAo_mY5a9j8{SW!J{%#+z;P#&b*v5w7 z4v)a?FM_*x0Prv>%)H|2ap2cL2LOTl*IpQbItI!C{3D>Cj$kW9FuxQyV9Loe0D(xj z{|k82Q;ZpTlkQJ-u1JD-X><<3>nuG3kVef6A zKQVYjSI^KL+jS3bfY>d9ynTJvp*|Y~;w(RtI0FvBFf|ns0Tl>({p^ zP-`Ds2=4vfKyx9)We}jvAHz+h z>@UAp0`~CAA3ZdPYtKOh>wFMV+Q5&$tZe^(%Q3Wdyu+K*S@xReF+SJ$48)#BZ9Da0igf^zTvFR;GbUuc7X9C zxKLspfQYz+ftg_s;babOle;Y!hMgJrITUCa2c$;wM zKU6Dn#Di^wg@YWt#VZ#grGX#(}GC&{(OHkN@U&`RvZ- zV;=vbn%Nw18`eekH)vh^Md};Qg{{7?Z@W;QBxHA);kVQ~+(oQpCr_?N<{Cf}oh^+b zd}~b4Q2-#c;e2vfZwHFL+M<&w;>$SPO>JK1qmHZ-7UNMdtglD*P5nXZ{Kygc2ew`0 zLAGNWBj)Bt3|5jZJI6$Ci-@%_@sRX?AG-KPL(9H-_W4ZW1CgmDVU{SMjMlN~P>_D7 z=^r>|{7}uRgo(V(_#R!8dB4SiU(=RX*Yi<pk5enuf2b7zFNn@4Ks{^IQj-*j9Oe6?OWxj+7MK9?Bp=~^mD0~Yw!{XzaMVXPC3O2J*~W@MWr z(gOZ*R_r>w`#Blugl}((YWvZAx%>y+V(*S~s$ihOYlzy}9)boGx2k;7p#<`ZrnCM8 z-va-~x>3Os>-cbav;U+xoyLqT_GzC&p-o%o?6oFf{-xk-njweeEn>wu70LUjnQfo* z`gLikdLccsKc!qfvL*>^W(k73mv#A(Gh;o7I|a$m`C-$w>9j&ED9ENO_h8yec#ZEf zGbn#eqv4sWERQXdDDv&kahPDjrHIumhSpdV4#NM~ewN4O@cxMc(D`K*%Peq1g<;U` z-+NZ;-@7VnjSHVvV|y$B2_Ypf#TfR9=d?Fk;PxRI&oN!e zwyQO-jY*~J>oB{D@Am;S?it?IBI*Y)K1-tIhPngApeyxi(LO%sSu<(i(}QBRH#m<( zWk|1~VWJ_#K~FN<;&~-JX;Pjz-tep%#B2}*v&2&SstC{v9Z;lU@3rDCfOX7iLESxr zUgx&ORx3D+MG5@-eZnPqIT9$W9erHUG&&bzX_oF@t4>X`if%WpCZcJSz5R0lx`jeV zFtdPAS(+^~1gYEGKW9jyQgRE*2&w;=f(~R0%RR=0!%)Q5i>d-XY9WW)*n564fXV1f z+sdib>E`Xb-AzS{EY?`RVxqyo4#T_pHj}4^J{DOv1=yCm4=`76y!mEf$;U(X*7x-q zN5D};fYsY%poOtJOM&Ed3K_5A+zxx|+02|dsfSJ)Wmdp%n{_JxAi;#bI((N?_S9_5 z+npOx3QoUp?&^K4Rq!msQ(sWoDl`Dw**U{KtAzSJYMeOe$37paqwslBoSq@?iz+Q| zI^c!=3i9(0oFJlS<9La6K`E-!N6b(`9GMYt-G-n09ktQ{ z)W2Sgzk1w7} zGDx^Br6bcB!`Vg>b3F@K2j%72_5dkX802eqaA2v*viEL_JTNt$NH^rQtJCcc>oF6uDNQfLG%daH>T&)WtocE zw_`W@;*@W!E6 zKPl#GKG(baC3rS09G`c{=oDe?NnglVlmdMC#v<@#EmPYY1@PujTI;p?GR4wLAI8IE z+qgr(s6q)C*-Aou84BjrhH7JXQA4e>o;H&(qN+4`b4Lfw( zB^@Oz|E!fS;UB&>jx`+fcT`pk7qcR*PxhuRrss znpjSg)o{Ma3|ECCjaG+(6rlw#5juvM*~N#RqA-e)rp7YSaM+%$q^%snxFoteg&uhE z)Z9_&yGvE(n!I^c#fSrA?HPlD=k|oD;^MJ2C9mF4t~a7%A%1-Z#pv=GCsZuWWb4aG z5?1(F1q2~v!myMbst8vAESe?S4%Oh{<4rC*%lz6A#%C)W;tNA&HaqgxhFSo#IdDT zK&PN+UNC)?{8#G@7Ux#Ie?$gPQ|0@+Lp#*l5b{&&B}`{g=IO&R*uCkg9s24!{rLBv zQ*R{^NF^3HlE8)>`c2kUZ@bfrJl@u2fDKWSGC=WRoE<7vM>(>(=-2iCVl zCX~HSMvX*pVSDU*i1@vZQ%5a9s^L=ZwI+%Kv05)xFXu@H^xZr(1d2t)k1MtB+@6op{cEY3s|u)>-4%{}_J(@Y8L}91kD^)%Zr)JZyd4I=R+wAA z6+T1sc1G!OZ?>Mn7j&do=89${(I&Ljy=oG_NH59I8T>o4qs{h8X$RUw+Wq1$lV_F<)O6>H6Q3 zq4XF~6YE1L_D>%3{E9rqneBe>^nf!5yl^A_i>Z&)tYFgAWZi|0^i4G?)d1*$>aFa9 zop3ZgHGOb4d@oHP#iMHNv*w-s;afk+JT1AtZL8G#Rz$7%Ew|4-g4@cn%- zJd(qQX?c*;vwv$Wzfa)I%BZNAaeXghkPB1Pe`uKj`I#iPI^6~>X7KURs13-Au-%oi zj&@4RK*)}Gwz^nZs=u6|=dygMokGt4DYc-R%m;&@90^qfW7y-zZ~1B+U+Ouqi+@Wnz)!Oo9PVR4&{=7vD%P$|; zo757&de5|Zne(HbA511|rm1(27Atu}K{~P8TK<@G&#(JrMT0nJUaXp03v@?&9!JYQ zE3vFM2RqXn3E{>(v2*sjTirs(jt9^bxB=ET8J+#N0`5&NZIugj1yE#iY)jR59!Ib& zsdnj`ec*-Db!bvyWE|}ST7*nHYiDYv&57-2MIxYdmAS*>?Ahp98!-F+I#AC2x>NeZ z%c#^XWA=Nq_z&mCQiK$|^!jD7BBQu}N^WrK@5f?s;LAH_2||1r!*g%Hkma zdp4Z`yaWi2bVEw4w3Oz@sRP&!yw>PizD&q@6k37^i66Ge4lgyLvL0c~BgWl_2ghdR zla4Rf?drEGePfp3IYBF;kcqP{m;L5sG{}ZT*lVhZR`lAEOcAm>f!$md{)~ZT^Sd0} zRVfatJXBKFaEgiDJG==n1La8}QU`xb zj7l%@WXp;&@-29|ho$y;SQ^V){fn(7>%3~L*0_PKv953BQhjQh6r-!C*mZ%!vt zZ0aUeWdEepFniy*=wIIV?l9BMU@~SAYYbibP>bIeYahIooRpIAfhoOIby7_?K-dKD z!28XZ)!be0$vwUDD#Jm#NU`Y-K8%LJn(4leWb4!K$(~sW{%K>_C)9)3A`g=A&#SVA zyNZZHc*U(upyL_9mfwF5c%XKHytz<5TMn`RwRbBnVv>>C4~8mJZ41b@saYuZ*-Ib+ zt+b{lbf?qDj3gTAZv2TotjhR5C$0}0R>k^wxEC55X?MJ%sOZX=@9Oi+Z9IBMR=K>D zk###g2nGpH>fEcFax;SlTq-Fk7Ou6I_~zZ(*(%$;`ymNSXl=E-<1CzF6(v4PY?z*A z?Bo284Zf?F2y!b=<>P3fL1oa7pqKR?E~N_7I`w3>3-gkW+PoE;Z?&l%%}s;LH7xIn z?$~B=CR1fRpNq9U$NW+AJj8?~#I18aW{-mOMGe0M#m-kFzY%u0t)KV>Y>FKA1B)ccvk6iXi zIuo~uc2a)&s`)9KCw?-S{{f{h##EHueEX79kAKwv{rIg5CG$Yboych1L{+AMe>`;$ zQMk>_@iiw_rSIE{^>9N{Bfg0c zyP}t!d`FvT1_x~sxaz!yL#s-&SivkB)Gkxv6Jv@>zRoW^BUc^f=#Pw9-pMCdv8lbP z^1&neO9+Zv&9Is5Dlc_vy~T@8qLHG5SS^69w74;!NN+$W!xj}6kPkdaj*9AvofCw5 zVaO~+a*(y3pOslIxa?$ z{9sLKhA$YS+n-C-x`UD6EkXD>oc@=)h`1G(1dZqYJ&NSM^G8XTo|5mn9o{B(euwO> zwg+)#Aj&;OZxb~sGAVLxM_tqxFD_NoAkluWE|YsV>cULfVkXrZ3(8vp{?UkBwNZ_z z_9iG$Krl~Got!QH(^3dt++UwVa~0QTbH@G{dvPWJ6C;t5=R$E$g~%rvdKI4S<~PA9 zHcPnZRK#WYBP{=T$e0f=L*7igjnLt^a1yN$)DWL|~*#0Z@d z(te>c%R^M!2x9kd9;>13zba?q%e7>gJnc;I^w zROQpaV_;jy1$NP6d7On;Y4wH}6Seg=vu9gPvOBZ_$C|=S??w912llVQ_jU$H$D8?Q@I% zt+CTJ`u$|OgN%OBysCaI)AY}S6~=cZyb`hE<6ptCd3FmgYiHMNd(=$N&tY1x8-7N5 z&}9(3a@IatXuU`eIV#pIXrDo7(h{LVVyDTyjcS~~TKeZd>5OADA;9r?;i0N1?#tdK zbcKR^LSL1KttIwYKjHB-ERNrMo<{5wZ_NyE6MTg}j6~gY22Sl^%)ggvk=3ROH8&#f z;A^>A2jHjY?_Z98IUnaoC?+c|@Df|I!40{}c`L^1t0ODylfF}jwml+TBVW@pL-Y+8 zC?iveMv;j`n(K-Tl7jK<&duLSez5S2TGnRUlk?A;{DL&2xSBH7^BEvely7R`&x(TBVT?+Zl_w6IKz>BqGxO z%ovwkLM}`kmLD-n`N=UGWU$j zzR1VN$W;`}{Ssx+=3Y){Ejue{L&4Qb|6F2B3-}C~ve?ulOJnK7&3YLxP(7O(ChieG zZ*V^p8IAqgFX&Gy_-^sduR$%Qk{stsfL*5povvp4?D|Adf~N_R?VUJ9t`s#;-l*| zF!FPheoWD8O{0^h^G|eMeU3yeUp>me6Etd|3@R1R5yG}{6U9M|_rfMFN@c814 zHzc!O^?`ZH>8_w1oATG9Nq&g9fXtegz zhxPj2f_%(eP7pWMiMjMnCLNQvft;l&RdYtIcD=)-1&DN6n}cpcVR&8m8*uql9UV5x ziB=wTXP)rZsFV!NFPAD04tNz4VV{OCK#TFmJuoeN1M#NaXPl%G)&1Mrve@fCpQg7w z-tI>;aeekLB+|pbIVNdVTui!r_F!_UyKW^Ed+`g!55+z-Oaivpiue8_Q4kQf-{qAj z!uI?ckLugi#v1j+Qqm&s&Da8>@Q-t1|e5Wg!;X9Hmk++0TpKTP01lW&ds61Qe|I9W9i0i%GD(7bH@f8K6 z3jUxY_9QJPPd@TKsOlmvSM7Njt3n5BvMc1yN7-=Y4}aR;&uA{&hhk+4#~!u5j2L!! zg``^RAwbC-;bb8%E|g6!vAKXSL$H?c6RVJIp@~_{T^C@weQ!By_XdI(z&sGt&pz^% zT%RYybrZ?8hfdhaShrBp0S`zq3K0nYx3{Y!>drTG<23h{YRpDZ^RJ}~2@pAoY;|zl zS;LrOriMxfu4GVc~BmWA}KtgIpD;I2MN1MK5Xsm2lKQ*NN=mJX&~ zn#lO_jO#g9LB-Z&q*Ra`trX54=^DG09Y5jJIa@1xsWqI0rjlgifu*I51vVj>%F*mr zfq4G_F14!KZ-8|I9bM}x&T~pth;Kh1RB!P$ofZsL1G>g8;L&O&m_B?7_VRkHbCqh3 zC=c1le?r$b^G#4l&Z$UlZ3gLC4yjt9ZMVN5e(xa5s_0s@U^ly-o z6$?tvD)GshX?d;>v96IB2H+I(>WCD$QRFF7{r5k6Ts(88LW8}axw9NrKODL(R9d=htTiQo{v}rHozb!B{nwtO3z$l)KmjLFRp$3Xtw}Zaql~}n zVJW8Wn^6`0rqx=v-I%`lCv@BV@1%+x!B=YIS)u2r2faT#78+`C;9aXqRWv-soYls4i203&&xcc0UpO(w^Po_+`p;pT zOva{YJTaU?AfiI4I(t4Rz(SV=?ESRo>9dODmI@(3%h`O;`rX;kB!sI?Y3KRk65RI< zh72r{oLnYT1XXHv-C0{P+Dw(VW#J&O5ANLA6X& zmKKYYc`Sa6-MDBk{uHunjULYztWXNvvSnbsmNL$B+V4cyv&4(!xI(bLfe8CY0n~n1 zd&{KPbT^JO>veAp4ax>4N~AP}5;oKN`0B2jp(hdvZE)|ih~g@@Oz<5UWdZ_K#9yA{ zLgEKWQvF7_q5%?3w7Ud#Hi4|QuuyVVY_);u52xInaln^S-82bkr5jHO#DAYLOf-mB8#t5t#eZh$01T!!4hCzEwCG|_lmu5 z#VG?5Req+|%8_HkmihK02XDTW8&ZHeTfqspOilbD!-2{nAK>xzB>JG-S$)Ku(GzI4 zsNv~eflW%cgM%|9p8j6o>*h51<-&Jhq# zxbB$?a~;aUPt&Sur5R+J(F#+pI``x-=`M`R%7EmaPrL8&U*)G~^r*#Kw)YpISZNwb z2iPBKZKCL29}J4Zs zIEus_=tDO>g5X25Q&GO^qB{bZ?Q06m>DW-PCn&7TFSZM3T`BgltHq5|Ya`djybbX# z6Z`rUjnSVMtEGA2Q^8<-Joo=b-%_zmrg94@^7eJ9ZjE;v6u(hY5^ZM+?TRT{3x+<^ z)xSM0#`HBoRIj~I6RJxUAL)!1SrVK7eyou$sjL01@t!-6A!EDf;DD(Wz21{#UH$3> zOxHQu8v9`_X)WHPOG+{BDU%&Ac6#Jf&xhQXw-scLD^D7q}w#%85P^62HS&0b3hbs^VqL*_iZiV!@G|N zYK2Vb%q!L8SYTQzDDO&2qitZ@o^XVB7?{^~UVVE7woTFU&}nWc$!Vwu*3=I%TYT6( z(@+_s;tP;^uWufGl}{nCAYlMLgGGxat$LFQTCn3%;L@u+`r&Lg{;ce#!> zcicw~Giq(E>_;<+S_HCfL0U>}5Rln-chWhvkcCMm5iE=q8#yeSv1sYCy)vqgb!*bL z8Dv;bj!Ho3;feclz@Ljdhm$eF2~vdJ)_?M`UnRmeV1K^%3t5&&1*l3#msoSPXKu7CKs+9v{^A!_eqewA>0RGAqNf@e#CS8G zETz9~8TfQOPhulW7IJSd(4kTELee#P%I(eDQV@0Y=}@jwe=GSNw$+oSqlJ$TsKqrH z8bGAWwNu^!1by9j(kDl!5EvhTG)8sQCF;%%Zyy@C#EaaciC@ld@&=t&RWE>55u-hC z`TIe9)4v!1$d2#5Nd zH7?fkuSH%F8@u0j?@FjDz5GgOmn3l_$vu=!NO4S-wbHl!H3O`fZsYt2oqvv>cNv8u zd0m6UPz3boyaUmcSEi@ytT1fF-(jdtRzRfNv~iGyB>5pe$L##j*60=@Wf~6XH!0E1s@>-L1-C1R zoWhxR;(5ScSHT9bAs>fS=dpF@orH%k$OoKN8bRXLbAFSnW9RSKhi8Q&Q_w0TY2uLD zys#jMNp>|=@|oe2iQF0YH<6oak8kEg5v0pZVyQf0K!Wa=NvP4S_f^IOM0-dEc^atF z9jM(!1oYZpUeXx_bf~H8EvamRS2$@?_6c^WUN{}v;n#t#&E1@<;lQcgza-C+>kPL@ zqhv+G;^4f$7=OG*6tu%S+X!vzu-1Gy`jc}1?ILVR1@!nf?&!@>v()qs19$kJr)~U+ zu0I&@R(wj=;b)S4&$OeMQS)FTVncI)cXDiuWN~!*ri3bX+1OXwA9A$P-=~}!4o4;P zM3npO*;mU~u4LkJ;&m8{kFb(Yz#>^BnX|Qi`V01HUH9Y>6*`&P;<3y9AUo@a#l{iu zI}2F8wqpL6_w{QMT8U#;$G(qkuC+2=fuEJ0D)bwZYB8e7kn5=m4{?-~uXd_f>M~bK z6}=um)Z-P`SZxVzYiAgFMY+P~MmKQIcw~oL7}S~HL=Co0Kd}J7-j)rL4f9_A(tsUmCuR2dK0zd31?C-o3wB-_N zyN3FaMEN?}7A5{$#2uzovHuLWwOXFU&W{FX8$Fs52Z5&;!H0QNOxfr;e7kTWVN+6*>t^$=3S|?LSZ$j+Ic1W|sx!cf8}I)1J;VNz2&aHznrZ1SSuUnrd$JUMefuMbxhf#s z`vxt0H>z+RKurf3OUNb>0N|OAy(nK-!Ek{M8o?(YJbR&}qlbK>EX-2t^OD1s)`C6H zC0Usqu}q4Cmsz0=MdPlNfSEx0SMMt%Bz(=8==%F<>T?X3AbN4zvo;|!q6TK*Uqh?f zs8w@ru*NNZ^35Q+PZC1DE;D~CzC;W?r`yq$cj_1Rgqb>zB9{g-7IOw*gZ)(@P<;&i zFUPMcQ{6RNpMSd%frDbwOUOR?iMA@f!02WaS$1zhIoVVeG{C2qj!53RI(gbUAk~R1 zjnB+*vxex2dGV4~6xR!lpU~U8>=*oYV(>=VqeYT~ZB%1vAfi!5$>TA+&9C{AI`R9* zqNqmx-a|(``4(zm2ei z)X*EBqb>_XNaD@uhpu8KES2vS>vpkKo*Flf>VOYbXSrRuJvn3iY_{nWO)2{*X2`nH zaL$#wV5H)%yX)#Th34!J00;}=;D1RK#7>LB>qUVjMC)fp45L6H$q3oH8fPkPNU@>|e z{bk$xw&SmF^{uA*#cXbxxyk(1FK=e>U-2BVb$oLuB_W~(9s|7u3_)E*1r-oLAc%(` zfu9f>8n8JF&TD#h!U)7^q>~uY@GmgI9b|A3BOfRQR`8Mt5rCDR1Aqnq02&f7babEq zfFFXyv%Ww{Ifek><&6#e{4wZ1LPQ1>!f2kwow=or1<2TqQ+;WGE?jT`8Y-&kA8uTN zE3hY*)?gxlEQMy|Y1pP>Tokx@@lDR5dA~o30lI?_v99QchmZI7d!ZeLZV7pDN;tcK zc;-#W0&w90o*u*30DWNK<^sEV{^SRwMgW+c97X@{PYLj5_+@0UevbWFHwF-> z^Y=Q$55LrboJOKSJ-mxkFyR8lkiJi4hu4q|!?>OJySbT8q6EH(fIb*-^N^mQI>PIo z?GG5lSv)-k)zCfy4D^FNK5+~z0KiBH=m-b^13Z9?x?JSFx<@d-+xk7hdwO=Wpnd@N z67GILW)PbB4ZyGuVi*Cz9z%fUa&#JoeSYA-W{3fUfSx8?ECXm~7cqoiUEHHE&hG}s z^t+2|Xa;b@c5tu&zn|Zp#^L!XyvTsBAJ{+NKA%mhO|HvN9e=W4cNsaj3uuV_19Xu4 zdtm_p1`HS=2xGLsKbm4-*WW7G`Mr)x2yhaB;J+QZ)12Rx#y5Q!gFk6poB)5cB_SgV zXyE$487F825R>qafWJANzud>a;`chLKkTW$E<#dzj&JvjANTJ+Na3BF13!O2hUym~ zW0Zo(;d6k8Jq6=+{1vOg>)f90U+&7NFryTLXounYOmLcUXr%8WcQH!Nufc2AoCP;I ze~zay`*&$;2Xhb^@JOfMmv)0jfr7s%LlCpGC{F=zB9H(tFQFd@M)mjxf&c&pvBFn|y}f0y`v;-~3mGT?W@mzazzfOutE>S6 zh=93|^t<@TLIC{3Ju-f>^Iv>LKbhq>ei?>T93>5V*~J{{t~2ML{tOtUp;S7bw@cjbCVM(S?zEIZRE=0b zZbPbz$p3K-$Xw2ElvRE!`;|iuPYI+!S;~s7S&teWWw-@xI>L&`X;VH%RLuAJ0N8bL z5!pYLlyiONqpQm%e>|ZC5)vP?FC$C{y+uiW*4oaxq@u-u>xKE^#zWjC)B}MCN{+aY zMV~%aI&%A)ALY#Y`ji3{L|eY*%*C}mZ7J)YlVX!A-=@(!!2ybsH>`=zfw?hV8RWhq zw_3M5v!>!C_1uXL>LH!K+fZPwemmL9v$Z>$t^|NEU$D2sRt@sIjqWLqI=fTv0O_sT zSvn28p8+_f4-M2NvR0;j64YqT)QWPbYWv`ix7XN9JDf{G*^3c>jJL$4wleK5+3O1$K&6F^`Q>`A8j~IKP~rMVud+=Dr3!3x!+FQu_@Dj_6a;WgMb4 zP`J|~e$7@-$&G;Sl(37aVaHN%KOz7xU3nh14;$z|)Rnq*(Dx-`y!Mc`+%}tATFj59 zr8F)(hAxt+{Vu&H2j^ujNfs<|*M%cf_wrr2$?XEO{Ni46EUbGZ$u{4{zd@(c2QhnX;!4A0!0#8povxpy=4iTe;k8KliIv_jSd9ks+f{IO z;o}@u&P`3_p2t-)!REBnd1k2Wycu1=(CAsccr1MGf|eGK8=grMpDFo} z(>gbvGVUp8&@pupTOHP&xV>gdel*Wlog+o14m+OG^_g_pC4uF@6nV_nMM>@O@DlTS zDv#}?mGLwz_!KP^Q&xB0wd35(zEYH>7T{o?q2LczxUne9&UT#W%Hv+p6JUl^W$>%TmzA1qt8dQfFeq1sZi%t3^nW zYe**!Wyv}bh|=KGRC4L3l2}`z@m;iLvOl;bWC!`-d)&o27G28gu%?ym#v2*YJ3@U=fyPHcbd ze=a2lrxES;+w}%~rJYbRJ6wjT0aZRwF_B4`>DrG(N*1fTQ2&&PG7WX{uIB?^v}=gW zk=MaY2!ONv;HTHI-azbDzqE>X18M8B?q-r^H`bLhm->yP<@w?1Q9m4wr&LEMC8~7k z2&IL8oGziX4wQ!2DcM3#UOvfjs(xf&84k$8`yz>`Wy3y^>7(PPT}|*L9;8x3RrhKp z5~yI|VU6;um?0GE?z|vGAo}s%ADnF842P0tUaolzIf=5! zH0hr#RS!K@;6$f)9}n$em1lBPJddnc-rv?XV61zBEfj)HpE#?&i2d6-)CyZSlR3TK zgJ!Ka)x?z;F)q(5xvc4aWy*R1#XFY%=osnCnK0JvaJ~L|R9o=#0kf0h8$#^WcTBnR zv_5-Dsj8a{sSj}dPVZR1Fjp%;YN|*1QA{hX4%M2lN!RX0KsHtm{a&Qy8O=C4L%J?J ztH&&77m92!oy*yb(l$TQqBp(2T@XRHf3&`Xx!f@}-!4<@o7!kzA5U;eec}QBF&n>R z-o<%%(!t(vfi#heqG$PeeF8SoNg|YjzU3_Ruztiv9x`$m@~}sy#U;^Z zHnk7r#i7m&SA1UebVI#?q6T$GmFk7W>V7vyz*>?BeORrJq4s%sgFNZcr^POgrmHG4 z9hqOm3Oh~B&mw-K=Ua-3cMNc;(2l>j`*g0;(W-pa(k|PucdVIMbrh2KrJX-lBupSU zucWiv;K3dje-i@oOacON!Akt&99xG)+a&%HvDM>GZp?s;)%Ls%|skh!25$luSntCn|hsC&=btr z!BtThKKtZ@CYOO3hMl8-9Byu_VpR-m$)2mV72G#M+lan9@;8IoDXxkBM9KM?SpU9m z&a~;;h)ThWmY|kMhvNHKtC0~%2OXumC@}HqZ89#|^+gGr9jI1^kl5B50}SxZ^a{~b z_js6c5VybyiH(M!f}M{L<4L*Q)@xlU-TTBg4(1%NG`hf^{6+3qX#2A?@W8tMiKH-p zln$N>ZdW8Y9#Iu3?;Z>}4MMo)b+x`14S@?@T$tnC^(p7S`U_i9vo2!cVazSn9=HY)-E@KH_t z$c?Wy^Rrm2Mq#CuxA4Eict6~BZ#@5PJY6rJb=h@zXmzP209xZN@r(V%-t4)P-1Wcr z1NsDU<6zG|Rm5sq)l{sDz+F}V9}i)~e%)5`D;#ZC`4{>0$>R9m40l9bky>d$-N5&TGmvaGi0Trp-Z)12&A-xu8UuoLz{-350Y+7Mg zxQsr~^(&d@jud;ao#*>EFfj#mg%kp6xQLb{>LRLm1G@S72l2G#Y<@J5j+j>1vU`uJ zPbWznl|&1B3Iy1@EiV;<+uGdK4K`C{rp}~56Zl@pCYM}lYfBbUYzL1$KRgztjv*^# zi6ooYeQ$^6>BF!G+@La5Qxm_u9*3M#4VflxH}ig3-RJQZ4qXlSjoC?Im3yIck_PlB zUrIi+sOY3_Z-Rr~E=%4Nd3^sGEHcDwoBu)7yBuZpepHbIgN+$^r}gm$)?sVZsx?w7 zs>=gl8;bR-e&FZ!EA{q7zNdWTr5L(~{VUQ)*hm5k0F2JsWvt*cq8-d`d4jG*S85F-u{;D2$sckPv~eL3YHoZIbI-$ z$BQp|x{__Ja+r{^T(O7b zt6t&)GvO-6dPv?w8;g*4w1@yZs8XR;e-;s)qPy)AImmeAf+?Zy@no9;E+#zG;QVNc z(Dre_u64nFM%uYLu`qPCp^)rcrJLIa5`}%wg+{~Cq}K($i!+hOGvlu&EBJ$`t0O+o zYHPYnMDn&2tih=@g5BR19RZ4w@SEpT&4IA!UgCLL&ssr@U`}WmLpLL5i^I6UQ3~xl zR@BBl*NG_JtJcP55=8ttBW8?=GhpS@2ia%u|1owBv7$t4gFUuw+qP}nwr$(Ct$S?S zwr%4c>%ae`)7^Q4H`tX_%_^1DVDI&VR7N`d%N!o;f<_w_>il82cb`0 z|EQtFvO|%F;-6HtlU_{jGM~xkmC{2T9)mRAUEM*3l9x#z=6)eMGwb`XICtW2(mzW6M^!Oq<635HoE6)_raIhZ_+MKQPuBP9f{;MxP?koV*pN|RpkJ1EPXS-QuM;gTr6B#5?!)`JJ1czY zvr!*waxCW+g>ugrRd8+o^|5p2a;K72G#tgW@;lLU+u^5id)XCbEJH~?eJM95Uo6dp zJez=WH#egq$=OUwCL`9n-x0VMio~xAj}jvBSiRF+x>1|LY+t@Vd(uQ}z5E3;*+}C= z-Xo)A!y#DLE?aQr>Me;N8x0(B?|LEJKE+Ze=I$VONk79o%ciBB;3S`!S9ry_^Ij20 zwp7YBLe9LV*;qcDxWzVpopU^S)`ftWR5P8QKSl>mSkz(jg+SSL;UW<-pU1=W#I8JS z+xtrq7PCXc($Y7W+ih%^bkAE)GX_ev8Rt6x*f*P(RIQHu)4h6fl>z>jKx?dHFm#lP zKQ!u7Twf3H?VYS3+5H=erN^D|FcZ8G$QV{}cT{I(Q;N(kI>@wT*b|MZ*BAKe-}f0L zQ{6|0J&vomvxy=bGIZ^0e{(&OJZO4@PuZ>y{+-t8qtkAWM$_cb`!NHfZ`_ia@~+tg z%ovu&bI%STMBYPoANJxJmp$t|>}Gt$7LP7%m9-&1I~dM=dH>UlLAvA=YF+FIkJ5c) z++FKFi1#ijCzc(8rnHNzp#gSvG)s6_G}5OTC~<+C<}KsHse)^KRrKXdZ4Z0J>{r@W zS)A)Gq5ClHEpegFzxa_g4F1jLWL?3&;VqAV8X3dSMUHBv9k<|^IPo!VI58i^1H_N7 z2bTpP{p`AnFGIpD@4H}csKCm2&|dJ}gWCAfGWI>0tpdM@Tv5+%06Ol~&$oKwnPj=x z{F_x8NiC~IHYxw9qA;l_v6~NAdz4m|X#^eMvaSYRcP zQZ{Hh6PbuyIp)cG#Y{RUrq;#I?2Q>$)G8F=TR3|3EqaVQptR%gxhSeELhRk_GJ0rS zSe9IO=Wh|D{>;L)IMl9l+7{%^NE10aEOKf~wH0d)JT* z_RihlC49V!E@NV$;92Ou`epB87NQS-bL5ke{~an@c1o-{d_E+wFWm(*@ry1FN+TG# z5@(Tk9T4^7r}dX5hPL$Frl=#QyJ1|o0+P%%8!1Sy)4Q{d`JL(<1fzAC!!_q#Pnb_u zc?Y>ZBT2WZaQojoisnd7r%Dx!zk(IFFT>p1(k%>9XiXSS zHT+<(*X%rcz$O)PJfh%8y_SMh-HxQ30=m+Uvam`_f2pQ*BWd&m_`u8t)sfwX{&twY zNYi?B$;(8gr-Qi-w~CKU7&~e2?dZXQAibGKZ%Iqr*?MPe z+&MmsY6;tGRt_+K;X!Y!c8!*YuiRl)Pc~&v@KA2Lcwl{TP6q9YOP3vflMGL2d3KD! zwd@B+U?yB|)I8LsW)6c`No#XXAwgtDXM3ycsKR_N;7hAK20k+6Vrg?b~%vE}sbt zxkTH@)Toz4WER=--uzgr)iyfT+9kf?$58RDVRpuaviRb1UGCw>&Yj>REcNU#VmC6S zTI1|jJOq4+3H_cnf(>XG+7_gLh1W1k5F~#L*yYn^*1wswd0CXE?%nR*CP%)}&q1KW zMcZDFw5+GtRpULnJ`IEI8A^Lqn&3L7kkfc@=&T7YN`5g4_wmh)!}6z=3nl;QH}@Ur zzEN?J#nQ8ES5EH)<#AbNP0o#}5;ln#sYXrec(*8!6_QuklGM{cH*xFMyB4FQC(`IP*Wxa!4 z!h*~EWpyQ9wmk*YBTXm7h}X{UQlWi+k$11Db6ZnebxYh(+K#Z>m{lZr@fN{;b>T-o zR%0>uCdz#PD3G8_H3j_+Umh+)6@z%vQX(`A+hz?(z}|3LMnO5UTT9iOR>m)qElE)! zWu!WFK>@SSO8wwm#~<15dQ98)*79ICec^$Kt7&ThEeB;h6=ou4S`R6i#|wq6D)2GC zFKw6)@}b6$T2Iyr&I!HF>_@~YwtzG@$l7S_&3ru>@@GZbaiNcZPHg%1+5Pa7?v{;S zPR`(Nv;I~|NAPZO-=DU$cjd@T-`&Nk8vt{b=Qb|Ubmnj#-A9B@Rd=YYIr+La;hFDI zs1XlzzU0S~Fz4sIpR%Z??i@;mD{ol+RTIW6~MX%EiUTKIz!8 zaMW!z9RaTZ!GEGn43R6cw>)Gj*sR@n5=#e(=LL8!zk^N``7OomkU`PLhCC-jdUPV& zNV&ZtLlQraY_8ksUyF5>8eLm)d0^|-VCeKL$u|C};!dMXH*i}MM0|G2h1moVLvl~T zZe+`Z%e<*#%}9Ktk!eP)w;iDD&(1;<*3=M{L$U`L?~jJe%Z5bgh49O9y~q0J5%{dn zYyDCl`}6e3hHYYLo`JozOOVYJDZnr-b|c5@G?*M7e3FeAE8Ea_vX79hkcb< z5&9TK2_*j$?~yuoAk_q47LB>08l4{gLEz%etZks3uUsPbk2yU&t1{sL(5f$k>`D(% z4Wa087c3zUU|90uHA?DE7TeT;Otmlf6X&6*tF6wc32+s;&*dBuw2Nm=9xiEki5uDH-B&<<&(}a7I`#q5m*JGY}Ozh{NGV%22=O*M}(nD1f`$xN{Ns6`) zamnf3e8@I!9FDYCflTptVhI6jdl1K4ST^@W*2!rBzG}N?v+K+kiS?%RkEYJyUzkg- zH@(rQfS)7y0oKf3uB|fLmz8!l*TMzD_7<_?FWy8hdo+udInA_4c^aD8`WmyHp<7<$ zF0Qb$kX4m*jIzB8CHko>@uQlBY#-8TvtCYm7MCY4#H=#Qd_;(fF~%i+^7t((!uaKi~|-{(p(w*x5Nb|C7g!gPr~V!xP;9Y20+z z*mR{LTy|X~rsoL=cVb!28K(OYm|ff@C?cRFh#?>%3Ro6*aFdW0cO)S2`JVaiUVp8> zf3sR{IoEdAcFpgcYklinn;0+7pC+}6YYe0)O0elO;7I_-t*xpi0|fyfNXEf|AQ9>t zFbTGC41PHv)?p0kY9UaR4)swy(J_W^R?7e!yG*T$5(2WifC11z`iYPX6d@5H5C8&) zf60n;NB}@1zz4DBkAasJBr>Q0vw0>bwm=PyuiUy8_M`)lCqV;7MnpY-Aizy<4e1~# zKp-uIwrvdK+PH-X;R5)eq5?WRf7PMnB(>Su$szsxijhGsVg)t<972F$=G7MW zou8bJ00|_n_Cz9rsV~{^4gm!@1ZwOc{g>eYQ%qa|$8DqiS`wgSB_G4}JOm-n`k10Du9nLR4TIfHnydK>j3uufhcXM%t6^2i*fr z3$#Ij02l1_`KzI|5jBYs;&%TE{~o2i%f`gG{$<7c+IiyFh45&XxW z&;Uj3(tZ7MC&Ga|s1yE1sfrFN2CU~l@8bP)xOsn(0?+n^g+RaE>1b7GKMw-T{zmNJ zkiZ1(^7a4jCH)c~|CasT)BM>p`rRX??BM4365Riae(*;ih=TyX>!WCUban5-1(jXC z5g_eE93Vjn0^4~n(R7iQg6GTEl103`byX<<4@%1hyMl-wAa`DTKx?I0^tARzgMgHs_-Asu3PFW zfat$_!KZM@p1jh(XIuUJ-^&^NoBoX8j;@Yf*RQZ%Tkdb{uZL;BfgS_Jz%mHb2g7tN zOU><>xu%xkfkF#1rwr>m0dh_NZEZK7E26z41H`qieU7HT8cIcWacD5`&R1vK$g=^I-S5G{CtdpW+M?MWq z`7MPslR7%SPm`|jDaDQ%cXVTdQ%<_njEsHVn0l{`<`1I|`o>~o*s7Y^@OUt{-Fa%; z9P+kTC()M4pk+|y!H~kL>PIY=9*Egnh9=O zEv`uDa26h|3l1T(rddtni<0Q6jUdjWy8aOG#{gH7NZ$;>0+9E&&&=( zH;J86;Lk+JSrs@g%%8r~KR0p?isVK|kus4h`?o~dH}|5CzCz)%RzyUS{D>BjV15&? zlZQt>Xl9wVTSe3RYC`dW)BGYE-i?llbqAq`-_vcbEyW3U2um&wAT5GhfuvwP^D@P; zV68s^SruMu;KTF`cS66k<~hNY-5Dqq$tzb<*Klc-WtcQRfLi;HXDN&><|x%{=dAt_ zDUU)Y+EYR|)~Z>d5>!RIzZKa1wABYYItR=QqG_U6RsVx0H6 zA=r?IBu|J)2t*LZ*x}|AV|fBficp>3Oy(2jkyejsNRGjyHU|rztz46$uR0538IeIl zIjM~!*7CddScBmuO5TD`&)7}fA$JtpY>sN~9v#KEZ}L3;5I)Wp1EO+`yR6*re69N# z=X0#7&HF)|r9}@KGY=0$dJ5fr+m6NZsceSN5~~VUs^|89q2EOJKZ&P|Yf}Ri8<|;& zf}Pf(xcjXkM?b(wz-M1sU*Wi?w)!%xxZx{(R+&BdNtUacdD?`u-6%+neM9Y#>}>Hm zT!|`7?k(M^$!w@9l_8vHo?CJ0;E`oz?g@thT@7}&4qv8@lyRhUF$$y$>gXGnBmA4O zU69I2%xPZ6>2=}e36GZ{qRFH8T%;Kp+cdT!8{y+ua_&ObhW5YwbLpWCL-k7odBFTdd- zFx#hzIrUgSmWuAr?{JrNbt$QszT2sWW#(K9*e=&Iu-xYOX{$mj%y{Ivu1v2aTP*D;-YG z!F8-7=S1n3zkp-2peAdN7%5^d(DR}ULzfsBSlQok&Rr%q_4fYEB^UJQ-_>x{SsEl7Zt0GTId|xk4qqee< zEK1cnpS}BZ+ih2>)O87K!PT=`jm3uU2)Ap0$UP9Vs|8u`8T}c9ZipEV4iEfB=);6q zjwt&z`5NfNL!HF0CgD7XbaMTWtjPFg$8pW`+ujY*I>OKA(5aK1;A$52Sp>_c<2y`D zkhU45p=6h0n+)bz`M$1Pq&MB~)fYJ+xf82OUnB3RnD^nq#y-uitN0^TV*^rZ%ypgF z$Qq$6YRCL@u2h;vPBA2J3bu}A=@e%1e&@j zK2*76ezgV$1`@nLwJ$9UvbuFOTGD#u_%DZ*wi;)`O|*TmLF>1#6Iy>=ay}0r0K-YB zZF@TAIDaAKRPc`kn@UFBZWN&df+_nE$##W|mOq(}GMF6_7@nJ;Oj#mY5;0^(417%8 zFgvkmnU#-h*@SL5ZOIiqMCX_$Hu*3l1RRza#(nVWC+uk`beGSL}Kqe;M}IYHdDE2@A{FjY2$l7yeOJC5%UJzNXa5F#Z>% z+qZ|b@vkgv3-p=lp)can1Ml9SGC7~0%;mSkFmoMTnX5J~G9*#9^}!8!cqBdx-G8#**(R!VkAtC(v6 zwp8B{f}y4Ym$3c0FItj4U7anUX}&LdK);@&B|pJgCS>v8M7@uwg{7y*{q@4nOs20z zW2`({*<5b8lO)#>0>1QX_K!=-z4Er^CbuAKR_RCuD%DP>G)(7GfFP*eZ@-$u2%LLh z&R4}T#7p;vihjo5*byAGq0@pna|NQ*OS$>mQjVO>mC^)@Sh<-}Nw?A3innQDOD5H` zf{5~1#*S83-11ecW!L%+s&VtQeY1V)jC=K_ASjm+6nM0RZNFW)KN!n4|S{1!S|`mQEE(lw^)-Qi7PYWKbtb$gb4`uh4c z9oKn3B@RGR$QpA)6D65;OWMWOVVa#yyBR;HmEQ%FO>CE^U6L3Jo=>Y}v$%&deVlwb z;nq&^r01|ep3xDt|UpS~ed z$$=r?QK5_xZPr%C?o^L^&E#gtxWk=RQ^p3V?)gha^d1FG8#rnVsn=ev!K}FpNSw3d z=^j*%W)IjYqHragJ>I$h__~eh+VY?DXja}o*&fyRtugCvlM&?mf+Doi87Q9Wz8EuT z&)hLAIvE2O0iQ*NIw@(^6G)ghXibBh*|gJ=HMgmAf*JXmlD)?UkH$;q^Q7A-sF;oq z-azrJ0`J;sbl=fEJgwy)WT{td3rP)p$?mX^8X~3ShcgwKg)v%nT6I>ZssZukdEFq| zA}ark2a1cOO4VRbpVhRqY(Z(7+hoNDIC}b-2t*yE%(ZvBE$Fhp47#1;ID%mv(bEni zYhg~uzYc7D%D(A!d(XR4l<+%@di4t?pXXIyh@x&an{97xnNG|YRSIS$RnH{zYKOO; zSbufN%@WcI>F^9bi2!cl9ID=yf1&tRP*ij3IUSTP4X?j`beVMW)B7?AIcSvfc-o7w z16dz!{E$){R+HVZSYipF3|$dnXYr>}q!bSCAQzKT4&CkbP{_-?cp?d(OH{L}f_{5u zFh37*{-!sL)kj;7ayw>V?s(5>-olFA|Avb z!(*19cYI;KmbYtGiFib$b0s6iolK{Bh(e-^{4|yH(~5z5JlON34jxPEQJMR^>|>ow zUZhqoPa;^qKdMPF|GG{;a{4~K)TDc5^PjlO8yGK6v&z^5R&ok1MWobt?)JLI2pKIw zbld^r)J0*;Mk|d@;I+ktdf1w-OX1~BvP6E|!jDV3RiST^(@MpP+8c*oBf1;aDKdOM z!CsF(9iZyAn;bT5Hdt^KJx;}=i%t|*#aYDTBK)a^96*z-F*(35g_Iyp$$#Fd7TqeB zOUX_jbv385CO-VDe@ti;vgK{lYzW<{51l!DBQJAQm#Y2_13L$^2E&v;HL^3NHp1Il zPtg1LOuR>iBwalMKmS~?uw>DwAAP;DMSpIXC*@gyM_ZeT-x)#4rQb)e3`0$4pwQUQ zg@t&W#P?=dZ24(Xj_Yrd7B@_FLZ#R$IUH>@D&cdMTh#(?#l1G$d;J88jh5)-T~QfV zd;J;k=@T1v7Q`AqrVM`@ElAWfw(1zX00VLFdcY=t_Ee3OEwnXclI@Wg=(tilOr9yD zQMSf!HA&&eqaVD!Jo;Clr`@VjmX-kiprM0)SmyZ~el^AjNOi$7+hMu4XOnpa+_@@J zY$=D_9a%I@tJhA->L;fnP2Q8K`u%5A=iy@g`iXj24SoS8BAs-t~&tT?>j~n@gJQIki z&SC(#JD)}SS-0%ZE5Glmu9R1G$)%7A8j>TgUYzj6DWZ%;rf(g*%smjY z<8U5L`Y9QOVIGqVRyVJ(^6_NM!kp~bv3!C=kq1E9&60=?@tsza)l7OUshm^rD$%=u=ckp2X2 z;)@q`qMk*CZya{-zW$-|L&!6aUg60Ir)h9FRj~7w%_cmKStA46E}--oX2L|lp;yBj z*IHv;#Og~l#jwsfI`O>3kE`(pYO>?t>htsnALy;Oiaii5 zo={#rR39*}X>HXUCxuLl1*D#~NEulRlQ1RLt^83}PPXDE*I;MfC7RVN)&-IPgGG5w zCBVir?oN8nr2;-pn^h>4*yzLgiUa&c?I=yH`!~2W8UyoNflU@PX=B0v8f#Yr%O7nZ z5rjE5TF7>iyjgqV4iuV-yak!+K2=6OJ=1qD$tDk>BbP)&%zwq$(XdOYB6pa`&xc^Y zXT6thdI*P^EkwaB4_>H2?R`-6=tDN~TU)A zS?_vlce7`SwUlI;cvw>6swm)~FE$b)}vrQD))<-TyAxR)XW|g+v(x*C< zqe9*GVke%?nqEw5xRVU%Ue_2+|Bfb}Q^!-vhl$qW3|mh2jXgN|%;DBJ&yMK02H!e6 zbe%3B)Hy=kv{+W@qIoj--SkNjpW1;pTzv_pi5kr%+Md{}<4H4ak)+QCjeM%vwiwM| zK$?qnm@en)gFQ0jJ(kSDGnC%-OlnqXR6ygB%)23X80uHRLkm7hq13P>DoQt0*LgU( z^Q~N0wbCDCD#<@h;8v2OuBCT!4#RzriP$OHOK7Kc^kpN9pG~}`m^%4v?!-PU+u={s zl3=xybK}qksycXais&+1e3Y=((QnRLESirVyl5*;lKw!#DNl}nwhv+G`-0E&*{-(* zu4%vq_INWN6>(?sb4LE#*nlR_$tg*SCWdn?j#BWf`Nr3hs=4(o*VY)KLC=7MRal@M zX6g9nyrSJY3muCGk8|A$-w?$WxH;5I-#+tjXD|p+*pwt@-->Z(Bhu42Tp@JdLrmX0 z`^npz{wfwHW}OS~ybZ1=x92y)*XpwYA0e|O<696F7{hk16}kvsOKgWTfGxO zO|}Xf6ZmXhFT=as+C#hZURT9Z;|nJ#DKN?MqlI6Wj1?DsG6Y9-#f7i3s?l)E7!n%~ zyXXqtn*(jzQ^vTy`=F8)eNr*a^)RUWM6LaM**{D^p>gGS)bOH~YOk(?IKFZa??`O_ zJvWYO%t!R9V#_93n#RbF6gvWDl72Pdy|=(WXM+oGu%yi9-92HnGa~VdI`FMF>QT}6 z;ey(St;fSp$=jjUDk9G3>cPc|p#K_2Lbm?JaHc59A${w1gOC+?K2+Q0DAhTsufv-9 zv2vP@G%Ouy0aB*OBt&3~Rb*b>Kf3b;bysFZX=fGZvTt}O7BlKc*Ac9+APLVxw(s=q zUBXXw4^pR7(40`k!C1R0lMlM#D{-qt$Ra&8vd6aGQCGtF_lnH4|hi{t7iow_{<-*jH2P z_=Ve6&2@dN8^2*Bx7lL|RbGyvxC#O?Tr-9Pl!RZS4JV&hH9TVF?!BPSn@ey}U*lI`-T5zIFQ4<;(9o+|@?nrD ze(${|mkoDb?tOiXoX2i1Mphf$(?q#co8t6>K53OTz=NN&hv%g7phh;wk4zX-P|4+dop`m0DQ@}5 z7h36bQEHa}d}vEPmAkEp)ez>P`lESxa?M+4%;)E&2>G40MDZR(eIpl*ZdpVusOj?- zIDGP3vdeLrGm{#^c|RUhDx5s>fgez}Kfzw|8(+#3d;-$Uo8-z(TTMbvR!@>e=_R(n zrBTF>CKV5{xoE9luY&~Dhuvr}TGU`}4#4XxXHle-+lk)k-qs#ba>35+`4yRylRX$Q zHOn~D%nEMWYT?b@T(%F6hMk^eD3Pm<%DagtO=n(I#RhYnvLsKNY;%6#L9-+Lgtq&= zF_;9nw@WOf>*?g;o5t+2U8tWgzjY}v-q_d-Ku@W(|2jukxPA)c6lXZ72dA>BTm7%c ztw@C}P4<4JW9l1A=(bqMa3}WbQgorZYN6Lf(g7oP#@zSxeDyt9gM$DvcP`b)0%{cM zCQRoDuk7F+^Os4Q(2_o6f4T3X*|@o9bxSBcTN@b&jnkLh!WmL29+q#p#RJWk7&)Lt ziD9liuduOhHS=~A^o2a^wzn^kF6D(1<@UY8?#{f z3-V~d>uGPOSau}lAtq5gJzDPM87KJPw+f8@1H4S>S~99d(MGr%+!1JZvXwcI>j)~QZ}#Fy9TR4V%jzWI z51c{sLH2$JF>>!o`Wc}bxz=HR=k~`-^4Ss8<)K-| zb^GlnrJ4YmM&4EFlhqrQz<4U9`^F-vE-C+C5mv{T(o;^rv z*7D>tA}$t(o3xvX`0ftr3{AKPcMZ1 zjaun{b~=MF?N@Vh9eE*H5S}NA;fdd>q^0lV*mDnNaGQlWKUoR`&4Zc$?ATKV!io=- zT-GLdNL;y*TsG_wk0P$Q5l2>RN4qp&*^vbT#vMZ*RMpF+P%2|Sd!tCpUyO<4ZbAfO z8A=*EFy)1YhC7HFv|B9+Wz!ZL!WzC5%EARg$KOowK4Q%dAbgx=I7E1I-nb3*fgLj+h&JKm7OfVdJTeziJS&J0Y}89tOg}QH z%=YLk*F43QW4!g_W{L&)L@J#tV)pD?qXOBc{1Gn4a0hR1ZXbB@_~?`(Jcwkg zwwI?jj=;RMO?Xm+f=@|Knd;=KA`|vXUqGZJdx70PC#G+)GJEuPf!58jRbmw<$E7oF zi4?7)xc#->M*P*%(K%`da7{Meav+?UM4zbpYbaT&xh=ePN?D=mdK63Sc3z~br_E1N zNpB=>Yql&MF?GM)?Nd$_I-0UldowcH;Vrf8l}%`Ie|5FcSs?re`bN|6(PIL*)clhi z-e{~+ZULGCW_)tYh&NLt0?C0lgXLWZqwsnys&TMzFg1wEvl#Zw=u(X0D5=EaF6|J> z?%n;UDUU=Q0Z5%FgK6uEotdia(B2XgTFb?DA=xO~Gxk1cn=6hEhgXE19%qrADMCbU z9oR9nV@^uq0sFkO)s z_98hKd8r*lb@KFOdBv`m|J6!rOk|erx#Cj`LY>=GO#4~iIES(=%|uCI`fwuz^p=DB z@y^eAN-bVU;wrI%iG##;_salo8?Qy~Y4(Z)vmfIuG0`OHU+P_`gfoE;?heX1&##)P zl+p{@=hV}%-KhznoV;+}sAYUtt}cE_*a?Ok-a!os6yB!b3r6Z}0HO^iJuYoL=_r(4 z{_th*NB$!57=M&PlT}!UE+2uy1f7LYR#)~L^0d^yp?V*cncq#>y#0zN`x6OOX;qg; zSn=!cnHamgg06*_LLR)3X1)93f|cz1@K#9Y15c>@Vl5uqedH(Q33m_wCZI};>~>PCWV@00frLw=+D-6%{Pb97kYo6?*xsx7IvYsTS|1F%I9|-8wjXYLe6pwJrpQhN zKcO*NR7C!<{qVp8}|9 zo>V?S>X=~l2KifLp8U&B?HMWqN3Der~L5%RLE8U%>Pi7 zoxW{Ap;iHMX=GyVfSkl=(0MeJh2e3q0wa4PNSB8%d?+eDXmoUNJTb9sUCNK}DfU3~aCw?bXZ)S9NVsZiilKKV~ zz)j9z9-SMRKsf*fhk&RQ8i4^oi`V#uYkn}70RLC8{^|ZN{Z4=HU$VyL&-A9m$jF{Q z!HK!$rMaB_(~Dpb3JB?@4i656z!)2uKWr?Gj;-MD*d3Ufn;4kEFh8jshypqikOm-B z_j@Ot*&Lc&?HtS;+M8c=i4W|s6;noTWkfHntpeQW=5KrNky>1UvI4fRCST@_t8Op1 zZo9u=W@&C^X8#7HTwM)Rnwnf(K&2vowm?XNeugC5v> zs>*@y^`%btj1)k7ci~>(0GJgJ1@xtv3C^K+w>HLMAsif?KtH^G|Gepg%uT~Ew6Hh= zVgS$3-t7O@2M-H0`7>C&$)(`|;F8VXG6HA#`Tu;DfNRk!dvjyY@t^)?(HA!+w8jJ> z-SDISs*}^$+yUN~nHvMmH`Ox(X86-%lAjN}`dgyJ(){L*>h~(SnY{qq`Zt2MT<~Ld zeR~5|{P=QI0RB#q+QV;Z5d>V$C0#K!FlPq*F#P)KJ^Ocj{chdw(fry=|M(*#xwkaD zr)OR2fBfRNB>pM=m)e6BkiNPE;sS7bDKP$*c9wu3rfiC znDO7TxS+AS0Ax{Zc42IIGuQq}tp4URWlM7t5cM{n+FOGPz+=h!Ee6J=MYf(_Ie^ic z@UILgNPg-g9J!Xcmi5PHM00}+NK8&nBM?eoy{0n~w#t`+5?#Kj)G4e}b22ebV zKMZ7$@)fKB7^CEm5TX3j7Xdw7^adXImGVoFkUxn(3}&G69W20F@hw#@kf-%4 zx=oO~fDaO7_XQqEBm3_e2(mOevbr`iwgUJsu^D(r#`;!3*)u-mmc8&i@89s3R}4(q z-=G3FfM13Ht*<$_@3jC>5x{0vR;SiCX|O7Emg_!KoIXz+T|x0%N&A-P|7|aLkNfP(jO|i7?n@7if8K=z<-6G=j_%eFT-N z6@7$dpQ}ECid6q}AgjI`{n7xhH}t2w#p~Z;u#KSI3ja#M4(>0-U>{rodsc4jf{lE( zCdOaw%fI|P=D?&E0G;92zcMkfDs92B)ld3g1d&JiI{>22E-mhWSy)?N@(^nOHo1Od z2PePnXMUqHGX?SdU2`y(`}qww1m$K0w5NV`IbQbI1lsyOX5ok&Tfdr0YzoAb^xi%sF@J>aw){zQ3kn{+>?s#pi-Ox5NiWc5? z9&8`QylvZH{fz!ge0mPFsypI

lQ9?I%yizl!k9VK#ujgtB=@=aZo&8R33+yVM7Y zd+Mz`NNjD@&FV9R!S_0BqWINl#n>7=!gfYM$qrB2N|ZFyR4i6eK@+?@J=gemwR3+_l((tU;)9ElVLYHgSz#a+vd zTELKSz1fg;t$S7OnVO_W^p5f?eSl^NEi`e!SzX=vSUBq8elJUVp`>lQ@V=iNJ15nO zH1p&E_P4V##Ab!aEsfL3atScHr%X@_m4GRO0)^U6pOeopwkVTlxGt1m5o6t|{lg_Q zpgX{PLH?t8N6zmPZH*5?KcAy8m))`4S$g-{4B=nd5Any*(Lg%TYK%iM3{~4M4YlLj zEgVv$yIclGG7gwWBVwdz!4{R|i8fzopMxg=nuOUYB6GJsD+(!g3FRxm|E$)TUZq-F z<}W^^hq=iX9}B^w{elPk^Ln@1OTmA(9-Rz*r-i+r!=t5MAr1=Vv#W9lI}-O&fg8DV zQI$wTiU^}_Tg|=qVpN&$B;HsPpc@QCB{Bl_en5Ty(*yk;TLtlP3iPDNV+(ZU||`v~`5gRMXbU42T!CoBdFk?{u>MYjn*!`R&Nj zIyAZ}212wDw@3Dv$JK2p;~{lOxdETxFBUnt(^OBKAvHyuksp|9_SajxHZCgEwLyPZ zMjB5Gu?8E+!YLFR4z#|TQ8I#E9VXGGE}&|TI7JGdds-<{D*hYf2uUbOti~)r_r4M- z8S5|6o$ROZ>gF`$b6y@y2CI_)E8~JUH!C^oC(#~dM)Ms>!e@UgM>Ly3d%-+hM78Af=dA>HBE;&A}atWOMF}mhv;k|o*V@POhJAP+MV_EacMsN z!<%fuQ|21I=}F|ss_vfq0&!b~OWm8l11e1qr;c^)Z8_&26E3Tn zEsJQl*KYW6g8dfXnDh#$=bb51gKU{&=*T_06a939E)@l+bSr<M8|h_p z!b#@DRWxe}dNd8i?ranknpJ}*0Ir&Pk3SEIdBolF zWYe2BA(u~P8x|ztRqZDOXV7I&XUk-viT+9xTm`cmLP8UUxC`$XYAY{t$l!^EiFkmH zBy%tg&dX^V)RpcJAjB}Dw2*_z&AO^zhjPjyzWkbsxunNVx&!{fJ-pKBokDDPvox>v zI6vF8=N&}>V1iNxq3Mo{nJr@>Ep{{)C79%~T%3(JXrJYDnCc;l%4RJ_GBa(Nz!DEu z8E)UzjI4&d0ZZ4#MDqoKI*Rec384ylks4x}>Gl!z5SOtyJ@N$7q<-I2^TD4-yjzh1 zB3s@0kXGdINb1-V7q?*=G{mI6AQa>AIqt~$AIOe;}ShYh53x>p{DKW{pi zu+^B=^~JJ0ZUBun!i>oW1;S`nO#MfARS;tW<}%8>K&amPms*tNSc<9-H>0#1XMlKb z$#lC1u8{QW6MIAl4V(k0SC7sTF@%3&+3~J%6)x;l zWnU=7`rJ5~31v5C1!%Nfb8v0~8iWNf>RzojAao2$k*HS#JGt(J>^?1qS&)ddQh|bn zR>MejxzW|%aSZPz08X~G<1RyIMu2{*37QRl43}oZhLCx5u;}D; z3Lnt(VYY7@4lM!)$q5N_^6d;Ef2@_+JW)PlU$wfPU{j)v4X~t86EhQ%y7Pa6?8hUDh8} z(KKRqkS%2a=t@D&9|d@DpnVn+J5@vYl2nX@`f{E0wB*2dfZXAASpLvLdVH(8HB>F6 z27}13eAxu2rjbOBcFjZ&0Z<7QzOwDjlh0+qs<-Q4*6LW!wW3Sn)$u**&A)rYvdSb4 zZMCV^op}hrF_m(F7tX>S7FjYxd&lI@;E>b-PwU(E4YPSwc<-{%70Q_O_M-;CV6$us}JszOyf$1S+3QPDp3x8tzRjbQAv2I4}!88(&F^iI35Fh0nNYnt)i&ucsyehtRX&@0&VgFS4{x>ew=my|6UcYV8vT9` zU2KomB9xj>Zzw)8_@DACSEpxGM`jAdeU?aiRAH6X4`fXZ2}d|hYukZvZqHMC@_d=H z@btR$?I*{W(JcMF7wuIc+R1FAqD!*nEJw3sKbEym;M<1w_?wevx%Z6^_bwX)F0wHNQYQ87@9?w=y<)fpsfYqjJ0L+VNo zPkWHn87h;%Gx^W_R_2p>%r z>-{*xa`v)_H5=RhiRK}iOtYl|`L*gZGY|K5mT13i87>;w;d#}!8DFPT8^yzL z!E5zZym_h7l^7SIpxJ8_o(*79A!i1k_#I0gwnsWC#2JG^^Sq=+Xx#>SUEb?0JE^N= z*_5lnZD#VQlDzEt$z8`34qu~#R2yWU4l5V4P@X7jrm}9jmjTrRVTaFh<>n!lY=XnB zHQX_w64}w}QGY>%NAq({QLD{xtP?g@^JVV}MP%BID%vW!0vcQ6yW_Q@eFAe`>V)zb zow^QeORsxtj3eGN+_$nesnZeoZxXp!bld&Qc>{q}*V=gD@3>p*0 z#Pgx=F(P_p(4-s3?|^2QDD9W@04VpgQ#lDr@D=jEvV)z*@Ez3L7M;-J{{S^W%D>R` zvWRv`(a8eP25VUQ2BFL581apMSy=sXys?IaH4~>LGQ#0&7aYLermhvD>Mzak9}^F3 zekeJ73BxPT^Pi^f3~S1KXe|827|Z)k1())@e#;Hdjti7@t(D*rhDUjQuoxAS#82L_ zR?KB3M~F|Q1BuqElr0xoD7;yGpB+EgE$p}ky4c8yFehmC0@z3KlHnb{%=bD@6$T3I zL{E4zi>T0c;^!+e_xKS4hagl~MiE%crIX~AeujLtp}L%IB!eYv1r90gGTJ)Gv&(RT zYrFuXe5iYt7uJlTB$FyPv|FaD*<54Qe1G)y?)O}mz+k8WCW(iWw7#Akfjtn`?>2OWgrC>rOP9|KMQAI-lJw~dKze!Zsp^d!;c!M0( zuQ(Vduy4hr%ZBq4c3R$6%Z98zHV|$ERfesUQZ_j+{u{N#yA98|H`9vUKTo_9^I*iP zQ_lIv9E=Y15ds%1juosS4Ku%;rEfdjKfbTza`jvxbNZFEdiB*6-ptp;v4@tu%hQke zWmRuB^YO!d=LwP;T_yN;mmKOnOCHHzIo}mRdzY!I41fxOhXms4-(MXkV6Z+`xE^fu z(o66}Y+m+y1!sk(OKR(q$ElsVEp&nrB2IX1>*H(;3&(nr2gs{#H8-*H<5X!LZwR#8 zVo1l|W6@8uhTIWYZqG{!u6zzO8xMZ5ZdPVEPQQ6^qYN0ZWk91GRoU(qZ5vs%@q8x2 z;Y`5Fd#`mfCsJS8XM5PF-&8H(%5ET${_ehUk-6vz*@ZD?2H|xhc4X@UeuFKtmbua{ z!r)2tqpt%D?VeegIkyEF!DC4uxSrs-+=JnQ{#1*E%q=f_IZT23z;PSYj+B$*xljqK znNZNW7OJIdML_rJPS3B7$@7ybG%Y8TLjuv8Tb{VsB~!w8%7u`tfCM2I)c42qWuNIV zsJB{;$_j>BEw;wFb!LiP-(XetakypTaYImhRb@(zG|6_{&4&`26oPfOAUvW!I1U8o zdqPQ3CB3y%AZZo)1*T2@&SpO2k1!TEG4h$A>eMk~Ip!M)S4$S+hSR_>>>D>)Yq=fxLIF(FFZ2 zb=NN3`BMs$9SxE9cEtc+O-hUk|$GqvvXKS;YjzBTYNRp!w|^n}8;ZUiW9V63MjDy!82BY5H9g zjr7HNu|6epn!G8}CZcTV(>&`2+{Khs` ze6}x;4mM7Cdve$F;4hACsxBcrM@PGl<&0S&@mjE<&)8h**w6ztbPH|~(}!H~@Ssgt z;T0lU>LU1_^$v)ZmY#hew;=e@ikeTu!f;2fJ>uireBRKT-zIS5R9#eh)+f2ORTJ5F zvRK3^Y7o0$bx>&V0Kp9B1tKLsK2gz^7dnb$x?SdWnsn@oYR)$#@w-ReeY}@D{h0(v z0z60r-c-0wpCe^}sBUi%qNM8#$D2~$%R~xgrV{I*F|P+{^Cu$KD*`5)ullcJ2ZvP!cXFqpBoEL>o zo}z>j-Lf=Fw^m-MOX`>8%;@z5QKx_^&#B;o_&N5z{2RhM70s?yrdqxV>NblFjX9XW z4mPtEanWxUamx$~^{Nom`YOl_U82;G z{gvB~&pbow22T(}A7_iWX{4BZv8Ee!NxT;@Vb59Bmc05ehg^5WGt3}I77Ide6xU0B zQj2|#;6e_1Rx8YSbf>PmFh`FX#&n$F*)X*tEo`Y?!HlqY=Qw~+n9=TRk4WDl7!NN4 zDZv@HO;YKjG!YK5SN6CI(EjD+>=PQ~o8K!t+n|CTRmc-yRyJ$fUfeCjdLB1-p@P8D z%a8kIPN&}V+d{&#bcXIqJr-dl{x2+(lO>#h=LcjTm|>UiR?L(A=|cNXuThv)os(6s zxFgbT-E=ZUKHzY_8bZgvs;_Z(OR;2Me=IRYyYxh;fIhxIduAjEYIv z4%NqyCw8jr(ef(fD-5H+c1q?IGL;hfV8|E|=nGG81pw#p(jB(>g*@^Sl_A51M>85I zLytSZs!^!2s~A06B~&Is8QhE2yYh%#KQT2TcFwXeA*smOg#y@|6bZNlbw8+7IGK2uk^3n2$ z$R3v4DPdI2+sopHy)T1MwIcG3m)vD#WG=Lg5qeLBwppVKQKuO_7l3&D-g-<@nACWh z37*JL;sHU7_fr|+U@DY+@|1WxX6N;esr~(fMW5(`C%DKrNmeDhtzGz$fE~IKBnurZ z5eh`OroL=2%WR+5*DK&*gUfnwBqm(p z)p_2x=;C_U zr}lXWvr_WM(vE{C|6mEG%`EYLJoua2xw;eV+d?C))076q0J|X+c%g`I^IP(?IFE?h z-et}7EXhM-D}V6Rbmwr`TBJo7(E9qzy9>YY-7{O)weglp z@g**7XqcYwH}}6)f7Q3IWg;n<6DV4{OiU`G-3$ARK~=qV%VOE=Azz&YE$rjh+IzxOeD~pqNo9`6FF4aj%C2*YZJphhccfBxd=H0QRC4sA{`Mn8;pY=;MB@r*qngl z%yQY!rn)66UBlE)D6SrXRXWXTqn~XEv}N=+XFEeSu{k`|M517}Y-Au(kr#$~Uy#{T z8;SJFhmIWLz!P{oGqzVud+#o?uQ|;jAODE({Z0F`+JN2lsVa?WC;k+kDzpR4{jsSo zlXy`I^CJe{_Qq>$^b0$T%7^mTkuE+Ia(P}9KMo1t<=VQrC}X+gML?DDz51&HstP&L z_J=zp2IO_t)=o`=L2Jw|sIb^(8g)6v<{K@i9^}s%yB-H*LrEWLAO^CM$RqKo622}@ z1*V%n!FG~B*w|BupxxYwC|mu&_MY<4LGt!m=oNcLutuQYzteo&81pa@4xRVa&hd|$ zK4BHXCv1axNegT8@cL0MOw);V0}&=@OlT?|K^MFtAs2WSN<;LZ#S|_oI*} zU=1AVZMj<}$6UR2E+sNmy8Q`%H8gKvHuy0@8_PF29qn3P2z?h! zjQ1`yGG;BaL5RvPHByz|Sv{nccgd5*oy5*+=_hv(%*PKpKk+@x3~xkxP}Otf!3-O7 z@iAI{?VDLt4{QR)f1qYZl+t(`ICVvj0M>(bFG~2mhtg_v%8swn*cRO)ah^0?dx}DE zKgL|)>!I-F?pYQyp5<5yxH84vyw!+ley9n_arOxt&MR#U!!@6FKK%8*1T2hWyR zjt|debe~Xwzc#D99)L@FNy?5=CTrgGd-e@-f!@$O7LK34Uf%8{Xz{cfQa57de71uWxzp-h@5+E?4=mG!P1)wOhqD%Cy1>W z6>SrXx#H5?5dKHlW)p=ixIO>2B(6YLU`r|sk;bj3yh5P92GUSk$m;IwTdLmIk@=a@ zRgR;?-t^NXW*6Vx4R&}ieOZ0$6uqApkj#sDawxC;=O`og2pXRIs3T8e?W@Hu#}hEg zF&)Rf>ZzOKE(m)I266VTr^)R@iH8V0I&AVmp;B?SkSp(Cb#r7kaxfsX_dK_H4PA)2 zQiuoCS=1F1#L+&rR{Nrs=dVz+98Tt$`Hb85!G^tCNx6-vtJ}>FM>oaDh-Ct>ow(rdpR-A;i<7@x%khNn4XM3R;6r3! zi58$^61>S~Nqoc;z12Ge;CMmP7AHIp(foAH1GS4(l?^f6ZAZGyWWED zN-y-{#0mzA^g1#|NQ|ed=V=o-^Wc?r<$+AR zuQn-XfItTk8L!^G%|uRN4yQcpRl2^}Ld+IpH#>)6kJofgXHrFN)d@wX_s2NHG7Z>y zbDY@1hI#9nWFBK~8D-{`UWxR3MBw~Ao}^xY{d{x^4_3|26eB!MzKzXG@#}YAg*=0i ztJQrvj|zErAppGqVqm@Tu{geAMy$kMh?Rt{>ldM{*oo6!8Ab zF8-j43SJ#5z_oMUA<^xe{KRXFd<_pDDOsE?BRWgg%85}Q&3Gz*XEzy-k@}^KT;*+` zaCfdt&&C6Nk>|J;U36Bkg8q=$Y~Y4>dtA`MaglWn9`ed%>N}gpMUpMJ(L)cgsbYek z)_w)odY=x9~ecg@U)RJ9j zNLz;Oqi^;;7pnO;9P+e^r4|)h>7J@=91Az_WcBkUr=lGlDdAzExW9^-EIvZa&|zMy zVR^&LLAtlc*#$z>bW0F7s=jElJUR>VU|Dz%C#3s~7U7y-c=pzJzZkKBucM5h9Kyag z%Kp4IqUNDU**_~Et;EsQZWD$Zkx|B@y2iyacaUT2g9t%;F2a{d3TwcbeKqmrIpnUL zHoOIXY5sI+`Vmu#Dg`-N9o4hD^TH1vJO4dKT@wtFQ}{#pw$0V?&)fb6)h-zk$*^5nS$rW$dzjN^<tIE|@JRH!E2aeZh1gjfW?R#Lc^<9({ebJ(LYL7276n83*7ic; z+7kRCCOett_-x>drrxhzA{mbFSYXp_A}zrZ!aX*;n)?!u*6&tS-jJRA_KWDcq^*?Y zsxt+hIaTs$;L^joGgaS?6-BH4KUbFNZ|71+MK|W!V*QBhWeR2;v@}x&Gx6^EfOLH> zqeBaMdqbUA^OYxs#R{9J8aZ7%Wa?KzyZYoETz6qAnHZaJ{q`*`1G*nt3C;JyIYkv$ zdBpshBFJD$D^yz3Fi2p~@I9{_tZWi|!HzxJ2o|}5a-RK;{|+Y9^np^2t-$ocuV}6+ z652vD=d}v@m(qt)6J_6l4=+Km_nsO>xd!1R%B|Lyr_l|QXwvmGwceu5lF=op+__Rd zX&pm#;@~POUyV9rJesM(d`yrNK5|J7NxK3%bT9tv3qK47SV%f9!jb=?qC@w7&L6}{*7E{uEnMa&lAR8`n zL`D^GD2=Peua5pcz9WA&EZ$mwr-wI{gTHdi)J?U7CCz}2yPqKHl&k6Ev~cj|G4oN8 z>}u>e2iKpRcG(A!&PTm~10^QVp-Xk|IXQGWV`?NK?!n0__Nrv(|VDv{W2Oi}h%K4srgx}#6UeN9jf+wz77#c40gq$ED0NufI-VYQtw zDQ<{m&){vMiWs}{ef~!L67NP2>!Rv!u87_y0$E%8o#I-ee|*}}@6uN8N{YJZtmq6! z$<4Z=yw!>DEHRoX67H0tIY@5M%EnYr_q&wzS3M@p9fNNkcKfsrwS0qGrP8@!yTy|m z%ul22k33kz#Z6V6ECU4R3rae(GDO0}tq36Tk&~BGYfwbre+MI zF0qB%8@^-f=#g+k$wMsXS4SX?;4S-Ry*wHgj>CvjPQ#IjVN9mlTI-TVO{njXOkZ)P?XQ71A@q3IF!?K{*t^dA^;)y}7ElcPf~)s({JM zd|UASqLtPlMS=vO-$+q*?q`jQ4?VTN$|;7?vU^a&j3Mbmk7{?VqY3u7kJ7>;^{x@r zr8D_RT*bmG-{?M5+5p+fB&Cm3`-WOyM6R$nXoRTDy29r>o@dvow2O5t3RR?Ok5 zpK8Msh+u{B*9v0CgR6AgMbhF3V&4S|d~B}((yAN2fT81p&(7KC{y1Va;Jn5CGO0IN zndr+=Puz{tw419ica2zUsp>c(s=!q*r}zR^ql!3oJ-9r1i)rA*GMi(EnAj^!dkd9|E6iynU!&jF5(C~NniRu+Lw58sdWJdcPODsCc6zn-=NtJ~DHg_co zBa4zfCRaP2&c&t}L0A_!o!a$zA^Ow})R09lwskvuiDJauP<;7nUj%0ozSVsHB!0CM zHTeBkM4j)%1O>@t^{TXJ@-buS`Z#3rWb#40WWLFb zI6Ns=C2rB)M;FXam|u-s0W^eUzE!Q7iHx;;0r33d ztpQhJsv3-{w~I(sihT%+cn^9>i5b@LpZTqd)4f~UO}eYZpdmbaY#lboXWGBY_NW#C zg-DOY_SU&o)hYM%*^w1T^apdLypBw7_18}3;pAwB)tSD3K;Znw)^K`mcd~LQR<;CP z<`)I`<0fikL5d(T6%4a>l79^ja^EJ=F^R4INLZU-Q^onz=OeshPFDjPmq)LATLF5P z{ST42wZ^#{K0z$3bGKCA+!gdBm$M*xt&}LSW%be=N*J|3l;`57Xw=9UE84wJrE3#V ztigd3K_Qe=BhqOZN5l_z$r>(UZF z%jI^2lHlQfzFz1i{NUsDJxJPMjfPN=OUn=2ARlRm#c;~zmSr~8F(NH$sp445f8)hv zBSP}#kTZ8)Wlmaet-nYlFI%<#IXW7WNom=d3&E>L5qwm&)!{@8m2Be-8&gk(K|zeL_nmQTUfe8D30Oa}e; zim5Ge0%;_I(C)Lf*vrwyVnmQa9P;MT{rsgK<~P=$BDHh%#a7dgriLri8g@A!0Q|9nE zX^y0<5OBZnTZsDRNVz57++}jJ@z6}IFL6#uJ6mJjY`~|h7fqwDN!n^$4e3!F@%lGO z)O^g6hE(Ox;jyL@-|lKMtV6ysv}J}+**5Z6kyHpRg!qGrj=%l$R}YY_ADaEbYjG$xA~SqW1)d}b*kld#f; zEXu~CGgMG|8VdI<+DYN^k}WyXO!lt+vHN@5$T3W{_=SLv!*K>TPl_q{)RPRQAJ$BY zeY?ey=Z?VNAwllwgXwQX;v$@^Rq@U6q0>+nhBOq6`9S$6yND9_?$TCAfb$GZXd!(v zGIj|^{WxP$`+h#{M;b?X$}X|verR5Kk1>nd`NfZ>Y@uPf{IK03%^qz|J2m|;*goTz zT6aw(!@%7m8j4T2U1eP7&&2wE5^aGWy4makG=gC(^S|*mLfXBJLDxO_%Mlo8w-oHa zvWb64_2?goU7u=|QdiXIX21YTXlrd?cMHkM)O1#XTKQ zS8rw%M_k&S`6U{O$n&<~dY0mWS^Vhd1*jNLbu|NSk55UZHR9+e1m0Tb$M|X$i~Hl> zz8rTVQ{^O$G4f%!i(d61Sef&wyEdkl34Ie;UBIx-qv-Z6nvKdfhAxlYa(ee5k&uK> zAU04%@Bg@ati#>WniLXbK5MXezV$+FMe~K=mp|vLC)t^Lzw4Jy;$ga}GL!oWiu7wU z*W^GB8Jb!Qyda-83;|<$<)G#A1Vsn~bOK8sMrf3vVzR+rJz-14?=ms;Y#b00&3Jex zBUcU$?g1!~8F+JW4+!cO_5r78qBc0wa5%oK{6EVrh?E=J2X90X@wCp|9Wj==e zqug>nGA@aStnA;5lTSk}$kaLTzljN$NZD8`M*mDpj0m*mQRXozh3VHEu>M%X=1oGG zID%Fp!}y3#;t9=No#Yw&aMr*Mk*zYg%Eu`3$fRW~>hjewlOP;Vt0ccW(Z7jqy?ir|&Isa1(?S0I)c#I}u7MUA5 z078oC(^--n94aS<`Eu{7p#2BRP9ua@2l$~>uu*@HDU@W!&m#1-4+soBFf!2DbyXD~ zOU;m2XEZaQ=&oOHN!v)aPf;J6#~S<@cW67RDYox5N&T`3o!t*A4(!p&pudxskD(W@ zjlAs?(+CEWz+8>st*G`HaGGl~XMEh#vNhjQnDU@@=(H}|Zetj#z%D%@mFg!OsJOV= zOtt=zyQ?hel7MOjNtD4-*0I}3X;0BUDl=;*o@}!ljTN`BUoG<_&}CMGPLduzvTwQ& zt-kj#RyALe@h%(ZB|ame0qqdnlTxFG>C=_!6oPobXT9m2)s&YG(gQl>_;;VJ!JT{8 z1H1i@>e*d-i?5ij$wLZ9*b+KDy^7+T(BNQ-GzuD8_waP8lM7Ej(+08BM)>opym&pv z5KiaPP1nd{OUdO~p|+?H)PL9}H?zvILR-H}$aEelXowTdd|_N~#Qin*9lO%U)zIbr zc&c&KaJ|Xx5{tO$T)oM5?CA?$$tXfC(|HmbNUQBqLK|x-jyL1%2s9M7st2vZ1u1(#ei2H0=-~6(M zb<{Wz61R?>WNQGTj>nJWbkudfCdiu&OC+;em)$FjoTcQH5#^JBzn%JRXskJYuilN^Q0*>w5Qpdk^r zCd1=t#3g~j=(@u_Iz6yZ7@6+5HvYH?^G`$M8d!%bmK)p*=b~z$7F&`|RC^o^>k-Qk zG9%(#$AlOT^<&BP?C8*}S(jqi!>qob2|V?soNEl4Feql-X47ic)y~?murFwu_hgrO z1%IHy!Pv{5Q#5-n#{w@wjM&3+e%?=e-d=_NLQD3BlO1RpRrv{$XLz#kXb4-JY2~1U zgF(KqR=bk7TBA~ z08G*EDm#q!DA~ri7BT|sPeO|ZPa3L2t{ioT)f{j-95YEaEQmwA0?c87%#EHuxNAGR zW3DwAO_fx+Q{^^=d(9)s;u_FdHQqU-eJMtmLES<{i6eIIB13TbK`&spAqZZ-o*Gj_ zP1Inm>06GZ*N9~))?YO7?CVO5p!$(b( zRS$}Udq*fIw;sWX%14oo{zQK+{tC^~sL%9;yEXRH4vLrJ4v8uS`O+o1#0sTeUd)83qkl!QLJNcO9-7l+3 zQ+BNDgI3lj&*h83-ai9xd;!%SF!hSRe zzYV_tQ%?j7Qak-i5Qje{Bo2$+-T)1!9vlb+H`DFo`U(}W=s)KUhC2}JDRAW76eM`- zGB9RW51;Sbim`gD8aBLGD`rq8$3nN%Nuopb$x{(&OOyNzvBJz1c1f{>USv-^>*7)? zr5vS({j;y2u$+>Za;+^X93wmuHD2y1=hFjk$+LVDuiZt|( zNkKWqRRyU>pJ-|4NSH!~8$?#vRvff98nxwTOLvN*-=9UdcPm0*ic&D;={U5{^svEPTM4cEf8Te2rOWk|Nr>z63A*w|yi0J)(-?j$$PhkbA z2Bn`@lP_Z_suoIqq#?duz>F1-Snz%-#0)n9=Q=oR!i;1D>qLw0Xs*h+e+4f!7Ds4m z#?RfHT@J}t!G-PO^&$NAVF`L@{^D}o)nUMu7RxoV`2|H->I5UCNW-11vljJzAId52 zx+)LEmjK2${fiGMUG$ETK5NpFbL^UJf!}!gWq?);z@L^xb4q~A3(~#oVMnhmpL|=E zCR_B6Hi^u3>cw)K(*2X^9MPI?l&{0QVDELUjs%jP7@kP12`?2puZ71j0AKi1>q?cu zgw1*3GnKW5izddy`~qk(_LX}+`$5Fp?cF=O&R&kyCTFh-&!)9=S$tD^$WUUmS^S=D zsethTM!nt+QG#oc&i4jSI3YdU_!>>==<3vUG7fAJJOF|n0zoW2&$gdNyNkO1cp(_B zQD?9wI&2}`%_7gOL_FB6cmlXU;@%RKArEWn;4R*8o3%DFPT zHOjKV#}@cecw&vns0oK)D*_e5Oz_(6bXVVKY|eL-SSXC^@jKPZlCl8kE}*1ii$|^w z3i%5FotSH;Mf&YuCX!^zFMM`m7IRcy-Rw?A zt4a55Yq7@sHb}WP^BdRa|;_6Z?`-sC9ActPT(4|$`B}Lx|rZQ~8F2Jl# zmirKNou2LVklv5;yI`etPq52|c;Y9oh4U3~nw9zR2fa_j_Jo};nuyJc z9*XtcWzqO>EceG%c8u6t(kGwq27rg-S~dL&#x%W`(7=hcJoF}f-kN~-g5fu@v6=(m!480t6@terM75^(AV1bhfIU4CrZ+ZbsL0sp28~; z9bP4w(ebiUFgEDFUmX9RH?&WIcSC2g|Sq8E9b69K*(3!S#$H&Pcz@HQ?x9 zY9~KVwRpqb|PNm-5|yYSpBq#^c*B_~210>^YdML|XWIXtfL&=-ZWY zL}W9i#vLAVPw?Wo`d&fM+9NxA!+CJdulh0_yBxUs6D6?6cpa0&nKa#urq#jWkg zdI#U&kCxI6kgQ8g31$Km;Y>Qjy|*Kv86lhyYmiUvru1FkDcz?`PHF2^+dQ3!o5{!somgT|!^ld-!A~k&ItHsL)6(^_4 z6b3U?x9MmD7708y+BhIP2S*zuDpTHUN4DDogj{*zCnvWfyn(ba%Cpb{Dne@S2pmQ8 zoVi?AwkGx9sM>AmdQ^WZm0(e`#g7kc!U4aQXs<)siRC+v?;TFi&f%=KpK^TELi@OK z$#PSC_Phvmz1oU>TppuIAp>VIQ-5AfHjUBi1tBNadjHTJAWVr%)MGEQ;j_nZHZbaI zkY-f-enr5rKOykUVrOdIa4YD^)z-tl(_ozxet0n$vz&y##IBG;_gqWbgFdN6W0=%- zL?%6@JsbivMy#qW{av#9=TZFAH^wCX#t!VMotKui!mHK<85?~0{!y!^$_KFZ@&J4E zY&>^v9CRBtjz?qOThFKV?cUz&{#S)v@9aHNqp87664(Zf&_yY@9Z6&VfMY~8F=35D zR4el&!hRb#3cDH+MkX}8crsbc8q4CJuibAD4M@65?&a^E)weow5XH%vfPqiaVe<`m z;H{C8G>MY>?TZBumU8!`r+)2R%A_M2Yc+C(j%Am8O*_$F}_ z^6PI0r%D{N)jFQQ!^Az@toxtnA&E;?rFe`7lqttV+;>|aLV4xoZDG2eNYW??kED)c z0tm$q^*=iGI1kUOGalDYXoU^hRBf^q5ls$Si&e9`9Y_&i~#8HsG(h+7e6(G zIOtr&lNUsHwj`8ua5F?hCpTP{H!P1j>2)kOJPs_INh^}GIgH~?f3x*VIj3MkAofZY z{sO&E@D55gzeNx#SpTj3>|~Vj=kf6Fb)yDMf&GEEn3_#QVPZ)Wr)j!mxnQ3g;^F#> z*fDi_XJz+yg2cCKZMF56J(S1LdCcGx>d?ZA(k||r{dt=pC3N#&EDC(k1)^#28IV#4 z{_z@87-L6m6-Q%EGrq21yu(iR$7+p)S4S7X7P9Eel!9A0K5<6d>UtqJ^_?!H?ucH$ zh4!uHb+<{+DY=+FbQ^&AkFJV=%Be(c9fd8D&`i2HIqCEsi^8TW-v1{c72oOuIyj`H zaSgNA8Kf^NaA$iwG6fI0QCAPiTW;4Ge{ofcY?V4- zaBF;DxP7AMKEqmbXiBzrH{5Ltv8STS<3>@y#l%I27PMjeBYTHvp_w171lg_nv7N=S zvt!er8HD0Qp~Y5+E0Zjf6Rtb&UeS6bfM7atavMV)N81t=uDXIzHYC65C7UV;EW=~H z@Urz~&RhDa_*t=sdc!^v9jVl-g5wHt-h|-KA|ZQN0I!`5b8L{gvqgPsDs{b1npPy_#tJuSK*;=s@ z&#}Q}c9yc;^%)XqILzcS!>FC>*#Rf_yr;`zL{#@-qL0Yp?r#qe$n~Ez> z@@eo&`H`Mt<)QDGw)Y0&LA@mF0cybs$^T-T*6odJCzgZnR z7|Pa~ug*s27Yq1Rwwe?x4gi*o?QBGXkH5cU8L}LaeQlO3Ck3yS_#!6ksKEx zdcNX!acZ7YI49Qf>#CrQ-cYUrR0&tmF=G@0 z;4&|z8J#>SY8O@I8<(O+LKA3W4sn2FXgZ6=kC&6_P?~WYQq5AZ8uewsj>WXzJOMkU z4C)P4x~taDY%54V_Ur|xKWb*UPo_Iv>#4_alDa|Uu+1(+{%oqDuq>+rmV4^GBD;L) z<)hLAW{5Fn;od2{+F0K32HZHjEqhU_t2b1RBX()2mgbRTFBOAo3f4hFgrg?cQ%G;7 z?q*C`t@#%1^miL8P?(Q`?P|xU!T+8s=-thQs4IoIz$oknCsF^<@#xHg(xjI z>E+v}qLEA%a;xK{YC6$c@l7hgm&GLD%11tH1_+OseT<2~hQr*D1au~B-x-GS94NMmYqsVPn{(TqS%Al~LfgrA8la?!RX zSNG1tD(wRauJU6D0ttu;ib1e?R2 zM8%Bzzglj%T!{HLQzqe25hVMD2CBj8z5w7h=4DZS_}J`Qh{Q6GV@j9g(j?M} z2rV9uKkbGriM`+lNJ7VdD~z2`zE#BT1rN;G4U{`1Dd>C|yMd}@D1Jv(EwOYw!LFaS zU*&3LK1skn&1i1#^Er7e=i1I?G)lXM|Hvf zP0>HKkwuZcX(XwWyKzjdq1LD+kp83Rbj`7n;oA2`uRL+$`$o5@Ilf(=BS=MdJ7;!^ z#U{G%Fu5%13t71{gQd=B-P6xa42HrRIg!%!dFL>K%hA273>JQhWuP~h- z`RhJ4@rdFjT};X(`B{AQn}c;>n`1R@=SBfdp3Dvn`JQhhB}s_ERGl@Z!||P|EiAi^ z0tGZ(dx(da^M8AV>cM1msW=U0gtoZMTRdDkT9JyD7jSeD;%OHyzoWroGAP|-=Z=^F zvI$2xWEQnP~91lBGJ{Ei{}aPQILVcE+w zTWkOVMwMb%3>Wru6*Im^Q}7uj;iMb-$xyORwRZFZD)CimjzW~#;x1LTxQ!p0KU9!r zzLe2p-{DMo*PFPgmD0_;H89NO7WXoJ1BrrrqYhWLdZuqSxAcJyir2RSIN}#eAYou_ zJ5N!Vzh@I`-?(aKlguo(TG!izG)`q$7ju2#)V?M9YOq^V+6yOAv%8QdDv2!KvSS6TO>HK^54fMQLB< zED#C*_RhD2=w6<3%F>=x2|P=tlpMX{=6h1QTv?x{ zsfPd4ep2g9NrPxihtKIYxu(g&9}gh3MXve7DGIG|?KI)_{^JnpXX)W8wijYGi$x+%DemY>Y6i-kFc_Ow(=m*n>v%YK9D8STWdzt2rK43<_*~9bY zdvO9ys;}Y)?~8+P^y}jm52^HAJON8$#LLf%xtgOl2bia+ZaP^*-<$HJyO*FXF0nyD z3uz=%Pox#1fQ1Sd@L9B^S<9~_KDg_w?$hWIwDzN+mwP~pl;dXg9}BArG4TA`z|W`_ zM4cV;K)Jbk-+w-g_w4%E2-iM{A2VuEh$_qP1GR2%dS7&XXRl_qYzk)FTi20686({< z#{J>J8vUQgWM$sBy8jN*0`yV0WE1yG)UU}BgT-5Q<*PPRM@Xm`35L1&ioNBKqt7v)G82b5w2`3;T#o&iEkLB0TN0$;?#{ofy2LT=I9HC@SG$bL z1|hi&P0L`Y7)VpY^l2#dk6hG;TfUu9L*!2gyyG|6hj@-*hdM1?&W2If8DawC&p>g8 zrVjR7@V$KJXWWE#1`A=HkO&Z?@vcd-heGnWTi&}V>exoVm-DHR&t1!XDF@#Lwq$1y zc!NZvX;QD%N+0?)mU$dHNcpqYleSnI@fW^)X4jT>gYqbFWGf3S5P6FZC=1Ni=y`z_ z^gY#TEl-DQ^7|>SF<+Z$h)&K+5?=F0_6Y1@hI|FK1b2zL@Uc=)!kJkfM>{U8bqY|O zU5)2=bP|FWGfXJPQbA(7RAv?{6e2Uisr8%CU6+H`PkF+9_MHqv>TpCX-P_cV-5Mr( zc@RbRx!8Yds{ZGFlDju@n|t#i0<(&;xQK2q05mfRks{#18)sDpR5>l-724dKMSg#@ z$?TBjlR**P+vNx(%{<0X=dP=TlQSj8I8tTsvTvLlj&{{J?ZS{=oT!W3Q5L5oQ=7eH z3f6MriB%JVjtzXumF1ZdyS|S9jrkqlmSm(>Detp7Z33p*&JhG7Nx?EaN_4H)qNt;T z(9a&@E>myiP^}JUuxnfGP=H0dH;Wogp46?HcQQcgFGpQz-dmk&AOB!!)kD4$>2`NI zZr@@grGOh@XRx}ciK&>wpWFVcmU<|22M&I6bHtMAp-xlQ}|mhqJ#DTFxNJhd+LvjegK&pkFg{CR&(xN;Kc@8 z*7f2o5^Tp$#n_Q7SQkc|WV8U_^uHawas3t8(vkA^5fPt1#2e_%D4$lJ@f>2J?Nl5Z zu-6elgfQK(Uik0W=IdUkA94sSOsllFp8WJnkK)=W64LF2wUjM5D)m}^>PJyLmSR}FXgen-|+j``Morq~K8B{PhB6Bpc z`z6{GP*5&UHZ*tFRBlf=SZ7qyE$AM=A5c*^R!5GIP+SOixvLikaZt5vNfr7Kv@o&Y zhBnD?dyS~)w=pkJq0{%2_1rqZT9P2;LLMQ-JzI$3_o6Q&gL#5C!zir|CYhY8V?#?& zz8k}F|8XoQ2wS&Q4=#R==pSCG?Je-ean&uMPD1HK0dapd?NFb?Y(c}!XfBo>hsE3D zg8aaYokMgcK%0eQ+qUg5w$rg~TOHfBt&VNmNyoNrdwTQFnK@?`v#d=m>YTz`@4e3j z-`Q1SE_N=S*&e1OZ%oG_lItW>P_5_18fNtOq8S8{+CN{lR@}xy!Rd>}{*tE4&ba}8 z^U06A0#!!uRr(TRfg~=M11@Et(;&Cmou(C7rZZeEiHz13C}i*`THW7XxPaVL)~fkE zaXfI=`XCHf5F+df?!L+1LxxpUX4D_X^Mk;6VQ>YlK3DzZ)r2cn$fp4b(0Gmz9Qg0yKZi<_W`eHVLRAI#^1h%6i`ws@OwZfH@~}(+1Q;r0{*tF<th4N3?_1{Up z4h8FQ6x`?cX>!XQr&s=dz_jkl&;Bia2dW_gt=T_X3n$C)$b9$uJ`%n z*Zb$1JZ3X=v+Sk|&Abh@UI)|&(y!u(o0Xu6y7$pzI6Yp52Oq|g$G@n?r4nfoBR>vO zE&;^g=BQeXpts_=l@?0P(da9jw~8I2<@j?J*9)6rNp1zax_T39#~0KksIF`YuLeh{ zY(tPe1oB}n*_i3_(AzW>?_Z4JwAK|h#!@>=H6=ps*#MG~Bfmwt(MZIJAVBMoO(o>t zgi`@juJW;x=Nj&>$bK!R6Js1ODZ*RT6s-kTm|6ekMZc)6^ZXHU!-4OACO7P_p53?04K z9J%FKAp7g09K42WvjG@ahM^_I~yRPi;YV&g5^lg1$Y9mv}^66w| z@C=3iK3X~=(I`)c!5=FV@^uD-Q>P$R2*yaUfa z=HS`=7-MtLAt;ciQJ-rvsJ2}|vB>zX)A*%ZgUU=6o59~e4cyCMKi;dLX5{|}K}eX4 z>;1;nYB2EtG|Bi)b{Wk^UFH<{n7YiaT4gl-_V(G@TfGgmwqA)~j*X`m! zxM2s%IJm+0+xiC>Lb$<0Uke3l&kD{CZ$V%8>w*UF{v}=O?)19(QSVk)W_RxS?)YfR z#qqRqrT+~rlg=fH0pV&0>Er+nT&%(d4y2>Q$ko=?#(a9#+|PhCo2LZlsT-ffiUooG zj>&ig#^UUeD3#UDTVCFm4 z3=8crT8I(c`PKzQd!vna>pqXve>@Ny2o3Gf{KFO@z7CQrfPN|;2%QxZH~woO2Ez== zA7csx>%x5%U)b2Ll6waCY`TFfg9k^ItqB$_w==8z8s3D0o5CLpUcVP)!iu5?BTH zM#wL@XwV>nd|S}p-^x|sjZTgLXAt0AFr+$gsPj*gU6^JtF5uj22n%W|&_z7KS%H+4 z9~A@8PgNYCc+l6@&fY3NE)Wqv+$>FvzDxY6{9J=F_C6RmVBkfQ6fPZJomC(+g-QKL zGbHoXr0$F?Y%C+Q@8Vk?2Uh>8V2Hj;>fYW4=N1PLo;FTr&LHAmmc!4ZBE69*`k?tQ}?SO)Rp-oD4F0Q+a0fG3sLNN1wmb?*6 z-wB#QIzU}IIy#?$fx-PwKPM{<7U*#Q1mso#-}`4H zsssDAma6T$Ue#Z#A1Kfd;zOn62ki1${Uzi3U!SJW??WksPnHg&t15Bv5fMq(KqYaQtHr=kbq ztG$MXNT#mx>!$&R!Azcq2)H@)Q&+UEk!}^#q#WUQechY0%6Ia`rxp_w7K~CDSCAhc z70_=Y%#|Mpd2Lg}mq!auf$0N#n8zlzAD&`ZhHy|@PIkQ|Wd3s;rE+G5e z1sttFUSD}8|0GZtXAc%&-jWm8xW3anm zKd>-BoWwtY@-5Flf<&19sPBxghcM58LyvhMPq-g3XHZW3?*e^(;_%9cUUveZ(uJM) z7icbls}TV2D>q)oTwS)EiXU&G9h@&&-^);3ukkbQm&q*;5*ysGPlPCw}^8B zX&0E^ws*F9UJ`^`f;>YIuN-3UHWKQ-AqBe`^f6aX{3YgYa-tw1;bSS{Z|)z$=k92^(FbC~=!hYx-w@8`9L?^xML5B|FdM}mi=JKY#!;+! zx4(@_J)H!_on(D7YGHFF;I%sgvy5IRuK^Ajkop3+1=$9hkqiXyDT_)aNY^G~wLC(> zM{^;e>Ad@kTuYF4s01m>WAg8zMNKtmSUJ;a<5~A+U!O_iir$MGNcbobD)fs`7rn_+ zaG1Gy>e6bb&vq_zOx7Di=+QVbe4}@Qk|c)n|4a)e)^28IDf$se+jU_VCd3#U9^`r3 z!l*2wwKz*;bbS`S+;J3PfrKSHDXZW8T{BMTlUUw@>S}(Q?ijEXtb^dXWSr(Ju8g(d z<18Y<-uk?$y_<`J;UXi2Dvq7PbcJcke0Dik#AaDk7JHAZ_^_SDQapkxq9ZY?2foxy zgs|ekq7AszW8KZGHud{E*)UXC+%)+&VR)xUGHbNw6NA2^hEAqxTdN+ z#%u50>=yY`%Elb>S(X*nDgu-n!h)=HO+MT0(c0*02@+S8#RS)__gh|UDN_oT-y0u^ zgkw0`WtNI!lddLEAlZ$oyhDj*rNWJX6nWp5J6nE99H$1xj znw8T@>gJStxOS150zHc7o14jQ7+)`s>ow`;o+O&1??3_4uC;Qwhq>cubCF}msIMmU zuWA{ASYxokwGXF;nM5gat0lKN7(nJQ-=q6?=HM&5$kAwsL8QhiOMCu9rM$*UkgjaC zV~jS|5lBn5UNKA(te4XGW8I(e&Y8J#D+Sy;c9g)# zya^NpH+PwCvU;-#1*bTlZDMakwSIXXei}ERw?(W|3>D)p3nPUS`?#4SX z%MX!#vg>GHw|{|iI|XeH18na5_uSvA`CuMu+muh3GJ4H-*fIQw?Ivr_?j9mmkgw+7Nd&1J<(<02T5QA#VJ-a#ZtmWH+uto^Oj~bG}g0>2TrbC~4i7%nF zR+wr-UQxWM^m~Ou@vB{L%hH5+qOFhpCr*d$ucgp zeZs)k)uvrF&8->lB7#?UnG`o&KhpAUN#GoaXn$9yow4X|xhN_rrN=up$HXNwtU6x} zk@z8eO6EkLXrQ({n&s*_3nn!YiyI$NZ^bw+3HgmEJ$Yan%ASsVi}ch%k#|3ANL&4m z{(J%k?rt(vgM`S1-9Q_VonMD#KQJ>e?P&?pPJZ+{IMfKdwo|DXTLiCSMeK<4!)wqI z`pfZ;T_x$<^2ReEwjvdv$=KOGlsn^*Urhzmi0F%x0ofeagq} zmT_r0ySqo8$DF~#)#FI!8Unz1qm#GX0<6GG+>Zwce2Ca(D3qLMhk_N5dp{W7K0am* z;?~mK67CB7a!%u;2}*qB+kP48wBb}-RTB9w;3GS@h7gW>||KerI4yz&voDPMhdPOLk6b}2oKAgm09 zq=QyC!H|XzUrBmU3@~k^eAj{h%iFiLtflJ)F+g6~6_|~{Xghkmby_QLj$DA3-bQ8S zP2qAWb0(a6PWcK+Vt*mE_Fpj0$868@eMZS9 z2jXKMMn?iqW~3Qww>I@PD(2fZ%yK3_;b}6Y*|wM`(Q;^%-aQHRgSjA$#u9941GRZI)udpbxPS6?~nLREg>g3>insL2PTko)$3xAEC zZ0TSRAgNSc#aX$}`SJ6yM)a$O@^vSe`ZP$b8wLvPA?R8^Y+EnKmx+XuU|;~oH2oCf z@55|MMBQ$=GAg^doveH)`?mo3lf*& zJi?ntHSU&*Q~6Z0fXDSFW~U8f?kj>@TX=^}LREk--blkLgU^W^&EaO!95L@Yx4c&t zH*FUHw92Aivijr%DjoF3{!jD)`^ z5_o0jL2v|UAGWbR67k9Z@Nku7jvnXx7JM0Evm`!EO>iq~>=l@nkSfxpQJ4xjIhiS~ zJ6FLdzX=|phfbkrBgTpK|7)ocKxEkC{ifo$Pd%NM0~flggDhyDM}FBt7IuEEzFSVX zyO1Hnht~aOB*5_{5?&|89ww%h({q=-7XG!-bi{v|NnOSnNcUHz0tB?6MBbR>Vj;-P z4v%-XOlv5)06e|b%Qv^HmF-g(NzGEwm?nSGF&h=THI~Zvtz^~amwkmkF3mk0 z|2L)6$!cWuH5R?!zXQ{E`BnQeYeBG8ku6|4p1iYpct3CP%a%-2AJK;osPOZhvPa0> z=ZxJeLmWd2e5c&p=1aP8$Qv8VVfu;Rr^+oGd{VTFOnm4iys?)sqP=J7B#R-Q>tLoj zb=?SEDKcvv@k62gclRNsbwsh1E{JFnuI1*RUcu-v++27%>DL1TLl=)mb7H8|c0Jjy zu8{i-A{VOJZZViZ?>1c}tqiV1sN}2Jx(Nu9>Ss1FG8i0+?^Vnj8@Y`F;q)D&bLf&X z_Sjz~@dctdl|7}kwI%~iN{=wO>rB3Pbk(8E^&K$qdu<3Zs0xF8c&IkdH5p}$R4=FS z1kb(Tus7tEAdu^#BOHtCGzq}U9FE2E>rb=L};&9%M;5HM^MrZt1BZ&8vV3-~(X zd#ec}JCUaULyjI)lQTE=Z~!FwH_BxN*NqiBt!&B+h(4IR@8!z!^2FTwB?JC8!R^Mj zHw3IS3hf@;us%+wdI5~08=SW1~1KC9OU66J%;F^!Z1%sQM)@K*`H+{ zi^@*4?_YfRdFKAW{maG8Vl|I%ED~>7rwu&LK?e}S{|qjoiN?MdI1pBC{s{@uN?nyy z5FL5jPAd}stX+TNF*d7eP>%B@4Iv0y4bW{8#TP4|Ykmzz{j#B_XUpKVFm{7jyV|wE$CevMm(z%=|%VBY)5&M0=pa>p|~n zJ_-*_Jo+qvnv3$6N}+ZxzGwks9)6@sIpdO69uKyir!BuVA&OcQw3>?q(G#b`322|J zRt~2R6uY+`U6x4$Vg?0gN(nDIS~uCoeJO(7T+GZA6E?6%s&pSWi!ZnD2m2RG*9rV( zphOLC9sTsTeJ&&A3`6e^T|MC#PSyS1Y;B-#6!J5dS@>Y5Ix9hxX`o(5bh2%6hpM?B zs=ZuyD`{|79|pOQnnjr>^>QQ}^j6<>SgYmiMStho2tAz>KWpe5lu;ocZ5kv1N0Y=g zfRG>Tt}0y5w<4e#wyH4k+mJ?dhHR(FEiw#hNWySB!FJYD@|KdtssD zW-Gf9b)Co0V%8BIM`bFG>a@GR8=_2GevW;KTZOhE69da|Zug4FCz_$to^|v?un;al z#~I7Bm_{smG23HaVwv~0#ZOs_;X?3m>BQsIS$$_Ix@wGZG(n;z-YhT}>`Xuu@)r{8 zocG`{4u+=x9^>#bcobx|J7w&oK)8j+x1mK1tAW2ekedC~lD+!LLuAduL~i^J^d`7O zRg?EV_rvQxYNgMdEVmTTd@mAL>0L^p&J@^gg+?8*tCGTuxu1>azy%9JWP3j#nz*#a zwzAE}m(yB&18C1|4dZw#TLW-r4j{E|b0eGXT8;;K4cW=gG(nkYD6GWA2AjqZP`O>PDp z1=(y9{*)M)Y-87f+k!yb>uaZiYNVzIfUg#Mb>R;S<4u#*U*oA znk`@1ds*5D^;ljKNNhr~%>9qU=&njlOCDK{B(O2Y`96#y#a_(YWiV_&(K&21Nt)DT z2_6xv7}b(JJQ`5>>|fT|_GSw$ijw4;voDHv8eu-{&gACT8#LACBf10SYV5N;E)!XFI zhJ(D7E{?@pzqRWjiBB^nrea||q4-NRt!>7IUZc6q*E~W_H@%M>4>f7X5@-kC@jY@G zxy26KHo4%r0$*$~D(CIt;6zJiq7vj{1&PoCDD&P0{e1?04Ga4%f=xsKiu8^2d8qSM zC@{1+Pe8oINY@_l>Jljg&gb?m;iONdUEs=`BTXY>i0x*T+?r6H-`GihIORXy*LI`Z zVZ^~Ct2g6jBtvbtw)OOmxF5|fQFZm4OXvX@)`#LUkwbdMyD8w}I7|0LFm|XdJmP&# zU%GR{42A-(D$=G z7DbObPyX7FRB)W($aZWVSSB&EVHf(YBodt+j{{id1$6s-j@;BJZ34n!^c(6C6+RpO zj#ULI?dOQqTBPH(uw}wBHdwN;ufM=F;{^~Hih$ejcnMYpD1f%NR*MtBsSHNUd|fs0 zbKFmCqB9$9dx%Z0Q|=UFrG(%!u3Ni##Pu{w0l&LlgpK-`ock!oy4|E+7cR>^3sa5S z(WM2m#f%b)du|qdp8`^%-aJ}aU`e_N9NSg8ADN&o0oD8uDoFD1aerF4Ym^cAX_NOR zvwRp(*akY9_HuJ`CM;3XXDUiPajJLbhjn0JbOsQShuj2bsP`@r1Y`aJgcenQe2*0}-ezts2KSjIj+#`~D z1ln@+BM7;D8l%kegY0Bug5yOdkJo?MLz9SS(WexvR&Sdtr`W$gI6gt#&T=r{`f%1B zBkR1eu)R6(cSW`qP`-%Co+wu803_=;lbBP4I1-;V%w1%40QXfTgV1L<#S>kZO6l*a zwI=RRFLaIYf3xPj>Ce4!wPZ7x*E%zqR9Xd(L^>#j%glW3c`Mu_Zv@qq+8EE&RBy63@6w2~}R{xdg}ugo&a z9FyR4i(yg5Bf-zALzeIvrs*!RZSEaXC-&WfP}0FS?RBC&;}ijmnTvUgeArXMD?oYup(^J0_NOfI_P--jb!n877q?{|DO4ohqCs$M6BA$6F-zLL! zuVT9?3AkZagZ!ZYDJpq|ME%#wjuitB-C*X)WcH#|)BxvqHi2y4H6@6b zT@(_3J-IcvJ8{eLx0G19O_q#g&;g=fKm-S#k#$`SV_mrMwe!fKe~4Pk$8X_~0TLWU z+wBbwhM?-_-%TIXffgjMwzSg3;2tpd^RZkV3B;x)PctTeNFOgJzhTNvf}zRE;ed}M zdNvD_YlGkfW|sgZt#G^$SYOk21ctAWWz$=>KaIIR=+5?jS6jhSocRFG-7Gh+S z@hxsT^wC25w7k_LSYzSy?qr&jL?|7=z2v;|?Gibun@r+4k8S=ZbI?nm51o8vs;XSQ zx%!8_NRK~`5q)bq@x)Mq41ad0W9gUe(QEskI)c%s4vZ>AOJ0zeC#(@p%K=G=x?iU={KRAP+GfQ z<_vq_5}9PUsDW*}f~#XZ2z5ra8I30SzKDrS$Nj(t1nV_nUPi%PHacB~Wjbm7)<$KT zJ~!!f*N7>5&MPC0$pIm4d%qgH7c+&RI%Lc2tGxwr1+A_8$`2HH+Z-;}N)8^r} zJzs(S$t{+vTj&~pM!+{3pdW9;nkKFaC~AID?Aw#@+T6H@9>2JngeaVXx?PM|uE*6w zKC<@9-NAkF<{L9p*Y*Q6h8OkIiL{({DhG{Vnj~qQ|k>O z=@gyAR4+@5a_FI{a>fIz`9_q^WttuKY&duEhji-;a z@SaN|rz&ab&>rDd5eTqmr5A)i=l0-+eK5g62a6TW?Mwh{;wFZIi@R8%#;k%{!bT#) z+2SB0gR>qs#ogZK=4y4=qsmtb@dwX-1uK-Np~0yPC0&m=cp`TlA!Z%KER7Eb>xPsL zS2E+TR0HNt&`!>V`C7a0WTNCQVjs$eheTN2x2_poKi$c24r=)YmN*25rpN_pL`YO5 zj2;T@@54y9u{9hqMo2da7koKP8QTl-5Z*7~k+o|AL=1#K!sm|Dw$CK_TMVvXa~ zRHfi^seLI_CGLuJNp&ntRq_Ylu-}J=7_6?_i6iQ0VY|VGZ-A%zBgxt36Q}cIYI<0F z^%rd5X-lFr5AMR?*6o(HrjUE9?eI*;6{;AQ`zkfMD8`=LLok(TbhDHuaZ5eaf`wj)vs@9q>MbGcnut4Q-rw! z;A_!v5WK3t4G{{AriGZ8fkh&Ln(CEG3#Pw0a?jI^iId7(Yx=$L}>{E^>Wjdebuc;W%U>F4q4kB(-S5Kfh*BZMgn>cA zDG`-OGTC3?S}44d4M&t!^nrC-?@W{K?Fam|OPc@6PBm!78qQ^MWP>WDx3ZPRted^gQR?Lk2$>A_b_xqyGZuxWj`?<;RPSjj-5>nykxF7eU61Jk3!bgDKIYpoY&oHL zI(C@}dP&Fd2-H6i_k_~K${s7~v^Qdt&`hLE=u7Nx6vcjH>dYGY|p!k^IR^frVSWRH%8BrJ4dBe7rF5!Uc-bxHM2+R~(6DFS%bXR<$QYZ?nHf;x;hkq+%zmfR)@GXB^cerz!UK`xbyKuw zL80p4-csC)7Wp(@e8A(diQm;t{?Is5{B$l?0_eT(eq88qNnW_VS&2TTahCV==(&t^ zu714B_um_#V~eTcC!Exu;4L5SpWY<`ZJNS(@aupe%!!W^ThTv8W<@L312Xtl^~iaW z_xH@~i>w+0_n%(3)1ffeFpuAFRyL2orJB~W=4>nvvT|JtN)F$OZ}%3W|2_Jq+LP|j z{>T^Y8;{O@7y~N$=G=#5Ax~(~eSVG2#FW~a zj=`de$78mh-LMszwpwr3+uVki!jk5SEm3y4r&{BWI-~#gS&u-+AWkt)h>+;SEz|!g z8|z)r&7IF}JjoJ2QtE2TVS34TnDQ=|clu6hj5#ggscyrr*!cl&RNjdGKa^vf|8M0O zI|ti;1Y#^i0A?=s|BU{pa*UIOjq`si$J`+~H@1FS))%YRX%};$#g?|c?5#vmf+gp} zWv8`Ny_BVGRTsC#6uoK@teO_7#1u=uN`2lxbAKMZb}l@3Xjf7WH($QqvLCokzO(IX zZk@2RA}RzG|1!y%*|a!9@=no*U4~S@;WsxO5`}#ghS%`QVZ{<3fQ+0tGbq!78S20J+v7;=wQ>fu0t| zGch{pv7@aMg1Wg5?jOH>&=gF8NHK+j_^S_KDgJO^DCe=Ho3-UQNV;b7xICZuI# z0)Xl|fzk^ER2mGYJ5z8wg??J&LrN=--O-llRkf6xm;}a49AJd zX(ZLNi^PNg!~TGufjzxU2LY@_tk{sYucORfhbaB8P=8Xx5h}*lT3iTBaIkO8Fl&}@ z$ZL$d0nG;h_~6rQ@5z#&u)?hVGzBp^JdiPyfuGZ+=7G49zaUZ#Z2?p7ju}LF6tSX) z4iu2OF;gFS2=R|=9f}f=BNI-H&|Ckt=K%t+#P^7OpaUmF(0vFu={NUyFSb;K0368i zJt7Rq1kg}UKUVgqKsp#h*hQ^1a_F0z6Eu+^UO?sf4i&;E-ps6fEeipXgBLfht_5_~T(LwowaR zO@9v2c!;)Aw_b|li&;sdCuB6h?wyQFYr#!5Cx7V|X~swtx}x%fP?d1r%*faE<6#KB zxdo=d9ozegDxxTCSP%YF+W==i6~+p5#?-3o`j-jnZ!1b3VV-Z5%D1QwmhQx?8Ga1? z-yXK>6W2hzz$KJyI@ndKVKi^LJgGP}#K6GW^&PPulCm;`whixFC4o+tq4 z2y?U@mVl(G`!c1?+MlhkD;Nf8|F(pLZT-)O(4BlJ9>~7{0 z8&y+vvk&E(l8YJGN_Cl5c7`Td$Qs*y^vPX9LnHqlID>yQuE>{25Yh&>QWfvOfNy)T zdN_z}nE(?0*nL$<-2h0!$jqk#+Q7<#^n}u?vy?N4dl{b1P`WHB&x~Z2%(yQF&3xMh zpTfk#Np;`4dB7PEdnvuQc(t8Q>cxisxXOoB@$h4t-ZbG$8ccdJw{NVB=k=VG zZn^sky9=K1R=Ik`^E7}dE+tbf{du!_O@Y;H|Rp-Lk$?gd8^U9;Y?uiko{6IOFgXE*-tqhoD zMVR(JVJulf?H`zfl5S@860{u8(gU8C8@FGgzlrq`auhrQ%$FFdC{aq^nrE0O)Qn$DpJ zg_ccA9N@gP@2F=m`@T|3(Qh!0n0W*h_*hedC$u+F=TwB=_;UM{pAR(?? z>)i<2FgKzDmy2~Nx}iw&n`lsyz_oOgJv8huL%1w@4y!Tb=fu0sP6=LzQrX}5-~M4h zhbk-sH(n?bn+mHnYjq*@a@{id+wQ~Zn3Fz{GsYb3_#s~Vo&07W%Ht6wUHobb5=LG9xiE_hD+B2AMIm`g%vI=8crI|4+4G&ZiNEJ(DR1kLEf(H(h7wcS?YzcJP>aU<|&dHk_K z+-pnG3NuM)pCs)6yo=PE8kR*Q1s~}qRGoOh@K3&Pg-UQ6p^AZ=j3(r}HE#?lGm*SO zS?xY1+2-T3C(z%_Y!9+Rbko?iJdXNtaIuj0f=$S6o4Z{4cQdb%<~Fq)6QvKDe(#x5 zrQbvOJ)NDDjK8af*2%G63%3tdKf>BW@-}KXp_dQZSgL}r1H|~p0RNmN#Y<}uuBiB% zFQsy{rUnWzPQJ3KBU7$i!Kn-;}MemKLg zkKC!qS-v>cX|gP!oJd$Vjv4v#9_s;>A#a|0#6@UK3nGCzg?>=n?2Mv)h!XxP)?K`coHsCY*X1}A7jIn~S zKUlTyQ#6i;alD_83I9mA2$e_F{_8JX!S2Y=FzmW#{F#H2O84mzjW=SdYb4V18TeZl zq}wI$Pyjy}p~a$R{d#Ep>XD=^!<}B}l6KE3CDh|XTBZ=fd?x0d=`d?n-6vjow3(K| zS$$s$mEpjLsaAObJedwM$`^8@wHff40+1-If(I%A+4|*k=BoHH1-x&6k(CPa=jp?S zG)T*Msn!8*6RqUC1!i$o1Tb8`nwiszR}NPrEub_pZma6RXaEDd~1A6^RU&RsNQUNd{}h&HH>M? zrEUTmzAlhHT1Foh-aE8yEpt5+NkSu14|`=gF@k77aqL2XR=8rdQ$d?2u&f=|$ECnru)mD_Sg}>>zef&i73!>o2-d`YD6tXEaTZAO)SC zq{#U{_|&@$GYv86tX{QJ!U<#mg{D94ib?b=>OVj_T!PnTRoUK4U3YzAz18Ag^^h;0 zKI)1a;+%&t5hQnoL;YJ@y2L>@k1N`HYW+*B{#O_0LvdFuP@MAmgWeAM0fVcwRjq@! z**u&%tl^qqFXx&3E*1sxopgWNJ!WI9B$+`LffvQ=5vg{9#~y*+88lk4y27ENDm%`} zH$!nncrrRPoI%y1=Sa_l2cU(^5mLv{^gaSW#gQ$jxUY4c)a3ubD#AYHRD$qmPXC?RC&nRM7V5h4{=8Bn zJKP_ey&-Ho`F_dpYK(aHVWRxnM}6%ya2fD;)n~!dKfXdkUE|a2DZF90?AiTlPnY!y znrag#uDYrZn@B8>_e-ZbkM%~f=xS2Vvq+#vxTLeu?{!=VU(eT4-P2)1=6h}fBSNo+ zaV3qua3;vQhiFR3AV(=nqVe51!255wD&8Nc|Jl^^oO>yP>b)mU4c`y{QzvkbO` z@a;&L3bE5~L-i)#b%nNH*DG9+$zRc#BU54=nMn2W`4m8{=(MpI1!)&QiXPc55o~^TM5hwkfx0gUxjC zw{j~@*wGzdE~sWqAx9{g8~8osv$TIjwM0OVD0}RpQer82W}dEj$Avw=()9NF*p@1F zZAZ(x$IIJLKNS1PMAT7vRt%XV-rTTMQl8LEv~IfDcrHQ2RMr!wBw?)^Qa#@YTG|?U z@5P;?r~KTU#>*G+fumdaPC3TR49N0W;uUoL?!fY0Ws&9dQM5f}2is`F0#UOo*Z3aH zuO&VPooIE=5OHqW;qYOAPlWzR=C&28f}WOVJgOkH<(bMg>*2!P)RftsA@LyA^LUEJ!Z-n2melwdx;?~*h(^?t*NG53lvT*2H%6if_eJYpnBLPO zLie->U&9%tx_HWTUd=1Mc8sbpr9x#DB3Xy9H*XJK*Pi3%+TJipV$NK@_tG+4y1qO5 z^{vt?m+E?@lS?E+cJ%q52ex|laPB4NwG>;K1TCd}7*+ajFTYdd%*n_<2Kzdr|8jst zZpyRr(sFiqqv#tqjilYe;ZuU3Ix( zSgO~Fb5_sC<}u*>_d#cmd-CHpgtx@Dtbt54enhV!kvz!CE7levPJN6>Bda=&{6kr) zCmZK++zMk331Vwp2e#wdS2JH~Qg{I$wEbo{R(5A$UqDy6GifdqgRBaJm-sv3WGq8O zn@j^hIqR9LJ@3BMmmkwr&!2dI?T@IhJbhcfJ^?8u(naB;UF)guY<$ya0#O^=60y#D z@Ci9k7*|0HLr-9`Z0Xy~$$D(Jf*Ti!Qgfc(auzr~OATBJHZL!^r=Yfs_XWYFj)=0B zYYoD|T_|-2Rcfv;Fv&GNXYZ?$LAKPhb$fYN5yR2RO4aOGt?R{9Hw-YEUFuJ}*^}x?NbW{lzy3(TO3P zV>o)1uE0JI>Ky8SWQo}z%kq{H-Siq&M=J+#lsAQ+?PBm7Jv!$hC^b-KF*!CElj_wh|N|4PV;bt6TGx)#2jSkj|ll1X$(gTp}uG% zRA*E!#?c!JF%pKai~NRRR}{W5{A&fK`+`TsQ~y;(linc==C`2fXZb!nm%=kz8U-$5 z^KSUcgB&ta?#-e>$NnABs^*`adojHtp^V6NnAr{9F0eG2)5|V1bNY0K$JO>)@w-;9 zTpLiR%PW?oy)ImZQPw6E?ML^iHe*78GB(A>tIS?fhx$Bxv2d>!OenqL>spX#z4#)$ zeww3k8}zAg`ByR=?Mf)&XkAjQ`&M~9@wjw}kzv(z|D3*Sz&UqX9q!fM7t1$8+DH$n zmcq3l#8J1A$XAM#eIf}f2YUunC2MsRU&52|D@W~UWWV}z%64J^#|ShJkrw1SdbJ_^ z2_5JtErR4Qty|~A@xvGOQ<3)1hj`RD9doXV(VaX>1>)GRs}3y6MupJ(YXE=Z_b%d& z_Zo1;AMIjKV$3NiABUe0`h@G9tHmhjQvG!m=&FbpWRE& zynSD0U27eaHX3KloFXrcOt&5LPfmiX>TvSXR#G{{8;N_R!}OD7PgQcEmtd|GPx<;w zQ|zhI$UBI=F5ADchspMW?PTdpnHkAku_FO;jT{4n8 zP;h;|F-nEQ++~Xm^5Rf33%+ffmbcMXh0{iQR5m-x2o?-!;o4x`lhWdf?BT*N-5J71 z8J!&E0h{PDn8v4ID20vg6HZ)sa#P zyD@8#Z)z*xtfOqrQb-tBff2 zF@~$}^L1kDB_xxG*=_TUTgS&1=2)i6>wva%#Sq!3C%pXDbDH+Tqn+03TPwO$Q#)oL zJh+8?ok+D;d1ZC0XqmyYXw`=6Xh()u{C4kx{s|H!Un%?F{W zz&%&H>Adc%;n%Ecka79+`b(MV5ab>gTcR;p?0Hhew0&WPXDTQ6pSaa(bx>y}s}Qq%Jz_QV5J@FI_Lsj9~)_!%87L zNTh~)%B0M;jp51*`{3EbrSgLeVUho>jbVH$v75MN3heI4}ox5JJj)tFj>2+4M;LnnjBouRc!^t`FrJI=yTe8YIE<;#z*3ek0*Pzj64 z7%af74UAld|3G8fKW#B}mOo-D-h0s~qg%DA@jBPZih$Up zdciQjeEC)oq+4lU@fx?pWY#4<;zlB1IN#{I@N&bc($(FsKbG(_V z5A$menJSZ}Ud##uN%-b}zTi{jM4l+abuEqWiMiyjIlZ;&85rf;f2k|l19fc`#87lL z$^eD9fA|?dD`}--x#R`!9|3!0HYdNKHe=+_>Q~hre*;bLqGS_xMm@1AmSbH4PIDmh z5xTw2G&ALw=q@Nfj+=*PU)#=3S;A(6tczCP^;dp^1De7>s)j?Gvqls;wnZBag{cJJ zxs8|95+Thd+9B-7{npBS2qh}1VcvS@R1+f-l$Jd5pNFFp%=&XHy$JQ(*A~a72n&2t zU7=?Gxr=Q#dRZ*8#VSbfRHIsY(PfGZx6e3jqL+mc;_^eoo1H~X6!M);(ZI^rQn>!Lyg;6<$~4@8ohL! zAfX~Sscz{L#*eXllGZrOb}F_AnG@m|HWQ!vnzCPVk3|$8C+^&dgXXpuyi({7?ZAZZ z)-?Z04H1j(pm(}x&|Et^VKc2JVL%Q}3yOl6RA957TIcaQ;B zlm95rlx2H=Om>AiQ1=pnUoA)oaZYYgF8uuq*J;0sEh@(Cs_nY99sf)N%AMLg;271p zd3cV}eeNimv^YzS^=M8DoOaB!YZBJw$Cqs5F+$&&=67Piaypb^!9^%9_}1{@1vX&H z6t#f-e81n4Q^KKm??o0(ds&E$e5C{m0IXr!^zgoL-smV_R{KP>a}S_=dQOlFnDhvg zRYYsrJH#5x=%`;i19NNR7)w!}C5Ch~oB@hY=f4Gu;AiYisnLV+7kQAI5gC7t$h9q% zqgsiV;vFZqHD)#Nw`2%aeE9w&&=kws*gHn>Oe-LHyRE=Vv3Ln=a?1cZPkgQfS5g|* zb3IZ)isTL|54eRQW!S8F8$DvbG4n71N_e(*>-7`|zcV3z8bmjMf(=Tbk*20_Wo-FYOQ?B&)?s`yVLt_UY+JDq=VGi31XSVVv@cz15}m}FzOn*qN)k_d7>2duUrSD zaBW-(999E*DY-$R-mkNJ*Y;J2kBeAilx$YbyC$-WU{q1Shm2Zb7cr*rtl*tx!g>Lj z3?vM7(Ib8f;W04`KJqf}Uq`!<%0s-1E>TwtUcKfEIUSfyEcc=ceUG-gb^^;^;J&9v zg#QIp;P^j-3QTMa|3MQN30OGjnf|l;@1O!J`~MFrxPU7sZMV`a4nr&oL?U@23ZAKW z(k%)=;D7z+9;4tqu-!`+h-6l zsF7k4zx6;=V1Ocrj4b7Ga?9dG0bRCo0*DOx5hXMbDKzLY$f3ZdzM{fM$AMPz@xOM>q(y@3;o@ zXZewtVIulHev3fzx`E+NDXFNh&d(tOJM{(3qkDk*2mj1Sf#AMa=y4S*MYC&XCd+fLh&F@Ly$oP74Gze%bCz( z=E6Mr6K3bZ-3M=H3;1D8hzU^m_IB^<>0uU8!$1uZX8S}@epJBxCNId_DK|zy0|pHM z`#zL}3=!zR8oZ!?J2c2pHjs}$-3-En2d;f#0o~kCS%nCk4_nCo5eFY%pA%qobnIBi zSKs&_x1Xr2D{3lA3w_UK2YzG9%JaJXdV~!0^5UX`K;%S3G=Ry8iGUx!P0@rX?`^Pm zevT~)uIBmEdA9dsPj#_8KT!U+bsTR2ztt|_F={kGA9bpLWpI=UTE+{atzsF1pkP-waK>?n?{q7tQ2e+GQAa>&HgO_cI z0fPi6SYdL22WC&;8wCvhdaF=iP+bHHH*0$2d-y2^HyAKG27RFZyDxf|yRM=H-3avk zPas%-&`;hdtMAJdGe(roHUZ90>1GxpQgalL*mEb$df`0Nm{`QNm2ZZoYF|q*WqZOg zGVY8J*VwV18f|Cba-~*0BZ=j2wdL25Ca-yRY+A&&f{QY)!-^LR(aYKJF}L%(;R!?U zcw5uiq0=mpwP^Jy+3iMYwI-?ob^JrXm9HwO+ruU~W~_o6Qm?f2>~CpmDh@2@z}v zsR836hXXF6l7-<)PiYakorLFSUo66ErhXFiyRFk$eOY^tGru^cas5T67PL`4n9EdW4ay>Tu-XwP&!p8CdeH# zj(J~Jy;zz#vDhd!hl-Me*@2~u^N&s z1{QAsInq=)whq-7W<)(FG;MaEolU1IpNX6++=_BLD>ET3_$Qcci?Q@XFDGwU+rEob zt*k?$^(b=IdvpN@%#e+?$OhrNp8M4&Yh%<%p7P2YnaeGU!;e>+{Avl$*X^Eh8e`R` z_b!|EWfQ$Iy;T)$UBP|P4(cm+rzPUr#SB|tYvM<{v*uj%c|<7XZ`)?=J{Oj2hq%#l zBO9fgC0>Jr^_U)!9}`7dPIHIk;5Q!pbjj34r+kr6wV6GTL>6@qaLsl~r4*L2M@ob< zy+My2;%^rU3jzY@?jUE6EYxyUGY0-zfiY%AT~zJN^r0lfgbK|{0=k|;>Gjgieox<8 zHD+CvJ}P-$w+$-zwT;SR-c%a^J#3dfBHZDWSkR}_g9>AE_;mAR2$gjU-Tv)%1-Yk% zuG3+-&JZTUO%z{q#1Ks3+DYz-%q^>E!8fMSK5e05Y4dS(J~$275bKz1+x$;j}w;90LCmC)maVe%fb2OGoT*l(*->p zd-FD7#euR6*d1VDmUG`xAgphaOG8F!(h=r)h2&&I0+c5}4(oIi(aYe9LWqf<1dZ`B zs1tuYi|)xw2bwGn^xu`*=&Ea!8M^Pon)S4S^gubJJc6z}D*M2vEHa+`V{^PJK--lD z4vN|ug$cSTb5nyCUkr~}TVKZ}z?aH{c9@bnEGZm4!c=duF~MBI8`kp%7&r|0kYMd5 zB~34Wr>#4vk$(hQhO%kopPN+lxiOCXJ8sHp1fpD3Aw4rUgyasOi@6~@w)PowJI>O^ z)UilgHV(m_pF@d9Lv3*3o=M>pGS$^#%PbbG=8Z}P`*a|bD)+B!&m4m~P6Ss;Gvm2) z;+9n&a;FA1$uq10#l8us8H9f}o-c7(S=&{tc@=6CJ{xY4asT;=jR8BDOP1u;qSAEq zXv5Ca;w95z+o6%jg^4%m1g?T+l5svr5eP0nJo<^Zjev@Xj3lO2s^l25&9;54cy-81 zuf47w5`cDKSSgh{>Uv~9`$ydDSdls$G+5wq8jky4#!Vw5t)P&4yYJcyQIjc%;`!Gy z!{1%;IM7G2A40}kB^(XM3+?JjLril9Hx^Ac7uD}O+=Tvg{gDTn&B+q}7IHKF9T=V~ z{N7MQAfgdm7mzv01jwJ!05_1AA`r;HQ#x7cK~kU1Y1n8tfvVaA$}@089547++f`q6 zEqR?Iv$}-DhRQ+!OM0vPv;f0%J2c)AP|bhQB{7BzpJVw2mC6hm9;4U^V-={%m#gMl z-V`p@vi3)wwPrc4cx-m}=X{LEie=P~PZaPkp3YucZPVhg-`qM=BJ|*k4b$pZ0)@*+ z!ch!4mu7#~>}FmrFCj0nraFT7+eZw}xn^luETA(6RVZ~Qsn=d+XdB)iy^(Znu4(4& zV;GzCVhSExAiB~gro2t`<+Dxi!mg(-BmnAfH5g`4F6`m4#U3Xa|0+Ss!-kprf!~+*`G{z07>bgIa z9D|;n|Dy7AB4*u*vygem@i4_^3R(e@i(K}%)@Q5_NzKRWD6;HL&9+n0g~jt19$9kD5f0?XOhPX0?n9CX1MlKijJR95_Mdj#?$+ zobr+3*Wi`Qq~d1>Lc^DdR#La+E!w-tJkKVdUX?SDyUSwdfx3ZfhzRbU%=;wWsGGA4 zqs@&!;EyCuzk!iiD^ZK|j zl9nQMyYseeX%wdg)G>y@VuvOa%32h(|gSDqcpo(x$-#tNm zq1}(wbT~;+Ib$#M%B>dSHmbzb9L4eAi~C1|%fup%)&Rq?Q=zfy^ew>7WGE~C36Q6d zd!^oHxFpK%QAH>dr|>=kR+iH%Vmq43k);wfQq|;+3w9)4n4D9RnWH@%P6E3fesxf< z(_ML6YLnJ98~NN*2UcayUF22&!4g&VZiP_#-?{RdjL&erpl1N~bn9IwU)iJBomuOJ zp46@jQZG|wV~E^LVFQAepfqxM$8PZN0&*q7mZmzbO;Ake^dT=33 zVI_RFuuguwyxjp>C{!EOjXMMJ6BO>pUL{cpJAF%>tbvp3J)4N$Rw^`YbXIal8$VhR z@D^exGa;p$*-LVE6`7DxgbSIjBl8j{A^qbjSO*j6Zc+Dm#-wSAnb#Ahm7St?+thUQ zg`vucu#;~PM+9@`2)#$$yGgNpRr_B2vrm5WxFmDL+MrLB7zW_eCTjYLrVMCB5nm^l~K#jrq*UVMJBAAmp;F~$7 z^68OSLg=F9JP6R!XZAtc;w0LiFiKTgW{PWr*vk#fO~u9iQ~o`aVz)lf^8-@c(P3ua zk$Wh6&AI|F6M0Zeu5JEf&tUL6Md}X}X{{3B1vDrFTg6BcZ!Fu+A&UPv&wFQg2@3&- zm#Lnss=244{gR)9G0$Qb--Ji*Kh>F=LgB~CS_e7c#rtRa8ix33PyYy-&%NP8ViSI+ z9Wvg8_h4$>sx^L{9*1-UMG*|g*#Rty}Xs?^1! zuE8&_y$^ZWu{saUqDMQ8E=CvDYn*z^bHTi<<6qmwJWh&wiV;dOwwyo`zqH@|L>d2n z_3g8Mx~i0-=>Q-Is^CX^z<6P2mU}5RA3zlp){J~5GnYm6qFdqhul;4l_s!`z@Yn^Z z7cr1Zpr%^#igfYwsbQX^7W2M*&Tx3Q#-rM3LL=gP7RqR=hv^$%_apC-EoMmViG$69 z*KRX;tjc)(hp%d54RFEUM+PeqUu;+??#MW*cdu2g{$a<8_j+oPbwC-9+zc6=>12oT zK{gc*+~LKZh_eqI3>0mMrKc9k#2X|*=jJ&K`ctBd;(uGcKW^L2u_UxBt-~3*|sAKB` z`l=7Yn9Pl`3)vC2a}ky~?)Eh-v~W(0S3(h`sJs?Yny`!-9~eJT|9F=I32zsQGD5jg z+qgkSEQM8n?`9+>Onv)Kjkx#L3{2!79X>bciK{ zaS5SN_HRO(OCC|#qlu2NlF67ZM`XSm_7it!&V;GZEZXTOR0Q462?Sy*p$3HK z1#0E$LcTc&kBK-ULtQdTI{}@pE;LDYGd(#JUZ7*Ug3^6m zkXhx|Eib~DM7t}{I_l-s%d8I97Y1mR0A93^t|O_gqrOgrlmwm-+qYPi6tEi)I2%pN zW7XNPRg#eDl9NA?4wB4gAqD5z)9f?{VfxJzPcnp(U~%mb4F41Z6`l(7bJPRp?W>Dl zh1^mlLGWS?RWq_G-X4}`r7gzqLxj5c_LiE15{<6qc9lpWF~(W33E0`(UJ5#xFmsyu z7T)!a0%17>?oUabz;_fJ8}QSGBV}fxbQb`oFB(zoqRqP)iViC+={M&)1%_a=0tsoX zWZB`OofOS=41E_wVSK%1C*^e7yY||tE$1?pA)=y&Idj2tc6sLVlsh!89^!i6&tLl(; zoAPz9^$9CTL1)a#fco_Cm&xT8I*!R{z~s(h2{&`gD_tu7>5$`AX_f%D`fkPJl$jDIL|W%m4B z%6=ZoDk8ZA1!0 z*g$w{gzw?A7H1WxS-2zR;oCa$&aNY=EAuQWi&X-tlgcaH-scI+o={-w{K9f z6;IU+$)ZSxPmJh5h8#$=M(&#PziD1)3HX!$%8j`5I}aOD`TJl9T1HBq#LT;;Lgwv9uAw9gXp0BRRJseCro1r@hTW-$?e{>)vzx z(asKjNY$kIFX2~K3p-x%Bqi`<6n_=;-9vNg%$ED8Y0DFos_vJGd5u@c_<93_O{x17 zFC`-1`*%d<83!03Yad5H5d{!FX-+Gw4-<0b_z^VMlsU<5SQgJtDFg?=2W`LKd_Mx4 zlPW9?6zAbL{ZI2_M=!R5@WVtf2d1-R0>POm0}8xA`hy|hc$RV9Jdc)Jqw z`xwONO*-tRsC(-2mDJjGyUc}VN@oK)dPB$|M@Vx-jzPHkup2`*aG5EezJXTD#F;l6 zNIIk~i<$z3t^We%=jdlhw3wmB!)cZ(uUXZ)Rg<)V#JYL>@dwQP1~Pu-_qA_TRx&0T5i73)fjqFAS(YNSjy(*Q6dYf~$u3bqe>6!>Be{^Se zWLl97q+Q7#uMirEOdo@Tcq|w4=C#Y)(yqgKJNxvw33)!#Epc(^EBkqTg(;eg_DZ&9 zC}m@L zE2SuSP8IbdifgI>g9Lb4)ozyZb~cw)rA9EpM$Ka0@}q{l61p**^1(*{sV^`M>dRQF zCJ26dbLX%3>fcNI)i1)$)FaqQWVLqC^!EJguf4n!={=>ch4MC+&p>L^A*KxOaeG&% z=Lg{9(d`W)#lYw)$pW`5_W52Fmb#rB*N6-Z&1t#osdTQ^8AXAUl~?tpDvBxKg2h{E zxea_ioDNNQoy^#FT6r_!&ouR$8IL6=xCnd$`pOELOX24Wl!98^;|t=+nleZHz(OcwUHhu{Gk zajSQk&n2(ez}uiz1A1Nmq8&lnh5HqS-M&_C@v9KX9VBGcaiV)5y}n&6u!{)Io@M^3 z=X73`f@>d{rRJ0z z5{%;0g(X%Lws|UFjbdd*+@@)b*>kQ2pte`a&tkIaw%65O zjfAD*27a4&H8V06zmHXkGP<)}-csfNX2A1xQ%{;TCss=*h3-yW8qF55Gl_Q*^tf5y z*{gFv(-ogPFO)RZ`IaV@Pu@Q22tAAMf{U0F(>2VyNo+Tzf>*M|KBT&hyV*)*c6wjB z`Ov49)}ba|qUxTv6)Byl|JqxdoGMDmzB59OKouXfCvW+@l3Mv+n*)9_nhct0L~`x* zK#NgT((GgNs11CaC;hEe=OqeJq2wI@syFD9=ny>=DEK4HF_B*)@BLbao+d&q@25a~ zF#cl|L8S6|bgc7}{;|wHSAZnM$_cnL2-fI8VAhjMqv66J@H&ln4UNtqx4!5Aw3CWU zd|Vs$QaYoRhfNYnrG7re!)zA-R`C@Fse$oM_YeEtIdC^VWIIFU#$6uO%Y!;x+LYmV0) zr`zATZng}Gmp1R3?;0LtFf7<>bVXHp=y+}vAisf;0ScISg(Zc90}y-12YY)*M%qMP@}YwK^wMCM8E;P08OOO{!-%N{@-z2{F8`B zK&{MS0L#<+tpsCZ(WxhJ05;{M7$C1-bqLdit@iCn^ay7+H?sye5QqMqYvE1xz*__M zTK;GdV2%#J8i2lSF!F3}Am7_q;D3Pm$IxItr3zqMLc6lM`~l*C!0SmNfV`X?LevAa z0pivHHzX_l(_{(8^+qfGFzbPT@ZkKTf-ZOWe_noYAz1m7pj`nqcxShf-(HV5gz|3?Zv6`o|_FD8^|Z062j8@lsp+cOjj*bNKy|wfjcmc-}m@ z1abiW#@YCL5B$v^!XVr%|@hjwu6!`16 zKlbSc=mh}7fqy;*y7%?{{yOoNV4x}=9(3wA{j1F&FQ+NFut&PNOY^HmK?C~?;NG{l z58SDT1$cOi=_5SRP6 z)!n$3>dOIoIX|uo;9XD2XI`(W3ak;Ri}R;W71H*n9aa$`OH8zH@8Edv=vxXdbRvj{ zUlmKgz2sW2`dzB_(`y%}A0ZwL1?=a0klWM2@h9%aVS@S^Uk`DOnB}*eKaT5Z*W;KV zRlaI>YIJ4{p5D!Y;dR)%`%-Ke{O-haOOh&n44)C$9|wW_YXS6bt%$B4>mu;|(=Y@C zfd6r~urD3~!2I3rsS7WEg^vIo0OAAu2o%8P7w{c`|BjD<55W8to*V*z^9!8!0R`e6 z+&dcP8~g|iAm<0x124+aHH24pI`92=?1G_hif_-zckSQuv1|jXF#6FLrML;qT)Lr$vnD>2fM{ME7|6XQ zJ}{$LF=MirqIif*Bl%QsG_l{KF8O|4ReS?z+uM@cLF6iYXNmMa3m2O-X>k$zR#pS| zb4qDi zuSQ?Y>!nU#lM!CuI*H~Dn-{Y>@qDmvM0r6@t4e^7G}eESIS`NkiK;zvkEu5z*3#%l zJt_>2mdBc#JjEL?C|_0JbHFphVj97KfOv!iYMN$Ss{OhOB`6*z+?3@?uLFY z>~cV1$S}Vbg1;?)y$E`7EdO>FcLh%g5x^9I1a9XqBi$d`YsS#86FlkDxFcJ233G155OqDkgte0>>=4*FiK!J5@l(0g|{sv=>>IQllYpmu0x zVS1ZPALM<~r2l55e|g^(>Jk|se;BrBsZdO>ShqQ;w-=TS687)!F&x&G+?f*e7k{WB z(npLjhggPseOEGd*egs0{?6?Ums%>A%BoEj)kUQ%XJJewFR;quJg!o=cWhd+^rxDw z>RrJQ-M|4l2YbK0JvgjyoCUl=Uw>`-RU@TJ&s7C^5KHCU(=~8j<1%hmvXhXd0f^ZO zF3N1|&}Zaw?iXGvF^-9qf2=PL*H1W zH2Gpl|0m8f#Xb|`?CSK>&}I^t?VQH*?huh1OYYX3;3T~@?2U^^?x~}5mJ&3^lkcg} z!;6rT)We4I)qv%S#z+)j(^OO%1i^V{fwqh&%Rshr3k}UwmqH-&CvOQzOhFAYW2<$e zl*O{{fkh7PkK!u|CLa5?SwiX?CMi~3yKduSKC#Ytrpg7zlT06I;GZ!Q3wt5 zq{pv0Tp-N@qPw&09cdAP3hX`=Q0u2v6%_rPK$x!ZqMRnHr)jT*HhwI7P1HAe6DH`8 zAyHfcCKL-HhLKGjKm`*pXVseXHHFaCwi&l`UAnaio(Dy!&IJ4mrowK8nryEYAaHzS z%#w|4=MIP?eD>=}1lD%9k$P-M^cfR4;zI`|A{~>jUgME~YSGJq3BLJlYB3eDO^%1WPX5oo;qW zC{R+d0d2+zXh)UsRs@~HE%cGNcH@e+pVac$I_vE{wdQJ|#GX}SrYxbG^iad`8&CS; z_Hkteu)PZ|rP` zNeNYM)7;EDH*Wv&hz%|d5+L7TVQi|zkbsY4Y25|Q)P~T%U08YkB{fB9fk> z{Q8<5*Zb|fQqETfkl9E+w}MkM-%T6FnM&mg%e{ZFRHG4ql3@RYq}?mtE96(mYwOBx zacZ5I9$y~&R&GA)TwE`v%frD6-4!jj<8yj;ERX0Cg+a|a5hB-7!vL8Mt~wVdu-b4N{~5tm$=CMxk%AqCu!mEgeW5!OcZ?~110v=MwPMe=i4x$YsPfz1xHx+) zZrCzEhM@f1C`>6A<0uQHlKK(xWek?#p7r;dVayFMyh%6X!n@4?V=nhp|InAu06+f} zZ1IM04>4E$^VIKTuGmz6!SKzrft=k+Egf+<4o&FVoj>_u1k;CK_Avy8Wfp;2pv3k- z;6>*A9=#}$pMeH1(YMfw${|zjaY&&{Fvij#Q>A?9p1((;>SBda_-O>L)$4o)l%(*1 z%7<~3prk0M9~7#Dsf@Xz$s0)P@4sg(Sr@OQ$SE4{`+Wz6t}JM8txo{&YckMboOrtr zURF&mxlchwtW594jdacBc9N159bp7;Ql`V)rle^?qV&yVNKekv06J5eFHi}|_Nd(4 z4$O6X@(GjWsGJj4YjLzh1!kF+9M)HI`7?cKBmkTCpKtEqvq(Ms?g>r(H&wqe?!TqP z_X*VG7U4k%W7$&AkYX`j*92?aN7spl7WdyTpgGb<&`j73rzGYkf1{|=IU7_Qp$LE2 z3P|!%NYyw73Ce@HJ7E8^>nUDY;G})Rc^%`r^TP4Iz2P@NR|SluK~E4#OH6NJjTT~5#Yf#w zMo3A67tv;HX85D-U%jooR!H;GjT!{x+C`MUAqZRoH@-V86MSKJxDgAfa63h`cX()^ z+^6YeYk1!yT-1dC+LjzFR5Pmr;3yAkm1(lt77O&H1SP1Z`Jy43B!nI{)T5f*&~feZ z#Bj9N&aWb-^K0B@u(PotMnk#gR$ZAZ)r zP&$5}6rdaPR9dEk9-z&sCc(V5cZDTdon5wwkp(b1=IlsFNIC486@LkXwXOw=V44UT6Nflcxdij$P+ zCP!bpI2g07>Fg2vnZtz5$?JcmraPuC@1XaN&&p1@(R29V(rZP{y0Z7@MS~grD`oQ* zot55PucX0q7P@DWX?q*S=OfBcM*0ezSAk?yLa|nBa(HY$X}pYVdQJ&^9;r{pu-Vo@OcXMFF-LS8I3qTOBON-9H_oyqa$9rZcU)?yYE2=(y z6N12xgdkkx)V##)Evy8uKsGDNMdMcNE_jT_7I6`5i895o}@6@FASd&Jee-5Du_8>$QqP#N$-$|-*XI)%jYfhSaM+a~Go5oBv zWyp)j5R$o+K7KjaCe|=rgAux);|mJ)mO#%&$@N=o*YGlerOt|S*)Ozc$*@e(o%9G_ zI@$@LjM;L1ugkUEu*L~~_2e01B>3hk^!Zqq)|V~H$6exmN4BSBrBOQ-1}+C@&IzA- zJ@dy$t-cM1S8w}uR$}OGV)er_#JMc;4aF*|cr1NhMs(6Osuw&igKkMlT-#nvQXZi* zXpF@^BS=eO`SnJp^rbD$XHC%-2?;U60dp!QN&FHP|M|+m5Y84&ig-O-Jn)-W#V1E} zrW9r;Y!|w61QWA|Jb6A`agNgdx$Zf$rEZ{8F#+6j-8u^5km1Rvv6o>@#th1=P0NCS z!Ab?c8xLR;Zwl(kLO3%bd)-4vVf!U8QER#h_Q5A02*AoarPPvD-Kex$4UFxo9J^$% z*EKAy#%Hsya^&-m*1!VUN(Vkk5_5NtY~AN0IETCftkR@3+W4$olDb zBvD;&>HQb#K>{w_{1GVUL!nP}NxItYe#ZM~O5u7jCXd7*haLJ43*L$N@FdfS256Ep z0WyxxufVVE)#mj{JryW^l?WRnR>geHhbEt+G3=pm$E`N54i?o1&`EN?OZb{8`TXfe zlyohin`Qs7Kd%FJOqcQjo#SV(?;l(i1&Qm1{=M-=Q!iKntHuK`hlqokq{X%%e|%1e zEkMeCx~i-i${JDjgQ?_%rwHVx@BJkvuawG-3wCeZ2SX|9TTk<|Qcy$z-ft$M24vQh z`|{EY6QxY?XAm>!!8s=A#RmmNqth7Y5?iez`D$TO8HwH%>Qr3A+6&OAauaIUM~{Kq zgk>Cfq+Wloo2-%8T zmkU9r44xZ(S^$@>51Xo$a;Z`gsb!12c?s^Ir}NU{0^Iqjm-GH$GzQ4`XVlDOOhDJM_|nqK{u{sn>%#`-ehWOpC3j}@+kd%%QzeF{b=ZCsq1SrP-FL6u zsc+XvV2%M*sJ8QZ5;<_yhnPb=30<1=HEzm*Y6-_}l5zuTTP(OvVpA%1W4rgC6Io+t z){Djkk}X_RuY44FoBCne@nS3{W;Y3_@7A_Y)rdLgZj^}F+_>l%3(r=xJWMuX3!M5F zOkARx@l*~fR}+fd^4FLRp8OfWXUt>#0y*<_pJTLSKYBB3tp#-jxW(lVP`%u`PdUU+ z_{5Y+$Ii8B%RPAFNz$PoB=Wi;>+?}`?fE>g$s0Y%zLzCBVGuhS;@+1YXu*Y_NQW+J zp@G7g#1HBbmbX7cCr^l#L7_(P*k78b$lTm4=k)}%stJB z3S%!T%CUohw2O;O3NpR@SBvoMQQ$yOS{I^={kL~LipLTZJU?&sy(Y714X4!Kgri&I zQw@1)tfY}DwByhT>h0oUrq;#1oB7E+BYO!*Y;C$7f3MliQLQ=TAQyjd8KTDO&{92G_ zRS7K+Y3PcS;^#CnYSHpT=&iDAV5%mnukqJ$suAqf7OWB(Sl~u2d3FTse)tmW3?^$m zy{;9BA1iO6jkpLi_wk;I!jb4k*bYJeGRc3xUJtFamK+ZIo}eARuxgo{z$MVqIsP(C;p;bZ3+d&FYl< zmY1OhWe~=NMzsCJpaEbXZ-{Fn^#2NGSGxXF7>sJPA^C{^&kD|BJ*VK_jgQ_I4^gd1 z8R7AsiXPeH-1(x|v3Eyw+Wq0nv`Fe;sEziXV=rDukm57M(7(T7ej%UK{FOp4DV)p|oiGz8)(-^gqave#5L8~k73pYVI4LXshu@4$cY~70nN?mY$ueJa*#?A7$#1@fyx6*6+R&7)Dd|#S)%K3Uzs@Dm?VB&%!!(euXmH??_b|F~iqi;LXk2G4b}8)ERrDPlw28 zD-s;*9c8%CyYRVIR`A69c|&@d-9zMzlA=q9z_UBqJ0SfZqn&e|o8`o_R{JAJj26zh5_>92zmC{HPIkYncft2iq49DPBgRBlEss`glC-wM{lMmvelssxorE>Sk-3s=M<9QPt zdUFjZ7vH>xQW8NR*i5WPEGsFQG~uPE#gXNF%n4;8dfI3m$=c}AUKzaFOT_W6(!y*g zwU;MnWr{uQ++$1;*djPZVowttIK@0iBuIafy@bfJIG?b35`ONe=8@jk%ek;pXD zDfBE+ZGY%6GofGq?Y;l_0LCrQRODUhCWj#al)};ta_U28sEt!QV8mm(e$*lzo%-Vy zpsd77V!-?r@FVue&e+Z;LhH8^@BQIe%y%FoznD0F5n9bdLIt1b;i0s6|6hX(+9R$7 z8)$oA1R*B4UTezE)hNcUlL@!bPjKJTN%5{fz6TYn_q;mLGn5<7DsE}lUGHE9q{F&b z?~Xx2NaYLDUYGbHw4a*B9N~{JBO04w#ZeCoN2(3fQKm7?FzT1Y`lBsL=A6D=_hI(P zk;O!ffsFym32WfhUwavwzDslkbuxQUR^nSa_3&`oRQUIS$qr&tzQxmnQEbd|CGm8% zbql>9O32+v(^kbZWs(14@125d?Yb@9v~AnAvC_6y+O{)S+O}=mwr$&3X*(--MOB>o z_xUQ~zo>I!U)0T<5p&*-=k0InqxaVCy{u~7c!|jHXNpm>E*IKp*=T{9X+%3I6!_d% zse8sCI(lr!Z7Cp>2I(oWGw4)o*$3`Xv~^f);n6yjsoBpk8DbB$xU(-WG@$RIv?W zp}lDNNKlb|ApX?qWM&Z8pKhuKhzRj$LnW9Z_;TAAGg1*)urGyFeK#2T4y#`ZKT1xE0C4AmfdnFI&Vf)0<+(2nH@+qRuRAI{=eHz#DmeGBB-e zVYGJSC=WuebT^{$I+ShTbI1>M@!Lej+_sQNV?KxcOs*$!zXuc{RTq2H|ZNo*G9+RpQ&`| zx`U;#k#7(Z@BeK;Q3>YcUpy0f3P4z|7(Kh$FrCurA!Up7f|3eV)DspNj#1dte!x6N z@plo~V_iqg&pxE9u$dIo@qSs+V)R>TQ=&1HNsK{5VggI>lZaF~d6Zk!ruj~_K!8EW zfM(g2Y%CML^@4JPj?VEGSOvU;B{@DP@66eiddSiVdgiP}u5H{wT5Fcnn9(Cvx}d8| zpcBHexH9|ZF_5OF#?yUOi9g{|Zm#}WFnqJ~g~P-!zPfg(XDwf5BU)<(hGZ3cW|V`^ z_G**YSYIx@VAaV+sMSV15tGfENs}PcWy!&N@GLcGnKCR)7;fleiPKV88=#Q`;6=pI z3C+Rqkw3+QyDU0y*>a?*Gw_NAiPq}0QyUohK*^16K?MleT(6-&_Ymr`18T-TgE#V^ zck^>C(nE|^@9!m%&H#p<(BvcT^MxuxPDOPE{_|L8TW*)EuH7c><#RdyaBy0gRvRFh zVlT z%#vR6tG86v88-kU_jn2y3N%rRmJ$aZ$J4<7m+l}75(8k#|J&E&7!QHKbSNoaNPhUO~i zBnvbi2ixNn3d33n1mpsXVVl&t-*Ik{z!qgySMOSi;uTOGDMs5&e(dRi7;wE8P?-;W zugL4X_o`ap8R|gXcon3oJ`(S0%{YCKK}`==4;=eM0-9M%q%|%MuVX(uwbbMrw(>*j zE4u0Gx@NNLx=Fz!@L?O2fVOVc@pTVw**qtv)6(dgZM5!4NST^AXP$z#D5luY*24Ql zEn|6{g=ytgxRs2UdvfR69zHE~Wt%I^C&X{mjv>x6JHVSdkKXd~THvn?J@kX3R8-rd z9v4ri1>US&Q>7>Otis<3Ch(sPt@8W#YJH-QEn!IQ1L)~H?lyn%<`Fd>TgQm zZZdt9o3bw1QJ*m`;`3Ek0$N=O=i#YQdBpZ|xTIIo^afGHtdb4_%2u6fE)$PCFAlu( zqfGC24OY7juVJ4E(w55l5juEFzc8aunh(Zr}K6tjTkfEU;K2PylF8`8l$H%aMeUvGumIi@zvyvW*gHh^L17V1ayucbU8pVwI8{pPE(n>hNqm(PN-Nn=4 zMQDWNaY<2kKN{~k=@_Yr0+{!i8sv>eT3Imse$o$V?Gnmw9k*ZtWXs`G9`X^gfSj9K zW?X%dQ2chXr+Xb`0u8c_@ba{0OY;6j?+=bD+AR~G{0cdb;FYo*y<#P^MhH{RNjJ(( zUmnrtB|+grRjEdl`?!meaW7of;dDUsM)|gJKJ!_J@op-A&Ld=!^6{#>18k7{!&|Ec zgRdG5U!CH-pc)5KS*47xInwJSqs49Giq4jq8G4fb?4!|s+tB42YN9EAv02bi4IwgRl&`|ZVEWOcJ2ec;BEs*{n5f#E4p6#{#e~wT1}%6(i4ll* zSX?2V!%_BR6{(qF36)_r?!}xfyke?F(!d?x3q!SG?iDUj%CHXvD+K-EwwF}G;Tb2a zdS)G}^+NuL_Wc+8$iK=dY7C+MflML!y9YT69IwNG$P>ANa{Y3*sOI{M81WeBV)f+K zx@;@JQ&QK0Vt`-N;9Ef%O47gu7ko~*Tfl|aWBAQQ&M!dgPQ}xv5F5YDKla%X{mX1q z(>}$+y=(~S@2JIYPS3dbO6{j=@(N$jNKu-|2m4~cb_(eQRJW&wqR*np13n$$sTLPK zN^8ZgnqAJ5iOS$u!xMg4?T92P@Ldm85o?_ub&JIaMN@h{1@D+zTQVpxL{GY3JA{;6i8u z8X2jBDn8&aT=-!hm-%b{rcJ%o+D|;!=eNmD$akF>lZZ1x^Uhn_Axb?GOZR?M`XN_j zOh$J%?<)Szuz6<^_x$57X!m4UXOnJX&R1N_UQK8$5nX7`oo|(R?e0rmw*r$R_bct! zHWPSQ;R1$iMVa*PXuah!fBK#xy6zO-_6TxRV#h;Y5UwB%$7c-9Hu7S_i`U)8y^yKV z@O(Eql+ue|_$k7tC93K;Sh)lhVK||e6HfeRU4vnQ$>mKvSH1=bx}N5rloe5WMRS9$ zcr~BAf9X`A(igjzrJ&Tuk3aTN#!Mz-^W${+=&3-WRZhC+VFI+aNz0Jm#ztNo310ay zQ6t!GCR(q=HhzNK9591fThH^w@;_fdaF)_x3u{j{>C;g0$0Be~4%qEUB{5PSgN9E1VazPL@l|K8i(Knodwy&y6>0)O}!(L_`PZIw_Y)CU~Pu` zv+JziabW1r(+lzeMmJ_w-Gyfjkx7}`2OXXu3b_WS3^#S}6$a=w7hh+yMC6x5U;LRZ z3eJWT6aXDT!EZhDAaS;Od0h4;?0-FhUVnDc-ild!od#5%xO2M`pU}fkLzaJ%B?FGC zXo1>lu?*LJCB8Fd66xovmyG{#CwGMw#TDP&cGRH%lR3&#fVOLPID#^s5`O>jKx3Sl z?|#y(iA8zcZldN7t1Epi1f)h^z{3|mMlj2+c^Qwb+}1vpbCX-mJ}ncY&K1;xUA=A z?b~dGUPP*`qenjTt&tw4Va#q&X-d#-&W5-j~g?Pf3o_ zEHZL`Qn_qOXH9*mu*5u{I&fQ`f@Ep~hR=G zS0xK;II&%v)2o!*^F+rSwTC_c@Iv|&MXUZ|ZqgycV2P1XtN=_J96%XpySRRnfxklw z3ShJGddJcM(P6Y8&QOmrlx7g#EqO$^g5I~2zSuHO!rVI#6(+!cCxRWp(F`wDPe zQ78qsx7FCP^%uqen%+3U1zSO~!@n>X5@~HT+NCh5!eh{4za|AXr-lgKtF!W=Dwb!-RO2=}G z_jhK)4By{1Q+`uk%TJEqtg#S{Wj*A|!oP&&f1~N;>sQhf(GUY7prH`&@5&1a2$*3Y z-GT%Lj|0)+=J0uye=Kf@AsiJ@yp)WAK!N6J=K+{v;6TYUgJ_szn*p`5!cGFD%Y&eR`UCs& z>2XX#=7Kx=6LseC0Q^{X0DO}Jau6aStm>wBf_|g zII|Keu>wE<0-lOYEc?En77U<;dyj{+2!_x<}4 z#{awS)OHi-ZKmr~h>!t4#^){1=i|k(0D%PP>YHEe3-jO_IOriN%Fm?T^P9GJ$JjX# z83{f8)L;)u#oL;I5~Q4^4X%Fl-^F+_w25Z}(W)act{59it&UpgzzT3MvQn_8F4A!wLv8>1SNW3! zFg69EWc{N%M>OlYP4ZrSYF9sLp~dTZ>25jO`WM1X=JvoCz%|7&Mpj)b0^A`k+RXS? z)%-1$O71L5m?Mql*)X}TJ1f6)@a$pTLH=apmkiL>u7?=k)m!HcLZwq%w=Z%Mex0bp zpuqL6#&5jiSJv@!W&aKd6X$mI-H_#j#1o*zm-;WaEC{NtMYBm@Hl*y$Su=7|Q}6MT zL?a5BZmFZ2;{oq%=*rl*Zl>K|EU(p4(;K)NR5ZY+{tpHw?-DK+#kYvl0%=@L$Q@aT z>_ie5)jhKd#;9r!0EG+8UR#L_dH}ZF-ZP2$7;7lu=3$D~$aDqyX&6*Y&aEx_#S^q+ zDYt~rqDdLqRqDV$vBe+xo#uvnQNsBTVU4>A|g%v%Jv$zpvZfA(aM$}-OeAY=}(?l!lmpgjyGh(U8d%LZgr zDT;py zybXbZF|^n^h9e#G!s*fcY~^rruwAri>9(&2%20|G8%vRILfeK^A2uT*z$-VkkpauRKBhxXt{cV%NhZk((QoB|3+xi6;RBdcn-mP#TpIc& zg*f7IqzKojO77NeF@Z((Jayk0(DUq5it1qq*0`Zb4$LXg1{aR6dc21*?{Gbg&7>t? z?WCdCe#Lw}@Vd1IT~2T<<00B6m7#+FY}!fV;%IqM#W0Y)6FK|zI1Xu^L@aH`s4D7r zCep0@8Px$M7O$mn=vZ!HSCqTpO^0y~y#pvh6YWpP%gi+{$Be60n^OwsIn{ahvt}uj zPr)EM9=!)KnkADd~Jq;@lq2c<<|x*e{E(?(_w5 z49?K#I_9clloy+(M_;`5sEY!2wD5WsR3nLn8v--7O008PRU5&()!Tfc7hHaX8C3}9 zj}~2)y|>CMa>}<5u1k~lx$JV?N`dU)QV)6P5yIL_`f-5;kud$d;sq0CC`1kWw{8JS zm=VOJw(*bN)akXvIMj+9p&H~#^m$~iR`fMdgTWzasxG`L zpX<)7;~NiihIJs^Z#37(>EPw76_k(Vtus)fPIXc00*h_OWTOM#9Y!L|h>8gCS&Dpg z&4GbECcuU(c5=ku=}M zZacdjH*DP37+dm)^X&0lWQL-?`!hI0lV*s}G|DzXc+Re9_jdGdfMJY}P5W%&q02fA zd{G9dYDAZXX;C@+)udsOvLKZPGw+e?0AEdX z7?R-m5aow)M9Ps>sM@`<%7WxeI=B2(6qes(fuoXFbH!bv##ffB<;eYNCKOsqfFnr* zQzCms_aB#|vDN;WQj$)`_IX{uRXH&W`r16fV{(~_O_JqoURsJQb|k}@tskuFD(D@) zkTElCUqB~AZVy&-?aW?}>{7HkcdjA#F1AZG?Q)I!^0=&W2z#ZD+EZi07lA zj?Th_$ibe$Wf^wqBYB59vTHa01p9F|LSEG)Y9!QR?y;S*L{S?nQi)Rbl+97%FR|E~ zfQgm*yFQCUmc@^@aoX4XpqOm}xsxkltkhboX`nf@eS7WI?s28%3X!B+q|`1(o=h03 zz|08m{abCiylNSD$rbA!sT}C-#l8m5q9+Jc^=%Mpa@=rL&gm~=s;Q>WL8%w;t2xz& zp1*)=DQD{`u1!iZ`g^evIw9TPBm)92yJiRGtG0UEr7?itql8L~3IOilXlV$>e;5O@ zwvf-o8K1Z}Qke6RzxZZk1JZtG&8hdQf)}lf2-s9i%)w#R1xJ~SUiwsTWUw^$TYPg( zpLQ!T^$$tcn`T{K%d(rKb>uiWYFegX-Jb5{u_s$jUHfU-xeqKiq%45Ly=V+k5naff z4KTQ(?Q?VbKrw}DqF)iQ(qDe;8gT6wio5YRS*wX)n&*Z_uNo=|?y4Uyp|qM))gzFD ze7d5O#Yu`k`^v+YJcz$SDGyr!Zh(Cs795B41b!n);n}biNo{4_a<7iOH|~5C7;@w= zu$(%y8mSAguY$6iwaW<1GaY~BVzCbeyGLY@FTEjvAsXXWG;aYoh#+KvM%lzqhnDR>G{9&PDsOt= zFfV84UYo>4f)q)JL;YQ;>{Q-!{{fRE%`|w&cji{e+az>jo$;*do(^Yon0U|BTvo_> zJT=ZGzz%+fhw53qOv=jotILgd`eJbK#0Y#OYEJw(d~}^pZ>G+rZxUB(0>8RvFCM0h~{2YR>u`QJvw+k)cX#N(;IqND7|Tmebfp)!-tODmifcd4;d9{V>17 z?kPp8cp3l0L8Cf+7DE7K*@UKUTRK4W85-hhdn>SKKq7j6<{@b*`IDt3h`XRfX_s>M zmJmZ>3;YT*=yALA@cFi&I_iG%*W7Pj9DOrBJg_K3y`RgHY3&mV=aU8No2@(K`QJLF z0z~tS>Ww)WOedtE@6x|uFndG)jPKOA%DhMgos&;2MhDABk%3Yhz_uw=N=tn}(EPqwz{fTcx#&nu!LFdB zZ&aC~LVi`>YU&hqXK4b`q9dneZ4JAg2UU=Ba@cB55;on|Z+>Wt`zI6{i5`d^&#@=o zc^kJ2NZkoa`%R-bJ=*YKhdt3kKM`N=wIH>3m?}t7S`~Q3k4eWf0d@j`k)(r8Gg>?U zsgwc+o5HeXrFWZaFudmb=`qmYFxFWz4{!s+NySd9cZ2V;^~pyUV0~rey9~8Rs?$hE zm|6pIs?0MvA{tGQA`ytnam&-Y!iKxr60zYdc<5kW2x6P&jhBLw7{{fjlm3>U z;|T+fTt;3lezkThVc}+l_IVzwi}aVgUFv*nKr0;(U%xR0Ol{;}1qw#tQev=N!l#pq zeCCY;?jDL~2PKop21DHPg6yJ>Z2)3S-S_c0d(gJ^TDWu%5_hd=ah2ji<0%PMxrJ3W z@I2GXj)`m{@;n}qy7j|f-s6ng{Q_TbNgHrUxd!*TJGC;FcWoNNd%{118&or#H?iud zbtoeVD8kjmh?6qv1>;rFK-W{791s%=NH_*Tu~HMDC-M_3Ty4m?Mux9xB{n~*RKz5{ zk0~e;f;u1dn;~EPNe4&gj!ap%+?>#uV5VNd!h>&KMN3wiN(86u&Km&5G)y*+`Pk$?XH#H5qu?g z$$3_9kzh%-R0V%1-Hqnl@gfu+Zf!BaC^<_J!CxL2w3k^9Omq^2HMqglm{F`^M6XcZ zh|pD+L+slXa%mDl6LJ_{!WA1@G%3cC=qE*X@;~A5$^jy|*EsG}B)37iJ(Mv9fRd{+ z;GOOld%GXXZpqlX`s<*K{<06=u>ne>7$Ofhnn8g;GVr|HRIUckOAfm53%s^-;L0Z4FR}%L)iGu-&}Rl zCf|tyUzsxpHJ-|NcIc>a&}|&`;Ec)9G~Svu*baqy6LoW25py*tDe*rVij`F=(vW$ueucKvu z!>K_Z#wTUQiBjkrpPd*+pG7@0wP&PZ(_hu1((leK?lzq>S8b<2bx@xXcf|v574W1P z$^|1x07y~q+Meh%$JLUY{9Q0;v?dz89qJVf+3Q~2a3RBh@}UPi3Cd_?eiQG#YqyHV#)a{$<0 z=tr;*6T67#ydv~R{;RGHR__SeX*w zX!9U&&qQ|zR=Rg{F|dpVUdl5Glp)vCQjV!tKzTG9v#C#kDacURQ#OO+DoKyqwv)m( zlHtl$-eCdam@w@Af8uw(nN;xfCl)HL$zP83bu7bXfg)|P9>BfTgZ}X6HzeT^v(!~) z-`eDi(lsR?BZ$!dk*O2&&s01w)TvEElQROLk;FKb{MPV!pAN@a4MP}26rw#@Ejd30 zT7$$Be+5LVV!d`U*Ycmazi@P}$~~xZQgyJ}Pgt^kKVNu(;r5*evG;R^ z@pgi|e!b>!#*RZ%j10qTTR@0)FsbAlu0<3!+j~+mst=5<3~qH7rI~aX-5rVSm9rwk z2U(2_6h?wz-!EC>t%yEqcrb=?25c9^i1 zI&6Wt=t@c!T=$imL)Nqm#?bSyUm3?-m7zDdI^DmLc<#cv#Ro(2UDcb1QGF-UKL#k;lMmHmP$9kVML_p;I{W1);PS~kn!>yErb)4RN! zWE0>)U_RZ|MjgGgRgL5!9Fg?)@o>?8yo1FB-Zyd>1%wc-pZg=ew5hiW>|)3~mOO3A zy9(XBY7)ua@tV-J{>BUvMS?fl&e^&H!c@vq-pB;7Wgn7S89dY*FE^`GLcDL%4k$X& zwLJQMm&74vhJ_LI+(l0XDNfl$M>bV=9yKBUGeFb{XkU>_JX*@vdOQ^F)v-QFO1+Si z!`rpyKBUP228aer*I7seQ`yPfk1azhp`PABx%H^CQ&I9e;(c>9h z5?@HY1Za;&Bw^5yRtl^xZ3ovCeRpVAnga7ngLX*g4Up>Jv za3#UIs*lQR%3**9sX*%1HCcm77tjL(7v1E9*I87{m`p6Tn|wgcL<9*i}@15J{l#w#tRPJ2{v{QMyArNMb!CD{8NdVa4nXnn!?W4Y~leOO3Xu zrzAI}wHgk>hA5{l0Kr?==S#39)3VB&dS(mBf5GCKVnQS>-*6v-w_$Y4EfCr1GH;$|!L(y%s z=pcTxs#)^)+;jI*v>BPKAk<5sjL%xfU*w3K>lQ<_~xHHN0dAmsNAi zQdy&3kUG^oYS(g}9d=FLDIOti!i1~`NXJS#Am17S6<}RpZAtf8^&c#abMUU^CMcS3 zEEV56PkVUmc!$|LFWMD9-5&P7py^e?z7c6KmOdTp3*x0MMNkik4(C=$aKR7nOXv)! zz;ZBd=SL_^!@(*eR{IiE6~=c)TlHAantCsb3Zj9aIr44nK0KyhnWH zX7S47Ys&M%Ld)zG0N-A!}HJT*`T9Qf*@FZ}@pbIRXxw^XEAk@d%&8I`BwZGTxg?BJ7@+ zuxwz0Ze-pX^zIVD!rQOlnkhH4xsA?#lT4bP!V7BCw(K)8!n?osImhW# zVTDBrCy0EkD%WFwATv1j(cW;l6MRyikc(YkzK*j_*A0r0D#3Hny@FTw>I?E_PszeG z8A>K^?~l8#n3$YY&xRX;!Bb-6#BrHt@-}mRuP5@;nXyq+vPRWrUrY4t3fyjjX{N$J zUrKtuX!;NraYi@A3RMSH9xO56Z z=aksT@7s)Znry#ab=JjFvF$D!f+?T+O3y2|$y+jbR|RYT_P>ot+jg|6jX)lo6N`gg zDmx4tKC0n_hwK)bWYE^d2Y)L2{1}ENe0qrj%ZHER;oayAfZW$##^*w|KP&iAmF%!n zhsssh*KqeuDCn3T^VJlVqRdTDCxA@3c#<@NR8ls41kBF`oriJ38lkiy8vaVNVxp1| zPv5|gNJ?A(aC6J_@7>%Iu(L4zi-C}}N}tU>14`!!b!Uj=rJn&ei60c<8e|-Yl_qNA zIyFf#HY5^?f8*!-;|po4l?Omn&d3b&lirngXSGM^i&b;B*kYNFQ}`l zx{_9O@l|#dr3~j}cFwBh28!iE-Mdp#)p@x`?V*Y`4qXxE@12B3_ZkbiKE4ZYL+_aI zgR7d|f~_JhCl%g(0^9N{J&B!ZW=*3Okz=$^rpq>qb8<2~&XeZa%85qK{$WmxXT?=F zgqE7~`pd^!+(l5q`g*E%@5Anh0$z9;9iL2YN3ErIvecQimnqroj-N0*Pl#c9YxDJT zZ`0?N`HRIj2QFL~BL+Mgv`Q9_jk!0UZ9G_PpTD=`Yo3`f2{tt1YIBLlp6h7ETg%sE zsgB)x_dL2F#dO~pQf5Oo{PM_BM@pVSR2m?Tm>M*OD6K=yzGL!A`WDdoHul1x5drQr zG_r}*zi}p!rO7Cz5Jz70GT&}t4klxiB2#i+fXRER{KzxG5%+08cvcgn zeM#-}2(a-7@EpKXT$@_>6;nn0sfC({>+AOw_o~=glN!zwn%mo=A-F$#LDf&nxAS z^WMA9kDo|b=8$K-@tjSbNYHy_J6+u;I^>inzwi{zpHOCLT~B`AZPDY}BJ0fmZBWx% zU+xaQYIBCi&2BAcTS0$a%&Z;v+En8EaMgQ=2mc26HCg`qA8`2(S1nru3n(5Q0(#LO z8wF#BpKmLDCu3n_Lt7)`|2fU@Uly0x|BK82#pVA4T>jXU8~g(XKy9q$V!SjwB%u5%Tr^h>cvS%8MYAy))T)3+?#)*O_}x zrKJV=ada(%*EOZPG2!C*3T12SNZZ}qiknAMbIpQ>m%nbMo4UnC?|F@Er}6P-cQm7! zM~8~L-kS{bU7^L#pYP&p>nkf!MhTj4P51mjz6BZX&Vv^R_s9M5_}3GvQR2hM(@DE! zPO95sCb!;}s``pvq$5k0r2c}!W}Z#OS9!=~9vxD=iZiFy&Z#=v6<=)UCl7q{T4M;E z2Ho1j6mE9NR{{&4@Ip#=z1Nm^?R(Aq=G@ayaiRSwE>)_P_26oAQ{SDIG#OtU2T}K5 z?)B319XIXc)%7O})s3IkpS5%G_o$j^Lsa$FkC)O8IraRJn~V0ZIPgUWNx(4stbn2% zzjD(7h2Kz;f!6}$LXL6(EF!dlqxkj@DY_9j`wF*fAy_a0h^GVtl;_Q=`t`K| zF$n#U)_#HMH>fpqijx4sg~TW`CDAi;nu}n_9M%#I+=~QafFHmt#6}KwJjaO**@Lk# z;(QJ5XweeWXczhg}T!>>Vxez1zkBy@Zbp&SHEu zw&~D0)32rz6X`AKmT^-x?Kx?G^8j?eX(UX}nPe%)-bd{eTZx{O(L?J6!%Yx}(6?k! zio#61EJb-X`8YeEL$VBR#&4#^1!!gSZy&EE;>SGGOOeWr)QrC_7o7JQ$xG3~Zpv~W zeHM66B#d{O$PG0zd(Y`aK0V~O)kWUMJO#bi^%Ep5wFdHU1ZPXz_lw1>SP_1Wz=PwV z4JpJ=aQn-E!G8dN_1^}7^}iwjGvx15UO4A2{e50FAq58?PLnvp-FlIVU#nkQu9wKj zF`16wl^axlu_o=Ji`8(gxTv@nt(SC%YIzGq1nbM`LjGd&P7G^<#kb^~^s!|;&5BHr zW^}g=+|T;N_lKCh&8s!nY{0vGi==U{>ByE81VIfKEQPB)?LxJ$<+w%}FXVuADs1!1 zB}@E4*HKwhdGcIOYTjwWXVY-#Hkio&Ez(@ooh5Ol^b``8!9|yIkmuCt;49Ec)(Zg+ zp^RJyjszf%$TxHdfCj(sKZwB#sS}|LnF;{M`WyjHhW&Q3S-^J;nF3Lf zA$v@azqW!MTljRYt@w0YUu{=(v-T|fSl}=f9h{El4;%-(=lcn=U)`csHFNX&NEM`= ztM3))w(?_@8wfgkH~n8WM+OCCFtO{C zJENIzlGud=dzkowH>mEr6*E0Le|0`_+?GWbzA;~2LwOmV7m=96K;r|;g%X3@B>sT} zg{6FqhgzTCbhJ~WT-xKjd0mp-P50n!HKp~})d1^hgz`R9zmXdGIrbnuPFNrFTrWlU zyD4#f^bHW+#{0+UUg{5|dpS|GP8*m%|$rk{31ivGS?zcnS(Loo)kOwoY<}CF2xZsK8>weZ)O)KCg*i z#RDQHR98tEcns^F7_I^t+qk~h%aHLn%|D8l;oqG20U%+##O!VPKLDVAax0nY+W7AP z!2J&ZB-?R2udpVH`D5IPy}Wa15*}ze>+35nUK^>cdn|jb8V@~(l11vmtu(i~5;jXN z;ECCtwfII-=5NOV!EVz5h;azyWd`xY0SH81P!fQD1I&UL;Q&~KZURI7+B2Z!iRJo5 zq)i9GiV09CB?Pb}Z&uN}s|A=!$XiV338v4u%Gf?i;uj4PxyX#fz|wvyf+1^2N8E2G z3Yhxy*q@Jr9N=_@8y&C%V`ah%o*)5m#-6tJ()t0Qy5pneZ_Tt_(=V(L7)s7|hqGHw z16^}{gc;9H(F@wy+1+@GVy=}}ij-ywk|i1ldWIGPK6VrjTgSoqXHu=VZq8*QuN@rc z!fQ>0tM~RW?aa4Sj#5fPq2>4$d$8_16Y*2E;SoDc<88HY#~Ad`6+Cjjr8s4u;m_(> z_F^4LgQwOT#+yJ6K>)e36#3a$Mf$Q_+9_V}e=PvnO%UGZm>=_0FGZ$(^tj+XPDmf~ z<~LG*cT=VVbVb2>CW&5>!ZLIpCh~QWzSdfWTPhTE-nMa3xYV4;>S*vzG$XevZ#qowILDD zC&77p{(DROulm}Gyxi)^1nEa#Tf7}_qMF2iZ8r67X)mLkB$S2d4ks4ln7)%g&9e?I z!(8xf8D+F%;nBD&p^rG4i!MKtSZ`OXE7ihx_%QpB4V58#*7K{4VZ#m~Pxq{Usw!|zmoDKUcqso}Sxu~VusP$y%jlG7`-g}~^wtv{t<)OY0h|AC< z&D^4vo1xMeo7F`s?4oS|kqOBJwb2H)4I!e^z$Mq!awt^m+1E-lq!pSCg8rd+kdOG; zrCBK@NQ(&%@9DV8&kBL2IWVIkjqxL0%JU5gWW9;J!Q#lr<*<`peQdk9SQacnnSUff zwvU7#F2kp1nEv1xa{CP9cewjWLG5=(Ae4rF+5xT1zTeEpPrgY9>xi7AFxA&CfZ-f0-RA@Qr zi`;*Mt0)I5E6yuqC&)z%%R5I3#E}rnfygnJ{vjxom_Yv!$$6VcI93YhE%*WBg*1P5 zrD#7NcCXxjA}W!Cjryao(`KT=e-!q`k10tGc9EwIim`}5OuL)w$B#<(ng$=vsR#5) z-#M0u_>tCkmf23H_l2fEy86z2zHTN#)-(HI^G8j4W;g!)uzn&@^7Ge^*8UHn{mxUg zc|wWGCs+31E@`^L?bze_EH$zb==$(>j(Sqv0H5z+wIvinUR^%*$ZL~GI8d3)>W6N&K z*;{$pe^(0|{q1xM#~{F73|*mm3ku75x{E&fRs|cr$`$Od@#zwitaeO1yQT~i(qJz z8KE`}G<%Io%NSaM7+N^;{fGLP(9p=o{{tFGvILZ<)?e^Jcoz0sL+4niB=-smx2`MN zjrVqb|EU#)r~~{zwRK9?md0tKV0*R^QS@ye$KwI$a2kFIMvd(YG5NO^@K5iFXiy!( zt(H6uKx$tw#}2PG8;~2G>8J4|U@}W}iiHBFPNJ;V>!|UUV;Xw~C*(>GmcHK|8Sw-9 zE{U7ZT@u$+1_x4_Z?ju*)>^11(J2bkP7tG8=)9~Kvdk1hR@}5OkGx$Nz!V9Q9Ee;a zLDwwQ;Vvkfk(`f(1aqlRE;J`kPLOL$n@X0;K3npq?R4f?Aee*Adf%oH_rr^qjq<)@ zLE=nQekH}J0{V4y&MQyZhNqrq0_@Aehhui*OFB7i&#^=ZpWL70`$FOz@}Kakv%wRI z8L#Yz{u2r69P+B42Gsd|;ZF~%>&bn-ZANL_D_e2zK2b8K#L13HS$C{>@Nj0#1hiTv=pn zH@FZw|Ekr70G#!)@{=gi!2lN;0dqb8%iP>lM-LuCh8hbs!@oYqG+1U>#|cF)*|l+V z;{?0rc=Jtr_V`3I-;0Fn-nR0~X=k$TG>7b8Rd2bTXyeH37+x6qX!Clb@|So$W614y zyPM$;?>%sm@<(oMw8gAc#v}-O;tpr}^X-38esTYG8F3{wojKXNWQk-BJ1p6INRH>z zLWe~0@%Lx@L@qg~#qWW76p>8xeOzUK#~tQCyN5<)?1}fl9QJO%L7dT3qo94u)ciwc$g<_Pp0 z;O&-UI==lH_K{o~j*(sIoQX!c=~aTS(9x7Tj?%BR*P!fO$8LV9Gm?H8dEN7RHTv0O zU6dw8V%@qmnJtx!gD;fCcx8kj<_JOv=^1I&`+ruTm)ZC<{_F-B`IQTHa*{d~sK zF%Fe8YxIM{uWN>BP<1=7GHG*CfaU&jfU!?_;ht|u;Vw3Arbt`0*-G7}-%*d7R!L6o z({%%Zi)pw6-?vAo-ozMIv2e7;UxRcWuBth`YES(v+3UsZMdIAnB|B(D+tb-hF=~&% zj_fLZA7j#&!R^Q=eO^01^{}sfcTavjt336ztbK1Af4_6R^N(J9=hlA*On@{Pu;T2=5MUB;cQw$e5B= z4-DO>|Hj!j#)#HvOSWwrr)}G|ZQHi()3$A$wr%^gZQIlLy<~Fl%s0u){MpH7_Mb{> zt*W(Z$dTfxXMXRNxeIwn?QGJplNlNBaMYz%TN``Ca;p<_BR;l({5q>rL zQiVEYwxJ0`8I3;@zlc8#pgI7Y|1&lK9{&yv7Qk6~N{c&y6#zC64uA}-yhddRAU`ZM zFdV=Vkzs{Mr~vE$3%7d`j`8@>XKOd2wF8eC9d6>9>Ar2vLoCCN2^PdXtc`mtx54DB>XT5^Bi%3PxRg z*!5eWff!1R=(Nma{TJ!<5|+_8Y^89HJ{*Z73VwtL?hs`f*lnOwUPsCWD0vm?NLeAv z$ZBP}kOWx88f8+?PTC#MNYeJ5uKj{lEPD8B6-q1S85Qgk)=~OKrlD$vw4pi`CPHFF zB|lmkHlW(ug&ug8hp4!Impvf<9znaA2Vp8YcjS6aZeTMm^-)~yayfR9$gK8h zF{fibwjnpu$k{EmBjvejg?a=tmpdI4ks!Jw*V;?Qtt?#`@k0a$RVJeMQg|AsLdYgOY z*Sy>#VdftjD$SLdZmxb(Q#92xBl}x{VEc21eUu$exY=KNnL#G|b}YIKcKBiwMKhqc zl{h!TPLchm<=2OgtL2NQBHfJz(7 z{>ZvP@~zN-u-X+U^~BUKkhKAskcPDarg-}-qd3~2JVC=GQAuZ5w@FW)(JRAFartcO zf>Aerg<(Deol)`RG8p4DkVJox;(lpUoHX_6NqP?BFgT=~P>>ByjZhfa<3~=VDIE|0(b}Pd`t(`axq_* z%tS$R(P6*#< zkOs{(j6F_$2;U$BFhL_fal%bFt+Yv;j@04%WB9lj)h52J;?+-le}voB>*7D!*=a9 zjD%`s1^BGdhv~=B+T>K+adz(FX69p%7lrP{YIf-O+uDrJ_2$Nbjtl2sSI@hvuw4i%T_k1P~T*D_wk`uGm-mVWO_EI7&0slF}`BT9DQ zeptzL@%MkF@nhd{Wm;Ko4>R(RdM@Z$b>0aUyOQQXBb%q&i9E5phN|SKrz7EIwBQ@X zZ^6cL<_l~qEWQfdT%1V>J)SvapIU9;vs-kdhN84^N_P`cwmqUs^P7bhx}(6L)xgI2qWoL99nXAK&i>1bGhATc5e_*;efiGIsR4$#W8XVtLFxAI4N zQZV7T2EYUa0%M+XQiT^Z7M#uarZq`n8d#OH6M?|BbpwWSm*3;0JuR(4rM-(w?j$)y z+OWMRqWU!PZ6Qiw#B3{h_SIft})947XY?&(~-q!}`m7 zF{_C<%`V$^5jotQVHG+G+dCH!>LW1SR)&v)6ZZ9cFY+ubsbg|>-*M;`0)rQ1BWCj@fUPn#qwAYxVTg#LnJn_*xD`V-?x z+0ZUgyNl`cF%a`E%7@L{7t%R1kb#@=LMO1xkaq>dW$*WMNO#&J@d;lJkKk0=BS;zM zJ?@W!bV>pAfK)nIs=K%5mZc$$l>$1nCiZ3X5{;bY(C^Lp?z{z!HJ>zt`c=~CdvhP| z=yW4Bd}#S)bwbzY7nAOsj9S_jdWI{v#VNR4r3>JiB_uhL1%e6@3wnO8fRd!WQB|>KS>f8W zXg>?d0QsQ=fPN9j-}L;VhKUG=geOMKurF4?gOVjCLPQsKL^@3qpH++=g{avPLnz)+ zM4HkEP>1A~8xGFLE$_1|ihzQMVkV=H9YgTtFkqJs2|lGKwI2&&CzeE*=Gc(x7m`9Y%cM&kzg1K8X&EL|H9PErCKmtF|Li zCV`VE&hXpH9&%%WA0X^F1Cj71H7G6%IZe>qUNR_58yd(@5d?5W!Y0BwLy?ZqJX_IOsC!F3 z%iku#OH8Ps_WZgL1Sgn~4YozLlnx^ip9=zw5;6{$d_6cjc)B=Wj?UHq`T4{u^^~y0 zqTY(qGKVBuF_C8Sdm!jZ^^YWFP7EJTZJrc9Gzw{uZ>E>A>!UStKgqGbQ(E_{vTnIN z$%!P);jOsSm)EImYR3R(Hvnxq1IQ6zcz7VZ1fvCb{0ghU;!VKq952_eOZcI=d9mP< z^?h-cy%C?nqT01#M z<+9z-Z-(!s*e(vpZ_HKm!NbYo*KOE#*@AH8i4MNlYLKYI8S)X^-=R(#kodXVdV%g!aAP3kX z1+1|vd#$s9evo_l$_iK{X#)RNiK{$irg3Op+IFsZAh_ zpLd`i)$0xNA%F96$})`iZ-mV1`D%b7!?cC2q=A5 zYv!Dlr>|Wkk&eb(=+rJAMeSD*742ILsxyDctRZVIF#(C?p3ir}=aOK*GAoN@UG?17 z%Y;>B0!4d(1p`LE zP9jN~JV(bZ%T|EGQgC1`(-DZ$6QtL0g>Fo1e91I*3Z&=&{+uVH@yu=&N@G1ZwVmzE zKAHz|0bS-_Wv6s5Ua6>+j}hurb{De@akdHC72_uuGHqk3rV+(_ zQp&bdd%^aJ8@A4yoaTWYG(#1liV0Xdrr~MWDvwulvtjvm2Q5Pb8G=gmN%oj&IIu9m z`tNRf?qugfPMY?=3g+3%_IXP7krnUSU0CI%P4~P7OJ?;vg#-Fzxz(xZxvFWLArb&= z4|eeEgMXk}EiE)+hE_NVo8D>;u5O1tyu9_OBR_`F^b}EEpJfcvxRmJQBmn0h|5~|} zo;q68ny%r5XH=J%G^c%)LBX4WEtRr0yUILGk%kytEA<~z*jg)Y82O5w58$r7JDPC& z7#-vTb%gt4Yb9X36irM|r#AhCD2cC-tqD#I;hw7fZHQz4?@QbRRBX)TZq zs5w~$JOgVWt-q)UK&uI7KZV~{FA(~!W{^s*eHDKoe`E%K0RL?Ufhg2vC(C|#?0Y{z zOg(LQt>h-v)xsez8DnDKb6}9*mm11XL_>a>4Qd7zadjzrjSnXo2CW+x%Em=w>1@*7&c$|9V{$Me%Ou#SX zNcs3bG{-B)@9p5d0NNROB!@`@)2yCeo^LFhJW(#qGOmu(vH@&ts9~At(M|@A@z3mS zlHM7DAQyKiP}e4rf@-D4$X7O!fNplB%I@GD$_~#;<(*;Wo?8qnoJczj@%&)DB;JG^ z?oc|vX59hv{2BJu0CcQD2+Run0Rz#*VAxZ|0i>lsSNtng4SU-JfY8qlvPnt+caZdV zb%yRwNb%WuJOQ#$2M<{I_&f!&-kw@#lEgFe{{c6COiMlXyw8y;@S>vbO*sCIkiG z0>Tprw4(qp135q$n(7Bt4)%8EoRt9irv#%4|~K+puwdFn%GYx zjQ<=Kse+t}buqK3V$%EC93o(*V`Raj%uinp0f~X&_zNvQQGAFI0F>)*QGhogb`3|F zU2_co$k!2&|5Bqv1=!T>)ex@U$&yOcj||bR+0o7m2*NE?huJVX)T9@-7X0~~=8j}Q zRv)v9C6v&CIJ{7C7S_wo_!<)bq(<7ZK!71r0DH2ujKRYhh0}ym@~XLsWki1qXHzJE z0}S2ysWUW#P4g2xz8`lw*#h{=L}KRs(qX?3dwOZ&tM#Kb3y{L$H(cOp(kx{>BNGP6;TaPGso@~*T&oRow*;2->l_Uhe&XjZFLGz>+tlZ zW)!H6eQPXg?4Vk4J~QTwV=mE5Hg9P#iLkVT_i z5Va2*Knb_9!y$mrHtpcl&$R~Zp=UGg`sf9sRaX%Vi&@ zxS{G#9xkhmKf#m5(j3C+#uNP|ZSu52qaS5J*8NS;jZYw`DfW1%-3w=%Ql)3*8X;aU zH8Bm4YcA~QF%S}tUnzSox(*L~Tn;#A1^K@}u9=^&b?#lmj!x?U&?2PtE{E!jQr8`u zm&MJ)P!c`c6U;oa4Ie0XT@|=Ed-~qq=kcm(?MMNCS^1EO41{8B?~c+o510ss71C!g zJg`Cq5tOn-x1E#B?H)9TPAD&P&rK%f?8eOw>q~~M?LmE<%o%sLX=ZclZ1IENPbC(P zacgzAoswozt!8PVv0MwUdYf!Jjc&TO3O&0O66uF4;^ozH$!~7Pq$=>NWp9dwkvjH? z-tux@kN?{Lb0-hY%Wg>jERZ5%r-`pWWuM35<`tiI52U#%hGwW#lt}#IuqJv)a=o>n2y@ ztB})s-{Ourc2b7z+ zf&Kf)Ne6emRBDjc%UV^7Sej!0m>uoKGlavcMlhpR+cN~P96q@H!))=Q59YShYsTYt z0IyWon{^Az3}!js%vB_h;4vD_q^4~uJu176*(rWW8fAkTzK(9vV|c=m*|0J&xeLxM zAq1X5d_A19c3ic6N;Jtq$hpzoo$~PUZz6s4yBzPg@5dav`W93=EgbLnGz8HbSyJ6x zuu#je$J6!b>|^>fO`;e>Nn>hMYyuUB=&}SPR#GEoGWc{!$U!KbG9;(jO5?M59;52! zfJFPHS0B)AGzZD__;odTNlY!GT*Soeszn+^2Dd-sWr>D{&5kyHE?#!_`#6SO7g=Y< zYT??2I>EVa*l{5QC;^S9Q#is-n3)$QxIu+EgdCPp)SZ4y)ULD1#&OH~6k<_6p^fnq zoMcIndQMGB%@3h9B93S zXw9O3>Y8#gVt!X?O!Tk~LS?N{)1+jU*&d1}WRMV3L86M1f>W`0lZeFRErn!P2C7mR zQybDHbHm?st5Q^Vm3N=g|5}ILQocAb`hu<>E~9&!gl$q3UgKjJBk#t{t*Ay>t`~#Y z5Abub81+CLW7MzbX?5QRLnxt8a}Xtt(r$%;(W$3DWomYv3qqKL7NuUOqGZ->PKloL zX_QoMFjfm}Pb!0_^h@B;4v_g^gWzrKdSXYUkt9a0V8;~6ib`0G$x%(i8PJLuH^XtM zHpZmpq%7H?U{t+J*p3t~I^cX@(D2j~HPaV{GASD@9mS~TovYLM)ik>!xxfJ(21nH3 z)Dm1Xzmgo!&>1vZZg?2L9$t`{c9xtoZLtuUIJMeZO6BUB@Hy2_ zEjOorG!C=Vd9f3@*qdhBFey`+2@&ZXB%wM83>psol76J9AK+k(oN3#>i!_qRIV#J(p-2d!{@svcA4v>Xm zscZ-?vHSQiaV)3Qucg5&i<_!V|J1fsLhrM|#9t&wVbXS{M;B+*S@mk^wS6H6ots`B6s%IYW^=I#`a6>Rk-N|-#`C2z-~%@j?!V$j7abFVuN4W|ZPIB$Dc^YR@jr{7{mU&Y#%YNt$ifR!kn6S=|w`4wH#d&KK=-kFO zH)@TcBlS#9WaHJ81)E_k2S2QpahV(1Ne2I<&W>N!*xd1k=2EQWB*gY-mF3WJeT3Ap{7WF<959z6%< zs1x6tu;Zf4qj3<9U(=_SrJ$hyfEIJ1Yf<~zMmEdF&!?yS9f+sFm#GTCHZbi`T6A{wLqJA=L$@UVss z+3@!~!LeA+l3tz6v{;};!js8XsA}#Au?ZxTB^}(lnI&OJF~S&TRUTvGW&(=UA^)BR zjynY82ap0%YGP8=h+^4HUGnkZ5^u*qvPGPUtIxQSByJ}0IbtHCQdZnv?jW%zHXg$` zho*%l7zQl83!eF#_Rxf^sx-y?@6(O=(%BpF(V+a4t=4>RT042ZHeLd}zhKTKTX zeLs%j^L^gkK2OUYMP=?s-6zV?>IGu(OsS8W`bq8d; z+_GIczVSX^-*|3B_P2F+aCHysc6iq}nAbNhn%=q=HBCuDzMt-Nny1algwv{rjg97m z=PMIL&CK@X-zUHn*gw=g#c-F+CZF9Vxu36F8lyj(Ifvs@BDYU zQ^?NN*~He_iQr#ijv@h_jES*@fuNl`f!5DCJpn5NBLUk_6{SN!CvV{R^B@7+zZ~K} z4=S2C*||6xnK%(J{5WC%>(YPMXYvMSCjTn6Ol*z+HF)ba^ z+MTJaNKj<2`PzN_GJ8ATYw@6s3P*Q#A@Y3dLbmc zhYmh|jl18*WAJPm*RQ3|Y_(e%)cKfWjaj7E*T_Z?GbRO%S;jz;Xk$8WOoeNgbl2a1 zpMqqo)=zCo8>y?=^y-%?TW0CXP!vo2Iiz0dZZCJe*D{@#`+BGHMR~c7veK%;OF3M25j*pBe?D%hG40_=Qo2>9H62oF za&f8E7J2jNz9XhH>OL3qz%Tlo zsYGVIQc6k|a!Q4N!fyx+UD#@_@X+7irFB^g|6-$opk1&+**QcSfhZ7Ev{;WnZ0sBv z_AL9m0Ad+BAcnA`#O_SkWcL#p4YN)xQJt zxHFm7iCU)v!X}s$E0m+W9P1+ZbRO&hxpaML$g+c4o}-Sx=-f;1w%nPnr-rJOkFL2} zM2AP2N^R{&+sZ5uby=uWfA6YN&D9ah*;*Mg@(8R!TI4^TOi~OiVK3#r|nr;uf093o)ZXLFdI-Z0Wrcz&)y5e z(N7Il3j{uG9Hvzl@mcY=twls7)oF(1<&Sny={|60u=WHw#-5IYdE6h*h*~I^;}Y7I zb;sSmDwSK})23<@A@A0hP}kt0K!7g%y;+Dsu@RW=P%RPHD{+~hHJUtwB3al7xe&=L zMCs2We_@4xgH(!v#CQLC4tMo3Xk`B(W>Dnv_jf;T@n z&sq>%Qt9cW)R=aBw{9k5Ppr#Expa}AuQ-Sv-b`oTCxSO>;7mTmvs%RauCAieM&ioC zfXZs`fKoZPZ>dgiPZKN2KE1&TK@Mf~q6qYfRegD$n5r55s!YE=e^XVof9Pm6Lp4@AJ2F1#<=WDni58N(MIt#A}g*XWBhY?iwB9TqHSnM*u{ z7OY>cW?vNDn*uqpU+y6^8o!O>B=Sj}1Id8=-5YaC{-8|gnRjm2e__52@`&To-g$dB z*h(?@>|@>3mE3Lb_lDDG7zw!hM1x~ zpt(ret19Eysn41!o~OmJOsz{7$?ZLbY~=|tE3Z1B%49ou%!itohYA~J-~I6EgDuj> zoxO-#ExDGsy_Vx=HtJkFom^~Lp2UGR_AD%^ir5B3Z4v2u_97lh?U89G#$5AImq4~! zqlt6}dLa~VwH@JYYu1Tc9+g$JIGfmgM3Svvl3S@YL^VmJ)KEbEypCG~l(PC#(q;z3 zL&{fZ;Vdm;GSM3dVYfp{r4 zQ2Zt)5!}#0G@pj`6hPxb-bx@ALZ3rjLcUQwkst-5IPTTD#UKf^1!WjVJy|~7odrEv zrnsw*IN$=^jUGu*{#o1QM)Q*+RHU%u+pBQu^tl}}kR#bT4B^3SJ@S2Pq?tp<-m5@j z!5oZjFXOq$a=U@m&A-i8m9lgUCTH}kj(k$gUOIrKz627>9~2~N5eJ7~K&f8yofrNc zNZTK`=nuHgWCvqtDU7@R?y;jPoToChU$n+$RxSOnM`XK|u4X5QrED`zkDcuqcvc3y zPN7l^7tj+{v!g$Tg65cin??#ar~)kTE6I+bLEH(_7k2DN794r%81dw&_;r%tke5#S zWB1x$P6@)}XFu2(Uuuo&L)-V0DAX_bZ_xV;y$DZ4)GwG1o=@ZtpZg8v)B~gv!}<(r zrSQN^p1rA`u;Wo~d#I30zcIyKe)eaH?oRcE+*TG{Xzq5!&M&}RugO>b)=!*r;;-J& znR?}$<^&0iVQ{?({sPK+bTo4eZp4a$Y=|({--a@csaRy8KacBZphYmn9l+?(d&e$% zst3mmI{`gd%EfPuW2K@s!(-~hI#Q5`DI;FC)j9oaccnAgRkV8!;hETeGAZO%U!EiR zpiZ$`#PDu93vKiZMe}_UTb=66*CxAiYD8Izz*YxR z0@5=VS^=xD^*Ec-uh(vW5<{otL({U;CR!n5ddWphUwk>$-Tt({Pkm7 z2$vC%AZE{b-JjZ|(`fML{Ecu!L;7l{#oM17*gQ-;aZsAslbc4A1|XKt2~JyA583Oj z=}dM$O^jGFG>|ATVE{Bx9vzzmxe5vzWi>&p}z;BcA7b?VOC-ke?#?K`R|WL z?<}z7PMbbdOD$yU)GAOUrYwy}1H?R_Nr!+F8|2bX)JCun~u%>)n3b6C3 zkkaj*s$xei5a-7|$1QNr6yB-M$V6YpnEkuP2Dtm24`Rd@_5YS6{@vX1zuEJ@WQzY^ z_WZArJj8Y4g z>wN0U06s#=%igupJiQ@pv_NQ%Yrp*C#ko)*y(lk?$4IW&5m5k1nCU18C5XjV5GS-yJS2=xI4Qf^!~tE zVE{OO@jO8{OU5aic}S-9aN#@W`+N$MnwWjUgVx@ISAqnADM6Kw;@BnV-X&%7EOWi1 zSyN}hranV5bz@=5ZF`}qymX%QT5n$`r*i~z_uO$4Ep@`OD{tLn2RIamj`cPB>aU2q zw?@@Ob=#vib0rbCkYZGUX1zs4c3@Y(TrSuJDjOLJ6KClZO(aXF3Z(_lLaU$*yy>Im zCTkrQuhl0tEOvK6%VR}RUnhl>r`W-{rE0f`BsOR_hf^n=ZahOW_V0RQQRBhk8O579 zF`;aTF%UN7Y2nh8@A$K-b2%x{#Ch5Itk23r`}X=Qx^ONf*;X&KMP z?%Q7=x<$N`P-dzbfK(z$$yw)sRKJEJjVLGHt3D=S?Z&sSDoS7|U$YnKb0cL>?MHev z!HV)xp?N zt!qV!=mofNrTZ_KBl7*}I>S~F)1fAc>WP&*#CqT!#06m+f08{nb&ElaN~tdA-*ozE zeiG1Ir5-qF2tWd&P^M73(snPvQ&+bFR6U%*kqWZMCUFx}!X6@Vzgd9a&W;aPMjx}+B>Q8cgr@fV&~DykR;(Dn=e`n* zfeI6_Jdn1ayn?aulz|kDEB^YM!bSu=Cs8U2cnfg*~!UFDz;EA|;-b!gb7hOgI zC7AMB3O>|bMD}%-n07K1?3!IXBz)2guv%6MHMOM+TMg!ihH47?!!)6|bu)C4Aq55J zZC;iOC;fsQO3}>jN`R=(3&2}`(w5(1N=6BK;~J}!CZ(pB-7lQBRrq_uk$Q_Lg=YjP zbySR;@l0f!^bA|HQM5ykBIjTQL!Fqy(4+^gZ$JeqK6Bl0(lq0!pgSs?{7Kz_{vdGR zg=a)?Qux)*cQb8fye-s;dm$cv;x&4tj*!vX*d8uxKkeckaBHi1N_6U#5sSxr&`_TQ zL^{+3%vUfFLenDbf+i*YzKI4JwqenRpqtJcxD?vnMlSVvRu#n1>q=JvM;9>qJZ`Y* z-9Nmc?Qxn}%Om+5m?BQBWiJE`&SHcU)WcCKLb@Q**u5OIM$$xA$s@a4(*TFMz?1OM zXN3A@I=!R`LBC)uiGh(okps+F5tg)))1Z=9$8-*XpYy=(Cpee%p8Dm=4N*>)I?L_M zaT&QW{CT$Aqrvw5R;FNu+XqZGgdNL3wiJb^~!lt>dqQo0-c5a4FbOK6FQqLyBery zH8qlw=SwglXHt2wsu~DYc_Zf?6D-QoCOwLnD6|>BP-vnox?z}?qb%XDu0DEWr^Xpp z45sv73Aj|;iHQ;xOac@E=BBPsQEgzr@+TcR+h{66FT=-hxG=l#<%hHMFv{HWIEC+7 zHxTg~Uo_Li$gd0(j(4Xdmf%z0uIHFl^>DqaqUvtv3f*XRyYPvqNc3dXr6mq>ZDfPtGuPi+h62eFJo!htNkA9KX`bq z`V}BpOd3NoLNmf|Pz*LLc7cUo-n7~~^K0eGokPLN!n7zp;(eNC=%xvn%H5!!D3H2n zG7Q_OQ-RY#cRc3z$@&sr)UsFRZr7 z*QDUwnG-@4h{@lCL`w;~VuLdU)Qm7zd2`U(eZkuP8(h(*0Zoem?^)N+jrQ;dl*=&; zm^v-fbp%vBUnfg-_#j+)@n|PX`dPw&44AD>z}UU9QERuD^`$_xE~w?iZWT#Bp=eu~ zmzzh@Fo6qf+I^DMQ0Gysqa>$%_Oiw3ulX{gK+f(a{M4&Qa; zAwgiu%*gd)Lvu~Q6a>J{9JEioLx_sfPjnUQ@GXBPCFb2aUvX{G?r|%}V96Cc)Vbdk zG!_iC2;Nm=+R;qZ9zxKJ`&$$kGA(#K4miXJr5hYYRH6@yo6CAeD{nRzeQ<&1H;`z- zgua`K8QoQs7VYlTw*xLqgiPzm>74mZ@kL|MyWCRYo3tl)LH1*W$!6d1b`Tz*nMXK- zV`mLKx23S~Qr((k5@%O(KBz;F?L_7ky*#`@?rn#Rz^kCE;FbP^cyz2u8OsP~aH|wL z{n@}wA0-qN*L(E%>KY)%`bF#qjrCW5N`fY^ymX)NuFX-aIFYV0`PGfZppr+FX3HOc zI%V$h=m|DNChK&D^9>Lv#(Y-LcxENP<+@6FkX#VIb1ilfiRozU?8PRAf}L^3^%Bh8 zzaCeL25F9t5I&(_6y5@BxhqD#c>wzXMsd&Twd6+Wh;yoQ@?QvyOY9-O4I|!?LUyeg zNdAo>&uQ9abd8&4E}`)n23Sdv8dk%mEX?{hSXQB?kE~dZC^@{))a&`)@Zi3D%M-qD z>F@1cYS6$9;~nLEXHh^$0IDpwP-4U&j)1KOIf@b&!7}T|*13y+Hw4U3n4go7Zh_!& zn7w@E+crs5MxN4)H01&E86Q`uPjYG(wgnmt#AJ@r?fL;@4R?;2liy-9j>jl;Pqe?n zw^9(fIYz*i3?;L56K&e9#?z+i31UCX5jsbj*KnVjE4Ht02|vI) z2m-72I$iMjkwdZc)ilth{3^cjBYe9T2qcmkf&}_;C&l!bcgEzN@LZ+Y1k>R_jPJJN z+=!q7gkpK$Ki{kQ0r=fr1pnXU^nbX%hJk>AiQ~s+{NL>Hr^U=xq& zs+?rCPD@bzXPzNxp59p^%sJ{0Fbq8e6FrkNTe!coTO@N}!Y^1Tq|8KfqiCoSFeR0G{+z5E!SowMf~yu6nb`27h<(68>yq_OfExtj zT>i8efT10M)qp*!VCI21eSX!$K{HUZEkOidAP@Si;%o>wF#H@i1giSvK*@VRO<)6n zWmf<^s4o5~$QW>3|gMcuz zii*bq?L=(=1Z9tO1fzg}LWe=x0tn#0NuX}LoDujXRKWoRZC+M)q){a9w7?Sa1Gfc)ANxL({j`mz96 z%UF7O5wPjcz_+0R9YKMA+oRXTt$f3MtoMTh0WKp@5%(flLkH}AE8!l3t$)-jJi~{z z0!zQhKL7*0`1*X^8;2UEvA~?|+`@l6quy7LkB?Q1Iej(V`2{*U(!2Siw*VmYPSFj5 z1Kiz00}IQ;^M2P9!Ule@fN%4)QOaXuQ0~ukmIb|enXdGR_dcZxt^$73mOu(Apu_0D zhn<#q3wo=T(d~S*ZTppeY@2^oj(;bfe)Gg9L?(qFx0?-oD#`)%|2n5MLAb@TXQOLk19~~fj8G#od7ue`q{)0@W59qyj2|-4(u3W5%V3|rTOI1xBKxG|uhnkS*4HY@l;IdJ6L};ny2A@h zzGwXa4%!AOhrvCuEM3##Kbqz9%4G6m8()PbS@#;tAA|8Ljx+;Y@O`-(Fp}rZFe$Yo zc76qZQO}&kCRk)|{wY>z#A0;1FxP?$B~iq-1BuPem-9v>cfQIC44BtXH@*=G;g;f! zrdC=i5}}+N)vF7aB09!FCbeIYvkZrY7a}8RdBtiah+`QR(v}I;$1e`H$%D{5pIwc_ z+0MDYfR%NC)t)p2 zk;~MkIpnOF39kbvb#5;pnLLX|L!5DL<@T?&Sy9P$j(Orj0J&?=lQF z??w>Eghq|Gm-Ax-%oD2{mFGkiKatn$1v1B%02)H80s{~$e8(>aFq^~^ zN2m<~Bi+wpMBv%zMy!=aR0D(XBO&^<}M!ja3 zH@T@{vymzlJ>Pg*18zV1W*a?gRYaY%t{qqQJ@VA_8$0-MBuvaYLjsY7h)UekH35k^ z7hqwDs>!&LSMJ8{$+4*rlvK};g$1ab*etafhB!fXl;cPBtsvaS=_-&4MeMlR#AV`J zF5f?6codV3BV4UMU&n~Yyc;u-?RFzkhn)1EmAfOOm$R`TIwTdMs&1r%Yab%@cBWv8 zPsAy!IWb2L`XisgHRZ{2CUJsCUUu;Umane@_yBSt_M zo5f2#Y1Sgf$QI?(g^nbi16v*-J}rN?y^3H3Ouw+VUY`}P32(F7f{pAcC7|uDmlm&v zFIqYR?Nva;W{Qv@{|Ps|Jl=0Q*UPu*$!c2p^v|3}5%y$j;m9wB>x5o^J77Oh-5{qywByx3}MnNaPl}cL7DhXK zB^k>|w+s4fDesLUz#|KpNQ;il?u*p_ zEkh80OD-!oRfDy3u&8iW3@Wd-`a1}bxBdyr*OzIU_l}@NcV2Wm#KqItOeVmrR3mGt zI(GVB8q@9=y4Yk0>Qle{{oGJeL`Xw2=}q2~=bu2Yp|z(}^U3~_PIv={%2J5`WyJYL z-85*?k~Nrs_qzO}qXO;=?4topYO>)|^=KM*85*h8UBRG=>hp&-!dh(HAD zTa$?#0ZmRczb@zse-x5NS=+FiuE1qfcweCm8kF%|abJ{dJnl(S zICj_2`d&p!YV#|mIaLf6HtsHr)6oPv^8Ky0CkYF$t%J$yJubm@twmNcK*#^(6@R|P z5Tu$H14X$Qf6c<#sn;{sjM0VZZwrfz@u1V|3JOK}=TUm6$Z}9Ugr?h6`vu%jM3%E| zrPSDFO5KlR8)Dsbn%8SCso6knbgm434yq*=Co^X1baD|yYLPl6L9ys1Ujt@2IAwUI zu}5~htH<-qO7yR`-xo2RyN;EghoXf2J&o0X0pin|n>2MgexQy(2Op*9gAU3fr$ z*mh1FML{+Gl(>mQ~YE(NXUi6`TU?4Ky_((qCairer#Nd#g&ixKEER+J6w z473)%Lfm89EX)C+ca|${+gl%%%zZI#k6>H$_8GVRm^vk@$h{2+qzsRsqokk-2h6)) z^NVb&l5l+Pakz ze=YU4#?N7FDI6=&+Kui^-I?pheKFIIrV8f z-EF%r&K)M6>L%4Msuh+yirZ+zzH)z&-bN1ZgQ!|X(RS~u={Ds-5P7x@G?C1Y zq}k1l>h`f6(qE1n_u~7wDH-n$Glr)f3vWD!XKM|#R0sx4sJLe@X@b zrGtmO9g>s1N}U)Gf|tlQpSp1yU(pt7en76d+aGBPu&Pm8S)KA8WG~axcuhXSs?|hO zw~B}g%!m}NyjY!9?%EE6n~p-fbq&Wl;HIA)*M9K)Tw?o|>>QKyLTZSP($cokY@ zde0-~mTcMW>gb-F$FGlFViCV$^ zIw1m75~96Of!<&GD|3uOi#zte*n6i~TcbAJcG~8ewr$(C?KN%Nwr$(C*R*Zh)>*al z?_E`?zv@)#BjVUZzuve8(l}E|1&d2|8rT{6*jGdFQBNtnn zdTxpS1~wdl&*pOQ4zu6R{V)8iI?$8xw84qX9jOFEc1yonSG#)A}` zQ97GA?2=+JC&8~$vQyW!9v871j|9TLDR`iD$LRB<)26WJiTJY!#pQkI#s~ZQEo^qy z4vz4I3g!V~$zoI%XK-|Msbm zaaf<03v>7?d=g)W<0Y!QJtmQwgb^uU`qYgh-Q@bF4^Xi5)%U(9jLi4nEcS$?km4tZ z-+N4~Ib~Bp;Ik!&!gGRhxgbessyg+0M778$NJlB!Znf1F@gug^p;~(Rk|3#fj3ytW zsKiJEFKIxO-&ViBXcCLlHB*d^PU3^l!nzHDBg>O5Uc63M#-DV^7CQKM>47q4@8;mf zew|1rD$(~6DEA?2ePvElcTKYX;x#7l%X}yKal|jJ&IY;f{ zF=zg^sO3q9X*Z3mCKjMHXR9*u*`B!B-@KR{n<6Gjp}{t7AKc(07?6T*ld@u>Up|0A5dV z7QWiyrhO**v8RhTkqT&&Adp^Pc*>6U`o1mlw4a)kG`}{;6L^&qXfP%?OoG+LWx=L( zKxtvoyeq^oF@HzpzIC&rRBQsF9hClOaM4F)`bw+Oj|`TZ4TGo9mK_AhQp*a=EN8*0 zd1_+rFr-&?-QX#c6l+i|oxR-${v519>L8WegT_{R+Gqp2o@3Ti_#Us4k{FMZHCp=N zN;Y!i{)rQ!rq#TU#Tb#cHdkt!sg}IBvApaomLxJ`&RdX+3fX2~&(`#L`inwL{`WX~ zfXgIK$!sc!fa5;+p8%2zIJkVgLZQ@RkgMeG`Y z?fDJuHk!3)vRgC5dI$@xD^;C}Hab)N#0?#hatHpqdRCLCNu;X)Ezx68>WXbzV-#2G z5i#iY>_pN(p3l*#Z`Bb@>^tN#@L1M%b@W{wInCY8weS={6)NSk#5S22%K@I`vJH{I zY33MwD1MKBPQ1jY>$kWZp%495cD+q<$x`BA6?wPhdo>6$AM0E(I=m7lYMX5R3_%Kp0H6Q@ zdKk*}gOz&3!wB_6=C9>eyx8!<0oyPm$lum%BGn~VAO09iJmY8^>PGhkB@!xN07v_W ze>z-lD8Hp8NKR4<^#SkX_$!5)P%puR8s|Nak3O&{zlSYPNjCH<%*JC`yX(b>4y-R7(h>+--YD2J^G8y zQHFLUZ;{!Ec$&+==Y~o{m+Cnwy#|RzoZ90~Ky zD8!nrqJ^i~smNfLogbOY*0YW}EI=o26tl3a(DW%aUqiystiw@iFqzY8vA2^@?Zc$> zZk7WIQT{rYz0`tvG}s`xT#shs0V$9z6PWKw=r$!)w7FhV z%C^H5Vu4_Z96N$S>=T7sA|P0)Be}9`^m}EqbW)&yGK!T(Y;{Nh`Zph$q)W!l`&aS$XQVQG|?aF7mjCwn|GbLsvOPfqWb!?;QjaQDU2F3XUvJ0 zKUkU=pXF4c-t6o&{ZNhHUVMZWX|CG6$ybxrVst?Q?}6 zadMady3H$r3&ALfRbrJj7+6Cnt1s80 zO)V$rDGnGtmO8A`eT*?4wM~n{h9`Z5Kty+xdDizEJ1t%n0zHol&qXuTiqkJs z1LRvTy9^|LTE`jou9iD-aoN=Bh%$LtYk7<3_Qew(8lk^RSxjrn1ZT)XsHmts~)pOpifn#dS08O*9=g1&bZPX6n&h~cO8VwFjQ15v7`!8>w zuC~Y_@dAuo8D^%3_q+QB(Bp*Ls5da zAHi7n4o*@t=G`+PkyfiaJfFJyAzz8x`4?wwalNRLSCW(EPq(V@(Yng7e9MWqSgh`E zcS^eTLJXTz5Km=GA>Dlk#nzY6qO-x1Isc4EW09=-aOv==np|S9XtPK>ivyD+3i|Uo zFp*M=yJ!UO5LbhbJq^d>sW+H;`Is4SW|GQG8y?tW;P|VJJg%|V z|EeWD2Snoe%1swGda|BJh%?GIp`Jhkw4lIScMPqW+*fb5fmkij=H~7@$r6+u*6bbohJ;12QA5;qyt90Tn0Rr0ASH^nGOx{xtfC&NqfK zD*9f~f6hY)=@H{8sRJlGQr6`1)#wnphlMo<+f3c*EQ}gfOQoDdJ{CfMWgiOOLx_YP z%*;B3B8$x(k5fAMB^KP5F?IWe_KHp+Nl2knWZ0+d0KA+`d@*ImMY#H&@&M)E@ z{O%Qw8u7Z%b&L}Lxzu1!jcrI900O;dqq5ao_8|p?s zd&~?cbQy|#Jbfr*Vhfh$e2WPShGTmoGlgy%XT7JCr9k$D7uW8JWg1nH$P(+TsM{f& z6z6@D(c>kEKM}w47R$68}&-SZe#uXpuay<9d|ss;hK)&HnH^y35uE#98-FkQsRO7j+(@kuUkTR|qgKSN9N zw_vL z^XgBKDt{}+AFdNNLE3VA;;vXN)QIFZvv&#QN)0-MQiUm1tK^J{vmweP=uALp%&b1# zu2>_%j78TSBuL^^#KzlRv;FOtk=I(Ydg&a_g>bg$x^U@i5VE z6!`u0r#8LxhM3xW9ChGV0{)R<$7F&Wpsz-4y;Z?)z zPIvyp0@+F5rc&Qdjg*4id_Z?9-jWZS%*OBD{bH~UM^SlX#kG7hygp;acDRV40+I|i z3w(w+9$$)y0wL}>0rwv{!PdWo+$kgP%Lf6ejmgDSOL!;m%6;8dTwrKwFyscwF1gxR zhz+*tb7Ij^$i#a&A;CAf@dQyG%T#lme;uK|Lt9GZhqr<_e+0iNiwv{zO|^!5Inh)L zp=TL3*|>RBZsrUwf%+wukpI1-H?-LDek}Jf5vizE%2$HWIL;&g_)d@mCKfC^>3ad) z&~tpc<Htqg$Ev?R|(-y$>z;t#!l;mP<{8#{rseS&YB6<_{{> zKUkK?Odj3F8PZ(uleXsb>m?DLWTUyiiW#0;mw`Xf$oMJ8g5Fd&`Js6GMyEzRTo>KT zJ?H-HNJXcjxB}y0#c0E|#UckSZzj?xNzC>zo96yieWp=K^X0t^{%D?)-J7?o#L6RU zU_ud`lbbBMvz&mdJr1||4R4CCHR(Uz`Tx(A9sdcv(n{<9S7#H)|8+L~UuV;Q%h^=; z5jg!H-~WGW?D#*0?0+#6{7(zn{{m|N&kEW9UE={GD=X8#1I{dI{bl#Hq58bk?h>&y zBWOc1rn``?S*;(JZ#}iZkGq7V;AdKfE0a^o-d}ja0Z0Cu(_e4L-}uVGaaiAsnvq3O^NP7%p436gY86}sNlMr+8G5Te$n@#IRQ8r@kg zqyqz4E9yIkF*gv%aMIP|jtaXBYQC z-+j{Rf~XralLVCVkh=diU5%9NknRD83%ro#IN58~hsyvtB8d4@xCM__Rk-jhU~EP*r&HxnlPByQ4J_~*G}xx4#GZAqAn`&|Buqls7wQVInja#108 zD7`PhBWwS0f&6;^q%sm79fmtWlzJZnf?1-F_$Vm+cT0!c3s>~GmaL@(aE1s=NdVxF93N*( z3nyoSeZxRslP>d!qj}h)>zR@^iY?nWi-CpLj0^d|}@y1^9@6P0tNo%+E^`vzSVDS6ffB^%E zPXPnS(_sgv%Gy9nM_Xz$8idm~DO1d?e!h z72{?Zy$OF3#>*ckrb(Cv&HzTh-qgfd&(!X}=IQK3W58w)Q3{EHXr!TDe96_!}Jty9~v$Ug-g9gQTFPNMxS)G5$< z(*fEJS^og8Ir9$ATyJU}2rm9Dl*J zhF1uAs zY|(lZC*M}>N!>;f+`$9(e zRUk?Ts)K}GYV)=q@u*6gS#R-7%T~!8@^)vcR6exNzIP%;t$D|Xy1kJv!)BYey9O|TbO2ixqlB;~ ztf^FiF0*#t4G=gg48aQYbB}FFTzQbHjqGNOL2Jh`sk03MhjBM|?QGUa>!`M<5MX$F zx6N^nJy1{fv2YDfANjI2IC!i6nDbgao`8&G7ilg>BYGF{QR5uhKN(2BWwwa}Yf>*7&eZl)h z?U-bJ-~?c#Pj~ai!2?b9+n$aakxg0}UiooLhhV0iXN zbj0u{8hmKWVxw3FbI;ypTZvSP=>=(K#qvc->^Raw>n5vUijZwaXnWikYNq4Hh2TIQ z!0lauN5U5_e*jdPUZzhr8ww3@r(V|M_miPKILO>8jdK}RAY|LGy?Qg6YmPA`V)%+* z%WFV4fegW32$Z~*s1%lb282t@Y6E3NpMjB} zeHcHQ32|2dh64*rnf!ztu+lSP7ke>Fef{~1ir3#%epM9#bQ`uWI|_=tAs)&H8B(Fd z7iRn7Mv;Zf<`U)vRcKv*UMifBiS0}LrU)bBzOto;kcNj7!o`y_eh1;WX4q~|J_&Rq zj8PAspar`lUaeM>F9hKN`JuW4L9~+QeoJ9pKWogv)7%ZdJ>0xArl$4zJ5XiJ$x<02 zdg5cvisHUdI$7k!!;m3=MfdzAV;qS!r%Wk9k9AUqJk2EoK)qg+_MkzrwO z$%nnRl%7hk)srbX1)l>yA7xi8XCy0{bp1x4dX7_Ls?rYldUsTlL|H>`zMXaq+GUzv zIZOScC8kmpMFjGkUqx5%KljQpky%_y%L@KX44>of0QkOe_6vLJo&CM^R+C$5AD&cA-#+u6Z(<`Uk9uBk|wxR^+ANWeKCGpk*qOJtU>HCv?;HR-a2O~Sp_7qAwO zOmf&==Ws=e+c#d`W#a*TLpkp{0Whxm!m#mArXg$Ep`Sfe23R67EhBl5n7XM&Ee~u< z1XX7a0QaSpQmdA^^+I<$t;kDcPW1lvG3Ye?L&E{mYg5Jz#7$iB`n1TZ2NFj`HNE&G zoCZaaqyUwQ@C9P>ePC79LQw+`$E4Na|6D;3_k__5URN@`Q zZ1m>(jm<3~jxt|6SwM-{XS6u%Cck{m^^}SOLq~wL{ISSd!SED9Mj1lDm;~o}jHHaI zT4YZI=e7cH6sd%;#3;{PD4GB>pDmKre3AehA#FkD)VlJ;BodF8B&Ua!{^|G{6Ui57 z=`OK(g9#$P0-Oq64FXTTy1t?h9ums4DNgdyK0l^S#b?zI)-Cp3w5pxjakh(|ufe?TSbHM4* z@)DhXF}@#1Pgrb0G#+TJr5rYwHRRFJWms4)DxVEj3IIMjYjzj3*X@X1C8=~@m~TFl zJn0=S(u4ZVj4$8&_+4m6IW(J~IL6>9FJ0sxaAEpJbki5lrb(Ay-w#W}zJNb|+CTp> z9RFMC(Eka?4F3Rj{7+yXEdNN>|8!mPe?9oWquXX=X8HH~idUK%jvHf$J}b5SZzlZ_ zkTc;J>@AgDx)T~|B*|{g$>5#`0TN?}8N_WMza_q(&T??&0hsf|-_+G8;gRUo?5?=BDf%l8n~!j;Rzrl*OB2nQR2C~&i73RmnoF&$~0KBaW3#Ei_H zs_^EaXi~ut& z1v;~%tD@qQlJ1JMYg%J?nSI0v2S&t|D%3ya6@KJ=3r|Y0A(8bqUuX_dP0`(DaK^gz z2*L$>G8DCVgnL{F-R&$iG6ix-85jDB#oLsJj8E^lRC79AH{J?DX!#(>oE=vpz4j@RPT0unjp=qK>#3FOQ6~6+$QH1)!b?iE=dsK& zoI#cmQzuN?3!W=BsUL#*P|Nc~n{{@33vR(D=uUJo_BFA`bcm~@qvR2#+MdB)@ffj; zHa250q!(USrzX1H%g2b*4Qw=_pp}`AB`9I1kO+vB!{Zq(raG2`*^oyc!bVY9jAO5q z$@q8iOO|lbQiP-zuDVbpv71ONN$i7$?Dkjp?ODu1Ill#wEeAe2R%5t@>JjK`b=0k_>s)}S1a`p~V zU@t9}eUa6%wedyuq-YrKw)ljw2Jo&lRZj)DDXsz!f%GhU3c5-$NA3|WJswXgM6}5c zkX9DO$cd>Aljuq=uhyD#-@smkQW#vs&c!-}s5vVk(1fnGL>T&ZxnK^v z6faB}!U-a3K=mosY#&sbgOUsA+CBTp(n1sH`|{3+ z4+H#~8c#pZGcblUF8<3$^_sR+dJhQ&bep;we?HjpFp~ndij4zXf4@{=(S%%mQ~_Nd z?A7NgWCEa)8~DrgoZi$qbS;DR={mO!z>X4qG0RN{6>BEzq3Eh^hj~sN%AU+=dTcF4 zMc_GHcSH~EP9(`8PnL7k%D8j#0@Cm%%1V@B%%SaSe~cEX;!6UpdiEofzzy`Z3x+5> zaP;G9tf(jtdZ3af$o9c-9R|qkOaFRBjW3%ubDcj=IrS(27F^2qms;u+7#H&;c+r-z zBaHIwL$pZ-`QF~ZYt+L|A&kx%_#_UF&KOCq-toj!!7awAv*{Ta2TzvS@6rNax(kQ& z+OoU-T<$dBN8~w;!~&Ei63~=gik4G?^MbjUc8W5ycBxPNMDGarquZ``znadrJpa#z zGVKJ!MWW$OglkjAE6qs_Esdf1rZj2*hzc9b4M{-Zl~OaqTt=mXZTIy&HWRl zhDzI|mdeS%VZV((DdWVUtC4It1xAcJVea|}##*06$B8CHO`_*&0#OmShN`zG!2B18Nl~r!K7RqjTv(-pK4JVg_oXc`^ST6MXx`Do z+yl6*;O^$>&_4&TKT@HL_L!C5rzCZZqG0dawNacdG&PN`%F%n$36$sn6^5AEJUGZ2K|A>_)SVef z7zR2H-IcMRRrpcHd)}gXfykYPi2%@ z`YkkYB?1bGPp~t$Ff1yfpcKiwXP4_pn8Msk?C1JU(rcN);F%T&0wETfR7$8w7sc6%?4Nqtzf!*=P_~kC$@a;FX z;vU~kQPw$unu-o}`4!)BASzmCK=8R~RuoA>zPUefl(jLwau{CrFW7jh!!lM&V<@#q zNJXz&6b!Hy`;jBS-Q_(+zuw?z9e=is`ZBTUfSUBH3>=?72@QiZ$;H2%(rjcXo604d zATBX>*EG$#H41-9%I{Kq)? zm!eIN|Gxv?zvjvR5AZnFf1oq|d7k`l)8m*Jng89m^+?M)_Afo|yQf!hEcH)c_#Rg| zGsiA%Y7xY2!IbqJyypskeRF3=BF#zy-Gz{^S7^~;a#s>fZ?SA7K)f{Uc=}!!w~&Lq z-Ct?I7HUoIj-DQmZ>2IneT2Pqz{Ljt9RJ=g1Grw&ewkOJNN_1(Fd zm7CmN&Zx6lqRM#n@$o zRHEVEvjsrc5cl$kwQ`?ma!pSY1Rml)gw$5#kdaon?d%?F0KXX!e zh!lf47#^Nw2v|>Vp56Bk&Alk9fHXW&;;T$YtfKJ9uy0o65uo$xAc#xL8LU@6_rG5x zG)fi_3-?O7o%L+d$D4det}r-7NgxTaN6g5VH>363q9h4RED99^qaCpX<|CfvnEMxaFSsLad#^2{HI zj!f1%7!!>$28>7=E%w~8 z*a>RQ87CL8M{Y1ClXY^2$ssgG|Iq(oMl4?BLiK031?cahpXj|drPLqdf-wm5r+^#K z-%tAWS6lJR3Vw@K?*-l$ypW<$Y^m&lxFX8XLWdlviI&{bDw^Jx6||9Kl`N4moyBH& z11Alvv%p{Uy)nOk5n-$53xKVZTjSQJ?A)a7;FS)Q92&8;640F!YRw4B$kQwkC< zP?Fu(U!t|)+Bsr1WDc3O{a4GOh0%DoMWT2BPp;>1r>t@%tc8t8t0Ow%bR5uc6a~O1 z_#Z~u_o3SsgXG3hC3oprGxSJzTf*r#kDTfEVZZ&RZFRodFwBU^X`~jJgU^ZaU!Kw~ z9c!TO4WbpmE-DiShGR+r{z9|r%n6JWgG-qgmA*Rh0E2u;b|Z1hga}A}f4>@ccgGtB zIP&W&ZdPjGYc9BcjW{*EXFi^Ly16PJ)a8i-XkRDAu4X1etpnqYfx7dtyZBZE!zSj-UQTWPnL9z};*Bv))x>0BCdIl+o2D-WMi%paH46Ht38M_?r$p;q>Sm z_FX}ISk~5XQNwOgBKBQTvZ@fGjgwPpeNn_!eUuJsAX?Ocv|7L!4>0w_zHhNh>gwE{ zbj^aaXH#XHKScUWur@FI+c9MOZd@nt6f0b!Xw;%m2x|-(JMMohW7Gkz>~V zKe?LUB0vy=KI}i}`8)UmFkAX`ABme`AI%J0t~_sXzz*VCqrWFPz>xa@Pa*ixZ0@62 zvlJ1(jZhxy)IT{5iKVCN8wl7<-gsSd#jR`cF z?QnwikAk?uEYIzm)Q??9jg>4I_INzObiN!b#J<$McO?38}H1GBlZ$!0tr7H_N#VA*C$@Y-K8Q{QSJ?{<< zG3qCBG~%4x-s*>d#YQFToW0lU`Ry`fGaRQ8rV7xr_;XjBP?IK)7?Ae|Orrmh_j%+S z{nGk_C5-Iliny2AlWU3cQI|Nrlqbvl5xfMQia1)P`NsFNxJ=rwh%`WuU52u?7&I6Y z*RH}cX^blqf-8yKmHf_c-SA<%60>1vN%O1w*NbST$IC%HR5anVM062 z`E?1UH0I|fv3&^r*4RERwBy)wqE&oMWmVcz?~gSuW7bY4fvO2BSX8G&ZpDXl>41dt z^tXI_N6*Z&{_KXKL31uODV)zYlqnCWI43QRfT#6t>4HQ`pohZ>U|2S~ zyRE&g{zYq{ddSq4)ipp17e%iQiqgvjD9ly`oVBA4{PXs)Dz<`XhlJ6n^EL8Mbe~$V ztJX^Uj049pH2G8Hc79J(uWb9!2XQsmB3DvVkC4v7Rhy7E#kKo7*JAZm*%XypT45UI zXJk_i746#D{qg%b-*7kg!#@dg{}g4$@ZV*bvHxR=_-{zSZ2uAu|Ff&}|MlSiogM#6 zm>CB<+rJBQTUru-hl8j+7ixK4kjh3b9ycLMyu=5S(heD`f5u%Z@R1VeOT;np4~maR zPr9$cMEqcpw28TtDv$sl?{#~hE}}_WA!U4e^7dYA)zE#v$J2ro66T^v)Y!uJ!t*im zk+w<4Hy)=N)U{)RP|L^e)Jks33J%P5SB|*;9J1@BJYaYk9o~N}@#S-MuIZFOq_Sez zOQ1COOw`vxps-T*;Mf~2q^c*`Nmdy^l1SU{9P-uoh$a21xi!_cA-@L8x$0&=jiYUaMEOu9RC=An(dFSx@s2KSdWgysn7s<>c zojn6nwUUcIbfV&-owU{8l^{=(rKD@4h7GcWAYSvPnZh;j@N^{*@UJZ5HW#X8Hn*57 z-XSZCE3Rx(nX5Lb_FUX)y&=q)G{vBZmX+_c6;KcW%6YuI(NTX9-J=C_hNo}71i=zD z*I>FCKJ;eWIJJBe-p)f(os>wal#rC3>nDpdOX{2ZTjk}RGToGg@}I{T$TfMdW4^6P zD!po~cwGQCZmH6vDhQlpey3x+VJdVp@+f5l5+=TZ&d-F6$KF@?x8VB8<5%de$?J%U zG=uSZ-}EFE22su#@4q%l?T)#@K{p>?4#TrAuj3uFhjZTCkn8i~4XdV%WIQ#0ZI#XA zC1cISd@rAcbCj~A)<$Q<7=RG*py&JqSQt?&d3r{!fOuljSA7%X z`h6W&VTont7Im94IcSl;l%f))R{;Y?^Hz!6EDQs8;L(4>lZg8(NQQ{xh>&iy>t)fr z{0(X%N~0UfOlz6<%NVs(1jNV-9;V^_5J(E1S~z(w1nOdV)Fb(%lf0Zw*kIc(&@F?A z=ot{8@!)@H38ObCYpJPd}s!xNncQ!cQ>}tL&~=ly^~xRL*{q4wmOUK4~7K zzbUimE5FF&5NCCuL49J%5V@C4X;8+Dq;2#2PI5G2ClEe4oot8mS0}{@Vd?SlXH5)u z-CpzVvTzXyE*Yxx8tMds6hK6h6dCZhzzHW25D=d@P6N-at#v-X&i4;MCt-GDNwjyR zWl16=1^~CCZs@jqO2m&{$4+NgU91u|sH0kk6X%3;a#e67YIR5O(6M zvuT9im4nvvSn}s)kmyE7=7@e~V0`?zW0D)wCkW%$9h|oEXP`jl^k%#u8k&PV?oms! zSg&X^zY6pF<&t0+l@|aNINc@pH08rHP>oLz=;mHE3=vep=o{kP3%9}!Vtqli-J5CO zIsp;k0S$(Cct#qx4do`W!gwf04#)Og3t|Xv)4?F*!AZ~x*~oF(ME2ZPOvF^Esgwat zTiIFW{aC2++j(ke_^@|9b%h6$Kueebh?$1j2_YH+Y8YEU#s|;(qj`Ryn-M$8LQ6zV zCEuEp{teRi_E-051Prn;grm>QYANz|Vd9N9$0NWT+!iO#3@gdTIzA6nv+G4H<25$~ zIt?m%bU6d!9Irl#QLO8@SNco_J)M>#Qd+%M3>L`-)A%%_B%{UBJuh6n;JJbPe%&U@ zYwY@nkPYL9;{rcCH%!B~L4nu?VXJy9r^s=^DTYc-NO>35m!}JT6HZvN?5x{Hc)%)o zyy)ez&5-`F4Y`dnd0NPyh3qC+Z00=B4TnV{7o;8$J09bA;$m#S6HO%MHegatq$s%U zjz%0TRJLTtS7rECch}o>Vzf?Oxud_X-%T3q$~JhIs6B0GCZnMiFx0uyqDUVQbS?S4 zUnU1O4p0G+@jxJ>)zQI`Vv+sxydExG7z5rL!KJ04b|>ryXvLg=%36fdpK38Q=(NQG5b6-fdx1^c00tu2s9J3TWpugQahyvFmX#!{DUZ0Z-D zoS|NcD9ddUkMEvltV3X~kBx0^vijXRKaE|c;ALjDsv%&mO6Caty6qJ3@+OF>y}*Dz)QK^4dM>jgan3H!xf7o1oe7+vz;hO@#a#+a15pd$woWY| zBU|f9AGRIkgAWN)LLTk5A;r2rBpMPrk@Qb+K(%rdpz7Et4GCHx*(B90N2(rfZleON z668U13-xELjq`QQpez+ord+#>7IU%j^@eYNr97Pm3!toACLPpsp)NEhGza%Yaj87& zZ@u%1JpK`E(=%G|?e%$D$lcsZq5jg`HSqPqJm}{nwN+CgB7Y5gu`YRA%^t7xwnPsf z@J1`^|AODHD^FF?-QKoFsX?3ZA`*sJaCj!5UXq_pw#M5U^{J9QQNgI0KtcW?$pvDf z?tZe(t+UdV5!!>dKl6@`?5~cd2pNTKq}Il1pxjLG-~RN;_hDBo+=LXi8Q8*|NkfNI z)~ZTr#){L2v9j%Z+wUKR0|x<+YIuHvjZ;EU{1vCE=ieWD;VFFk*|`$9i|LiyjCyxg zgMGk$LtBsC;mnrAuFHy%e;N3EQL?IZWWB`y6sQuo(nsuSim69?_)Z*ZuRW!c0_a$C zw~gRaevE(tRV&UNX0m!c&(;w$`lt(ZuuF{0uWdk) z{_pku)fE`#GNAZY48A(QRwSkUgi2JvkC}de^L+5R{>d5R-xBHmbzuAtiOBzJ0pXvW zG5)K1F2jGf49~#8_U{V_)v9{22h0e*J93D30YtRCo>rrfwsxaHFG1H(NbA598znkY z=87a|4w0|7Q9QDAh-c=_`^D+&2XB1681dLh@t86SS26&tKQ`=6~6~vy8d@KolqM>5x4Iy9qBi>8QLhqx;TNhehw4ih% z6y5Ui#(tDAag$R*(YD6ZFgBEH=REC>%)z$d~>d9FV_q#Au75LcJA1q z*B{s7i+;~YDmY5ytKD2#Tc_v#rRl09>$59&3cfbyQL z30PaWH_3(vLf)UtOxpVy_*mO{DEj_hk{;XO}n|;aI&Mkm*75X`0krC+9sNoE?ewNkx4ZgfO+RRGxC;__>1HNS77Ju zGAo7cI8f(viC57a`_m8cABZ#Wyd%I?hwkSi`b^uYd2DMO3>_?03DHlDN1hbK4`hKg zTyjm-Nw;1RuKbDvbBZ+;teNTZ-2Cq=wscm4Qp!26=PUH2AJwN)LuTa>50{_1GIa?sQTPviyFQxee0%@z7L zDvHq*DN9m+S9#0*1|s0L6Iub;)NpZ#JKg~D!@`gWJ#qTL66QH!NnQ2K{sDT5zv-KG zjWs_###khTeqPL2nFm_A|FMcQY!*t%QO_|_qD??UfQYUd*M=uOnQIQUWRFWld}%Vq zE1pj^$OG)J=2L~;$}Zc&_J80H1-ut>=>AbmnmAO=-E0nc!su4yNqdZgH+ByPc#i&z zkQ^;VjLwEfl`Op9G92PyRt`CELSGV*e*1)4Bi_QXd-OMXLci1q#F~u&?z5m=(iV<6 z0+y-+Zp0<114W+OXU*We~q9V`H}C9yHO0T{%})f7aQA2H0;J z>TBq|*d={cv_%wn+}i}t;)e(}FL}GrU>|wH_Nb9jt~KKr8oKSO3!5*dASWeM^$t@^ zc_;{@%G92)?iaB^+9fHYXa$;(Jbo5D60Tl9dSkV04vq_4Vq~f$p(Qfa7RXe$zc9QM zJT=R8FhWyIr5I;EgfQ`GgVaqsRabwRHmD!c$E~!#fXDsR!&rfaz*1EGh}Wn-^1c+A2ookPj2@3&q`ePRFlnefyL7U0w#SyTCJYY-kA*zF+B zWf}->a)d}1UFv99auz_-Mn49{n(!TI*c~7Wrv+{0WJHB7!DD6n0V0B<+WsfMr~h`_ z;lCK7{3U#{FtGe9;ggl+FUj*Cyw86b`~2f0J{t=w$G@AkL^pvdqnx9$N=v#@G5CoO z!fa*FZw&wd!!Q63#tFFwN>bisBk2>CPy!@=Z_pn$_O?Kv* z{XdLdLy#~$kR98$`HgMcwr$(CZQHhO+qUhQ{f~Rt!=@_7T#`yxS3ljkjWy}9n(6@S zdU&jd;r`f%5W|$k^M^;d0GSVS7ev@a@anHi1l-hT8_!#Ozuy1| zm6f0C0|0IZUIdT!2e5^$mFI$(ep(%YHiZ`eu(bonD7OM~-X^T?8_)DZbO-Ru1O|8r z_(i^rd#mG@U$-->&%xcE!G(DW8pHvFlUIY_7ZXW>zlb^p^f!3z3)feZd#~YJ$A)nM z-P%R+ErSCqAHM?ZZ$tg9m|KDabP@A>^bpkXTN(eOnzqSGF?fx%XJdnaxrq3q;v=O1 zGIZN=thvzKq7!aK}SGE z1mx!iK+xkN|J6gs`0Nn!4a(O$-NFJ=xV3llAF{!W=Pw67eg(%rfqV@Gh=-sPC%DY( z?~{8cK-zqi_*P5) zt6KbHBSxiDTiatF(+mEChjR_;{QNQ4mRy7O=mOKc-!k$4p<4lYT)VXtxGvDO{fnw3 z9%#EFfOm5Kks~h1{U@&%-b0IGarT^M_}hs6v&o`H0aFP57X0g}1JF%CaPL>Y1={4) z;UmCpXYzp^xP3dvEYlj&a%0T9ja|8s9Q=Iw<9me1dYZ2|xALt_lUhYu6m z?E<)+iVk7#Pkiq;qYMDC-zMUJqfO9Omk+#%c6t6Db&n4A3IFO9`v)XI1mOF&1rG8$ zB?I`W2k;Kxb;EZ}u)x=Ur~da0@Pqumb)u)T=|O1gaBN4q+q!@Ebk_z7^boRsFgG`N zLqeQ=MZ7s@d2;u0ZyPJoXST&WaeOQ?L(JLji*!`%uxcDuLnM2$6zVCS#!KmxJx)Wf zQ}C*ZR<#HLutEPHX9^WLG6B9JJr)9m%#pF~HdDoLSS)Y8IM$0+*Num=^Ut zo@V@c{LJIA`wqJ_G`9U7@D&kAO7X-JQ2d1XcOoeSI7i$0<$T%)NwL6X#D1Gl zX>7irme<|mMV=C=`HIEDu1;ya&l4Pvh!UscrT1(f?-xCQ;1gadTU|I5cVjqP5&kep`dr~R!bH1( zq(oYICi*RaYdPr z;2Nn6?Td8Ugu@htuCR0-aN%u@;#W$H?|RxdlqK3D(k{-GV}Z*#*+;=XwE~x)Y${gW zOA+HoizN2gdmq+pWc5!|Myf4RnzB+`nHB(-X{#;8D<91&m~@7@=Q(_o=L6hXv?XQB zmnGQI1WmbYn-NJ-m%y{Yc=A)ItT~R^)`BZixQ*_c0vWVU_sWs%9YV83_0@Mhq_yuC z@;&PYcqWdiDFm&`?TjDZ!rMO~nn#nGy`Sj8F9_?wQLiWOZM=pI;H34)fc9{>wi~qlD#~u zdlJdgq^6h%2j_kp`3`cb2_DL#iwhA?GcX1J+E1W!*`@DDmmJfS({W~26_nw?L6eq& zJf#g+djM`JX8SRB0usz61HkF7t}&N*wy$Z`H25lzxmMWh-fSzg1()gEjbO0qF&xhz ziPQD5^Y%dVC9l&BalX5eL;P3JdAwA2ITsqorXEg@j~a$Ht1rV=uFq2srFezVdlEWV z(r+jBY8$j{T)Fa9zSMEBfrvNPozH*aNJI3jkdC*)@U_Ny;dt?TA*UgH=_-51H|C4rYV*ot6AUpVuhVE_*eliG!hSP2H6ho|)v~ti!K_1f z7h8MR;5IQb9{^Uq3YsN9ET)MyMM=0?hQ9jbQ@L+4B)`nuj+x%TUfAKn@MU z+-6AMEuO7_k{>KCIn{%%6Yx`wH~^nN#g$>8eW*YNJ!AKYIm)v=s`@mOsUBcnt&$v+ zL~u#8m?kN7tZ`W)CRew+f*5ku2qMF>8%2m67i7^#H{Wfy$|+)3FYHFaXK6w22DRqs ze!Ivi4od~>u(j;1I{jvhgDv$Xx^kN=e-)74d^D25MmhpwhL8+&KD3(-W8?qO>f2iN__xBt@t_$Md;`~}94@eZ_9Ze=BR1kY$Nnu72U{iWS25c!hry-E=ZerW7B&+J ztCJQo6;|eHeR%6m@JuKs)6K~kxwZa_?`@w)h#dHxwJ)dMqtel4BV#BmVS>d=KV)Ua zZG3+oOf}0GfaRWBK@$5iRu<+S;;vn_Y;UjOA>+;;4RvtWPEF**yYQ)Q)H!Ej3q{z+ zN!QnpG|4{M+y4o!IMN}H-jG|RIYa+uLa6y!l{r-pi*z*+e((P9XXt zq;zUVc1OZrbd?_{c)3l`ebSV_wU;xX*-|d?mG&ns08$Q;%DSO2j|*rAGU0jYcja9J zBoyfj=!fX?gTKztdvvb9Gy4JZ-OdTzmURH&1*B41yh^gfi2i6&K5Ge1hR=?g7merkWSLqMrgj1ljwW-q7YY-jt^ z&wh;M&s|m#`a~YzKYXf>UsyMOi5ZtDOtZo-M?zw)xuvI`Uv+)buk`*RRH#y=e=}ZP zi54f-nIU+Ohm!nzeb{NI<&0ofk!+INt0U6vt7Ogp!p|Qml%8II;YY*vnQB5pS#!5C#6;@OCziWvCfS0JD0n&&+tT=KwYp}2W_w_3 z`@$f>8Snm?j_+(K5$J-1SNo9gScC~^_-ab-VQ914^I*GQ6?>C1$nze zX4e`xBgVyq`a*Dn8!Ky%1fJ#G%6Z7;Dn$yFJQe8R_{LeKfXkUqnTJ@2y%y41)Cv%z z2G_C)))nD+<&NWVL7&87$Av#B9HLitVg8m|ycc3^?bN)7fx^cv$(80gFj&lU5Z|!t zRlRMPuI#1sFI;PM?_-|CNchjE(6GR*`p;L%J9Zaz=2vF9Lr!h8e#NXDeuR2QOu;kW zc1#7g%BQsTM{r3z&AP-~U7<#hfAqxmGwq^)KF`&IuC9%dV#t@2YGF02r-1nD#bEAYGryQAhW!-`1EsDa&e26?;WFY=_DmSz6?Ww9^9j6zxR;Bl~c1_CN?VOHl4<59_ zh<=aTufeB}j+-3QhwX}!1r?KmW9@aZhH(2Xi~okO-GvWG;a~ChGNR9nu2goz70-V? zK$a~}{sXKJlIW{u_D!X}@JOs+6&)I6aPqw}T=8A;QM3=5L=3iv?FX@w^1$3|82eHl zXPCSGIwn7qg{9}8?oE)j|v2LaUmMucb*DTiwy=UT047##+3hhA9rCin8budne zsoSPGD;lb+*4)e+H5UU)IR+I`NY0=m!i)lm^W=Y8PUY7)icgc*e0cU9I^mu0#cz-D&C&gk=0E~7mk#wHG-i=mN?;in1nUXu+mjBpUSr3|u3 zFi}!_zsVIGMk+7%-*GuOXWnj^X^{0JdqK>Vy`F6U<)sc4ocr?oEjwezVHu|S@`&A( z8wav!RyY_g8T9@=$B{J)=av(B24rj%(ytCpHv;9UH8~Ilf>DvGwtq>LRepjNRAHWM z%G7hgvt|fF%*O;t0C$`#)L0Y<6Z?9<+Zmf%as@@IunBr}v7=buyrYu;4!qkV_9!If z7fBa|1?^fFSRTapvH%y_iKBMJi+otExJ!6B?%*vw556eG)O^jXPfc0M9j~a>h{GVa zpg)H9Pa9%9-ZLwEVT%khi}rgp+vYuI!Cxi9LwOTqJ`~HP;NGetQ9EBy6&cU`U(gmv z-!-!`TW@jUAJtSN9B^ti*}UM%6&$1H0QNYiP_36dbgav>T-{G^a_&D7`*?+*CSc zBv>~a5s?xIBV2LuyL4I*Oi*J(pPDtrqCW$1-w(sbT|4i4H8NqRqpX{|*M!~cCu%!A z1Ss3YZZ^~Q#@vMfWO_0xTO!we!{6>kvY)}_PwAb37=p z{|UGYlE>ic%u3fb=8fX;YnO1iQl?0}ImX7UkGURL!a@GC+_E9zQ7t@fP$_#be3=N+ zrhCYNu2zVvW+0`EP~lgS;oj&hwE@r5|9X(I58fGNVciO>QyB?Um#Dt1yycZ1B+iVL zxfgIM?bTDpTPXYp9F{h$yE-anD~l7HGr<3rh{zCoM@$oir2EgM2M5aGmFuG0voNH{ zWRFd9v+;%G-80o5p2T@^+|Cp6YZ6&o3fh=sII(WM${LG1fFQSqjn6@5P`I{dC%vL<$GvYnh$ z%D}hK+|?7@hpBY8EiXonX#{6_7oksQgOU6DCor%W`2eoP4!+vA21Co! zt@GvicZKiX%C4nK>G+#<8DBI2VpWPOHOX!j4paIRG^OMlwG+;L2NgH8QIyyO>ljk~ zoz?1hpE2EM_?LUbwu5M7-bVp!z0SIAClmuYQ0{5c`fR?Ho^^pt^99#s%Va6I@D-Tu z_&KuYZNGg73&=MLD;Y-D(N*C3|KPoD;P7G*ImTZM-9A!gaXLIBVoO&giT6|YdfYUcf zRv5da%Msd}4AnLnWC`&0u)0uM`#DP_P182ZU{Zfnq{>4vnB7A}y<@IQeV1s^$H@pm ziCW`pm?pb7ocKD)ag3<0?pQ>Br@C9*?KAAwU2{qPD~@eltaY}db3Sjo_YVCbO)6oA z(@p;`br*u@_nlxv`X<{iKDQz8gY(w2U&_S0?^_A}lP&R6AG&nGR~G1H*dfGN7v=-J zRe}O^j1cSb2c)MAHm{l+Q4GP{S9gFy2EQS>lFKW$>F!mhbIFFM&3#{ z{;v?s7|lRw3-byVvgZXkWGYEuzK1BeKaB@H+E4kA;KhaASd$fs41!yN!5Cr<1CB zjWsStRA}os`rn(<>7G$a7L4XBaZr+&j=8)M|M6YG>SNzRD|eJ_^jwsHWq@CMEJA+9 z=FUCdr0do~M?7-fRV23+JX(`MCnkE}c|pTTuaA#zy#W*30_(aR^^{qDo1gdcG>S}s zYHNySmEoKAB!lJK!SvWaBh6ur$K&LbrMQq6mE+2?+I{$TnG4hi@r6izM$S7^5AX#I zVB~ruTXs(o<#L@T%`2%(8e{NRjk$?6^K zoS2^h#mZ?TbjxU^kT-7M?>uGYP~1?;vL;kWSiuc}j^q#1pu&jW!k9{>O45%K;WGJZ zU?s~WYeSZ>KsHXIFUIYtvuag!$}gR9<4nP@j8a-9lL|WAr=*9clwp*Hf{QCOfG4wS z183D1gL^Oc8d7UBHoe2d_{4`K?Y%#Kzujpv^QC?GI*@N_xXK+Sp><*zOYe9tzn$|? zEHPuZEOCjHDCcpQo4U*+wQwC7kqb96zg&Yd)gWBy+v(8~f@hD!S^}--yQ266?p2=7 zDS;{qqQgF|rNt7qEbMD3g)Zcr8ynSE%H|6*HVP};Zs)t{#ZCogD3}DOh*4&H_ze~W zGZ$9wq51>b7Cb37on`6iXo0uQ+`N7tRYt5B*VgQG?LHIwy&W z!kQqd8n(U5J{9Rc=f3+q?Y=ZRH4$lJSH$+BDdc)VnyVeue47pGdiQHqsV&NLCH)dE zD6F$SHD!+qHoNQwjb4P_(YSN74RV#tvZSZk#)DMya;s+sYa5odS)6?oVhQ*aTu6Q_ zuVKiaL-Z7;wRBBZxD{=68(hPxX9J~9+<$p8Lf=au59^xEBKZ!dK8RObjU&ZSb+e2_ znW`?M*=J<7(iin^l}L_eFnna$jXf)MoIQ9X&pIQ4%YWH z;v=KA8z@TlQ8W!U++z}6GD-_r2RI-<6A-*S7=p5S8G%e)h@Vubbn!|G^t2~ z7Wrt+h>_f_YQeM5uFWHJjeO(1EpSYa76R(|!wA84gy*tK=dy5_Jdw{?UZ^B>`%YL@ zRW2J5RIEGL52T{~G7?zIe`u!W=s>^|LeV}I%)|Ll4*{%I=qTpgBPzj><(VI z~sI{rfSxi6M$Y)5&aZ#H7{9Hx@_rtB=5FPK8@oNp%g=M6b z=~JcA9)R}mpYfrOC6->~P`BDnse18=+AUTRcj@%wOA^uJCa7Frl#cQ0!;UrNT^3U{ zOjEfCuf-9S(U9s6hLy}<%}+n(phy!hUx_f)(JNRG0TOH-kkVw{E6qFx<%InTTH03^ zC$ZLDcp(f;u=(8!W&6RFJws+~zD};+hGfykS`2bO{5964=k)MnA}R{cMT5*5ahT7q zA3zCC+vop*0RKNN=>9{1**X3f0?fcj|DQ(k|A2rQm>B<~&G7O|NK+^Wnws8YNfd&G(AQ8S3h~Kik{^~sIN-a%0 zy;^QpWF$%pXDKWX%)yc!o$XDGO$-l!!>KII>l*>o)z>rr+wl~XEc~^u{e3Uu$(sE2 z(BlgMcX|*G^z+LvD&z*2pHRxq&H&>b8-VH?fYsXG)!W|G)Bvn#XuEv@vHHCJ!4+KN zK>6b!@lMVFodgPzT$~;O0;;REbsoRJ(D@8yp!JWBj!fSNa0o5nfdZ$cZ~!7oYF7C_ zR-#TyT>hO!91!Q1FM5RLAk{iLIq&HiJlx#r(lS}PEKN8bpyCmgK+<|#-&K6*PW0mwDr+Wsv zW7HS=gtz8)@Xq!w0-rj0AP_LjemPy}PkM1ySNrD&`%i7gkdF2B-#eipS;$SLz~dXR z6jTrBrz#=OakEh8Q2WLP1_uUazyLXb{BllKr+bjh-Txu17#e<6dS3TW4vx-1>bKcG(1Ws!HnDbD_{?BsHYAo}Qavv{00|avZ zyi-&^>VVXJe19Ki@00YYPCCf7Guol78sdzv#f`znbux{eEMLj@~CU2>eg* zGqCFH8q<1x>VJ6?zhP5<_+x%zAAO78epHE$O-)}zvQOmue@1LA;2R!4A?_zNSyxwZ z6r8=bfkS_SEdhSCwM6qk$EJUMsv2rbYdQ!n^^IS11Ol{*1akQyP~$7xpYXQd6|3Jp zX08O_`H@A?=Wix}^o@=6-*GoC9n&^?bzxIfq<{2)dTwWZOp=`GT${*)Nj zmm$NClO(LNvi|T_SFD-h(q+x;JZl^Mv>L5a471np)D5 zUal-Y#;#PrKhwrR^;(=YOMz7!HUe&Iz zM1IpgT7=8|rt30tbR#azAMjDR!2LHiW)@J*4NTwY+SG3PHcfqO_VXgy^Qs!TCG6#~QlfBf7Kd<+E*x>L7mK+v$#- z{J~GSVTnBJ8(w49{X^2zdiyOKS5vbic%MuD8)0-}qkn%{{&j%RrF?Ju9@7B_;t4nv zr;>_2{VrgIEy(lrK_PwC-_AkHF56z2%{O`00CelvDHId$bq=$$@a#H3s z1h;T>pW;0!X}}Jg@}O>(M!-%ID(*$*F)s7|glbfGr*_>()xD5_>YEikCCC9p8P3*m zK_>46D>G^~@%EI0ho`(CI%!=LDC${&7~T@6?+GdN;_gmNo7-K5nr^v$X!(Ay7>e$F zYwtZ_C0b;i)vQ|Y999Z$!fz$QS(xL=)!jqNx`vAM%md8IKrZu`6mHIlDL^po_l$qEL313%0%LHmPQ?;GP(Bj<4I2Rwo<5ST&r{m;wZ^r z_}4nu-grL%^pu0@GxXD-e-$wAz&stOYa49AuVvNAs?fa1;@S*TM*DOb>#sXxKOrDt zFf7kVLR)aW4E_^gQ5ndtaqJr#G_r-gynbhIasIw4+nQRFAo z52;v&v>=b&4@Yv zc5BnkH1$F)Ba>pfts(9adj6Hel}*%2dDAMuo#Bd@m!w7nUG7ye$Zl<}D%>e+(F;Ni zooQ?xx%l|U#9@ffK5F06KB|_Im!c|Pgz2GAPcA$KvkW}sYWeKpi-qK8a%i^+b8)33 zRok_S=tp^)WAWmdML_yh=|a_@nG@ixq0oOzqJ`?eJH$~Wb23Oc8kG41SrKZpBA}tN zV@tb9>b<%?Yj|j0Ib1KrF}TXhSg15JwxrmoB6P_-8<2u%X~BfN?wk znugkZN9E0OHXBA2Yee&~e_OdL&Yaf%JE&eSen&@zP(3?)kp1~U>7QF)ay%W{759ii z@|YOg^<#>XlnUTT>nIq6X}HSqSaZ5ry=?GfBgkbHS#>OZf42HUgt**M$j_}B7;p$i zNz8J8cHa10u)TO0+&EToF96^yQ7J7bbfbjWw@x2$ zs_;_XTLw2>dYa(gk)2MwZEKvBal7+G{2v1Z5=D#JEj#W?oZH6;1bH#dw^S_?KFquO zQ7|V{9yu1Q;+ly(1(8L+Go^+H>-pX)G|!2rOn5}s*&w->-^yd#%cq;2atkMo8E7wf zM;sWIQf~w|;__xJj>|`EB_g!V(sCo^5P#Sp`jS1*eeVZ_XQvPy50R^MT@Sl}2T8(m zpQ>n~bl1o~*54fsJF!-nP#=U`#u6p8jP~#{5XfL&XavLBsbK1@f*z=}ie#c`hn7pt zneC2BdNzdqELvKeAk$pY>a^nEn&~bg;iO{Wr0q| zdsgwdChW^Ln#Sy9V>-y13)kc^X-a>-ee?_^94kWCylJ0-*T#%-2w>j6K+LRhVoE>) z6vmtS#kOyvv;|R{FEUiL+d3sk8fE_0OA66+O?h$UYbyW2p_ZtB}=^fHsGPkXKOvyC- zA?B;~_y{PhjDcL@*w%YMa?Hqim0)PDn=#6UOV+XpvdP6PlsN;N%-`{G3^=!dMwpZ| zOshxWf=b=ptc@~pHQ|$V1f~2o&qozL3>s~EUS9e>w(QqANXJ553wP)Ih=ZR zyxI)bH}*W>5rLf9;*7V@&P)fzEnFrTFrC6<2H6(`qgP#xLmff=L^Mxr${bHs!)yBq zmCyyRFMN|E-eTYzqTvLE8>@73m4+KIq1yc$BJX~LYHSYH4ZSW(0nqbKd|=rxii-X{dJ_OvCScNNSTtm>H{A$T7uSF>d?D|*%Iu1o}??hhNq66LT zbTu0o^U{_la=sije3~wDiIm%cH0$mt?1i3;cuy#m0K(qxeVLNoX9%Z#rLe?1sKrH} zt9KL+$uqIyK>d;8c7Kd;x$+GN@8^68a`b9x+3O&sdRk92zIMk^>UduVb(7hF#Qrwd z5RP`^kx%$(TQ*7!{%NM+m{g}0?RKTZ*by7`sX3W7$=mpG{?rd*%Gvl_WcZ7qRNsnf z?;3c{Dnj4nWgNi5?OaRbC4&B*i8u4GoKoijXha6ZA?~ZI1+4(tb_V%r$iE^0?foCb zr7FcWL>MdS^TxEr>U#B$;*H&q%G~`46`iIP1uCYbt^IR1UDY|xb~=OZ;yJU^&m1;( z`H4XJPtU?J%kI&Z`F|bLC}r=;spp*Vt|6%xAyJKIKw z6ZVnIrbQxS<2X_lnMR^gQNZz{*>XPD3BgoE*3)7LeSxaA?|-%^wF2c_xN6=?B}AXL z>x>NYLEDKGsW_q-?peRpN}?&nt2`7Oj?vcYv!w{`D7+8@ph1q5)-qEhBodN?Q0ZW%}2*ot@1C~wDo2RFneud|!<=}$8 z)|MdGY82Ou?Q-ar?G0+wOa%tBBf<@T<&j`K6I8S1~&&*w*sad(?) z7a84lS7%_~xQrCya6?-5r`8GBF1f{=OZMxa)y9L~S?pTrHx^wO?X`E}V5|-ylv`)E zN;QH-D_;JeyBZ(;l;QMz{qLbHHlIDikWkIAM?M&W=lc0>gUXCDPsB#E>o3_-!5eUJPmA=KcfM3W!erjol)YHMO#eJuq zwg`S1@T^#G)#Rv42p?%!sRz}`)-|CuXCkdJDH^%bji5ltu=t95uO2FJh)UPg%A6(< zNltPna)jIdmV`w@c5{IEoWn z-6c#_*M#Xxn|}ZHrTnz;5bTH1gu3+=M1nyvdyLFa4`p_kCfm4-Drq*AGbo1x$| zR3ODIUK}uvz`6}YIHob|A@`XCQVN(a<1`eehi)Y2< z8kyEI=0O!(T32DmV;j_Urr3BccI~d(R^KkL4Ojv1(av@%Q_xzLjLob5PKtjmv_a}o zx>Z!Ua3stuIWJCazJZuM$jSzws=db;E|uS7KNeUwHA<}TG8aDGx=KB*ZhUy#E2-f& z`lsahZF_hUmD%QeN9)Ib-j*CRfF_C?OXM?fpA|+=ncfe*V9nkmKCQTlO&8aoEp%?> zuDtmtmkp+uFv0Ly!gVcgBbPBY{aW!*T1)46EDt{~@W^r+O!zf% zi6=BeR>mr@YFv;7|28a_!aw^~VrU4iWm)SBs$cV}5!%mEi$BeMuNHUjv~^%N=nXa) z8xHN!vVCV>3(9*W3?NAg)o8*yHSF?3D`oI%R#jN~FBDN5nJ{dV(1V-7R$|EdX<-Bn z3(GRZs9pQh>xQ=yFWXhmh9|RYzDNTTbeJKbC)~mo`Xu16=Rw}=Cf$B%m@2Td1*@Bz z7oA(u-3^J;Q6xZuJrSmE=)?wFmsA6IJ=$QF{c6O;Sv2VQyz35%#1xv{2gXHp5^kBB z-6*aog{8&V-HsG}u;L>kZ%Ew%5RvPE;|OpWgirb<6wvic_~dDYZQJcQWXUuDD^Fx` zTm@2zJG<1T(IFAN#zox@`=g?6%FG}uS~6z=)YN>|4`lnzLGq0#49J5%8d$+((>W8$V`eKyy;hA!-nj0Gaw=@%1T)sz!*lI-QA!3!3lWOb*Nxm&!mT;#m zl^9tCjM;|F=$`reJZ8N)fn0)oY-G(X8U<=TGsIA1aWNNScQ!ATHgm~2^GZ>zZy zgG%5QDkJP5kl&%YtS$;+d((NX^qtg(TiwyHZ7}EM_yNcvjHG(yLR%(urGLJzc4hA+ z$s+=v8O`+O))w{Hbdxf>zpOM`e zy=Tb|@1_gzfzBzM{&Va1Kjj=~*f(0wJ0Nw()it3}ILvT@(kg?H1VG?6D7Cw=Dur@` zOa@#`oD4k{;Qy*tkA8~YX2-pEfs&>4UFM+XxF}U;@M)96@0Ir$xABLOfT2o98&uAv zut?`;<7O==?nQ6TBIRzHdlMV05hCikJf4p2sF2D0yD&BO`!#;F*EKju!GFaQNSV%$ zwNvAFn^v&1I8{VBkn(aH4bSVyTFE0rB8vIvNy)*Vf|c}HVFgp?_Z zXtv83KJ*25AB;`^C%(7nII2Ann6C}OyQrcuk@XVa+VZ*XNtq*<2`YK-x0T<2t*yeV z4x5Z2LHf6fCIm=py)h+=#D~Rd2)>C&!tAi?NZ^?F%Lwj;wMP_VKJ9ChZ|@1cPT6e{ zY1^HV0Cfx2;*pyev^hv0Hek5wI8uT?8)X!G`vQz{&ne@R7X3WHxb|#oF$`9UkhhXg z3@B0;OgEUokE}1m-F*ET@6>PVmMZg{rln-cp$PU*BuCtoTgbMG`YwL;4>XIhY+AYx zTuH-y-!UAYTyKWhu*gTaF|e zB}L7cRtK?~d(O-oJArGPIt#TcMU1uCtT2-v(%;b+Nq|smn651llR{s8{`YhnK8iD1 za>pxvIzxGZ^t-qj8f{m8re`M7lmsV%1Fc83p$Q>nZ3(8L9vP}k_jhreq|^Oqh{a6O zs(#;(_>||tZlW035hC`TryV%QXmcpgiMtGA&{p?3+C?nM9#$nS_edeRyu|l~*3D-_9xu?V&iKahYHAVQu^S zTw(cUvQ_Hb@jkU++O>tt!zK^K!0(*y5e57wG(5B@ka2X$f7y{7sEWOmhK7@jP&`Mp zrQ^8*^`h$CQv-=dJVleqF=23CYVhfpjh=lAhO%pvp^y@Kx|St2Bfuw{Hr_ss0-BPT@h@va``CGt550jP6tl~BT6&M!`07;lhE`9MgzTms zGPaZ()4;SE2`Ncgo*JT}$nU9)qPvoyLH1)=BcYz4Ua5uC$!3n?KK1wZsAQc*+qUID zD6cu%Pg245{r2B8>q_`KB<7TjaZFv6We+@+Qu;lImk-%mnHl%Yc;D2|o_Zwt3ATQY zU2ANB-4?wr%!2!Q9#Mu(HqWgeI6>}6FmADZoe(@?HR`RTPTj#m)()&s6bn`%`{lV{ z`}{7R0_7h*;h>%IPF(;hBqP)nt5|Uxa^KhOU7H2INo^jL9qv#Q-~y5X&dl|QEpU!*T|q7BYhwczKY5sO;)@IgA)SDS{rajc0^u4b8@LVVYhbB-lQw1?0?><)sRE<+HNjr#(q_1fZ9x|gf8cT+MZ};iBV+> zs1Z1r;zKG!(i+bo^5W}J2O?r1Y05iqO_=99q>SAId2&Er(b?*5nVa<&tst=~r46|l zFtvLd#v?(Q2M3<*RU60_K}EpfBB{nU>2!{MIKeKV`h>ZcB!h1;oI@0ld7Q3^x@m{1 zw(R4wU3UG59M3&oi$iQavtutJ`D8wmP>po7%y1O=_~vl3KVB1y`$Z*M?oS#&3WyL5 zrQ@lT;%boD1YTiCiAVmZhg3mYCuuQv53Y4Ew>|@wk4bt^l~t!#7Q9f;CEv_m?@m@d zk#>E=X;tyzb+J;=kAc)kV)2sd>d*olh!)h^q+xa9K!Wp~X^)o7#`x-wnHO1!jOP(S z;uAoLAgjXblcHqku?5x5t#Mv{8&N{$X+@M29Jf&v08CX#{K9D=Jm9eK@+h?9dtwwN zQ`y4f);A9(jl;Oik(DHZrWkN=b%au8y&K_f1PV?s8z+<86SL zEe$m_r9>VpsWnpKktDEe&Zrhjc`)jAyC$7{)~y_hHit$hfe#MeC59J{x3GVMf_;`< zB;Y}8wA*e0k$^pkEFlnS%xi*I{e zAZ4pQetEUPDp4Y%#BDGo`!~m-K@E}X;FyTU%>v1el;=L6GxmlV#N~HS57gz9_He3Z zw|D|&bb4}Jk(WbOufxf->=!7qL%aTnIwpT)mO-6DW~~tzgW>LB6(%tRwlIpGxkkcx zk!jWahB^TI`jE}cb$(QXQa{|D4+rpv*)sQZPFxN*jVDiN#m>u#+gal5e@02Mz?i}F z8t}k{uTubx>Zr|Sikt-c$N3H0ux1myJl~}*gQ1{>1f{5|PN8UAjC%GWN!zHe>5G0G z-QUV}Ssn5)Jt>Zm1Z)HoZC1+z94B24+Nf1vHK~vO1aHiJ$?oEEmFu8R*)+kh1K%-0 zc1I%x`68g+QQMQQ1;}yDGh<_iKLQ^`2=Z$hCcbkzsVH4xK@k}}yZxQJryy8xB(umm zQLIIpx1lJE0sHs5b!u-4GO{WGLbk$+{1P=&$WFIjqI1@TmXxSu(BNVlZ zvw+rb&a@o_B{i4OTnmqa8bLkmj_pwwp)D`XfVO<21Po4-30;&_wY-x5CvI0Sn^Atk zrzG?Bx<-TfY?5&vdPyALKP0kyUjc+=OAcKOFyY@Db+1)H4!@LEw*OJ!T3id zk0_lkNZ+}2$9lFo=7V>tng8>y8#+&zwB}crpYAr!_xhQ3_Y4p%m#WNS^VkNC0OSda z@RB^Cz`XrZwx_3|U_z({cm4S5p!>bFmA0fonn$S)v)@&KhNN-MYFO<3s^y|)i8#Kg z;alQOI$f3Am-U`h7j{~EkV|BQS0mD;VMjRr->sqv2W6KyAr38Vi5>_rk*UEk)E3+B!*vX`IVMx zfkigOBt?F;QztIqL9}7LAn)qBe&R$EbTjYW!=`43aLdYOt>lpzi$$He2Vx-6V5o-A z;3Hn>k^7PHAP;dn%6DZU1~%b}DGv!ZP~L2C@v2L*P{aIZpT3WWmQ$lyG=6H7gqkCU z=I5zzsM+ppY=hz#Euewa*FwJ@8)bThwW=~qog7sO<^u2Quq8{T#Kiz1~y_wI6#F0E^W9hL0w{Wsx zhNdQP^vXk_sVi1oYaZbUTDE))!}VlsuBAFt=A^aw`bg<$9{H=}4w(>VRbz22I&fO^ zJETwb%y5W8m9jXbp6D5x-^0&_=-jBq4F(r8fg9k^WK4!M=7V}jn1)KH=5jrg&ogHq z!MHIbm3+|T!A9CYC`SErCy%}3p;FhgodM)Kj~nGr6q4lc1xf`9aRH;F_SDOBBz4@q zMToB&XpW#(yU!pQbj-dh^pmXu&5-jS&A0?SSp|lu`QgDt^3d$81(>aRgn#P8zib}p z!$kDm@-hVwd*NmnyMDAy>;Hv&%Lu*gtnumnPix;96jigWEg8W90VRhaBbgx%C^?FN z?OnMXFjl<6J$Rqb?4c_99aQwv2|-+S?eKyYI{M^MI6ibK@*>!*-CW8S`Pum3qCB9 z2gZ{K!L*F4kWbd{`wXH9cVIM~K9@V6d67E$KdZ3yhRcs$dC8CMM|?oJxk^8JEKuFr z-{C(9Ey%s8`c9W|O&p}|U7@{n4Ni!rsx5^0doq(4!i&8w#d44G^ZcZcj~ToH#q1?%DY z+nP12lF7w;!8b65;wDg;_f)&z#y^x@Irj3cX!}T@d;xmZ?#kfTe|=0*qAZ)LGf`w@ zcuXAo3Pj|;)5RM~JDu1S7MVYRljX@+8in3tLYYn%9T&0X#qqbcbB{HQF+4KsRWlQp zcS*@2e3kkJ;V9lAQH_jjlfYZ7Pgd$qYd1oC&NR;^Q3-3;F<{fRAmPh=Y?DSoDY-<7 z!#<=H5K^3vgZo9u)t-avR-`3X#3IkKD%I-EfX{MPHQ8ySkabDPk2;@=7pusRdL@ic z3G67u74LhDM|2mNZpI=V1%0`#_<{@XlAD5Sf~VVzcS|#mm{hiLD;kJV5-Jw&xVbeu zgX=!`75>Op9!SrVb2z+W97{VWi`hIcZEgv|0X$`CB0E+?JRk*w&`Iy1)lHlRZ%g24 z9X8Q5-ymUm*xozvirm;U8e&C}kPli^*WoIo@n-c(ONxwIhOD_Bg*y9LhO-vws~c1y z=BtgkK_lbAs;pJKK6r87n&(nko*mloK=IY>;iw78w{8*xiLQfCFGN*9d+A^nXLlO7)bJV^ct~$UN zO2w}Mw_QwB48XQB_{xL+X_yNq{UzC3?uBmYq%@s z=`fPjj8|pBKX4Jbb>s7b=XwT0UmOzX-W8^Y5Tl8F?DX8>uoytff4q^`>CaH zb{@Tsyq$JN-HdKM6RXh0Vt2WtjQV>#AW5yF-*Qx9-8U^GRAQv;cvl_N|1+5y3)LVbp7t85h~FdnhU; z1qW~Iva(|HAAW(~7#K;LSCQ!5yW`v#i8tC1*1lM^ zM>40DduI#)TC=;)>fpx~3c{8QX{3iqu7wARHxZ+m%QpM!s$c@#fB?p9{e4HHb};$R zbKLIt)~6OxO3Y%Y-@cv56#%UY8>)$5X+O6=KzQA1;Ctm|oj@no2rEk|-xevBE+?qQ zaD}R6H~~>c zc=ia`zFG(+U5lYNl$Rtr#sslsJRJSYb=ue8aO$?*-?LCdffoSPch6NyymJW64U#pK z);FlIT@d#T`B>dkm{U_wN4H6|k7ZAXn0-3`@h?Eecm$3}!lU(Mz~Pu_ZWn zJp2RNX@VYHDGI|%xQ9kjQf)iWNB_|Eu9#ok6BNHCDJ~xsF|BpJ0L)D!;{F80w=YHr zT1a)1UNbpK3tfs_f$kbTT7S$}6JYOm(|>5PzR&D%!Tqh5E^Rf(z{NUt!~Eo#Fxk_k zN}?PBo~mcz0r}gZeIr8mY`p2-TR<)RxvY>7KWM@d9HihPkGtN5pkG! zfxz>8sn7ggKB8Mc)y0NtGQ(IUW%{JfjeKQ+!yJ9#VCc>@aqy_2CkL?I$O2l|^l1kO zMbe*XtoejA`w9>oJW)BlnK?qHg{q1qs4;M=YR6iffi`g0(5n&h(k1?)(_c?9rXG|k z*S8!(+j}Y%OSk(mJSk|9KvXlb5jAc;;7-qsTuckWH+qcx!sGUQeE2YDCc$8KS>~J1 zZ`7eQTGI#(C0{Uba_Aft_Up!=5B2$*00|a!8{Kbd0#RvR8gSYkHAm*R4hcv*f=do4 z-}yV!otm4p6XQrvgI8aNNP*CH*_?9~!3NT}3~sN-u9NJO#Lz3TC-%CummS4dwfyfS zgG48;PnfPz-oz+n*26$I+E!dt&E##R%m`ci=tYReU%X?3631fd=iOv-!%1(`W!Qhe z+P0*kptjd;7FH?{?o_Ib6=2njx8?r5ZYAG0)PYK0y_NoHxWKF&OJ;2JM$tTjK9poG zBHc?`h`L>W+aj9j;JB{WUu z?0xI=gDA$={|cz7EEkYWc|El_iuk#75Fqyh0M`E|NUsIA^ zCk=e_nzVCR7q^Qy4rL$p`$f_GMX0b+P49u)vAsHeU)_K(ip!yTL zFZq1+;OLdU^4p~CsW!E!#T`FL=~Z;pEy8oB!aePRivG%f+~fW^K3Uyut|aJ5-T=0W z%qXK+D?h`xpQ=`kFP$Y|J;v)%Ya^}&x6P@?P&ye^NL79i?zvE)t!sq2bkhqSD?iDX zI*H!?Q^`YDGd{9BZDO5rQcCf%;pA?#SYj*yuNqcXi#O zxl0jDqMFhVY)71qW?fiW!3Aas>j%v3JvdMh!(C%j*3o>`r@K8x8(jhm1Y5@&Jq`{* zV?&W}5VPko$n;ZZiW$0R8pRYpj>2S6S8%G+FmotLYS$unqnB+v?L&?dPnPIY_D{FZTPya_RNqk(AIWoQXd)*%ns16a#)*74O5)mt zYELr-0)Ll!XW5L<97$cgcZmD79shEqq?wbB?sL0tX8$Rz?RjmB7;FoCta`hbB$yIL zSKRV^IAHX^z-_jlWFB;=2}+81`ABtdJk3ukCbihAiyJahdAS#QK*KQ*h!R&k;LV_D zW}`99c~w=_Ih?9`5t;6;uJ&=NhKH_cXFa4s$@o9EIPLZzS+Hkv# z+j)9z*07woX<$@%*H zoON3KcEWyoE+fX`l4pBaYl76BzcsNtJ2#-Uj^0dRoMedt(=CY?v68dR* zI)9{6?1xwSn~%7k7)X9dfGN&GB*RH)1tw%^aZg9lY2TEpYGuxnM- zt;1{C%M)0uV|t1E$b2t<40tFgI@P#hMpb9NY2jv-V&OY~Vuis_Q;EKAwsK7;)wWPE z(sBaPuAgS4}7Z;6T7PT8j6GR@yNaHnx=Czabj}S5<<-y!he{5ZkF3EOX=G$h^$L+DX_Ou$>-10K`OTvAFm6X;4Ec4b!?`e3EgK>2sdX7PS9=Yn}JzGE3J zA14eGjqWC=a1!IsHpf(Us8;E&Z%76NY$_Hf=T;?@Q5giiRm{~lS=(>DI#aF4agxEL z`K^q(A=tkDEQ{YNr@I6QJ2)Rs;P@mit(?qkHNbXT%^djAMCbyzT2VQ%-vvQj?`$BH z)I__YLMRjRb7yj%fWpM_;3(qc{Cv!foks@o(}HjL!F1KG-=n8wSHASm3fn$W6LV40 z27USU-cm0q1$d##hX2vPX6lowyI*-$Rdu$!kKcDueTFAO!LQsfu9k5xFCm{7b{08b z^y1I{I(>^&mk%h!J*8Hey|>dHp?JAsj<20Ir4YRZ+XjF8gXjN!2=pHyLI29~`~N8l z2^0hWJ4>2Nnil-C@WaU8HzdDV_52GmlL8EhWBL?EAWP*jM(tc@94aJ)bjcEbf}Sy} z&l!>_B-yRfb>gKB*POTKS6tx--HaiLzIwwsF0$7K2eMx%3tW?Uos$&ECm_!v+Oy3t zA8lsFwfDV{&rA=sN1bY38(@$0HuTW&`>VahL>DJ8f?y>~{?*Z9`XY))_T9={Ec0#_ zpe|owH})>XVbrX%_8`mC70nmXsNVh%4!VyL&w;zsa6SgjYx8mlZV~RWv z?Y}l(QfQb#Eo$mh2mFNvlxH7bY!kp$L!X>RXa$?qmj$kg8Ot-ozcC$nl;ff%^Jni1 zF7?x#!)ov{{p%E&sBO)8lEqz~ZpKrBws*(zMJg$Xg1O*tA2+?23#}nV)($LBzuQ$? zkM;Xj-AL05C0H)(_~e?BG0}K#M{k;MXKwOshi9@+L|gvKIUzU-+XNq_N-4jhfG2xy z(jv6>F^dn?hQdsM@EEG?FpOgU@H&h5@Op5}(~H5@)b2k$M zML9Mv`ovomW%qsT5pa$%N8b76m(xW&VN!5H;_hYjd&0+;^@A&Z10=-=>RE(YDM z*sy6oe!Qwwbe23Ifs@J`3uQ?5_^Z*eeC`#MTZ?*(f;`#n^=Z74Z7Uk*gtjvavBkZM z8QgO%MxVX5J7l+m``8Nw!t8cY9dQ`UQDaL^6+?bimCLhSGM)VfcttJ~vK_f=z7S8I z*XBL+0+^XpE^Gea4HZ@e3*+rtVQO#;<;!m5Lxx^oz z0S4441gT5Bcv5m0`+PkV{TxT`Y63kKv-mc}9^C4|L5AQ35XkeHO&KPCQ_egQFnnE-tqyzGJY z2sfCA2h0{btO-N-!abm#|E*064*h>CdTF3yBB<)^>}(Bjb%kLS8rVB{0W>#cw$WfiVBK|iHL(i65^r)AVCQM5kWCwL69WSg6D4oUO4!`fLJrdEuH|K+#p`| zo-hc|=l@KV5EK&>!CLjw0}l1J`FoLnDF3Gp?2x{%Z+aaPV@*ZX5g6zysoj zg=zwYR3Xluu)lwGm@D+}!~ptN{>^_dbeibFZ2yTO1xkUia~zz#uxkmaI%B=446}hl zVL+jO^e-VEE}p=rPqChcJA1phdIGU{)R!JGsDq6c)~O1I?ep#BGGFg~8TP8(T2cR!UMz(po}9L<9_y1VP1Ygl%P?LTzneB2Zy4 zR1zX=BaD@>k&+S@77>HMY(&A<;viYef6H7p*7tC@REtyb3AuoLG|C=U_$l$PB{FcL z4K8rmvgnd$o$u8jcR4bL&7t0^f0wG2${feuy8ljM#6F16L8le2;LPP&n& joints) { JointAxesAtRest out; + // initialize the running transformation + // stores rotation in .linear() and translation in .translation() Eigen::Isometry3d cumulative = Eigen::Isometry3d::Identity(); for (const auto& j : joints) { + // With reference to dh_params.pdf: Step 1 substeps (a) and (b) are done in one Isometry3d multiply: + // translation: p_cum_new = p_cum + R_cum * t_i + // rotation: R_cum_new = R_cum * R_i cumulative = cumulative * pose_in_meters(j.origin); if (j.type == "fixed") { // Accumulated only; no joint frame. } else if (j.type == "revolute" || j.type == "continuous") { try { + // normalize as we cannot assume unit length const Eigen::Vector3d local_axis = axis_unit(j.axis); + // substep (c): axis is expressed in the child's frame, so use the updated R_cum const Eigen::Vector3d world_axis = cumulative.linear() * local_axis; + // record (p_i, a_i) in the base frame out.axes.push_back(world_axis); out.origins.push_back(cumulative.translation()); } catch (const Exception& e) { @@ -284,6 +295,7 @@ JointAxesAtRest joint_axes_at_rest(const std::vector& joints) { if (out.axes.empty()) { throw Exception(ErrorCondition::k_general, "URDFToDHParams: no revolute joints in chain"); } + // full base-to-leaf transform, this includes any trailing fixed joints like tool0 out.end_pose = cumulative; return out; } From ac6af36ec5ca940baa40306a4241275da609130f Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 11 May 2026 13:54:44 -0400 Subject: [PATCH 3/7] annotate build_dh_frames --- .../private/urdf_to_dh_internals.hpp | 2 +- .../sdk/referenceframe/urdf_to_dh_params.cpp | 45 +++++++++++-------- src/viam/sdk/tests/test_urdf_to_dh_params.cpp | 6 +-- 3 files changed, 31 insertions(+), 22 deletions(-) diff --git a/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp b/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp index f46776f7e..71b08bdda 100644 --- a/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp +++ b/src/viam/sdk/referenceframe/private/urdf_to_dh_internals.hpp @@ -41,7 +41,7 @@ struct JointAxesAtRest { struct DHFrames { std::vector zs; std::vector xs; - std::vector pts; + std::vector origins; }; /// @brief Result of common_normal: direction, feet on each line, and diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp index b5c78ff71..9e60f7f13 100644 --- a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp @@ -265,13 +265,12 @@ JointAxesAtRest joint_axes_at_rest(const std::vector& joints) { Eigen::Isometry3d cumulative = Eigen::Isometry3d::Identity(); for (const auto& j : joints) { - // With reference to dh_params.pdf: Step 1 substeps (a) and (b) are done in one Isometry3d multiply: + // with reference to dh_params.pdf: Step 1 substeps (a) and (b) are done in one Isometry3d multiply: // translation: p_cum_new = p_cum + R_cum * t_i // rotation: R_cum_new = R_cum * R_i cumulative = cumulative * pose_in_meters(j.origin); if (j.type == "fixed") { - // Accumulated only; no joint frame. } else if (j.type == "revolute" || j.type == "continuous") { try { // normalize as we cannot assume unit length @@ -300,6 +299,10 @@ JointAxesAtRest joint_axes_at_rest(const std::vector& joints) { return out; } +// Build all n+1 DH frames from the (axes, origins) list produced by +// joint_axes_at_rest. Frame 0 comes from a base-frame projection (dh_params.pdf step 2), +// frames 1 through n from successive common normals (dh_params.pdf step 3), and frame n is +// finally pinned to the URDF tool pose DHFrames build_dh_frames(const std::vector& axes, const std::vector& origins, const Eigen::Isometry3d& end_pose) { @@ -309,53 +312,59 @@ DHFrames build_dh_frames(const std::vector& axes, const Eigen::Vector3d end_x = end_pose.linear() * Eigen::Vector3d(1, 0, 0); const Eigen::Vector3d end_p = end_pose.translation(); + // Append the synthetic end entry so the loop body handles frame n uniformly. std::vector all_z(axes.begin(), axes.end()); all_z.push_back(end_z); std::vector all_p(origins.begin(), origins.end()); all_p.push_back(end_p); + // n revolute joints means n+1 DH frames DHFrames out; out.zs.resize(n + 1); out.xs.resize(n + 1); - out.pts.resize(n + 1); + out.origins.resize(n + 1); - // Frame 0: Z = joint-1 axis; origin = point on axis closest to world origin. + // dh_params.pdf step 2: Choose Frame 0. out.zs[0] = axes[0]; const Eigen::Vector3d& p0 = origins[0]; - const double t = -p0.dot(axes[0]); - out.pts[0] = p0 + axes[0] * t; + const double t = -p0.dot(axes[0]); // signed distance along axis from p0 toward (0,0,0) + out.origins[0] = p0 + axes[0] * t; out.xs[0] = pick_base_x(axes[0]); - // Frames 1..N via common normal with previous Z. + // dh_params.pdf step 3: build frame i from the common normal of axis i and axis i+1. for (std::size_t i = 1; i <= n; ++i) { const Eigen::Vector3d& z_prev = out.zs[i - 1]; const Eigen::Vector3d& z_curr = all_z[i]; - const Eigen::Vector3d& p_prev = out.pts[i - 1]; + const Eigen::Vector3d& p_prev = out.origins[i - 1]; const Eigen::Vector3d& p_curr = all_p[i]; + // steps 3a/3b/3c: classify, find feet f_i and f_{i+1}, derive x_i const auto cn = common_normal(z_prev, p_prev, z_curr, p_curr); if (cn.x_dir.isZero(k_axis_parallel_epsilon)) { - // Coincident axes: keep previous X direction. + // coincident axes (step 3c parallel degenerate) + // common normal is undefined, so inherit x from the previous frame out.xs[i] = out.xs[i - 1]; - out.pts[i] = p_curr; + out.origins[i] = p_curr; out.zs[i] = z_curr; continue; } + // sign disambiguation: keep x_i dot x_{i-1} >= 0 so theta_i stays near zero Eigen::Vector3d x_dir = cn.x_dir; if (x_dir.dot(out.xs[i - 1]) < 0) { x_dir = -x_dir; } + // step 3d: assemble frame i. + // x_i as above + // o_i = f_i (= cn.foot1) + // z_i = a_{i+1} out.xs[i] = x_dir; - out.pts[i] = cn.foot1; + out.origins[i] = cn.foot1; out.zs[i] = z_curr; } - // Final frame N overwrites the loop's canonical placement so that frame N - // coincides with the URDF's end-effector frame. Consistency is validated - // separately in validate_end_effector_dh. - out.pts[n] = end_p; + out.origins[n] = end_p; out.zs[n] = end_z; out.xs[n] = end_x; @@ -383,7 +392,7 @@ std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf) { auto frames = build_dh_frames(axes_origins.axes, axes_origins.origins, axes_origins.end_pose); - validate_end_effector_dh(frames.zs[n - 1], frames.xs[n], frames.pts[n - 1], frames.pts[n]); + validate_end_effector_dh(frames.zs[n - 1], frames.xs[n], frames.origins[n - 1], frames.origins[n]); // Revolute joint names in chain order (matches joint_axes_at_rest filter). std::vector revolute_names; @@ -399,10 +408,10 @@ std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf) { double d, theta, a, alpha; extract_dh_row(frames.zs[i], frames.xs[i], - frames.pts[i], + frames.origins[i], frames.zs[i + 1], frames.xs[i + 1], - frames.pts[i + 1], + frames.origins[i + 1], d, theta, a, diff --git a/src/viam/sdk/tests/test_urdf_to_dh_params.cpp b/src/viam/sdk/tests/test_urdf_to_dh_params.cpp index 2cdd44b2f..c99fed491 100644 --- a/src/viam/sdk/tests/test_urdf_to_dh_params.cpp +++ b/src/viam/sdk/tests/test_urdf_to_dh_params.cpp @@ -205,17 +205,17 @@ BOOST_AUTO_TEST_CASE(test_build_dh_frames_ur5e) { // 7 frames: base + 6 per joint. BOOST_REQUIRE_EQUAL(frames.zs.size(), 7u); BOOST_REQUIRE_EQUAL(frames.xs.size(), 7u); - BOOST_REQUIRE_EQUAL(frames.pts.size(), 7u); + BOOST_REQUIRE_EQUAL(frames.origins.size(), 7u); // Frame 0: world. BOOST_CHECK_SMALL(frames.zs[0].z() - 1.0, 1e-9); BOOST_CHECK_SMALL(frames.xs[0].x() - 1.0, 1e-9); - BOOST_CHECK_SMALL(frames.pts[0].x(), 1e-9); + BOOST_CHECK_SMALL(frames.origins[0].x(), 1e-9); // Frame 1: Z along -Y, X along world X, origin at z=0.1625. BOOST_CHECK_SMALL(frames.zs[1].y() - (-1.0), 1e-9); BOOST_CHECK_SMALL(frames.xs[1].x() - 1.0, 1e-9); - BOOST_CHECK_SMALL(frames.pts[1].z() - 0.1625, 1e-9); + BOOST_CHECK_SMALL(frames.origins[1].z() - 0.1625, 1e-9); } BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_ur5e) { From 9ff056155c8620d2bbb6ab4d9d847fbe32ac66f6 Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 11 May 2026 15:12:07 -0400 Subject: [PATCH 4/7] annotate common_normal + pick_base_x --- .../sdk/referenceframe/urdf_to_dh_params.cpp | 44 +++++++++++++------ 1 file changed, 30 insertions(+), 14 deletions(-) diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp index 9e60f7f13..6c118035b 100644 --- a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp @@ -168,49 +168,61 @@ Eigen::Vector3d axis_unit(const boost::optional& axis) { return *axis / norm; } +// dh_params.pdf steps 3a, 3b, 3c for a single (axis i, axis i+1) pair +// Inputs: z0 = a_i, p0 = p_i, z1 = a_{i+1}, p1 = p_{i+1} CommonNormalResult common_normal(const Eigen::Vector3d& z0, const Eigen::Vector3d& p0, const Eigen::Vector3d& z1, const Eigen::Vector3d& p1) { CommonNormalResult r{}; + // step 3a: c = a_i x a_{i+1}. Drives the classify branch below. const Eigen::Vector3d cross = z0.cross(z1); if (cross.norm() < k_axis_parallel_epsilon) { + // ||c|| equiv to 0 --> case C r.parallel = true; - // Perpendicular from line0 to line1: project (p1-p0) onto plane perp. to z0. + // step 3b case C: d = d_pp = p_{i+1} - p_i + // perp = component of d_pp perpendicular to a_i (= p_{i+1} - f_i). const Eigen::Vector3d d = p1 - p0; const Eigen::Vector3d perp = d - z0 * d.dot(z0); const double perp_norm = perp.norm(); if (perp_norm < k_axis_parallel_epsilon) { - // Coincident lines. + // degenerate case C: axes coincident, not merely parallel, x_i is undefined + // chose to signal via zero x_dir so the caller + // can inherit x from the previous frame. r.x_dir = Eigen::Vector3d::Zero(); r.foot0 = p0; r.foot1 = p0; return r; } + // step 3c case C: x_i = (p_{i+1} - f_i) / ||p_{i+1} - f_i|| = perp / ||perp|| r.x_dir = perp / perp_norm; - r.foot0 = p0; + r.foot0 = p0; // f_i = p_i (d_pp dot a_i component lies on the axis itself) r.foot1 = r.foot0 + r.x_dir * perp_norm; return r; } - // Non-parallel lines: skew-line closest-point formula. - const Eigen::Vector3d d = p1 - p0; - const double a = z0.dot(z0); // = 1 (unit) - const double b = z0.dot(z1); - const double c = z1.dot(z1); // = 1 - const double det = a * c - b * b; // = |cross|^2 > 0 - const double t0 = (d.dot(z0) * c - d.dot(z1) * b) / det; - const double t1 = (d.dot(z0) * b - d.dot(z1) * a) / det; - + // ||c|| > eps --> cases A (skew) and B (intersecting) + // step 3b + const Eigen::Vector3d d = p1 - p0; // d_pp + const double a = z0.dot(z0); // = 1 (unit) + const double b = z0.dot(z1); // a_i dot a_{i+1} + const double c = z1.dot(z1); // = 1 + const double det = a * c - b * b; // = |cross|^2 > 0 + const double t0 = (d.dot(z0) * c - d.dot(z1) * b) / det; // = s + const double t1 = (d.dot(z0) * b - d.dot(z1) * a) / det; // = t + + // step 3b feet: f_i = p_i + s*a_i, f_{i+1} = p_{i+1} + t*a_{i+1} r.foot0 = p0 + z0 * t0; r.foot1 = p1 + z1 * t1; const Eigen::Vector3d diff = r.foot1 - r.foot0; const double diff_norm = diff.norm(); if (diff_norm < k_axis_parallel_epsilon) { - // Lines intersect; use cross as the common-normal direction. + // case B (intersecting): feet coincide, so foot-to-foot is undefined + // step 3c Case B: x_i = (a_i x a_{i+1}) / ||a_i x a_{i+1}|| r.x_dir = cross / cross.norm(); } else { + // case A (skew): step 3c case A: x_i = (f_{i+1} - f_i) / ||f_{i+1} - f_i|| r.x_dir = diff / diff_norm; } r.parallel = false; @@ -312,7 +324,6 @@ DHFrames build_dh_frames(const std::vector& axes, const Eigen::Vector3d end_x = end_pose.linear() * Eigen::Vector3d(1, 0, 0); const Eigen::Vector3d end_p = end_pose.translation(); - // Append the synthetic end entry so the loop body handles frame n uniformly. std::vector all_z(axes.begin(), axes.end()); all_z.push_back(end_z); std::vector all_p(origins.begin(), origins.end()); @@ -371,10 +382,15 @@ DHFrames build_dh_frames(const std::vector& axes, return out; } +// dh_params.pdf step 2 helper: pick x_0 given z_0, x_0 perpendicular to z_0 +// Standard choice is world +x projected onto the plane perp to z, normalized +// Falls back to world +y if z is (anti)parallel to world +x (projection ~0) Eigen::Vector3d pick_base_x(const Eigen::Vector3d& z) { const Eigen::Vector3d world_x(1, 0, 0); + // remove the component of world_x along z, leaving the perpendicular part Eigen::Vector3d proj = world_x - z * z.dot(world_x); if (proj.norm() < k_axis_parallel_epsilon) { + // z parallel to world +x --> projection ~ 0. retry with world +y const Eigen::Vector3d world_y(0, 1, 0); proj = world_y - z * z.dot(world_y); } From 64ad32e89d47e48eb956dbdfed8b66c500256395 Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 11 May 2026 15:22:38 -0400 Subject: [PATCH 5/7] final comments --- .../sdk/referenceframe/urdf_to_dh_params.cpp | 37 +++++++++++++++++-- 1 file changed, 34 insertions(+), 3 deletions(-) diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp index 6c118035b..d56ed8add 100644 --- a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp @@ -229,6 +229,14 @@ CommonNormalResult common_normal(const Eigen::Vector3d& z0, return r; } +// dh_params.pdf step 4: compute one DH row (d, theta, a, alpha) from two +// consecutive DH frames (i-1, i). All inputs in the base frame. +// Inputs: z_prev = z_{i-1}, x_prev = x_{i-1}, p_prev = o_{i-1} +// z_curr = z_i, x_curr = x_i, p_curr = o_i +// +// dh.tex writes Eq. (a) as (f_{i+1} - f_i).x_i. That equals (o_i - o_{i-1}).x_i +// used below: the offsets between f's and o's lie along z_{i-1}, which vanishes +// under the x_i projection (x_i is perpendicular to z_{i-1} by construction). void extract_dh_row(const Eigen::Vector3d& z_prev, const Eigen::Vector3d& x_prev, const Eigen::Vector3d& p_prev, @@ -239,17 +247,38 @@ void extract_dh_row(const Eigen::Vector3d& z_prev, double& theta, double& a, double& alpha) { - const Eigen::Vector3d delta = p_curr - p_prev; + const Eigen::Vector3d delta = p_curr - p_prev; // o_i - o_{i-1} + // d_i = (o_i - o_{i-1}) dot z_{i-1} d = delta.dot(z_prev); + // a_i = (o_i - o_{i-1}) dot x_i a = delta.dot(x_curr); + // theta_i = atan2((x_{i-1} x x_i) dot z_{i-1}, x_{i-1} dot x_i) theta = std::atan2(x_prev.cross(x_curr).dot(z_prev), x_prev.dot(x_curr)); + // alpha_i = atan2((z_{i-1} x z_i) dot x_i, z_{i-1} dot z_i) alpha = std::atan2(z_prev.cross(z_curr).dot(x_curr), z_prev.dot(z_curr)); } +// Fail-fast guard for the last DH row. +// Frames 0 through n-1 are built by the common-normal procedure, so they satisfy +// the DH constraints by construction. Frame n is overwritten with the URDF +// tool pose, which the URDF author chose freely so nothing forces it to be DH-compatible. +// +// A DH row T = Rz(theta)*Tz(d)*Tx(a)*Rx(alpha) has only 4 scalars but a rigid +// transform has 6 DoF. The 2 "missing" DoF correspond to two geometric +// constraints that must hold at the frame boundary, both checked here: +// +// (1) x_n perpendicular to z_{n-1} -- otherwise no (d,theta,a,alpha) row +// can represent the orientation step from frame n-1 to frame n. +// (2) (p_n - o_{n-1}) lies in the (z_{n-1}, x_n) plane -- the row can only +// translate along z_{n-1} and x_n, so a y-component is unrepresentable. +// +// Without this, a bad URDF produces a DH table that compiles, looks plausible +// but silently disagrees with FK. void validate_end_effector_dh(const Eigen::Vector3d& z_prev, const Eigen::Vector3d& x_end, const Eigen::Vector3d& origin_prev, const Eigen::Vector3d& p_end) { + // check (1): x_n . z_{n-1} == 0 const double perp_dot = x_end.dot(z_prev); if (std::abs(perp_dot) > k_dh_compat_epsilon) { throw Exception(ErrorCondition::k_general, @@ -257,6 +286,8 @@ void validate_end_effector_dh(const Eigen::Vector3d& z_prev, "(residual dot = " + std::to_string(perp_dot) + ")"); } + // check (2): displacement to tool origin has no y_{n-1} component. + // y = z_{n-1} x x_n is the plane normal; delta . y must be ~0. const Eigen::Vector3d delta = p_end - origin_prev; const Eigen::Vector3d y_dir = z_prev.cross(x_end); const double plane_residual = delta.dot(y_dir); @@ -277,7 +308,7 @@ JointAxesAtRest joint_axes_at_rest(const std::vector& joints) { Eigen::Isometry3d cumulative = Eigen::Isometry3d::Identity(); for (const auto& j : joints) { - // with reference to dh_params.pdf: Step 1 substeps (a) and (b) are done in one Isometry3d multiply: + // with reference to dh_params.pdf: Step 1a and 1b are done in one Isometry3d multiply: // translation: p_cum_new = p_cum + R_cum * t_i // rotation: R_cum_new = R_cum * R_i cumulative = cumulative * pose_in_meters(j.origin); @@ -287,7 +318,7 @@ JointAxesAtRest joint_axes_at_rest(const std::vector& joints) { try { // normalize as we cannot assume unit length const Eigen::Vector3d local_axis = axis_unit(j.axis); - // substep (c): axis is expressed in the child's frame, so use the updated R_cum + // step 1c: axis is expressed in the child's frame, so use the updated R_cum const Eigen::Vector3d world_axis = cumulative.linear() * local_axis; // record (p_i, a_i) in the base frame out.axes.push_back(world_axis); From 83963c3273c90784eaac0112164174f8979e400f Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 11 May 2026 15:37:11 -0400 Subject: [PATCH 6/7] simpler --- .../sdk/referenceframe/urdf_to_dh_params.cpp | 12 ------ .../sdk/referenceframe/urdf_to_dh_params.hpp | 9 ----- src/viam/sdk/tests/test_urdf_to_dh_params.cpp | 37 ------------------- 3 files changed, 58 deletions(-) diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp index d56ed8add..5d5263df9 100644 --- a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp @@ -11,10 +11,8 @@ #include #include #include -#include #include -#include #include namespace viam { @@ -468,15 +466,5 @@ std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf) { return result; } -std::vector urdf_to_dh_params(Arm& arm) { - KinematicsData kin = arm.get_kinematics(); - const KinematicsDataURDF* urdf = boost::get(&kin); - if (urdf == nullptr) { - throw Exception(ErrorCondition::k_not_supported, - "urdf_to_dh_params(Arm&): kinematics format is not URDF"); - } - return urdf_to_dh_params(*urdf); -} - } // namespace sdk } // namespace viam diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp index 52931d78e..b2d507be2 100644 --- a/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.hpp @@ -11,8 +11,6 @@ namespace viam { namespace sdk { -class Arm; - /// @brief One Denavit-Hartenberg row for a single revolute joint. /// /// Units: meters for `d` and `a`, radians for `theta` and `alpha`. @@ -38,12 +36,5 @@ struct DHParam { /// plane), or fails to parse as XML. std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf); -/// @brief Convenience overload: fetches `arm.get_kinematics()`, requires -/// URDF format, and forwards to the byte-based overload. -/// -/// @throws viam::sdk::Exception if the arm's kinematics are not in URDF -/// format, or for any reason the byte-based overload would throw. -std::vector urdf_to_dh_params(Arm& arm); - } // namespace sdk } // namespace viam diff --git a/src/viam/sdk/tests/test_urdf_to_dh_params.cpp b/src/viam/sdk/tests/test_urdf_to_dh_params.cpp index c99fed491..815a8bc06 100644 --- a/src/viam/sdk/tests/test_urdf_to_dh_params.cpp +++ b/src/viam/sdk/tests/test_urdf_to_dh_params.cpp @@ -10,10 +10,8 @@ #include #include -#include #include #include -#include using namespace viam::sdk::urdf_to_dh_internals; @@ -399,41 +397,6 @@ BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_gp12_fk_round_trip) { check_fk_roundtrip("gp12.urdf"); } -namespace { - -// Subclass of MockArm that returns a caller-supplied KinematicsData. -class ArmWithKinematics : public viam::sdktests::arm::MockArm { - public: - ArmWithKinematics(std::string name, viam::sdk::KinematicsData k) - : MockArm(std::move(name)), kinematics_(std::move(k)) {} - - viam::sdk::KinematicsData get_kinematics(const viam::sdk::ProtoStruct&) override { - return kinematics_; - } - - private: - viam::sdk::KinematicsData kinematics_; -}; - -} // namespace - -BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_arm_overload_urdf) { - auto urdf = load_urdf("ur5e-real.urdf"); - ArmWithKinematics arm("test-arm", urdf); - auto params = urdf_to_dh_params(arm); - BOOST_CHECK_EQUAL(params.size(), 6u); - BOOST_CHECK_EQUAL(params[0].name, "shoulder_pan_joint"); -} - -BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_arm_overload_rejects_non_urdf) { - viam::sdk::KinematicsDataSVA sva{}; // wrong format - ArmWithKinematics arm("test-arm", sva); - auto match = [](const Exception& e) { - return std::string(e.what()).find("kinematics format is not URDF") != std::string::npos; - }; - BOOST_CHECK_EXCEPTION(urdf_to_dh_params(arm), Exception, match); -} - BOOST_AUTO_TEST_CASE(test_urdf_to_dh_params_non_dh_compatible_end) { const std::string xml = R"( From dc1d667fcaafc55cd3f6509c29a766476c9ce578 Mon Sep 17 00:00:00 2001 From: Nick Franczak Date: Mon, 11 May 2026 15:52:26 -0400 Subject: [PATCH 7/7] pass ci --- src/viam/sdk/referenceframe/urdf_to_dh_params.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp index 5d5263df9..f54e2e52c 100644 --- a/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp +++ b/src/viam/sdk/referenceframe/urdf_to_dh_params.cpp @@ -437,7 +437,8 @@ std::vector urdf_to_dh_params(const KinematicsDataURDF& urdf) { auto frames = build_dh_frames(axes_origins.axes, axes_origins.origins, axes_origins.end_pose); - validate_end_effector_dh(frames.zs[n - 1], frames.xs[n], frames.origins[n - 1], frames.origins[n]); + validate_end_effector_dh( + frames.zs[n - 1], frames.xs[n], frames.origins[n - 1], frames.origins[n]); // Revolute joint names in chain order (matches joint_axes_at_rest filter). std::vector revolute_names;