From 288d6e925e68b6a6bee2a5a0026173086e53b626 Mon Sep 17 00:00:00 2001 From: Francesco Romano Date: Mon, 25 Sep 2017 12:10:57 +0200 Subject: [PATCH 01/92] Migrated old DH conversion code from embedded to iDynTree --- toolbox/CMakeLists.txt | 3 +- toolbox/src/InverseKinematics.cpp | 149 ++++++------------------------ 2 files changed, 27 insertions(+), 125 deletions(-) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index e648f87f6..52c60000f 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -40,8 +40,7 @@ add_install_rpath_support(BIN_DIRS ${CMAKE_INSTALL_PREFIX}/bin find_package(Eigen3 REQUIRED) find_package(wholeBodyInterface 0.2.5 REQUIRED) find_package(yarpWholeBodyInterface 0.3.2 REQUIRED) -# Workaround section, aka, this stuff should be defined by imported libraries -find_package(iDynTree REQUIRED) +find_package(iDynTree 0.7.2 REQUIRED) #On new versions of Clang, MATLAB requires C++11. #I enable it on all Clangs diff --git a/toolbox/src/InverseKinematics.cpp b/toolbox/src/InverseKinematics.cpp index 1ad048a52..43c45a7e0 100644 --- a/toolbox/src/InverseKinematics.cpp +++ b/toolbox/src/InverseKinematics.cpp @@ -14,20 +14,12 @@ #include #include -//These includes are to convert from URDF to DH -#include -#include -#include -#include -#include -#include -#include -//End of temporary include section +#include +#include +#include namespace wbt { - static bool iKinLimbFromUrdfFile(const std::string &urdf_file_name, const std::string &base_link_name, const std::string& end_effector_link_name, iCub::iKin::iKinLimb &convertedChain, std::vector& jointNames); - struct InverseKinematics::InverseKinematicsPimpl { bool m_firstTime; //input buffers @@ -204,11 +196,32 @@ namespace wbt { if (!m_piml->m_leg) return false; std::vector jointNames; - if (!iKinLimbFromUrdfFile(urdfFile, baseLink, endEffectorLink, *((iCub::iKin::iKinLimb*)m_piml->m_leg), jointNames)) { - if (error) error->message = "Cannot convert urdf to iKin chain"; + iDynTree::ModelLoader loader; + loader.loadModelFromFile(urdfFile); + if (!loader.isValid()) { + if (error) error->message = "Cannot load urdf file"; + return false; + } + + iDynTree::DHChain dhChain; + if (!iDynTree::ExtractDHChainFromModel(loader.model(), + baseLink, + endEffectorLink, + dhChain)) { + if (error) error->message = "Cannot extract DH parameters from model"; + return false; + } + if (!iDynTree::iKinLimbFromDHChain(dhChain, *((iCub::iKin::iKinLimb*)m_piml->m_leg))) { + if (error) error->message = "Cannot convert DH parameters to iKin chain"; return false; } + // Retrieve joint names + jointNames.reserve(dhChain.getNrOfDOFs()); + for (size_t i = 0; i < dhChain.getNrOfDOFs(); ++i) { + jointNames.push_back(dhChain.getDOFName(i)); + } + m_piml->m_solver = new iCub::iKin::iKinIpOptMin(*m_piml->m_leg, IKINCTRL_POSE_XYZ, 1e-3, 1e-6, 100); if (!m_piml->m_solver) return false; @@ -329,114 +342,4 @@ namespace wbt { return false; } - - bool iKinLimbFromUrdfFile(const std::string &urdf_file_name, const std::string &base_link_name, const std::string& end_effector_link_name, iCub::iKin::iKinLimb &convertedChain, std::vector& jointNames) { - - KDL::Tree kdl_tree; - KDL::Chain kdl_chain; - std::vector joint_names; - KDL::JntArray min,max; - - // - // URDF --> KDL::Tree - // - bool root_inertia_workaround = true; - if (!iDynTree::treeFromUrdfFile(urdf_file_name,kdl_tree,root_inertia_workaround)) - { - std::cerr << "Could not parse urdf robot model" << std::endl; - std::cerr << "Please open an issue at https://github.com/robotology-playground/idyntree/issues " << std::endl; - - return false; - } - - // - // URDF --> position ranges - // - if (!iDynTree::jointPosLimitsFromUrdfFile(urdf_file_name,joint_names,min,max)) - { - std::cerr << "Could not parse urdf robot model limits" << std::endl; - return false; - } - - if (joint_names.size() != min.rows() || - joint_names.size() != max.rows() || - joint_names.size() == 0) - { - std::cerr << "Inconsistent joint limits got from urdf (nr of joints extracted: " << joint_names.size() << " ) " << std::endl; - return false; - } - - // - // KDL::Tree --> KDL::CoDyCo::UndirectedTree - // (for extracting arbitrary chains, - // using KDL::Tree you can just get chains where the base of the chain - // is proximal to the tree base with respect to the end effector. - // - KDL::CoDyCo::UndirectedTree undirected_tree(kdl_tree); - - KDL::Tree kdl_rotated_tree = undirected_tree.getTree(base_link_name); - - bool result = kdl_rotated_tree.getChain(base_link_name,end_effector_link_name,kdl_chain); - if (!result) - { - std::cerr << "Impossible to find " << base_link_name << " or " - << end_effector_link_name << " in the URDF." << std::endl; - return false; - } - - // - // Copy the limits extracted from the URDF to the chain - // - int nj = kdl_chain.getNrOfJoints(); - KDL::JntArray chain_min(nj), chain_max(nj); - - jointNames.clear(); - jointNames.reserve(nj); - - size_t seg_i, jnt_i; - for (seg_i = 0,jnt_i = 0; seg_i < kdl_chain.getNrOfSegments(); seg_i++) - { - const KDL::Segment & seg = kdl_chain.getSegment(seg_i); - if( seg.getJoint().getType() != KDL::Joint::None ) - { - std::string jnt_name = seg.getJoint().getName(); - // std::cerr << "searching for joint " << jnt_name << std::endl; - int tree_jnt = 0; - for(tree_jnt = 0; tree_jnt < joint_names.size(); tree_jnt++ ) - { - //std::cerr << "joint_names[ " << tree_jnt << "] is " << joint_names[tree_jnt] << std::endl; - if( joint_names[tree_jnt] == jnt_name ) - { - chain_min(jnt_i) = min(tree_jnt); - chain_max(jnt_i) = max(tree_jnt); - jnt_i++; - jointNames.push_back(jnt_name); - break; - } - } - if( tree_jnt == joint_names.size() ) - { - std::cerr << "Failure in converting limits from tree to chain, unable to find joint " << jnt_name << std::endl; - return false; - } - } - } - - if (jnt_i != nj) - { - std::cerr << "Failure in converting limits from tree to chain" << std::endl; - return false; - } - - // - // Convert the chain and the limits to an iKin chain (i.e. DH parameters) - // - result = iDynTree::iKinLimbFromKDLChain(kdl_chain,convertedChain,chain_min,chain_max); - if (!result) - { - std::cerr << "Could not export KDL::Tree to iKinChain" << std::endl; - return false; - } - return true; - } } From aa70f727dc7cd15db3f52f4d1eae4e16324edfbc Mon Sep 17 00:00:00 2001 From: Francesco Romano Date: Mon, 25 Sep 2017 17:38:09 +0200 Subject: [PATCH 02/92] Fixed bug introduced with toolbox refactoring SetReferences subList parameter was erroneously converted to a boolean, while it is actually the index of the selected item in the Simulink mask dropdown. Being the index >=1 the boolean conversion resulted always in a true value. Fix https://github.com/robotology/WB-Toolbox/issues/57 --- toolbox/src/SetReferences.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 8a8f4464e..4f3e4c97d 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -33,7 +33,10 @@ namespace wbt { unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_fullControl = blockInfo->getScalarParameterAtIndex(WBIBlock::numberOfParameters() + 2).booleanData(); + // In Toolbox mask the options are the following: + // - 1 => full control + // - 2 => sublist control + m_fullControl = blockInfo->getScalarParameterAtIndex(WBIBlock::numberOfParameters() + 2).int32Data() == 1; if (!m_fullControl) { //sublist From 6716aaac2de5dea93ac48e3dc3bfed4f07e9287f Mon Sep 17 00:00:00 2001 From: Francesco Romano Date: Tue, 24 Oct 2017 17:12:26 +0200 Subject: [PATCH 03/92] Temporary fix: included iostream Note: actually the std::cerr are warnings for the user, this is why they are not returned as an error. We have to find a smarter way to return the warning to the user. --- toolbox/src/InverseKinematics.cpp | 2 ++ toolbox/src/SetReferences.cpp | 2 ++ toolbox/src/YarpRead.cpp | 1 + 3 files changed, 5 insertions(+) diff --git a/toolbox/src/InverseKinematics.cpp b/toolbox/src/InverseKinematics.cpp index 43c45a7e0..f8f6e61ff 100644 --- a/toolbox/src/InverseKinematics.cpp +++ b/toolbox/src/InverseKinematics.cpp @@ -18,6 +18,8 @@ #include #include +#include + namespace wbt { struct InverseKinematics::InverseKinematicsPimpl { diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 4f3e4c97d..397bd6020 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -7,6 +7,8 @@ #include #include +#include + namespace wbt { std::string SetReferences::ClassName = "SetReferences"; diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 9fd15c3ca..82fa279f4 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -10,6 +10,7 @@ #include #include +#include #define PARAM_IDX_1 1 // port name #define PARAM_IDX_2 2 // Size of the port you're reading From 22954931291da1a88e6951361b7ea74405b6ea1e Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 30 Oct 2017 10:17:22 +0000 Subject: [PATCH 04/92] New Matlab WBToolboxConfig class This class contains and validates the configuration passed to every wbt::WBBlock object. ValidConfiguration is a Dependent property and it is set to 1 only if the basic checks currently implemented in other properties don't fail. From this state, it is possible to call getSimulinkParameters() in order to obtain the struct which is passed to the S-Functions and then parsed in C++. This class also contains utilities functions for obtainng a simple string representation of 1D vectors and 1D chars, required to serialize the data in the Config Block's mask. The deserialization is performed using eval(). --- +WBToolbox/WBToolboxConfig.m | 143 +++++++++++++++++++++++++++++++++++ 1 file changed, 143 insertions(+) create mode 100644 +WBToolbox/WBToolboxConfig.m diff --git a/+WBToolbox/WBToolboxConfig.m b/+WBToolbox/WBToolboxConfig.m new file mode 100644 index 000000000..20374e498 --- /dev/null +++ b/+WBToolbox/WBToolboxConfig.m @@ -0,0 +1,143 @@ +classdef WBToolboxConfig < matlab.mixin.Copyable + %WBTOOLBOXCONFIG Summary of this class goes here + % Detailed explanation goes here + + % PROPERTIES + % ========== + + properties + % Robot state + RobotName (1,:) char + UrdfFile (1,:) char + ControlledJoints (1,:) cell + ControlBoardsNames (1,:) cell + LocalName (1,:) char + % Other Variables + GravityVector (1,3) double = [0, 0, -9.81] + end + + properties (Dependent) + ValidConfiguration (1,1) logical + end + + properties (Hidden, Dependent) + SimulinkParameters (1,1) struct + end + + % METHODS + % ======= + + methods + + % SET METHODS + % ----------- + + % Dependent properties + % -------------------- + + function set.ValidConfiguration(~,~) + error(['ValidConfiguration is set to 1 automatically ', ... + 'when the configuration is valid.']); + end + + function set.SimulinkParameters(~,~) + error(['SimulinkParameters is created automatically ', ... + 'when the configuration is valid.']); + end + + % Other properties + % ---------------- + + function set.ControlledJoints(obj, value) + if (~iscellstr(value)) + error(['ControlledJoints must be a cell array of ', ... + 'charachter vectors']); + end + obj.ControlledJoints = value; + end + + function set.ControlBoardsNames(obj, value) + if (~iscellstr(value)) + error(['ControlBoardsNames must be a cell array of ', ... + 'charachter vectors']); + end + obj.ControlBoardsNames = value; + end + + % GET METHODS + % ----------- + + % Dependent properties + % -------------------- + + function value = get.ValidConfiguration(obj) + % Check if all the properties have been set + value = ... + ~isempty(obj.RobotName) && ... + ~isempty(obj.UrdfFile) && ... + ~isempty(obj.ControlledJoints) && ... + ~isempty(obj.ControlBoardsNames) && ... + ~isempty(obj.LocalName) && ... + ~isequal(obj.GravityVector,[0, 0, 0]); + end + + function value = get.SimulinkParameters(obj) + % Create and populate the struct + value = struct(); + value.RobotName = obj.RobotName; + value.UrdfFile = obj.UrdfFile; + value.LocalName = obj.LocalName; + value.ControlledJoints = obj.ControlledJoints; + value.ControlBoardsNames = obj.ControlBoardsNames; + value.GravityVector = obj.GravityVector; + end + + % Other properties + % ---------------- + + % OTHER METHODS + % ============= + + function value = getSimulinkParameters(obj) + if (obj.ValidConfiguration) + value = obj.SimulinkParameters; + else + error('The configuration is not complete'); + end + end + end + + methods(Static) + + function cellArraySerialized = serializeCellArray1D(cellArray) + [m,n] = size(cellArray); + if (m>1 && n>1) + error('The input cell must be 1D'); + end + cellArraySerialized = '{'; + for i=1:length(cellArray) + cellArraySerialized = strcat(cellArraySerialized,"'",cellArray{i},"'"); + if i ~= length(cellArray) + cellArraySerialized = strcat(cellArraySerialized,','); + end + end + cellArraySerialized = strcat(cellArraySerialized,'}'); + end + + function vectorSerialized = serializeVector1D(vector) + [m,n] = size(vector); + if (m>1 && n>1) + error('The input vector must be 1D'); + end + vectorSerialized = '['; + for i=1:length(vector) + vectorSerialized = strcat(vectorSerialized,num2str(vector(i))); + if i ~= length(vector) + vectorSerialized = strcat(vectorSerialized,','); + end + end + vectorSerialized = strcat(vectorSerialized,']'); + end + + end +end From be52d5bdd48d0818540583600c50be9a19e895f3 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 30 Oct 2017 10:21:52 +0000 Subject: [PATCH 05/92] New Anytype interface and MxAnyType implementation Initial version of the library, which will become independent in the future. MxAnyType handles the C / C++ mxArray pointer that represents any generic data type in Matlab. It wraps most of the C APIs, and it has optional support of strict type checking. --- CMakeLists.txt | 1 + MxAnyType/CMakeLists.txt | 56 +++++++++ MxAnyType/include/AnyType.h | 67 +++++++++++ MxAnyType/include/MxAnyType.h | 99 ++++++++++++++++ MxAnyType/src/MxAnyType.cpp | 213 ++++++++++++++++++++++++++++++++++ 5 files changed, 436 insertions(+) create mode 100644 MxAnyType/CMakeLists.txt create mode 100644 MxAnyType/include/AnyType.h create mode 100644 MxAnyType/include/MxAnyType.h create mode 100644 MxAnyType/src/MxAnyType.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index acd0156d3..034310442 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,6 +12,7 @@ include(YCMDefaultDirs) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_SOURCE_DIR}/cmake) set(WB-TOOLBOX_SHARE_DIR "${CMAKE_INSTALL_PREFIX}/share/WB-Toolbox") +add_subdirectory(MxAnyType) add_subdirectory(toolbox) install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/images DESTINATION ${WB-TOOLBOX_SHARE_DIR}) diff --git a/MxAnyType/CMakeLists.txt b/MxAnyType/CMakeLists.txt new file mode 100644 index 000000000..8d3250642 --- /dev/null +++ b/MxAnyType/CMakeLists.txt @@ -0,0 +1,56 @@ +cmake_policy(SET CMP0048 NEW) +project(MxAnyType LANGUAGES CXX VERSION 0.1) +cmake_minimum_required(VERSION 3.0.2) + +# Configure the project +# ===================== +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +include(GNUInstallDirs) +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + +# Use a general prefix for the project +set(VARS_PREFIX ${PROJECT_NAME}) +# set(VARS_PREFIX "MxAnyType") + +# Build the library +# ================= + +# Export the includes needed to who inherits this library +# Set this up properly for handling either BUILD and INSTALL trees +set(${VARS_PREFIX}_INCLUDE_BUILD ${CMAKE_CURRENT_SOURCE_DIR}/include) +set(${VARS_PREFIX}_INCLUDE_INSTALL ${CMAKE_INSTALL_INCLUDEDIR}/${VARS_PREFIX}) + +# Add the target +add_library(${VARS_PREFIX} STATIC ${CMAKE_CURRENT_SOURCE_DIR}/include/AnyType.h + ${CMAKE_CURRENT_SOURCE_DIR}/include/MxAnyType.h + ${CMAKE_CURRENT_SOURCE_DIR}/src/MxAnyType.cpp) + + +# TODO: temporary, waiting the library becomes a shared +if (CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set_target_properties(${VARS_PREFIX} PROPERTIES COMPILE_FLAGS "-fPIC") +endif() + +# Find Eigen +find_package(Eigen3 REQUIRED) +target_include_directories(${VARS_PREFIX} PUBLIC "${EIGEN3_INCLUDE_DIR}") + +# Find Matlab resources +find_package(Matlab REQUIRED MX_LIBRARY) +# target_include_directories(${VARS_PREFIX} SYSTEM PUBLIC "${Matlab_INCLUDE_DIRS}") // TODO: when committing +target_include_directories(${VARS_PREFIX} PUBLIC "${Matlab_INCLUDE_DIRS}") + +# Setup the include directories +# TODO why in the how to was INTERFACE? +target_include_directories(${VARS_PREFIX} PUBLIC + $ + $) + +# Assign some useful properties +# set_target_properties(${VARS_PREFIX} PROPERTIES VERSION ${PROJECT_VERSION} +# PUBLIC_HEADER MxAnyType.h) + +# Build tests +# =========== +# add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/tests) diff --git a/MxAnyType/include/AnyType.h b/MxAnyType/include/AnyType.h new file mode 100644 index 000000000..1637b38b8 --- /dev/null +++ b/MxAnyType/include/AnyType.h @@ -0,0 +1,67 @@ +#ifndef ANYTYPE_H +#define ANYTYPE_H + +#include +#include +#include +#include + +class AnyType; + +typedef std::shared_ptr AnyTypeSPtr; +typedef std::vector AnyCell; +typedef std::unordered_map AnyStruct; + +class AnyType +{ +protected: + // void* m_AnyData; + +public: + // AnyType() : m_AnyData(nullptr) {}; + AnyType() = default; + // virtual void* getAnyDataPtr() const = 0; + + virtual ~AnyType() = default; + + // Integers + virtual bool asInt(int& i) = 0; + // virtual bool asInt8(int8_t& i) = 0; + // virtual bool asInt16(int16_t& i) = 0; + virtual bool asInt32(int32_t& i) = 0; + // virtual bool asInt64(int64_t& i) = 0; + + // Unsigned Integers + virtual bool asUInt(unsigned& i) = 0; + // virtual bool asUInt8(uint8_t& i) = 0; + // virtual bool asUInt16(uint16_t& i) = 0; + // virtual bool asUInt32(uint32_t& i) = 0; + // virtual bool asUInt64(uint64_t& i) = 0; + + // Boolean + virtual bool asBool(bool& b) = 0; + + // Floating-point + // virtual bool asFloat(float& f) = 0; + virtual bool asDouble(double& d) = 0; + + // Characters + virtual bool asString(std::string& s) = 0; + + // Struct + virtual bool asAnyStruct(AnyStruct& map) = 0; + + // Cell array + virtual bool asAnyCell(AnyCell& map) = 0; + + // Matrix + // TODO: constraint max 2-dimension + // virtual bool asMatrixFloat(Eigen::MatrixXf mat) = 0; + // virtual bool asMatrixDouble(Eigen::MatrixXd mat) = 0; + + // Vector + virtual bool asVectorDouble(Eigen::VectorXd& vec) = 0; + virtual bool asVectorDouble(std::vector& vec) = 0; +}; + +#endif /* ANYTYPE_H */ diff --git a/MxAnyType/include/MxAnyType.h b/MxAnyType/include/MxAnyType.h new file mode 100644 index 000000000..21fc7090f --- /dev/null +++ b/MxAnyType/include/MxAnyType.h @@ -0,0 +1,99 @@ +#ifndef MXANYTYPE_H +#define MXANYTYPE_H + +#include +#include +#include +#include +#include "AnyType.h" +#include "matrix.h" + +class MxAnyType; + +// If needed in the future +// class MxAnyCell : public AnyCell {}; +// class MxAnyStruct : public AnyStruct {}; + +struct MxArrayMetadata { + mxClassID id; + bool isScalar; + size_t rows; + size_t cols; + size_t nElem; + size_t nDims; + std::vector dims; +}; + +class MxAnyType : public AnyType +{ +private: + const mxArray* mx; + MxArrayMetadata md; + bool validate; + + // TODO: https://it.mathworks.com/help/matlab/apiref/mxgetscalar.html returns a double always + bool asScalar(double& d); + bool validateClassId(mxClassID id1, mxClassID id2); + + // mxArray* getMxArrayPtr() const { return static_cast(getAnyDataPtr()); } + +public: + // void* getAnyDataPtr() const override { + // return (void*) mx; + // } + + MxAnyType(); + MxAnyType(const mxArray* m, bool validateId = false); + ~MxAnyType() = default; + MxAnyType(const MxAnyType& mxAnyType); + + void enableClassIDValidation(); + + // STRING / CHARS + // ============== + + bool asString(std::string& s) override; + + // SCALAR TYPES + // ============ + + // Generic casting + // --------------- + + bool asInt(int& i) override; + bool asUInt(unsigned& i) override; + + // Specific casting + // ---------------- + + bool asInt32(int32_t& i) override; + + // TODO: complete with all the other scalar types + // bool asInt64(int64_t& i) override + // { + // double buffer; + // if (!asScalar(buffer)) return false; + // i = static_cast(buffer); + // return validateClassId(md.id, mxINT64_CLASS); + // } + + bool asDouble(double& d) override; + bool asBool(bool& b) override; + + // COMPOSITE DATA TYPES + // ==================== + + bool asAnyStruct(AnyStruct& s) override; + bool asAnyCell(AnyCell& cell) override; + + // MATRIX + // ====== + + // VECTOR + // ====== + + bool asVectorDouble(Eigen::VectorXd& vec) override; + bool asVectorDouble(std::vector& vec) override; +}; + +#endif /* MXANYTYPE_H */ diff --git a/MxAnyType/src/MxAnyType.cpp b/MxAnyType/src/MxAnyType.cpp new file mode 100644 index 000000000..77a2f10f4 --- /dev/null +++ b/MxAnyType/src/MxAnyType.cpp @@ -0,0 +1,213 @@ +#include "MxAnyType.h" +#include + +// PRIVATE METHODS +// =============== + +bool MxAnyType::asScalar(double& d) +{ + if (!mx) return false; + if (!mxIsScalar(mx)) return false; // 1x1 + if (!mxIsNumeric(mx)) return false; // Types: https://it.mathworks.com/help/matlab/apiref/mxisnumeric.html + + // Cast to double since even a mxINT8_CLASS is returned as double: + // https://it.mathworks.com/help/matlab/apiref/mxgetscalar.html + d = static_cast(mxGetScalar(mx)); + return true; +} + +bool MxAnyType::validateClassId(mxClassID id1, mxClassID id2) +{ + if (validate) + return id1 == id2; + else + return true; +} + +// PUBLIC METHODS +// ============== + +// Constructors +// ============ + +MxAnyType::MxAnyType() : mx(nullptr), validate(false) +{ + md.id = mxUNKNOWN_CLASS; +} + +MxAnyType::MxAnyType(const mxArray* m, bool validateId) : mx(m), validate(validateId) +{ + assert(mx); + + // Get the ID + md.id = mxGetClassID(mx); + assert(md.id != mxVOID_CLASS); + assert(md.id != mxUNKNOWN_CLASS); + + // Get the other metadata + md.isScalar = mxIsScalar(mx); + md.rows = static_cast(mxGetN(mx)); + md.cols = static_cast(mxGetM(mx)); + md.nElem = static_cast(mxGetNumberOfElements(mx)); + md.nDims = static_cast(mxGetNumberOfDimensions(mx)); + + if (md.isScalar) + assert(md.rows == md.cols == md.nElem == 1); + + // TODO: only 2 dims currently supported + assert(md.nDims == 2); + assert(md.rows * md.cols == md.nElem); + + const size_t* size = mxGetDimensions(mx); + for (unsigned dim = 0; dim < md.nDims; ++dim) { + md.dims.push_back(static_cast(size[dim])); + } + assert(md.dims.size() == 2); +} + +MxAnyType::MxAnyType(const MxAnyType& mxAnyType) +: mx(mxAnyType.mx) +, md(mxAnyType.md) +, validate(mxAnyType.validate) +{} + +void MxAnyType::enableClassIDValidation() +{ + validate = true; +} + +// STRING / CHARS +// ============== + +bool MxAnyType::asString(std::string& s) +{ + if (!mx) return false; + if (md.id != mxCHAR_CLASS) return false; + char* buffer = mxArrayToString(mx); + s = std::string(buffer); + mxFree(buffer); + return true; +} + +// SCALAR TYPES +// ============ + +// Generic casting +// --------------- + +bool MxAnyType::asInt(int& i) +{ + double buffer; + if (!asScalar(buffer)) return false; + i = static_cast(buffer); + return true; +} + +bool MxAnyType::asUInt(unsigned& i) +{ + double buffer; + if (!asScalar(buffer)) return false; + i = static_cast(buffer); + return true; +} + +// Specific casting +// ---------------- + +bool MxAnyType::asInt32(int32_t& i) +{ + double buffer; + if (!asScalar(buffer)) return false; + i = static_cast(buffer); + return validateClassId(md.id, mxINT32_CLASS); +} + +// TODO: complete with all the other scalar types +// bool asInt64(int64_t& i) +// { +// double buffer; +// if (!asScalar(buffer)) return false; +// i = static_cast(buffer); +// return validateClassId(md.id, mxINT64_CLASS); +// } + +bool MxAnyType::asDouble(double& d) +{ + bool ok = asScalar(d); + return ok && validateClassId(md.id, mxDOUBLE_CLASS); +} + +bool MxAnyType::asBool(bool& b) + { + if (!mx) return false; + if (!mxIsLogicalScalar(mx)) return false; + b = mxIsLogicalScalarTrue(mx); + return true; +} + +// COMPOSITE DATA TYPES +// ==================== + +bool MxAnyType::asAnyStruct(AnyStruct& s) +{ + if (!mx) return false; + if (md.id != mxSTRUCT_CLASS) return false; + + for (unsigned i = 0; i < mxGetNumberOfFields(mx); ++i) { + const char* fieldName = mxGetFieldNameByNumber(mx,i); + // TODO multidimensional struct + mxArray* fieldContent = mxGetFieldByNumber(mx,0,i); + if (fieldName == nullptr) return false; + if (fieldContent == nullptr) return false; + s[std::string(fieldName)] = std::make_shared(fieldContent); + } + return true; +} + +bool MxAnyType::asAnyCell(AnyCell& cell) +{ + if (!mx) return false; + if (md.id != mxCELL_CLASS) return false; + + // TODO: AnyCell then will have a operator()(3,4) method; + for (unsigned i=0; i < mxGetNumberOfElements(mx); ++i) { + mxArray* cellContent = mxGetCell(mx, i); + if (!cellContent) return false; + cell.push_back(std::make_shared(cellContent)); + } + return true; +} + +// MATRIX +// ====== + +// VECTOR +// ====== + +// TODO tests with other types (uint8) https://it.mathworks.com/help/matlab/apiref/mxgetdata.html (Descriptio) +bool MxAnyType::asVectorDouble(Eigen::VectorXd& vec) +{ + if (!mx) return false; + if (!mxIsDouble(mx)) return false; + + if (md.rows > 1 && md.cols > 1) { + return false; + } + + // TODO add method for complex vectors (and move the check into md) + if (mxIsComplex(mx)) return false; + + double* buffer = mxGetPr(mx); + if (!buffer) return false; + + vec = Eigen::Map(buffer, md.nElem); + return true; +} + +bool MxAnyType::asVectorDouble(std::vector& vec) +{ + Eigen::VectorXd vecEigen; + if (!asVectorDouble(vecEigen)) return false; + vec.assign(vecEigen.data(), vecEigen.data() + vecEigen.rows() * vecEigen.cols()); + return true; +} From 705766370b9eac6ea2160fff06fdc045f1318390 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 30 Oct 2017 10:30:52 +0000 Subject: [PATCH 06/92] Error class has been enhanced and renamed to Log wbt::Log is the new class that provides log support to the WBToolbox. It now supports both Errors and Warnings. For being more flexible, wbt::Log is a singleton. This approach simplifies dramatically the handling of warnings, and can be called from every method without the need of passing it though arguments. Since singletons cannot be deleted, wbt::Log state is reset in the early stage of the processing. [Squash] toolbox.cpp --- toolbox/CMakeLists.txt | 4 +- toolbox/include/base/Error.h | 19 ---- toolbox/include/base/Log.h | 42 ++++++++ toolbox/include/base/toolbox.h | 2 +- toolbox/src/base/Error.cpp | 0 toolbox/src/base/Log.cpp | 71 ++++++++++++++ toolbox/src/base/toolbox.cpp | 174 +++++++++++++++++++++------------ 7 files changed, 230 insertions(+), 82 deletions(-) delete mode 100644 toolbox/include/base/Error.h create mode 100644 toolbox/include/base/Log.h delete mode 100644 toolbox/src/base/Error.cpp create mode 100644 toolbox/src/base/Log.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 52c60000f..9838ee86f 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -62,7 +62,7 @@ configure_block(BLOCK_NAME "Base" src/base/Block.cpp src/base/BlockInformation.cpp src/base/WBIBlock.cpp - src/base/Error.cpp + src/base/Log.cpp src/base/WBInterface.cpp src/base/factory.cpp src/base/WBIModelBlock.cpp @@ -72,7 +72,7 @@ configure_block(BLOCK_NAME "Base" include/base/Block.h include/base/BlockInformation.h include/base/WBIBlock.h - include/base/Error.h + include/base/Log.h include/base/WBInterface.h include/base/WBIModelBlock.h include/base/SimulinkBlockInformation.h #this is temp diff --git a/toolbox/include/base/Error.h b/toolbox/include/base/Error.h deleted file mode 100644 index f11dc413c..000000000 --- a/toolbox/include/base/Error.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef WBT_ERROR_H -#define WBT_ERROR_H - -#include - -namespace wbt { - class Error; -} - -/** - * Basic Error class - */ -class wbt::Error { -public: - std::string message; /**< a string representing the error message */ -}; - - -#endif /* end of include guard: WBT_ERROR_H */ diff --git a/toolbox/include/base/Log.h b/toolbox/include/base/Log.h new file mode 100644 index 000000000..699c431b6 --- /dev/null +++ b/toolbox/include/base/Log.h @@ -0,0 +1,42 @@ +#ifndef WBT_LOG_H +#define WBT_LOG_H + +#include +#include + +namespace wbt { + class Log; +} + +/** + * Basic Log class + */ +class wbt::Log +{ +private: + std::vector errors; + std::vector warnings; + std::string prefix; + + static std::string serializeVectorString(std::vector v, std::string prefix=""); +public: + + static wbt::Log& getSingleton(); + + void error(std::string errorMessage); + void warning(std::string warningMessage); + + void resetPrefix(); + void setPrefix(std::string prefixMessage); + + std::string getErrors() const; + std::string getWarnings() const; + + void clearErrors(); + void clearWarnings(); + + void clear(); +}; + + +#endif /* end of include guard: WBT_LOG_H */ diff --git a/toolbox/include/base/toolbox.h b/toolbox/include/base/toolbox.h index a61e5e74e..a1ff7505f 100644 --- a/toolbox/include/base/toolbox.h +++ b/toolbox/include/base/toolbox.h @@ -1,4 +1,4 @@ -#include "Error.h" +#include "Log.h" //General Yarp utilities #include "YarpRead.h" #include "YarpWrite.h" diff --git a/toolbox/src/base/Error.cpp b/toolbox/src/base/Error.cpp deleted file mode 100644 index e69de29bb..000000000 diff --git a/toolbox/src/base/Log.cpp b/toolbox/src/base/Log.cpp new file mode 100644 index 000000000..9ee6abdaa --- /dev/null +++ b/toolbox/src/base/Log.cpp @@ -0,0 +1,71 @@ +#include "Log.h" +#include +#include + +using namespace wbt; + +Log& Log::getSingleton() +{ + static Log logInstance; + return logInstance; +} + +void Log::error(std::string errorMessage) +{ + errors.push_back(errorMessage); +} + +void Log::warning(std::string warningMessage) +{ + warnings.push_back(warningMessage); +} + +void Log::setPrefix(std::string prefixMessage) +{ + prefix = prefixMessage; +} + +void Log::resetPrefix() +{ + prefix.clear(); +} + +std::string Log::serializeVectorString(std::vector v, std::string prefix) +{ + std::stringstream output; + std::ostream_iterator output_iterator(output, "\n"); + std::copy(v.begin(), v.end(), output_iterator); + + if (prefix.empty()) { + return output.str(); + } + else { + return prefix + "\n" + output.str(); + } +} + +std::string Log::getErrors() const +{ + return serializeVectorString(errors, prefix); +} + +std::string Log::getWarnings() const +{ + return serializeVectorString(warnings, prefix); +} + +void Log::clearWarnings() +{ + warnings.clear(); +} + +void Log::clearErrors() +{ + errors.clear(); +} + +void Log::clear() +{ + clearErrors(); + clearWarnings(); +} diff --git a/toolbox/src/base/toolbox.cpp b/toolbox/src/base/toolbox.cpp index 5162f3505..2e2d9037f 100644 --- a/toolbox/src/base/toolbox.cpp +++ b/toolbox/src/base/toolbox.cpp @@ -26,11 +26,74 @@ #include "toolbox.h" #include "Block.h" +#include "Log.h" #include "SimulinkBlockInformation.h" #include #include +static void catchLogMessages(bool status, SimStruct *S, std::string prefix) +{ + // Initialize static buffers + const unsigned bufferLen = 1024; + static char errorBuffer[bufferLen]; + static char warningBuffer[bufferLen]; + + // Notify warnings + if (!wbt::Log::getSingleton().getWarnings().empty()) { + // Get the singleton + wbt::Log& log = wbt::Log::getSingleton(); + + // Handle the prefix + std::string warningMsg; + if (!prefix.empty()) { + log.setPrefix(prefix); + warningMsg = log.getWarnings(); + log.resetPrefix(); + } + else { + warningMsg = log.getWarnings(); + } + + // Trim the message if needed + if (warningMsg.length() >= bufferLen) { + warningMsg = warningMsg.substr(0, bufferLen-1); + } + + // Forward to Simulink + sprintf(warningBuffer, "%s", warningMsg.c_str()); + ssWarning(S, warningBuffer); + log.clearWarnings(); + } + + // Notify errors + if (!status) { + // Get the singleton + wbt::Log& log = wbt::Log::getSingleton(); + + // Handle the prefix + std::string errorMsg; + if (!prefix.empty()) { + log.setPrefix(prefix); + errorMsg = log.getErrors(); + log.resetPrefix(); + } + else { + errorMsg = log.getErrors(); + } + + // Trim the message if needed + if (errorMsg.length() >= bufferLen) { + errorMsg = errorMsg.substr(0, bufferLen-1); + } + + // Forward to Simulink + sprintf(errorBuffer, "%s", errorMsg.c_str()); + ssSetErrorStatus(S, errorBuffer); + return; + } +} + // Function: MDL_CHECK_PARAMETERS #define MDL_CHECK_PARAMETERS #if defined(MDL_CHECK_PARAMETERS) && defined(MATLAB_MEX_FILE) @@ -65,10 +128,12 @@ static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, // block's characteristics (number of inputs, s, states, etc.). static void mdlInitializeSizes(SimStruct *S) { - static char errorBuffer[512]; + // Initialize the Log singleton + wbt::Log::getSingleton().clear(); + if (ssGetSFcnParamsCount(S) < 1) { - sprintf(errorBuffer, "%s", "The block type parameter must be specified"); - ssSetErrorStatus(S, errorBuffer); + wbt::Log::getSingleton().error("The block type parameter must be specified"); + catchLogMessages(false, S, "\n[" + std::string(__func__) + "]"); return; } char *classNameStr = mxArrayToString(ssGetSFcnParam(S, 0)); @@ -78,43 +143,39 @@ static void mdlInitializeSizes(SimStruct *S) //We cannot save data in PWork during the initializeSizes phase ssSetNumPWork(S, 1); - + + // Notify errors if (!block) { - sprintf(errorBuffer, "Could not create an object of type %s", className.c_str()); - ssSetErrorStatus(S, errorBuffer); + wbt::Log::getSingleton().error("Could not create an object of type " + className); + catchLogMessages(false, S, "\n[" + std::string(__func__) + "]"); return; } - + ssSetNumSFcnParams(S, 1 + block->numberOfParameters()); ssSetSFcnParamTunable(S, 0, false); for (unsigned i = 1; i < ssGetNumSFcnParams(S); ++i) { bool tunable = false; block->parameterAtIndexIsTunable(i - 1, tunable); ssSetSFcnParamTunable(S, i, tunable); - } - - + + #if defined(MATLAB_MEX_FILE) - if(ssGetNumSFcnParams(S) == ssGetSFcnParamsCount(S)){ + if(ssGetNumSFcnParams(S) == ssGetSFcnParamsCount(S)) { mdlCheckParameters(S); - if(ssGetErrorStatus(S)){ + if(ssGetErrorStatus(S)) { return; } - } else{ - sprintf(errorBuffer, "%s", "Number of parameters different from those defined"); - ssSetErrorStatus(S, errorBuffer); + } else { + wbt::Log::getSingleton().error("Number of parameters different from those defined"); + catchLogMessages(false, S, "\n[" + std::string(__func__) + "]"); return; } #endif - wbt::Error error; wbt::SimulinkBlockInformation blockInfo(S); - if (!block->configureSizeAndPorts(&blockInfo, &error)) { - sprintf(errorBuffer, "%s", error.message.substr(0, 511).c_str()); - ssSetErrorStatus(S, errorBuffer); - return; - } + bool ok = block->configureSizeAndPorts(&blockInfo); + catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); ssSetNumSampleTimes(S, 1); @@ -134,17 +195,15 @@ static void mdlInitializeSizes(SimStruct *S) std::vector additionalOptions = block->additionalBlockOptions(); - for (std::vector::const_iterator it = additionalOptions.begin(); - it < additionalOptions.end(); ++it) { - wbt::Data option; - if (blockInfo.optionFromKey(*it, option)) { - options |= option.uint32Data(); + for (auto additionalOption: additionalOptions) { + double option; + if (blockInfo.optionFromKey(additionalOption, option)) { + options |= static_cast(option); } } ssSetOptions(S, options); delete block; - } // Function: mdlInitializeSampleTimes ========================================= @@ -173,15 +232,12 @@ static void mdlStart(SimStruct *S) wbt::Block *block = wbt::Block::instantiateBlockWithClassName(className); ssSetPWorkValue(S, 0, block); - wbt::Error error; wbt::SimulinkBlockInformation blockInfo(S); - if (!block || !block->initialize(&blockInfo, &error)) { - yError() << "[mdlStart]" << error.message; - static char errorBuffer[1024]; - sprintf(errorBuffer, "[mdlStart]%s", error.message.substr(0, 1023 - strlen("[mdlStart]")).c_str()); - ssSetErrorStatus(S, errorBuffer); + bool ok = false; + if (block) { + ok = block->initialize(&blockInfo); } - + catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); } @@ -192,13 +248,13 @@ static void mdlUpdate(SimStruct *S, int_T tid) UNUSED_ARG(tid); if (ssGetNumPWork(S) > 0) { wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); - wbt::Error error; + wbt::SimulinkBlockInformation blockInfo(S); - if (!block || !block->updateDiscreteState(&blockInfo, &error)) { - static char errorBuffer[1024]; - sprintf(errorBuffer, "[mdlOutputs]%s", error.message.substr(0, 1023 - strlen("[mdlOutputs]")).c_str()); - ssSetErrorStatus(S, errorBuffer); + bool ok = false; + if (block) { + ok = block->updateDiscreteState(&blockInfo); } + catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); } } #endif @@ -210,13 +266,13 @@ static void mdlInitializeConditions(SimStruct *S) { if (ssGetNumPWork(S) > 0) { wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); - wbt::Error error; + wbt::SimulinkBlockInformation blockInfo(S); - if (!block || !block->initializeInitialConditions(&blockInfo, &error)) { - static char errorBuffer[1024]; - sprintf(errorBuffer, "[mdlInitializeConditions]%s", error.message.substr(0, 1023 - strlen("[mdlInitializeConditions]")).c_str()); - ssSetErrorStatus(S, errorBuffer); + bool ok = false; + if (block) { + ok = block->initializeInitialConditions(&blockInfo); } + catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); } } #endif @@ -240,35 +296,33 @@ static void mdlOutputs(SimStruct *S, int_T tid) UNUSED_ARG(tid); if (ssGetNumPWork(S) > 0) { wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); - wbt::Error error; + wbt::SimulinkBlockInformation blockInfo(S); - if (!block || !block->output(&blockInfo, &error)) { - static char errorBuffer[1024]; - sprintf(errorBuffer, "[mdlOutputs]%s", error.message.substr(0, 1023 - strlen("[mdlOutputs]")).c_str()); - ssSetErrorStatus(S, errorBuffer); + bool ok = false; + if (block) { + ok = block->output(&blockInfo); } + catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); } - } static void mdlTerminate(SimStruct *S) { if (ssGetNumPWork(S) > 0 && ssGetPWork(S)) { wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); - wbt::Error error; + wbt::SimulinkBlockInformation blockInfo(S); + bool ok = false; if (block) { - if (block->terminate(&blockInfo, &error)) { - delete block; - ssSetPWorkValue(S, 0, NULL); - } else { - static char errorBuffer[1024]; - sprintf(errorBuffer, "[mdlTerminate]%s", error.message.substr(0, 1023 - strlen("[mdlTerminate]")).c_str()); - ssSetErrorStatus(S, errorBuffer); - } + ok = block->terminate(&blockInfo); } - } + catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); + if (ok) { + delete block; + ssSetPWorkValue(S, 0, NULL); + } + } } // Required S-function trailer From b4beb26830179ee9299ca4cabc1d3a7374463caa Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 30 Oct 2017 10:37:45 +0000 Subject: [PATCH 07/92] Removed WBIModelBlock Its functionality are implemented by the new generic WBBlock, which is a refactored version of WBIBlock that access robot resources in a lazy way. This approach allows avoiding the previous separation between WBIBlock and WBIModelBlock. --- toolbox/CMakeLists.txt | 2 -- toolbox/include/base/WBIModelBlock.h | 36 ---------------------------- toolbox/src/base/WBIModelBlock.cpp | 27 --------------------- 3 files changed, 65 deletions(-) delete mode 100644 toolbox/include/base/WBIModelBlock.h delete mode 100644 toolbox/src/base/WBIModelBlock.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 9838ee86f..7ae729c4a 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -65,7 +65,6 @@ configure_block(BLOCK_NAME "Base" src/base/Log.cpp src/base/WBInterface.cpp src/base/factory.cpp - src/base/WBIModelBlock.cpp src/base/SimulinkBlockInformation.cpp #this is temp src/base/Signal.cpp HEADERS include/base/toolbox.h @@ -74,7 +73,6 @@ configure_block(BLOCK_NAME "Base" include/base/WBIBlock.h include/base/Log.h include/base/WBInterface.h - include/base/WBIModelBlock.h include/base/SimulinkBlockInformation.h #this is temp include/base/Signal.h ) diff --git a/toolbox/include/base/WBIModelBlock.h b/toolbox/include/base/WBIModelBlock.h deleted file mode 100644 index ff054e655..000000000 --- a/toolbox/include/base/WBIModelBlock.h +++ /dev/null @@ -1,36 +0,0 @@ -#ifndef WBT_WBIMODELBLOCK_H -#define WBT_WBIMODELBLOCK_H - -#include "WBIBlock.h" - -namespace wbt { - class WBIModelBlock; - class BlockInformation; -} - -/** - * Basic class for WBI related blocks. - * This class (the whole toolbox in reality) assumes the block represent - * an instantaneous system (i.e. not a dynamic system). - * - * You can create a new block by deriving this class and implementing at least - * the output method. - * - * This block implements the following default behaviours: - * - it ask for 4 parameters (robot name, local (module) name, wbi config file and wbi list) - * - It initializes the yarp network and the whole body interface object - * - During terminate it closes and release the interface object and terminate the yarp network - * - * @Note: Usually you want to call this class implementations at some point in your - * method overridings, unless you want to completely change the code (but at that point - * you probabily want to derive from Block instead) - */ -class wbt::WBIModelBlock : public wbt::WBIBlock { - -public: - virtual ~WBIModelBlock(); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); -}; - -#endif /* WBT_WBIMODELBLOCK_H */ diff --git a/toolbox/src/base/WBIModelBlock.cpp b/toolbox/src/base/WBIModelBlock.cpp deleted file mode 100644 index 3921b3cf2..000000000 --- a/toolbox/src/base/WBIModelBlock.cpp +++ /dev/null @@ -1,27 +0,0 @@ -#include "WBIModelBlock.h" - -#include "WBInterface.h" -#include "Error.h" - -wbt::WBIModelBlock::~WBIModelBlock() {} - -bool wbt::WBIModelBlock::initialize(wbt::BlockInformation *blockInfo, wbt::Error *error) -{ - if (!configureWBIParameters(blockInfo, error)) - return false; - - if (!WBInterface::sharedInstance().initializeModel()) { - if (error) error->message = "Failed to initialize WBI"; - return false; - } - return true; -} - -bool wbt::WBIModelBlock::terminate(wbt::BlockInformation *blockInfo, wbt::Error *error) -{ - if (!WBInterface::sharedInstance().terminateModel()) { - if (error) error->message = "Failed to terminate WBI"; - return false; - } - return true; -} From aee4eed5b118ee4b2e9ca556bf9ae3d75d528386 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 30 Oct 2017 10:43:49 +0000 Subject: [PATCH 08/92] New Configuration class This class contains the data passed from Simulink. It matches the data structure of Matlab's WBToolboxConfig.getSimulinkParameters() struct. --- toolbox/CMakeLists.txt | 2 + toolbox/include/base/Configuration.h | 162 +++++++++++++++++++++++++++ toolbox/src/base/Configuration.cpp | 123 ++++++++++++++++++++ 3 files changed, 287 insertions(+) create mode 100644 toolbox/include/base/Configuration.h create mode 100644 toolbox/src/base/Configuration.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 7ae729c4a..25a304fa7 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -67,6 +67,7 @@ configure_block(BLOCK_NAME "Base" src/base/factory.cpp src/base/SimulinkBlockInformation.cpp #this is temp src/base/Signal.cpp + src/base/Configuration.cpp HEADERS include/base/toolbox.h include/base/Block.h include/base/BlockInformation.h @@ -75,6 +76,7 @@ configure_block(BLOCK_NAME "Base" include/base/WBInterface.h include/base/SimulinkBlockInformation.h #this is temp include/base/Signal.h + include/base/Configuration.h ) configure_block(BLOCK_NAME "Inverse Kinematics" diff --git a/toolbox/include/base/Configuration.h b/toolbox/include/base/Configuration.h new file mode 100644 index 000000000..192656cdf --- /dev/null +++ b/toolbox/include/base/Configuration.h @@ -0,0 +1,162 @@ +#ifndef WBT_TOOLBOXCONFIG_H +#define WBT_TOOLBOXCONFIG_H + +#include +#include + +namespace wbt { + class Configuration; +} + +/** + * \class Configuration Configuration.h + * + * This class stores in a C++ object the content of the WBToolboxConfig Matlab class. + * + * @see WBToolboxConfig Matlab Class + * @see RobotInterface + */ +class wbt::Configuration +{ +// TODO: check how localName is used +private: + std::string m_robotName; ///< Name of the robot + std::string m_urdfFile; ///< Name of the file containing the urdf model + std::string m_localName; ///< Prefix appended to the opened ports + std::vector m_controlledJoints; ///< Subset of controlled joints + std::vector m_controlBoardsNames; ///< Names of the used ControlBoard names + std::vector m_gravityVector; ///< The gravity vector + size_t m_dofs; //< DoFs extracted my m_controlBoardsNames vector + +public: + Configuration(); + ~Configuration() = default; + + // SET METHODS + // =========== + + /** + * Initialize the Configuration object + * + * @param robotName Name of the robot + * @param urdfFile Name of the file containing the urdf model + * @param controlledJoints Subset of controlled joints + * @param controlBoardsNames Names of the used ControlBoard names + * @param localName Prefix appended to the opened ports + * @param gravityVector The gravity vector + */ + void setParameters(std::string robotName, + std::string urdfFile, + std::vector controlledJoints, + std::vector controlBoardsNames, + std::string localName, + std::vector gravityVector); + + /** + * Set the name of the robot + * + * @param robotName Name of the robot + */ + void setRobotName(const std::string& robotName); + + /** + * Set the name of the file containing the urdf model + * + * @param urdfFile Name of the file containing the urdf model + */ + void setUrdfFile(const std::string& urdfFile); + + /** + * Set the subset of controlled joints + * @param controlledJoints Subset of controlled joints + */ + void setControlledJoints(const std::vector& controlledJoints); + + /** + * Set the names of the used ControlBoard names + * @param controlBoardsNames Names of the used ControlBoard names + */ + void setControlBoardsNames(const std::vector& controlBoardsNames); + + /** + * Set the prefix appended to the opened ports + * @param localName Prefix appended to the opened ports + */ + void setLocalName(const std::string& localName); + + /** + * Set the gravity vector + * @param gravityVector The gravity vector + */ + void setGravityVector(const std::vector& gravityVector); + + // GET METHODS + // =========== + + /** + * Set the name of the robot + * + * @return Name of the robot + */ + const std::string& getRobotName() const; + + /** + * Set the name of the file containing the urdf model + * + * @return Name of the file containing the urdf model + */ + const std::string& getUrdfFile() const; + + /** + * Set the subset of controlled joints + * + * @return Subset of controlled joints + */ + const std::vector& getControlledJoints() const; + + /** + * Set the names of the used ControlBoard names + * + * @return Names of the used ControlBoard names + */ + const std::vector& getControlBoardsNames() const; + + /** + * Set the prefix appended to the opened ports + * + * @return Prefix appended to the opened ports + */ + const std::string& getLocalName() const; + + /** + * Set the gravity vector + * + * @return The gravity vector + */ + const std::vector& getGravityVector() const; + + /** + * Get the configured number of DoFs + * + * @return The configured number of DoFs + */ + const size_t& getNumberOfDoFs() const; + + // OTHER METHODS + // ============= + + /** + * Checks if the stored configuration is valid, i.e. all the required fields have + * been saved successfully + * + * @return True if the configuration is valid + */ + bool isValid() const; + + // OPERATORS OVERLOADING + // ===================== + + bool operator==(const Configuration &config) const; +}; + +#endif // WBT_TOOLBOXCONFIG_H diff --git a/toolbox/src/base/Configuration.cpp b/toolbox/src/base/Configuration.cpp new file mode 100644 index 000000000..d28857016 --- /dev/null +++ b/toolbox/src/base/Configuration.cpp @@ -0,0 +1,123 @@ +#include "Configuration.h" + +using namespace wbt; + +Configuration::Configuration() +: m_dofs(0) +{} + +// SET METHODS +// =========== + +void Configuration::setParameters(std::string robotName, + std::string urdfFile, + std::vector controlledJoints, + std::vector controlBoardsNames, + std::string localName, + std::vector gravityVector) +{ + setRobotName(robotName); + setUrdfFile(urdfFile); + setControlledJoints(controlledJoints); + setControlBoardsNames(controlBoardsNames); + setLocalName(localName); + setGravityVector(gravityVector); +} + +void Configuration::setRobotName(const std::string& robotName) +{ + m_robotName = robotName; +} + +void Configuration::setUrdfFile(const std::string& urdfFile) +{ + m_urdfFile = urdfFile; +} + +void Configuration::setControlledJoints(const std::vector& controlledJoints) +{ + m_controlledJoints = controlledJoints; + m_dofs = controlledJoints.size(); +} + +void Configuration::setControlBoardsNames(const std::vector& controlBoardsNames) +{ + m_controlBoardsNames = controlBoardsNames; +} + +void Configuration::setLocalName(const std::string& localName) +{ + m_localName = localName; +} + +void Configuration::setGravityVector(const std::vector& gravityVector) +{ + m_gravityVector = gravityVector; +} + +// GET METHODS +// =========== + +const std::string& Configuration::getRobotName() const +{ + return m_robotName; +} + +const std::string& Configuration::getUrdfFile() const +{ + return m_urdfFile; +} + +const std::vector& Configuration::getControlledJoints() const +{ + return m_controlledJoints; +} + +const std::vector& Configuration::getControlBoardsNames() const +{ + return m_controlBoardsNames; +} + +const std::string& Configuration::getLocalName() const +{ + return m_localName; +} + +const std::vector& Configuration::getGravityVector() const +{ + return m_gravityVector; +} + +const size_t& Configuration::getNumberOfDoFs() const +{ + return m_dofs; +} + +// OTHER METHODS +// ============= + +bool Configuration::isValid() const +{ + bool status = !m_robotName.empty() && + !m_urdfFile.empty() && + !m_localName.empty() && + !m_controlledJoints.empty() && + !m_controlBoardsNames.empty() && + !m_gravityVector.empty() && + m_dofs > 0; + return status; +} + +// OPERATORS OVERLOADING +// ===================== + +bool Configuration::operator==(const Configuration &config) const +{ + return this->m_robotName == config.m_robotName && + this->m_urdfFile == config.m_urdfFile && + this->m_localName == config.m_localName && + this->m_controlledJoints == config.m_controlledJoints && + this->m_controlBoardsNames == config.m_controlBoardsNames && + this->m_gravityVector == config.m_gravityVector && + this->m_dofs == config.m_dofs; +} From 8a68ac718e9a75d4d9e8952ea02be3f3842ddfe3 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 30 Oct 2017 10:47:50 +0000 Subject: [PATCH 09/92] New RobotInterface class This class contains all the required data structures to operate on a robot, either through the model or the interfaces to the hardware / gazebo. From the Simulink point of view, there is one instance of RobotInterface for every Configuration block added in the model. In fact, RobotInterface extends by composition the Configuration object. It handles the pointers to its members in a lazy way, initializing on the fly the asked resource. --- toolbox/CMakeLists.txt | 2 + toolbox/include/base/RobotInterface.h | 228 +++++++++++++ toolbox/src/base/RobotInterface.cpp | 447 ++++++++++++++++++++++++++ 3 files changed, 677 insertions(+) create mode 100644 toolbox/include/base/RobotInterface.h create mode 100644 toolbox/src/base/RobotInterface.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 25a304fa7..f084744c7 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -68,6 +68,7 @@ configure_block(BLOCK_NAME "Base" src/base/SimulinkBlockInformation.cpp #this is temp src/base/Signal.cpp src/base/Configuration.cpp + src/base/RobotInterface.cpp HEADERS include/base/toolbox.h include/base/Block.h include/base/BlockInformation.h @@ -77,6 +78,7 @@ configure_block(BLOCK_NAME "Base" include/base/SimulinkBlockInformation.h #this is temp include/base/Signal.h include/base/Configuration.h + include/base/RobotInterface.h ) configure_block(BLOCK_NAME "Inverse Kinematics" diff --git a/toolbox/include/base/RobotInterface.h b/toolbox/include/base/RobotInterface.h new file mode 100644 index 000000000..83da54cde --- /dev/null +++ b/toolbox/include/base/RobotInterface.h @@ -0,0 +1,228 @@ +#ifndef WBT_ROBOTINTERFACE_H +#define WBT_ROBOTINTERFACE_H + +#include "Configuration.h" +#include +#include +#include +#include +#include +#include + +namespace yarp { + namespace dev { + class PolyDriver; + class IPositionControl; + class IPositionDirect; + class IVelocityControl; + class ITorqueControl; + class IPWMControl; + class IControlMode2; + class ICurrentControl; + class IEncoders; + class IControlLimits2; + class IPidControl; + } +} + +namespace iDynTree { + class KinDynComputations; +} + +namespace wbt { + class RobotInterface; + struct YarpDevices; + + typedef int jointIdx_yarp; + typedef int jointIdx_iDynTree; + typedef unsigned cb_idx; + typedef std::unordered_map> JointsMapIndex; + typedef std::unordered_map> JointsMapString; +} + +/** + * \struct wbt::YarpDevices RobotInterface.h + * + * This struct contains shared_ptrs to the devices which are (lazy) asked from the blocks. + * + * @note The shared_ptr is owned only by wbt::RobotInterface. All the blocks will receive a + * weak_ptr. + * @remark Right now only asking / setting the whole joint set of the current Configuration is + * supported. If in the future the support of operating on a subset will be implemented, + * IPositionControl2 and IVelocityControl2 should be implemented. For the time being, + * a possible workaround for this situation is creating a new configuration block + * containing only the reduced set in a deeper-hierarchy Simulink's subsystem. + * @see RobotInterface::getDevice + */ +struct wbt::YarpDevices +{ + std::shared_ptr iControlMode2; + std::shared_ptr iPositionControl; + std::shared_ptr iPositionDirect; + std::shared_ptr iVelocityControl; + std::shared_ptr iTorqueControl; + std::shared_ptr iPWMControl; + std::shared_ptr iCurrentControl; + std::shared_ptr iEncoders; + std::shared_ptr iControlLimits2; + std::shared_ptr iPidControl; +}; + +// TODO o pensare come evitare di avere due conf con es position e torque nei setref con lo stesso robot. +// e' un casino -> aggiungere max un warning o solo documentazione. +// Solo un setReference attivo per configuration.Se ci sono due setReference con lo stesso +// set di giunti attivi contemporaneamente. Oppure due stessi blocchi setReference con lo stesso blocco config. + +/** + * \class wbt::RobotInterface RobotInterface.h + * + * This class holds the configuration used by one or more blocks, and all the objects to operate + * with the specified robot (real or model). + * + * @see wbt::Configuration + * @see wbt::YarpDevices + * @see iDynTree::KinDynComputations + */ +class wbt::RobotInterface +{ +private: + std::shared_ptr m_robotDevice; + std::shared_ptr m_kinDynComp; + wbt::YarpDevices m_yarpDevices; + + // Maps used to store infos about yarp's and idyntree's internal joint indexing + std::shared_ptr m_jointsMapIndex; + std::shared_ptr m_jointsMapString; + // std::unordered_map, joint_name> m_yarp2joint; + + // Configuration from Simulink Block's parameters + const wbt::Configuration m_config; + + // Counters for resource allocation / deallocation + unsigned m_robotDeviceCounter; + + // INITIALIZATION HELPERS + // ====================== + + /** + * Initialize the iDynTree::KinDynComputations with the information contained + * in wbt::Configuration. It finds the urdf file and stores the object to operate on it. + * If the joint list contained in RobotInterface::m_config is not complete, it loads a + * reduced model of the robot + * + * @return True if success + */ + bool initializeModel(); + + /** + * Configure a RemoteControlBoardRemapper device in order to allow + * interfacing the toolbox with the robot (real or in Gazebo). + * + * @return True if success + */ + bool initializeRemoteControlBoardRemapper(); + + // OTHER PRIVATE METHODS + // ===================== + + /** + * Gather a device from the RemoteControlBoardRemapper as a \c weak_ptr + * + * @param device The RemoteControlBoardRemapper device + * @return The dynamic(ally)_cast device + * @tparam T The type of the retured device + */ + template std::weak_ptr getDevice(std::shared_ptr device); + + /** + * Creates the map between joints (specified as either names or idyntree indices) and + * their YARP representation, which consist in a pair: Control Board index and joint index inside + * the its Control Board. + * + * @see getJointsMapString + * @see getJointsMapIndex + * + * @return True if the map has been created successfully + */ + bool mapDoFs(); +public: + + // CONSTRUCTOR / DESTRUCTOR + // ======================== + + RobotInterface() = delete; + RobotInterface(const wbt::Configuration& c); + ~RobotInterface(); + + // GET METHODS + // =========== + + /** + * Get the current configuration + * + * @return A reference of the Configuration object containing the current configuraton + */ + const wbt::Configuration& getConfiguration() const; + + /** + * Get the map between model joint namesand the YARP representation (Control Board and + * joint index) + * + * @return The joint map + */ + const std::shared_ptr getJointsMapString(); + + /** + * Get the map between model joint indices and the YARP representation (Control Board and + * joint index) + * + * @return The joint map + */ + const std::shared_ptr getJointsMapIndex(); + + /** + * Get the object to operate on the configured model + * + * @return A \c shared_ptr to the KinDynComputations object + */ + const std::shared_ptr getKinDynComputations(); + + /** + * Get a \c weak_ptr to an interface from the RemoteControlBoardRemapper + * + * param interface [out] A \c weak_ptr to the interface + * @return True if the \c weak_ptr is valid + * @tparam T The type of interface + */ + template + bool getInterface(std::weak_ptr& interface); + + // LAZY EVALUATION + // =============== + + /** + * Handles the internal counter for using the RemoteControlBoardRemapper + * + * @attention All the blocks which need to use any of the interfaces provided by + * wbt::YarpDevices must call this function in their initialize() method. + * @see releaseRemoteControlBoardRemapper + * + * @return True if success + */ + bool retainRemoteControlBoardRemapper(); + + /** + * Handles the internal counter for using the RemoteControlBoardRemapper. After the call + * from the last instance which retained the object, the RemoteControlBoardRemapper and all + * the allocated drivers get destroyed. + * + * @note On the contrary of retainRemoteControlBoardRemapper, this method is already + * called in wbt::~WBBlock + * @see retainRemoteControlBoardRemapper + * + * @return True if success + */ + bool releaseRemoteControlBoardRemapper(); +}; + +#endif /* end of include guard: WBT_ROBOTINTERFACE_H */ diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp new file mode 100644 index 000000000..59633f63b --- /dev/null +++ b/toolbox/src/base/RobotInterface.cpp @@ -0,0 +1,447 @@ +#include "RobotInterface.h" +#include "Log.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace wbt { + static std::string vectorToString(std::vector v, std::string prefix=""); + + // The declaration of the following template specializations are required only by GCC + using namespace yarp::dev; + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(std::weak_ptr& interface); +} + +using namespace wbt; + +// CONSTRUCTOR / DESTRUCTOR +// ======================== + + +RobotInterface::RobotInterface(const wbt::Configuration& c) +: m_config(c) +, m_robotDeviceCounter(0) +{} + +RobotInterface::~RobotInterface() +{ + // Asserts for debugging purpose. + + // - 1 if at least one block asked the model. At this point only the shared_ptr + // of m_kinDynComp should be still alive (--> 1) + // - 0 if no block asked for the model. m_kinDynComp was never allocated. + assert(m_kinDynComp.use_count() <= 1); + + // m_robotDevice should be destroyed by the last releaseCB() + assert(!m_robotDevice); + assert(m_robotDeviceCounter == 0); +} + +bool RobotInterface::mapDoFs() +{ + std::unique_ptr controlBoard; + std::vector> iAxisInfos; + yarp::os::Property options; + + for (unsigned cbNum = 0; cbNum < m_config.getControlBoardsNames().size(); ++cbNum) { + // Configure the single control board + options.clear(); + options.put("device","remotecontrolboard"); + const std::string prefix = "/" + m_config.getRobotName() + "/"; + const std::string remoteName = prefix + m_config.getControlBoardsNames().at(cbNum); + options.put("remote", remoteName); + options.put("localPortPrefix", "WBTtmp"); + + // Try to open the control board + if (!controlBoard->open(options) || !controlBoard->isValid()) { + Log::getSingleton().error("Unable to open RemoteControlBoard " + remoteName); + return false; + } + + // Get an IAxisInfo object from the device + std::unique_ptr iAxisInfo; + yarp::dev::IAxisInfo* iAxisInfoPtr = iAxisInfo.get(); + controlBoard->view(iAxisInfoPtr); + if (!iAxisInfoPtr) { + Log::getSingleton().error("Unable to open IAxisInfo from " + remoteName); + return false; + } + + // Get an IEncoders object from the device + // This is used to get how many joints the control board contains + std::unique_ptr iEnc; + yarp::dev::IEncoders* iEncPtr = iEnc.get(); + controlBoard->view(iEncPtr); + int numAxes; + if (!iEncPtr || !iEncPtr->getAxes(&numAxes)) { + Log::getSingleton().error("Unable to open IEncoders from " + remoteName); + return false; + } + + // Iterate all the joints in the selected Control Board + for (unsigned axis = 0; axis < numAxes; ++axis) { + std::string axisName; + if (!iAxisInfoPtr->getAxisName(axis, axisName)) { + Log::getSingleton().error("Unable to get AxisName from " + remoteName); + return false; + } + // Look if axisName is a controlledJoint + bool found = false; + for (const auto& controlledJoint : m_config.getControlledJoints()) { + if (controlledJoint == axisName) { + // Get the iDynTree index + const auto& model = getKinDynComputations()->model(); + iDynTree::LinkIndex iDynLinkIdx = model.getLinkIndex(axisName); + if (iDynLinkIdx == iDynTree::LINK_INVALID_INDEX) { + Log::getSingleton().error("Joint " + axisName + " exists in the " + + remoteName + "control board but not in the model."); + return false; + } + // If this is the first entry to add, allocate the objects + if (!m_jointsMapIndex) { + m_jointsMapIndex = std::make_shared(); + } + if (!m_jointsMapString) { + m_jointsMapString = std::make_shared(); + } + // Create a new entry in the map objects + m_jointsMapString->at(controlledJoint) = {cbNum, axis}; + m_jointsMapIndex->at(static_cast(iDynLinkIdx)) = {cbNum, axis}; + found = true; + break; + } + } + // Notify that the control board just checked is not used by any joint + // of the controlledJoints list + if (!found) { + Log::getSingleton().warning("No controlled joints found in " + + m_config.getControlBoardsNames().at(cbNum) + + " control board. It might be unsed."); + } + } + } + + if (!controlBoard->close()) { + Log::getSingleton().error("Unable to close the device of the Control Board."); + return false; + } + return true; +} + +// GET METHODS +// =========== + +const wbt::Configuration& RobotInterface::getConfiguration() const +{ + return m_config; +} + +const std::shared_ptr RobotInterface::getJointsMapString() +{ + if (m_jointsMapString->empty()) { + if (!mapDoFs()) { + Log::getSingleton().error("Failed to create the Yarp - iDynTree joint map."); + return nullptr; + } + } + + assert (m_jointsMapString); + return m_jointsMapString; +} + +const std::shared_ptr RobotInterface::getJointsMapIndex() +{ + if (m_jointsMapIndex->empty()) { + if (!mapDoFs()) { + Log::getSingleton().error("Failed to create the Yarp - iDynTree joint map."); + return nullptr; + } + } + + assert (m_jointsMapIndex); + return m_jointsMapIndex; +} + +const std::shared_ptr RobotInterface::getKinDynComputations() +{ + if (m_kinDynComp) { + return m_kinDynComp; + } + + // Otherwise, initialize a new object + if (initializeModel()) { + return m_kinDynComp; + } + + // Return an empty shared_ptr (implicitly initialized) + return nullptr; +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iControlMode2); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iPositionControl); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iPositionDirect); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iVelocityControl); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iTorqueControl); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iPWMControl); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iCurrentControl); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iEncoders); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iControlLimits2); + return !interface.expired(); +} + +template <> +bool RobotInterface::getInterface(std::weak_ptr& interface) +{ + interface = getDevice(m_yarpDevices.iPidControl); + return !interface.expired(); +} + +// LAZY EVALUATION +// =============== + +bool RobotInterface::retainRemoteControlBoardRemapper() +{ + if (m_robotDeviceCounter > 0) { + m_robotDeviceCounter++; + return true; + } + + assert(!m_robotDevice); + if (m_robotDevice) { + m_robotDevice.reset(); + } + + if (!initializeRemoteControlBoardRemapper()) { + return false; + } + + m_robotDeviceCounter++; + return true; +} + +bool RobotInterface::releaseRemoteControlBoardRemapper() +{ + // The RemoteControlBoardRemapper has not been used + if (m_robotDeviceCounter == 0) { + return true; + } + + // If there are at most 2 blocks with th CB still used + if (m_robotDeviceCounter > 1) { + m_robotDeviceCounter--; + return true; + } + + // This should be executed by the last block which uses CB (m_robotDeviceCounter=1) + assert(m_robotDevice); + if (m_robotDevice) { + // Free all the drivers + m_yarpDevices.iControlMode2.reset(); + m_yarpDevices.iPositionControl.reset(); + m_yarpDevices.iPositionDirect.reset(); + m_yarpDevices.iVelocityControl.reset(); + m_yarpDevices.iTorqueControl.reset(); + m_yarpDevices.iPWMControl.reset(); + m_yarpDevices.iCurrentControl.reset(); + m_yarpDevices.iEncoders.reset(); + m_yarpDevices.iControlLimits2.reset(); + m_yarpDevices.iPidControl.reset(); + // Close the device + m_robotDevice->close(); + // Free the object + m_robotDevice.reset(); + } + + m_robotDeviceCounter = 0; + return true; +} + +// INITIALIZATION HELPERS +// ====================== + +bool RobotInterface::initializeModel() +{ + assert (!m_kinDynComp); + + // Allocate the object + m_kinDynComp = std::make_shared(); + if (!m_kinDynComp) return false; + + // Use RF to load the urdf file + // ---------------------------- + + // Initialize RF + // Workaround for the fact that ResourceFinder initializes the network by itself. See YARP#1014 + using namespace yarp::os; + Network network; + ResourceFinder& rf = ResourceFinder::getResourceFinderSingleton(); + rf.configure(0, 0); + + // Get the absolute path of the urdf file + std::string urdf_file = getConfiguration().getUrdfFile(); + std::string urdf_file_path = rf.findFile(urdf_file.c_str()); + + // Load the reduced model into KinDynComputations + // ---------------------------------------------- + + // Load the joint list + std::vector controlledJoints = getConfiguration().getControlledJoints(); + + // Use ModelLoader to load the reduced model + iDynTree::ModelLoader mdlLoader; + if (!mdlLoader.loadReducedModelFromFile(urdf_file_path, controlledJoints)) { + Log::getSingleton().error("ToolboxSingleton: impossible to load " + urdf_file + "."); + Log::getSingleton().error("Probably the joint list contains an entry not present in the urdf model."); + return false; + } + + // Add the loaded model to the KinDynComputations object + return m_kinDynComp->loadRobotModel(mdlLoader.model()); +} + +bool RobotInterface::initializeRemoteControlBoardRemapper() +{ + // Setup the RemoteControlBoardRemapper + yarp::os::Property options; + options.put("device", "remotecontrolboardremapper"); + options.put("axesNames", vectorToString(m_config.getControlledJoints())); + std::string prefix = "/" + m_config.getRobotName() + "/"; + options.put("remoteControlBoards", vectorToString(m_config.getControlBoardsNames(), prefix)); + options.put("localPortPrefix", m_config.getLocalName()); + yarp::os::Property& remoteCBOpts = options.addGroup("REMOTE_CONTROLBOARD_OPTIONS"); + remoteCBOpts.put("writeStrict","on"); + + // Allocate the device driver + m_robotDevice = std::make_shared(); + + if (!m_robotDevice) { + return false; + } + + // Open the device driver + if (m_robotDevice->open(options) && m_robotDevice->isValid()) { + return true; + } + + // Remove garbage if the opening fails + m_robotDevice.reset(); + return false; +} + +// OTHER METHODS +// ============= + +template +std::weak_ptr RobotInterface::getDevice(std::shared_ptr device) +{ + if (!device) { + // Blocks which require the RemoteControlBoardRemapper need to retain / release it + // in their initialization / terminate phase; + assert(m_robotDevice); + if (!m_robotDevice) { + // Return an empty weak pointer + return std::weak_ptr(); + } + + T* ptr = nullptr; + if (!m_robotDevice->view(ptr)) { + // Return an empty weak_ptr + return std::weak_ptr(); + } + // Store ptr into the smart pointer + device.reset(ptr); + } + // Implicit conversion from shared_ptr to weak_ptr + return device; +} + +/** + * Converts a vector of strings into a string format \code (element1 element2 element3) \endcode. + * It optioanlly support appending a prefix to the elements. e.g. + * \code ({prefix}element1 {prefix}element2 {prefix}element3) + * + * @param v The vector of strings + * @param prefix The optional element prefix + * @return The serialized string + */ +std::string wbt::vectorToString(std::vector v, std::string prefix) +{ + // Add the prefix if specified + if (!prefix.empty()) { + for (auto& str : v) { + str = prefix + str; + } + } + + // Create a string in a format which YARP likes: (item1 item2 item3) + std::stringstream output; + std::ostream_iterator output_iterator(output, " "); + std::copy(v.begin(), v.end(), output_iterator); + return "(" + output.str() + ")"; +} From af1fa4106a4597254b28b4f3eaecb41261600124 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 11:14:43 +0000 Subject: [PATCH 10/92] ClockServer thrift messages are now a static library This is a temporary fix. The cpp file should be generated by its thrift source, which should be found already installed in the system. A new CMake option e.g. USE_GAZEBO should be added. --- toolbox/CMakeLists.txt | 10 +++-- toolbox/autogenerated/CMakeLists.txt | 38 +++++++++++++++++++ .../autogenerated/src/thrift/ClockServer.cpp | 4 +- 3 files changed, 45 insertions(+), 7 deletions(-) create mode 100644 toolbox/autogenerated/CMakeLists.txt diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index f084744c7..8da7e2e47 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -143,13 +143,11 @@ configure_block(BLOCK_NAME "Yarp Clock" SOURCES src/YarpClock.cpp HEADERS include/YarpClock.h) -# TODO: this should be removed with a proper inclusion of the library -include_directories(SYSTEM "autogenerated/include/") configure_block(BLOCK_NAME "Simulator Synchronizer" GROUP "Utilities" LIST_PREFIX WBT - SOURCES src/SimulatorSynchronizer.cpp autogenerated/src/thrift/ClockServer.cpp - HEADERS include/SimulatorSynchronizer.h autogenerated/include/thrift/ClockServer.h) + SOURCES src/SimulatorSynchronizer.cpp + HEADERS include/SimulatorSynchronizer.h) configure_block(BLOCK_NAME "Mass Matrix" GROUP "Model" @@ -275,6 +273,10 @@ else() target_link_libraries(WBToolbox ${LINKED_LIBRARIES} ${Matlab_LIBRARIES}) endif() +# Link with ClockServer library +add_subdirectory(autogenerated/) +target_link_libraries(WBToolbox PUBLIC ClockServer) + # Remote Inverse Kinematics requires C++11 if (CMAKE_VERSION VERSION_LESS "3.1") if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR diff --git a/toolbox/autogenerated/CMakeLists.txt b/toolbox/autogenerated/CMakeLists.txt new file mode 100644 index 000000000..3ce96c1c5 --- /dev/null +++ b/toolbox/autogenerated/CMakeLists.txt @@ -0,0 +1,38 @@ +cmake_policy(SET CMP0048 NEW) +project(ClockServer LANGUAGES CXX VERSION 0.1) +cmake_minimum_required(VERSION 3.0.2) + +# Configure the project +# ===================== +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +include(GNUInstallDirs) +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + +# Use a general prefix for the project +set(VARS_PREFIX ${PROJECT_NAME}) + +# Build the library +# ================= + +# Export the includes needed to who inherits this library +# Set this up properly for handling either BUILD and INSTALL trees +set(${VARS_PREFIX}_INCLUDE_BUILD ${CMAKE_CURRENT_SOURCE_DIR}/include) +set(${VARS_PREFIX}_INCLUDE_INSTALL ${CMAKE_INSTALL_INCLUDEDIR}/${VARS_PREFIX}) + +# Add the target +add_library(${VARS_PREFIX} STATIC ${CMAKE_CURRENT_SOURCE_DIR}/include/thrift/ClockServer.h + ${CMAKE_CURRENT_SOURCE_DIR}/src/thrift/ClockServer.cpp) + +if (CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set_target_properties(${VARS_PREFIX} PROPERTIES COMPILE_FLAGS "-fPIC") +endif() + +# Setup the include directories +target_include_directories(${VARS_PREFIX} PUBLIC + $ + $) + +# YARP +find_package(YARP REQUIRED) +target_include_directories(${VARS_PREFIX} PUBLIC ${YARP_INCLUDE_DIRS}) diff --git a/toolbox/autogenerated/src/thrift/ClockServer.cpp b/toolbox/autogenerated/src/thrift/ClockServer.cpp index 30ced2c9d..64d4cf3e8 100644 --- a/toolbox/autogenerated/src/thrift/ClockServer.cpp +++ b/toolbox/autogenerated/src/thrift/ClockServer.cpp @@ -1,7 +1,7 @@ // This is an automatically-generated file. // It could get re-generated if the ALLOW_IDL_GENERATION flag is on. -#include +#include "thrift/ClockServer.h" #include namespace gazebo { @@ -382,5 +382,3 @@ std::vector ClockServer::help(const std::string& functionName) { return helpString; } } // namespace - - From 1d71a8628a3721213555da85780ce7f6aecd7c6a Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 12:18:16 +0000 Subject: [PATCH 11/92] Substituted C-style cast with static_cast in Signal.cpp This commit fixes also some error in computing the address used in memcpy calls --- toolbox/src/base/Signal.cpp | 92 +++++++++++++++++++++++++++++-------- 1 file changed, 73 insertions(+), 19 deletions(-) diff --git a/toolbox/src/base/Signal.cpp b/toolbox/src/base/Signal.cpp index de33aaf15..86c40a89d 100644 --- a/toolbox/src/base/Signal.cpp +++ b/toolbox/src/base/Signal.cpp @@ -42,38 +42,92 @@ namespace wbt { Data data; switch (portType) { case PortDataTypeDouble: - data.doubleData(isContiguous ? ((double*)contiguousData)[index] : *((double **)nonContiguousData)[index]); + if (isContiguous) { + data.doubleData((static_cast(contiguousData))[index]); + } + else { + const double* buffer = static_cast(*nonContiguousData); + data.doubleData(static_cast(buffer[index])); + } break; case PortDataTypeSingle: - data.floatData(isContiguous ? ((float*)contiguousData)[index] : *((float **)nonContiguousData)[index]); + if (isContiguous) { + data.floatData((static_cast(contiguousData))[index]); + } + else { + const float* buffer = static_cast(*nonContiguousData); + data.floatData(static_cast(buffer[index])); + } break; case PortDataTypeInt8: - data.int8Data(isContiguous ? ((int8_t*)contiguousData)[index] : *((int8_t **)nonContiguousData)[index]); + if (isContiguous) { + data.int8Data((static_cast(contiguousData))[index]); + } + else { + const int8_t* buffer = static_cast(*nonContiguousData); + data.int8Data(static_cast(buffer[index])); + } break; case PortDataTypeUInt8: - data.uint8Data(isContiguous ? ((uint8_t*)contiguousData)[index] : *((uint8_t **)nonContiguousData)[index]); + if (isContiguous) { + data.uint8Data((static_cast(contiguousData))[index]); + } + else { + const uint8_t* buffer = static_cast(*nonContiguousData); + data.uint8Data(static_cast(buffer[index])); + } break; case PortDataTypeInt16: - data.int8Data(isContiguous ? ((int16_t*)contiguousData)[index] : *((int16_t **)nonContiguousData)[index]); + if (isContiguous) { + data.int16Data((static_cast(contiguousData))[index]); + } + else { + const int16_t* buffer = static_cast(*nonContiguousData); + data.int16Data(static_cast(buffer[index])); + } break; case PortDataTypeUInt16: - data.uint8Data(isContiguous ? ((uint16_t*)contiguousData)[index] : *((uint16_t **)nonContiguousData)[index]); + if (isContiguous) { + data.uint16Data((static_cast(contiguousData))[index]); + } + else { + const uint16_t* buffer = static_cast(*nonContiguousData); + data.uint16Data(static_cast(buffer[index])); + } break; case PortDataTypeInt32: - data.int8Data(isContiguous ? ((int32_t*)contiguousData)[index] : *((int32_t **)nonContiguousData)[index]); + if (isContiguous) { + data.int32Data((static_cast(contiguousData))[index]); + } + else { + const int32_t* buffer = static_cast(*nonContiguousData); + data.int32Data(static_cast(buffer[index])); + } break; case PortDataTypeUInt32: - data.uint8Data(isContiguous ? ((uint32_t*)contiguousData)[index] : *((uint32_t **)nonContiguousData)[index]); + if (isContiguous) { + data.uint32Data((static_cast(contiguousData))[index]); + } + else { + const uint32_t* buffer = static_cast(*nonContiguousData); + data.uint32Data(static_cast(buffer[index])); + } break; case PortDataTypeBoolean: - data.booleanData(isContiguous ? ((bool*)contiguousData)[index] : *((bool **)nonContiguousData)[index]); + if (isContiguous) { + data.booleanData((static_cast(contiguousData))[index]); + } + else { + const bool* buffer = static_cast(*nonContiguousData); + data.booleanData(static_cast(buffer[index])); + } } return data; } void* Signal::getContiguousBuffer() { - if (!isContiguous) return 0; + if (!isContiguous) return nullptr; return this->contiguousData; } @@ -110,13 +164,13 @@ namespace wbt { case PortDataTypeDouble: { dataSize = sizeof(double); - address = data + startIndex; + address = static_cast(address) + startIndex; break; } case PortDataTypeSingle: { dataSize = sizeof(float); - address = ((float*)data) + startIndex; + address = static_cast(address) + startIndex; break; } default: @@ -164,19 +218,19 @@ namespace wbt { case PortDataTypeInt32: { dataSize = sizeof(int32_t); - address = ((int32_t*)data) + startIndex; + address = static_cast(address) + startIndex; break; } case PortDataTypeInt16: { dataSize = sizeof(int16_t); - address = ((int16_t*)data) + startIndex; + address = static_cast(address) + startIndex; break; } case PortDataTypeInt8: { dataSize = sizeof(int8_t); - address = ((int8_t*)data) + startIndex; + address = static_cast(address) + startIndex; break; } default: @@ -223,19 +277,19 @@ namespace wbt { case PortDataTypeUInt32: { dataSize = sizeof(uint32_t); - address = ((uint32_t*)data) + startIndex; + address = data + startIndex; break; } case PortDataTypeUInt16: { dataSize = sizeof(uint16_t); - address = ((uint16_t*)data) + startIndex; + address = data + startIndex; break; } case PortDataTypeUInt8: { dataSize = sizeof(uint8_t); - address = ((uint8_t*)data) + startIndex; + address = data + startIndex; break; } default: @@ -255,7 +309,7 @@ namespace wbt { { if (isConstPort) return; unsigned dataSize = sizeof(bool); - const void * address = ((bool*)data) + startIndex; + const void* address = static_cast(data) + startIndex; memcpy(contiguousData, address, dataSize * length); } From 19cf4d6fe51b7e4a8df2df5a6413bb538d53c691 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 13:49:23 +0000 Subject: [PATCH 12/92] Switch to AnyType interface to handle data read by BlockInformation Furthermore: - All methods that read parameters return a bool value - optionFromKey doesn't use anymore wbt::Data - setNumberOfOuputPorts() became setNumberOfOutputPorts() --- toolbox/include/base/BlockInformation.h | 31 ++++++---- .../include/base/SimulinkBlockInformation.h | 13 +++-- toolbox/src/base/BlockInformation.cpp | 2 +- toolbox/src/base/SimulinkBlockInformation.cpp | 57 +++++++++++-------- 4 files changed, 63 insertions(+), 40 deletions(-) diff --git a/toolbox/include/base/BlockInformation.h b/toolbox/include/base/BlockInformation.h index b16461d89..f49ba843c 100644 --- a/toolbox/include/base/BlockInformation.h +++ b/toolbox/include/base/BlockInformation.h @@ -1,6 +1,7 @@ #ifndef WBT_BLOCKINFORMATION_H #define WBT_BLOCKINFORMATION_H +#include "AnyType.h" #include #include @@ -20,8 +21,8 @@ namespace wbt { PortDataTypeBoolean, } PortDataType; - - struct Data { + class Data + { private: double buffer; public: @@ -59,7 +60,8 @@ class wbt::BlockInformation { public: virtual ~BlockInformation(); - //Block Options methods + // Block Options methods + // ===================== /** * Convert a block option from its Toolbox identifier to a specific implementation @@ -68,10 +70,12 @@ class wbt::BlockInformation { * @param [out] option implementation-specific block option * @return true if the option has been converted. False otherwise */ - virtual bool optionFromKey(const std::string& key, Data &option) const; + virtual bool optionFromKey(const std::string& key, double& option) const; + + // Parameters methods + // ================== - //Parameters methods /** * Reads the parameter at the specified index and interpret it as a string * @@ -81,12 +85,16 @@ class wbt::BlockInformation { * @return true if success, false otherwise */ virtual bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) = 0; - virtual Data getScalarParameterAtIndex(unsigned parameterIndex) = 0; + virtual bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) = 0; + virtual bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) = 0; + virtual bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) = 0; + virtual bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) = 0; + + // Port information methods + // ======================== - //Port information methods virtual bool setNumberOfInputPorts(unsigned numberOfPorts) = 0; - virtual bool setNumberOfOuputPorts(unsigned numberOfPorts) = 0; - //If portSize == -1, then it is dynamic + virtual bool setNumberOfOutputPorts(unsigned numberOfPorts) = 0; virtual bool setInputPortVectorSize(unsigned portNumber, int portSize) = 0; virtual bool setInputPortMatrixSize(unsigned portNumber, int rows, int columns) = 0; virtual bool setOutputPortVectorSize(unsigned portNumber, int portSize) = 0; @@ -103,12 +111,13 @@ class wbt::BlockInformation { virtual bool setInputPortType(unsigned portNumber, PortDataType portType) = 0; virtual bool setOutputPortType(unsigned portNumber, PortDataType portType) = 0; - //Port data + // Port data + // ========= + virtual unsigned getInputPortWidth(unsigned portNumber) = 0; virtual unsigned getOutputPortWidth(unsigned portNumber) = 0; virtual wbt::Signal getInputPortSignal(unsigned portNumber) = 0; virtual wbt::Signal getOutputPortSignal(unsigned portNumber) = 0; - }; #endif /* end of include guard: WBT_BLOCKINFORMATION_H */ diff --git a/toolbox/include/base/SimulinkBlockInformation.h b/toolbox/include/base/SimulinkBlockInformation.h index 40b3c36c6..9c26b23b1 100644 --- a/toolbox/include/base/SimulinkBlockInformation.h +++ b/toolbox/include/base/SimulinkBlockInformation.h @@ -2,8 +2,8 @@ #define WBT_SIMULINKBLOCKINFORMATION_H #include "BlockInformation.h" - #include "simstruc.h" +#include "AnyType.h" namespace wbt { class SimulinkBlockInformation; @@ -18,21 +18,24 @@ class wbt::SimulinkBlockInformation : public wbt::BlockInformation { virtual ~SimulinkBlockInformation(); - virtual bool optionFromKey(const std::string& key, Data &option) const; + bool optionFromKey(const std::string& key, double& option) const override; //Parameters methods - virtual bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter); - virtual Data getScalarParameterAtIndex(unsigned parameterIndex); + bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) override; + bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) override; + bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) override; + bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) override; + bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) override; //Port information methods virtual bool setNumberOfInputPorts(unsigned numberOfPorts); - virtual bool setNumberOfOuputPorts(unsigned numberOfPorts); virtual bool setInputPortVectorSize(unsigned portNumber, int portSize); virtual bool setInputPortMatrixSize(unsigned portNumber, int rows, int columns); virtual bool setOutputPortVectorSize(unsigned portNumber, int portSize); virtual bool setOutputPortMatrixSize(unsigned portNumber, int rows, int columns); virtual bool setInputPortType(unsigned portNumber, PortDataType portType); virtual bool setOutputPortType(unsigned portNumber, PortDataType portType); + bool setNumberOfOutputPorts(unsigned numberOfPorts) override; //Port data virtual unsigned getInputPortWidth(unsigned portNumber); diff --git a/toolbox/src/base/BlockInformation.cpp b/toolbox/src/base/BlockInformation.cpp index c2fc14f0d..5fa160eef 100644 --- a/toolbox/src/base/BlockInformation.cpp +++ b/toolbox/src/base/BlockInformation.cpp @@ -3,4 +3,4 @@ const std::string wbt::BlockOptionPrioritizeOrder = "wbt.BlockOptionPrioritizeOrder"; wbt::BlockInformation::~BlockInformation() {} -bool wbt::BlockInformation::optionFromKey(const std::string& key, wbt::Data &option) const { return false; } +bool wbt::BlockInformation::optionFromKey(const std::string& key, double& option) const { return false; } diff --git a/toolbox/src/base/SimulinkBlockInformation.cpp b/toolbox/src/base/SimulinkBlockInformation.cpp index 85dc6593d..9f1f69f71 100644 --- a/toolbox/src/base/SimulinkBlockInformation.cpp +++ b/toolbox/src/base/SimulinkBlockInformation.cpp @@ -1,8 +1,10 @@ #include "SimulinkBlockInformation.h" #include "Signal.h" - +#include "MxAnyType.h" #include "simstruc.h" +#include +#include namespace wbt { @@ -11,10 +13,10 @@ namespace wbt { SimulinkBlockInformation::~SimulinkBlockInformation() {} - bool SimulinkBlockInformation::optionFromKey(const std::string& key, Data &option) const + bool SimulinkBlockInformation::optionFromKey(const std::string& key, double& option) const { if (key == wbt::BlockOptionPrioritizeOrder) { - option.uint32Data(SS_OPTION_PLACE_ASAP); + option = SS_OPTION_PLACE_ASAP; return true; } @@ -24,26 +26,33 @@ namespace wbt { //Parameters methods bool SimulinkBlockInformation::getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) { - int_T buflen, status; - char *buffer = NULL; + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asString(stringParameter); + } - //robot name - buflen = (1 + mxGetN(ssGetSFcnParam(simstruct, parameterIndex))) * sizeof(mxChar); - buffer = static_cast(mxMalloc(buflen)); - status = mxGetString((ssGetSFcnParam(simstruct, parameterIndex)), buffer, buflen); - if (status) { - return false; - } - stringParameter = buffer; - mxFree(buffer); buffer = NULL; - return true; + bool SimulinkBlockInformation::getStructAtIndex(unsigned parameterIndex, AnyStruct& map) + { + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asAnyStruct(map); + } + + + bool SimulinkBlockInformation::getVectorAtIndex(unsigned parameterIndex, std::vector& vec) + { + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asVectorDouble(vec); + } + + bool SimulinkBlockInformation::getScalarParameterAtIndex(unsigned parameterIndex, double& value) + { + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asDouble(value); } - Data SimulinkBlockInformation::getScalarParameterAtIndex(unsigned parameterIndex) + bool SimulinkBlockInformation::getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) { - Data data; - data.doubleData(mxGetScalar(ssGetSFcnParam(simstruct, parameterIndex))); - return data; + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asBool(value); } //Port information methods @@ -52,7 +61,7 @@ namespace wbt { return ssSetNumInputPorts(simstruct, numberOfPorts); } - bool SimulinkBlockInformation::setNumberOfOuputPorts(unsigned numberOfPorts) + bool SimulinkBlockInformation::setNumberOfOutputPorts(unsigned numberOfPorts) { return ssSetNumOutputPorts(simstruct, numberOfPorts); } @@ -170,7 +179,8 @@ namespace wbt { { Signal signal; InputPtrsType port = ssGetInputPortSignalPtrs(simstruct, portNumber); - signal.initSignalType(PortDataTypeDouble, true); + bool isConstPort = true; + signal.initSignalType(PortDataTypeDouble, isConstPort); signal.setNonContiguousBuffer(port); return signal; } @@ -178,9 +188,10 @@ namespace wbt { wbt::Signal SimulinkBlockInformation::getOutputPortSignal(unsigned portNumber) { Signal signal; - signal.initSignalType(PortDataTypeDouble, false); + bool isConstPort = false; + signal.initSignalType(PortDataTypeDouble, isConstPort); signal.setContiguousBuffer(ssGetOutputPortSignal(simstruct, portNumber)); return signal; } - + } From f0973693c675e28491c50091288126b730985464 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 14:26:05 +0000 Subject: [PATCH 13/92] WBIBlock refactored and renamed to WBBlock This new WBBlock implements the same functionalities of the former WBIBlock and WBIModelBlock blocks. Resources are lazy-handled, and it is not anymore necessary having two different setups. Furthermore: - The parameters from Simulink are stored in the ToolboxSingleton in the configureSizeAndPorts() instead of initialize(). This is possible because singletons are not deleted by Simulink between these two steps (Blocks instead are deleted). --- toolbox/CMakeLists.txt | 4 +- toolbox/include/base/WBBlock.h | 82 +++++++++++ toolbox/include/base/WBIBlock.h | 48 ------- toolbox/src/base/WBBlock.cpp | 241 ++++++++++++++++++++++++++++++++ toolbox/src/base/WBIBlock.cpp | 140 ------------------- 5 files changed, 325 insertions(+), 190 deletions(-) create mode 100644 toolbox/include/base/WBBlock.h delete mode 100644 toolbox/include/base/WBIBlock.h create mode 100644 toolbox/src/base/WBBlock.cpp delete mode 100644 toolbox/src/base/WBIBlock.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 8da7e2e47..855625d45 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -61,7 +61,7 @@ configure_block(BLOCK_NAME "Base" SOURCES src/base/toolbox.cpp src/base/Block.cpp src/base/BlockInformation.cpp - src/base/WBIBlock.cpp + src/base/WBBlock.cpp src/base/Log.cpp src/base/WBInterface.cpp src/base/factory.cpp @@ -72,7 +72,7 @@ configure_block(BLOCK_NAME "Base" HEADERS include/base/toolbox.h include/base/Block.h include/base/BlockInformation.h - include/base/WBIBlock.h + include/base/WBBlock.h include/base/Log.h include/base/WBInterface.h include/base/SimulinkBlockInformation.h #this is temp diff --git a/toolbox/include/base/WBBlock.h b/toolbox/include/base/WBBlock.h new file mode 100644 index 000000000..cee7d7d11 --- /dev/null +++ b/toolbox/include/base/WBBlock.h @@ -0,0 +1,82 @@ +#ifndef WBT_WBIBLOCK_H +#define WBT_WBIBLOCK_H + +#include "Block.h" +#include +#include +#include +#include +#include +#include + +namespace wbt { + class WBBlock; + class Configuration; + class BlockInformation; + class RobotInterface; +} + +namespace iDynTree { + class MatrixDynSize; +} + +/** + * \struct iDynTreeRobotState WBBlock.h + * + * This struct contains the iDynTree objects used to configure the + * state of iDynTree::KinDynComputations objects. + */ +struct iDynTreeRobotState { + iDynTree::Twist m_baseVelocity; + iDynTree::Vector3 m_gravity; + iDynTree::Transform m_world_T_base; + iDynTree::VectorDynSize m_jointsVelocity; + iDynTree::VectorDynSize m_jointsPosition; + + iDynTreeRobotState() = default; + ~iDynTreeRobotState() = default; + + iDynTreeRobotState(const unsigned& dofs, const std::vector& gravity); +}; + +/** + * Basic class for Whole-Body related blocks. + * This class (the whole toolbox in reality) assumes the block represent + * an instantaneous system (i.e. not a dynamic system). + * + * You can create a new block by deriving this class and implementing at least + * the output method. + * + * This block implements the following default behaviours: + * - it ask for 4 parameters (robot name, local (module) name, names of the remote control boards, + * and the list of joints which should all belong to one of the remote control boards) + * - It initializes the yarp network and the whole body interface object + * - During terminate it closes and release the interface object and terminate the yarp network + * + * @note Usually you want to call this class implementations at some point in your + * method overridings, unless you want to completely change the code (but at that point + * you probabily want to derive from Block instead) + */ +class wbt::WBBlock : public wbt::Block +{ +private: + static const unsigned ConfigurationParameterIndex; + static const unsigned ConfBlockNameParameterIndex; + +protected: + std::string confKey; + iDynTreeRobotState robotState; + bool getWBToolboxParameters(Configuration& config, BlockInformation* blockInfo); + const std::shared_ptr getRobotInterface(); + const Configuration& getConfiguration(); + +public: + WBBlock() = default; + ~WBBlock() override = default; + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; +}; + +#endif /* end of include guard: WBT_WBIBLOCK_H */ diff --git a/toolbox/include/base/WBIBlock.h b/toolbox/include/base/WBIBlock.h deleted file mode 100644 index 33ffe9c36..000000000 --- a/toolbox/include/base/WBIBlock.h +++ /dev/null @@ -1,48 +0,0 @@ -#ifndef WBT_WBIBLOCK_H -#define WBT_WBIBLOCK_H - -#include "Block.h" -#include - -namespace wbt { - class WBIBlock; - class BlockInformation; -} - -/** - * Basic class for WBI related blocks. - * This class (the whole toolbox in reality) assumes the block represent - * an instantaneous system (i.e. not a dynamic system). - * - * You can create a new block by deriving this class and implementing at least - * the output method. - * - * This block implements the following default behaviours: - * - it ask for 4 parameters (robot name, local (module) name, wbi config file and wbi list) - * - It initializes the yarp network and the whole body interface object - * - During terminate it closes and release the interface object and terminate the yarp network - * - * @note Usually you want to call this class implementations at some point in your - * method overridings, unless you want to completely change the code (but at that point - * you probabily want to derive from Block instead) - */ -class wbt::WBIBlock : public wbt::Block { - -protected: - - std::string m_wbiConfigurationFileName; - std::string m_wbiListName; - - bool configureWBIParameters(BlockInformation *blockInfo, wbt::Error *error); - -public: - WBIBlock(); - virtual ~WBIBlock(); - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); -}; - - -#endif /* end of include guard: WBT_WBIBLOCK_H */ diff --git a/toolbox/src/base/WBBlock.cpp b/toolbox/src/base/WBBlock.cpp new file mode 100644 index 000000000..27f9913f2 --- /dev/null +++ b/toolbox/src/base/WBBlock.cpp @@ -0,0 +1,241 @@ +#include "WBBlock.h" + +#include "BlockInformation.h" +#include "Log.h" +#include "ToolboxSingleton.h" +#include "Configuration.h" +#include "RobotInterface.h" +#include "AnyType.h" +#include +#include +#include +#include +#include +#include + +using namespace wbt; + +const unsigned WBBlock::ConfigurationParameterIndex = 1; // Struct from Simulink +const unsigned WBBlock::ConfBlockNameParameterIndex = 2; // Absolute name of the block containing the + // configuration + +iDynTreeRobotState::iDynTreeRobotState(const unsigned& dofs, const std::vector& gravity) +: m_gravity(gravity.data(), 3) +, m_jointsVelocity(dofs) +, m_jointsPosition(dofs) +{ + m_jointsPosition.zero(); + m_jointsVelocity.zero(); +} + +unsigned WBBlock::numberOfParameters() { return 2; } + +bool WBBlock::getWBToolboxParameters(Configuration& config, BlockInformation* blockInfo) +{ + // Infos + // ===== + // + // For what concern initialization, the callback order is: + // + // -> configureSizeAndPorts() + // -> initialize() + // -> initializeInitialConditions() + // + // Despite class objects after the configureSizeAndPorts() are destroyed and + // reallocated before the initialize(), the ToolboxSingleton remains alive and + // can store from this stage the configuration created by reading the parameters. + // + + // Gather the parameters from the Mask of the Simulink Block + // ========================================================= + + // Get the struct containing the parameters + AnyStruct s; + if (!blockInfo->getStructAtIndex(ConfigurationParameterIndex, s)) { + Log::getSingleton().error("Failed to retrieve the struct with parameters."); + return false; + } + + // Check the existence of all the fields + try { + s.at("RobotName"); + s.at("UrdfFile"); + s.at("ControlledJoints"); + s.at("ControlBoardsNames"); + s.at("LocalName"); + s.at("GravityVector"); + } + catch (const std::out_of_range& e) { + Log::getSingleton().error("Cannot retrieve one or more parameter from config struct."); + return false; + } + + // RobotName + std::string robotName; + if (!s["RobotName"]->asString(robotName)) { + Log::getSingleton().error("Cannot retrieve string from RobotName parameter."); + return false; + } + + // UrdfFile + std::string urdfFile; + if (!s["UrdfFile"]->asString(urdfFile)) { + Log::getSingleton().error("Cannot retrieve string from UrdfFile parameter."); + return false; + } + + // ControlledJoints + AnyCell cellCJ; + if (!s["ControlledJoints"]->asAnyCell(cellCJ)) { + Log::getSingleton().error("Cannot retrieve ControlledJoints parameter."); + return false; + } + + std::vector controlledJoints; + for (auto cell: cellCJ) { + std::string joint; + if (!cell->asString(joint)) { + Log::getSingleton().error("Failed to convert ControlledJoints from cell to strings."); + return false; + } + controlledJoints.push_back(joint); + } + + // ControlBoardsNames + AnyCell cellCBN; + if (!s["ControlBoardsNames"]->asAnyCell(cellCBN)) { + Log::getSingleton().error("Cannot retrieve ControlBoardsNames parameter."); + return false; + } + + std::vector controlBoardsNames; + for (auto cell: cellCBN) { + std::string joint; + if (!cell->asString(joint)) { + Log::getSingleton().error("Failed to convert ControlBoardsNames from cell to string."); + return false; + } + controlBoardsNames.push_back(joint); + } + + // LocalName + std::string localName; + if (!s["LocalName"]->asString(localName)) { + Log::getSingleton().error("Cannot retrieve string from LocalName parameter."); + return false; + } + + std::vector gravityVector; + if (!s["GravityVector"]->asVectorDouble(gravityVector)) { + Log::getSingleton().error("Cannot retrieve vector from GravityVector parameter."); + return false; + } + + // Create the ToolboxConfig object + // =============================== + + // Populate a Property object that stores the input parameters + config.setRobotName(robotName); + config.setUrdfFile(urdfFile); + config.setControlledJoints(controlledJoints); + config.setControlBoardsNames(controlBoardsNames); + config.setLocalName(localName); + config.setGravityVector(gravityVector); + + return true; +} + +const Configuration& WBBlock::getConfiguration() +{ + ToolboxSingleton& interface = ToolboxSingleton::sharedInstance(); + return interface.getConfiguration(confKey); +} + +const std::shared_ptr WBBlock::getRobotInterface() +{ + ToolboxSingleton& interface = ToolboxSingleton::sharedInstance(); + return interface.getRobotInterface(confKey); +} + +bool WBBlock::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Remember not allocate / save any data in this function, it won't be persistent. + + // Setup the ToolboxSingleton + // ========================== + + // Setup the DOFs (required by childs for configuring port sizes) + // -------------------------------------------------------------- + + // Initialize the ToolboxSingleton + ToolboxSingleton& interface = ToolboxSingleton::sharedInstance(); + + // Get the absolute name of the block from which the configuration has been retrieved. + // This will be the key of the map containing all the configurations of the ToolboxSingleton. + if (!blockInfo->getStringParameterAtIndex(ConfBlockNameParameterIndex, confKey)) { + Log::getSingleton().error("Failed to retrieve the struct with parameters."); + return false; + } + + // Get the configuration struct from the block + Configuration config; + if (!getWBToolboxParameters(config, blockInfo)) { + return false; + } + + // Check if the configuration is valid + if (!config.isValid()) { + Log::getSingleton().error("The provided configuration is not valid."); + return false; + } + + // Store the configuration inside the ToolboxSingleton + if (!interface.storeConfiguration(confKey, config)) { + Log::getSingleton().error("Failed to configure ToolboxSingleton."); + return false; + } + + // Check if the DoFs are positive (and if the config has been stored successfully) + const Configuration& configFromSingleton = getConfiguration(); + + if (configFromSingleton.getNumberOfDoFs() < 1) { + Log::getSingleton().error("Failed to configure WBBlock. Read 0 DoFs."); + return false; + } + + return true; +} + +bool WBBlock::initialize(BlockInformation* blockInfo) +{ + // CONFIGURE the ToolboxSingleton + // ============================== + + ToolboxSingleton& interface = ToolboxSingleton::sharedInstance(); + + // Gather again confKey + // Note: despite data for blocks is not persistent between configureSizeAndPorts() + // and initialize() (e.g. confKey), the singleton is not destroyed. + // This means that the stored configurations are still there. + if (!blockInfo->getStringParameterAtIndex(ConfBlockNameParameterIndex, confKey)) { + Log::getSingleton().error("Failed to retrieve the struct with parameters."); + return false; + } + + // Check if the key is valid + if (!interface.isKeyValid(confKey)) { + Log::getSingleton().error("Failed to retrieve the configuration object from the singleton."); + return false; + } + + // Initialize the iDynTreeRobotState struct + const unsigned& dofs = interface.numberOfDoFs(confKey); + robotState = iDynTreeRobotState(dofs, getConfiguration().getGravityVector()); + + return true; +} + +bool WBBlock::terminate(BlockInformation* /*blockInfo*/) +{ + return true; +} diff --git a/toolbox/src/base/WBIBlock.cpp b/toolbox/src/base/WBIBlock.cpp deleted file mode 100644 index 475ffee97..000000000 --- a/toolbox/src/base/WBIBlock.cpp +++ /dev/null @@ -1,140 +0,0 @@ -#include "WBIBlock.h" - -#include "BlockInformation.h" -#include "Error.h" -#include "WBInterface.h" -#include - -#define PARAM_IDX_1 1 // robot name -#define PARAM_IDX_2 2 // local (module) name -#define PARAM_IDX_3 3 // wbi config file -#define PARAM_IDX_4 4 // wbi list - -wbt::WBIBlock::WBIBlock() -: m_wbiConfigurationFileName("") -, m_wbiListName("") {} - -wbt::WBIBlock::~WBIBlock() { } - -unsigned wbt::WBIBlock::numberOfParameters() { return 4; } - -bool wbt::WBIBlock::configureWBIParameters(BlockInformation *blockInfo, wbt::Error *error) -{ - //parameters needed by this block: - // - YARP_ROBOT_NAME: needed by resource finder for resource lookup (for now it is taken by the environment) - // - robot: robot port. If defined overrides the one specified by wbi file - // - moduleName: local (opened) ports. - // - wbi config file name (default: yarpWholeBodyInterface.ini): specifies the wbi config file - // - wbi list (default ROBOT_TORQUE_CONTROL_JOINTS): specifies the WBI list . - // It it is a normal string, it is interpreted as a named list of joints that is loaded from the - // yarpWholeBodyInterface.ini file. If instead it s - - - //robot name - std::string robotName; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_1, robotName)) { - if (error) error->message = "Cannot retrieve string from robot parameter"; - return false; - } - - //local name - std::string localName; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_2, localName)) { - if (error) error->message = "Cannot retrieve string from localName parameter"; - return false; - } - //default local name - if (localName.empty()) localName = "WBIT"; - - //wbi config file - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_3, m_wbiConfigurationFileName)) { - if (error) error->message = "Cannot retrieve string from WBI config file parameter"; - return false; - } - - //default config file: - if (m_wbiConfigurationFileName.empty()) m_wbiConfigurationFileName = "yarpWholeBodyInterface.ini"; - - //wbi list name - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_4, m_wbiListName)) { - if (error) error->message = "Cannot retrieve string from WBI list parameter"; - return false; - } - - //default list: - if (m_wbiListName.empty()) m_wbiListName = "ROBOT_TORQUE_CONTROL_JOINTS"; - - WBInterface &interface = WBInterface::sharedInstance(); - - Error interfaceError; - if (!interface.configure(robotName, localName, m_wbiConfigurationFileName, m_wbiListName, &interfaceError)) { - if (error) error->message = "Failed to configure WholeBodyInterface with error " + interfaceError.message; - return false; - } - return true; -} - -bool wbt::WBIBlock::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) -{ - //wbi config file - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_3, m_wbiConfigurationFileName)) { - if (error) error->message = "Could not read WBI configuration file parameter"; - return false; - } - - //default config file: - if (m_wbiConfigurationFileName.empty()) m_wbiConfigurationFileName = "yarpWholeBodyInterface.ini"; - - //wbi list name - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_4, m_wbiListName)) { - if (error) error->message = "Could not read WBI list parameter"; - return false; - } - - //default list: - if (m_wbiListName.empty()) m_wbiListName = "ROBOT_TORQUE_CONTROL_JOINTS"; - - WBInterface &interface = WBInterface::sharedInstance(); - - int dofs = interface.dofsForConfigurationFileAndList(m_wbiConfigurationFileName, m_wbiListName); - if (dofs == -1) { - if (error) error->message = "Failed to configure WholeBodyInterface. Could not load WBI properties from file"; - return false; - } else if (dofs == -2) { - if (error) error->message = "Failed to configure WholeBodyInterface. WBI joint list not found or failed to configure. Check if joint list exists."; - return false; - } - - return true; -} - -bool wbt::WBIBlock::initialize(BlockInformation *blockInfo, wbt::Error *error) -{ - using namespace yarp::os; - Network::init(); - if (!Network::initialized() || !Network::checkNetwork(5.0)) { - if (error) error->message = "YARP server wasn't found active"; - return false; - } - - if (!configureWBIParameters(blockInfo, error)) { - return false; - } - - WBInterface &interface = WBInterface::sharedInstance(); - if (!interface.initialize()) { - if (error) error->message = "Failed to initialize WBI"; - return false; - } - return true; -} - -bool wbt::WBIBlock::terminate(BlockInformation */*S*/, wbt::Error *error) -{ - if (!WBInterface::sharedInstance().terminate()) { - if (error) error->message = "Failed to terminate WBI"; - return false; - } - yarp::os::Network::fini(); - return true; -} From 04531f146dd55050a5c11e9b270558c540c8a552 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 10 Nov 2017 14:47:40 +0000 Subject: [PATCH 14/92] Minor edits of base/ classes - Removed old Error parameter from methods - Small documentation changes - Small style edits --- toolbox/include/base/Block.h | 31 ++++++------- toolbox/include/base/BlockInformation.h | 4 +- toolbox/include/base/Signal.h | 19 ++++---- .../include/base/SimulinkBlockInformation.h | 33 +++++++------- toolbox/src/base/Block.cpp | 8 ++-- toolbox/src/base/Signal.cpp | 43 +++++++++--------- toolbox/src/base/SimulinkBlockInformation.cpp | 8 ++-- toolbox/src/base/factory.cpp | 2 +- toolbox/src/base/toolbox.cpp | 44 +++++++++---------- 9 files changed, 92 insertions(+), 100 deletions(-) diff --git a/toolbox/include/base/Block.h b/toolbox/include/base/Block.h index b65f52a7b..a233859e6 100644 --- a/toolbox/include/base/Block.h +++ b/toolbox/include/base/Block.h @@ -6,7 +6,6 @@ namespace wbt { class Block; - class Error; class BlockInformation; } @@ -15,14 +14,15 @@ namespace wbt { * Basic abstract class for all the blocks. * This class (the whole toolbox in reality) assumes the block represent * an instantaneous system (i.e. not a dynamic system). - * + * * You can create a new block by deriving this class and implementing at least * all the pure virtual methods. * * @Note: if you need to implement a block which uses the WBI, you should derive * from WBIBlock as it already provides some facilities. */ -class wbt::Block { +class wbt::Block +{ public: /** * Create and returns a new Block object of the specified class. @@ -39,7 +39,7 @@ class wbt::Block { * */ virtual ~Block(); - + /** * Returns the number of configuration parameters needed by this block * @@ -59,7 +59,7 @@ class wbt::Block { * Returns the number of discrete states of the block. * * The base implementation returns 0, i.e. no discrete states - * @note if you return a number > 0, you should implement the + * @note if you return a number > 0, you should implement the * updateDiscreteState function * @return the number of discrete states */ @@ -82,7 +82,7 @@ class wbt::Block { * @param S the SimStruct structure * @return true for success, false otherwise */ - virtual bool updateDiscreteState(BlockInformation *blockInfo, wbt::Error *error); + virtual bool updateDiscreteState(BlockInformation* blockInfo); /** * Not called for now @@ -90,7 +90,7 @@ class wbt::Block { * @param S the SimStruct structure * @return true for success, false otherwise */ - virtual bool stateDerivative(BlockInformation *blockInfo, wbt::Error *error); + virtual bool stateDerivative(BlockInformation* blockInfo); /** @@ -111,21 +111,19 @@ class wbt::Block { * their size and configuration. * @Note: you should not save any object in this method because it will not persist * @param S simulink structure - * @param [out]error output error object that can be filled in case of error. Check if the pointer exists before dereference it. * * @return true for success, false otherwise */ - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) = 0; + virtual bool configureSizeAndPorts(BlockInformation* blockInfo) = 0; /** * Never called. * * @param S simulink structure - * @param [out]error output error object that can be filled in case of error. Check if the pointer exists before dereference it. * * @return true for success, false otherwise */ - virtual bool checkParameters(BlockInformation *blockInfo, wbt::Error *error); + virtual bool checkParameters(BlockInformation* blockInfo); /** * Initialize the object for the simulation @@ -133,11 +131,10 @@ class wbt::Block { * This method is called at model startup (i.e. during mdlStart) * @Note: you can save and initialize your object in this method * @param S simulink structure - * @param [out]error output error object that can be filled in case of error. * * @return true for success, false otherwise */ - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error) = 0; + virtual bool initialize(BlockInformation* blockInfo) = 0; /** * Called to initialize the initial conditions @@ -146,11 +143,10 @@ class wbt::Block { * @note this function is also called on a reset event * @note if you need to perform initialization only once, than implement initialize * @param S simulink structure - * @param [out]error output error object that can be filled in case of error. * * @return true for success, false otherwise */ - virtual bool initializeInitialConditions(BlockInformation *blockInfo, wbt::Error *error); + virtual bool initializeInitialConditions(BlockInformation* blockInfo); /** * Perform model cleanup. @@ -158,11 +154,10 @@ class wbt::Block { * This method is called at model termination (i.e. during mdlTerminate). * You should release all the resources you requested during the initialize method * @param S simulink structure - * @param [out]error output error object that can be filled in case of error. * * @return true for success, false otherwise */ - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error) = 0; + virtual bool terminate(BlockInformation* blockInfo) = 0; @@ -175,7 +170,7 @@ class wbt::Block { * * @return true for success, false otherwise */ - virtual bool output(BlockInformation *blockInfo, wbt::Error *error) = 0; + virtual bool output(BlockInformation* blockInfo) = 0; public: diff --git a/toolbox/include/base/BlockInformation.h b/toolbox/include/base/BlockInformation.h index f49ba843c..a4ea9da0a 100644 --- a/toolbox/include/base/BlockInformation.h +++ b/toolbox/include/base/BlockInformation.h @@ -66,9 +66,9 @@ class wbt::BlockInformation { /** * Convert a block option from its Toolbox identifier to a specific implementation * - * @param [in] key identifier of the block option + * @param [in] key identifier of the block option * @param [out] option implementation-specific block option - * @return true if the option has been converted. False otherwise + * @return true if the option has been converted. False otherwise */ virtual bool optionFromKey(const std::string& key, double& option) const; diff --git a/toolbox/include/base/Signal.h b/toolbox/include/base/Signal.h index 97f567669..b46d70ecd 100644 --- a/toolbox/include/base/Signal.h +++ b/toolbox/include/base/Signal.h @@ -7,7 +7,9 @@ namespace wbt { class Signal; } -class wbt::Signal { +class wbt::Signal +{ +private: PortDataType portType; bool isContiguous; bool isConstPort; @@ -16,31 +18,30 @@ class wbt::Signal { void* contiguousData; public: - Signal(); + Signal() = default; void initSignalType(wbt::PortDataType type, bool constPort); - void setContiguousBuffer(void* buffer); void setContiguousBuffer(const void* buffer); void setNonContiguousBuffer(void** buffer); - void setNonContiguousBuffer(const void* const * buffer); + void setNonContiguousBuffer(const void* const* buffer); const Data get(unsigned index) const; void* getContiguousBuffer(); - + //the missing are cast void set(unsigned index, double data); - void setBuffer(const double *data, const unsigned length, unsigned startIndex = 0); + void setBuffer(const double* data, const unsigned length, unsigned startIndex = 0); void set(unsigned index, int32_t data); - void setBuffer(const int32_t *data, const unsigned length, unsigned startIndex = 0); + void setBuffer(const int32_t* data, const unsigned length, unsigned startIndex = 0); void set(unsigned index, uint32_t data); - void setBuffer(const uint32_t *data, const unsigned length, unsigned startIndex = 0); + void setBuffer(const uint32_t* data, const unsigned length, unsigned startIndex = 0); void set(unsigned index, bool data); - void setBuffer(const bool *data, const unsigned length, unsigned startIndex = 0); + void setBuffer(const bool* data, const unsigned length, unsigned startIndex = 0); }; diff --git a/toolbox/include/base/SimulinkBlockInformation.h b/toolbox/include/base/SimulinkBlockInformation.h index 9c26b23b1..2334d32a4 100644 --- a/toolbox/include/base/SimulinkBlockInformation.h +++ b/toolbox/include/base/SimulinkBlockInformation.h @@ -10,13 +10,14 @@ namespace wbt { class Signal; } -class wbt::SimulinkBlockInformation : public wbt::BlockInformation { - SimStruct *simstruct; +class wbt::SimulinkBlockInformation : public wbt::BlockInformation +{ +private: + SimStruct* simstruct; public: - SimulinkBlockInformation(SimStruct *simstruct); - - virtual ~SimulinkBlockInformation(); + SimulinkBlockInformation(SimStruct* simstruct); + ~SimulinkBlockInformation() override = default; bool optionFromKey(const std::string& key, double& option) const override; @@ -28,20 +29,20 @@ class wbt::SimulinkBlockInformation : public wbt::BlockInformation { bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) override; //Port information methods - virtual bool setNumberOfInputPorts(unsigned numberOfPorts); - virtual bool setInputPortVectorSize(unsigned portNumber, int portSize); - virtual bool setInputPortMatrixSize(unsigned portNumber, int rows, int columns); - virtual bool setOutputPortVectorSize(unsigned portNumber, int portSize); - virtual bool setOutputPortMatrixSize(unsigned portNumber, int rows, int columns); - virtual bool setInputPortType(unsigned portNumber, PortDataType portType); - virtual bool setOutputPortType(unsigned portNumber, PortDataType portType); + bool setNumberOfInputPorts(unsigned numberOfPorts) override; bool setNumberOfOutputPorts(unsigned numberOfPorts) override; + bool setInputPortVectorSize(unsigned portNumber, int portSize) override; + bool setInputPortMatrixSize(unsigned portNumber, int rows, int columns) override; + bool setOutputPortVectorSize(unsigned portNumber, int portSize) override; + bool setOutputPortMatrixSize(unsigned portNumber, int rows, int columns) override; + bool setInputPortType(unsigned portNumber, PortDataType portType) override; + bool setOutputPortType(unsigned portNumber, PortDataType portType) override; //Port data - virtual unsigned getInputPortWidth(unsigned portNumber); - virtual unsigned getOutputPortWidth(unsigned portNumber); - virtual wbt::Signal getInputPortSignal(unsigned portNumber); - virtual wbt::Signal getOutputPortSignal(unsigned portNumber); + unsigned getInputPortWidth(unsigned portNumber) override; + unsigned getOutputPortWidth(unsigned portNumber) override; + wbt::Signal getInputPortSignal(unsigned portNumber) override; + wbt::Signal getOutputPortSignal(unsigned portNumber) override; }; #endif /* end of include guard: WBT_SIMULINKBLOCKINFORMATION_H */ diff --git a/toolbox/src/base/Block.cpp b/toolbox/src/base/Block.cpp index 396e1084d..b7d36396a 100644 --- a/toolbox/src/base/Block.cpp +++ b/toolbox/src/base/Block.cpp @@ -4,12 +4,12 @@ wbt::Block::~Block() {} std::vector wbt::Block::additionalBlockOptions() { return std::vector(); } void wbt::Block::parameterAtIndexIsTunable(unsigned /*index*/, bool &tunable) { tunable = false; } -bool wbt::Block::checkParameters(wbt::BlockInformation */*blockInfo*/, wbt::Error */*error*/) { return true; } +bool wbt::Block::checkParameters(wbt::BlockInformation* /*blockInfo*/) { return true; } unsigned wbt::Block::numberOfDiscreteStates() { return 0; } unsigned wbt::Block::numberOfContinuousStates() { return 0; } -bool wbt::Block::updateDiscreteState(wbt::BlockInformation */*blockInfo*/, wbt::Error */*error*/) { return true; } -bool wbt::Block::stateDerivative(wbt::BlockInformation */*blockInfo*/, wbt::Error */*error*/) { return true; } +bool wbt::Block::updateDiscreteState(wbt::BlockInformation* /*blockInfo*/) { return true; } +bool wbt::Block::stateDerivative(wbt::BlockInformation* /*blockInfo*/) { return true; } -bool wbt::Block::initializeInitialConditions(wbt::BlockInformation */*blockInfo*/, wbt::Error */*error*/) { return true; } +bool wbt::Block::initializeInitialConditions(wbt::BlockInformation* /*blockInfo*/) { return true; } diff --git a/toolbox/src/base/Signal.cpp b/toolbox/src/base/Signal.cpp index 86c40a89d..5d57938fc 100644 --- a/toolbox/src/base/Signal.cpp +++ b/toolbox/src/base/Signal.cpp @@ -4,9 +4,6 @@ namespace wbt { - - Signal::Signal() {} - void Signal::initSignalType(wbt::PortDataType type, bool constPort) { this->portType = type; @@ -30,7 +27,7 @@ namespace wbt { this->isContiguous = false; } - void Signal::setNonContiguousBuffer(const void* const * buffer) + void Signal::setNonContiguousBuffer(const void* const* buffer) { nonContiguousData = const_cast(buffer); this->isContiguous = false; @@ -139,13 +136,13 @@ namespace wbt { switch (portType) { case PortDataTypeDouble: { - double *buffer = static_cast(contiguousData); + double* buffer = static_cast(contiguousData); buffer[index] = data; break; } case PortDataTypeSingle: { - float *buffer = static_cast(contiguousData); + float* buffer = static_cast(contiguousData); buffer[index] = data; break; } @@ -154,11 +151,11 @@ namespace wbt { } } - void Signal::setBuffer(const double *data, const unsigned length, unsigned startIndex) + void Signal::setBuffer(const double* data, const unsigned length, unsigned startIndex) { if (isConstPort) return; unsigned dataSize = 0; - const void * address = data; + const void* address = data; switch (portType) { case PortDataTypeDouble: @@ -187,19 +184,19 @@ namespace wbt { switch (portType) { case PortDataTypeInt32: { - int32_t *buffer = static_cast(contiguousData); + int32_t* buffer = static_cast(contiguousData); buffer[index] = data; break; } case PortDataTypeInt16: { - int16_t *buffer = static_cast(contiguousData); + int16_t* buffer = static_cast(contiguousData); buffer[index] = data; break; } case PortDataTypeInt8: { - int8_t *buffer = static_cast(contiguousData); + int8_t* buffer = static_cast(contiguousData); buffer[index] = data; break; } @@ -208,11 +205,11 @@ namespace wbt { } } - void Signal::setBuffer(const int32_t *data, const unsigned length, unsigned startIndex) + void Signal::setBuffer(const int32_t* data, const unsigned length, unsigned startIndex) { if (isConstPort) return; unsigned dataSize = 0; - const void * address = data; + const void* address = data; switch (portType) { case PortDataTypeInt32: @@ -237,7 +234,7 @@ namespace wbt { break; } - memcpy(contiguousData, address, dataSize * length); + memcpy(contiguousData, address, dataSize* length); } void Signal::set(unsigned index, uint32_t data) @@ -246,19 +243,19 @@ namespace wbt { switch (portType) { case PortDataTypeUInt32: { - uint32_t *buffer = static_cast(contiguousData); + uint32_t* buffer = static_cast(contiguousData); buffer[index] = data; break; } case PortDataTypeUInt16: { - uint16_t *buffer = static_cast(contiguousData); + uint16_t* buffer = static_cast(contiguousData); buffer[index] = data; break; } case PortDataTypeUInt8: { - uint8_t *buffer = static_cast(contiguousData); + uint8_t* buffer = static_cast(contiguousData); buffer[index] = data; break; } @@ -267,11 +264,11 @@ namespace wbt { } } - void Signal::setBuffer(const uint32_t *data, const unsigned length, unsigned startIndex) + void Signal::setBuffer(const uint32_t* data, const unsigned length, unsigned startIndex) { if (isConstPort) return; unsigned dataSize = 0; - const void * address = data; + const void* address = data; switch (portType) { case PortDataTypeUInt32: @@ -296,22 +293,22 @@ namespace wbt { break; } - memcpy(contiguousData, address, dataSize * length); + memcpy(contiguousData, address, dataSize* length); } void Signal::set(unsigned index, bool data) { - bool *buffer = static_cast(contiguousData); + bool* buffer = static_cast(contiguousData); buffer[index] = data; } - void Signal::setBuffer(const bool *data, const unsigned length, unsigned startIndex) + void Signal::setBuffer(const bool* data, const unsigned length, unsigned startIndex) { if (isConstPort) return; unsigned dataSize = sizeof(bool); const void* address = static_cast(data) + startIndex; - memcpy(contiguousData, address, dataSize * length); + memcpy(contiguousData, address, dataSize* length); } diff --git a/toolbox/src/base/SimulinkBlockInformation.cpp b/toolbox/src/base/SimulinkBlockInformation.cpp index 9f1f69f71..48ccdde51 100644 --- a/toolbox/src/base/SimulinkBlockInformation.cpp +++ b/toolbox/src/base/SimulinkBlockInformation.cpp @@ -1,5 +1,4 @@ #include "SimulinkBlockInformation.h" - #include "Signal.h" #include "MxAnyType.h" #include "simstruc.h" @@ -8,10 +7,9 @@ namespace wbt { - SimulinkBlockInformation::SimulinkBlockInformation(SimStruct *S) - : simstruct(S) {} - - SimulinkBlockInformation::~SimulinkBlockInformation() {} + SimulinkBlockInformation::SimulinkBlockInformation(SimStruct* S) + : simstruct(S) + {} bool SimulinkBlockInformation::optionFromKey(const std::string& key, double& option) const { diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index 9ff5aac03..69a962e08 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -3,7 +3,7 @@ wbt::Block* wbt::Block::instantiateBlockWithClassName(std::string blockClassName) { wbt::Block *block = NULL; - + if (blockClassName == wbt::YarpRead::ClassName) { block = new wbt::YarpRead(); } else if (blockClassName == wbt::YarpWrite::ClassName) { diff --git a/toolbox/src/base/toolbox.cpp b/toolbox/src/base/toolbox.cpp index 2e2d9037f..ba9c86cb5 100644 --- a/toolbox/src/base/toolbox.cpp +++ b/toolbox/src/base/toolbox.cpp @@ -32,7 +32,7 @@ #include #include -static void catchLogMessages(bool status, SimStruct *S, std::string prefix) +static void catchLogMessages(bool status, SimStruct* S, std::string prefix) { // Initialize static buffers const unsigned bufferLen = 1024; @@ -97,7 +97,7 @@ static void catchLogMessages(bool status, SimStruct *S, std::string prefix) // Function: MDL_CHECK_PARAMETERS #define MDL_CHECK_PARAMETERS #if defined(MDL_CHECK_PARAMETERS) && defined(MATLAB_MEX_FILE) -static void mdlCheckParameters(SimStruct *S) +static void mdlCheckParameters(SimStruct* S) { UNUSED_ARG(S); //TODO: still to find a way to call Block implementation @@ -105,8 +105,8 @@ static void mdlCheckParameters(SimStruct *S) #endif /*MDL_CHECK_PARAMETERS*/ #define MDL_SET_INPUT_PORT_DIMENSION_INFO -static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, - const DimsInfo_T *dimsInfo) +static void mdlSetInputPortDimensionInfo(SimStruct* S, int_T port, + const DimsInfo_T* dimsInfo) { //TODO: for now accept the proposed size. //If we want to change the behaviour we have to implement some callbacks @@ -114,8 +114,8 @@ static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, } #define MDL_SET_OUTPUT_PORT_DIMENSION_INFO -static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, - const DimsInfo_T *dimsInfo) +static void mdlSetOutputPortDimensionInfo(SimStruct* S, int_T port, + const DimsInfo_T* dimsInfo) { //TODO: for now accept the proposed size. //If we want to change the behaviour we have to implement some callbacks @@ -126,7 +126,7 @@ static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, // Abstract: // The sizes information is used by Simulink to determine the S-function // block's characteristics (number of inputs, s, states, etc.). -static void mdlInitializeSizes(SimStruct *S) +static void mdlInitializeSizes(SimStruct* S) { // Initialize the Log singleton wbt::Log::getSingleton().clear(); @@ -136,10 +136,10 @@ static void mdlInitializeSizes(SimStruct *S) catchLogMessages(false, S, "\n[" + std::string(__func__) + "]"); return; } - char *classNameStr = mxArrayToString(ssGetSFcnParam(S, 0)); + char* classNameStr = mxArrayToString(ssGetSFcnParam(S, 0)); std::string className(classNameStr); mxFree(classNameStr); - wbt::Block *block = wbt::Block::instantiateBlockWithClassName(className); + wbt::Block* block = wbt::Block::instantiateBlockWithClassName(className); //We cannot save data in PWork during the initializeSizes phase ssSetNumPWork(S, 1); @@ -211,7 +211,7 @@ static void mdlInitializeSizes(SimStruct *S) // This function is used to specify the sample time(s) for your // S-function. You must register the same number of sample times as // specified in ssSetNumSampleTimes. -static void mdlInitializeSampleTimes(SimStruct *S) +static void mdlInitializeSampleTimes(SimStruct* S) { ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME); ssSetOffsetTime(S, 0, 0.0); @@ -224,12 +224,12 @@ static void mdlInitializeSampleTimes(SimStruct *S) // have states that should be initialized once, this is the place // to do it. #define MDL_START -static void mdlStart(SimStruct *S) +static void mdlStart(SimStruct* S) { - char *classNameStr = mxArrayToString(ssGetSFcnParam(S, 0)); + char* classNameStr = mxArrayToString(ssGetSFcnParam(S, 0)); std::string className(classNameStr); mxFree(classNameStr); - wbt::Block *block = wbt::Block::instantiateBlockWithClassName(className); + wbt::Block* block = wbt::Block::instantiateBlockWithClassName(className); ssSetPWorkValue(S, 0, block); wbt::SimulinkBlockInformation blockInfo(S); @@ -243,11 +243,11 @@ static void mdlStart(SimStruct *S) #define MDL_UPDATE #if defined(MDL_UPDATE) && defined(MATLAB_MEX_FILE) -static void mdlUpdate(SimStruct *S, int_T tid) +static void mdlUpdate(SimStruct* S, int_T tid) { UNUSED_ARG(tid); if (ssGetNumPWork(S) > 0) { - wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); + wbt::Block* block = static_cast(ssGetPWorkValue(S, 0)); wbt::SimulinkBlockInformation blockInfo(S); bool ok = false; @@ -262,10 +262,10 @@ static void mdlUpdate(SimStruct *S, int_T tid) //Initialize the state vectors of this C MEX S-function #define MDL_INITIALIZE_CONDITIONS #if defined(MDL_INITIALIZE_CONDITIONS) && defined(MATLAB_MEX_FILE) -static void mdlInitializeConditions(SimStruct *S) +static void mdlInitializeConditions(SimStruct* S) { if (ssGetNumPWork(S) > 0) { - wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); + wbt::Block* block = static_cast(ssGetPWorkValue(S, 0)); wbt::SimulinkBlockInformation blockInfo(S); bool ok = false; @@ -280,7 +280,7 @@ static void mdlInitializeConditions(SimStruct *S) #define MDL_DERIVATIVES #if defined(MDL_DERIVATIVES) && defined(MATLAB_MEX_FILE) -static void mdlDerivatives(SimStruct *S) +static void mdlDerivatives(SimStruct* S) { /* Add mdlDerivatives code here */ } @@ -291,11 +291,11 @@ static void mdlDerivatives(SimStruct *S) // Abstract: // In this function, you compute the outputs of your S-function // block. -static void mdlOutputs(SimStruct *S, int_T tid) +static void mdlOutputs(SimStruct* S, int_T tid) { UNUSED_ARG(tid); if (ssGetNumPWork(S) > 0) { - wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); + wbt::Block* block = static_cast(ssGetPWorkValue(S, 0)); wbt::SimulinkBlockInformation blockInfo(S); bool ok = false; @@ -306,10 +306,10 @@ static void mdlOutputs(SimStruct *S, int_T tid) } } -static void mdlTerminate(SimStruct *S) +static void mdlTerminate(SimStruct* S) { if (ssGetNumPWork(S) > 0 && ssGetPWork(S)) { - wbt::Block *block = static_cast(ssGetPWorkValue(S, 0)); + wbt::Block* block = static_cast(ssGetPWorkValue(S, 0)); wbt::SimulinkBlockInformation blockInfo(S); bool ok = false; From 639fb718b461f1bbf0d02f8d922026111dd30b33 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 14:37:43 +0000 Subject: [PATCH 15/92] WBInterface refactored and renamed to ToolboxSingleton The new ToolboxSingleton class contains in a persistent wat Configuration and RobotInterface objects. Most of the logic previously contained in WBInterface has been moved in these two new classes. --- toolbox/CMakeLists.txt | 4 +- toolbox/include/base/ToolboxSingleton.h | 143 +++++++++++ toolbox/include/base/WBInterface.h | 189 -------------- toolbox/src/base/ToolboxSingleton.cpp | 122 +++++++++ toolbox/src/base/WBInterface.cpp | 318 ------------------------ 5 files changed, 267 insertions(+), 509 deletions(-) create mode 100644 toolbox/include/base/ToolboxSingleton.h delete mode 100644 toolbox/include/base/WBInterface.h create mode 100644 toolbox/src/base/ToolboxSingleton.cpp delete mode 100644 toolbox/src/base/WBInterface.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 855625d45..d9fcf56eb 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -63,7 +63,7 @@ configure_block(BLOCK_NAME "Base" src/base/BlockInformation.cpp src/base/WBBlock.cpp src/base/Log.cpp - src/base/WBInterface.cpp + src/base/ToolboxSingleton.cpp src/base/factory.cpp src/base/SimulinkBlockInformation.cpp #this is temp src/base/Signal.cpp @@ -74,7 +74,7 @@ configure_block(BLOCK_NAME "Base" include/base/BlockInformation.h include/base/WBBlock.h include/base/Log.h - include/base/WBInterface.h + include/base/ToolboxSingleton.h include/base/SimulinkBlockInformation.h #this is temp include/base/Signal.h include/base/Configuration.h diff --git a/toolbox/include/base/ToolboxSingleton.h b/toolbox/include/base/ToolboxSingleton.h new file mode 100644 index 000000000..1140a2d76 --- /dev/null +++ b/toolbox/include/base/ToolboxSingleton.h @@ -0,0 +1,143 @@ +#ifndef WBT_ToolboxSingleton_H +#define WBT_ToolboxSingleton_H + +#include +#include +#include +#include +#include "Configuration.h" + +namespace wbt { + class ToolboxSingleton; + class RobotInterface; +} + +namespace iDynTree { + class KinDynComputations; +} + +// TODO: check class doxygen macro +/** + * \class ToolboxSingleton ToolboxSingleton.h + * + * This class handles and contains configuration and devices used by all the blocks + * allocated by a running model. It is possible obtaining a singleton of this class + * by calling WBToolbox::sharedInstance. + * + * @see wbt::RobotInterface + * @see wbt::Configuration + * @see wbt::yarpDevices + * + */ +class wbt::ToolboxSingleton { // TODO: wbt::ToolboxSingleton +private: + /// Object that stores all the configurations labelled by the name of the Simulink Block's + /// name. + /// @see wbt::RobotInterface + std::unordered_map> m_interfaces; + +public: + + // CONSTRUCTOR / DESTRUCTOR + // ======================== + + ToolboxSingleton(); + ~ToolboxSingleton(); + + ToolboxSingleton(const ToolboxSingleton&) = delete; + ToolboxSingleton& operator=(const ToolboxSingleton&) = delete; + + // UTILITIES + // ========= + + /** + * Check if a Configuration labelled by confKey exists and is a + * valid object. + * + * @param confKey The key describing the configuration (name of the Simulink block) + * @return True if the configuration is valid + */ + bool isKeyValid(const std::string& confKey); + + /** + * Returns the DoFs associated with the configuration labelled by confKey + * + * @param confKey The key describing the configuration (name of the Simulink block) + * @return The number of degrees of freedom. It returns -1 when failing. + */ + int numberOfDoFs(const std::string& confKey); + + // GET METHODS + // =========== + + /** + * Returns the singleton instance to this object. + * + * @note The singleton stays in memory until the entire matlab is closed. The WBToolbox + * is designed in such a way that assures to reach a clean state when all blocks + * have been terminated. + * + * @return the singleton instance + */ + static wbt::ToolboxSingleton& sharedInstance(); + + // TODO: check if doxygen ref work + + /** + * Returns the Configuration object labelled by confKey. + * This object is contained into the wbt::RobotInterface object. + * + * @see ToolboxSingleton::getRobotInterface + * @param confKey The key describing the configuration (name of the Simulink block) + * @return A constant reference to the Configuration object + */ + const Configuration& getConfiguration(const std::string& confKey); + + /** + * Returns a \c shared_ptr to the RobotInterface object containing the configuration + * labelled by confKey and all the objects used to gather and set robot data + * + * @param confKey The key describing the configuration (name of the Simulink block) + * @return A \c shared_ptr to the RobotInterface of the requested configuration + */ + const std::shared_ptr getRobotInterface(const std::string& confKey); + + /** + * Returns a \c shared_ptr to the KinDynComputations object used to perform calculation + * on the provided model + * + * @param confKey The key describing the configuration (name of the Simulink block) + * @return A \c shared_ptr to the iDynTree::KinDynComputations of the requested + * configuration + */ + const std::shared_ptr getModel(const std::string& confKey); + + // TOOLBOXSINGLETON CONFIGURATION + // ============================== + + /*! Saves in the singleton a new configuration \c config. + * + * If the config is valid and hasn't been already stored, it creates a new entry + * in ToolboxSingleton::m_interfaces. If a configuration with matching confKey is found, + * if the Configuration object is the same it does nothing, otherwise it overrides it. + * + * @note Since confKey is the name of the block, the overriding can happen only after + * subsequent compilation in Simulink, when the block's parameters have been + * changed. + * + * @param confKey The key describing the configuration (name of the Simulink block) + * @param config The wbt::Configuration object parsed from Simulink's parameters + * @return Returns \c true if configure is successful, \c false otherwise + * @see ToolboxSingleton::isKeyValid + */ + bool storeConfiguration(const std::string& confKey, const Configuration& config); + + /** + * Delete the wbt::RobotInterface referred by confKey. No-op if it doesn't exist. + * + * @param confKey The key describing the configuration (name of the Simulink block) + */ + void eraseConfiguration(const std::string& confKey); +}; + +#endif /* end of include guard: WBT_ToolboxSingleton_H */ diff --git a/toolbox/include/base/WBInterface.h b/toolbox/include/base/WBInterface.h deleted file mode 100644 index bfae00cc9..000000000 --- a/toolbox/include/base/WBInterface.h +++ /dev/null @@ -1,189 +0,0 @@ -#ifndef WBT_WBINTERFACE_H -#define WBT_WBINTERFACE_H - -#include - -namespace wbt { - class WBInterface; - class Error; -} - -namespace wbi { - class wholeBodyInterface; - class iWholeBodyModel; - class IDList; -} -namespace yarp { - namespace os { - class Property; - } -} - -/** - * This class holds a reference counted handle to the whole body interface object. - * You can obtain the singleton reference to this object by calling the sharedInstance method. - * @note at the current state, and because of how the wbi is structured, the model and the interface are - * two different objects, even if this should not lead to any problem - */ -class wbt::WBInterface { - - // Private constructor, destructor, copy constructor and assignemnt operator - WBInterface(); - WBInterface(const WBInterface&); - WBInterface& operator=(const WBInterface&); - ~WBInterface(); - - - wbi::wholeBodyInterface* m_interface; /**< Reference to the interface object */ - wbi::iWholeBodyModel* m_model; /**< Reference to the model object */ - - wbi::IDList *m_robotList; /**< Reference to the joint list object */ - yarp::os::Property *m_configuration; /**< Reference to the configuration used to configure the interface */ - - bool m_initialized; /**< true if the interface has been initialized */ - bool m_modelInitialized; /**< true if the model has been initialized */ - bool m_configured; /**< true if the interface has been configured */ - int m_dofs; /**< dofs modelled by the interface */ - - std::string m_wbiFilePath; - std::string m_wbiListName; - - static unsigned s_referenceCount; /**< number of blocks currently initialized */ - static unsigned s_modelReferenceCount; /**< number of model blocks currently initialized */ - -public: - /** - * Returns the singleton instance to this object. - * - * This is the only way to obtain a reference to an instance of this class - * @return the singleton instance - */ - static wbt::WBInterface& sharedInstance(); - - /** - * Returns the constant pointer to the whole body interface object - * - * @return the whole body interface object - */ - wbi::wholeBodyInterface * const interface(); - - /** - * @return a weak pointer to the model; - */ - wbi::iWholeBodyModel * const model(); - - /** - * @return the current configuration used for the interface and/or model - */ - const yarp::os::Property * const currentConfiguration() const; - - /** - * Returns the degrees of freedom associated with the interface object - * - * @return degrees of freedom of the WBI object - */ - int numberOfDoFs() const; - - /** - * Load the used wbi::IDList from the WBI configuration and the list parameter - * - * @param wbiConfigFile wbi configuration file - * @param list either the name of joint list to be found in the wbi configuration file, - * or directly a list in the format (value1 value2 value3) - * @return true if loading the list was successful, false otherwise. - */ - static bool wbdIDListFromConfigPropAndList(const yarp::os::Property & wbiConfigProp, - const std::string & list, - wbi::IDList & idList); - - /** - * Returns the degrees of freedom for the specified configuration file and the list parameter - * - * @note this method also save the dofs in the internal state. It is thus possible to retrieve it - * by calling numberOfDofs. - * @todo: maybe we should transform this method into const? - * @param wbiConfigFile wbi configuration file - * @param list either the name of joint list to be found in the wbi configuration file, - * or directly a list in the format (Value1 value2 value3) - * - * @return the degrees of freedom of the specified list - */ - int dofsForConfigurationFileAndList(const std::string & wbiConfigFile, const std::string & list); - - /** - * Configure the interface with the specified paramters. - * - * @Note: the interface is configured only once. Subsequent calls are ignored. - * Call clearConfiguration() to clear the configuration. - * @param robotName name of the robot (The model will connect to port with this name as prefix). - * empty the one specified in the configuration file is taken - * @param localName name of the model (ports will be open with this name) - * @param wbiConfigFile name of the wbi configuration file. The file will be looked for by using - * yarp::os::ResourceFinder policies - * @param list either the name of joint list to be found in the wbi configuration file, - * or directly a list in the format (Value1 value2 value3) - * @param [out]error Pointer to the error object to be filled in case of error. - * Check for NULL before using it - * - * @return true if configure is successful, false otherwise. - */ - bool configure(const std::string &robotName, - const std::string & localName, - const std::string & wbiConfigFile, - const std::string & list, - wbt::Error *error); - - /** - * Clear the current configuration, so that configure can be called again. - */ - void clearConfiguration(); - - /** - * Initialize the whole body interface. - * - * This call has effect only the first time. Subsequent calls only increase the reference count - * @Note: Each initialize call should be matched by a subsequent call to terminate. - * @return: true if configure is successful, false otherwise. - */ - bool initialize(); - - /** - * Initialize the model. - * - * This call has effect only the first time. Subsequent calls only increase the reference count - * @Note: Each initialize call should be matched by a subsequent call to terminateModel. - * @return: true if configure is successful, false otherwise. - */ - bool initializeModel(); - - /** - * Release the resources associated with the whole body interface - * - * @Note: resources are released only if the call is made by the last object using the interface - * otherwise the reference count is decreased and no resources are relased. - * @return true if configure is successful, false otherwise. - */ - bool terminate(); - - /** - * Release the resources associated with the model - * - * @Note: resources are released only if the call is made by the last object using the interface - * otherwise the reference count is decreased and no resources are relased. - * @return true if configure is successful, false otherwise. - */ - bool terminateModel(); - - /** - * Returns true if the interface is initialized. False otherwise - * - * @return true if the interface is initialized, false otherwise - */ - bool isInterfaceInitialized() const; - - const wbi::IDList* wbiList() const; - const std::string& wbiFilePath() const; - const std::string& wbiListName() const; -}; - -#endif /* end of include guard: WBT_WBINTERFACE_H */ diff --git a/toolbox/src/base/ToolboxSingleton.cpp b/toolbox/src/base/ToolboxSingleton.cpp new file mode 100644 index 000000000..a3d7981b5 --- /dev/null +++ b/toolbox/src/base/ToolboxSingleton.cpp @@ -0,0 +1,122 @@ +#include "ToolboxSingleton.h" + +#include "Log.h" +#include "RobotInterface.h" +#include +#include +#include +#include +#include + +// TODO: remove nesting +namespace wbt { + + // CONSTRUCTOR / DESTRUCTOR + // ======================== + + ToolboxSingleton::ToolboxSingleton() {} + ToolboxSingleton::~ToolboxSingleton() {} + + // UTILITIES + // ========= + + int ToolboxSingleton::numberOfDoFs(const std::string& confKey) + { + if (!isKeyValid(confKey)) + return -1; + else + return m_interfaces[confKey]->getConfiguration().getNumberOfDoFs(); + } + + bool ToolboxSingleton::isKeyValid(const std::string& confKey) + { + if (m_interfaces.find(confKey) != m_interfaces.end()) { + if (m_interfaces[confKey]) + return true; + else + return false; + } + else { + return false; + } + } + + // GET METHODS + // =========== + + ToolboxSingleton& ToolboxSingleton::sharedInstance() + { + static ToolboxSingleton instance; + return instance; + } + + const Configuration& ToolboxSingleton::getConfiguration(const std::string& confKey) + { + return getRobotInterface(confKey)->getConfiguration(); + } + + const std::shared_ptr ToolboxSingleton::getRobotInterface(const std::string& confKey) + { + if (!isKeyValid(confKey)) { + return nullptr; + } + + return m_interfaces[confKey]; + } + + const std::shared_ptr ToolboxSingleton::getModel(const std::string& confKey) + { + if (!isKeyValid(confKey)) { + return nullptr; + } + + return m_interfaces[confKey]->getKinDynComputations(); + } + + // TOOLBOXSINGLETON CONFIGURATION + // ============================== + + bool ToolboxSingleton::storeConfiguration(const std::string& confKey, const Configuration& config) + { + if (!config.isValid()) { + return false; + } + + // Add the new Configuration object and override an existing key if it already exist. + // Note: Simulink doesn't flush memory unless Matlab is closed, and static objects stay in memory. + // This may cause problems if the config block's mask is changed after the first compilation. + if (m_interfaces.find(confKey) == m_interfaces.end()) { + m_interfaces[confKey] = std::make_shared(config); + return static_cast(m_interfaces[confKey]); + } + + if (!(m_interfaces[confKey]->getConfiguration() == config)) { + assert(m_interfaces[confKey]); + + // Check that at top there are 2 instances of the model: + // the private member of RobotInterface and the one returned + // by the model() called by the assert itself + assert(getModel(confKey).use_count() <= 2); + // TODO: and also m_robotDeviceCounter should be max 1 + // + // TODO: domani: quando finisce la simulazione (terminate) dovrei avere + // dentro tutti i Configuration al massimo 1 sia di model che di + // device (e le interfacce tutte chiuse?) + + // Delete the old configuration (calling the destructor for cleaning garbage) + m_interfaces[confKey].reset(); + m_interfaces.erase(confKey); + + // Allocate a new configuration + m_interfaces[confKey] = std::make_shared(config); + return static_cast(m_interfaces[confKey]); + } + + return true; + } + + void ToolboxSingleton::eraseConfiguration(const std::string& confKey) + { + m_interfaces.erase(confKey); + } +} diff --git a/toolbox/src/base/WBInterface.cpp b/toolbox/src/base/WBInterface.cpp deleted file mode 100644 index befd4051d..000000000 --- a/toolbox/src/base/WBInterface.cpp +++ /dev/null @@ -1,318 +0,0 @@ -#include "WBInterface.h" - -#include "Error.h" -#include -#include - -namespace wbt { - - unsigned WBInterface::s_referenceCount = 0; - unsigned WBInterface::s_modelReferenceCount = 0; - - WBInterface::WBInterface() - : m_interface(0) - , m_model(0) - , m_robotList(0) - , m_configuration(0) - , m_initialized(false) - , m_modelInitialized(false) - , m_configured(false) - , m_dofs(-1) {} - - WBInterface::WBInterface(const WBInterface&) {} - WBInterface::~WBInterface() {} - WBInterface& WBInterface::operator=(const wbt::WBInterface &) { return *this; } - - WBInterface& WBInterface::sharedInstance() - { - static WBInterface instance; - return instance; - //TODO: check if the destructor get called at simulink exit - } - - wbi::wholeBodyInterface * const WBInterface::interface() { return m_interface; } - - wbi::iWholeBodyModel * const WBInterface::model() - { - if (!m_model) - return ((yarpWbi::yarpWholeBodyInterface*)m_interface)->wholeBodyModel(); - return m_model; - } - - const yarp::os::Property * const WBInterface::currentConfiguration() const - { - return m_configuration; - } - - - int WBInterface::numberOfDoFs() const { return m_dofs; } - - bool WBInterface::wbdIDListFromConfigPropAndList(const yarp::os::Property& wbiConfigProp, - const std::string& list, wbi::IDList& idList) { - // There are two ways of specifying the list throuth the mask parameter: - // either the specified parameter is a list (in the sense of YARP configuration file list, - // so something like (joint1,joint2,joint3) ) and it that case it is - // considered to by directly the list of joints to load, or otherwise - // the wbi list is just a string, and it is considered the name of the list - // in the yarpWholeBodyInterface.ini file - - // Reset the idList - idList.removeAllIDs(); - - // Check if the list string is actually a list - yarp::os::Value listAsValue; - listAsValue.fromString(list.c_str()); - - if (listAsValue.isList()) { - // If the list param is a (YARP) list, load the IDList from it - for (int jnt = 0; jnt < listAsValue.asList()->size(); jnt++) - { - yarp::os::ConstString jntName = listAsValue.asList()->get(jnt).asString(); - idList.addID(wbi::ID(jntName.c_str())); - } - } else { - // Otherwise consider the list to be a - if (!yarpWbi::loadIdListFromConfig(list, wbiConfigProp, idList)) { - return false; - } - } - return true; - } - - int WBInterface::dofsForConfigurationFileAndList(const std::string & wbiConfigFile, const std::string & list) - { - using namespace yarp::os; - - //Workaround for the fact that ResourceFinder initializes the network by itself. See YARP#1014 - Network network; - - ResourceFinder &resourceFinder = ResourceFinder::getResourceFinderSingleton(); - resourceFinder.configure(0, 0); - - Property configurations; - //loading defaults from configuration file - if (!configurations.fromConfigFile(resourceFinder.findFile(wbiConfigFile))) { - return -1; - } - - wbi::IDList jointList; - //parse the file to get the joint list - if (!WBInterface::wbdIDListFromConfigPropAndList(configurations,list,jointList)) { - return -2; - } - - m_dofs = jointList.size(); - - return m_dofs; - } - - bool WBInterface::configure(const std::string &robotName, - const std::string & localName, - const std::string & wbiConfigFile, - const std::string & list, - wbt::Error *error) - { - if (m_configured) return true; - - using namespace yarp::os; - - //Workaround for the fact that ResourceFinder initializes the network by itself. See YARP#1014 - Network network; - ResourceFinder &resourceFinder = ResourceFinder::getResourceFinderSingleton(); - resourceFinder.configure(0, 0); - - //parameters needed by this block: - // - YARP_ROBOT_NAME: needed by resource finder for resource lookup (for now it is taken by the environment) - // - robot: robot port. If defined overrides the one specified by wbi file - // - moduleName: local (opened) ports. - // - wbi config file name (default: yarpWholeBodyInterface.ini): specifies the wbi config file - // - wbi list (default ROBOT_TORQUE_CONTROL_JOINTS): specifies the WBI list. - // If it is a list [of style: (value1 value2 value3)] it specifies directly the list of joints to control, - // otherwise its value specifies the name of list present the wbi config file. - - if (m_configuration) { - delete m_configuration; - m_configuration = 0; - } - m_configuration = new Property(); - //loading defaults - m_wbiFilePath = resourceFinder.findFile(wbiConfigFile); - if (!m_configuration->fromConfigFile(m_wbiFilePath)) { - if (error) error->message = "Could not load the WBI configuration file"; - return false; - } - - //overwriting values - if (!robotName.empty()) - m_configuration->put("robot", robotName); - - m_configuration->put("localName", localName); - - //loading joint list - if (m_robotList) { - delete m_robotList; - m_robotList = 0; - } - - m_robotList = new wbi::IDList(); - - if (!WBInterface::wbdIDListFromConfigPropAndList(*m_configuration,list,*m_robotList)) { - if(error) error->message = "Could not load the specified WBI list (list param: " + list + " )"; - Network::fini(); - return false; - } - m_wbiListName = list; - - m_dofs = m_robotList->size(); - - m_configured = true; - - return true; - } - - void WBInterface::clearConfiguration() - { - m_configured = false; - if (m_robotList) { - delete m_robotList; - m_robotList = 0; - } - if (m_configuration) { - delete m_configuration; - m_configuration = 0; - } - } - - bool WBInterface::initialize() - { - if (m_initialized) { - s_referenceCount++; - return true; - } - - if (!m_configuration || !m_robotList) return false; - - if (m_interface) { - m_interface->close(); - delete m_interface; - m_interface = 0; - } - - m_interface = new yarpWbi::yarpWholeBodyInterface(m_configuration->find("localName").toString().c_str(), *m_configuration); - if (!m_interface) return false; - - s_referenceCount = 1; - - if (!m_interface->addJoints(*m_robotList)) { - terminate(); - return false; - } - - if (!m_interface->init()) { - terminate(); - return false; - } - - m_initialized = true; - return true; - } - - bool WBInterface::initializeModel() - { - if (m_modelInitialized) { - s_modelReferenceCount++; - return true; - } - - if (!m_configuration || !m_robotList) return false; - - if (m_model) { - m_model->close(); - delete m_model; - m_model = 0; - } - - m_model = new yarpWbi::yarpWholeBodyModel(m_configuration->find("localName").toString().c_str(), *m_configuration); - if (!m_model) return false; - - s_modelReferenceCount = 1; - - if (!m_model->addJoints(*m_robotList)) { - terminateModel(); - return false; - } - - if (!m_model->init()) { - terminateModel(); - return false; - } - - m_modelInitialized = true; - return true; - } - - bool WBInterface::terminate() - { - if (s_referenceCount > 1) { - s_referenceCount--; - return true; - } - - bool result = true; - if (m_interface) { - result = m_interface->close(); - if (result) { - delete m_interface; - m_interface = 0; - } - } - - //clean also configuration if also model has been removed - if (!m_modelInitialized) clearConfiguration(); - m_initialized = false; - s_referenceCount = 0; - return result; - } - - bool WBInterface::terminateModel() - { - if (s_modelReferenceCount > 1) { - s_modelReferenceCount--; - return true; - } - - bool result = true; - if (m_model) { - result = m_model->close(); - if (result) { - delete m_model; - m_model = 0; - } - } - - //clean also configuration if also interface has been removed - if (!m_initialized) clearConfiguration(); - m_modelInitialized = false; - s_modelReferenceCount = 0; - return result; - } - - bool WBInterface::isInterfaceInitialized() const { return m_initialized; } - - const wbi::IDList* WBInterface::wbiList() const - { - if (m_robotList) - return m_robotList; - return NULL; - } - - const std::string& WBInterface::wbiFilePath() const - { - return m_wbiFilePath; - } - - const std::string& WBInterface::wbiListName() const - { - return m_wbiListName; - } -} From 42a06f4546a9411de615eb96f5cdc71dfadcf7cc Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:14:11 +0000 Subject: [PATCH 16/92] CentroidalMomentum refactored --- toolbox/include/CentroidalMomentum.h | 37 +++-- toolbox/src/CentroidalMomentum.cpp | 237 ++++++++++++++------------- 2 files changed, 142 insertions(+), 132 deletions(-) diff --git a/toolbox/include/CentroidalMomentum.h b/toolbox/include/CentroidalMomentum.h index c4c5c121d..d3abb34bb 100644 --- a/toolbox/include/CentroidalMomentum.h +++ b/toolbox/include/CentroidalMomentum.h @@ -1,35 +1,36 @@ #ifndef WBT_CENTROIDALMOMENTUM_H #define WBT_CENTROIDALMOMENTUM_H -#include "WBIModelBlock.h" +#include "WBBlock.h" namespace wbt { class CentroidalMomentum; } -class wbt::CentroidalMomentum : public wbt::WBIModelBlock { +namespace iDynTree { + class SpatialMomentum; +} - double *m_basePose; - double *m_centroidalMomentum; +class wbt::CentroidalMomentum : public wbt::WBBlock +{ +private: + iDynTree::SpatialMomentum* m_centroidalMomentum; - //input buffers - double *m_basePoseRaw; - double *m_configuration; - double *m_baseVelocity; - double *m_jointsVelocity; + static const unsigned INPUT_IDX_BASE_POSE; + static const unsigned INPUT_IDX_JOINTCONF; + static const unsigned INPUT_IDX_BASE_VEL; + static const unsigned INPUT_IDX_JOINT_VEL; + static const unsigned OUTPUT_IDX_CENTRMOM; public: - static std::string ClassName; + static const std::string ClassName; CentroidalMomentum(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); + bool configureSizeAndPorts(BlockInformation* blockInfo) override; - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - - + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - -#endif /* end of include guard: WBT_CENTROIDALMOMENTUM_H */ +#endif /* WBT_CENTROIDALMOMENTUM_H */ diff --git a/toolbox/src/CentroidalMomentum.cpp b/toolbox/src/CentroidalMomentum.cpp index 35a707f68..ca93b9308 100644 --- a/toolbox/src/CentroidalMomentum.cpp +++ b/toolbox/src/CentroidalMomentum.cpp @@ -2,158 +2,167 @@ #include "BlockInformation.h" #include "Signal.h" -#include "Error.h" -#include "WBInterface.h" -#include -#include +#include "Log.h" +#include "RobotInterface.h" +#include +#include +#include +#include #include namespace wbt { - std::string CentroidalMomentum::ClassName = "CentroidalMomentum"; + const std::string CentroidalMomentum::ClassName = "CentroidalMomentum"; + + const unsigned CentroidalMomentum::INPUT_IDX_BASE_POSE = 0; + const unsigned CentroidalMomentum::INPUT_IDX_JOINTCONF = 1; + const unsigned CentroidalMomentum::INPUT_IDX_BASE_VEL = 2; + const unsigned CentroidalMomentum::INPUT_IDX_JOINT_VEL = 3; + const unsigned CentroidalMomentum::OUTPUT_IDX_CENTRMOM = 0; CentroidalMomentum::CentroidalMomentum() - : m_basePose(0) - , m_centroidalMomentum(0) - , m_basePoseRaw(0) - , m_configuration(0) - , m_baseVelocity(0) - , m_jointsVelocity(0) {} - - bool CentroidalMomentum::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + : m_centroidalMomentum(nullptr) + {} + + bool CentroidalMomentum::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + // Memory allocation / Saving data not allowed here - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // Specify I/O - // Input ports: - // - 4x4 matrix (homogenous transformation for the base pose w.r.t. world) - // - DoFs vector for the robot (joints) configurations + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // 4) Joints velocity (1xDoFs vector) + // + // Number of inputs if (!blockInfo->setNumberOfInputPorts(4)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(0, 4, 4); //base pose - success = success && blockInfo->setInputPortVectorSize(1, dofs); //joint configuration - success = success && blockInfo->setInputPortVectorSize(2, 6); //base velocity - success = success && blockInfo->setInputPortVectorSize(3, dofs); //joints velocitity + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - blockInfo->setInputPortType(0, PortDataTypeDouble); - blockInfo->setInputPortType(1, PortDataTypeDouble); - blockInfo->setInputPortType(2, PortDataTypeDouble); - blockInfo->setInputPortType(3, PortDataTypeDouble); + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); + + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - // - 6 vector representing the centroidal momentum - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) Vector representing the centroidal momentum (1x6) + // + + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - success = blockInfo->setOutputPortVectorSize(0, 6); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_CENTRMOM, 6); + blockInfo->setOutputPortType(OUTPUT_IDX_CENTRMOM, PortDataTypeDouble); return success; } - bool CentroidalMomentum::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool CentroidalMomentum::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_basePose = new double[16]; - m_centroidalMomentum = new double[6]; - m_basePoseRaw = new double[16]; - m_configuration = new double[dofs]; - m_baseVelocity = new double[6]; - m_jointsVelocity = new double[dofs]; - - return m_basePose && m_centroidalMomentum && m_basePoseRaw && m_configuration && m_baseVelocity && m_jointsVelocity; + if (!WBBlock::initialize(blockInfo)) return false; + + // OUTPUT + // ====== + + m_centroidalMomentum = new iDynTree::SpatialMomentum(); + return m_centroidalMomentum; } - bool CentroidalMomentum::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool CentroidalMomentum::terminate(BlockInformation* blockInfo) { - if (m_basePose) { - delete [] m_basePose; - m_basePose = 0; - } if (m_centroidalMomentum) { - delete [] m_centroidalMomentum; + delete m_centroidalMomentum; m_centroidalMomentum = 0; } - if (m_basePoseRaw) { - delete [] m_basePoseRaw; - m_basePoseRaw = 0; - } - if (m_configuration) { - delete [] m_configuration; - m_configuration = 0; - } - if (m_baseVelocity) { - delete [] m_baseVelocity; - m_baseVelocity = 0; - } - if (m_jointsVelocity) { - delete [] m_jointsVelocity; - m_jointsVelocity = 0; - } - return WBIModelBlock::terminate(blockInfo, error); + return WBBlock::terminate(blockInfo); } - bool CentroidalMomentum::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool CentroidalMomentum::output(BlockInformation* blockInfo) { - //get input - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (interface) { - Signal basePoseRaw = blockInfo->getInputPortSignal(0); - Signal configuration = blockInfo->getInputPortSignal(1); - Signal baseVelocity = blockInfo->getInputPortSignal(2); - Signal jointsVelocity = blockInfo->getInputPortSignal(3); - - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_basePoseRaw[i] = basePoseRaw.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(1); ++i) { - m_configuration[i] = configuration.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(2); ++i) { - m_baseVelocity[i] = baseVelocity.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(3); ++i) { - m_jointsVelocity[i] = jointsVelocity.get(i).doubleData(); - } - - Eigen::Map > basePoseColMajor(m_basePoseRaw); - Eigen::Map > basePose(m_basePose); - basePose = basePoseColMajor; - - wbi::Frame frame; - wbi::frameFromSerialization(basePose.data(), frame); - - interface->computeCentroidalMomentum(m_configuration, - frame, - m_jointsVelocity, - m_baseVelocity, - m_centroidalMomentum); - - Signal output = blockInfo->getOutputPortSignal(0); - output.setBuffer(m_centroidalMomentum, blockInfo->getOutputPortWidth(0)); - - return true; + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; } - return false; + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // Base velocity + Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); + double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); + robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), + AngVelocity(m_baseVelocityBuffer+3, 3)); + + // Joints velocity + Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); + robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Calculate the centroidal momentum + *m_centroidalMomentum = model->getCentroidalTotalMomentum(); + + // Forward the output to Simulink + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_CENTRMOM); + output.setBuffer(toEigen(*m_centroidalMomentum).data(), + blockInfo->getOutputPortWidth(OUTPUT_IDX_CENTRMOM)); + return true; } } From aab17af561e3022a1ea6c0ada7bfd5305425af10 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:15:08 +0000 Subject: [PATCH 17/92] DotJNu refactored --- toolbox/include/DotJNu.h | 44 ++++--- toolbox/src/DotJNu.cpp | 278 ++++++++++++++++++++++----------------- 2 files changed, 177 insertions(+), 145 deletions(-) diff --git a/toolbox/include/DotJNu.h b/toolbox/include/DotJNu.h index 343b8b15c..d844bb510 100644 --- a/toolbox/include/DotJNu.h +++ b/toolbox/include/DotJNu.h @@ -1,38 +1,40 @@ #ifndef WBT_DOTJDOTQ_H #define WBT_DOTJDOTQ_H -#include "WBIModelBlock.h" +#include "WBBlock.h" +#include +#include namespace wbt { class DotJNu; } -class wbt::DotJNu : public wbt::WBIModelBlock { +class wbt::DotJNu : public wbt::WBBlock +{ +private: + // Output + iDynTree::Vector6* m_dotJNu; - double *m_basePose; - double *m_dotJNu; + // Other variables + bool m_frameIsCoM; + iDynTree::FrameIndex m_frameIndex; - //input buffers - double *m_basePoseRaw; - double *m_configuration; - double *m_baseVelocity; - double *m_jointsVelocity; - - int m_frameIndex; + static const unsigned INPUT_IDX_BASE_POSE; + static const unsigned INPUT_IDX_JOINTCONF; + static const unsigned INPUT_IDX_BASE_VEL; + static const unsigned INPUT_IDX_JOINT_VEL; + static const unsigned OUTPUT_IDX_DOTJ_NU; public: - static std::string ClassName; + static const std::string ClassName; DotJNu(); - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - - + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - -#endif /* end of include guard: WBT_DOTJDOTQ_H */ +#endif /* WBT_DOTJDOTQ_H */ diff --git a/toolbox/src/DotJNu.cpp b/toolbox/src/DotJNu.cpp index 1dfaef8e8..db9264ab2 100644 --- a/toolbox/src/DotJNu.cpp +++ b/toolbox/src/DotJNu.cpp @@ -1,186 +1,216 @@ #include "DotJNu.h" -#include "Error.h" -#include "WBInterface.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" -#include -#include +#include "RobotInterface.h" +#include +#include +#include #include namespace wbt { - std::string DotJNu::ClassName = "DotJNu"; + const std::string DotJNu::ClassName = "DotJNu"; + + const unsigned DotJNu::INPUT_IDX_BASE_POSE = 0; + const unsigned DotJNu::INPUT_IDX_JOINTCONF = 1; + const unsigned DotJNu::INPUT_IDX_BASE_VEL = 2; + const unsigned DotJNu::INPUT_IDX_JOINT_VEL = 3; + const unsigned DotJNu::OUTPUT_IDX_DOTJ_NU = 0; DotJNu::DotJNu() - : m_basePose(0) - , m_dotJNu(0) - , m_basePoseRaw(0) - , m_configuration(0) - , m_baseVelocity(0) - , m_jointsVelocity(0) - , m_frameIndex(-1) {} + : m_dotJNu(nullptr) + , m_frameIsCoM(false) + , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) + {} unsigned DotJNu::numberOfParameters() { - return WBIBlock::numberOfParameters() + 1; + return WBBlock::numberOfParameters() + 1; } - bool DotJNu::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool DotJNu::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + // Memory allocation / Saving data not allowed here - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // Specify I/O - // Input ports: - // - 4x4 matrix (homogenous transformation for the base pose w.r.t. world) - // - DoFs vector for the robot (joints) configurations + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // 4) Joints velocity (1xDoFs vector) + // + // Number of inputs if (!blockInfo->setNumberOfInputPorts(4)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(0, 4, 4); //base pose - success = success && blockInfo->setInputPortVectorSize(1, dofs); //joint configuration - success = success && blockInfo->setInputPortVectorSize(2, 6); //base velocity - success = success && blockInfo->setInputPortVectorSize(3, dofs); //joints velocitity + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - blockInfo->setInputPortType(0, PortDataTypeDouble); - blockInfo->setInputPortType(1, PortDataTypeDouble); - blockInfo->setInputPortType(2, PortDataTypeDouble); - blockInfo->setInputPortType(3, PortDataTypeDouble); + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); + + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - // - 6-d vector representing the \dot{J} \dot{q} vector - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) Vector representing the \dot{J} \nu vector (1x6) + // + + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - success = blockInfo->setOutputPortVectorSize(0, 6); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_DOTJ_NU, 6); + blockInfo->setOutputPortType(OUTPUT_IDX_DOTJ_NU, PortDataTypeDouble); return success; } - bool DotJNu::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool DotJNu::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; + if (!WBBlock::initialize(blockInfo)) return false; + + // INPUT PARAMETERS + // ================ - int parentParameters = WBIBlock::numberOfParameters() + 1; std::string frame; - if (!blockInfo->getStringParameterAtIndex(parentParameters, frame)) { - if (error) error->message = "Cannot retrieve string from frame parameter"; + int parentParameters = WBBlock::numberOfParameters(); + + if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { + Log::getSingleton().error("Cannot retrieve string from frame parameter."); return false; } - //here obtain joint list and get the frame - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (!interface) { - if (error) error->message = "Cannot retrieve handle to WBI interface"; + + // Check if the frame is valid + // --------------------------- + + const auto& model = getRobotInterface()->getKinDynComputations(); + if (!model) { + Log::getSingleton().error("Cannot retrieve handle to KinDynComputations."); return false; } - wbi::IDList frames = interface->getFrameList(); + if (frame != "com") { - if (!frames.idToIndex(wbi::ID(frame), m_frameIndex)) { - if (error) error->message = "Cannot find " + frame + " in the frame list"; + m_frameIndex = model->getFrameIndex(frame); + if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { + Log::getSingleton().error("Cannot find " + frame + " in the frame list."); return false; } - } else { - m_frameIndex = wbi::wholeBodyInterface::COM_LINK_ID; } - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_basePose = new double[16]; - m_dotJNu = new double[6]; - m_basePoseRaw = new double[16]; - m_configuration = new double[dofs]; - m_baseVelocity = new double[6]; - m_jointsVelocity = new double[dofs]; - - return m_basePose && m_dotJNu && m_basePoseRaw && m_configuration && m_baseVelocity && m_jointsVelocity; + else { + m_frameIsCoM = true; + m_frameIndex = iDynTree::FRAME_INVALID_INDEX; + } + + // OUTPUT + // ====== + m_dotJNu = new iDynTree::Vector6(); + m_dotJNu->zero(); + + return m_dotJNu; } - bool DotJNu::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool DotJNu::terminate(BlockInformation* blockInfo) { - if (m_basePose) { - delete [] m_basePose; - m_basePose = 0; - } + // Output if (m_dotJNu) { - delete [] m_dotJNu; + delete m_dotJNu; m_dotJNu = 0; } - if (m_basePoseRaw) { - delete [] m_basePoseRaw; - m_basePoseRaw = 0; - } - if (m_configuration) { - delete [] m_configuration; - m_configuration = 0; - } - if (m_baseVelocity) { - delete [] m_baseVelocity; - m_baseVelocity = 0; - } - if (m_jointsVelocity) { - delete [] m_jointsVelocity; - m_jointsVelocity = 0; - } - return WBIModelBlock::terminate(blockInfo, error); + + return WBBlock::terminate(blockInfo); } - bool DotJNu::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool DotJNu::output(BlockInformation* blockInfo) { - //get input - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (interface) { - Signal basePoseRaw = blockInfo->getInputPortSignal(0); - Signal configuration = blockInfo->getInputPortSignal(1); - Signal baseVelocity = blockInfo->getInputPortSignal(2); - Signal jointsVelocity = blockInfo->getInputPortSignal(3); - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_basePoseRaw[i] = basePoseRaw.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(1); ++i) { - m_configuration[i] = configuration.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(2); ++i) { - m_baseVelocity[i] = baseVelocity.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(3); ++i) { - m_jointsVelocity[i] = jointsVelocity.get(i).doubleData(); - } - - Eigen::Map > basePoseColMajor(m_basePoseRaw); - Eigen::Map > basePose(m_basePose); - basePose = basePoseColMajor; + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; - wbi::Frame frame; - wbi::frameFromSerialization(basePose.data(), frame); + const auto& model = getRobotInterface()->getKinDynComputations(); - interface->computeDJdq(m_configuration, - frame, - m_jointsVelocity, - m_baseVelocity, - m_frameIndex, - m_dotJNu); - - Signal output = blockInfo->getOutputPortSignal(0); - output.setBuffer(m_dotJNu, blockInfo->getOutputPortWidth(0)); + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } - return true; + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // Base velocity + Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); + double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); + robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), + AngVelocity(m_baseVelocityBuffer+3, 3)); + + // Joints velocity + Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); + robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Compute the dot{J}*\nu + Vector6 biasAcc; + if (!m_frameIsCoM) { + biasAcc = model->getFrameBiasAcc(m_frameIndex); + } + else { + Vector3 comBiasAcc = model->getCenterOfMassBiasAcc(); + toEigen(biasAcc).segment<3>(0) = iDynTree::toEigen(comBiasAcc); + toEigen(biasAcc).segment<3>(3).setZero(); } - return false; + + // Forward the output to Simulink + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_DOTJ_NU); + output.setBuffer(m_dotJNu->data(), + blockInfo->getOutputPortWidth(OUTPUT_IDX_DOTJ_NU)); + return true; } } From 2881b1b08176df3e8cae95773bfeeefafdf78a3a Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:16:12 +0000 Subject: [PATCH 18/92] ForwardKinematics refactored --- toolbox/include/ForwardKinematics.h | 37 +++-- toolbox/src/ForwardKinematics.cpp | 228 ++++++++++++++++------------ 2 files changed, 147 insertions(+), 118 deletions(-) diff --git a/toolbox/include/ForwardKinematics.h b/toolbox/include/ForwardKinematics.h index 6ed0e5bf9..147f2c7b4 100644 --- a/toolbox/include/ForwardKinematics.h +++ b/toolbox/include/ForwardKinematics.h @@ -1,36 +1,33 @@ #ifndef WBT_FORWARDKINEMATICS_H #define WBT_FORWARDKINEMATICS_H -#include "WBIModelBlock.h" +#include "WBBlock.h" +#include namespace wbt { class ForwardKinematics; } -class wbt::ForwardKinematics : public wbt::WBIModelBlock { +class wbt::ForwardKinematics : public wbt::WBBlock +{ +private: + bool m_frameIsCoM; + iDynTree::FrameIndex m_frameIndex; - double *m_basePose; - double *m_frameForwardKinematics; - - //input buffers - double *m_basePoseRaw; - double *m_configuration; - - int m_frameIndex; + static const unsigned INPUT_IDX_BASE_POSE; + static const unsigned INPUT_IDX_JOINTCONF; + static const unsigned OUTPUT_IDX_FW_FRAME; public: - static std::string ClassName; + static const std::string ClassName; ForwardKinematics(); - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - -#endif /* end of include guard: WBT_FORWARDKINEMATICS_H */ +#endif /* WBT_FORWARDKINEMATICS_H */ diff --git a/toolbox/src/ForwardKinematics.cpp b/toolbox/src/ForwardKinematics.cpp index 81f7dee14..052713745 100644 --- a/toolbox/src/ForwardKinematics.cpp +++ b/toolbox/src/ForwardKinematics.cpp @@ -2,160 +2,192 @@ #include "BlockInformation.h" #include "Signal.h" -#include "Error.h" -#include "WBInterface.h" -#include -#include +#include "Log.h" +#include "RobotInterface.h" +#include +#include +#include #include namespace wbt { - std::string ForwardKinematics::ClassName = "ForwardKinematics"; + const std::string ForwardKinematics::ClassName = "ForwardKinematics"; + + const unsigned ForwardKinematics::INPUT_IDX_BASE_POSE = 0; + const unsigned ForwardKinematics::INPUT_IDX_JOINTCONF = 1; + const unsigned ForwardKinematics::OUTPUT_IDX_FW_FRAME = 0; ForwardKinematics::ForwardKinematics() - : m_basePose(0) - , m_frameForwardKinematics(0) - , m_basePoseRaw(0) - , m_configuration(0) - , m_frameIndex(-1) {} + : m_frameIsCoM(false) + , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) + {} unsigned ForwardKinematics::numberOfParameters() { - return WBIBlock::numberOfParameters() + 1; + return WBBlock::numberOfParameters() + 1; } - bool ForwardKinematics::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool ForwardKinematics::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + // Memory allocation / Saving data not allowed here - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // Specify I/O - // Input ports: - // - 4x4 matrix (homogenous transformation for the base pose w.r.t. world) - // - DoFs vector for the robot (joints) configurations + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // + // Number of inputs if (!blockInfo->setNumberOfInputPorts(2)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Size and type bool success = true; - success = success && blockInfo->setInputPortMatrixSize(0, 4, 4); - success = success && blockInfo->setInputPortVectorSize(1, dofs); + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - blockInfo->setInputPortType(0, PortDataTypeDouble); - blockInfo->setInputPortType(1, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - // - (4)x(4) matrix representing the homogenous transformation between the specified frame and the world frame - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) Homogeneous transformation between the world and the specified frame (4x4 matrix) + // + + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - success = blockInfo->setOutputPortMatrixSize(0, 4, 4); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_FW_FRAME, 4, 4); + blockInfo->setOutputPortType(OUTPUT_IDX_FW_FRAME, PortDataTypeDouble); return success; } - bool ForwardKinematics::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool ForwardKinematics::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; + if (!WBBlock::initialize(blockInfo)) return false; + + // INPUT PARAMETERS + // ================ - int parentParameters = WBIBlock::numberOfParameters() + 1; std::string frame; - if (!blockInfo->getStringParameterAtIndex(parentParameters, frame)) { - if (error) error->message = "Cannot retrieve string from frame parameter"; + int parentParameters = WBBlock::numberOfParameters(); + + if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { + Log::getSingleton().error("Cannot retrieve string from frame parameter."); return false; } - //here obtain joint list and get the frame - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (!interface) { - if (error) error->message = "Cannot retrieve handle to WBI interface"; + // Check if the frame is valid + // --------------------------- + + const auto& model = getRobotInterface()->getKinDynComputations(); + if (!model) { + Log::getSingleton().error("Cannot retrieve handle to WBI model."); return false; } - wbi::IDList frames = interface->getFrameList(); + if (frame != "com") { - if (!frames.idToIndex(wbi::ID(frame), m_frameIndex)) { - if (error) error->message = "Cannot find " + frame + " in the frame list"; + m_frameIndex = model->getFrameIndex(frame); + if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { + Log::getSingleton().error("Cannot find " + frame + " in the frame list."); return false; } - } else { - m_frameIndex = wbi::wholeBodyInterface::COM_LINK_ID; + } + else { + m_frameIsCoM = true; + m_frameIndex = iDynTree::FRAME_INVALID_INDEX; } - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_basePose = new double[16]; - m_frameForwardKinematics = new double[4 * 4]; - m_basePoseRaw = new double[16]; - m_configuration = new double[dofs]; - - return m_basePose && m_frameForwardKinematics && m_basePoseRaw && m_configuration; + return true; } - bool ForwardKinematics::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool ForwardKinematics::terminate(BlockInformation* blockInfo) { - if (m_basePose) { - delete [] m_basePose; - m_basePose = 0; - } - if (m_frameForwardKinematics) { - delete [] m_frameForwardKinematics; - m_frameForwardKinematics = 0; - } - if (m_basePoseRaw) { - delete [] m_basePoseRaw; - m_basePoseRaw = 0; - } - if (m_configuration) { - delete [] m_configuration; - m_configuration = 0; - } - return WBIModelBlock::terminate(blockInfo, error); + return WBBlock::terminate(blockInfo); } - bool ForwardKinematics::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool ForwardKinematics::output(BlockInformation* blockInfo) { - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (interface) { - Signal basePoseRaw = blockInfo->getInputPortSignal(0); - Signal configuration = blockInfo->getInputPortSignal(1) - ; - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_basePoseRaw[i] = basePoseRaw.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(1); ++i) { - m_configuration[i] = configuration.get(i).doubleData(); - } + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + typedef Matrix Matrix4diDynTree; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + + // Get the signals and convert them to iDynTree objects + // ==================================================== - Eigen::Map > basePoseColMajor(m_basePoseRaw); - Eigen::Map > basePose(m_basePose); - basePose = basePoseColMajor; + unsigned signalWidth; - wbi::Frame frame; - wbi::frameFromSerialization(basePose.data(), frame); + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - wbi::Frame outputFrame; - interface->computeH(m_configuration, frame, m_frameIndex, outputFrame); - outputFrame.get4x4Matrix(m_frameForwardKinematics); + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - Eigen::Map > frameRowMajor(m_frameForwardKinematics); + // TODO: the other 3 inputs are taken from the previous block's setRobotState(). + // How to handle it? What happens if a nullptr is passed? - Signal output = blockInfo->getOutputPortSignal(0); - Eigen::Map > frameColMajor((double*)output.getContiguousBuffer(), 4, 4); - frameColMajor = frameRowMajor; - return true; + // Update the robot status + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // Output + // ====== + + iDynTree::Transform world_H_frame; + + // Compute the transform to the selected frame + if (!m_frameIsCoM) { + world_H_frame = model->getWorldTransform(m_frameIndex); + } + else { + world_H_frame.setPosition(model->getCenterOfMassPosition()); } - return false; + + // Get the output signal memory location + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_FW_FRAME); + + // Allocate objects for row-major -> col-major conversion + Map world_H_frame_RowMajor = toEigen(world_H_frame.asHomogeneousTransform()); + Map world_H_frame_ColMajor((double*)output.getContiguousBuffer(), + 4, 4); + + // Forward the buffer to Simulink transforming it to ColMajor + world_H_frame_ColMajor = world_H_frame_RowMajor; + return true; } } From 881f382909b74732c819d136d2105446ee6940e2 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:17:50 +0000 Subject: [PATCH 19/92] GetLimits refactored --- toolbox/include/GetLimits.h | 41 ++++--- toolbox/src/GetLimits.cpp | 209 +++++++++++++++++++++++------------- 2 files changed, 163 insertions(+), 87 deletions(-) diff --git a/toolbox/include/GetLimits.h b/toolbox/include/GetLimits.h index 539386a67..81570ee24 100644 --- a/toolbox/include/GetLimits.h +++ b/toolbox/include/GetLimits.h @@ -1,30 +1,41 @@ #ifndef WBT_GETLIMITS_H #define WBT_GETLIMITS_H -#include "WBIBlock.h" +#include "WBBlock.h" +#include namespace wbt { class GetLimits; + struct Limit; } -class wbt::GetLimits : public wbt::WBIBlock { +struct wbt::Limit +{ + std::vector min; + std::vector max; - struct Limit; - struct Limit *m_limits; - -public: - static std::string ClassName; - GetLimits(); + Limit(unsigned size = 0) + : min(size) + , max(size) + {} +}; - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); +class wbt::GetLimits : public wbt::WBBlock +{ +private: + std::unique_ptr m_limits; - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); +public: + static const std::string ClassName; + GetLimits() = default; + ~GetLimits() override = default; + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - -#endif /* end of include guard: WBT_GETLIMITS_H */ +#endif /* WBT_GETLIMITS_H */ diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index 8ad4a6093..bc2f55b10 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -1,131 +1,196 @@ #include "GetLimits.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" -#include "WBInterface.h" -#include -#include +#include "RobotInterface.h" +#include "iDynTree/KinDynComputations.h" +#include "iDynTree/Model/Model.h" +#include +#include +#include namespace wbt { - std::string GetLimits::ClassName = "GetLimits"; - - struct GetLimits::Limit { - double *min; - double *max; - - Limit(unsigned size) : min(0), max(0) - { - min = new double[size](); - max = new double[size](); - } - - ~Limit() - { - if (min) { - delete [] min; - min = 0; - } - if (max) { - delete [] max; - max = 0; - } - } - }; - - GetLimits::GetLimits() - : m_limits(0) {} + const std::string GetLimits::ClassName = "GetLimits"; unsigned GetLimits::numberOfParameters() { - return WBIBlock::numberOfParameters() + 1; + return WBBlock::numberOfParameters() + 1; } - bool GetLimits::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool GetLimits::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + // INPUTS + // ====== + // + // No inputs + // if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } - // Output port: - // - DoFs vector with the information asked - if (!blockInfo->setNumberOfOuputPorts(2)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) vector with the information asked (1xDoFs) + // + + if (!blockInfo->setNumberOfOutputPorts(2)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - bool success = blockInfo->setOutputPortVectorSize(0, dofs); //Min limit - success = success && blockInfo->setOutputPortVectorSize(1, dofs); //Max limit + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + bool success = true; + success = success && blockInfo->setOutputPortVectorSize(0, dofs); // Min limit + success = success && blockInfo->setOutputPortVectorSize(1, dofs); // Max limit blockInfo->setOutputPortType(0, PortDataTypeDouble); blockInfo->setOutputPortType(1, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure output ports"; + Log::getSingleton().error("Failed to configure output ports."); return false; } - return true; } - bool GetLimits::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool GetLimits::initialize(BlockInformation* blockInfo) { using namespace yarp::os; - if (!WBIBlock::initialize(blockInfo, error)) return false; - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - wbi::wholeBodyInterface * const interface = WBInterface::sharedInstance().interface(); + if (!WBBlock::initialize(blockInfo)) return false; - // Reading the control type + // Read the control type std::string limitType; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 1, limitType)) { - if (error) error->message = "Could not read estimate type parameter"; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, limitType)) { + Log::getSingleton().error("Could not read estimate type parameter."); return false; } - bool success = true; - if (limitType == "Position") { - m_limits = new Limit(dofs); - if (m_limits) { - success = interface->getJointLimits(m_limits->min, m_limits->max); + // Initialize the structure that stores the limits + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_limits.reset(new Limit(dofs)); + + // Initializes some buffers + double min = 0; + double max = 0; + + // From the RemoteControlBoardRemapper + // =================================== + // + // In the next methods, the values are asked using joint index and not string. + // The ControlBoardRemapper internally uses the same joints ordering of its + // initialization. In this case, it matches 1:1 the joint vector. It is hence + // possible using i to point to the correct joint. + + // Get the RemoteControlBoardRemapper and IControlLimits2 interface if needed + std::weak_ptr iControlLimits2; + if (limitType == "ControlBoardPosition" || limitType == "ControlBoardVelocity") { + // Retain the control board remapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + return false; + } + // Get the interface + if (!getRobotInterface()->getInterface(iControlLimits2)) { + Log::getSingleton().error("Failed to get IControlLimits2 interface."); + return false; + } + } + + if (limitType == "ControlBoardPosition") { + for (auto i = 0; i < dofs; ++i) { + if (!iControlLimits2.lock()->getLimits(i, &min, &max)) { + Log::getSingleton().error("Failed to get limits from the interface."); + return false; + } + m_limits->min[i] = min; + m_limits->max[i] = max; + } + } + else if (limitType == "ControlBoardVelocity") { + for (auto i = 0; i < dofs; ++i) { + if (!iControlLimits2.lock()->getVelLimits(i, &min, &max)) { + Log::getSingleton().error("Failed to get limits from the interface."); + return false; + } + m_limits->min[i] = min; + m_limits->max[i] = max; } - } else { - if (error) error->message = "Limit type not supported"; + } + + // From the URDF model + // =================== + // + // For the time being, only position limits are supported. + + else if (limitType == "ModelPosition") { + iDynTree::IJointConstPtr p_joint; + const iDynTree::Model model = getRobotInterface()->getKinDynComputations()->model(); + + for (auto i = 0; i < dofs; ++i) { + // Get the joint name + std::string joint = getConfiguration().getControlledJoints()[i]; + + // Get its index + iDynTree::LinkIndex jointIndex = model.getLinkIndex(joint); + + // Get the joint from the model + p_joint = model.getJoint(jointIndex); + + if (!p_joint->hasPosLimits()) { + Log::getSingleton().warning("Joint " + joint + " has no model limits."); + // TODO: test how these values are interpreted by Simulink + min = -std::numeric_limits::infinity(); + max = std::numeric_limits::infinity(); + } + else { + p_joint->getPosLimits(0, min, max); + } + } + } + // TODO + // else if (limitType == "ModelVelocity") { + // } + // else if (limitType == "ModelEffort") { + // } + else { + Log::getSingleton().error("Limit type " + limitType + " not recognized."); return false; } - return m_limits && success; + return true; } - bool GetLimits::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool GetLimits::terminate(BlockInformation* blockInfo) { - if (m_limits) { - delete m_limits; - m_limits = 0; + // Release the RemoteControlBoardRemapper + bool ok = true; + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); } - return WBIBlock::terminate(blockInfo, error); + + return ok && WBBlock::terminate(blockInfo); } - bool GetLimits::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool GetLimits::output(BlockInformation* blockInfo) { if (!m_limits) return false; Signal minPort = blockInfo->getOutputPortSignal(0); Signal maxPort = blockInfo->getOutputPortSignal(1); - for (int i = 0; i < blockInfo->getOutputPortWidth(0); ++i) { - minPort.set(i, m_limits->min[i]); - maxPort.set(i, m_limits->max[i]); - } + minPort.setBuffer(m_limits->min.data(), getConfiguration().getNumberOfDoFs()); + maxPort.setBuffer(m_limits->max.data(), getConfiguration().getNumberOfDoFs()); + return true; } } From fade9bb24c14769233ee31ed8da81f62bfaccd9e Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:19:28 +0000 Subject: [PATCH 20/92] InverseDynamics refactored --- toolbox/include/InverseDynamics.h | 51 +++-- toolbox/src/InverseDynamics.cpp | 340 +++++++++++++++--------------- 2 files changed, 195 insertions(+), 196 deletions(-) diff --git a/toolbox/include/InverseDynamics.h b/toolbox/include/InverseDynamics.h index 58e796131..2b035663c 100644 --- a/toolbox/include/InverseDynamics.h +++ b/toolbox/include/InverseDynamics.h @@ -1,41 +1,46 @@ #ifndef WBT_INVERSEDYNAMICS_H #define WBT_INVERSEDYNAMICS_H -#include "WBIModelBlock.h" +#include "WBBlock.h" +#include namespace wbt { class InverseDynamics; } -class wbt::InverseDynamics : public wbt::WBIModelBlock { +namespace iDynTree { + class VectorDynSize; + class FreeFloatingGeneralizedTorques; +} - double *m_basePose; - double *m_torques; +class wbt::InverseDynamics : public wbt::WBBlock +{ +private: + iDynTree::Vector6* m_baseAcceleration; + iDynTree::VectorDynSize* m_jointsAcceleration; - bool m_explicitGravity; + // Output + iDynTree::FreeFloatingGeneralizedTorques* m_torques; - //input buffers - double *m_basePoseRaw; - double *m_configuration; - double *m_baseVelocity; - double *m_jointsVelocity; - double *m_baseAcceleration; - double *m_jointsAcceleration; - double m_gravity[3]; + static const unsigned INPUT_IDX_BASE_POSE; + static const unsigned INPUT_IDX_JOINTCONF; + static const unsigned INPUT_IDX_BASE_VEL; + static const unsigned INPUT_IDX_JOINT_VEL; + static const unsigned INPUT_IDX_BASE_ACC; + static const unsigned INPUT_IDX_JOINT_ACC; + static const unsigned OUTPUT_IDX_TORQUES; public: - static std::string ClassName; + static const std::string ClassName; InverseDynamics(); - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - - -}; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; +}; -#endif /* end of include guard: WBT_INVERSEDYNAMICS_H */ +#endif /* WBT_INVERSEDYNAMICS_H */ diff --git a/toolbox/src/InverseDynamics.cpp b/toolbox/src/InverseDynamics.cpp index 45999d7cc..28b8a70c7 100644 --- a/toolbox/src/InverseDynamics.cpp +++ b/toolbox/src/InverseDynamics.cpp @@ -1,221 +1,215 @@ #include "InverseDynamics.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" -#include "WBInterface.h" -#include -#include +#include "RobotInterface.h" +#include +#include +#include +#include #include -#define PARAM_IDX_1 5 - +// TODO: Substitute with using namespace wbt { - std::string InverseDynamics::ClassName = "InverseDynamics"; + const std::string InverseDynamics::ClassName = "InverseDynamics"; + + const unsigned InverseDynamics::INPUT_IDX_BASE_POSE = 0; + const unsigned InverseDynamics::INPUT_IDX_JOINTCONF = 1; + const unsigned InverseDynamics::INPUT_IDX_BASE_VEL = 2; + const unsigned InverseDynamics::INPUT_IDX_JOINT_VEL = 3; + const unsigned InverseDynamics::INPUT_IDX_BASE_ACC = 4; + const unsigned InverseDynamics::INPUT_IDX_JOINT_ACC = 5; + const unsigned InverseDynamics::OUTPUT_IDX_TORQUES = 0; InverseDynamics::InverseDynamics() - : m_basePose(0) - , m_torques(0) - , m_explicitGravity(false) - , m_basePoseRaw(0) - , m_configuration(0) - , m_baseVelocity(0) - , m_jointsVelocity(0) - , m_baseAcceleration(0) - , m_jointsAcceleration(0) - { - m_gravity[0] = 0; - m_gravity[1] = 0; - m_gravity[2] = -9.81; - } + : m_baseAcceleration(nullptr) + , m_jointsAcceleration(nullptr) + , m_torques(nullptr) + {} unsigned InverseDynamics::numberOfParameters() { - return WBIBlock::numberOfParameters() + 1; + return WBBlock::numberOfParameters(); } - bool InverseDynamics::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool InverseDynamics::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { + // Memory allocation / Saving data not allowed here + + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // 4) Joints velocity (1xDoFs vector) + // 5) Base frame acceleration (1x6 vector) + // 6) Joints acceleration (1xDoFs vector) + // + + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(6)) { + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + // Get the DoFs + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - // Specify I/O - // Input ports: - // - 4x4 matrix (homogenous transformation for the base pose w.r.t. world) - // - DoFs vector for the robot (joints) configurations - - m_explicitGravity = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1).booleanData(); - - int portNumber = 6; - if (m_explicitGravity) portNumber++; - - if (!blockInfo->setNumberOfInputPorts(portNumber)) { - if (error) error->message = "Failed to configure the number of input ports"; - return false; - } + // Size and type bool success = true; - - success = success && blockInfo->setInputPortMatrixSize(0, 4, 4); //base pose - success = success && blockInfo->setInputPortVectorSize(1, dofs); //joint configuration - success = success && blockInfo->setInputPortVectorSize(2, 6); //base velocity - success = success && blockInfo->setInputPortVectorSize(3, dofs); //joints velocitity - success = success && blockInfo->setInputPortVectorSize(4, 6); //base acceleration - success = success && blockInfo->setInputPortVectorSize(5, dofs); //joints acceleration - if (m_explicitGravity) - success = success && blockInfo->setInputPortVectorSize(6, 3); //gravity acceleration - - blockInfo->setInputPortType(0, PortDataTypeDouble); - blockInfo->setInputPortType(1, PortDataTypeDouble); - blockInfo->setInputPortType(2, PortDataTypeDouble); - blockInfo->setInputPortType(3, PortDataTypeDouble); - blockInfo->setInputPortType(4, PortDataTypeDouble); - blockInfo->setInputPortType(5, PortDataTypeDouble); - - if (m_explicitGravity) - blockInfo->setInputPortType(6, PortDataTypeDouble); + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_ACC, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_ACC, dofs); + + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_ACC, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_ACC, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - // - DoFs + 6) vector representing the torques - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) Vector representing the torques (1x(DoFs+6)) + // + + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - success = blockInfo->setOutputPortVectorSize(0, dofs + 6); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_TORQUES, dofs + 6); + blockInfo->setOutputPortType(OUTPUT_IDX_TORQUES, PortDataTypeDouble); return success; } - bool InverseDynamics::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool InverseDynamics::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; - - m_explicitGravity = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1).booleanData(); - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_basePose = new double[16]; - m_torques = new double[6 + dofs]; - m_basePoseRaw = new double[16]; - m_configuration = new double[dofs]; - m_baseVelocity = new double[6]; - m_jointsVelocity = new double[dofs]; - m_baseAcceleration = new double[6]; - m_jointsAcceleration = new double[dofs]; - - return m_basePose && m_torques && m_basePoseRaw && m_configuration && m_baseVelocity && m_jointsVelocity && m_baseAcceleration && m_jointsAcceleration; + if (!WBBlock::initialize(blockInfo)) return false; + + // OUTPUT / VARIABLES + // ================== + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + m_baseAcceleration = new iDynTree::Vector6(); + m_baseAcceleration->zero(); + m_jointsAcceleration = new iDynTree::VectorDynSize(dofs); + m_jointsAcceleration->zero(); + + const auto& model = getRobotInterface()->getKinDynComputations()->model(); + m_torques = new iDynTree::FreeFloatingGeneralizedTorques(model); + + return m_baseAcceleration && m_jointsAcceleration && m_torques; } - bool InverseDynamics::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool InverseDynamics::terminate(BlockInformation* blockInfo) { - if (m_basePose) { - delete [] m_basePose; - m_basePose = 0; - } - if (m_torques) { - delete [] m_torques; - m_torques = 0; - } - if (m_basePoseRaw) { - delete [] m_basePoseRaw; - m_basePoseRaw = 0; - } - if (m_configuration) { - delete [] m_configuration; - m_configuration = 0; - } - if (m_baseVelocity) { - delete [] m_baseVelocity; - m_baseVelocity = 0; - } - if (m_jointsVelocity) { - delete [] m_jointsVelocity; - m_jointsVelocity = 0; - } - if (m_baseAcceleration) { - delete [] m_baseAcceleration; - m_baseAcceleration = 0; + delete m_baseAcceleration; + m_baseAcceleration = nullptr; } - if (m_jointsAcceleration) { - delete [] m_jointsAcceleration; - m_jointsAcceleration = 0; + delete m_jointsAcceleration; + m_jointsAcceleration = nullptr; + } + if (m_torques) { + delete m_torques; + m_torques = nullptr; } - return WBIModelBlock::terminate(blockInfo, error); + return WBBlock::terminate(blockInfo); } - bool InverseDynamics::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool InverseDynamics::output(BlockInformation* blockInfo) { - //get input - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (interface) { - - Signal basePoseRaw = blockInfo->getInputPortSignal(0); - Signal configuration = blockInfo->getInputPortSignal(1); - Signal baseVelocity = blockInfo->getInputPortSignal(2); - Signal jointsVelocity = blockInfo->getInputPortSignal(3); - Signal baseAcceleration = blockInfo->getInputPortSignal(4); - Signal jointsAcceleration = blockInfo->getInputPortSignal(5); - - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_basePoseRaw[i] = basePoseRaw.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(1); ++i) { - m_configuration[i] = configuration.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(2); ++i) { - m_baseVelocity[i] = baseVelocity.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(3); ++i) { - m_jointsVelocity[i] = jointsVelocity.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(4); ++i) { - m_baseAcceleration[i] = baseAcceleration.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(5); ++i) { - m_jointsAcceleration[i] = jointsAcceleration.get(i).doubleData(); - } - - if (m_explicitGravity) { - Signal gravity = blockInfo->getInputPortSignal(6); - for (unsigned i = 0; i < blockInfo->getInputPortWidth(6); ++i) { - m_gravity[i] = gravity.get(i).doubleData(); - } - } - - Eigen::Map > basePoseColMajor(m_basePoseRaw); - Eigen::Map > basePose(m_basePose); - basePose = basePoseColMajor; - - wbi::Frame frame; - wbi::frameFromSerialization(basePose.data(), frame); - - interface->inverseDynamics(m_configuration, - frame, - m_jointsVelocity, - m_baseVelocity, - m_jointsAcceleration, - m_baseAcceleration, - m_gravity, - m_torques); - - Signal output = blockInfo->getOutputPortSignal(0); - output.setBuffer(m_torques, blockInfo->getOutputPortWidth(0)); - - return true; + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; } - return false; + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // Base velocity + Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); + double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); + robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), + AngVelocity(m_baseVelocityBuffer+3, 3)); + + // Joints velocity + Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); + robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + // Base acceleration + Signal baseAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_ACC); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_ACC); + m_baseAcceleration->fillBuffer(baseAccelerationSignal.getStdVector(signalWidth).data()); + + // Joints acceleration + Signal jointsAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_ACC); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_ACC); + m_jointsAcceleration->fillBuffer(jointsAccelerationSignal.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Calculate the inverse dynamics (assuming zero external forces) + model->inverseDynamics(*m_baseAcceleration, + *m_jointsAcceleration, + LinkNetExternalWrenches(model->getNrOfLinks()), // TODO + *m_torques); + + // Forward the output to Simulink + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_TORQUES); + output.setBuffer(m_torques->jointTorques().data(), + blockInfo->getOutputPortWidth(OUTPUT_IDX_TORQUES)); + return true; } } From 58eecea9eb6c207136d589d0afe5eb3314220d2f Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:20:13 +0000 Subject: [PATCH 21/92] Jacobian refactored --- toolbox/include/Jacobian.h | 44 ++++--- toolbox/src/Jacobian.cpp | 251 +++++++++++++++++++++++-------------- 2 files changed, 183 insertions(+), 112 deletions(-) diff --git a/toolbox/include/Jacobian.h b/toolbox/include/Jacobian.h index 0c5307a19..b0726e900 100644 --- a/toolbox/include/Jacobian.h +++ b/toolbox/include/Jacobian.h @@ -1,36 +1,44 @@ #ifndef WBT_JACOBIAN_H #define WBT_JACOBIAN_H -#include "WBIModelBlock.h" +#include "WBBlock.h" +#include namespace wbt { class Jacobian; } -class wbt::Jacobian : public wbt::WBIModelBlock { +namespace iDynTree { + class MatrixDynSize; +} + +class wbt::Jacobian : public wbt::WBBlock +{ +private: + // Support variables + iDynTree::MatrixDynSize* m_jacobianCOM; - double *m_basePose; - double *m_jacobian; + // Output + iDynTree::MatrixDynSize* m_jacobian; - //input buffers - double *m_basePoseRaw; - double *m_configuration; + // Other variables + bool m_frameIsCoM; + iDynTree::FrameIndex m_frameIndex; - int m_frameIndex; + static const unsigned INPUT_IDX_BASE_POSE; + static const unsigned INPUT_IDX_JOINTCONF; + static const unsigned OUTPUT_IDX_FW_FRAME; public: - static std::string ClassName; + static const std::string ClassName; Jacobian(); - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - -#endif /* end of include guard: WBT_JACOBIAN_H */ +#endif /* WBT_JACOBIAN_H */ diff --git a/toolbox/src/Jacobian.cpp b/toolbox/src/Jacobian.cpp index eefcc8d1c..8988cf4bc 100644 --- a/toolbox/src/Jacobian.cpp +++ b/toolbox/src/Jacobian.cpp @@ -1,161 +1,224 @@ #include "Jacobian.h" -#include "Error.h" -#include "WBInterface.h" +#include "Log.h" +#include "RobotInterface.h" #include "BlockInformation.h" #include "Signal.h" -#include -#include +#include +#include +#include #include namespace wbt { - std::string Jacobian::ClassName = "Jacobian"; + const std::string Jacobian::ClassName = "Jacobian"; + + const unsigned Jacobian::INPUT_IDX_BASE_POSE = 0; + const unsigned Jacobian::INPUT_IDX_JOINTCONF = 1; + const unsigned Jacobian::OUTPUT_IDX_FW_FRAME = 0; Jacobian::Jacobian() - : m_basePose(0) - , m_jacobian(0) - , m_basePoseRaw(0) - , m_configuration(0) - , m_frameIndex(-1) {} + : m_jacobianCOM(nullptr) + , m_jacobian(nullptr) + , m_frameIsCoM(false) + , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) + {} unsigned Jacobian::numberOfParameters() { - return WBIBlock::numberOfParameters() + 1; + return WBBlock::numberOfParameters() + 1; } - bool Jacobian::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool Jacobian::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + // Memory allocation / Saving data not allowed here - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // Specify I/O - // Input ports: - // - 4x4 matrix (homogenous transformation for the base pose w.r.t. world) - // - DoFs vector for the robot (joints) configurations + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // + // Number of inputs if (!blockInfo->setNumberOfInputPorts(2)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Size and type bool success = true; - success = success && blockInfo->setInputPortMatrixSize(0, 4, 4); - success = success && blockInfo->setInputPortVectorSize(1, dofs); + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - blockInfo->setInputPortType(0, PortDataTypeDouble); - blockInfo->setInputPortType(1, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - // - (6)x(6+dofs) matrix - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) Matrix representing the Jacobian (6x(DoFs+6)) + // + + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - success = blockInfo->setOutputPortMatrixSize(0, 6, 6 + dofs); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_FW_FRAME, 6, 6 + dofs); + blockInfo->setOutputPortType(OUTPUT_IDX_FW_FRAME, PortDataTypeDouble); return success; } - bool Jacobian::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool Jacobian::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; + if (!WBBlock::initialize(blockInfo)) return false; + + // INPUT PARAMETERS + // ================ - int parentParameters = WBIBlock::numberOfParameters() + 1; - //robot name std::string frame; - if (!blockInfo->getStringParameterAtIndex(parentParameters, frame)) { - if (error) error->message = "Cannot retrieve string from frame parameter"; + int parentParameters = WBBlock::numberOfParameters(); + + if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { + Log::getSingleton().error("Cannot retrieve string from frame parameter."); return false; } - //here obtain joint list and get the frame - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (!interface) { - if (error) error->message = "Cannot retrieve handle to WBI interface"; + // Check if the frame is valid + // --------------------------- + + const auto& model = getRobotInterface()->getKinDynComputations(); + if (!model) { + Log::getSingleton().error("Cannot retrieve handle to KinDynComputations."); return false; } - wbi::IDList frames = interface->getFrameList(); + if (frame != "com") { - if (!frames.idToIndex(wbi::ID(frame), m_frameIndex)) { - if (error) error->message = "Cannot find " + frame + " in the frame list"; + m_frameIndex = model->getFrameIndex(frame); + if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { + Log::getSingleton().error("Cannot find " + frame + " in the frame list."); return false; } - } else { - m_frameIndex = wbi::wholeBodyInterface::COM_LINK_ID; } + else { + m_frameIsCoM = true; + m_frameIndex = iDynTree::FRAME_INVALID_INDEX; + } + + // OUTPUT / VARIABLES + // ================== - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_basePose = new double[16]; - m_jacobian = new double[6 * (6 + dofs)]; - m_basePoseRaw = new double[16]; - m_configuration = new double[dofs]; + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - return m_basePose && m_jacobian && m_basePoseRaw && m_configuration; + m_jacobianCOM = new iDynTree::MatrixDynSize(3, 6 + dofs); + m_jacobianCOM->zero(); + + // Output + m_jacobian = new iDynTree::MatrixDynSize(6, 6 + dofs); + m_jacobian->zero(); + + return m_jacobianCOM && m_jacobian; } - bool Jacobian::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool Jacobian::terminate(BlockInformation* blockInfo) { - if (m_basePose) { - delete [] m_basePose; - m_basePose = 0; + if (m_jacobianCOM) { + delete m_jacobianCOM; + m_jacobianCOM = nullptr; } if (m_jacobian) { - delete [] m_jacobian; - m_jacobian = 0; - } - if (m_basePoseRaw) { - delete [] m_basePoseRaw; - m_basePoseRaw = 0; - } - if (m_configuration) { - delete [] m_configuration; - m_configuration = 0; + delete m_jacobian; + m_jacobian = nullptr; } - return WBIModelBlock::terminate(blockInfo, error); + + return WBBlock::terminate(blockInfo); } - bool Jacobian::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool Jacobian::output(BlockInformation* blockInfo) { - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (interface) { - Signal basePoseRaw = blockInfo->getInputPortSignal(0); - Signal configuration = blockInfo->getInputPortSignal(1); - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_basePoseRaw[i] = basePoseRaw.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(1); ++i) { - m_configuration[i] = configuration.get(i).doubleData(); - } + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + typedef Matrix MatrixXdSimulink; + typedef Matrix MatrixXdiDynTree; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== - Eigen::Map > basePoseColMajor(m_basePoseRaw); - Eigen::Map > basePose(m_basePose); - basePose = basePoseColMajor; + unsigned signalWidth; - wbi::Frame frame; - wbi::frameFromSerialization(basePose.data(), frame); + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - interface->computeJacobian(m_configuration, frame, m_frameIndex, m_jacobian); + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - Eigen::Map > jacobianRowMajor(m_jacobian, 6, 6 + dofs); + // TODO: what about the other inputs of setRobotState? - Signal output = blockInfo->getOutputPortSignal(0); - Eigen::Map > jacobianColMajor((double*)output.getContiguousBuffer(), 6, 6 + dofs); + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); - jacobianColMajor = jacobianRowMajor; - return true; + // OUTPUT + // ====== + + iDynTree::Transform world_H_frame; + + // Compute the jacobian + bool ok = false; + if (!m_frameIsCoM) { + world_H_frame = model->getWorldTransform(m_frameIndex); + ok = model->getFrameFreeFloatingJacobian(m_frameIndex, *m_jacobian); } - return false; - } + else { + world_H_frame.setPosition(model->getCenterOfMassPosition()); + ok = model->getCenterOfMassJacobian(*m_jacobianCOM); + int cols = m_jacobianCOM->cols(); + toEigen(*m_jacobian).block(0,0,3,cols) = toEigen(*m_jacobianCOM); + toEigen(*m_jacobian).block(3,0,3,cols).setZero(); + } + + // Get the output signal memory location + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_FW_FRAME); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Allocate objects for row-major -> col-major conversion + Map jacobianRowMajor = toEigen(*m_jacobian); + Map jacobianColMajor((double*)output.getContiguousBuffer(), + 6, 6 + dofs); + + // Forward the buffer to Simulink transforming it to ColMajor + jacobianColMajor = jacobianRowMajor; + return true; + } } From 648aef94d8071bcaf6e95d66d65a2336f0d1e23b Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:21:07 +0000 Subject: [PATCH 22/92] MassMatrix refactored --- toolbox/include/MassMatrix.h | 34 +++--- toolbox/src/MassMatrix.cpp | 198 ++++++++++++++++++++--------------- 2 files changed, 132 insertions(+), 100 deletions(-) diff --git a/toolbox/include/MassMatrix.h b/toolbox/include/MassMatrix.h index ea0d58ce0..6529d4504 100644 --- a/toolbox/include/MassMatrix.h +++ b/toolbox/include/MassMatrix.h @@ -1,33 +1,35 @@ #ifndef WBT_MASSMATRIX_H #define WBT_MASSMATRIX_H -#include "WBIModelBlock.h" +#include "WBBlock.h" namespace wbt { class MassMatrix; } -class wbt::MassMatrix : public wbt::WBIModelBlock { +namespace iDynTree { + class MatrixDynSize; +} - double *m_basePose; - double *m_massMatrix; +class wbt::MassMatrix : public wbt::WBBlock +{ +private: + iDynTree::MatrixDynSize* m_massMatrix; - //input buffers - double *m_basePoseRaw; - double *m_configuration; + static const unsigned INPUT_IDX_BASE_POSE; + static const unsigned INPUT_IDX_JOINTCONF; + static const unsigned OUTPUT_IDX_MASS_MAT; public: - static std::string ClassName; + static const std::string ClassName; MassMatrix(); + ~MassMatrix() = default; - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - -#endif /* end of include guard: WBT_MASSMATRIX_H */ +#endif /* WBT_MASSMATRIX_H */ diff --git a/toolbox/src/MassMatrix.cpp b/toolbox/src/MassMatrix.cpp index 2644213ee..4fcbf7510 100644 --- a/toolbox/src/MassMatrix.cpp +++ b/toolbox/src/MassMatrix.cpp @@ -2,130 +2,160 @@ #include "BlockInformation.h" #include "Signal.h" -#include "Error.h" -#include "WBInterface.h" -#include -#include +#include "Log.h" +#include "RobotInterface.h" +#include +#include +#include #include +// TODO: remove wbt nesting; namespace wbt { - std::string MassMatrix::ClassName = "MassMatrix"; + const std::string MassMatrix::ClassName = "MassMatrix"; + + const unsigned MassMatrix::INPUT_IDX_BASE_POSE = 0; + const unsigned MassMatrix::INPUT_IDX_JOINTCONF = 1; + const unsigned MassMatrix::OUTPUT_IDX_MASS_MAT = 0; MassMatrix::MassMatrix() - : m_basePose(0) - , m_massMatrix(0) - , m_basePoseRaw(0) - , m_configuration(0) {} + : m_massMatrix(nullptr) + {} - bool MassMatrix::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool MassMatrix::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { + // Memory allocation / Saving data not allowed here + + if (!WBBlock::configureSizeAndPorts(blockInfo)) { return false; } - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - - // Specify I/O - // Input ports: - // - 4x4 matrix (homogenous transformation for the base pose w.r.t. world) - // - DoFs vector for the robot (joints) configurations + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // + // Number of inputs if (!blockInfo->setNumberOfInputPorts(2)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Size and type bool success = true; - success = success && blockInfo->setInputPortMatrixSize(0, 4, 4); - success = success && blockInfo->setInputPortVectorSize(1, dofs); - blockInfo->setInputPortType(0, PortDataTypeDouble); - blockInfo->setInputPortType(1, PortDataTypeDouble); + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - // - (DoFs + 6)x(DoFs + 6) matrix representing the mass matrix - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // 1) Matrix epresenting the mass matrix (DoFs+6)x(DoFs+6) + // + + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } - success = blockInfo->setOutputPortMatrixSize(0, dofs + 6, dofs + 6); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_MASS_MAT, dofs + 6, dofs + 6); + blockInfo->setOutputPortType(OUTPUT_IDX_MASS_MAT, PortDataTypeDouble); return success; } - bool MassMatrix::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool MassMatrix::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; + if (!WBBlock::initialize(blockInfo)) return false; - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_basePose = new double[16]; - m_massMatrix = new double[(6 + dofs)*(6 + dofs)]; - m_basePoseRaw = new double[16]; - m_configuration = new double[dofs]; + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - return m_basePose && m_massMatrix && m_basePoseRaw && m_configuration; + // Output + m_massMatrix = new iDynTree::MatrixDynSize(6 + dofs, 6 + dofs); + m_massMatrix->zero(); + + return m_massMatrix; } - bool MassMatrix::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool MassMatrix::terminate(BlockInformation* blockInfo) { - if (m_basePose) { - delete [] m_basePose; - m_basePose = 0; - } if (m_massMatrix) { - delete [] m_massMatrix; - m_massMatrix = 0; - } - if (m_basePoseRaw) { - delete [] m_basePoseRaw; - m_basePoseRaw = 0; + delete m_massMatrix; + m_massMatrix = nullptr; } - if (m_configuration) { - delete [] m_configuration; - m_configuration = 0; - } - return WBIModelBlock::terminate(blockInfo, error); + + return WBBlock::terminate(blockInfo); } - bool MassMatrix::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool MassMatrix::output(BlockInformation* blockInfo) { - //get input - wbi::iWholeBodyModel * const interface = WBInterface::sharedInstance().model(); - if (interface) { - Signal basePoseRaw = blockInfo->getInputPortSignal(0); - Signal configuration = blockInfo->getInputPortSignal(1); - - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_basePoseRaw[i] = basePoseRaw.get(i).doubleData(); - } - for (unsigned i = 0; i < blockInfo->getInputPortWidth(1); ++i) { - m_configuration[i] = configuration.get(i).doubleData(); - } - - Eigen::Map > basePoseColMajor(m_basePoseRaw); - Eigen::Map > basePose(m_basePose); - basePose = basePoseColMajor; - - wbi::Frame frame; - wbi::frameFromSerialization(basePose.data(), frame); - - interface->computeMassMatrix(m_configuration, frame, m_massMatrix); - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - Eigen::Map > massMatrixRowMajor(m_massMatrix, 6 + dofs, 6 + dofs); - - Signal output = blockInfo->getOutputPortSignal(0); - Eigen::Map > massMatrixColMajor((double*)output.getContiguousBuffer(), 6 + dofs, 6 + dofs); - massMatrixColMajor = massMatrixRowMajor; - return true; + using namespace Eigen; + using namespace iDynTree; + typedef Matrix Matrix4dSimulink; + typedef Matrix MatrixXdSimulink; + typedef Matrix MatrixXdiDynTree; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; } - return false; + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Compute the Mass Matrix + model->getFreeFloatingMassMatrix(*m_massMatrix); + + // Get the output signal memory location + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_MASS_MAT); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Allocate objects for row-major -> col-major conversion + Map massMatrixRowMajor = toEigen(*m_massMatrix); + Map massMatrixColMajor((double*)output.getContiguousBuffer(), + 6 + dofs, 6 + dofs); + + // Forward the buffer to Simulink transforming it to ColMajor + massMatrixColMajor = massMatrixRowMajor; + return true; } } From 6953aa23b16fdd2aed19d0ddc32729dc39481118 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:22:20 +0000 Subject: [PATCH 23/92] MinimumJerkTrajectoryGenerator refactored --- .../include/MinimumJerkTrajectoryGenerator.h | 35 ++-- .../src/MinimumJerkTrajectoryGenerator.cpp | 159 ++++++++++++------ 2 files changed, 128 insertions(+), 66 deletions(-) diff --git a/toolbox/include/MinimumJerkTrajectoryGenerator.h b/toolbox/include/MinimumJerkTrajectoryGenerator.h index ba0415e9f..8bf0f29b7 100644 --- a/toolbox/include/MinimumJerkTrajectoryGenerator.h +++ b/toolbox/include/MinimumJerkTrajectoryGenerator.h @@ -22,19 +22,19 @@ namespace yarp { class wbt::MinimumJerkTrajectoryGenerator : public wbt::Block { public: - static std::string ClassName; - + static const std::string ClassName; + MinimumJerkTrajectoryGenerator(); - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; + private: - iCub::ctrl::minJerkTrajGen *m_generator; + iCub::ctrl::minJerkTrajGen* m_generator; int m_outputFirstDerivativeIndex; int m_outputSecondDerivativeIndex; @@ -45,9 +45,18 @@ class wbt::MinimumJerkTrajectoryGenerator : public wbt::Block { bool m_explicitInitialValue; bool m_externalSettlingTime; bool m_resetOnSettlingTimeChange; - yarp::sig::Vector *m_initialValues; - yarp::sig::Vector *m_reference; - + yarp::sig::Vector* m_initialValues; + yarp::sig::Vector* m_reference; + + static const unsigned PARAM_IDX_SAMPLE_TIME; // Sample Time (double) + static const unsigned PARAM_IDX_SETTLING_TIME; // Settling Time (double) + static const unsigned PARAM_IDX_OUTPUT_1ST_DERIVATIVE; // Output first derivative (boolean) + static const unsigned PARAM_IDX_OUTPUT_2ND_DERIVATIVE; // Output second derivative (boolean) + static const unsigned PARAM_IDX_INITIAL_VALUE; // Initial signal value as input (boolean) + static const unsigned PARAM_IDX_EXT_SETTLINGTIME; // Control if the settling time comes from + // external port or static parameter + static const unsigned PARAM_IDX_RESET_CHANGEST; // True if the block should reset the traj + // generator in case settling time changes }; #endif /* end of include guard: WBT_MINJERKTRAJGENERATOR_H */ diff --git a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp index 65832b2bd..2760a7624 100644 --- a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp +++ b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp @@ -1,6 +1,6 @@ #include "MinimumJerkTrajectoryGenerator.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" @@ -13,48 +13,76 @@ #include -#define PARAM_IDX_1 1 //Sample Time (double) -#define PARAM_IDX_2 2 //Settling Time (double) -#define PARAM_IDX_3 3 //Output first derivative (boolean) -#define PARAM_IDX_4 4 //Output second derivative (boolean) -#define PARAM_IDX_5 5 //Initial signal value as input (boolean) -#define PARAM_IDX_6 6 //Control if the settling time comes from external port or static parameter -#define PARAM_IDX_7 7 //True if the block should reset the traj generator in case settling time changes - namespace wbt { - - std::string MinimumJerkTrajectoryGenerator::ClassName = "MinimumJerkTrajectoryGenerator"; + + const std::string MinimumJerkTrajectoryGenerator::ClassName = "MinimumJerkTrajectoryGenerator"; + + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_SAMPLE_TIME = 1; + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_SETTLING_TIME = 2; + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_OUTPUT_1ST_DERIVATIVE = 3; + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_OUTPUT_2ND_DERIVATIVE = 4; + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_INITIAL_VALUE = 5; + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_EXT_SETTLINGTIME = 6; + const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_RESET_CHANGEST = 7; MinimumJerkTrajectoryGenerator::MinimumJerkTrajectoryGenerator() - : m_generator(0) + : m_generator(nullptr) , m_outputFirstDerivativeIndex(-1) , m_outputSecondDerivativeIndex(-1) , m_firstRun(true) , m_explicitInitialValue(false) , m_externalSettlingTime(false) , m_resetOnSettlingTimeChange(false) - , m_initialValues(0) - , m_reference(0) {} - + , m_initialValues(nullptr) + , m_reference(nullptr) + {} + unsigned MinimumJerkTrajectoryGenerator::numberOfParameters() { return 7; } - bool MinimumJerkTrajectoryGenerator::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool MinimumJerkTrajectoryGenerator::configureSizeAndPorts(BlockInformation* blockInfo) { - bool outputFirstDerivative = blockInfo->getScalarParameterAtIndex(PARAM_IDX_3).booleanData(); - bool outputSecondDerivative = blockInfo->getScalarParameterAtIndex(PARAM_IDX_4).booleanData(); - bool explicitInitialValue = blockInfo->getScalarParameterAtIndex(PARAM_IDX_5).booleanData(); - bool externalSettlingTime = blockInfo->getScalarParameterAtIndex(PARAM_IDX_6).booleanData(); + // PARAMETERS + // ========== + // + // 1) Sample time (double) + // 2) Settling time (double) + // 3) Enable the output of 1st derivative (bool) + // 4) Enable the output of 2nd derivative (bool) + // 5) Enable the input with the initial conditions (bool) + // 6) Enable the input with the external settling time (bool) + // 7) Reset the trajectory generator when settling time changes (bool) + // + + bool outputFirstDerivative; + bool outputSecondDerivative; + bool explicitInitialValue; + bool externalSettlingTime; + bool ok = true; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, outputFirstDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, outputSecondDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, explicitInitialValue); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, externalSettlingTime); + + if (!ok) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } int numberOfInputPorts = 1; - if (explicitInitialValue) - numberOfInputPorts++; - if (externalSettlingTime) - numberOfInputPorts++; + numberOfInputPorts += static_cast(explicitInitialValue); + numberOfInputPorts += static_cast(externalSettlingTime); - // Specify I/O // INPUTS + // ====== + // + // 1) The reference signal (1xn) + // 2) The optional initial conditions + // 3) The optional settling time + // + if(!blockInfo->setNumberOfInputPorts(numberOfInputPorts)) { - if (error) error->message = "Failed to set input port number"; + Log::getSingleton().error("Failed to set input port number."); return false; } @@ -69,20 +97,26 @@ namespace wbt { portIndex++; } - if (externalSettlingTime) - { + if (externalSettlingTime) { blockInfo->setInputPortVectorSize(portIndex, 1); blockInfo->setInputPortType(portIndex, PortDataTypeDouble); portIndex++; } // OUTPUTS + // ======= + // + // 1) The calculated trajectory + // 2) The optional 1st derivative + // 3) The optional 2nd derivative + // + int numberOfOutputPorts = 1; - if (outputFirstDerivative) numberOfOutputPorts++; - if (outputSecondDerivative) numberOfOutputPorts++; + numberOfOutputPorts += static_cast(outputFirstDerivative); + numberOfOutputPorts += static_cast(outputSecondDerivative); - if (!blockInfo->setNumberOfOuputPorts(numberOfOutputPorts)) { - if (error) error->message = "Failed to set output port number"; + if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { + Log::getSingleton().error("Failed to set output port number."); return false; } @@ -94,32 +128,50 @@ namespace wbt { return true; } - bool MinimumJerkTrajectoryGenerator::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool MinimumJerkTrajectoryGenerator::initialize(BlockInformation* blockInfo) { - //Save parameters - bool outputFirstDerivative = blockInfo->getScalarParameterAtIndex(PARAM_IDX_3).booleanData(); - bool outputSecondDerivative = blockInfo->getScalarParameterAtIndex(PARAM_IDX_4).booleanData(); + // Get the additional parameters + bool outputFirstDerivative; + bool outputSecondDerivative; + bool ok = true; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, + outputFirstDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, + outputSecondDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, m_explicitInitialValue); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, m_externalSettlingTime); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_RESET_CHANGEST, + m_resetOnSettlingTimeChange); + + if (!ok) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } + + if (outputFirstDerivative) { + m_outputFirstDerivativeIndex = 1; + } - if (outputFirstDerivative) m_outputFirstDerivativeIndex = 1; if (outputSecondDerivative) { m_outputSecondDerivativeIndex = outputFirstDerivative ? 2 : 1; } - double sampleTime = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1).doubleData(); - double settlingTime = blockInfo->getScalarParameterAtIndex(PARAM_IDX_2).doubleData(); + double sampleTime; + double settlingTime; - m_explicitInitialValue = blockInfo->getScalarParameterAtIndex(PARAM_IDX_5).booleanData(); - m_externalSettlingTime = blockInfo->getScalarParameterAtIndex(PARAM_IDX_6).booleanData(); - m_resetOnSettlingTimeChange = blockInfo->getScalarParameterAtIndex(PARAM_IDX_7).booleanData(); + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SAMPLE_TIME, sampleTime); + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SETTLING_TIME, settlingTime); - unsigned size = blockInfo->getInputPortWidth(0); + unsigned signalSize = blockInfo->getInputPortWidth(0); - m_generator = new iCub::ctrl::minJerkTrajGen(size, sampleTime, settlingTime); + m_generator = new iCub::ctrl::minJerkTrajGen(signalSize, sampleTime, settlingTime); m_previousSettlingTime = settlingTime; - m_initialValues = new yarp::sig::Vector(size); - m_reference = new yarp::sig::Vector(size); + m_initialValues = new yarp::sig::Vector(signalSize); + m_reference = new yarp::sig::Vector(signalSize); + if (!m_generator || !m_initialValues || !m_reference) { - if (error) error->message = "Could not allocate memory for trajectory generator"; + Log::getSingleton().error("Could not allocate memory for trajectory generator."); return false; } @@ -127,24 +179,24 @@ namespace wbt { return true; } - bool MinimumJerkTrajectoryGenerator::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool MinimumJerkTrajectoryGenerator::terminate(BlockInformation* blockInfo) { if (m_generator) { delete m_generator; - m_generator = 0; + m_generator = nullptr; } if (m_initialValues) { delete m_initialValues; - m_initialValues = 0; + m_initialValues = nullptr; } if (m_reference) { delete m_reference; - m_reference = 0; + m_reference = nullptr; } return true; } - - bool MinimumJerkTrajectoryGenerator::output(BlockInformation *blockInfo, wbt::Error *error) + + bool MinimumJerkTrajectoryGenerator::output(BlockInformation* blockInfo) { if (!m_generator) return false; @@ -198,6 +250,7 @@ namespace wbt { Signal derivativeOutput = blockInfo->getOutputPortSignal(m_outputFirstDerivativeIndex); derivativeOutput.setBuffer(derivative.data(), blockInfo->getOutputPortWidth(m_outputFirstDerivativeIndex)); } + if (m_outputSecondDerivativeIndex != -1) { const yarp::sig::Vector &derivative = m_generator->getAcc(); Signal derivativeOutput = blockInfo->getOutputPortSignal(m_outputSecondDerivativeIndex); From c931213cffe5b515603b50151730494488a4a938 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:24:36 +0000 Subject: [PATCH 24/92] RealTimeSyncronizer refactored --- toolbox/include/RealTimeSynchronizer.h | 25 ++++++---- toolbox/src/RealTimeSynchronizer.cpp | 69 ++++++++++++++++---------- 2 files changed, 58 insertions(+), 36 deletions(-) diff --git a/toolbox/include/RealTimeSynchronizer.h b/toolbox/include/RealTimeSynchronizer.h index 3438d727f..5a2bc601d 100644 --- a/toolbox/include/RealTimeSynchronizer.h +++ b/toolbox/include/RealTimeSynchronizer.h @@ -7,24 +7,27 @@ namespace wbt { class RealTimeSynchronizer; } -class wbt::RealTimeSynchronizer : public wbt::Block { +class wbt::RealTimeSynchronizer : public wbt::Block +{ public: - static std::string ClassName; - + static const std::string ClassName; + RealTimeSynchronizer(); - virtual ~RealTimeSynchronizer(); - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + ~RealTimeSynchronizer() override = default; + + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; + private: double m_period; double m_initialTime; unsigned long m_counter; + + static const unsigned PARAM_PERIOD; // Period }; #endif /* end of include guard: WBT_REALTIMESYNCHRONIZER_H */ diff --git a/toolbox/src/RealTimeSynchronizer.cpp b/toolbox/src/RealTimeSynchronizer.cpp index 678350493..752674d44 100644 --- a/toolbox/src/RealTimeSynchronizer.cpp +++ b/toolbox/src/RealTimeSynchronizer.cpp @@ -1,69 +1,88 @@ #include "RealTimeSynchronizer.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include -#define PARAM_IDX_1 1 // Period - namespace wbt { - - std::string RealTimeSynchronizer::ClassName = "RealTimeSynchronizer"; + + const std::string RealTimeSynchronizer::ClassName = "RealTimeSynchronizer"; + + const unsigned RealTimeSynchronizer::PARAM_PERIOD = 1; // Period RealTimeSynchronizer::RealTimeSynchronizer() : m_period(0.01) , m_initialTime(0) - , m_counter(0) {} + , m_counter(0) + {} - RealTimeSynchronizer::~RealTimeSynchronizer() {} - unsigned RealTimeSynchronizer::numberOfParameters() { return 1; } - bool RealTimeSynchronizer::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool RealTimeSynchronizer::configureSizeAndPorts(BlockInformation* blockInfo) { + // INPUTS + // ====== + // + // No inputs + // + if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to set input port number to 0"; + Log::getSingleton().error("Failed to set input port number to 0."); return false; } - - if (!blockInfo->setNumberOfOuputPorts(0)) { - if (error) error->message = "Failed to set output port number"; + + // OUTPUTS + // ======= + // + // No outputs + // + + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to set output port number."); return false; } return true; } - bool RealTimeSynchronizer::initialize(BlockInformation *blockInfo, wbt::Error */*error*/) + bool RealTimeSynchronizer::initialize(BlockInformation* blockInfo) { - m_period = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1).doubleData(); + if (!blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period)) { + Log::getSingleton().error("Failed to get input parametes."); + return false; + } + + if (m_period < 0) { + Log::getSingleton().error("Period must be greater than 0."); + return false; + } + m_counter = 0; - return m_period > 0; + return true; } - - bool RealTimeSynchronizer::terminate(BlockInformation *blockInfo, wbt::Error */*error*/) + + bool RealTimeSynchronizer::terminate(BlockInformation* blockInfo) { return true; } - - bool RealTimeSynchronizer::output(BlockInformation *blockInfo, wbt::Error */*error*/) - { - using namespace yarp::os; + bool RealTimeSynchronizer::output(BlockInformation* blockInfo) + { if (m_counter == 0) { m_initialTime = yarp::os::Time::now(); } //read current time double currentTime = yarp::os::Time::now() - m_initialTime; - double desiredTime = m_counter * m_period; + double desiredTime = m_counter* m_period; double sleepPeriod = desiredTime - currentTime; //sleep for the remaining time - if (sleepPeriod > 0) + if (sleepPeriod > 0) { yarp::os::Time::delay(sleepPeriod); - + } + m_counter++; return true; From 0bc69bd31e400d7ce8801fb4bec39b025041f669 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 10 Nov 2017 14:39:46 +0000 Subject: [PATCH 25/92] SetLowLevelPID refactored --- toolbox/include/SetLowLevelPID.h | 70 +++--- toolbox/include/base/toolbox.h | 4 +- toolbox/src/SetLowLevelPID.cpp | 373 ++++++++++++++----------------- toolbox/src/base/factory.cpp | 7 +- 4 files changed, 199 insertions(+), 255 deletions(-) diff --git a/toolbox/include/SetLowLevelPID.h b/toolbox/include/SetLowLevelPID.h index e0d154a27..ff781a885 100644 --- a/toolbox/include/SetLowLevelPID.h +++ b/toolbox/include/SetLowLevelPID.h @@ -1,65 +1,49 @@ #ifndef WBT_SETLOWLEVELPID_H_ #define WBT_SETLOWLEVELPID_H_ -#include "WBIBlock.h" -#include -#include +#include "WBBlock.h" +#include +#include namespace wbt { class SetLowLevelPID; -} - -namespace wbi { - class wholeBodyInterface; - class iWholeBodyActuators; -} - -namespace yarpWbi { - class PIDList; + enum PidDataIndex { + PGAIN = 0, + IGAIN = 1, + DGAIN = 2 + }; + typedef std::tuple PidData; } namespace yarp { - namespace os { - class Value; + namespace dev { + class Pid; } } -typedef std::map PidMap; - -class wbt::SetLowLevelPID : public wbt::WBIBlock { +class wbt::SetLowLevelPID : public wbt::WBBlock +{ +private: + std::vector m_appliedPidValues; + std::vector m_defaultPidValues; + std::unordered_map m_pidJointsFromParameters; - bool m_firstRun; - PidMap m_pids; - int m_lastGainSetIndex; - wbi::ControlMode m_controlMode; + yarp::dev::PidControlTypeEnum m_controlType; - bool loadLowLevelGainsFromFile(std::string filename, - const yarpWbi::PIDList &originalList, - wbi::wholeBodyInterface& interface, - yarpWbi::PIDList &loadedPIDs); - - bool loadGainsFromValue(const yarp::os::Value &gains, - PidMap &pidMap, - wbi::wholeBodyInterface& interface); - - bool setCurrentGains(const PidMap &pidMap, - std::string key, - wbi::iWholeBodyActuators& actuators); + bool readWBTPidConfigObject(BlockInformation* blockInfo); public: - static std::string ClassName; - SetLowLevelPID(); + static const std::string ClassName; - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); + SetLowLevelPID() = default; + ~SetLowLevelPID() override = default; - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; - + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - - #endif /* end of include guard: WBT_SETLOWLEVELPID_H_ */ diff --git a/toolbox/include/base/toolbox.h b/toolbox/include/base/toolbox.h index a1ff7505f..71a034c28 100644 --- a/toolbox/include/base/toolbox.h +++ b/toolbox/include/base/toolbox.h @@ -16,13 +16,11 @@ #include "DotJNu.h" #include "GetLimits.h" #include "CentroidalMomentum.h" +#include "SetLowLevelPID.h" #ifdef WBT_USES_ICUB #include "MinimumJerkTrajectoryGenerator.h" #endif #ifdef WBT_USES_IPOPT #include "InverseKinematics.h" -#endif #include "RemoteInverseKinematics.h" -#ifdef WBT_USES_CODYCO_COMMONS -#include "SetLowLevelPID.h" #endif diff --git a/toolbox/src/SetLowLevelPID.cpp b/toolbox/src/SetLowLevelPID.cpp index b772cb742..9448b4eb0 100644 --- a/toolbox/src/SetLowLevelPID.cpp +++ b/toolbox/src/SetLowLevelPID.cpp @@ -1,275 +1,240 @@ #include "SetLowLevelPID.h" -#include "Error.h" -#include "WBInterface.h" +#include "Log.h" +#include "RobotInterface.h" #include "BlockInformation.h" -#include -#include -#include -#include -#include -#include +#include +#include namespace wbt { - static const std::string TorquePIDInitialKey = "__ORIGINAL_PIDs__"; - static const std::string TorquePIDDefaultKey = "__DEFAULT_PIDs__"; + const std::string SetLowLevelPID::ClassName = "SetLowLevelPID"; -#pragma mark - SetLowLevelPID class implementation - - std::string SetLowLevelPID::ClassName = "SetLowLevelPID"; + unsigned SetLowLevelPID::numberOfParameters() + { + return WBBlock::numberOfParameters() + + 1 // WBTPIDConfig object + + 1; // Control type + } - SetLowLevelPID::SetLowLevelPID() - : m_firstRun(true) - , m_lastGainSetIndex(-1) - , m_controlMode(wbi::CTRL_MODE_TORQUE) {} + bool SetLowLevelPID::configureSizeAndPorts(BlockInformation* blockInfo) + { + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + // INPUTS + // ====== + // + // No inputs + // - bool SetLowLevelPID::loadLowLevelGainsFromFile(std::string filename, - const yarpWbi::PIDList &originalList, - wbi::wholeBodyInterface& interface, - yarpWbi::PIDList &loadedPIDs) - { - //List of list. Each element has a key: joint name, and a list of pairs: kp, kd, ki and its respective value - using namespace yarp::os; - yarp::os::ResourceFinder resourceFinder = yarp::os::ResourceFinder::getResourceFinderSingleton(); - Property file; - std::string fileName = resourceFinder.findFileByName(filename); - if (fileName.empty()) return false; - file.fromConfigFile(fileName); - - Bottle externalList; - externalList.fromString(file.toString()); - - bool result = true; - wbi::IDList jointList = interface.getJointList(); - for (int i = 0; i < externalList.size(); ++i) { - if (!externalList.get(i).isList()) continue; - Bottle *jointConfig = externalList.get(i).asList(); - if (jointConfig->size() < 2 || !jointConfig->get(0).isString()) continue; - wbi::ID jointID(jointConfig->get(0).asString()); - int jointIndex = -1; - if (!jointList.idToIndex(jointID, jointIndex)) continue; - if (jointIndex < 0 || jointIndex >= jointList.size()) { - yWarning("Specified joint %s index is outside joint list size", jointID.toString().c_str()); - continue; - } + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } - loadedPIDs.pidList()[jointIndex] = originalList.pidList()[jointIndex]; - loadedPIDs.motorParametersList()[jointIndex] = originalList.motorParametersList()[jointIndex]; + // OUTPUTS + // ======= + // + // No outputs + // - result = result && yarpWbi::pidFromBottleDescription(*jointConfig, loadedPIDs.pidList()[jointIndex]); - if (m_controlMode == wbi::CTRL_MODE_TORQUE) { - result = result && yarpWbi::motorTorqueParametersFromBottleDescription(*jointConfig, loadedPIDs.motorParametersList()[jointIndex]); - } + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; } - return result; + + return true; } - bool SetLowLevelPID::loadGainsFromValue(const yarp::os::Value &gains, - PidMap &pidMap, - wbi::wholeBodyInterface& interface) + bool SetLowLevelPID::readWBTPidConfigObject(BlockInformation* blockInfo) { - pidMap.clear(); - - yarpWbi::yarpWholeBodyInterface *yarpInterface = dynamic_cast(&interface); - if (!yarpInterface) { + AnyStruct s; + if (!blockInfo->getStructAtIndex(WBBlock::numberOfParameters() + 1, s)) { + Log::getSingleton().error("Failed to retrieve the struct with parameters."); return false; } - //Load original gains from controlboards and save them to the original key. - yarpWbi::PIDList originalGains(interface.getDoFs()); - yarpWbi::yarpWholeBodyActuators *actuators = yarpInterface->wholeBodyActuator(); - if (!actuators) { + // Check the existence of all the fields + try { + s.at("P"); + s.at("I"); + s.at("D"); + s.at("jointList"); + } + catch (const std::out_of_range& e) { + Log::getSingleton().error("Cannot retrieve one or more parameter from parameter's struct."); return false; } - //TODO: should be made not limited to torque - actuators->getPIDGains(originalGains.pidList(), wbi::CTRL_MODE_TORQUE); - actuators->getMotorTorqueParameters(originalGains.motorParametersList()); - pidMap.insert(PidMap::value_type(TorquePIDInitialKey, originalGains)); - - //Now load additional gains - bool result = true; - if (gains.isString()) { - yarpWbi::PIDList pids(interface.getDoFs()); - result = loadLowLevelGainsFromFile(gains.asString(), originalGains, interface, pids); - pidMap.insert(PidMap::value_type(TorquePIDDefaultKey, pids)); - } else if (gains.isList()) { - using namespace yarp::os; - Bottle *list = gains.asList(); - - //list of files. gains will be saved as integer-values - for (int i = 0; i < list->size(); ++i) { - if (!list->get(i).isString()) continue; - std::string filename = list->get(i).asString(); - yarpWbi::PIDList pids(interface.getDoFs()); - result = loadLowLevelGainsFromFile(filename, originalGains, interface, pids); - - if (result) { - pidMap.insert(PidMap::value_type(yarpWbi::stringFromInt(i + 1), pids)); - } - } + + // Proportional gains + std::vector Pvector; + if (!s["P"]->asVectorDouble(Pvector)) { + Log::getSingleton().error("Cannot retrieve vector from P parameter."); + return false; } - return result; - } - //TODO: for performance it is probably better to change the map so that the index is an integer - //i.e. a non continuous vector - bool SetLowLevelPID::setCurrentGains(const PidMap &pidMap, - std::string key, - wbi::iWholeBodyActuators& actuators) - { - yarpWbi::yarpWholeBodyActuators *yarpActuators = static_cast(&actuators); - if (!yarpActuators) return false; + // Integral gains + std::vector Ivector; + if (!s["I"]->asVectorDouble(Ivector)) { + Log::getSingleton().error("Cannot retrieve vector from I parameter."); + return false; + } - PidMap::const_iterator found = pidMap.find(key); - //Treat one exception: pidMap with size == 2, the default can be set to either the string or the num 1 - if (found == pidMap.end() && key == TorquePIDDefaultKey && pidMap.size() == 2) { - found = pidMap.find("1"); + // Derivative gains + std::vector Dvector; + if (!s["D"]->asVectorDouble(Dvector)) { + Log::getSingleton().error("Cannot retrieve vector from D parameter."); + return false; } - if (found == pidMap.end()) return false; - bool result = yarpActuators->setPIDGains(found->second.pidList(), m_controlMode); //to be made generic (torque, position, etc) - if (m_controlMode == wbi::CTRL_MODE_TORQUE) { - result = result && yarpActuators->setMotorTorqueParameters(found->second.motorParametersList()); + // Considered joint names + AnyCell jointPidsCell; + if (!s["jointList"]->asAnyCell(jointPidsCell)) { + Log::getSingleton().error("Cannot retrieve string from jointList parameter."); + return false; } - return result; - } -#pragma mark - overloaded methods + // From AnyCell to vector + std::vector jointNamesFromParameters; + for (auto cell: jointPidsCell) { + std::string joint; + if (!cell->asString(joint)) { + Log::getSingleton().error("Failed to convert jointList from cell to strings."); + return false; + } + jointNamesFromParameters.push_back(joint); + } - unsigned SetLowLevelPID::numberOfParameters() - { - return WBIBlock::numberOfParameters() - + 1 // pid parameters file - + 1;// control method - } + assert(Pvector.size() == Ivector.size() == Dvector.size() == jointNamesFromParameters.size()); - bool SetLowLevelPID::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) - { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + // Store this data into a private member map + for (unsigned i = 0; i < jointNamesFromParameters.size(); ++i) { + // Check the processed joint is actually a controlledJoint + const auto& controlledJoints = getConfiguration().getControlledJoints(); + auto findElement = std::find(std::begin(controlledJoints), + std::end(controlledJoints), + jointNamesFromParameters[i]); + if (findElement != std::end(controlledJoints)) { + m_pidJointsFromParameters[jointNamesFromParameters[i]] = {Pvector[i], Ivector[i], Dvector[i]}; + } + else { + Log::getSingleton().warning("Attempted to set PID of joint " + jointNamesFromParameters[i] + + " non currently controlled. Skipping it."); + } - // Specify I/O - if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to configure the number of input ports"; - return false; } - // Output port: - if (!blockInfo->setNumberOfOuputPorts(0)) { - if (error) error->message = "Failed to configure the number of output ports"; - return false; + if (m_pidJointsFromParameters.size() != jointNamesFromParameters.size()) { + Log::getSingleton().warning("PID have been passed only for a subset of the controlled joints."); } return true; } - bool SetLowLevelPID::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool SetLowLevelPID::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIBlock::initialize(blockInfo, error)) return false; + if (!WBBlock::initialize(blockInfo)) return false; // Reading the control type std::string controlType; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 2, controlType)) { - if (error) error->message = "Could not read control type parameter"; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 2, controlType)) { + Log::getSingleton().error("Could not read control type parameter."); return false; } - m_controlMode = wbi::CTRL_MODE_UNKNOWN; if (controlType == "Position") { - m_controlMode = wbi::CTRL_MODE_POS; - } else if (controlType == "Torque") { - m_controlMode = wbi::CTRL_MODE_TORQUE; - } else { - if (error) error->message = "Control Mode not supported"; + m_controlType = yarp::dev::VOCAB_PIDTYPE_POSITION; + } + else if (controlType == "Torque") { + m_controlType = yarp::dev::VOCAB_PIDTYPE_TORQUE; + } + else { + Log::getSingleton().error("Control type not recognized."); return false; } + // Reading the WBTPIDConfig matlab class + if (!readWBTPidConfigObject(blockInfo)) { + Log::getSingleton().error("Failed to parse the WBTPIDConfig object."); + return 1; + } - // Reading the PID specification parameter - std::string pidParameter; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 1, pidParameter)) { - if (error) error->message = "Could not read PID file specification parameter"; + // Retain the RemoteControlBoardRemapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to retain the control board remapper."); return false; } - Value value; - value.fromString(pidParameter.c_str()); - m_pids.clear(); + const unsigned& dofs = getConfiguration().getNumberOfDoFs(); - yarpWbi::yarpWholeBodyInterface * const interface = dynamic_cast(WBInterface::sharedInstance().interface()); - if (!interface) { - if (error) error->message = "This block currently work only with YARP-WBI implementation"; + // Initialize the vector size to the number of dofs + m_defaultPidValues.resize(dofs); + + // Get the interface + std::weak_ptr iPidControl; + if (!getRobotInterface()->getInterface(iPidControl)) { + Log::getSingleton().error("Failed to get IPidControl interface."); return false; } - if (!loadGainsFromValue(value, m_pids, *interface)) { - m_pids.clear(); - if (error) error->message = "Error while loading PIDs configuration"; - yError("Error while loading PIDs configuration"); + + // Store the default gains + if (!iPidControl.lock()->getPids(m_controlType, m_defaultPidValues.data())) { + Log::getSingleton().error("Failed to get default data from IPidControl."); return false; - } else { - yInfo("Loaded PIDs configuration"); } - m_lastGainSetIndex = -1; - m_firstRun = true; - return true; - } + // Initialize the vector of the applied pid gains with the default gains + m_appliedPidValues = m_defaultPidValues; - bool SetLowLevelPID::terminate(BlockInformation *blockInfo, wbt::Error *error) - { - //static_cast as the dynamic has been done in the initialize - //and the pointer should not change - yarpWbi::yarpWholeBodyInterface * const interface = static_cast(WBInterface::sharedInstance().interface()); - - if (interface) { - yarpWbi::yarpWholeBodyActuators *actuators = interface->wholeBodyActuator(); - if (actuators && m_pids.size() > 1) { - setCurrentGains(m_pids, TorquePIDInitialKey, *actuators); + // Override the PID with the gains specified as block parameters + for (unsigned i = 0; i < dofs; ++i) { + const std::string jointName = getConfiguration().getControlledJoints()[i]; + // If the pid has been passed, set the new gains + if (m_pidJointsFromParameters.find(jointName) != m_pidJointsFromParameters.end()) { + PidData gains = m_pidJointsFromParameters[jointName]; + m_appliedPidValues[i].setKp(std::get(gains)); + m_appliedPidValues[i].setKi(std::get(gains)); + m_appliedPidValues[i].setKd(std::get(gains)); } } - m_pids.clear(); - m_lastGainSetIndex = -1; + // Apply the new pid gains + if (!iPidControl.lock()->setPids(m_controlType, m_appliedPidValues.data())) { + Log::getSingleton().error("Failed to set PID values."); + return false; + } - return WBIBlock::terminate(blockInfo, error); + return true; } - bool SetLowLevelPID::output(BlockInformation *blockInfo, wbt::Error *error) + bool SetLowLevelPID::terminate(BlockInformation* blockInfo) { - //static_cast as the dynamic has been done in the initialize - //and the pointer should not change - yarpWbi::yarpWholeBodyInterface * const interface = static_cast(WBInterface::sharedInstance().interface()); - if (interface) { - if (m_firstRun) { - m_firstRun = false; - - yarpWbi::yarpWholeBodyActuators *actuators = interface->wholeBodyActuator(); - if (!actuators) { - if (error) error->message = "Failed to retrieve the interface to the actuators"; - return false; - } - - //First case: only one element - if (m_lastGainSetIndex == -1 && m_pids.size() == 2) { - //just switch to the only existing set - setCurrentGains(m_pids, TorquePIDDefaultKey, *actuators); - m_lastGainSetIndex = 0; - } else { -// InputPtrsType u = ssGetInputPortSignalPtrs(S, 0); -// InputInt8PtrsType uPtrs = (InputInt8PtrsType)u; -// if (*uPtrs[0] != lastGainIndex) { -// wbitoolbox::setCurrentGains(*pids, *uPtrs[0], *((yarpWbi::yarpWholeBodyInterface*)robot->wbInterface)); -// info[0] = *uPtrs[0]; -// } - } + bool ok = true; - } - return true; + // Get the IPidControl interface + std::weak_ptr iPidControl; + ok = ok & getRobotInterface()->getInterface(iPidControl); + if (!ok) { + Log::getSingleton().error("Failed to get IPidControl interface."); + } + + // Reset default pid gains + ok = ok & iPidControl.lock()->setPids(m_controlType, m_defaultPidValues.data()); + if (!ok) { + Log::getSingleton().error("Failed to set default PID values."); } - return false; + + // Release the RemoteControlBoardRemapper + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + } + + return ok && WBBlock::terminate(blockInfo); + } + + bool SetLowLevelPID::output(BlockInformation* blockInfo) + { + return true; } } diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index 69a962e08..dcbe75d60 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -34,6 +34,8 @@ wbt::Block* wbt::Block::instantiateBlockWithClassName(std::string blockClassName block = new wbt::GetLimits(); } else if (blockClassName == wbt::CentroidalMomentum::ClassName) { block = new wbt::CentroidalMomentum(); + } else if (blockClassName == wbt::SetLowLevelPID::ClassName) { + block = new wbt::SetLowLevelPID(); } #ifdef WBT_USES_ICUB else if (blockClassName == wbt::MinimumJerkTrajectoryGenerator::ClassName) { @@ -48,11 +50,6 @@ wbt::Block* wbt::Block::instantiateBlockWithClassName(std::string blockClassName else if (blockClassName == wbt::RemoteInverseKinematics::ClassName) { block = new wbt::RemoteInverseKinematics(); } -#ifdef WBT_USES_CODYCO_COMMONS - else if (blockClassName == wbt::SetLowLevelPID::ClassName) { - block = new wbt::SetLowLevelPID(); - } -#endif return block; From 0eada49c511af56815b6593eeb3b2cab9254b990 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:37:51 +0000 Subject: [PATCH 26/92] SetReferences refactored --- toolbox/include/SetReferences.h | 32 ++-- toolbox/src/SetReferences.cpp | 328 +++++++++++++++++++------------- 2 files changed, 212 insertions(+), 148 deletions(-) diff --git a/toolbox/include/SetReferences.h b/toolbox/include/SetReferences.h index ca3e1465f..c7c4c2ed8 100644 --- a/toolbox/include/SetReferences.h +++ b/toolbox/include/SetReferences.h @@ -1,36 +1,32 @@ #ifndef WBT_SETREFERENCES_H #define WBT_SETREFERENCES_H -#include "WBIBlock.h" -#include +#include "WBBlock.h" #include namespace wbt { class SetReferences; } -class wbt::SetReferences : public wbt::WBIBlock { - - double *m_references; - wbi::ControlMode m_controlMode; - bool m_fullControl; - std::vector m_controlledJoints; +class wbt::SetReferences : public wbt::WBBlock +{ +private: + std::vector m_controlModes; bool m_resetControlMode; + static void rad2deg(std::vector& v); public: - static std::string ClassName; - SetReferences(); - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); + static const std::string ClassName; - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initializeInitialConditions(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); + SetReferences(); + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool initializeInitialConditions(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; - #endif /* end of include guard: WBT_SETREFERENCES_H */ diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 397bd6020..3858a55a5 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -1,206 +1,274 @@ #include "SetReferences.h" -#include "Error.h" -#include "WBInterface.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" -#include -#include +#include "RobotInterface.h" +#include -#include +#define _USE_MATH_DEFINES +#include namespace wbt { - std::string SetReferences::ClassName = "SetReferences"; + const std::string SetReferences::ClassName = "SetReferences"; SetReferences::SetReferences() - : m_references(0) - , m_controlMode(wbi::CTRL_MODE_UNKNOWN) - , m_fullControl(true) - , m_resetControlMode(true) {} + : m_resetControlMode(true) + {} + + void rad2deg(std::vector& v) + { + const double rad2deg = 180.0 / (2 * M_PI); + for (auto& element : v) { + element *= rad2deg; + } + } unsigned SetReferences::numberOfParameters() { - // 1 - Control Type - // 2 - Full/Sublist type - // 3 - (only if sublist) controlled joints - return WBIBlock::numberOfParameters() + 3; + return WBBlock::numberOfParameters() + 1; } - bool SetReferences::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool SetReferences::configureSizeAndPorts(BlockInformation* blockInfo) { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } + // Memory allocation / Saving data not allowed here - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // In Toolbox mask the options are the following: - // - 1 => full control - // - 2 => sublist control - m_fullControl = blockInfo->getScalarParameterAtIndex(WBIBlock::numberOfParameters() + 2).int32Data() == 1; + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - if (!m_fullControl) { - //sublist - std::string controlledList; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 3, controlledList)) { - if (error) error->message = "Could not read control type parameter"; - return false; - } - const yarp::os::Property * controlledListProperty = WBInterface::sharedInstance().currentConfiguration(); + // INPUTS + // ====== + // + // 1) Joint refereces (1xDoFs vector) + // - wbi::IDList idList; - WBInterface::wbdIDListFromConfigPropAndList(*controlledListProperty, - controlledList, idList); - dofs = idList.size(); - } - - // Specify I/O + // Number of inputs if (!blockInfo->setNumberOfInputPorts(1)) { - if (error) error->message = "Failed to configure the number of input ports"; + Log::getSingleton().error("Failed to configure the number of input ports."); return false; } + // Size and type bool success = blockInfo->setInputPortVectorSize(0, dofs); blockInfo->setInputPortType(0, PortDataTypeDouble); if (!success) { - if (error) error->message = "Failed to configure input ports"; + Log::getSingleton().error("Failed to configure input ports."); return false; } - // Output port: - if (!blockInfo->setNumberOfOuputPorts(0)) { - if (error) error->message = "Failed to configure the number of output ports"; + // OUTPUTS + // ======= + // + // No outputs + // + + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of output ports."); return false; } return true; } - bool SetReferences::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool SetReferences::initialize(BlockInformation* blockInfo) { - using namespace yarp::os; - if (!WBIBlock::initialize(blockInfo, error)) return false; + if (!WBBlock::initialize(blockInfo)) return false; // Reading the control type std::string controlType; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 1, controlType)) { - if (error) error->message = "Could not read control type parameter"; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, + controlType)) { + Log::getSingleton().error("Could not read control type parameter."); return false; } - m_controlMode = wbi::CTRL_MODE_UNKNOWN; + // Initialize the std::vectors + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_controlModes.assign(dofs, VOCAB_CM_UNKNOWN); + + // IControlMode.h if (controlType == "Position") { - m_controlMode = wbi::CTRL_MODE_POS; - } else if (controlType == "Position Direct") { - m_controlMode = wbi::CTRL_MODE_DIRECT_POSITION; - } else if (controlType == "Velocity") { - m_controlMode = wbi::CTRL_MODE_VEL; - } else if (controlType == "Torque") { - m_controlMode = wbi::CTRL_MODE_TORQUE; - } else if (controlType == "Open Loop") { - m_controlMode = wbi::CTRL_MODE_MOTOR_PWM; - } else { - if (error) error->message = "Control Mode not supported"; + m_controlModes.assign(dofs, VOCAB_CM_POSITION); + } + else if (controlType == "Position Direct") { + m_controlModes.assign(dofs, VOCAB_CM_POSITION_DIRECT); + } + else if (controlType == "Velocity") { + m_controlModes.assign(dofs, VOCAB_CM_VELOCITY); + } + else if (controlType == "Torque") { + m_controlModes.assign(dofs, VOCAB_CM_TORQUE); + } + else if (controlType == "PWM") { + m_controlModes.assign(dofs, VOCAB_CM_PWM); + } + else if (controlType == "Current") { + m_controlModes.assign(dofs, VOCAB_CM_CURRENT); + } + else { + Log::getSingleton().error("Control Mode not supported."); return false; } - //Read if full or sublist control - m_fullControl = blockInfo->getScalarParameterAtIndex(WBIBlock::numberOfParameters() + 2).booleanData(); - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - if (!m_fullControl) { - //sublist - std::string controlledList; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 3, controlledList)) { - if (error) error->message = "Could not read control type parameter"; - return false; - } - const yarp::os::Property * controlledListProperty = WBInterface::sharedInstance().currentConfiguration(); - - wbi::IDList idList; - bool result = WBInterface::wbdIDListFromConfigPropAndList(*controlledListProperty, - controlledList, idList); - wbi::IDList fullList = WBInterface::sharedInstance().interface()->getJointList(); - m_controlledJoints.clear(); - m_controlledJoints.reserve(idList.size()); - if (result) { - for (int i = 0; i < idList.size(); i++) { - int index; - if (fullList.idToIndex(idList.at(i), index)) - m_controlledJoints.push_back(index); - else - std::cerr << "Joint " << idList.at(i).toString() << " not found\n"; - } - } - dofs = idList.size(); + // Retain the ControlBoardRemapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + return false; } - m_references = new double[dofs]; m_resetControlMode = true; - return m_references; + return true; } - bool SetReferences::terminate(BlockInformation *blockInfo, wbt::Error *error) + bool SetReferences::terminate(BlockInformation* blockInfo) { - wbi::wholeBodyInterface * const interface = WBInterface::sharedInstance().interface(); - if (interface) { - if (m_fullControl) { - interface->setControlMode(wbi::CTRL_MODE_POS); - } else { - for (int i = 0; i < m_controlledJoints.size(); i++) { - interface->setControlMode(wbi::CTRL_MODE_POS, 0, m_controlledJoints[i]); - } - } + using namespace yarp::dev; + bool ok = true; + + // Get the interface + std::weak_ptr icmd2; + ok = ok & getRobotInterface()->getInterface(icmd2); + if (!ok) { + Log::getSingleton().error("Failed to get the IControlMode2 interface."); } - if (m_references) { - delete [] m_references; - m_references = 0; + + // Set all the controlledJoints VOCAB_CM_POSITION + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_controlModes.assign(dofs, VOCAB_CM_POSITION); + + ok = ok & icmd2.lock()->setControlModes(m_controlModes.data()); + if (!ok) { + Log::getSingleton().error("Failed to set control mode."); + } + + // Release the RemoteControlBoardRemapper + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); } - return WBIBlock::terminate(blockInfo, error); + + return ok && WBBlock::terminate(blockInfo); } - bool SetReferences::initializeInitialConditions(BlockInformation */*blockInfo*/, wbt::Error */*error*/) + bool SetReferences::initializeInitialConditions(BlockInformation* /*blockInfo*/) { - //Simply reset the variable m_resetControlMode - //It will be read at the first cycle of output + // Simply reset the variable m_resetControlMode. + // It will be read at the first cycle of output. m_resetControlMode = true; return true; } - bool SetReferences::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool SetReferences::output(BlockInformation* blockInfo) { - //get input - wbi::wholeBodyInterface * const interface = WBInterface::sharedInstance().interface(); - if (!interface) return false; - - Signal references = blockInfo->getInputPortSignal(0); - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - m_references[i] = references.get(i).doubleData(); - } + using namespace yarp::dev; + // Set the control mode at the first run if (m_resetControlMode) { m_resetControlMode = false; + // Get the interface + std::weak_ptr icmd2; + if (!getRobotInterface()->getInterface(icmd2)) { + Log::getSingleton().error("Failed to get the IControlMode2 interface."); + return false; + } + // Set the control mode to all the controlledJoints + if (!icmd2.lock()->setControlModes(m_controlModes.data())) { + Log::getSingleton().error("Failed to set control mode."); + return false; + } + } + + // Get the signal + Signal references = blockInfo->getInputPortSignal(0); + unsigned signalWidth = blockInfo->getInputPortWidth(0); + std::vector referencesVector = references.getStdVector(signalWidth); - //now switch control mode - if (m_fullControl) { - interface->setControlMode(m_controlMode, m_references); - } else { - for (int i = 0; i < m_controlledJoints.size(); i++) { - interface->setControlMode(m_controlMode, &m_references[i], m_controlledJoints[i]); + bool ok = false; + // TODO: here only the first element is checked + switch (m_controlModes.front()) { + case VOCAB_CM_UNKNOWN: + Log::getSingleton().error("Control mode has not been successfully set."); + return false; + break; + case VOCAB_CM_POSITION: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IPositionControl interface."); + return false; + } + // Convert from rad to deg + rad2deg(referencesVector); + // Set the references + ok = interface.lock()->positionMove(referencesVector.data()); + break; + } + case VOCAB_CM_POSITION_DIRECT: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IPositionDirect interface."); + return false; + } + // Convert from rad to deg + rad2deg(referencesVector); + // Set the references + ok = interface.lock()->setPositions(referencesVector.data()); + break; + } + case VOCAB_CM_VELOCITY: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IVelocityControl interface."); + return false; + } + // Convert from rad to deg + rad2deg(referencesVector); + // Set the references + ok = interface.lock()->velocityMove(referencesVector.data()); + break; + } + case VOCAB_CM_TORQUE: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get ITorqueControl interface."); + return false; } + ok = interface.lock()->setRefTorques(referencesVector.data()); + break; + } + case VOCAB_CM_PWM: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IPWMControl interface."); + return false; + } + ok = interface.lock()->setRefDutyCycles(referencesVector.data()); + break; + } + case VOCAB_CM_CURRENT: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get ICurrentControl interface."); + return false; + } + ok = interface.lock()->setRefCurrents(referencesVector.data()); + break; } - return true; } - if (m_fullControl) { - interface->setControlReference(m_references); - } else { - for (int i = 0; i < m_controlledJoints.size(); i++) { - interface->setControlReference(&m_references[i], m_controlledJoints[i]); - } + if (!ok) { + Log::getSingleton().error("Failed to set references."); + return false; } + return true; } } From 520266f1097cdadf4f25ad21c5755a2ed30e23e7 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:39:05 +0000 Subject: [PATCH 27/92] SimulatorSynchronizer refactored --- toolbox/include/SimulatorSynchronizer.h | 26 +++++---- toolbox/src/SimulatorSynchronizer.cpp | 78 +++++++++++++++---------- 2 files changed, 61 insertions(+), 43 deletions(-) diff --git a/toolbox/include/SimulatorSynchronizer.h b/toolbox/include/SimulatorSynchronizer.h index 863fc6067..aa5c3eced 100644 --- a/toolbox/include/SimulatorSynchronizer.h +++ b/toolbox/include/SimulatorSynchronizer.h @@ -7,27 +7,31 @@ namespace wbt { class SimulatorSynchronizer; } -class wbt::SimulatorSynchronizer : public wbt::Block { +class wbt::SimulatorSynchronizer : public wbt::Block +{ public: - static std::string ClassName; + static const std::string ClassName; SimulatorSynchronizer(); - virtual ~SimulatorSynchronizer(); + ~SimulatorSynchronizer() override = default; - virtual unsigned numberOfParameters(); - virtual std::vector additionalBlockOptions(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); + unsigned numberOfParameters() override; + std::vector additionalBlockOptions() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; private: - double m_period; bool m_firstRun; struct RPCData; - RPCData *m_rpcData; + RPCData* m_rpcData; + + static const unsigned PARAM_PERIOD; // Period + static const unsigned PARAM_GZCLK_PORT; // Gazebo clock port + static const unsigned PARAM_RPC_PORT; // RPC client port name }; #endif /* end of include guard: WBT_SIMULATORSYNCHRONIZER_H */ diff --git a/toolbox/src/SimulatorSynchronizer.cpp b/toolbox/src/SimulatorSynchronizer.cpp index 6ed88c3e4..741a48ad6 100644 --- a/toolbox/src/SimulatorSynchronizer.cpp +++ b/toolbox/src/SimulatorSynchronizer.cpp @@ -1,17 +1,12 @@ #include "SimulatorSynchronizer.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" +#include "thrift/ClockServer.h" #include #include -#include #include -#define PARAM_IDX_1 1 // Period -#define PARAM_IDX_2 2 // Gazebo clock port -#define PARAM_IDX_3 3 // RPC client port name - - namespace wbt { struct SimulatorSynchronizer::RPCData @@ -26,16 +21,19 @@ namespace wbt { yarp::os::Port clientPort; gazebo::ClockServer clockServer; }; - - std::string SimulatorSynchronizer::ClassName = "SimulatorSynchronizer"; + + const std::string SimulatorSynchronizer::ClassName = "SimulatorSynchronizer"; + + const unsigned SimulatorSynchronizer::PARAM_PERIOD = 1; + const unsigned SimulatorSynchronizer::PARAM_GZCLK_PORT = 2; + const unsigned SimulatorSynchronizer::PARAM_RPC_PORT = 3; SimulatorSynchronizer::SimulatorSynchronizer() : m_period(0.01) , m_firstRun(true) - , m_rpcData(0) {} + , m_rpcData(0) + {} - SimulatorSynchronizer::~SimulatorSynchronizer() {} - unsigned SimulatorSynchronizer::numberOfParameters() { return 3; } std::vector SimulatorSynchronizer::additionalBlockOptions() @@ -43,43 +41,57 @@ namespace wbt { return std::vector(1, wbt::BlockOptionPrioritizeOrder); } - bool SimulatorSynchronizer::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool SimulatorSynchronizer::configureSizeAndPorts(BlockInformation* blockInfo) { - // Specify I/O // INPUTS + // ====== + // + // No inputs + // + if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to set input port number to 0"; + Log::getSingleton().error("Failed to set input port number to 0."); return false; } - if (!blockInfo->setNumberOfOuputPorts(0)) { - if (error) error->message = "Failed to set output port number"; + // OUTPUT + // ====== + // + // No outputs + // + + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to set output port number."); return false; } return true; } - bool SimulatorSynchronizer::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool SimulatorSynchronizer::initialize(BlockInformation* blockInfo) { - m_period = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1).doubleData(); std::string serverPortName; std::string clientPortName; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_2, serverPortName) || !blockInfo->getStringParameterAtIndex(PARAM_IDX_3, clientPortName)) { - if (error) error->message = "Error reading RPC parameters"; + bool ok = true; + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period); + ok = ok & blockInfo->getStringParameterAtIndex(PARAM_GZCLK_PORT, serverPortName); + ok = ok & blockInfo->getStringParameterAtIndex(PARAM_RPC_PORT, clientPortName); + + if (!ok) { + Log::getSingleton().error("Error reading RPC parameters."); return false; } yarp::os::Network::init(); if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork()) { - if (error) error->message = "Error initializing Yarp network"; + Log::getSingleton().error("Error initializing Yarp network."); return false; } m_rpcData = new struct RPCData(); if (!m_rpcData) { - if (error) error->message = "Error creating RPC data structure"; + Log::getSingleton().error("Error creating RPC data structure."); return false; } @@ -90,32 +102,34 @@ namespace wbt { return true; } - - bool SimulatorSynchronizer::terminate(BlockInformation */*S*/, wbt::Error *error) + + bool SimulatorSynchronizer::terminate(BlockInformation* /*S*/) { if (m_rpcData) { if (m_rpcData->clientPort.isOpen()) { m_rpcData->clockServer.continueSimulation(); - if (!yarp::os::Network::disconnect(m_rpcData->configuration.clientPortName, m_rpcData->configuration.serverPortName)) { - if (error) error->message = "Error disconnecting from simulator clock server"; + if (!yarp::os::Network::disconnect(m_rpcData->configuration.clientPortName, + m_rpcData->configuration.serverPortName)) { + Log::getSingleton().error("Error disconnecting from simulator clock server."); } m_rpcData->clientPort.close(); } delete m_rpcData; - m_rpcData = 0; + m_rpcData = nullptr; } yarp::os::Network::fini(); return true; } - bool SimulatorSynchronizer::output(BlockInformation */*S*/, wbt::Error *error) + bool SimulatorSynchronizer::output(BlockInformation* /*S*/) { if (m_firstRun) { m_firstRun = false; - if (!m_rpcData->clientPort.open(m_rpcData->configuration.clientPortName) - || !yarp::os::Network::connect(m_rpcData->configuration.clientPortName, m_rpcData->configuration.serverPortName)) { - if (error) error->message = "Error connecting to simulator clock server"; + if (!m_rpcData->clientPort.open(m_rpcData->configuration.clientPortName) || + !yarp::os::Network::connect(m_rpcData->configuration.clientPortName, + m_rpcData->configuration.serverPortName)) { + Log::getSingleton().error("Error connecting to simulator clock server."); return false; } From d23242cbfa8c7c63aa357186984d48a3d7c71731 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:39:44 +0000 Subject: [PATCH 28/92] YarpClock refactored --- toolbox/include/YarpClock.h | 16 ++++++++-------- toolbox/src/YarpClock.cpp | 36 +++++++++++++++++++++++------------- 2 files changed, 31 insertions(+), 21 deletions(-) diff --git a/toolbox/include/YarpClock.h b/toolbox/include/YarpClock.h index 9d0e551e5..000229579 100644 --- a/toolbox/include/YarpClock.h +++ b/toolbox/include/YarpClock.h @@ -7,16 +7,16 @@ namespace wbt { class YarpClock; } -class wbt::YarpClock : public wbt::Block { +class wbt::YarpClock : public wbt::Block +{ public: - static std::string ClassName; - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); + static const std::string ClassName; + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_YARPCLOCK_H */ diff --git a/toolbox/src/YarpClock.cpp b/toolbox/src/YarpClock.cpp index f20ba9b5b..b504287df 100644 --- a/toolbox/src/YarpClock.cpp +++ b/toolbox/src/YarpClock.cpp @@ -1,6 +1,6 @@ #include "YarpClock.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" @@ -9,22 +9,31 @@ namespace wbt { - std::string YarpClock::ClassName = "YarpClock"; + const std::string YarpClock::ClassName = "YarpClock"; unsigned YarpClock::numberOfParameters() { return 0; } - bool YarpClock::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool YarpClock::configureSizeAndPorts(BlockInformation* blockInfo) { - // Specify I/O // INPUTS + // ====== + // + // No inputs + // + if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to set input port number to 0"; + Log::getSingleton().error("Failed to set input port number to 0."); return false; } - // OUTPUTS - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to set output port number"; + // OUTPUT + // ====== + // + // 1) The yarp time. In short, it streams yarp::os::Time::now(). + // + + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to set output port number."); return false; } @@ -34,24 +43,25 @@ namespace wbt { return true; } - bool YarpClock::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool YarpClock::initialize(BlockInformation* blockInfo) { yarp::os::Network::init(); - if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork(5.0)){ - if (error) error->message = "YARP server wasn't found active!! \n"; + if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork(5.0)) { + Log::getSingleton().error("YARP server wasn't found active!!"); return false; } return true; } - bool YarpClock::terminate(BlockInformation */*S*/, wbt::Error */*error*/) + + bool YarpClock::terminate(BlockInformation* /*S*/) { yarp::os::Network::fini(); return true; } - bool YarpClock::output(BlockInformation *blockInfo, wbt::Error */*error*/) + bool YarpClock::output(BlockInformation* blockInfo) { Signal signal = blockInfo->getOutputPortSignal(0); signal.set(0, yarp::os::Time::now()); From 525a62002670342302f73103d234d5e904551e3b Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:41:26 +0000 Subject: [PATCH 29/92] YarpRead refactored --- toolbox/include/YarpRead.h | 32 +++++---- toolbox/src/YarpRead.cpp | 133 ++++++++++++++++++++++++------------- 2 files changed, 108 insertions(+), 57 deletions(-) diff --git a/toolbox/include/YarpRead.h b/toolbox/include/YarpRead.h index 14edd2564..bc79bcb61 100644 --- a/toolbox/include/YarpRead.h +++ b/toolbox/include/YarpRead.h @@ -17,25 +17,33 @@ namespace yarp { } } -class wbt::YarpRead : public wbt::Block { +class wbt::YarpRead : public wbt::Block +{ public: - static std::string ClassName; - + static const std::string ClassName; + YarpRead(); - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; + private: bool m_autoconnect; bool m_blocking; bool m_shouldReadTimestamp; bool m_errorOnMissingPort; - - yarp::os::BufferedPort *m_port; + + yarp::os::BufferedPort* m_port; + + static const unsigned PARAM_IDX_PORTNAME; // port name + static const unsigned PARAM_IDX_PORTSIZE; // Size of the port you're reading + static const unsigned PARAM_IDX_WAITDATA; // boolean for blocking reading + static const unsigned PARAM_IDX_READ_TS; // boolean to stream timestamp + static const unsigned PARAM_IDX_AUTOCONNECT; // Autoconnect boolean + static const unsigned PARAM_IDX_ERR_NO_PORT; // Error on missing port if autoconnect is on boolean }; #endif /* end of include guard: WBT_YARPREAD_H */ diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 82fa279f4..5542b9a42 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -1,6 +1,6 @@ #include "YarpRead.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" @@ -12,55 +12,79 @@ #include #include -#define PARAM_IDX_1 1 // port name -#define PARAM_IDX_2 2 // Size of the port you're reading -#define PARAM_IDX_3 3 // boolean for blocking reading -#define PARAM_IDX_4 4 // boolean to stream timestamp -#define PARAM_IDX_5 5 // Autoconnect boolean -#define PARAM_IDX_6 6 // Error on missing port if autoconnect is on boolean - namespace wbt { - - std::string YarpRead::ClassName = "YarpRead"; + + const std::string YarpRead::ClassName = "YarpRead"; + + const unsigned YarpRead::PARAM_IDX_PORTNAME = 1; // port name + const unsigned YarpRead::PARAM_IDX_PORTSIZE = 2; // Size of the port you're reading + const unsigned YarpRead::PARAM_IDX_WAITDATA = 3; // boolean for blocking reading + const unsigned YarpRead::PARAM_IDX_READ_TS = 4; // boolean to stream timestamp + const unsigned YarpRead::PARAM_IDX_AUTOCONNECT = 5; // Autoconnect boolean + const unsigned YarpRead::PARAM_IDX_ERR_NO_PORT = 6; // Error on missing port if autoconnect is on boolean YarpRead::YarpRead() : m_autoconnect(false) , m_blocking(false) , m_shouldReadTimestamp(false) , m_errorOnMissingPort(true) - , m_port(0) {} + , m_port(0) + {} unsigned YarpRead::numberOfParameters() { return 6; } - bool YarpRead::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool YarpRead::configureSizeAndPorts(BlockInformation* blockInfo) { - // Specify I/O // INPUTS + // ====== + // + // No inputs + // + if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to set input port number to 0"; + Log::getSingleton().error("Failed to set input port number to 0."); return false; } - + // OUTPUTS - bool shouldReadTimestamp = blockInfo->getScalarParameterAtIndex(PARAM_IDX_4).booleanData(); - int signalSize = blockInfo->getScalarParameterAtIndex(PARAM_IDX_2).int32Data(); - bool autoconnect = blockInfo->getScalarParameterAtIndex(PARAM_IDX_5).booleanData(); + // ======= + // + // 1) Vector with the data read from the port (1 x signalSize) + // 2) Optional: Timestamp read from the port + // 3) Optional: If autoconnect is disabled, this output becomes 1 when data starts arriving + // (and hence it means that the user connected manually the port) + // + + bool shouldReadTimestamp; + bool autoconnect; + double signalSize; + + bool ok = false; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, shouldReadTimestamp); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, autoconnect); + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_PORTSIZE, signalSize); + + if (!ok) { + Log::getSingleton().error("Failed to read input parameters."); + return false; + } if (signalSize < 0) { - if (error) error->message = "Signal size must be non negative"; + Log::getSingleton().error("Signal size must be non negative."); return false; } int numberOfOutputPorts = 1; - if (shouldReadTimestamp) numberOfOutputPorts++; //timestamp is the second port - if (!autoconnect) numberOfOutputPorts++; //!autoconnect => additional port with 1/0 depending on the connection status + numberOfOutputPorts += static_cast(shouldReadTimestamp); //timestamp is the second port + numberOfOutputPorts += static_cast(!autoconnect); //!autoconnect => additional port with 1/0 depending on the connection status - if (!blockInfo->setNumberOfOuputPorts(numberOfOutputPorts)) { - if (error) error->message = "Failed to set output port number"; + if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { + Log::getSingleton().error("Failed to set output port number."); return false; } - blockInfo->setOutputPortVectorSize(0, signalSize); + blockInfo->setOutputPortVectorSize(0, static_cast(signalSize)); blockInfo->setOutputPortType(0, PortDataTypeDouble); int portIndex = 1; @@ -77,76 +101,92 @@ namespace wbt { return true; } - bool YarpRead::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool YarpRead::initialize(BlockInformation* blockInfo) { using namespace yarp::os; using namespace yarp::sig; Network::init(); - if (!Network::initialized() || !Network::checkNetwork(5.0)){ - if (error) error->message = "YARP server wasn't found active!! \n"; + if (!Network::initialized() || !Network::checkNetwork(5.0)) { + Log::getSingleton().error("YARP server wasn't found active!!"); return false; } - m_shouldReadTimestamp = blockInfo->getScalarParameterAtIndex(PARAM_IDX_4).booleanData(); - m_autoconnect = blockInfo->getScalarParameterAtIndex(PARAM_IDX_5).booleanData(); - m_blocking = blockInfo->getScalarParameterAtIndex(PARAM_IDX_3).booleanData(); - m_errorOnMissingPort = blockInfo->getScalarParameterAtIndex(PARAM_IDX_6).booleanData(); + bool ok = true; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, m_shouldReadTimestamp); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_WAITDATA, m_blocking); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, m_errorOnMissingPort); + + if (!ok) { + Log::getSingleton().error("Failed to read input parameters."); + return false; + } std::string portName; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_1, portName)) { - if (error) error->message = "Cannot retrieve string from port name parameter"; + if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_PORTNAME, portName)) { + Log::getSingleton().error("Cannot retrieve string from port name parameter."); return false; } std::string sourcePortName; std::string destinationPortName; + // Autoconnect: the block opens a temporary input port ..., and it connects to an existing + // port portName (which is streaming data). if (m_autoconnect) { sourcePortName = portName; destinationPortName = "..."; - } else { + } + // Manual connection: the block opens an input port portName, and waits a manual connection to an + // output port. + else { destinationPortName = portName; } m_port = new BufferedPort(); if (!m_port || !m_port->open(destinationPortName)) { - if (error) error->message = "Error while opening yarp port"; + Log::getSingleton().error("Error while opening yarp port."); return false; } if (m_autoconnect) { if (!Network::connect(sourcePortName, m_port->getName())) { - std::cerr << "Failed to connect " << sourcePortName << " to " << m_port->getName() << "\n"; + Log::getSingleton().warning("Failed to connect " + + sourcePortName + + " to " + + m_port->getName()); if (m_errorOnMissingPort) { - if (error) error->message = "ERROR connecting ports"; + Log::getSingleton().error("Failed connecting ports."); return false; } } } return true; } - bool YarpRead::terminate(BlockInformation */*S*/, wbt::Error */*error*/) + + bool YarpRead::terminate(BlockInformation* /*blockInfo*/) { if (m_port) { m_port->close(); delete m_port; - m_port = 0; + m_port = nullptr; } yarp::os::Network::fini(); return true; } - - bool YarpRead::output(BlockInformation *blockInfo, wbt::Error */*error*/) + + bool YarpRead::output(BlockInformation* blockInfo) { int timeStampPortIndex = 1; int connectionStatusPortIndex = 1; - yarp::sig::Vector *v = m_port->read(m_blocking); // Read from the port. Waits until data arrives. - if (v) - { + yarp::sig::Vector* v = m_port->read(m_blocking); // Read from the port. Waits until data arrives. + + if (v) { if (m_shouldReadTimestamp) { connectionStatusPortIndex++; yarp::os::Stamp timestamp; @@ -155,9 +195,11 @@ namespace wbt { Signal pY1 = blockInfo->getOutputPortSignal(timeStampPortIndex); pY1.set(0, timestamp.getCount()); pY1.set(1, timestamp.getTime()); - } + Signal signal = blockInfo->getOutputPortSignal(0); + + // Crop the buffer if it exceeds the OutputPortWidth. signal.setBuffer(v->data(), std::min(blockInfo->getOutputPortWidth(0), (unsigned)v->size())); if (!m_autoconnect) { @@ -170,6 +212,7 @@ namespace wbt { //we set the port to zero again } } + return true; } } From 3ff628603e27845fd832bb04af6d1ec379c7b90e Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:43:00 +0000 Subject: [PATCH 30/92] YarpWrite refactored --- toolbox/include/YarpWrite.h | 27 ++++++----- toolbox/src/YarpWrite.cpp | 93 +++++++++++++++++++++++++------------ 2 files changed, 79 insertions(+), 41 deletions(-) diff --git a/toolbox/include/YarpWrite.h b/toolbox/include/YarpWrite.h index b7ea198ce..807b774cd 100644 --- a/toolbox/include/YarpWrite.h +++ b/toolbox/include/YarpWrite.h @@ -17,24 +17,29 @@ namespace yarp { } } -class wbt::YarpWrite : public wbt::Block { +class wbt::YarpWrite : public wbt::Block +{ public: - static std::string ClassName; - + static const std::string ClassName; + YarpWrite(); - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - + + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; + private: bool m_autoconnect; bool m_errorOnMissingPort; std::string m_destinationPortName; - yarp::os::BufferedPort *m_port; + yarp::os::BufferedPort* m_port; + + static const unsigned PARAM_IDX_PORTNAME; // Port name + static const unsigned PARAM_IDX_AUTOCONNECT; // Autoconnect boolean + static const unsigned PARAM_IDX_ERR_NO_PORT; // Error on missing port if autoconnect is true }; #endif /* end of include guard: WBT_YARPWRITE_H */ diff --git a/toolbox/src/YarpWrite.cpp b/toolbox/src/YarpWrite.cpp index a6f920c04..f557eccbb 100644 --- a/toolbox/src/YarpWrite.cpp +++ b/toolbox/src/YarpWrite.cpp @@ -1,6 +1,6 @@ #include "YarpWrite.h" -#include "Error.h" +#include "Log.h" #include "BlockInformation.h" #include "Signal.h" @@ -9,39 +9,53 @@ #include #include -#define PARAM_IDX_1 1 // port name -#define PARAM_IDX_2 2 // Autoconnect boolean -#define PARAM_IDX_3 3 // Error on missing port if autoconnect is on boolean - namespace wbt { - - std::string YarpWrite::ClassName = "YarpWrite"; + + const std::string YarpWrite::ClassName = "YarpWrite"; + + const unsigned YarpWrite::PARAM_IDX_PORTNAME = 1; // Port name + const unsigned YarpWrite::PARAM_IDX_AUTOCONNECT = 2; // Autoconnect boolean + const unsigned YarpWrite::PARAM_IDX_ERR_NO_PORT = 3; // Error on missing port if autoconnect is true YarpWrite::YarpWrite() : m_autoconnect(false) , m_errorOnMissingPort(true) , m_destinationPortName("") - , m_port(0) {} - + , m_port(nullptr) + {} + unsigned YarpWrite::numberOfParameters() { return 3; } - bool YarpWrite::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) + bool YarpWrite::configureSizeAndPorts(BlockInformation* blockInfo) { + // INPUT + // ===== + // + // 1) The signal to stream to the specified yarp port + // + if (!blockInfo->setNumberOfInputPorts(1)) { - if (error) error->message = "Failed to set input port number to 0"; + Log::getSingleton().error("Failed to set input port number to 0."); return false; } blockInfo->setInputPortVectorSize(0, -1); blockInfo->setInputPortType(0, PortDataTypeDouble); - if (!blockInfo->setNumberOfOuputPorts(0)) { - if (error) error->message = "Failed to set output port number"; + // OUTPUT + // ====== + // + // No outputs + // + + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to set output port number."); return false; } + return true; } - bool YarpWrite::initialize(BlockInformation *blockInfo, wbt::Error *error) + bool YarpWrite::initialize(BlockInformation* blockInfo) { using namespace yarp::os; using namespace yarp::sig; @@ -49,70 +63,89 @@ namespace wbt { Network::init(); if (!Network::initialized() || !Network::checkNetwork(5.0)){ - if (error) error->message = "YARP server wasn't found active!! \n"; + Log::getSingleton().error("YARP server wasn't found active!!"); return false; } - m_autoconnect = blockInfo->getScalarParameterAtIndex(PARAM_IDX_2).booleanData(); - m_errorOnMissingPort = blockInfo->getScalarParameterAtIndex(PARAM_IDX_3).booleanData(); + bool ok = true; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, + m_errorOnMissingPort); + + if (!ok) { + Log::getSingleton().error("Failed to read input parameters."); + return false; + } std::string portParameter; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_1, portParameter)) { - if (error) error->message = "Error reading port name parameter"; + if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_PORTNAME, portParameter)) { + Log::getSingleton().error("Error reading port name parameter."); return false; } std::string sourcePortName; + // Autoconnect: the block opens a temporary output port ..., and it connects to an existing + // port portName (which will receive data). if (m_autoconnect) { sourcePortName = "..."; m_destinationPortName = portParameter; - } else { + } + // Manual connection: the block opens an output port portName, and waits a manual connection to an + // input port. + else { sourcePortName = portParameter; } m_port = new BufferedPort(); if (!m_port || !m_port->open(sourcePortName)) { - if (error) error->message = "Error while opening yarp port"; + Log::getSingleton().error("Error while opening yarp port."); return false; } if (m_autoconnect) { if (!Network::connect(m_port->getName(), m_destinationPortName)) { + Log::getSingleton().warning("Failed to connect " + + m_port->getName() + + " to " + + m_destinationPortName); if (m_errorOnMissingPort) { - if (error) error->message ="Failed to connect " + m_port->getName() + " to " + m_destinationPortName; + Log::getSingleton().error("Failed connecting ports."); return false; } } } - //prepare the first object allocation - yarp::sig::Vector &outputVector = m_port->prepare(); + // Initialize the size of the internal buffer handled by m_port + yarp::sig::Vector& outputVector = m_port->prepare(); outputVector.resize(blockInfo->getInputPortWidth(0)); return true; } - bool YarpWrite::terminate(BlockInformation */*S*/, wbt::Error */*error*/) + bool YarpWrite::terminate(BlockInformation* /*S*/) { if (m_port) { - if (m_autoconnect) + if (m_autoconnect) { yarp::os::Network::disconnect(m_port->getName(), m_destinationPortName); + } m_port->close(); delete m_port; - m_port = 0; + m_port = nullptr; } yarp::os::Network::fini(); return true; } - - bool YarpWrite::output(BlockInformation *blockInfo, wbt::Error */*error*/) + + bool YarpWrite::output(BlockInformation* blockInfo) { if (!m_port) return false; - yarp::sig::Vector &outputVector = m_port->prepare(); + yarp::sig::Vector& outputVector = m_port->prepare(); outputVector.resize(blockInfo->getInputPortWidth(0)); //this should be a no-op Signal signal = blockInfo->getInputPortSignal(0); + for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { outputVector[i] = signal.get(i).doubleData(); } From 0f36c3399635085221f34c6a7dbc0dd64a87aea4 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:47:46 +0000 Subject: [PATCH 31/92] GetEstimate refactored and renamed to GetMeasurement --- toolbox/CMakeLists.txt | 4 +- toolbox/include/GetEstimate.h | 31 ------ toolbox/include/GetMeasurement.h | 38 +++++++ toolbox/include/base/toolbox.h | 2 +- toolbox/src/GetEstimate.cpp | 106 ------------------ toolbox/src/GetMeasurement.cpp | 183 +++++++++++++++++++++++++++++++ toolbox/src/base/factory.cpp | 4 +- 7 files changed, 226 insertions(+), 142 deletions(-) delete mode 100644 toolbox/include/GetEstimate.h create mode 100644 toolbox/include/GetMeasurement.h delete mode 100644 toolbox/src/GetEstimate.cpp create mode 100644 toolbox/src/GetMeasurement.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index d9fcf56eb..730222497 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -200,8 +200,8 @@ configure_block(BLOCK_NAME "Set Low-Level PIDs" configure_block(BLOCK_NAME "Get Estimate" GROUP "State" LIST_PREFIX WBT - SOURCES src/GetEstimate.cpp - HEADERS include/GetEstimate.h) + SOURCES src/GetMeasurement.cpp + HEADERS include/GetMeasurement.h) configure_block(BLOCK_NAME "Get Limits" GROUP "State" diff --git a/toolbox/include/GetEstimate.h b/toolbox/include/GetEstimate.h deleted file mode 100644 index a376d1484..000000000 --- a/toolbox/include/GetEstimate.h +++ /dev/null @@ -1,31 +0,0 @@ -#ifndef WBT_GETESTIMATE_H -#define WBT_GETESTIMATE_H - -#include "WBIBlock.h" -#include - -namespace wbt { - class GetEstimate; -} - -class wbt::GetEstimate : public wbt::WBIBlock { - - double *m_estimate; - wbi::EstimateType m_estimateType; - -public: - static std::string ClassName; - GetEstimate(); - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - - -}; - - -#endif /* end of include guard: WBT_GETESTIMATE_H */ diff --git a/toolbox/include/GetMeasurement.h b/toolbox/include/GetMeasurement.h new file mode 100644 index 000000000..8673874f7 --- /dev/null +++ b/toolbox/include/GetMeasurement.h @@ -0,0 +1,38 @@ +#ifndef WBT_GETMEASUREMENT_H +#define WBT_GETMEASUREMENT_H + +#include "WBBlock.h" + +namespace wbt { + class GetMeasurement; + enum EstimateType { + ESTIMATE_JOINT_POS, + ESTIMATE_JOINT_VEL, + ESTIMATE_JOINT_ACC, + ESTIMATE_JOINT_TORQUE + }; +} + + +class wbt::GetMeasurement : public wbt::WBBlock +{ +private: + std::vector m_estimate; + wbt::EstimateType m_estimateType; + static void deg2rad(std::vector& v); + +public: + static const std::string ClassName; + + GetMeasurement() = default; + ~GetMeasurement() override = default; + + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; +}; + +#endif /* end of include guard: WBT_GETMEASUREMENT_H */ diff --git a/toolbox/include/base/toolbox.h b/toolbox/include/base/toolbox.h index 71a034c28..fe4ea5680 100644 --- a/toolbox/include/base/toolbox.h +++ b/toolbox/include/base/toolbox.h @@ -11,7 +11,7 @@ #include "RealTimeSynchronizer.h" #include "SimulatorSynchronizer.h" #include "Jacobian.h" -#include "GetEstimate.h" +#include "GetMeasurement.h" #include "InverseDynamics.h" #include "DotJNu.h" #include "GetLimits.h" diff --git a/toolbox/src/GetEstimate.cpp b/toolbox/src/GetEstimate.cpp deleted file mode 100644 index ec2ed17c9..000000000 --- a/toolbox/src/GetEstimate.cpp +++ /dev/null @@ -1,106 +0,0 @@ -#include "GetEstimate.h" - -#include "Error.h" -#include "WBInterface.h" -#include "BlockInformation.h" -#include "Signal.h" -#include -#include - -namespace wbt { - - std::string GetEstimate::ClassName = "GetEstimate"; - - GetEstimate::GetEstimate() - : m_estimate(0) - , m_estimateType(wbi::ESTIMATE_JOINT_POS) {} - - unsigned GetEstimate::numberOfParameters() - { - return WBIBlock::numberOfParameters() + 1; - } - - bool GetEstimate::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) - { - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - - if (!blockInfo->setNumberOfInputPorts(0)) { - if (error) error->message = "Failed to configure the number of input ports"; - return false; - } - - // Output port: - // - DoFs vector with the information asked - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; - return false; - } - - bool success = blockInfo->setOutputPortVectorSize(0, dofs); - blockInfo->setOutputPortType(0, PortDataTypeDouble); - if (!success) { - if (error) error->message = "Failed to configure output ports"; - return false; - } - - - return true; - } - - bool GetEstimate::initialize(BlockInformation *blockInfo, wbt::Error *error) - { - using namespace yarp::os; - if (!WBIBlock::initialize(blockInfo, error)) return false; - - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - m_estimate = new double[dofs]; - - // Reading the control type - std::string informationType; - if (!blockInfo->getStringParameterAtIndex(WBIBlock::numberOfParameters() + 1, informationType)) { - if (error) error->message = "Could not read estimate type parameter"; - return false; - } - - if (informationType == "Joints Position") { - m_estimateType = wbi::ESTIMATE_JOINT_POS; - } else if (informationType == "Joints Velocity") { - m_estimateType = wbi::ESTIMATE_JOINT_VEL; - } else if (informationType == "Joints Acceleration") { - m_estimateType = wbi::ESTIMATE_JOINT_ACC; - } else if (informationType == "Joints Torque") { - m_estimateType = wbi::ESTIMATE_JOINT_TORQUE; - } else { - if (error) error->message = "Estimate not supported"; - return false; - } - return m_estimate; - } - - bool GetEstimate::terminate(BlockInformation *blockInfo, wbt::Error *error) - { - if (m_estimate) { - delete [] m_estimate; - m_estimate = 0; - } - return WBIBlock::terminate(blockInfo, error); - } - - bool GetEstimate::output(BlockInformation *blockInfo, wbt::Error */*error*/) - { - //get input - wbi::wholeBodyInterface * const interface = WBInterface::sharedInstance().interface(); - if (interface) { - interface->getEstimates(m_estimateType, m_estimate); - Signal signal = blockInfo->getOutputPortSignal(0); - signal.setBuffer(m_estimate, blockInfo->getOutputPortWidth(0)); - - return true; - } - return false; - } -} diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp new file mode 100644 index 000000000..c0e0f01f6 --- /dev/null +++ b/toolbox/src/GetMeasurement.cpp @@ -0,0 +1,183 @@ +#include "GetMeasurement.h" + +#include "Log.h" +#include "BlockInformation.h" +#include "Signal.h" +#include "RobotInterface.h" +#include +#include + +#define _USE_MATH_DEFINES +#include + +namespace wbt { + + const std::string GetMeasurement::ClassName = "GetMeasurement"; + + void deg2rad(std::vector& v) + { + const double deg2rad = (2 * M_PI) / 180.0; + for (auto& element : v) { + element *= deg2rad; + } + } + + unsigned GetMeasurement::numberOfParameters() + { + return WBBlock::numberOfParameters() + 1; + } + + bool GetMeasurement::configureSizeAndPorts(BlockInformation* blockInfo) + { + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + // INPUTS + // ====== + // + // No inputs + // + + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } + + // OUTPUTS + // ======= + // + // 1) Vector with the information asked (1xDoFs) + // + + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + bool success = blockInfo->setOutputPortVectorSize(0, dofs); + blockInfo->setOutputPortType(0, PortDataTypeDouble); + if (!success) { + Log::getSingleton().error("Failed to configure output ports."); + return false; + } + + return true; + } + + bool GetMeasurement::initialize(BlockInformation* blockInfo) + { + if (!WBBlock::initialize(blockInfo)) return false; + + // Reading the control type + std::string informationType; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, informationType)) { + Log::getSingleton().error("Could not read estimate type parameter."); + return false; + } + + if (informationType == "Joints Position") { + m_estimateType = wbt::ESTIMATE_JOINT_POS; + } else if (informationType == "Joints Velocity") { + m_estimateType = wbt::ESTIMATE_JOINT_VEL; + } else if (informationType == "Joints Acceleration") { + m_estimateType = wbt::ESTIMATE_JOINT_ACC; + } else if (informationType == "Joints Torque") { + m_estimateType = wbt::ESTIMATE_JOINT_TORQUE; + } else { + Log::getSingleton().error("Estimate not supported."); + return false; + } + + // Initialize the size of the output vector + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_estimate.reserve(dofs); + + // Retain the ControlBoardRemapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + return false; + } + + return true; + } + + bool GetMeasurement::terminate(BlockInformation* blockInfo) + { + // Release the RemoteControlBoardRemapper + bool ok = true; + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + } + + return ok && WBBlock::terminate(blockInfo); + } + + bool GetMeasurement::output(BlockInformation* blockInfo) + { + bool ok; + switch (m_estimateType) { + case ESTIMATE_JOINT_POS: { + // Get the interface + std::weak_ptr iEncoders; + if (!getRobotInterface()->getInterface(iEncoders)) { + Log::getSingleton().error("Failed to get IPidControl interface."); + return false; + } + // Get the measurement + ok = iEncoders.lock()->getEncoders(m_estimate.data()); + deg2rad(m_estimate); + break; + } + case ESTIMATE_JOINT_VEL: { + // Get the interface + std::weak_ptr iEncoders; + if (!getRobotInterface()->getInterface(iEncoders)) { + Log::getSingleton().error("Failed to get IEncoders interface."); + return false; + } + // Get the measurement + ok = iEncoders.lock()->getEncoderSpeeds(m_estimate.data()); + deg2rad(m_estimate); + break; + } + case ESTIMATE_JOINT_ACC: { + // Get the interface + std::weak_ptr iEncoders; + if (!getRobotInterface()->getInterface(iEncoders)) { + Log::getSingleton().error("Failed to get IEncoders interface."); + return false; + } + // Get the measurement + ok = iEncoders.lock()->getEncoderAccelerations(m_estimate.data()); + deg2rad(m_estimate); + break; + } + case ESTIMATE_JOINT_TORQUE: { + // Get the interface + std::weak_ptr iTorqueControl; + if (!getRobotInterface()->getInterface(iTorqueControl)) { + Log::getSingleton().error("Failed to get ITorqueControl interface."); + return false; + } + // Get the measurement + ok = iTorqueControl.lock()->getTorques(m_estimate.data()); + break; + } + default: + Log::getSingleton().error("Estimate type not recognized."); + return false; + } + + if (!ok) { + Log::getSingleton().error("Failed to get estimate."); + return false; + } + + Signal signal = blockInfo->getOutputPortSignal(0); + signal.setBuffer(m_estimate.data(), blockInfo->getOutputPortWidth(0)); + + return true; + } +} diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index dcbe75d60..0320676bc 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -24,8 +24,8 @@ wbt::Block* wbt::Block::instantiateBlockWithClassName(std::string blockClassName block = new wbt::SimulatorSynchronizer(); } else if (blockClassName == wbt::Jacobian::ClassName) { block = new wbt::Jacobian(); - } else if (blockClassName == wbt::GetEstimate::ClassName) { - block = new wbt::GetEstimate(); + } else if (blockClassName == wbt::GetMeasurement::ClassName) { + block = new wbt::GetMeasurement(); } else if (blockClassName == wbt::InverseDynamics::ClassName) { block = new wbt::InverseDynamics(); } else if (blockClassName == wbt::DotJNu::ClassName) { From 028dbd603947979aded515f44cfa3bed1b41903c Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:55:03 +0000 Subject: [PATCH 32/92] YARPWBIConverter refactored and renamed to ModelPartitioner --- toolbox/CMakeLists.txt | 6 +- toolbox/include/ModelPartitioner.h | 33 ++++ toolbox/include/YARPWBIConverter.h | 29 ---- toolbox/include/base/toolbox.h | 2 +- toolbox/src/ModelPartitioner.cpp | 197 +++++++++++++++++++++ toolbox/src/YARPWBIConverter.cpp | 268 ----------------------------- toolbox/src/base/factory.cpp | 4 +- 7 files changed, 236 insertions(+), 303 deletions(-) create mode 100644 toolbox/include/ModelPartitioner.h delete mode 100644 toolbox/include/YARPWBIConverter.h create mode 100644 toolbox/src/ModelPartitioner.cpp delete mode 100644 toolbox/src/YARPWBIConverter.cpp diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 730222497..99625ae0d 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -131,11 +131,11 @@ configure_block(BLOCK_NAME "Real Time Synchronizer" SOURCES src/RealTimeSynchronizer.cpp HEADERS include/RealTimeSynchronizer.h) -configure_block(BLOCK_NAME "YARP - WBI Converter" +configure_block(BLOCK_NAME "Model Partitioner" GROUP "Utilities" LIST_PREFIX WBT - SOURCES src/YARPWBIConverter.cpp - HEADERS include/YARPWBIConverter.h) + SOURCES src/ModelPartitioner.cpp + HEADERS include/ModelPartitioner.h) configure_block(BLOCK_NAME "Yarp Clock" GROUP "Utilities" diff --git a/toolbox/include/ModelPartitioner.h b/toolbox/include/ModelPartitioner.h new file mode 100644 index 000000000..929da6c7e --- /dev/null +++ b/toolbox/include/ModelPartitioner.h @@ -0,0 +1,33 @@ +#ifndef WBT_MODELPARTITIONER_H +#define WBT_MODELPARTITIONER_H + +#include "WBBlock.h" +#include "RobotInterface.h" +#include +#include + +namespace wbt { + class ModelPartitioner; +} + +class wbt::ModelPartitioner : public wbt::WBBlock +{ +private: + bool m_yarp2WBI; + + std::shared_ptr m_jointsMapString; + +public: + static const std::string ClassName; + ModelPartitioner() = default; + ~ModelPartitioner() override = default; + + unsigned numberOfParameters() override; + + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(BlockInformation* blockInfo) override; + bool terminate(BlockInformation* blockInfo) override; + bool output(BlockInformation* blockInfo) override; +}; + +#endif /* end of include guard: WBT_MODELPARTITIONER_H */ diff --git a/toolbox/include/YARPWBIConverter.h b/toolbox/include/YARPWBIConverter.h deleted file mode 100644 index 37f334057..000000000 --- a/toolbox/include/YARPWBIConverter.h +++ /dev/null @@ -1,29 +0,0 @@ -#ifndef WBT_YARP2DOFS_H -#define WBT_YARP2DOFS_H - -#include "WBIModelBlock.h" - -namespace wbt { - class YARPWBIConverter; -} - -class wbt::YARPWBIConverter : public wbt::WBIModelBlock { - - struct YARPWBIConverterPimpl; - YARPWBIConverterPimpl *m_pimpl; - -public: - static std::string ClassName; - YARPWBIConverter(); - - virtual unsigned numberOfParameters(); - - virtual bool configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error); - virtual bool initialize(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation *blockInfo, wbt::Error *error); - virtual bool output(BlockInformation *blockInfo, wbt::Error *error); - -}; - - -#endif /* end of include guard: WBT_YARP2DOFS_H */ diff --git a/toolbox/include/base/toolbox.h b/toolbox/include/base/toolbox.h index fe4ea5680..cc0750e51 100644 --- a/toolbox/include/base/toolbox.h +++ b/toolbox/include/base/toolbox.h @@ -2,7 +2,7 @@ //General Yarp utilities #include "YarpRead.h" #include "YarpWrite.h" -#include "YARPWBIConverter.h" +#include "ModelPartitioner.h" #include "YarpClock.h" //WBI-related stuff #include "MassMatrix.h" diff --git a/toolbox/src/ModelPartitioner.cpp b/toolbox/src/ModelPartitioner.cpp new file mode 100644 index 000000000..bedee09c9 --- /dev/null +++ b/toolbox/src/ModelPartitioner.cpp @@ -0,0 +1,197 @@ +#include "ModelPartitioner.h" + +#include "BlockInformation.h" +#include "Configuration.h" +#include "RobotInterface.h" +#include "Signal.h" +#include "Log.h" + +namespace wbt { + + const std::string ModelPartitioner::ClassName = "ModelPartitioner"; + + unsigned ModelPartitioner::numberOfParameters() + { + return 1; + } + + bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) + { + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + // PARAMETERS + // ========== + // + // 1) Boolean specifying if yarp2WBI (true) or WBI2yarp (false) + // + + bool yarp2WBI; + if (!blockInfo->getBooleanParameterAtIndex(1, yarp2WBI)) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } + + // TODO: update to new logic + // INPUTS + // ====== + // + // yarp2WBI + // -------- + // + // 1) Map of joints / control boards (1 x nJoints) + // 2) Vector containing the full set of robot's joints (1 x nJoints) + // + // WBI2yarp + // -------- + // + // 1) Map of joints / control boards (1 x nJoints) + // 2) Torso Control Board Signals + // 3) Head Control Board Signals + // 4) Left Arm Control Board Signals + // 5) Right Arm Control Board Signals + // 6) Left Leg Control Board Signals + // 7) Right Leg Control Board Signals + // + + bool ok; + unsigned numberOfInputs; + unsigned controlBoardsNumber = getConfiguration().getControlBoardsNames().size(); + + if (yarp2WBI) { + numberOfInputs = 1; + ok = blockInfo->setNumberOfInputPorts(numberOfInputs); + blockInfo->setInputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); + } + else { + numberOfInputs = controlBoardsNumber; + ok = blockInfo->setNumberOfInputPorts(numberOfInputs); + // Set the size as dynamic + for (unsigned i = 0; i < numberOfInputs; ++i) { + blockInfo->setInputPortType(i, PortDataTypeDouble); + } + } + + if (!ok) { + Log::getSingleton().error("Failed to set input port number."); + return false; + } + + + // TODO: update + // OUTPUTS + // ======= + // + // yarp2WBI + // -------- + // + // 1) Torso Control Board Signals + // 2) Head Control Board Signals + // 3) Left Arm Control Board Signals + // 4) Right Arm Control Board Signals + // 5) Left Leg Control Board Signals + // 6) Right Leg Control Board Signals + // + // WBI2yarp + // -------- + // + // 1) Vector containing the full set of robot's joints (1 x nJoints) + // + + unsigned numberOfOutputs; + + if (yarp2WBI) { + numberOfOutputs = controlBoardsNumber; + ok = blockInfo->setNumberOfOutputPorts(numberOfOutputs); + // Set the size as dynamic + for (unsigned i = 0; i < numberOfOutputs; ++i) { + blockInfo->setOutputPortVectorSize(i, -1); + blockInfo->setOutputPortType(i, PortDataTypeDouble); + } + } + else { + numberOfOutputs = 1; + ok = blockInfo->setNumberOfOutputPorts(numberOfOutputs); + blockInfo->setOutputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); + blockInfo->setOutputPortType(0, PortDataTypeDouble); + } + + if (!ok) { + Log::getSingleton().error("Failed to set output port number."); + return false; + } + + return true; + } + + bool ModelPartitioner::initialize(BlockInformation* blockInfo) + { + if (!WBBlock::initialize(blockInfo)) return false; + + if (!blockInfo->getBooleanParameterAtIndex(1, m_yarp2WBI)) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } + + m_jointsMapString = getRobotInterface()->getJointsMapString(); + + if (!m_jointsMapString) { + return false; + } + + return true; + } + + bool ModelPartitioner::terminate(BlockInformation* blockInfo) + { + return WBBlock::terminate(blockInfo); + } + + bool ModelPartitioner::output(BlockInformation* blockInfo) + { + if (m_yarp2WBI) { + // Input + Signal jointListSignal = blockInfo->getInputPortSignal(0); + + // Outputs + Signal ithControlBoardSignal; + + for (unsigned ithJoint = 0; ithJoint < blockInfo->getInputPortWidth(0); ++ithJoint) { + // Get the ControlBoard number the ith joint belongs, and its index into the CB itself + std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; + const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); + cb_idx controlBoardOfJoint = mappedJointInfos.first; + jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; + + // Get the data to forward + Data value = jointListSignal.get(ithJoint); + + // Forward the value to the correct output / output index + ithControlBoardSignal = blockInfo->getOutputPortSignal(controlBoardOfJoint); + ithControlBoardSignal.set(yarpIndexOfJoint, value.doubleData()); + } + } + else { + // Inputs + Signal ithControlBoardSignal; + + // Output + Signal jointListSignal = blockInfo->getOutputPortSignal(0); + + for (unsigned ithJoint = 0; ithJoint < blockInfo->getOutputPortWidth(0); ++ithJoint) { + // Get the ControlBoard number the ith joint belongs, and its index into the CB itself + std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; + const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); + cb_idx controlBoardOfJoint = mappedJointInfos.first; + jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; + + // Get the data to forward + ithControlBoardSignal = blockInfo->getInputPortSignal(controlBoardOfJoint); + Data value = ithControlBoardSignal.get(ithJoint); + + // Forward the value to the correct output index + jointListSignal.set(yarpIndexOfJoint, value.doubleData()); + } + } + return true; + } +} diff --git a/toolbox/src/YARPWBIConverter.cpp b/toolbox/src/YARPWBIConverter.cpp deleted file mode 100644 index 0cca8ff77..000000000 --- a/toolbox/src/YARPWBIConverter.cpp +++ /dev/null @@ -1,268 +0,0 @@ -#include "YARPWBIConverter.h" - -#include "BlockInformation.h" -#include "Signal.h" -#include "Error.h" -#include "WBInterface.h" -#include -#include -#include -#include - - -namespace wbt { - namespace hidden { - struct Joint; - - struct Part { - std::string partName; - std::vector joints; - }; - - struct Joint { - unsigned yarpIndex; - unsigned dofIndex; - std::string name; - }; - - /** - * Parse the configuration file to extract parts, joints and indices - * - * @param filepath full path and name to the configuration file - * @return the YARP parts representation - */ - static bool parseConfigurationFileForPartsConfiguration(const std::string& filepath, const wbi::IDList& wbiList, std::vector &parts); - - } -} - -namespace wbt { - - struct YARPWBIConverter::YARPWBIConverterPimpl { - std::vector parts; - bool yarpToWBI; - }; - - std::string YARPWBIConverter::ClassName = "YARPWBIConverter"; - - YARPWBIConverter::YARPWBIConverter() {} - - unsigned YARPWBIConverter::numberOfParameters() { return wbt::WBIModelBlock::numberOfParameters() + 1; } - bool YARPWBIConverter::configureSizeAndPorts(BlockInformation *blockInfo, wbt::Error *error) - { - //This is a check that list, dofs and files are ok - if (!WBIBlock::configureSizeAndPorts(blockInfo, error)) { - return false; - } - - //This specify the output port size - unsigned dofs = WBInterface::sharedInstance().numberOfDoFs(); - - using namespace wbt::hidden; - //Parse the yarpwbi file - //Need to retrieve both parameters, i.e. wbiFile and list - //The following is to avoid to configure the WBInterface during compilation - //(why I don't know :D ) - std::vector parts; - - //Workaround for the fact that ResourceFinder initializes the network by itself. See YARP#1014 - yarp::os::Network network; - yarp::os::ResourceFinder resourceFinder = yarp::os::ResourceFinder::getResourceFinderSingleton(); - - std::string configFilePath = resourceFinder.findFile(m_wbiConfigurationFileName); - - yarp::os::Property configurations; - //loading defaults from configuration file - if (!configurations.fromConfigFile(configFilePath)) { - if (error) error->message = "Failed to parse WBI configuration file"; - return false; - } - - wbi::IDList jointList; - //parse the file to get the joint list - if (!WBInterface::wbdIDListFromConfigPropAndList(configurations, m_wbiListName, jointList)) { - if (error) error->message = "Failed to parse Joint list"; - return false; - } - - if (!parseConfigurationFileForPartsConfiguration(configFilePath, jointList, parts)) { - return false; - } - - blockInfo->getScalarParameterAtIndex(wbt::WBIModelBlock::numberOfParameters() + 1).int8Data(); - - bool yarpToWBI = blockInfo->getScalarParameterAtIndex(wbt::WBIModelBlock::numberOfParameters() + 1).int8Data() == 1; - - // Specify I/O - bool success = true; - //Input - if (yarpToWBI) { - if (!blockInfo->setNumberOfInputPorts(parts.size())) { - if (error) error->message = "Failed to configure the number of input ports"; - return false; - } - - for (unsigned i = 0 ; i < parts.size(); ++i) { - success = success && blockInfo->setInputPortVectorSize(i, parts[i].joints.size()); - blockInfo->setInputPortType(i, PortDataTypeDouble); - } - - } else { - if (!blockInfo->setNumberOfInputPorts(1)) { - if (error) error->message = "Failed to configure the number of input ports"; - return false; - } - - success = success && blockInfo->setInputPortVectorSize(0, dofs); - blockInfo->setInputPortType(0, PortDataTypeDouble); - } - - if (!success) { - if (error) error->message = "Failed to configure input ports"; - return false; - } - - if (yarpToWBI) { - // Output port: - // - one port of size dofs - if (!blockInfo->setNumberOfOuputPorts(1)) { - if (error) error->message = "Failed to configure the number of output ports"; - return false; - } - - success = blockInfo->setOutputPortVectorSize(0, dofs); - blockInfo->setOutputPortType(0, PortDataTypeDouble); - } else { - if (!blockInfo->setNumberOfOuputPorts(parts.size())) { - if (error) error->message = "Failed to configure the number of input ports"; - return false; - } - - for (unsigned i = 0 ; i < parts.size(); ++i) { - success = success && blockInfo->setOutputPortVectorSize(i, parts[i].joints.size()); - blockInfo->setOutputPortType(i, PortDataTypeDouble); - } - } - - if (!success) { - if (error) error->message = "Failed to configure output ports"; - return false; - } - - return success; - } - - bool YARPWBIConverter::initialize(BlockInformation *blockInfo, wbt::Error *error) - { - using namespace wbt::hidden; - if (!WBIModelBlock::initialize(blockInfo, error)) return false; - - m_pimpl = new YARPWBIConverterPimpl(); - if (!m_pimpl) return false; - - m_pimpl->yarpToWBI = blockInfo->getScalarParameterAtIndex(wbt::WBIModelBlock::numberOfParameters() + 1).int8Data() == 1; - return parseConfigurationFileForPartsConfiguration(WBInterface::sharedInstance().wbiFilePath(), *WBInterface::sharedInstance().wbiList(), m_pimpl->parts); - } - - bool YARPWBIConverter::terminate(BlockInformation *blockInfo, wbt::Error *error) - { - delete m_pimpl; - m_pimpl = 0; - - return WBIModelBlock::terminate(blockInfo, error); - } - - bool YARPWBIConverter::output(BlockInformation *blockInfo, wbt::Error *error) - { - if (!m_pimpl) return false; - using namespace wbt::hidden; - - if (m_pimpl->yarpToWBI) { - //From YARP to WBI: - //Multiple inputs, single output - - Signal output = blockInfo->getOutputPortSignal(0); - - for (unsigned partIdx = 0; partIdx < m_pimpl->parts.size(); ++partIdx) { - Signal partPort = blockInfo->getInputPortSignal(partIdx); - - Part part = m_pimpl->parts[partIdx]; - for (unsigned jointIdx = 0; jointIdx < part.joints.size(); ++jointIdx) { - Joint joint = part.joints[jointIdx]; - output.set(joint.dofIndex, partPort.get(joint.yarpIndex).doubleData()); - } - } - - } else { - //From WBI to YARP - //Single Input port, multiple outputs - Signal inputPort = blockInfo->getInputPortSignal(0); - - for (unsigned partIdx = 0; partIdx < m_pimpl->parts.size(); ++partIdx) { - Signal output = blockInfo->getOutputPortSignal(partIdx); - - Part part = m_pimpl->parts[partIdx]; - for (unsigned jointIdx = 0; jointIdx < part.joints.size(); ++jointIdx) { - Joint joint = part.joints[jointIdx]; - output.set(joint.yarpIndex, inputPort.get(joint.dofIndex).doubleData()); - } - - } - } - - return true; - } - - namespace hidden { - - bool parseConfigurationFileForPartsConfiguration(const std::string& filepath, const wbi::IDList& wbiList, std::vector &parts) - { - parts.clear(); - yarp::os::Property configurationFile; - configurationFile.fromConfigFile(filepath); - //retrieve joints/yarp mapping - yarp::os::Bottle &mapping = configurationFile.findGroup("WBI_YARP_JOINTS"); - if (mapping.isNull() || mapping.size() <= 0) { - return false; - } - - //for every joint in the list - for (unsigned i = 0; i < wbiList.size(); ++i) { - const wbi::ID &id = wbiList.at(i); - //look in the configuration file for that key - yarp::os::Value &jointList = mapping.find(id.toString()); - - if (!jointList.isNull() && jointList.isList() && jointList.asList()->size() == 2) { - yarp::os::Bottle *list = jointList.asList(); - Joint joint; - std::string partName = list->get(0).asString(); - joint.yarpIndex = list->get(1).asInt(); - joint.dofIndex = i; - joint.name = id.toString(); - - std::vector::iterator found = parts.end(); - //look for the part in the vector.. a map would be nicer - for (std::vector::iterator part = parts.begin(); - part != parts.end(); ++part) { - if (part->partName == partName) { - found = part; - break; - } - } - - if (found != parts.end()) { - found->joints.push_back(joint); - } else { - Part newPart; - newPart.partName = partName; - newPart.joints.push_back(joint); - parts.push_back(newPart); - } - } - } - return true; - } - } -} - - diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index 0320676bc..e30b81379 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -8,8 +8,8 @@ wbt::Block* wbt::Block::instantiateBlockWithClassName(std::string blockClassName block = new wbt::YarpRead(); } else if (blockClassName == wbt::YarpWrite::ClassName) { block = new wbt::YarpWrite(); - } else if (blockClassName == wbt::YARPWBIConverter::ClassName) { - block = new wbt::YARPWBIConverter(); + } else if (blockClassName == wbt::ModelPartitioner::ClassName) { + block = new wbt::ModelPartitioner(); } else if (blockClassName == wbt::YarpClock::ClassName) { block = new wbt::YarpClock(); } else if (blockClassName == wbt::MassMatrix::ClassName) { From 1ad29cb87074262914631647fd41d1d42b90ac54 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:58:26 +0000 Subject: [PATCH 33/92] Removed support of CMake < 3.0 --- toolbox/CMakeLists.txt | 52 +++++------------------------------------- 1 file changed, 6 insertions(+), 46 deletions(-) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 99625ae0d..3b0487bdb 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -19,7 +19,6 @@ find_package(Matlab REQUIRED ENG_LIBRARY MAIN_PROGRAM) - if(NOT Matlab_FOUND) message(FATAL_ERROR "Matlab not found") endif() @@ -228,50 +227,11 @@ if (WBT_USES_ICUB) endif() #Adding files used for the generation of the dynamic library -if (CMAKE_VERSION GREATER 3.0.0) - matlab_add_mex( - NAME WBToolbox - SRC ${ALL_HEADERS} ${ALL_SOURCES} - LINK_TO ${LINKED_LIBRARIES} - ) -else() - #Adding files used for the generation of the dynamic library - add_library(WBToolbox SHARED ${ALL_HEADERS} ${ALL_SOURCES}) - - set(SFUNCTION_SUFFIX ${Matlab_MEX_EXTENSION}) - #Removing default dynamic library extensions (.dll for Windows, .so for UNIX) and prefixes (lib) otherwise automatically prepended to the mex file. - set_target_properties(WBToolbox PROPERTIES SUFFIX .${SFUNCTION_SUFFIX}) - set_target_properties(WBToolbox PROPERTIES PREFIX "") - - # This seems to be the most reliable method to date to know installed Matlab arch - STRING(REGEX MATCH ..$ MATLAB_ARCH Matlab_MEX_EXTENSION 64) - - #In the following specific flags will be set to ensure compliance with the default settings of Matlab's mex compiler - if(WIN32) - if(NOT "${MATLAB_ARCH}" STREQUAL "64") - message("Flags have been passed to compiler for Matlab 32bits on a Windows computer") - elseif() - message("Flags have been passed to compiler for Matlab 64bits on a Windows computer") - endif() - if(MSVC) - #Setting Compiler Flags - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /Z7 /nologo /W3 /WX- /O2 /Oy- /D_REENTRANT /D_CRT_SECURE_NO_DEPRECATE /D_SCL_SECURE_NO_DEPRECATE /D_SECURE_SCL=0 /DyWrite_EXPORTS /Gm- /EHs /Zp8 /GS /fp:precise /Zc:wchar_t /Zc:forScope /GR /Gd /TP /showIncludes") - #Setting Linker Flags - set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} /INCREMENTAL:NO /NOLOGO /MANIFEST /debug /MAP.mexw64.map /MACHINE:X64 /EXPORT:mexFunction") - if(NOT "${MATLAB_ARCH}" STREQUAL "64") - #Changing some flags according to system/MATLAB version (32, 64 bits) - set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} /MAP.mexw32.map /MACHINE:X32") - endif() - elseif(MSVC) - message("You are not compiling using Microsoft Visual Studio, ERRORS might occur") - endif(MSVC) - elseif(WIN32) - message("No particular flags have been passed to compiler for Matlab 64bits on a UNIX computer") - endif(WIN32) - - # Linking Libraries - target_link_libraries(WBToolbox ${LINKED_LIBRARIES} ${Matlab_LIBRARIES}) -endif() +matlab_add_mex( + NAME WBToolbox + SRC ${ALL_HEADERS} ${ALL_SOURCES} + LINK_TO ${LINKED_LIBRARIES} +) # Link with ClockServer library add_subdirectory(autogenerated/) @@ -279,7 +239,7 @@ target_link_libraries(WBToolbox PUBLIC ClockServer) # Remote Inverse Kinematics requires C++11 if (CMAKE_VERSION VERSION_LESS "3.1") - if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR + if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR CMAKE_CXX_COMPILER_ID STREQUAL "Clang") target_compile_options(WBToolbox PUBLIC "-std=c++11") endif() From 0c2ecfd249f7b00d58ee721eeaf51c6b7f835992 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 15:59:10 +0000 Subject: [PATCH 34/92] iDynTree is now a global dependency --- toolbox/CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 3b0487bdb..1ce390bc9 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -219,10 +219,11 @@ include_directories(SYSTEM ${Matlab_INCLUDE_DIRS} "${Matlab_ROOT_DIR}/simulink/i include_directories(SYSTEM ${YARP_INCLUDE_DIRS} ${yarpWholeBodyInterface_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR}) list(APPEND LINKED_LIBRARIES ${YARP_LIBRARIES} ${yarpWholeBodyInterface_LIBRARIES}) +list(APPEND LINKED_LIBRARIES ${iDynTree_LIBRARIES}) if (WBT_USES_ICUB) list(APPEND LINKED_LIBRARIES ctrlLib) if (${ICUB_USE_IPOPT}) - list(APPEND LINKED_LIBRARIES iKin ${iDynTree_LIBRARIES}) + list(APPEND LINKED_LIBRARIES iKin) endif() endif() From d73ea70195f07513a962c3d36003b81acfeb0a5a Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 16:00:21 +0000 Subject: [PATCH 35/92] Link the project against the MxAnyType library --- toolbox/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 1ce390bc9..93f3a71b7 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -234,6 +234,10 @@ matlab_add_mex( LINK_TO ${LINKED_LIBRARIES} ) +# Link with MxAnyType library +# TODO: this will become an external project sooner or later +target_link_libraries(WBToolbox PUBLIC MxAnyType) + # Link with ClockServer library add_subdirectory(autogenerated/) target_link_libraries(WBToolbox PUBLIC ClockServer) From d1bc77597006ee70acdb04f58be57cd31e500985 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 16:04:49 +0000 Subject: [PATCH 36/92] New PID and WBTPIDConfig matlab classes These classes are used to store PID gains for the SetLowLevelPID block --- +WBToolbox/PID.m | 50 +++++++++++++++++++++++++++++++ +WBToolbox/WBTPIDConfig.m | 63 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 113 insertions(+) create mode 100644 +WBToolbox/PID.m create mode 100644 +WBToolbox/WBTPIDConfig.m diff --git a/+WBToolbox/PID.m b/+WBToolbox/PID.m new file mode 100644 index 000000000..33badfea0 --- /dev/null +++ b/+WBToolbox/PID.m @@ -0,0 +1,50 @@ +classdef PID < handle + %PID Class to store pid parameters for a single joint. + % PID('jointName') creates an object for the joint 'jointName' with + % all pid gains set to 0. + % + % PID('jointName', P, I, D) creates an object for the joint 'jointName' + % initializing the gains respectively to P, I, D. + % + % PID Properties: + % P - Proportional gain + % I - Integral gain + % D - Derivative gain + % joint - Reference joint + % + % See also: WBTOOLBOX.WBTPIDCONFIG + + properties + P (1,1) double = 0 + I (1,1) double = 0 + D (1,1) double = 0 + joint (1,:) char + end + + methods + % function obj = PID(jointName) + % obj.joint = jointName; + % end + + function obj = PID(jointName, P, I, D) + if (nargin == 4) + obj.joint = jointName; + obj.P = P; + obj.I = I; + obj.D = D; + elseif (nargin == 1) + obj.joint = jointName; + else + error(... + [... + 'Wrong number of arguments: ', ... + 'You can either specify 1 argument (joint) ', ... + 'or 4 arguments (joint, P, I, D).',... + ]... + ); + end + end + + end +end + diff --git a/+WBToolbox/WBTPIDConfig.m b/+WBToolbox/WBTPIDConfig.m new file mode 100644 index 000000000..9d23b523f --- /dev/null +++ b/+WBToolbox/WBTPIDConfig.m @@ -0,0 +1,63 @@ +classdef WBTPIDConfig < handle + % WBTPIDCONFIG Class to store a set of PID config for many joints. + % WBTPIDCONFIG(WBToolbox.PID('jointName', P, I, D)) adds a new PID + % for joint 'jointName'. + % + % WBTPIDCONFIG Properties: + % P - Proportional gains + % I - Integral gains + % D - Derivative gains + % jointList - List of joints + % + % WBTPIDCONFIG Methods: + % addPID - Add a new joint PID + % removePID - Remove a stored joint PID + % + % See also: WBTOOLBOX.PID + + % Read-Only properties + properties (SetAccess = private) + P (1,:) double + I (1,:) double + D (1,:) double + jointList (1,:) cell + end + + methods + function addPID(obj, pid) + % Add + if ~isa(pid,'WBToolbox.PID') + error('The argument must be a WBToolbox.PID object.') + end + + matches = find(strcmp(obj.jointList, pid.joint), 1); + if ~isempty(matches) + error('The PID''s joint has been already processed.') + end + + obj.jointList{1, end+1} = pid.joint; + obj.P(1, end+1) = pid.P; + obj.I(1, end+1) = pid.I; + obj.D(1, end+1) = pid.D; + end + + function removePID(obj, jointName) + if ~ischar(jointName) + error('The argument must be a char containing the joint name.') + end + + idx = find(strcmp(obj.jointList, jointName), 1); + + if isempty(idx) + error('The specified joint has no configuration stored') + end + + obj.jointList(:,idx) = []; + obj.P(:,idx) = []; + obj.I(:,idx) = []; + obj.D(:,idx) = []; + end + end + +end + From 82b760ba3a00fa12de55047d1b25e6ba514a23fb Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 8 Nov 2017 16:20:42 +0000 Subject: [PATCH 37/92] Matlab functions used by Blocks which inherit from WBBlock class - BlockInitialization: Find the Config block hierarchically closer to the caller block - Mask2WBToolboxConfig: Read the mask of a config block and generates from it a WBToolboxConfig object, validating also its data - WBToolboxConfig2Mask: Read a WBToolboxConfig object and populates the mask of a Config block --- +WBToolbox/BlockInitialization.m | 61 +++++++++++++++++++++ +WBToolbox/Mask2WBToolboxConfig.m | 39 ++++++++++++++ +WBToolbox/WBToolboxConfig2Mask.m | 90 +++++++++++++++++++++++++++++++ 3 files changed, 190 insertions(+) create mode 100644 +WBToolbox/BlockInitialization.m create mode 100644 +WBToolbox/Mask2WBToolboxConfig.m create mode 100644 +WBToolbox/WBToolboxConfig2Mask.m diff --git a/+WBToolbox/BlockInitialization.m b/+WBToolbox/BlockInitialization.m new file mode 100644 index 000000000..5783432e0 --- /dev/null +++ b/+WBToolbox/BlockInitialization.m @@ -0,0 +1,61 @@ +function [configBlock, WBTConfig] = BlockInitialization(currentBlock, currentSystem) +%BLOCKINITIALIZATION Initialize blocks that read a Config block +% This function is used to initialize the mask of block that need to +% gather the WBToolbox configuration from a Config block. + +try + % Get the name of this block from the model's root + %blockAbsoluteName = gcb; + + % Get the top level name + %blockNameSplit = strsplit(blockAbsoluteName,'/'); + blockNameSplit = strsplit(currentBlock,'/'); + topLevel = blockNameSplit{1}; + + % Get all the blocks from the top level of the system + blocks_system = find_system(topLevel,'LookUnderMasks','on'); + + % Get the name of the block's subsystem + %[blockScopeName,~] = fileparts(blockAbsoluteName); + %blockScopeName = gcs; + blockScopeName = currentSystem; +catch + error('[%s::Initialization] Failed to process model''s tree',char(blockAbsoluteName)) +end + +% Look a config block from the block's scope going up in the tree +analyzedScope = blockScopeName; +configBlock = char; +while ~isempty(analyzedScope) + rule = strcat(strrep(analyzedScope,'/','\/'),'\/\w+\/ImConfig'); + idx = cellfun(@(x) ~isequal(regexp(x,rule),[]), blocks_system); + if (sum(idx) > 1) + error('[%s::Initialization] Found more than one configuration',char(blockAbsoluteName)); + elseif (sum(idx) == 1) + configBlock = blocks_system{idx}; + configBlock = fileparts(configBlock); + break; + end + analyzedScope = fileparts(analyzedScope); +end + +if isempty(configBlock) + error('[%s::Initialization] No configuration found',char(blockAbsoluteName)); +end + +configSource = get_param(configBlock,'ConfigSource'); + +if strcmp(configSource,'Mask') + % Read the mask + WBTConfig = WBToolbox.Mask2WBToolboxConfig(configBlock); +elseif strcmp(configSource,'Workspace') + % Get the object name and populate the mask + configObjectName = get_param(configBlock,'ConfigObject'); + WBToolbox.WBToolboxConfig2Mask(configBlock, configObjectName); + % Read the mask + WBTConfig = WBToolbox.Mask2WBToolboxConfig(configBlock); +else + error('[%s::Initialization] Read ConfigSource from Config block not recognized',char(blockAbsoluteName)); +end + +end diff --git a/+WBToolbox/Mask2WBToolboxConfig.m b/+WBToolbox/Mask2WBToolboxConfig.m new file mode 100644 index 000000000..0396a46a3 --- /dev/null +++ b/+WBToolbox/Mask2WBToolboxConfig.m @@ -0,0 +1,39 @@ +function [ WBTConfig ] = Mask2WBToolboxConfig(configBlock) +%MASK2WBTOOLBOXCONFIG Summary of this function goes here +% Detailed explanation goes here + +defaultString = '''NonValid'''; + +if (... + strcmp(char(get_param(configBlock,'RobotName')),defaultString) && ... + strcmp(char(get_param(configBlock,'UrdfFile')),defaultString) && ... + strcmp(char(get_param(configBlock,'LocalName')),defaultString) && ... + strcmp(char(get_param(configBlock,'GravityVector')),defaultString) && ... + strcmp(char(get_param(configBlock,'ControlledJoints')),defaultString) && ... + strcmp(char(get_param(configBlock,'ControlBoardsNames')),defaultString) ... + ) + error('[Mask2WBToolboxConfig] The provided config is NonValid.'); +end + +WBTConfig = WBToolbox.WBToolboxConfig; + +WBTConfig.RobotName = stripApices(char(get_param(configBlock,'RobotName'))); +WBTConfig.UrdfFile = stripApices(char(get_param(configBlock,'UrdfFile'))); +WBTConfig.LocalName = stripApices(char(get_param(configBlock,'LocalName'))); + +ControlledJointsChar = stripApices(char(get_param(configBlock,'ControlledJoints'))); +WBTConfig.ControlledJoints = eval('base',ControlledJointsChar); + +ControlBoardsNamesChar = stripApices(char(get_param(configBlock,'ControlBoardsNames'))); +WBTConfig.ControlBoardsNames = eval('base',ControlBoardsNamesChar); + +GravityVectorChar = stripApices(char(get_param(configBlock,'GravityVector'))); +WBTConfig.GravityVector = eval('base',GravityVectorChar); + +end + +function str = stripApices(str) + if (strcmp(str(1),'''') && strcmp(str(end),'''')) + str = str(2:end-1); + end +end diff --git a/+WBToolbox/WBToolboxConfig2Mask.m b/+WBToolbox/WBToolboxConfig2Mask.m new file mode 100644 index 000000000..1e7e3b227 --- /dev/null +++ b/+WBToolbox/WBToolboxConfig2Mask.m @@ -0,0 +1,90 @@ +function WBToolboxConfig2Mask(configBlock, WBTConfigObjectName) +%WBTOOLBOXCONFIG2MASK Summary of this function goes here +% Detailed explanation goes here + +% Assign names to labels +item_ConfigSource = 1; +item_ConfigObject = 2; +item_RobotName = 3; +item_UrdfFile = 4; +item_ControlledJoints = 5; +item_ControlBoardsNames = 6; +item_LocalName = 7; +item_GravityVector = 8; + +% Get the mask of the Config Block +try + mask = Simulink.Mask.get(configBlock); +catch + error('[WBToolboxConfig2Mask] Impossible to gather Config Block: %s', configBlock); +end + + +% Remove apices if present +if (strcmp(WBTConfigObjectName(1),'''') && strcmp(WBTConfigObjectName(end),'''')) + WBTConfigObjectName = WBTConfigObjectName(2:end-1); +end + +% Try to get the object from the workspace +try + WBTConfigHandle = evalin('base', WBTConfigObjectName); % Get the handle + WBTConfigObject = copy(WBTConfigHandle); % Shallow copy the handle +catch + error('[WBToolboxConfig2Mask] Failed to get %s object from the workspace', WBTConfigObjectName); +end + +try + if (isa(WBTConfigObject,'WBToolbox.WBToolboxConfig') && WBTConfigObject.ValidConfiguration) + SetParamFromReadOnly(... + configBlock,'RobotName',... + strcat('''',WBTConfigObject.RobotName,''''),... + mask.Parameters(item_RobotName)); + SetParamFromReadOnly(... + configBlock,'UrdfFile',... + strcat('''',WBTConfigObject.UrdfFile,''''),mask.Parameters(item_UrdfFile)); + SetParamFromReadOnly(... + configBlock,'ControlledJoints',... + WBTConfigObject.serializeCellArray1D(WBTConfigObject.ControlledJoints),mask.Parameters(item_ControlledJoints)); + SetParamFromReadOnly(... + configBlock,'ControlBoardsNames',... + WBTConfigObject.serializeCellArray1D(WBTConfigObject.ControlBoardsNames),mask.Parameters(item_ControlBoardsNames)); + SetParamFromReadOnly(... + configBlock,'GravityVector',... + WBTConfigObject.serializeVector1D(WBTConfigObject.GravityVector),mask.Parameters(item_GravityVector)) + SetParamFromReadOnly(... + configBlock,'LocalName',... + strcat('''',WBTConfigObject.LocalName,''''),mask.Parameters(item_LocalName)); + else + error('[WBToolboxConfig2Mask] Failed to get the %s object', WBTConfigObjectName); + end +catch + SetParamFromReadOnly(... + configBlock,'RobotName',... + '''NonValid''',mask.Parameters(item_RobotName)); + SetParamFromReadOnly(... + configBlock,'UrdfFile',... + '''NonValid''',mask.Parameters(item_UrdfFile)); + SetParamFromReadOnly(... + configBlock,'ControlledJoints',... + '''NonValid''',mask.Parameters(item_ControlledJoints)); + SetParamFromReadOnly(... + configBlock,'ControlBoardsNames',... + '''NonValid''',mask.Parameters(item_ControlBoardsNames)); + SetParamFromReadOnly(... + configBlock,'LocalName',... + '''NonValid''',mask.Parameters(item_LocalName)); + SetParamFromReadOnly(... + configBlock,'GravityVector',... + '''NonValid''',mask.Parameters(item_GravityVector)); +end + +end + +function SetParamFromReadOnly(block, parameterName, parameterValue, maskParameter) +if ~strcmp(get_param(block,parameterName),parameterValue) + maskParameter.ReadOnly = 'off'; + maskParameter.Enabled = 'on'; + set_param(block,parameterName,parameterValue); + maskParameter.ReadOnly = 'on'; +end +end From 68dc0100644e8e7a03be0b617ba8762c5b247314 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Thu, 9 Nov 2017 10:59:31 +0000 Subject: [PATCH 38/92] New getStdVector() method in Signal This method returns a std::vector either if the signal is contiguous or non-contiguous. Considering that all the input signals are const and non-contiguous, this function assures makes the situation clear encapsulating data in a std::vector. --- toolbox/include/base/Signal.h | 2 ++ toolbox/src/base/Signal.cpp | 9 +++++++++ 2 files changed, 11 insertions(+) diff --git a/toolbox/include/base/Signal.h b/toolbox/include/base/Signal.h index b46d70ecd..0fbe27f3c 100644 --- a/toolbox/include/base/Signal.h +++ b/toolbox/include/base/Signal.h @@ -2,6 +2,7 @@ #define WBT_SIGNAL_H #include "BlockInformation.h" +#include namespace wbt { class Signal; @@ -29,6 +30,7 @@ class wbt::Signal const Data get(unsigned index) const; void* getContiguousBuffer(); + std::vector getStdVector(unsigned length) const; //the missing are cast void set(unsigned index, double data); diff --git a/toolbox/src/base/Signal.cpp b/toolbox/src/base/Signal.cpp index 5d57938fc..9d5f6adbc 100644 --- a/toolbox/src/base/Signal.cpp +++ b/toolbox/src/base/Signal.cpp @@ -128,6 +128,15 @@ namespace wbt { return this->contiguousData; } + std::vector Signal::getStdVector(unsigned length) const + { + std::vector v(length); + for (unsigned i = 0; i < length; ++i) { + v[i] = get(i).doubleData(); + } + return v; + } + //the missing are cast void Signal::set(unsigned index, double data) { From 3bbad1f782e7dea6ed3b92acea6aa3dd23f8c802 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 10 Nov 2017 17:10:04 +0000 Subject: [PATCH 39/92] BlockInformation is now a const pointer, changed indentation in cpp --- toolbox/include/CentroidalMomentum.h | 6 +- toolbox/include/DotJNu.h | 6 +- toolbox/include/ForwardKinematics.h | 6 +- toolbox/include/GetLimits.h | 6 +- toolbox/include/GetMeasurement.h | 6 +- toolbox/include/InverseDynamics.h | 6 +- toolbox/include/Jacobian.h | 6 +- toolbox/include/MassMatrix.h | 6 +- .../include/MinimumJerkTrajectoryGenerator.h | 6 +- toolbox/include/ModelPartitioner.h | 6 +- toolbox/include/RealTimeSynchronizer.h | 6 +- toolbox/include/SetLowLevelPID.h | 8 +- toolbox/include/SetReferences.h | 8 +- toolbox/include/SimulatorSynchronizer.h | 6 +- toolbox/include/YarpClock.h | 6 +- toolbox/include/YarpRead.h | 6 +- toolbox/include/YarpWrite.h | 6 +- toolbox/include/base/Block.h | 14 +- toolbox/include/base/BlockInformation.h | 23 +- .../include/base/SimulinkBlockInformation.h | 18 +- toolbox/include/base/WBBlock.h | 6 +- toolbox/src/CentroidalMomentum.cpp | 289 +++++---- toolbox/src/DotJNu.cpp | 341 ++++++----- toolbox/src/ForwardKinematics.cpp | 276 +++++---- toolbox/src/GetLimits.cpp | 297 +++++---- toolbox/src/GetMeasurement.cpp | 277 +++++---- toolbox/src/InverseDynamics.cpp | 376 ++++++------ toolbox/src/Jacobian.cpp | 329 +++++----- toolbox/src/MassMatrix.cpp | 274 +++++---- .../src/MinimumJerkTrajectoryGenerator.cpp | 418 +++++++------ toolbox/src/ModelPartitioner.cpp | 312 +++++----- toolbox/src/RealTimeSynchronizer.cpp | 123 ++-- toolbox/src/SetLowLevelPID.cpp | 373 ++++++------ toolbox/src/SetReferences.cpp | 425 +++++++------ toolbox/src/SimulatorSynchronizer.cpp | 213 ++++--- toolbox/src/YarpClock.cpp | 93 ++- toolbox/src/YarpRead.cpp | 329 +++++----- toolbox/src/YarpWrite.cpp | 241 ++++---- toolbox/src/base/Block.cpp | 20 +- toolbox/src/base/BlockInformation.cpp | 6 +- toolbox/src/base/Signal.cpp | 562 +++++++++--------- toolbox/src/base/SimulinkBlockInformation.cpp | 328 +++++----- toolbox/src/base/ToolboxSingleton.cpp | 166 +++--- toolbox/src/base/WBBlock.cpp | 6 +- toolbox/src/base/factory.cpp | 76 +-- 45 files changed, 3136 insertions(+), 3181 deletions(-) diff --git a/toolbox/include/CentroidalMomentum.h b/toolbox/include/CentroidalMomentum.h index d3abb34bb..754e4249b 100644 --- a/toolbox/include/CentroidalMomentum.h +++ b/toolbox/include/CentroidalMomentum.h @@ -28,9 +28,9 @@ class wbt::CentroidalMomentum : public wbt::WBBlock bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* WBT_CENTROIDALMOMENTUM_H */ diff --git a/toolbox/include/DotJNu.h b/toolbox/include/DotJNu.h index d844bb510..9c70fe864 100644 --- a/toolbox/include/DotJNu.h +++ b/toolbox/include/DotJNu.h @@ -32,9 +32,9 @@ class wbt::DotJNu : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* WBT_DOTJDOTQ_H */ diff --git a/toolbox/include/ForwardKinematics.h b/toolbox/include/ForwardKinematics.h index 147f2c7b4..4a683e761 100644 --- a/toolbox/include/ForwardKinematics.h +++ b/toolbox/include/ForwardKinematics.h @@ -25,9 +25,9 @@ class wbt::ForwardKinematics : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* WBT_FORWARDKINEMATICS_H */ diff --git a/toolbox/include/GetLimits.h b/toolbox/include/GetLimits.h index 81570ee24..fcabddeb0 100644 --- a/toolbox/include/GetLimits.h +++ b/toolbox/include/GetLimits.h @@ -33,9 +33,9 @@ class wbt::GetLimits : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* WBT_GETLIMITS_H */ diff --git a/toolbox/include/GetMeasurement.h b/toolbox/include/GetMeasurement.h index 8673874f7..101aed7af 100644 --- a/toolbox/include/GetMeasurement.h +++ b/toolbox/include/GetMeasurement.h @@ -30,9 +30,9 @@ class wbt::GetMeasurement : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_GETMEASUREMENT_H */ diff --git a/toolbox/include/InverseDynamics.h b/toolbox/include/InverseDynamics.h index 2b035663c..63c8e8a3e 100644 --- a/toolbox/include/InverseDynamics.h +++ b/toolbox/include/InverseDynamics.h @@ -37,9 +37,9 @@ class wbt::InverseDynamics : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; diff --git a/toolbox/include/Jacobian.h b/toolbox/include/Jacobian.h index b0726e900..5db8f6d95 100644 --- a/toolbox/include/Jacobian.h +++ b/toolbox/include/Jacobian.h @@ -36,9 +36,9 @@ class wbt::Jacobian : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* WBT_JACOBIAN_H */ diff --git a/toolbox/include/MassMatrix.h b/toolbox/include/MassMatrix.h index 6529d4504..4ebea06b8 100644 --- a/toolbox/include/MassMatrix.h +++ b/toolbox/include/MassMatrix.h @@ -27,9 +27,9 @@ class wbt::MassMatrix : public wbt::WBBlock bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* WBT_MASSMATRIX_H */ diff --git a/toolbox/include/MinimumJerkTrajectoryGenerator.h b/toolbox/include/MinimumJerkTrajectoryGenerator.h index 8bf0f29b7..5d175e7ab 100644 --- a/toolbox/include/MinimumJerkTrajectoryGenerator.h +++ b/toolbox/include/MinimumJerkTrajectoryGenerator.h @@ -28,9 +28,9 @@ class wbt::MinimumJerkTrajectoryGenerator : public wbt::Block { unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; private: diff --git a/toolbox/include/ModelPartitioner.h b/toolbox/include/ModelPartitioner.h index 929da6c7e..2a8b5c435 100644 --- a/toolbox/include/ModelPartitioner.h +++ b/toolbox/include/ModelPartitioner.h @@ -25,9 +25,9 @@ class wbt::ModelPartitioner : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_MODELPARTITIONER_H */ diff --git a/toolbox/include/RealTimeSynchronizer.h b/toolbox/include/RealTimeSynchronizer.h index 5a2bc601d..26a797589 100644 --- a/toolbox/include/RealTimeSynchronizer.h +++ b/toolbox/include/RealTimeSynchronizer.h @@ -17,9 +17,9 @@ class wbt::RealTimeSynchronizer : public wbt::Block unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; private: double m_period; diff --git a/toolbox/include/SetLowLevelPID.h b/toolbox/include/SetLowLevelPID.h index ff781a885..96b8384d6 100644 --- a/toolbox/include/SetLowLevelPID.h +++ b/toolbox/include/SetLowLevelPID.h @@ -30,7 +30,7 @@ class wbt::SetLowLevelPID : public wbt::WBBlock yarp::dev::PidControlTypeEnum m_controlType; - bool readWBTPidConfigObject(BlockInformation* blockInfo); + bool readWBTPidConfigObject(const BlockInformation* blockInfo); public: static const std::string ClassName; @@ -41,9 +41,9 @@ class wbt::SetLowLevelPID : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_SETLOWLEVELPID_H_ */ diff --git a/toolbox/include/SetReferences.h b/toolbox/include/SetReferences.h index c7c4c2ed8..d599a1410 100644 --- a/toolbox/include/SetReferences.h +++ b/toolbox/include/SetReferences.h @@ -23,10 +23,10 @@ class wbt::SetReferences : public wbt::WBBlock unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool initializeInitialConditions(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool initializeInitialConditions(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_SETREFERENCES_H */ diff --git a/toolbox/include/SimulatorSynchronizer.h b/toolbox/include/SimulatorSynchronizer.h index aa5c3eced..f307c8fc7 100644 --- a/toolbox/include/SimulatorSynchronizer.h +++ b/toolbox/include/SimulatorSynchronizer.h @@ -18,9 +18,9 @@ class wbt::SimulatorSynchronizer : public wbt::Block unsigned numberOfParameters() override; std::vector additionalBlockOptions() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; private: double m_period; diff --git a/toolbox/include/YarpClock.h b/toolbox/include/YarpClock.h index 000229579..c4857e8e0 100644 --- a/toolbox/include/YarpClock.h +++ b/toolbox/include/YarpClock.h @@ -14,9 +14,9 @@ class wbt::YarpClock : public wbt::Block unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_YARPCLOCK_H */ diff --git a/toolbox/include/YarpRead.h b/toolbox/include/YarpRead.h index bc79bcb61..6fed985ad 100644 --- a/toolbox/include/YarpRead.h +++ b/toolbox/include/YarpRead.h @@ -26,9 +26,9 @@ class wbt::YarpRead : public wbt::Block unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; private: bool m_autoconnect; diff --git a/toolbox/include/YarpWrite.h b/toolbox/include/YarpWrite.h index 807b774cd..4d9e8238b 100644 --- a/toolbox/include/YarpWrite.h +++ b/toolbox/include/YarpWrite.h @@ -26,9 +26,9 @@ class wbt::YarpWrite : public wbt::Block unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; - bool output(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; private: bool m_autoconnect; diff --git a/toolbox/include/base/Block.h b/toolbox/include/base/Block.h index a233859e6..65f8447b6 100644 --- a/toolbox/include/base/Block.h +++ b/toolbox/include/base/Block.h @@ -82,7 +82,7 @@ class wbt::Block * @param S the SimStruct structure * @return true for success, false otherwise */ - virtual bool updateDiscreteState(BlockInformation* blockInfo); + virtual bool updateDiscreteState(const BlockInformation* blockInfo); /** * Not called for now @@ -90,7 +90,7 @@ class wbt::Block * @param S the SimStruct structure * @return true for success, false otherwise */ - virtual bool stateDerivative(BlockInformation* blockInfo); + virtual bool stateDerivative(const BlockInformation* blockInfo); /** @@ -123,7 +123,7 @@ class wbt::Block * * @return true for success, false otherwise */ - virtual bool checkParameters(BlockInformation* blockInfo); + virtual bool checkParameters(const BlockInformation* blockInfo); /** * Initialize the object for the simulation @@ -134,7 +134,7 @@ class wbt::Block * * @return true for success, false otherwise */ - virtual bool initialize(BlockInformation* blockInfo) = 0; + virtual bool initialize(const BlockInformation* blockInfo) = 0; /** * Called to initialize the initial conditions @@ -146,7 +146,7 @@ class wbt::Block * * @return true for success, false otherwise */ - virtual bool initializeInitialConditions(BlockInformation* blockInfo); + virtual bool initializeInitialConditions(const BlockInformation* blockInfo); /** * Perform model cleanup. @@ -157,7 +157,7 @@ class wbt::Block * * @return true for success, false otherwise */ - virtual bool terminate(BlockInformation* blockInfo) = 0; + virtual bool terminate(const BlockInformation* blockInfo) = 0; @@ -170,7 +170,7 @@ class wbt::Block * * @return true for success, false otherwise */ - virtual bool output(BlockInformation* blockInfo) = 0; + virtual bool output(const BlockInformation* blockInfo) = 0; public: diff --git a/toolbox/include/base/BlockInformation.h b/toolbox/include/base/BlockInformation.h index a4ea9da0a..06e2c37c1 100644 --- a/toolbox/include/base/BlockInformation.h +++ b/toolbox/include/base/BlockInformation.h @@ -58,7 +58,8 @@ namespace wbt { class wbt::BlockInformation { public: - virtual ~BlockInformation(); + BlockInformation() = default; + virtual ~BlockInformation() = default; // Block Options methods // ===================== @@ -84,11 +85,13 @@ class wbt::BlockInformation { * * @return true if success, false otherwise */ - virtual bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) = 0; - virtual bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) = 0; - virtual bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) = 0; - virtual bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) = 0; - virtual bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) = 0; + virtual bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) const = 0; + virtual bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) const = 0; + virtual bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) const = 0; + // virtual bool getAnyTypeAtIndex(unsigned parameterIndex, AnyType* data) = 0; + // virtual bool getCellAtIndex(unsigned parameterIndex, AnyCell& map) = 0; + virtual bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const = 0; + virtual bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const = 0; // Port information methods // ======================== @@ -114,10 +117,10 @@ class wbt::BlockInformation { // Port data // ========= - virtual unsigned getInputPortWidth(unsigned portNumber) = 0; - virtual unsigned getOutputPortWidth(unsigned portNumber) = 0; - virtual wbt::Signal getInputPortSignal(unsigned portNumber) = 0; - virtual wbt::Signal getOutputPortSignal(unsigned portNumber) = 0; + virtual unsigned getInputPortWidth(unsigned portNumber) const = 0; + virtual unsigned getOutputPortWidth(unsigned portNumber) const = 0; + virtual wbt::Signal getInputPortSignal(unsigned portNumber) const = 0; + virtual wbt::Signal getOutputPortSignal(unsigned portNumber)const = 0; }; #endif /* end of include guard: WBT_BLOCKINFORMATION_H */ diff --git a/toolbox/include/base/SimulinkBlockInformation.h b/toolbox/include/base/SimulinkBlockInformation.h index 2334d32a4..0da7f51c5 100644 --- a/toolbox/include/base/SimulinkBlockInformation.h +++ b/toolbox/include/base/SimulinkBlockInformation.h @@ -22,11 +22,11 @@ class wbt::SimulinkBlockInformation : public wbt::BlockInformation bool optionFromKey(const std::string& key, double& option) const override; //Parameters methods - bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) override; - bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) override; - bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) override; - bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) override; - bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) override; + bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) const override; + bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) const override; + bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) const override; + bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const override; + bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const override; //Port information methods bool setNumberOfInputPorts(unsigned numberOfPorts) override; @@ -39,10 +39,10 @@ class wbt::SimulinkBlockInformation : public wbt::BlockInformation bool setOutputPortType(unsigned portNumber, PortDataType portType) override; //Port data - unsigned getInputPortWidth(unsigned portNumber) override; - unsigned getOutputPortWidth(unsigned portNumber) override; - wbt::Signal getInputPortSignal(unsigned portNumber) override; - wbt::Signal getOutputPortSignal(unsigned portNumber) override; + unsigned getInputPortWidth(unsigned portNumber) const override; + unsigned getOutputPortWidth(unsigned portNumber) const override; + wbt::Signal getInputPortSignal(unsigned portNumber) const override; + wbt::Signal getOutputPortSignal(unsigned portNumber) const override; }; #endif /* end of include guard: WBT_SIMULINKBLOCKINFORMATION_H */ diff --git a/toolbox/include/base/WBBlock.h b/toolbox/include/base/WBBlock.h index cee7d7d11..b3d5cf33c 100644 --- a/toolbox/include/base/WBBlock.h +++ b/toolbox/include/base/WBBlock.h @@ -66,7 +66,7 @@ class wbt::WBBlock : public wbt::Block protected: std::string confKey; iDynTreeRobotState robotState; - bool getWBToolboxParameters(Configuration& config, BlockInformation* blockInfo); + bool getWBToolboxParameters(Configuration& config, const BlockInformation* blockInfo); const std::shared_ptr getRobotInterface(); const Configuration& getConfiguration(); @@ -75,8 +75,8 @@ class wbt::WBBlock : public wbt::Block ~WBBlock() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; - bool initialize(BlockInformation* blockInfo) override; - bool terminate(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; }; #endif /* end of include guard: WBT_WBIBLOCK_H */ diff --git a/toolbox/src/CentroidalMomentum.cpp b/toolbox/src/CentroidalMomentum.cpp index ca93b9308..1294c7e19 100644 --- a/toolbox/src/CentroidalMomentum.cpp +++ b/toolbox/src/CentroidalMomentum.cpp @@ -10,159 +10,158 @@ #include #include -namespace wbt { - - const std::string CentroidalMomentum::ClassName = "CentroidalMomentum"; - - const unsigned CentroidalMomentum::INPUT_IDX_BASE_POSE = 0; - const unsigned CentroidalMomentum::INPUT_IDX_JOINTCONF = 1; - const unsigned CentroidalMomentum::INPUT_IDX_BASE_VEL = 2; - const unsigned CentroidalMomentum::INPUT_IDX_JOINT_VEL = 3; - const unsigned CentroidalMomentum::OUTPUT_IDX_CENTRMOM = 0; - - CentroidalMomentum::CentroidalMomentum() - : m_centroidalMomentum(nullptr) - {} - - bool CentroidalMomentum::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here - - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - - // INPUTS - // ====== - // - // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) - // 2) Joints position (1xDoFs vector) - // 3) Base frame velocity (1x6 vector) - // 4) Joints velocity (1xDoFs vector) - // - - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(4)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } - - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - - // Size and type - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); - - blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); - - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } - - // OUTPUTS - // ======= - // - // 1) Vector representing the centroidal momentum (1x6) - // - - // Number of outputs - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } - - // Size and type - success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_CENTRMOM, 6); - blockInfo->setOutputPortType(OUTPUT_IDX_CENTRMOM, PortDataTypeDouble); - - return success; +using namespace wbt; + +const std::string CentroidalMomentum::ClassName = "CentroidalMomentum"; + +const unsigned CentroidalMomentum::INPUT_IDX_BASE_POSE = 0; +const unsigned CentroidalMomentum::INPUT_IDX_JOINTCONF = 1; +const unsigned CentroidalMomentum::INPUT_IDX_BASE_VEL = 2; +const unsigned CentroidalMomentum::INPUT_IDX_JOINT_VEL = 3; +const unsigned CentroidalMomentum::OUTPUT_IDX_CENTRMOM = 0; + +CentroidalMomentum::CentroidalMomentum() +: m_centroidalMomentum(nullptr) +{} + +bool CentroidalMomentum::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here + + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // 4) Joints velocity (1xDoFs vector) + // + + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(4)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; } - bool CentroidalMomentum::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - // OUTPUT - // ====== + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); - m_centroidalMomentum = new iDynTree::SpatialMomentum(); - return m_centroidalMomentum; + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); + + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; } - bool CentroidalMomentum::terminate(BlockInformation* blockInfo) - { - if (m_centroidalMomentum) { - delete m_centroidalMomentum; - m_centroidalMomentum = 0; - } + // OUTPUTS + // ======= + // + // 1) Vector representing the centroidal momentum (1x6) + // - return WBBlock::terminate(blockInfo); + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; } - bool CentroidalMomentum::output(BlockInformation* blockInfo) - { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - - const auto& model = getRobotInterface()->getKinDynComputations(); - - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } - - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== - - unsigned signalWidth; - - // Base pose - Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Base velocity - Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); - double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); - robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), - AngVelocity(m_baseVelocityBuffer+3, 3)); - - // Joints velocity - Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); - robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); - - // OUTPUT - // ====== - - // Calculate the centroidal momentum - *m_centroidalMomentum = model->getCentroidalTotalMomentum(); - - // Forward the output to Simulink - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_CENTRMOM); - output.setBuffer(toEigen(*m_centroidalMomentum).data(), - blockInfo->getOutputPortWidth(OUTPUT_IDX_CENTRMOM)); - return true; + // Size and type + success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_CENTRMOM, 6); + blockInfo->setOutputPortType(OUTPUT_IDX_CENTRMOM, PortDataTypeDouble); + + return success; +} + +bool CentroidalMomentum::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; + + // OUTPUT + // ====== + + m_centroidalMomentum = new iDynTree::SpatialMomentum(); + return m_centroidalMomentum; +} + +bool CentroidalMomentum::terminate(const BlockInformation* blockInfo) +{ + if (m_centroidalMomentum) { + delete m_centroidalMomentum; + m_centroidalMomentum = 0; } + + return WBBlock::terminate(blockInfo); +} + +bool CentroidalMomentum::output(const BlockInformation* blockInfo) +{ + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // Base velocity + Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); + double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); + robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), + AngVelocity(m_baseVelocityBuffer+3, 3)); + + // Joints velocity + Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); + robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Calculate the centroidal momentum + *m_centroidalMomentum = model->getCentroidalTotalMomentum(); + + // Forward the output to Simulink + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_CENTRMOM); + output.setBuffer(toEigen(*m_centroidalMomentum).data(), + blockInfo->getOutputPortWidth(OUTPUT_IDX_CENTRMOM)); + return true; } diff --git a/toolbox/src/DotJNu.cpp b/toolbox/src/DotJNu.cpp index db9264ab2..7c82c2c39 100644 --- a/toolbox/src/DotJNu.cpp +++ b/toolbox/src/DotJNu.cpp @@ -9,208 +9,207 @@ #include #include -namespace wbt { +using namespace wbt; - const std::string DotJNu::ClassName = "DotJNu"; +const std::string DotJNu::ClassName = "DotJNu"; - const unsigned DotJNu::INPUT_IDX_BASE_POSE = 0; - const unsigned DotJNu::INPUT_IDX_JOINTCONF = 1; - const unsigned DotJNu::INPUT_IDX_BASE_VEL = 2; - const unsigned DotJNu::INPUT_IDX_JOINT_VEL = 3; - const unsigned DotJNu::OUTPUT_IDX_DOTJ_NU = 0; +const unsigned DotJNu::INPUT_IDX_BASE_POSE = 0; +const unsigned DotJNu::INPUT_IDX_JOINTCONF = 1; +const unsigned DotJNu::INPUT_IDX_BASE_VEL = 2; +const unsigned DotJNu::INPUT_IDX_JOINT_VEL = 3; +const unsigned DotJNu::OUTPUT_IDX_DOTJ_NU = 0; - DotJNu::DotJNu() - : m_dotJNu(nullptr) - , m_frameIsCoM(false) - , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) - {} +DotJNu::DotJNu() +: m_dotJNu(nullptr) +, m_frameIsCoM(false) +, m_frameIndex(iDynTree::FRAME_INVALID_INDEX) +{} - unsigned DotJNu::numberOfParameters() - { - return WBBlock::numberOfParameters() + 1; +unsigned DotJNu::numberOfParameters() +{ + return WBBlock::numberOfParameters() + 1; +} + +bool DotJNu::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here + + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // 4) Joints velocity (1xDoFs vector) + // + + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(4)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; } - bool DotJNu::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); - // INPUTS - // ====== - // - // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) - // 2) Joints position (1xDoFs vector) - // 3) Base frame velocity (1x6 vector) - // 4) Joints velocity (1xDoFs vector) - // + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(4)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; + } - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + // OUTPUTS + // ======= + // + // 1) Vector representing the \dot{J} \nu vector (1x6) + // - // Size and type - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } - blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_DOTJ_NU, 6); + blockInfo->setOutputPortType(OUTPUT_IDX_DOTJ_NU, PortDataTypeDouble); - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } + return success; +} - // OUTPUTS - // ======= - // - // 1) Vector representing the \dot{J} \nu vector (1x6) - // +bool DotJNu::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - // Number of outputs - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + // INPUT PARAMETERS + // ================ - // Size and type - success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_DOTJ_NU, 6); - blockInfo->setOutputPortType(OUTPUT_IDX_DOTJ_NU, PortDataTypeDouble); + std::string frame; + int parentParameters = WBBlock::numberOfParameters(); - return success; + if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { + Log::getSingleton().error("Cannot retrieve string from frame parameter."); + return false; } - bool DotJNu::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; - - // INPUT PARAMETERS - // ================ - - std::string frame; - int parentParameters = WBBlock::numberOfParameters(); + // Check if the frame is valid + // --------------------------- - if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { - Log::getSingleton().error("Cannot retrieve string from frame parameter."); - return false; - } - - // Check if the frame is valid - // --------------------------- + const auto& model = getRobotInterface()->getKinDynComputations(); + if (!model) { + Log::getSingleton().error("Cannot retrieve handle to KinDynComputations."); + return false; + } - const auto& model = getRobotInterface()->getKinDynComputations(); - if (!model) { - Log::getSingleton().error("Cannot retrieve handle to KinDynComputations."); + if (frame != "com") { + m_frameIndex = model->getFrameIndex(frame); + if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { + Log::getSingleton().error("Cannot find " + frame + " in the frame list."); return false; } - - if (frame != "com") { - m_frameIndex = model->getFrameIndex(frame); - if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { - Log::getSingleton().error("Cannot find " + frame + " in the frame list."); - return false; - } - } - else { - m_frameIsCoM = true; - m_frameIndex = iDynTree::FRAME_INVALID_INDEX; - } - - // OUTPUT - // ====== - m_dotJNu = new iDynTree::Vector6(); - m_dotJNu->zero(); - - return m_dotJNu; + } + else { + m_frameIsCoM = true; + m_frameIndex = iDynTree::FRAME_INVALID_INDEX; } - bool DotJNu::terminate(BlockInformation* blockInfo) - { - // Output - if (m_dotJNu) { - delete m_dotJNu; - m_dotJNu = 0; - } + // OUTPUT + // ====== + m_dotJNu = new iDynTree::Vector6(); + m_dotJNu->zero(); + + return m_dotJNu; +} - return WBBlock::terminate(blockInfo); +bool DotJNu::terminate(const BlockInformation* blockInfo) +{ + // Output + if (m_dotJNu) { + delete m_dotJNu; + m_dotJNu = 0; } - bool DotJNu::output(BlockInformation* blockInfo) - { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; + return WBBlock::terminate(blockInfo); +} - const auto& model = getRobotInterface()->getKinDynComputations(); +bool DotJNu::output(const BlockInformation* blockInfo) +{ + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } + const auto& model = getRobotInterface()->getKinDynComputations(); - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== - - unsigned signalWidth; - - // Base pose - Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Base velocity - Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); - double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); - robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), - AngVelocity(m_baseVelocityBuffer+3, 3)); - - // Joints velocity - Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); - robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); - - // OUTPUT - // ====== - - // Compute the dot{J}*\nu - Vector6 biasAcc; - if (!m_frameIsCoM) { - biasAcc = model->getFrameBiasAcc(m_frameIndex); - } - else { - Vector3 comBiasAcc = model->getCenterOfMassBiasAcc(); - toEigen(biasAcc).segment<3>(0) = iDynTree::toEigen(comBiasAcc); - toEigen(biasAcc).segment<3>(3).setZero(); - } + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } - // Forward the output to Simulink - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_DOTJ_NU); - output.setBuffer(m_dotJNu->data(), - blockInfo->getOutputPortWidth(OUTPUT_IDX_DOTJ_NU)); - return true; + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // Base velocity + Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); + double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); + robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), + AngVelocity(m_baseVelocityBuffer+3, 3)); + + // Joints velocity + Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); + robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Compute the dot{J}*\nu + Vector6 biasAcc; + if (!m_frameIsCoM) { + biasAcc = model->getFrameBiasAcc(m_frameIndex); } + else { + Vector3 comBiasAcc = model->getCenterOfMassBiasAcc(); + toEigen(biasAcc).segment<3>(0) = iDynTree::toEigen(comBiasAcc); + toEigen(biasAcc).segment<3>(3).setZero(); + } + + // Forward the output to Simulink + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_DOTJ_NU); + output.setBuffer(m_dotJNu->data(), + blockInfo->getOutputPortWidth(OUTPUT_IDX_DOTJ_NU)); + return true; } diff --git a/toolbox/src/ForwardKinematics.cpp b/toolbox/src/ForwardKinematics.cpp index 052713745..a34f5c72b 100644 --- a/toolbox/src/ForwardKinematics.cpp +++ b/toolbox/src/ForwardKinematics.cpp @@ -9,185 +9,181 @@ #include #include -namespace wbt { +using namespace wbt; - const std::string ForwardKinematics::ClassName = "ForwardKinematics"; +const std::string ForwardKinematics::ClassName = "ForwardKinematics"; - const unsigned ForwardKinematics::INPUT_IDX_BASE_POSE = 0; - const unsigned ForwardKinematics::INPUT_IDX_JOINTCONF = 1; - const unsigned ForwardKinematics::OUTPUT_IDX_FW_FRAME = 0; +const unsigned ForwardKinematics::INPUT_IDX_BASE_POSE = 0; +const unsigned ForwardKinematics::INPUT_IDX_JOINTCONF = 1; +const unsigned ForwardKinematics::OUTPUT_IDX_FW_FRAME = 0; - ForwardKinematics::ForwardKinematics() - : m_frameIsCoM(false) - , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) - {} +ForwardKinematics::ForwardKinematics() +: m_frameIsCoM(false) +, m_frameIndex(iDynTree::FRAME_INVALID_INDEX) +{} - unsigned ForwardKinematics::numberOfParameters() - { - return WBBlock::numberOfParameters() + 1; - } - - bool ForwardKinematics::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here +unsigned ForwardKinematics::numberOfParameters() +{ + return WBBlock::numberOfParameters() + 1; +} - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; +bool ForwardKinematics::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here - // INPUTS - // ====== - // - // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) - // 2) Joints position (1xDoFs vector) - // + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(2)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - - // Size and type - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(2)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } - blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - // OUTPUTS - // ======= - // - // 1) Homogeneous transformation between the world and the specified frame (4x4 matrix) - // + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - // Number of outputs - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; + } - // Size and type - success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_FW_FRAME, 4, 4); - blockInfo->setOutputPortType(OUTPUT_IDX_FW_FRAME, PortDataTypeDouble); + // OUTPUTS + // ======= + // + // 1) Homogeneous transformation between the world and the specified frame (4x4 matrix) + // - return success; + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; } - bool ForwardKinematics::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + // Size and type + success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_FW_FRAME, 4, 4); + blockInfo->setOutputPortType(OUTPUT_IDX_FW_FRAME, PortDataTypeDouble); - // INPUT PARAMETERS - // ================ + return success; +} - std::string frame; - int parentParameters = WBBlock::numberOfParameters(); +bool ForwardKinematics::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { - Log::getSingleton().error("Cannot retrieve string from frame parameter."); - return false; - } + // INPUT PARAMETERS + // ================ - // Check if the frame is valid - // --------------------------- + std::string frame; + int parentParameters = WBBlock::numberOfParameters(); - const auto& model = getRobotInterface()->getKinDynComputations(); - if (!model) { - Log::getSingleton().error("Cannot retrieve handle to WBI model."); - return false; - } + if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { + Log::getSingleton().error("Cannot retrieve string from frame parameter."); + return false; + } - if (frame != "com") { - m_frameIndex = model->getFrameIndex(frame); - if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { - Log::getSingleton().error("Cannot find " + frame + " in the frame list."); - return false; - } - } - else { - m_frameIsCoM = true; - m_frameIndex = iDynTree::FRAME_INVALID_INDEX; - } + // Check if the frame is valid + // --------------------------- - return true; + const auto& model = getRobotInterface()->getKinDynComputations(); + if (!model) { + Log::getSingleton().error("Cannot retrieve handle to WBI model."); + return false; } - bool ForwardKinematics::terminate(BlockInformation* blockInfo) - { - return WBBlock::terminate(blockInfo); + if (frame != "com") { + m_frameIndex = model->getFrameIndex(frame); + if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { + Log::getSingleton().error("Cannot find " + frame + " in the frame list."); + return false; + } + } + else { + m_frameIsCoM = true; + m_frameIndex = iDynTree::FRAME_INVALID_INDEX; } - bool ForwardKinematics::output(BlockInformation* blockInfo) - { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - typedef Matrix Matrix4diDynTree; + return true; +} - const auto& model = getRobotInterface()->getKinDynComputations(); +bool ForwardKinematics::terminate(const BlockInformation* blockInfo) +{ + return WBBlock::terminate(blockInfo); +} - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } +bool ForwardKinematics::output(const BlockInformation* blockInfo) +{ + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + typedef Matrix Matrix4diDynTree; - // Get the signals and convert them to iDynTree objects - // ==================================================== + const auto& model = getRobotInterface()->getKinDynComputations(); - unsigned signalWidth; + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } - // Base pose - Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + // Get the signals and convert them to iDynTree objects + // ==================================================== - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + unsigned signalWidth; - // TODO: the other 3 inputs are taken from the previous block's setRobotState(). - // How to handle it? What happens if a nullptr is passed? + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - // Update the robot status - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - // Output - // ====== + // Update the robot status + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); - iDynTree::Transform world_H_frame; + // Output + // ====== - // Compute the transform to the selected frame - if (!m_frameIsCoM) { - world_H_frame = model->getWorldTransform(m_frameIndex); - } - else { - world_H_frame.setPosition(model->getCenterOfMassPosition()); - } + iDynTree::Transform world_H_frame; - // Get the output signal memory location - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_FW_FRAME); + // Compute the transform to the selected frame + if (!m_frameIsCoM) { + world_H_frame = model->getWorldTransform(m_frameIndex); + } + else { + world_H_frame.setPosition(model->getCenterOfMassPosition()); + } - // Allocate objects for row-major -> col-major conversion - Map world_H_frame_RowMajor = toEigen(world_H_frame.asHomogeneousTransform()); - Map world_H_frame_ColMajor((double*)output.getContiguousBuffer(), - 4, 4); + // Get the output signal memory location + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_FW_FRAME); - // Forward the buffer to Simulink transforming it to ColMajor - world_H_frame_ColMajor = world_H_frame_RowMajor; - return true; - } + // Allocate objects for row-major -> col-major conversion + Map world_H_frame_RowMajor = toEigen(world_H_frame.asHomogeneousTransform()); + Map world_H_frame_ColMajor((double*)output.getContiguousBuffer(), + 4, 4); + + // Forward the buffer to Simulink transforming it to ColMajor + world_H_frame_ColMajor = world_H_frame_RowMajor; + return true; } diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index bc2f55b10..4923021e7 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -10,187 +10,186 @@ #include #include -namespace wbt { +using namespace wbt; - const std::string GetLimits::ClassName = "GetLimits"; +const std::string GetLimits::ClassName = "GetLimits"; - unsigned GetLimits::numberOfParameters() - { - return WBBlock::numberOfParameters() + 1; - } - - bool GetLimits::configureSizeAndPorts(BlockInformation* blockInfo) - { - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; +unsigned GetLimits::numberOfParameters() +{ + return WBBlock::numberOfParameters() + 1; +} - // INPUTS - // ====== - // - // No inputs - // +bool GetLimits::configureSizeAndPorts(BlockInformation* blockInfo) +{ + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + // INPUTS + // ====== + // + // No inputs + // - // OUTPUTS - // ======= - // - // 1) vector with the information asked (1xDoFs) - // + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } - if (!blockInfo->setNumberOfOutputPorts(2)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + // OUTPUTS + // ======= + // + // 1) vector with the information asked (1xDoFs) + // - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + if (!blockInfo->setNumberOfOutputPorts(2)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } - bool success = true; - success = success && blockInfo->setOutputPortVectorSize(0, dofs); // Min limit - success = success && blockInfo->setOutputPortVectorSize(1, dofs); // Max limit + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - blockInfo->setOutputPortType(0, PortDataTypeDouble); - blockInfo->setOutputPortType(1, PortDataTypeDouble); + bool success = true; + success = success && blockInfo->setOutputPortVectorSize(0, dofs); // Min limit + success = success && blockInfo->setOutputPortVectorSize(1, dofs); // Max limit - if (!success) { - Log::getSingleton().error("Failed to configure output ports."); - return false; - } + blockInfo->setOutputPortType(0, PortDataTypeDouble); + blockInfo->setOutputPortType(1, PortDataTypeDouble); - return true; + if (!success) { + Log::getSingleton().error("Failed to configure output ports."); + return false; } - bool GetLimits::initialize(BlockInformation* blockInfo) - { - using namespace yarp::os; - if (!WBBlock::initialize(blockInfo)) return false; + return true; +} + +bool GetLimits::initialize(const BlockInformation* blockInfo) +{ + using namespace yarp::os; + if (!WBBlock::initialize(blockInfo)) return false; + + // Read the control type + std::string limitType; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, limitType)) { + Log::getSingleton().error("Could not read estimate type parameter."); + return false; + } - // Read the control type - std::string limitType; - if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, limitType)) { - Log::getSingleton().error("Could not read estimate type parameter."); + // Initialize the structure that stores the limits + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_limits.reset(new Limit(dofs)); + + // Initializes some buffers + double min = 0; + double max = 0; + + // From the RemoteControlBoardRemapper + // =================================== + // + // In the next methods, the values are asked using joint index and not string. + // The ControlBoardRemapper internally uses the same joints ordering of its + // initialization. In this case, it matches 1:1 the joint vector. It is hence + // possible using i to point to the correct joint. + + // Get the RemoteControlBoardRemapper and IControlLimits2 interface if needed + std::weak_ptr iControlLimits2; + if (limitType == "ControlBoardPosition" || limitType == "ControlBoardVelocity") { + // Retain the control board remapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); return false; } + // Get the interface + if (!getRobotInterface()->getInterface(iControlLimits2)) { + Log::getSingleton().error("Failed to get IControlLimits2 interface."); + return false; + } + } - // Initialize the structure that stores the limits - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_limits.reset(new Limit(dofs)); - - // Initializes some buffers - double min = 0; - double max = 0; - - // From the RemoteControlBoardRemapper - // =================================== - // - // In the next methods, the values are asked using joint index and not string. - // The ControlBoardRemapper internally uses the same joints ordering of its - // initialization. In this case, it matches 1:1 the joint vector. It is hence - // possible using i to point to the correct joint. - - // Get the RemoteControlBoardRemapper and IControlLimits2 interface if needed - std::weak_ptr iControlLimits2; - if (limitType == "ControlBoardPosition" || limitType == "ControlBoardVelocity") { - // Retain the control board remapper - if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + if (limitType == "ControlBoardPosition") { + for (auto i = 0; i < dofs; ++i) { + if (!iControlLimits2.lock()->getLimits(i, &min, &max)) { + Log::getSingleton().error("Failed to get limits from the interface."); return false; } - // Get the interface - if (!getRobotInterface()->getInterface(iControlLimits2)) { - Log::getSingleton().error("Failed to get IControlLimits2 interface."); + m_limits->min[i] = min; + m_limits->max[i] = max; + } + } + else if (limitType == "ControlBoardVelocity") { + for (auto i = 0; i < dofs; ++i) { + if (!iControlLimits2.lock()->getVelLimits(i, &min, &max)) { + Log::getSingleton().error("Failed to get limits from the interface."); return false; } + m_limits->min[i] = min; + m_limits->max[i] = max; } + } - if (limitType == "ControlBoardPosition") { - for (auto i = 0; i < dofs; ++i) { - if (!iControlLimits2.lock()->getLimits(i, &min, &max)) { - Log::getSingleton().error("Failed to get limits from the interface."); - return false; - } - m_limits->min[i] = min; - m_limits->max[i] = max; - } - } - else if (limitType == "ControlBoardVelocity") { - for (auto i = 0; i < dofs; ++i) { - if (!iControlLimits2.lock()->getVelLimits(i, &min, &max)) { - Log::getSingleton().error("Failed to get limits from the interface."); - return false; - } - m_limits->min[i] = min; - m_limits->max[i] = max; - } - } + // From the URDF model + // =================== + // + // For the time being, only position limits are supported. - // From the URDF model - // =================== - // - // For the time being, only position limits are supported. - - else if (limitType == "ModelPosition") { - iDynTree::IJointConstPtr p_joint; - const iDynTree::Model model = getRobotInterface()->getKinDynComputations()->model(); - - for (auto i = 0; i < dofs; ++i) { - // Get the joint name - std::string joint = getConfiguration().getControlledJoints()[i]; - - // Get its index - iDynTree::LinkIndex jointIndex = model.getLinkIndex(joint); - - // Get the joint from the model - p_joint = model.getJoint(jointIndex); - - if (!p_joint->hasPosLimits()) { - Log::getSingleton().warning("Joint " + joint + " has no model limits."); - // TODO: test how these values are interpreted by Simulink - min = -std::numeric_limits::infinity(); - max = std::numeric_limits::infinity(); - } - else { - p_joint->getPosLimits(0, min, max); - } + else if (limitType == "ModelPosition") { + iDynTree::IJointConstPtr p_joint; + const iDynTree::Model model = getRobotInterface()->getKinDynComputations()->model(); + + for (auto i = 0; i < dofs; ++i) { + // Get the joint name + std::string joint = getConfiguration().getControlledJoints()[i]; + + // Get its index + iDynTree::LinkIndex jointIndex = model.getLinkIndex(joint); + + // Get the joint from the model + p_joint = model.getJoint(jointIndex); + + if (!p_joint->hasPosLimits()) { + Log::getSingleton().warning("Joint " + joint + " has no model limits."); + // TODO: test how these values are interpreted by Simulink + min = -std::numeric_limits::infinity(); + max = std::numeric_limits::infinity(); + } + else { + p_joint->getPosLimits(0, min, max); } } - // TODO - // else if (limitType == "ModelVelocity") { - // } - // else if (limitType == "ModelEffort") { - // } - else { - Log::getSingleton().error("Limit type " + limitType + " not recognized."); - return false; - } - - return true; + } + // TODO + // else if (limitType == "ModelVelocity") { + // } + // else if (limitType == "ModelEffort") { + // } + else { + Log::getSingleton().error("Limit type " + limitType + " not recognized."); + return false; } - bool GetLimits::terminate(BlockInformation* blockInfo) - { - // Release the RemoteControlBoardRemapper - bool ok = true; - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); - if (!ok) { - Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); - } + return true; +} - return ok && WBBlock::terminate(blockInfo); +bool GetLimits::terminate(const BlockInformation* blockInfo) +{ + // Release the RemoteControlBoardRemapper + bool ok = true; + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); } - bool GetLimits::output(BlockInformation* blockInfo) - { - if (!m_limits) return false; + return ok && WBBlock::terminate(blockInfo); +} + +bool GetLimits::output(const BlockInformation* blockInfo) +{ + if (!m_limits) return false; - Signal minPort = blockInfo->getOutputPortSignal(0); - Signal maxPort = blockInfo->getOutputPortSignal(1); + Signal minPort = blockInfo->getOutputPortSignal(0); + Signal maxPort = blockInfo->getOutputPortSignal(1); - minPort.setBuffer(m_limits->min.data(), getConfiguration().getNumberOfDoFs()); - maxPort.setBuffer(m_limits->max.data(), getConfiguration().getNumberOfDoFs()); + minPort.setBuffer(m_limits->min.data(), getConfiguration().getNumberOfDoFs()); + maxPort.setBuffer(m_limits->max.data(), getConfiguration().getNumberOfDoFs()); - return true; - } + return true; } diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index c0e0f01f6..65cc1a49e 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -10,174 +10,173 @@ #define _USE_MATH_DEFINES #include -namespace wbt { +using namespace wbt; - const std::string GetMeasurement::ClassName = "GetMeasurement"; +const std::string GetMeasurement::ClassName = "GetMeasurement"; - void deg2rad(std::vector& v) - { - const double deg2rad = (2 * M_PI) / 180.0; - for (auto& element : v) { - element *= deg2rad; - } - } - - unsigned GetMeasurement::numberOfParameters() - { - return WBBlock::numberOfParameters() + 1; +void deg2rad(std::vector& v) +{ + const double deg2rad = (2 * M_PI) / 180.0; + for (auto& element : v) { + element *= deg2rad; } +} - bool GetMeasurement::configureSizeAndPorts(BlockInformation* blockInfo) - { - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; +unsigned GetMeasurement::numberOfParameters() +{ + return WBBlock::numberOfParameters() + 1; +} - // INPUTS - // ====== - // - // No inputs - // +bool GetMeasurement::configureSizeAndPorts(BlockInformation* blockInfo) +{ + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + // INPUTS + // ====== + // + // No inputs + // - // OUTPUTS - // ======= - // - // 1) Vector with the information asked (1xDoFs) - // + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + // OUTPUTS + // ======= + // + // 1) Vector with the information asked (1xDoFs) + // - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } - bool success = blockInfo->setOutputPortVectorSize(0, dofs); - blockInfo->setOutputPortType(0, PortDataTypeDouble); - if (!success) { - Log::getSingleton().error("Failed to configure output ports."); - return false; - } + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - return true; + bool success = blockInfo->setOutputPortVectorSize(0, dofs); + blockInfo->setOutputPortType(0, PortDataTypeDouble); + if (!success) { + Log::getSingleton().error("Failed to configure output ports."); + return false; } - bool GetMeasurement::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + return true; +} - // Reading the control type - std::string informationType; - if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, informationType)) { - Log::getSingleton().error("Could not read estimate type parameter."); - return false; - } +bool GetMeasurement::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - if (informationType == "Joints Position") { - m_estimateType = wbt::ESTIMATE_JOINT_POS; - } else if (informationType == "Joints Velocity") { - m_estimateType = wbt::ESTIMATE_JOINT_VEL; - } else if (informationType == "Joints Acceleration") { - m_estimateType = wbt::ESTIMATE_JOINT_ACC; - } else if (informationType == "Joints Torque") { - m_estimateType = wbt::ESTIMATE_JOINT_TORQUE; - } else { - Log::getSingleton().error("Estimate not supported."); - return false; - } + // Reading the control type + std::string informationType; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, informationType)) { + Log::getSingleton().error("Could not read estimate type parameter."); + return false; + } - // Initialize the size of the output vector - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_estimate.reserve(dofs); + if (informationType == "Joints Position") { + m_estimateType = wbt::ESTIMATE_JOINT_POS; + } else if (informationType == "Joints Velocity") { + m_estimateType = wbt::ESTIMATE_JOINT_VEL; + } else if (informationType == "Joints Acceleration") { + m_estimateType = wbt::ESTIMATE_JOINT_ACC; + } else if (informationType == "Joints Torque") { + m_estimateType = wbt::ESTIMATE_JOINT_TORQUE; + } else { + Log::getSingleton().error("Estimate not supported."); + return false; + } - // Retain the ControlBoardRemapper - if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); - return false; - } + // Initialize the size of the output vector + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_estimate.reserve(dofs); - return true; + // Retain the ControlBoardRemapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + return false; } - bool GetMeasurement::terminate(BlockInformation* blockInfo) - { - // Release the RemoteControlBoardRemapper - bool ok = true; - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); - if (!ok) { - Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); - } + return true; +} - return ok && WBBlock::terminate(blockInfo); +bool GetMeasurement::terminate(const BlockInformation* blockInfo) +{ + // Release the RemoteControlBoardRemapper + bool ok = true; + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); } - bool GetMeasurement::output(BlockInformation* blockInfo) - { - bool ok; - switch (m_estimateType) { - case ESTIMATE_JOINT_POS: { - // Get the interface - std::weak_ptr iEncoders; - if (!getRobotInterface()->getInterface(iEncoders)) { - Log::getSingleton().error("Failed to get IPidControl interface."); - return false; - } - // Get the measurement - ok = iEncoders.lock()->getEncoders(m_estimate.data()); - deg2rad(m_estimate); - break; - } - case ESTIMATE_JOINT_VEL: { - // Get the interface - std::weak_ptr iEncoders; - if (!getRobotInterface()->getInterface(iEncoders)) { - Log::getSingleton().error("Failed to get IEncoders interface."); - return false; - } - // Get the measurement - ok = iEncoders.lock()->getEncoderSpeeds(m_estimate.data()); - deg2rad(m_estimate); - break; + return ok && WBBlock::terminate(blockInfo); +} + +bool GetMeasurement::output(const BlockInformation* blockInfo) +{ + bool ok; + switch (m_estimateType) { + case ESTIMATE_JOINT_POS: { + // Get the interface + std::weak_ptr iEncoders; + if (!getRobotInterface()->getInterface(iEncoders)) { + Log::getSingleton().error("Failed to get IPidControl interface."); + return false; } - case ESTIMATE_JOINT_ACC: { - // Get the interface - std::weak_ptr iEncoders; - if (!getRobotInterface()->getInterface(iEncoders)) { - Log::getSingleton().error("Failed to get IEncoders interface."); - return false; - } - // Get the measurement - ok = iEncoders.lock()->getEncoderAccelerations(m_estimate.data()); - deg2rad(m_estimate); - break; + // Get the measurement + ok = iEncoders.lock()->getEncoders(m_estimate.data()); + deg2rad(m_estimate); + break; + } + case ESTIMATE_JOINT_VEL: { + // Get the interface + std::weak_ptr iEncoders; + if (!getRobotInterface()->getInterface(iEncoders)) { + Log::getSingleton().error("Failed to get IEncoders interface."); + return false; } - case ESTIMATE_JOINT_TORQUE: { - // Get the interface - std::weak_ptr iTorqueControl; - if (!getRobotInterface()->getInterface(iTorqueControl)) { - Log::getSingleton().error("Failed to get ITorqueControl interface."); - return false; - } - // Get the measurement - ok = iTorqueControl.lock()->getTorques(m_estimate.data()); - break; + // Get the measurement + ok = iEncoders.lock()->getEncoderSpeeds(m_estimate.data()); + deg2rad(m_estimate); + break; + } + case ESTIMATE_JOINT_ACC: { + // Get the interface + std::weak_ptr iEncoders; + if (!getRobotInterface()->getInterface(iEncoders)) { + Log::getSingleton().error("Failed to get IEncoders interface."); + return false; } - default: - Log::getSingleton().error("Estimate type not recognized."); + // Get the measurement + ok = iEncoders.lock()->getEncoderAccelerations(m_estimate.data()); + deg2rad(m_estimate); + break; + } + case ESTIMATE_JOINT_TORQUE: { + // Get the interface + std::weak_ptr iTorqueControl; + if (!getRobotInterface()->getInterface(iTorqueControl)) { + Log::getSingleton().error("Failed to get ITorqueControl interface."); return false; + } + // Get the measurement + ok = iTorqueControl.lock()->getTorques(m_estimate.data()); + break; } - - if (!ok) { - Log::getSingleton().error("Failed to get estimate."); + default: + Log::getSingleton().error("Estimate type not recognized."); return false; - } - - Signal signal = blockInfo->getOutputPortSignal(0); - signal.setBuffer(m_estimate.data(), blockInfo->getOutputPortWidth(0)); + } - return true; + if (!ok) { + Log::getSingleton().error("Failed to get estimate."); + return false; } + + Signal signal = blockInfo->getOutputPortSignal(0); + signal.setBuffer(m_estimate.data(), blockInfo->getOutputPortWidth(0)); + + return true; } diff --git a/toolbox/src/InverseDynamics.cpp b/toolbox/src/InverseDynamics.cpp index 28b8a70c7..5aa635a93 100644 --- a/toolbox/src/InverseDynamics.cpp +++ b/toolbox/src/InverseDynamics.cpp @@ -10,206 +10,204 @@ #include #include -// TODO: Substitute with using -namespace wbt { - - const std::string InverseDynamics::ClassName = "InverseDynamics"; - - const unsigned InverseDynamics::INPUT_IDX_BASE_POSE = 0; - const unsigned InverseDynamics::INPUT_IDX_JOINTCONF = 1; - const unsigned InverseDynamics::INPUT_IDX_BASE_VEL = 2; - const unsigned InverseDynamics::INPUT_IDX_JOINT_VEL = 3; - const unsigned InverseDynamics::INPUT_IDX_BASE_ACC = 4; - const unsigned InverseDynamics::INPUT_IDX_JOINT_ACC = 5; - const unsigned InverseDynamics::OUTPUT_IDX_TORQUES = 0; - - InverseDynamics::InverseDynamics() - : m_baseAcceleration(nullptr) - , m_jointsAcceleration(nullptr) - , m_torques(nullptr) - {} - - unsigned InverseDynamics::numberOfParameters() - { - return WBBlock::numberOfParameters(); +using namespace wbt; + +const std::string InverseDynamics::ClassName = "InverseDynamics"; + +const unsigned InverseDynamics::INPUT_IDX_BASE_POSE = 0; +const unsigned InverseDynamics::INPUT_IDX_JOINTCONF = 1; +const unsigned InverseDynamics::INPUT_IDX_BASE_VEL = 2; +const unsigned InverseDynamics::INPUT_IDX_JOINT_VEL = 3; +const unsigned InverseDynamics::INPUT_IDX_BASE_ACC = 4; +const unsigned InverseDynamics::INPUT_IDX_JOINT_ACC = 5; +const unsigned InverseDynamics::OUTPUT_IDX_TORQUES = 0; + +InverseDynamics::InverseDynamics() +: m_baseAcceleration(nullptr) +, m_jointsAcceleration(nullptr) +, m_torques(nullptr) +{} + +unsigned InverseDynamics::numberOfParameters() +{ + return WBBlock::numberOfParameters(); +} + +bool InverseDynamics::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here + + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // 4) Joints velocity (1xDoFs vector) + // 5) Base frame acceleration (1x6 vector) + // 6) Joints acceleration (1xDoFs vector) + // + + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(6)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; } - bool InverseDynamics::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here - - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - - // INPUTS - // ====== - // - // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) - // 2) Joints position (1xDoFs vector) - // 3) Base frame velocity (1x6 vector) - // 4) Joints velocity (1xDoFs vector) - // 5) Base frame acceleration (1x6 vector) - // 6) Joints acceleration (1xDoFs vector) - // - - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(6)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } - - // Get the DoFs - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - - // Size and type - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_ACC, 6); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_ACC, dofs); - - blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_BASE_ACC, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINT_ACC, PortDataTypeDouble); - - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } - - // OUTPUTS - // ======= - // - // 1) Vector representing the torques (1x(DoFs+6)) - // - - // Number of outputs - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } - - // Size and type - success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_TORQUES, dofs + 6); - blockInfo->setOutputPortType(OUTPUT_IDX_TORQUES, PortDataTypeDouble); - - return success; + // Get the DoFs + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_VEL, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_VEL, dofs); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_BASE_ACC, 6); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINT_ACC, dofs); + + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_VEL, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_ACC, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINT_ACC, PortDataTypeDouble); + + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; } - bool InverseDynamics::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + // OUTPUTS + // ======= + // + // 1) Vector representing the torques (1x(DoFs+6)) + // - // OUTPUT / VARIABLES - // ================== + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + // Size and type + success = blockInfo->setOutputPortVectorSize(OUTPUT_IDX_TORQUES, dofs + 6); + blockInfo->setOutputPortType(OUTPUT_IDX_TORQUES, PortDataTypeDouble); - m_baseAcceleration = new iDynTree::Vector6(); - m_baseAcceleration->zero(); - m_jointsAcceleration = new iDynTree::VectorDynSize(dofs); - m_jointsAcceleration->zero(); + return success; +} - const auto& model = getRobotInterface()->getKinDynComputations()->model(); - m_torques = new iDynTree::FreeFloatingGeneralizedTorques(model); +bool InverseDynamics::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - return m_baseAcceleration && m_jointsAcceleration && m_torques; - } + // OUTPUT / VARIABLES + // ================== - bool InverseDynamics::terminate(BlockInformation* blockInfo) - { - if (m_baseAcceleration) { - delete m_baseAcceleration; - m_baseAcceleration = nullptr; - } - if (m_jointsAcceleration) { - delete m_jointsAcceleration; - m_jointsAcceleration = nullptr; - } - if (m_torques) { - delete m_torques; - m_torques = nullptr; - } - - return WBBlock::terminate(blockInfo); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + m_baseAcceleration = new iDynTree::Vector6(); + m_baseAcceleration->zero(); + m_jointsAcceleration = new iDynTree::VectorDynSize(dofs); + m_jointsAcceleration->zero(); + + const auto& model = getRobotInterface()->getKinDynComputations()->model(); + m_torques = new iDynTree::FreeFloatingGeneralizedTorques(model); + + return m_baseAcceleration && m_jointsAcceleration && m_torques; +} + +bool InverseDynamics::terminate(const BlockInformation* blockInfo) +{ + if (m_baseAcceleration) { + delete m_baseAcceleration; + m_baseAcceleration = nullptr; + } + if (m_jointsAcceleration) { + delete m_jointsAcceleration; + m_jointsAcceleration = nullptr; } + if (m_torques) { + delete m_torques; + m_torques = nullptr; + } + + return WBBlock::terminate(blockInfo); +} + +bool InverseDynamics::output(const BlockInformation* blockInfo) +{ + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; - bool InverseDynamics::output(BlockInformation* blockInfo) - { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - - const auto& model = getRobotInterface()->getKinDynComputations(); - - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } - - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== - - unsigned signalWidth; - - // Base pose - Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Base velocity - Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); - double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); - robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), - AngVelocity(m_baseVelocityBuffer+3, 3)); - - // Joints velocity - Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); - robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); - - // Base acceleration - Signal baseAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_ACC); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_ACC); - m_baseAcceleration->fillBuffer(baseAccelerationSignal.getStdVector(signalWidth).data()); - - // Joints acceleration - Signal jointsAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_ACC); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_ACC); - m_jointsAcceleration->fillBuffer(jointsAccelerationSignal.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); - - // OUTPUT - // ====== - - // Calculate the inverse dynamics (assuming zero external forces) - model->inverseDynamics(*m_baseAcceleration, - *m_jointsAcceleration, - LinkNetExternalWrenches(model->getNrOfLinks()), // TODO - *m_torques); - - // Forward the output to Simulink - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_TORQUES); - output.setBuffer(m_torques->jointTorques().data(), - blockInfo->getOutputPortWidth(OUTPUT_IDX_TORQUES)); - return true; + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; } + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // Base velocity + Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); + double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); + robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), + AngVelocity(m_baseVelocityBuffer+3, 3)); + + // Joints velocity + Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); + robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + // Base acceleration + Signal baseAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_ACC); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_ACC); + m_baseAcceleration->fillBuffer(baseAccelerationSignal.getStdVector(signalWidth).data()); + + // Joints acceleration + Signal jointsAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_ACC); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_ACC); + m_jointsAcceleration->fillBuffer(jointsAccelerationSignal.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Calculate the inverse dynamics (assuming zero external forces) + model->inverseDynamics(*m_baseAcceleration, + *m_jointsAcceleration, + LinkNetExternalWrenches(model->getNrOfLinks()), // TODO + *m_torques); + + // Forward the output to Simulink + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_TORQUES); + output.setBuffer(m_torques->jointTorques().data(), + blockInfo->getOutputPortWidth(OUTPUT_IDX_TORQUES)); + return true; } diff --git a/toolbox/src/Jacobian.cpp b/toolbox/src/Jacobian.cpp index 8988cf4bc..4901c7ebc 100644 --- a/toolbox/src/Jacobian.cpp +++ b/toolbox/src/Jacobian.cpp @@ -9,216 +9,215 @@ #include #include -namespace wbt { +using namespace wbt; - const std::string Jacobian::ClassName = "Jacobian"; +const std::string Jacobian::ClassName = "Jacobian"; - const unsigned Jacobian::INPUT_IDX_BASE_POSE = 0; - const unsigned Jacobian::INPUT_IDX_JOINTCONF = 1; - const unsigned Jacobian::OUTPUT_IDX_FW_FRAME = 0; +const unsigned Jacobian::INPUT_IDX_BASE_POSE = 0; +const unsigned Jacobian::INPUT_IDX_JOINTCONF = 1; +const unsigned Jacobian::OUTPUT_IDX_FW_FRAME = 0; - Jacobian::Jacobian() - : m_jacobianCOM(nullptr) - , m_jacobian(nullptr) - , m_frameIsCoM(false) - , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) - {} +Jacobian::Jacobian() +: m_jacobianCOM(nullptr) +, m_jacobian(nullptr) +, m_frameIsCoM(false) +, m_frameIndex(iDynTree::FRAME_INVALID_INDEX) +{} - unsigned Jacobian::numberOfParameters() - { - return WBBlock::numberOfParameters() + 1; - } +unsigned Jacobian::numberOfParameters() +{ + return WBBlock::numberOfParameters() + 1; +} - bool Jacobian::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here +bool Jacobian::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // INPUTS - // ====== - // - // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) - // 2) Joints position (1xDoFs vector) - // 3) Base frame velocity (1x6 vector) - // + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // 3) Base frame velocity (1x6 vector) + // - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(2)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(2)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - // Size and type - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; + } - // OUTPUTS - // ======= - // - // 1) Matrix representing the Jacobian (6x(DoFs+6)) - // + // OUTPUTS + // ======= + // + // 1) Matrix representing the Jacobian (6x(DoFs+6)) + // - // Number of outputs - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } - // Size and type - success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_FW_FRAME, 6, 6 + dofs); - blockInfo->setOutputPortType(OUTPUT_IDX_FW_FRAME, PortDataTypeDouble); + // Size and type + success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_FW_FRAME, 6, 6 + dofs); + blockInfo->setOutputPortType(OUTPUT_IDX_FW_FRAME, PortDataTypeDouble); - return success; - } + return success; +} - bool Jacobian::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; +bool Jacobian::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - // INPUT PARAMETERS - // ================ + // INPUT PARAMETERS + // ================ - std::string frame; - int parentParameters = WBBlock::numberOfParameters(); + std::string frame; + int parentParameters = WBBlock::numberOfParameters(); - if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { - Log::getSingleton().error("Cannot retrieve string from frame parameter."); - return false; - } + if (!blockInfo->getStringParameterAtIndex(parentParameters + 1, frame)) { + Log::getSingleton().error("Cannot retrieve string from frame parameter."); + return false; + } - // Check if the frame is valid - // --------------------------- + // Check if the frame is valid + // --------------------------- + + const auto& model = getRobotInterface()->getKinDynComputations(); + if (!model) { + Log::getSingleton().error("Cannot retrieve handle to KinDynComputations."); + return false; + } - const auto& model = getRobotInterface()->getKinDynComputations(); - if (!model) { - Log::getSingleton().error("Cannot retrieve handle to KinDynComputations."); + if (frame != "com") { + m_frameIndex = model->getFrameIndex(frame); + if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { + Log::getSingleton().error("Cannot find " + frame + " in the frame list."); return false; } + } + else { + m_frameIsCoM = true; + m_frameIndex = iDynTree::FRAME_INVALID_INDEX; + } - if (frame != "com") { - m_frameIndex = model->getFrameIndex(frame); - if (m_frameIndex == iDynTree::FRAME_INVALID_INDEX) { - Log::getSingleton().error("Cannot find " + frame + " in the frame list."); - return false; - } - } - else { - m_frameIsCoM = true; - m_frameIndex = iDynTree::FRAME_INVALID_INDEX; - } + // OUTPUT / VARIABLES + // ================== - // OUTPUT / VARIABLES - // ================== + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_jacobianCOM = new iDynTree::MatrixDynSize(3, 6 + dofs); + m_jacobianCOM->zero(); - m_jacobianCOM = new iDynTree::MatrixDynSize(3, 6 + dofs); - m_jacobianCOM->zero(); + // Output + m_jacobian = new iDynTree::MatrixDynSize(6, 6 + dofs); + m_jacobian->zero(); - // Output - m_jacobian = new iDynTree::MatrixDynSize(6, 6 + dofs); - m_jacobian->zero(); + return m_jacobianCOM && m_jacobian; +} - return m_jacobianCOM && m_jacobian; +bool Jacobian::terminate(const BlockInformation* blockInfo) +{ + if (m_jacobianCOM) { + delete m_jacobianCOM; + m_jacobianCOM = nullptr; } - - bool Jacobian::terminate(BlockInformation* blockInfo) - { - if (m_jacobianCOM) { - delete m_jacobianCOM; - m_jacobianCOM = nullptr; - } - if (m_jacobian) { - delete m_jacobian; - m_jacobian = nullptr; - } - - return WBBlock::terminate(blockInfo); + if (m_jacobian) { + delete m_jacobian; + m_jacobian = nullptr; } - bool Jacobian::output(BlockInformation* blockInfo) - { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - typedef Matrix MatrixXdSimulink; - typedef Matrix MatrixXdiDynTree; + return WBBlock::terminate(blockInfo); +} - const auto& model = getRobotInterface()->getKinDynComputations(); +bool Jacobian::output(const BlockInformation* blockInfo) +{ + using namespace iDynTree; + using namespace Eigen; + typedef Matrix Matrix4dSimulink; + typedef Matrix MatrixXdSimulink; + typedef Matrix MatrixXdiDynTree; - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } + const auto& model = getRobotInterface()->getKinDynComputations(); - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } - unsigned signalWidth; + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== - // Base pose - Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + unsigned signalWidth; - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - // TODO: what about the other inputs of setRobotState? + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + // TODO: what about the other inputs of setRobotState? - // OUTPUT - // ====== + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); - iDynTree::Transform world_H_frame; + // OUTPUT + // ====== - // Compute the jacobian - bool ok = false; - if (!m_frameIsCoM) { - world_H_frame = model->getWorldTransform(m_frameIndex); - ok = model->getFrameFreeFloatingJacobian(m_frameIndex, *m_jacobian); - } - else { - world_H_frame.setPosition(model->getCenterOfMassPosition()); - ok = model->getCenterOfMassJacobian(*m_jacobianCOM); - int cols = m_jacobianCOM->cols(); - toEigen(*m_jacobian).block(0,0,3,cols) = toEigen(*m_jacobianCOM); - toEigen(*m_jacobian).block(3,0,3,cols).setZero(); - } + iDynTree::Transform world_H_frame; + + // Compute the jacobian + bool ok = false; + if (!m_frameIsCoM) { + world_H_frame = model->getWorldTransform(m_frameIndex); + ok = model->getFrameFreeFloatingJacobian(m_frameIndex, *m_jacobian); + } + else { + world_H_frame.setPosition(model->getCenterOfMassPosition()); + ok = model->getCenterOfMassJacobian(*m_jacobianCOM); + int cols = m_jacobianCOM->cols(); + toEigen(*m_jacobian).block(0,0,3,cols) = toEigen(*m_jacobianCOM); + toEigen(*m_jacobian).block(3,0,3,cols).setZero(); + } - // Get the output signal memory location - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_FW_FRAME); - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + // Get the output signal memory location + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_FW_FRAME); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - // Allocate objects for row-major -> col-major conversion - Map jacobianRowMajor = toEigen(*m_jacobian); - Map jacobianColMajor((double*)output.getContiguousBuffer(), - 6, 6 + dofs); + // Allocate objects for row-major -> col-major conversion + Map jacobianRowMajor = toEigen(*m_jacobian); + Map jacobianColMajor((double*)output.getContiguousBuffer(), + 6, 6 + dofs); - // Forward the buffer to Simulink transforming it to ColMajor - jacobianColMajor = jacobianRowMajor; - return true; - } + // Forward the buffer to Simulink transforming it to ColMajor + jacobianColMajor = jacobianRowMajor; + return true; } diff --git a/toolbox/src/MassMatrix.cpp b/toolbox/src/MassMatrix.cpp index 4fcbf7510..96f841253 100644 --- a/toolbox/src/MassMatrix.cpp +++ b/toolbox/src/MassMatrix.cpp @@ -9,153 +9,151 @@ #include #include -// TODO: remove wbt nesting; -namespace wbt { - - const std::string MassMatrix::ClassName = "MassMatrix"; - - const unsigned MassMatrix::INPUT_IDX_BASE_POSE = 0; - const unsigned MassMatrix::INPUT_IDX_JOINTCONF = 1; - const unsigned MassMatrix::OUTPUT_IDX_MASS_MAT = 0; - - MassMatrix::MassMatrix() - : m_massMatrix(nullptr) - {} - - bool MassMatrix::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here - - if (!WBBlock::configureSizeAndPorts(blockInfo)) { - return false; - } - - // INPUTS - // ====== - // - // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) - // 2) Joints position (1xDoFs vector) - // - - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(2)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } - - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - - // Size and type - bool success = true; - success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); - success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - - blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); - blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } - - // OUTPUTS - // ======= - // - // 1) Matrix epresenting the mass matrix (DoFs+6)x(DoFs+6) - // - - // Number of outputs - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } - - // Size and type - success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_MASS_MAT, dofs + 6, dofs + 6); - blockInfo->setOutputPortType(OUTPUT_IDX_MASS_MAT, PortDataTypeDouble); - - return success; +using namespace wbt; + +const std::string MassMatrix::ClassName = "MassMatrix"; + +const unsigned MassMatrix::INPUT_IDX_BASE_POSE = 0; +const unsigned MassMatrix::INPUT_IDX_JOINTCONF = 1; +const unsigned MassMatrix::OUTPUT_IDX_MASS_MAT = 0; + +MassMatrix::MassMatrix() +: m_massMatrix(nullptr) +{} + +bool MassMatrix::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here + + if (!WBBlock::configureSizeAndPorts(blockInfo)) { + return false; + } + + // INPUTS + // ====== + // + // 1) Homogeneous transform for base pose wrt the world frame (4x4 matrix) + // 2) Joints position (1xDoFs vector) + // + + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(2)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; } - bool MassMatrix::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + const unsigned dofs = getConfiguration().getNumberOfDoFs(); - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + // Size and type + bool success = true; + success = success && blockInfo->setInputPortMatrixSize(INPUT_IDX_BASE_POSE, 4, 4); + success = success && blockInfo->setInputPortVectorSize(INPUT_IDX_JOINTCONF, dofs); - // Output - m_massMatrix = new iDynTree::MatrixDynSize(6 + dofs, 6 + dofs); - m_massMatrix->zero(); + blockInfo->setInputPortType(INPUT_IDX_BASE_POSE, PortDataTypeDouble); + blockInfo->setInputPortType(INPUT_IDX_JOINTCONF, PortDataTypeDouble); - return m_massMatrix; + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; } - bool MassMatrix::terminate(BlockInformation* blockInfo) - { - if (m_massMatrix) { - delete m_massMatrix; - m_massMatrix = nullptr; - } + // OUTPUTS + // ======= + // + // 1) Matrix epresenting the mass matrix (DoFs+6)x(DoFs+6) + // - return WBBlock::terminate(blockInfo); + // Number of outputs + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; } - bool MassMatrix::output(BlockInformation* blockInfo) - { - using namespace Eigen; - using namespace iDynTree; - typedef Matrix Matrix4dSimulink; - typedef Matrix MatrixXdSimulink; - typedef Matrix MatrixXdiDynTree; - - const auto& model = getRobotInterface()->getKinDynComputations(); - - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } - - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== - - unsigned signalWidth; - - // Base pose - Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); - - // OUTPUT - // ====== - - // Compute the Mass Matrix - model->getFreeFloatingMassMatrix(*m_massMatrix); - - // Get the output signal memory location - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_MASS_MAT); - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - - // Allocate objects for row-major -> col-major conversion - Map massMatrixRowMajor = toEigen(*m_massMatrix); - Map massMatrixColMajor((double*)output.getContiguousBuffer(), - 6 + dofs, 6 + dofs); - - // Forward the buffer to Simulink transforming it to ColMajor - massMatrixColMajor = massMatrixRowMajor; - return true; + // Size and type + success = blockInfo->setOutputPortMatrixSize(OUTPUT_IDX_MASS_MAT, dofs + 6, dofs + 6); + blockInfo->setOutputPortType(OUTPUT_IDX_MASS_MAT, PortDataTypeDouble); + + return success; +} + +bool MassMatrix::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Output + m_massMatrix = new iDynTree::MatrixDynSize(6 + dofs, 6 + dofs); + m_massMatrix->zero(); + + return m_massMatrix; +} + +bool MassMatrix::terminate(const BlockInformation* blockInfo) +{ + if (m_massMatrix) { + delete m_massMatrix; + m_massMatrix = nullptr; } + + return WBBlock::terminate(blockInfo); +} + +bool MassMatrix::output(const BlockInformation* blockInfo) +{ + using namespace Eigen; + using namespace iDynTree; + typedef Matrix Matrix4dSimulink; + typedef Matrix MatrixXdSimulink; + typedef Matrix MatrixXdiDynTree; + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + + // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS + // ==================================================== + + unsigned signalWidth; + + // Base pose + Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); + fromEigen(robotState.m_world_T_base, + Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); + + // Joints position + Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); + robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + + // UPDATE THE ROBOT STATUS + // ======================= + model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + // OUTPUT + // ====== + + // Compute the Mass Matrix + model->getFreeFloatingMassMatrix(*m_massMatrix); + + // Get the output signal memory location + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_MASS_MAT); + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // Allocate objects for row-major -> col-major conversion + Map massMatrixRowMajor = toEigen(*m_massMatrix); + Map massMatrixColMajor((double*)output.getContiguousBuffer(), + 6 + dofs, 6 + dofs); + + // Forward the buffer to Simulink transforming it to ColMajor + massMatrixColMajor = massMatrixRowMajor; + return true; } diff --git a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp index 2760a7624..80505a592 100644 --- a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp +++ b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp @@ -13,251 +13,249 @@ #include -namespace wbt { - - const std::string MinimumJerkTrajectoryGenerator::ClassName = "MinimumJerkTrajectoryGenerator"; - - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_SAMPLE_TIME = 1; - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_SETTLING_TIME = 2; - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_OUTPUT_1ST_DERIVATIVE = 3; - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_OUTPUT_2ND_DERIVATIVE = 4; - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_INITIAL_VALUE = 5; - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_EXT_SETTLINGTIME = 6; - const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_RESET_CHANGEST = 7; - - MinimumJerkTrajectoryGenerator::MinimumJerkTrajectoryGenerator() - : m_generator(nullptr) - , m_outputFirstDerivativeIndex(-1) - , m_outputSecondDerivativeIndex(-1) - , m_firstRun(true) - , m_explicitInitialValue(false) - , m_externalSettlingTime(false) - , m_resetOnSettlingTimeChange(false) - , m_initialValues(nullptr) - , m_reference(nullptr) - {} - - unsigned MinimumJerkTrajectoryGenerator::numberOfParameters() { return 7; } - - bool MinimumJerkTrajectoryGenerator::configureSizeAndPorts(BlockInformation* blockInfo) - { - // PARAMETERS - // ========== - // - // 1) Sample time (double) - // 2) Settling time (double) - // 3) Enable the output of 1st derivative (bool) - // 4) Enable the output of 2nd derivative (bool) - // 5) Enable the input with the initial conditions (bool) - // 6) Enable the input with the external settling time (bool) - // 7) Reset the trajectory generator when settling time changes (bool) - // - - bool outputFirstDerivative; - bool outputSecondDerivative; - bool explicitInitialValue; - bool externalSettlingTime; - bool ok = true; - - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, outputFirstDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, outputSecondDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, explicitInitialValue); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, externalSettlingTime); - - if (!ok) { - Log::getSingleton().error("Failed to get input parameters."); - return false; - } +using namespace wbt; + +const std::string MinimumJerkTrajectoryGenerator::ClassName = "MinimumJerkTrajectoryGenerator"; + +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_SAMPLE_TIME = 1; +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_SETTLING_TIME = 2; +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_OUTPUT_1ST_DERIVATIVE = 3; +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_OUTPUT_2ND_DERIVATIVE = 4; +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_INITIAL_VALUE = 5; +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_EXT_SETTLINGTIME = 6; +const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_RESET_CHANGEST = 7; + +MinimumJerkTrajectoryGenerator::MinimumJerkTrajectoryGenerator() +: m_generator(nullptr) +, m_outputFirstDerivativeIndex(-1) +, m_outputSecondDerivativeIndex(-1) +, m_firstRun(true) +, m_explicitInitialValue(false) +, m_externalSettlingTime(false) +, m_resetOnSettlingTimeChange(false) +, m_initialValues(nullptr) +, m_reference(nullptr) +{} + +unsigned MinimumJerkTrajectoryGenerator::numberOfParameters() { return 7; } + +bool MinimumJerkTrajectoryGenerator::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // PARAMETERS + // ========== + // + // 1) Sample time (double) + // 2) Settling time (double) + // 3) Enable the output of 1st derivative (bool) + // 4) Enable the output of 2nd derivative (bool) + // 5) Enable the input with the initial conditions (bool) + // 6) Enable the input with the external settling time (bool) + // 7) Reset the trajectory generator when settling time changes (bool) + // + + bool outputFirstDerivative; + bool outputSecondDerivative; + bool explicitInitialValue; + bool externalSettlingTime; + bool ok = true; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, outputFirstDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, outputSecondDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, explicitInitialValue); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, externalSettlingTime); + + if (!ok) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } - int numberOfInputPorts = 1; - numberOfInputPorts += static_cast(explicitInitialValue); - numberOfInputPorts += static_cast(externalSettlingTime); - - // INPUTS - // ====== - // - // 1) The reference signal (1xn) - // 2) The optional initial conditions - // 3) The optional settling time - // - - if(!blockInfo->setNumberOfInputPorts(numberOfInputPorts)) { - Log::getSingleton().error("Failed to set input port number."); - return false; - } + int numberOfInputPorts = 1; + numberOfInputPorts += static_cast(explicitInitialValue); + numberOfInputPorts += static_cast(externalSettlingTime); + + // INPUTS + // ====== + // + // 1) The reference signal (1xn) + // 2) The optional initial conditions + // 3) The optional settling time + // + + if(!blockInfo->setNumberOfInputPorts(numberOfInputPorts)) { + Log::getSingleton().error("Failed to set input port number."); + return false; + } - blockInfo->setInputPortVectorSize(0, -1); - blockInfo->setInputPortType(0, PortDataTypeDouble); + blockInfo->setInputPortVectorSize(0, -1); + blockInfo->setInputPortType(0, PortDataTypeDouble); - unsigned portIndex = 1; + unsigned portIndex = 1; - if (explicitInitialValue) { - blockInfo->setInputPortVectorSize(portIndex, -1); - blockInfo->setInputPortType(portIndex, PortDataTypeDouble); - portIndex++; - } - - if (externalSettlingTime) { - blockInfo->setInputPortVectorSize(portIndex, 1); - blockInfo->setInputPortType(portIndex, PortDataTypeDouble); - portIndex++; - } + if (explicitInitialValue) { + blockInfo->setInputPortVectorSize(portIndex, -1); + blockInfo->setInputPortType(portIndex, PortDataTypeDouble); + portIndex++; + } - // OUTPUTS - // ======= - // - // 1) The calculated trajectory - // 2) The optional 1st derivative - // 3) The optional 2nd derivative - // - - int numberOfOutputPorts = 1; - numberOfOutputPorts += static_cast(outputFirstDerivative); - numberOfOutputPorts += static_cast(outputSecondDerivative); - - if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } + if (externalSettlingTime) { + blockInfo->setInputPortVectorSize(portIndex, 1); + blockInfo->setInputPortType(portIndex, PortDataTypeDouble); + portIndex++; + } - for (int i = 0; i < numberOfOutputPorts; ++i) { - blockInfo->setOutputPortVectorSize(i, -1); - blockInfo->setOutputPortType(i, PortDataTypeDouble); - } + // OUTPUTS + // ======= + // + // 1) The calculated trajectory + // 2) The optional 1st derivative + // 3) The optional 2nd derivative + // + + int numberOfOutputPorts = 1; + numberOfOutputPorts += static_cast(outputFirstDerivative); + numberOfOutputPorts += static_cast(outputSecondDerivative); + + if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { + Log::getSingleton().error("Failed to set output port number."); + return false; + } - return true; + for (int i = 0; i < numberOfOutputPorts; ++i) { + blockInfo->setOutputPortVectorSize(i, -1); + blockInfo->setOutputPortType(i, PortDataTypeDouble); } - bool MinimumJerkTrajectoryGenerator::initialize(BlockInformation* blockInfo) - { - // Get the additional parameters - bool outputFirstDerivative; - bool outputSecondDerivative; - bool ok = true; - - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, - outputFirstDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, - outputSecondDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, m_explicitInitialValue); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, m_externalSettlingTime); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_RESET_CHANGEST, - m_resetOnSettlingTimeChange); - - if (!ok) { - Log::getSingleton().error("Failed to get input parameters."); - return false; - } + return true; +} - if (outputFirstDerivative) { - m_outputFirstDerivativeIndex = 1; - } +bool MinimumJerkTrajectoryGenerator::initialize(const BlockInformation* blockInfo) +{ + // Get the additional parameters + bool outputFirstDerivative; + bool outputSecondDerivative; + bool ok = true; + + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, + outputFirstDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, + outputSecondDerivative); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, m_explicitInitialValue); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, m_externalSettlingTime); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_RESET_CHANGEST, + m_resetOnSettlingTimeChange); + + if (!ok) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } - if (outputSecondDerivative) { - m_outputSecondDerivativeIndex = outputFirstDerivative ? 2 : 1; - } + if (outputFirstDerivative) { + m_outputFirstDerivativeIndex = 1; + } - double sampleTime; - double settlingTime; + if (outputSecondDerivative) { + m_outputSecondDerivativeIndex = outputFirstDerivative ? 2 : 1; + } - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SAMPLE_TIME, sampleTime); - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SETTLING_TIME, settlingTime); + double sampleTime; + double settlingTime; - unsigned signalSize = blockInfo->getInputPortWidth(0); + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SAMPLE_TIME, sampleTime); + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SETTLING_TIME, settlingTime); - m_generator = new iCub::ctrl::minJerkTrajGen(signalSize, sampleTime, settlingTime); - m_previousSettlingTime = settlingTime; - m_initialValues = new yarp::sig::Vector(signalSize); - m_reference = new yarp::sig::Vector(signalSize); + unsigned signalSize = blockInfo->getInputPortWidth(0); - if (!m_generator || !m_initialValues || !m_reference) { - Log::getSingleton().error("Could not allocate memory for trajectory generator."); - return false; - } + m_generator = new iCub::ctrl::minJerkTrajGen(signalSize, sampleTime, settlingTime); + m_previousSettlingTime = settlingTime; + m_initialValues = new yarp::sig::Vector(signalSize); + m_reference = new yarp::sig::Vector(signalSize); - m_firstRun = true; - return true; + if (!m_generator || !m_initialValues || !m_reference) { + Log::getSingleton().error("Could not allocate memory for trajectory generator."); + return false; } - bool MinimumJerkTrajectoryGenerator::terminate(BlockInformation* blockInfo) - { - if (m_generator) { - delete m_generator; - m_generator = nullptr; - } - if (m_initialValues) { - delete m_initialValues; - m_initialValues = nullptr; - } - if (m_reference) { - delete m_reference; - m_reference = nullptr; - } - return true; + m_firstRun = true; + return true; +} + +bool MinimumJerkTrajectoryGenerator::terminate(const BlockInformation* blockInfo) +{ + if (m_generator) { + delete m_generator; + m_generator = nullptr; } + if (m_initialValues) { + delete m_initialValues; + m_initialValues = nullptr; + } + if (m_reference) { + delete m_reference; + m_reference = nullptr; + } + return true; +} - bool MinimumJerkTrajectoryGenerator::output(BlockInformation* blockInfo) - { - if (!m_generator) return false; +bool MinimumJerkTrajectoryGenerator::output(const BlockInformation* blockInfo) +{ + if (!m_generator) return false; - if (m_externalSettlingTime) { - unsigned portIndex = 1; - if (m_explicitInitialValue) portIndex++; - Signal externalTimePort = blockInfo->getInputPortSignal(portIndex); - double externalTime = externalTimePort.get(0).doubleData(); + if (m_externalSettlingTime) { + unsigned portIndex = 1; + if (m_explicitInitialValue) portIndex++; + Signal externalTimePort = blockInfo->getInputPortSignal(portIndex); + double externalTime = externalTimePort.get(0).doubleData(); - if (std::abs(m_previousSettlingTime - externalTime) > 1e-5) { - m_previousSettlingTime = externalTime; + if (std::abs(m_previousSettlingTime - externalTime) > 1e-5) { + m_previousSettlingTime = externalTime; - m_generator->setT(externalTime); - if (m_resetOnSettlingTimeChange && !m_firstRun) { - m_generator->init(m_generator->getPos()); - } + m_generator->setT(externalTime); + if (m_resetOnSettlingTimeChange && !m_firstRun) { + m_generator->init(m_generator->getPos()); } } + } - if (m_firstRun) { - m_firstRun = false; - Signal initialValues; - unsigned portIndex = 0; - if (m_explicitInitialValue) { - portIndex = 1; - } - initialValues = blockInfo->getInputPortSignal(portIndex); - for (unsigned i = 0; i < blockInfo->getInputPortWidth(portIndex); ++i) { - (*m_initialValues)[i] = initialValues.get(i).doubleData(); - } - m_generator->init(*m_initialValues); + if (m_firstRun) { + m_firstRun = false; + Signal initialValues; + unsigned portIndex = 0; + if (m_explicitInitialValue) { + portIndex = 1; + } + initialValues = blockInfo->getInputPortSignal(portIndex); + for (unsigned i = 0; i < blockInfo->getInputPortWidth(portIndex); ++i) { + (*m_initialValues)[i] = initialValues.get(i).doubleData(); } + m_generator->init(*m_initialValues); + } - Signal references = blockInfo->getInputPortSignal(0); - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - (*m_reference)[i] = references.get(i).doubleData(); - } - m_generator->computeNextValues(*m_reference); + Signal references = blockInfo->getInputPortSignal(0); + for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { + (*m_reference)[i] = references.get(i).doubleData(); + } + m_generator->computeNextValues(*m_reference); - const yarp::sig::Vector &signal = m_generator->getPos(); - Signal output = blockInfo->getOutputPortSignal(0); - output.setBuffer(signal.data(), signal.size()); + const yarp::sig::Vector &signal = m_generator->getPos(); + Signal output = blockInfo->getOutputPortSignal(0); + output.setBuffer(signal.data(), signal.size()); // for (unsigned i = 0; i < blockInfo->getOutputPortWidth(0); ++i) { // output.set(i, signal[i]); // } - //note: index of the port is not known a priori. - //I should save it in the initialization phase - if (m_outputFirstDerivativeIndex != -1) { - const yarp::sig::Vector &derivative = m_generator->getVel(); - Signal derivativeOutput = blockInfo->getOutputPortSignal(m_outputFirstDerivativeIndex); - derivativeOutput.setBuffer(derivative.data(), blockInfo->getOutputPortWidth(m_outputFirstDerivativeIndex)); - } - - if (m_outputSecondDerivativeIndex != -1) { - const yarp::sig::Vector &derivative = m_generator->getAcc(); - Signal derivativeOutput = blockInfo->getOutputPortSignal(m_outputSecondDerivativeIndex); - derivativeOutput.setBuffer(derivative.data(), blockInfo->getOutputPortWidth(m_outputSecondDerivativeIndex)); - } + //note: index of the port is not known a priori. + //I should save it in the initialization phase + if (m_outputFirstDerivativeIndex != -1) { + const yarp::sig::Vector &derivative = m_generator->getVel(); + Signal derivativeOutput = blockInfo->getOutputPortSignal(m_outputFirstDerivativeIndex); + derivativeOutput.setBuffer(derivative.data(), blockInfo->getOutputPortWidth(m_outputFirstDerivativeIndex)); + } - return true; + if (m_outputSecondDerivativeIndex != -1) { + const yarp::sig::Vector &derivative = m_generator->getAcc(); + Signal derivativeOutput = blockInfo->getOutputPortSignal(m_outputSecondDerivativeIndex); + derivativeOutput.setBuffer(derivative.data(), blockInfo->getOutputPortWidth(m_outputSecondDerivativeIndex)); } + return true; } diff --git a/toolbox/src/ModelPartitioner.cpp b/toolbox/src/ModelPartitioner.cpp index bedee09c9..2c54458bd 100644 --- a/toolbox/src/ModelPartitioner.cpp +++ b/toolbox/src/ModelPartitioner.cpp @@ -6,192 +6,176 @@ #include "Signal.h" #include "Log.h" -namespace wbt { +using namespace wbt; - const std::string ModelPartitioner::ClassName = "ModelPartitioner"; +const std::string ModelPartitioner::ClassName = "ModelPartitioner"; - unsigned ModelPartitioner::numberOfParameters() - { - return 1; - } +unsigned ModelPartitioner::numberOfParameters() +{ + return 1; +} - bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) - { - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; +bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) +{ + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // PARAMETERS - // ========== - // - // 1) Boolean specifying if yarp2WBI (true) or WBI2yarp (false) - // + // PARAMETERS + // ========== + // + // 1) Boolean specifying if yarp2WBI (true) or WBI2yarp (false) + // - bool yarp2WBI; - if (!blockInfo->getBooleanParameterAtIndex(1, yarp2WBI)) { - Log::getSingleton().error("Failed to get input parameters."); - return false; - } + bool yarp2WBI; + if (!blockInfo->getBooleanParameterAtIndex(1, yarp2WBI)) { + Log::getSingleton().error("Failed to get input parameters."); + return false; + } - // TODO: update to new logic - // INPUTS - // ====== - // - // yarp2WBI - // -------- - // - // 1) Map of joints / control boards (1 x nJoints) - // 2) Vector containing the full set of robot's joints (1 x nJoints) - // - // WBI2yarp - // -------- - // - // 1) Map of joints / control boards (1 x nJoints) - // 2) Torso Control Board Signals - // 3) Head Control Board Signals - // 4) Left Arm Control Board Signals - // 5) Right Arm Control Board Signals - // 6) Left Leg Control Board Signals - // 7) Right Leg Control Board Signals - // - - bool ok; - unsigned numberOfInputs; - unsigned controlBoardsNumber = getConfiguration().getControlBoardsNames().size(); - - if (yarp2WBI) { - numberOfInputs = 1; - ok = blockInfo->setNumberOfInputPorts(numberOfInputs); - blockInfo->setInputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); - } - else { - numberOfInputs = controlBoardsNumber; - ok = blockInfo->setNumberOfInputPorts(numberOfInputs); - // Set the size as dynamic - for (unsigned i = 0; i < numberOfInputs; ++i) { - blockInfo->setInputPortType(i, PortDataTypeDouble); - } + // INPUTS + // ====== + // + // yarp2WBI + // -------- + // + // 1) Vector containing the data vector (1 x DoFs) + // + // WBI2yarp + // -------- + // + // n signals) The n ControlBoards configured from the config block + // + + bool ok; + unsigned numberOfInputs; + unsigned controlBoardsNumber = getConfiguration().getControlBoardsNames().size(); + + if (yarp2WBI) { + numberOfInputs = 1; + ok = blockInfo->setNumberOfInputPorts(numberOfInputs); + blockInfo->setInputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); + } + else { + numberOfInputs = controlBoardsNumber; + ok = blockInfo->setNumberOfInputPorts(numberOfInputs); + // Set the size as dynamic + for (unsigned i = 0; i < numberOfInputs; ++i) { + blockInfo->setInputPortType(i, PortDataTypeDouble); } + } - if (!ok) { - Log::getSingleton().error("Failed to set input port number."); - return false; + if (!ok) { + Log::getSingleton().error("Failed to set input port number."); + return false; + } + + // OUTPUTS + // ======= + // + // yarp2WBI + // -------- + // + // n signals) The n ControlBoards configured from the config block + // + // WBI2yarp + // -------- + // + // 1) Vector containing the data vector (1 x DoFs) + // + + unsigned numberOfOutputs; + + if (yarp2WBI) { + numberOfOutputs = controlBoardsNumber; + ok = blockInfo->setNumberOfOutputPorts(numberOfOutputs); + // Set the size as dynamic + for (unsigned i = 0; i < numberOfOutputs; ++i) { + blockInfo->setOutputPortVectorSize(i, -1); + blockInfo->setOutputPortType(i, PortDataTypeDouble); } + } + else { + numberOfOutputs = 1; + ok = blockInfo->setNumberOfOutputPorts(numberOfOutputs); + blockInfo->setOutputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); + blockInfo->setOutputPortType(0, PortDataTypeDouble); + } + if (!ok) { + Log::getSingleton().error("Failed to set output port number."); + return false; + } - // TODO: update - // OUTPUTS - // ======= - // - // yarp2WBI - // -------- - // - // 1) Torso Control Board Signals - // 2) Head Control Board Signals - // 3) Left Arm Control Board Signals - // 4) Right Arm Control Board Signals - // 5) Left Leg Control Board Signals - // 6) Right Leg Control Board Signals - // - // WBI2yarp - // -------- - // - // 1) Vector containing the full set of robot's joints (1 x nJoints) - // - - unsigned numberOfOutputs; - - if (yarp2WBI) { - numberOfOutputs = controlBoardsNumber; - ok = blockInfo->setNumberOfOutputPorts(numberOfOutputs); - // Set the size as dynamic - for (unsigned i = 0; i < numberOfOutputs; ++i) { - blockInfo->setOutputPortVectorSize(i, -1); - blockInfo->setOutputPortType(i, PortDataTypeDouble); - } - } - else { - numberOfOutputs = 1; - ok = blockInfo->setNumberOfOutputPorts(numberOfOutputs); - blockInfo->setOutputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); - blockInfo->setOutputPortType(0, PortDataTypeDouble); - } + return true; +} - if (!ok) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } +bool ModelPartitioner::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - return true; + if (!blockInfo->getBooleanParameterAtIndex(1, m_yarp2WBI)) { + Log::getSingleton().error("Failed to get input parameters."); + return false; } - bool ModelPartitioner::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + m_jointsMapString = getRobotInterface()->getJointsMapString(); - if (!blockInfo->getBooleanParameterAtIndex(1, m_yarp2WBI)) { - Log::getSingleton().error("Failed to get input parameters."); - return false; - } + if (!m_jointsMapString) { + return false; + } - m_jointsMapString = getRobotInterface()->getJointsMapString(); + return true; +} - if (!m_jointsMapString) { - return false; - } +bool ModelPartitioner::terminate(const BlockInformation* blockInfo) +{ + return WBBlock::terminate(blockInfo); +} - return true; - } +bool ModelPartitioner::output(const BlockInformation* blockInfo) +{ + if (m_yarp2WBI) { + // Input + Signal jointListSignal = blockInfo->getInputPortSignal(0); - bool ModelPartitioner::terminate(BlockInformation* blockInfo) - { - return WBBlock::terminate(blockInfo); - } + // Outputs + Signal ithControlBoardSignal; - bool ModelPartitioner::output(BlockInformation* blockInfo) - { - if (m_yarp2WBI) { - // Input - Signal jointListSignal = blockInfo->getInputPortSignal(0); - - // Outputs - Signal ithControlBoardSignal; - - for (unsigned ithJoint = 0; ithJoint < blockInfo->getInputPortWidth(0); ++ithJoint) { - // Get the ControlBoard number the ith joint belongs, and its index into the CB itself - std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; - const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); - cb_idx controlBoardOfJoint = mappedJointInfos.first; - jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; - - // Get the data to forward - Data value = jointListSignal.get(ithJoint); - - // Forward the value to the correct output / output index - ithControlBoardSignal = blockInfo->getOutputPortSignal(controlBoardOfJoint); - ithControlBoardSignal.set(yarpIndexOfJoint, value.doubleData()); - } + for (unsigned ithJoint = 0; ithJoint < blockInfo->getInputPortWidth(0); ++ithJoint) { + // Get the ControlBoard number the ith joint belongs, and its index into the CB itself + std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; + const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); + cb_idx controlBoardOfJoint = mappedJointInfos.first; + jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; + + // Get the data to forward + Data value = jointListSignal.get(ithJoint); + + // Forward the value to the correct output / output index + ithControlBoardSignal = blockInfo->getOutputPortSignal(controlBoardOfJoint); + ithControlBoardSignal.set(yarpIndexOfJoint, value.doubleData()); } - else { - // Inputs - Signal ithControlBoardSignal; - - // Output - Signal jointListSignal = blockInfo->getOutputPortSignal(0); - - for (unsigned ithJoint = 0; ithJoint < blockInfo->getOutputPortWidth(0); ++ithJoint) { - // Get the ControlBoard number the ith joint belongs, and its index into the CB itself - std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; - const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); - cb_idx controlBoardOfJoint = mappedJointInfos.first; - jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; - - // Get the data to forward - ithControlBoardSignal = blockInfo->getInputPortSignal(controlBoardOfJoint); - Data value = ithControlBoardSignal.get(ithJoint); - - // Forward the value to the correct output index - jointListSignal.set(yarpIndexOfJoint, value.doubleData()); - } + } + else { + // Inputs + Signal ithControlBoardSignal; + + // Output + Signal jointListSignal = blockInfo->getOutputPortSignal(0); + + for (unsigned ithJoint = 0; ithJoint < blockInfo->getOutputPortWidth(0); ++ithJoint) { + // Get the ControlBoard number the ith joint belongs, and its index into the CB itself + std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; + const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); + cb_idx controlBoardOfJoint = mappedJointInfos.first; + jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; + + // Get the data to forward + ithControlBoardSignal = blockInfo->getInputPortSignal(controlBoardOfJoint); + Data value = ithControlBoardSignal.get(ithJoint); + + // Forward the value to the correct output index + jointListSignal.set(yarpIndexOfJoint, value.doubleData()); } - return true; } + return true; } diff --git a/toolbox/src/RealTimeSynchronizer.cpp b/toolbox/src/RealTimeSynchronizer.cpp index 752674d44..62701a38c 100644 --- a/toolbox/src/RealTimeSynchronizer.cpp +++ b/toolbox/src/RealTimeSynchronizer.cpp @@ -4,87 +4,86 @@ #include -namespace wbt { +using namespace wbt; - const std::string RealTimeSynchronizer::ClassName = "RealTimeSynchronizer"; +const std::string RealTimeSynchronizer::ClassName = "RealTimeSynchronizer"; - const unsigned RealTimeSynchronizer::PARAM_PERIOD = 1; // Period +const unsigned RealTimeSynchronizer::PARAM_PERIOD = 1; // Period - RealTimeSynchronizer::RealTimeSynchronizer() - : m_period(0.01) - , m_initialTime(0) - , m_counter(0) - {} +RealTimeSynchronizer::RealTimeSynchronizer() +: m_period(0.01) +, m_initialTime(0) +, m_counter(0) +{} - unsigned RealTimeSynchronizer::numberOfParameters() { return 1; } +unsigned RealTimeSynchronizer::numberOfParameters() { return 1; } - bool RealTimeSynchronizer::configureSizeAndPorts(BlockInformation* blockInfo) - { - // INPUTS - // ====== - // - // No inputs - // +bool RealTimeSynchronizer::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // INPUTS + // ====== + // + // No inputs + // - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to set input port number to 0."); - return false; - } - - // OUTPUTS - // ======= - // - // No outputs - // + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to set input port number to 0."); + return false; + } - if (!blockInfo->setNumberOfOutputPorts(0)) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } + // OUTPUTS + // ======= + // + // No outputs + // - return true; + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to set output port number."); + return false; } - bool RealTimeSynchronizer::initialize(BlockInformation* blockInfo) - { - if (!blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period)) { - Log::getSingleton().error("Failed to get input parametes."); - return false; - } - - if (m_period < 0) { - Log::getSingleton().error("Period must be greater than 0."); - return false; - } + return true; +} - m_counter = 0; - return true; +bool RealTimeSynchronizer::initialize(const BlockInformation* blockInfo) +{ + if (!blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period)) { + Log::getSingleton().error("Failed to get input parametes."); + return false; } - bool RealTimeSynchronizer::terminate(BlockInformation* blockInfo) - { - return true; + if (m_period < 0) { + Log::getSingleton().error("Period must be greater than 0."); + return false; } - bool RealTimeSynchronizer::output(BlockInformation* blockInfo) - { - if (m_counter == 0) { - m_initialTime = yarp::os::Time::now(); - } + m_counter = 0; + return true; +} - //read current time - double currentTime = yarp::os::Time::now() - m_initialTime; - double desiredTime = m_counter* m_period; +bool RealTimeSynchronizer::terminate(const BlockInformation* blockInfo) +{ + return true; +} - double sleepPeriod = desiredTime - currentTime; +bool RealTimeSynchronizer::output(const BlockInformation* blockInfo) +{ + if (m_counter == 0) { + m_initialTime = yarp::os::Time::now(); + } - //sleep for the remaining time - if (sleepPeriod > 0) { - yarp::os::Time::delay(sleepPeriod); - } + //read current time + double currentTime = yarp::os::Time::now() - m_initialTime; + double desiredTime = m_counter* m_period; - m_counter++; + double sleepPeriod = desiredTime - currentTime; - return true; + //sleep for the remaining time + if (sleepPeriod > 0) { + yarp::os::Time::delay(sleepPeriod); } + + m_counter++; + + return true; } diff --git a/toolbox/src/SetLowLevelPID.cpp b/toolbox/src/SetLowLevelPID.cpp index 9448b4eb0..b2d9772c4 100644 --- a/toolbox/src/SetLowLevelPID.cpp +++ b/toolbox/src/SetLowLevelPID.cpp @@ -6,235 +6,234 @@ #include #include -namespace wbt { +using namespace wbt; - const std::string SetLowLevelPID::ClassName = "SetLowLevelPID"; +const std::string SetLowLevelPID::ClassName = "SetLowLevelPID"; - unsigned SetLowLevelPID::numberOfParameters() - { - return WBBlock::numberOfParameters() - + 1 // WBTPIDConfig object - + 1; // Control type - } +unsigned SetLowLevelPID::numberOfParameters() +{ + return WBBlock::numberOfParameters() + + 1 // WBTPIDConfig object + + 1; // Control type +} - bool SetLowLevelPID::configureSizeAndPorts(BlockInformation* blockInfo) - { - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; +bool SetLowLevelPID::configureSizeAndPorts(BlockInformation* blockInfo) +{ + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; - // INPUTS - // ====== - // - // No inputs - // + // INPUTS + // ====== + // + // No inputs + // - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; + } - // OUTPUTS - // ======= - // - // No outputs - // + // OUTPUTS + // ======= + // + // No outputs + // - if (!blockInfo->setNumberOfOutputPorts(0)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } + + return true; +} - return true; +bool SetLowLevelPID::readWBTPidConfigObject(const BlockInformation* blockInfo) +{ + AnyStruct s; + if (!blockInfo->getStructAtIndex(WBBlock::numberOfParameters() + 1, s)) { + Log::getSingleton().error("Failed to retrieve the struct with parameters."); + return false; } - bool SetLowLevelPID::readWBTPidConfigObject(BlockInformation* blockInfo) - { - AnyStruct s; - if (!blockInfo->getStructAtIndex(WBBlock::numberOfParameters() + 1, s)) { - Log::getSingleton().error("Failed to retrieve the struct with parameters."); - return false; - } + // Check the existence of all the fields + try { + s.at("P"); + s.at("I"); + s.at("D"); + s.at("jointList"); + } + catch (const std::out_of_range& e) { + Log::getSingleton().error("Cannot retrieve one or more parameter from parameter's struct."); + return false; + } - // Check the existence of all the fields - try { - s.at("P"); - s.at("I"); - s.at("D"); - s.at("jointList"); - } - catch (const std::out_of_range& e) { - Log::getSingleton().error("Cannot retrieve one or more parameter from parameter's struct."); - return false; - } + // Proportional gains + std::vector Pvector; + if (!s["P"]->asVectorDouble(Pvector)) { + Log::getSingleton().error("Cannot retrieve vector from P parameter."); + return false; + } - // Proportional gains - std::vector Pvector; - if (!s["P"]->asVectorDouble(Pvector)) { - Log::getSingleton().error("Cannot retrieve vector from P parameter."); - return false; - } + // Integral gains + std::vector Ivector; + if (!s["I"]->asVectorDouble(Ivector)) { + Log::getSingleton().error("Cannot retrieve vector from I parameter."); + return false; + } - // Integral gains - std::vector Ivector; - if (!s["I"]->asVectorDouble(Ivector)) { - Log::getSingleton().error("Cannot retrieve vector from I parameter."); - return false; - } + // Derivative gains + std::vector Dvector; + if (!s["D"]->asVectorDouble(Dvector)) { + Log::getSingleton().error("Cannot retrieve vector from D parameter."); + return false; + } - // Derivative gains - std::vector Dvector; - if (!s["D"]->asVectorDouble(Dvector)) { - Log::getSingleton().error("Cannot retrieve vector from D parameter."); - return false; - } + // Considered joint names + AnyCell jointPidsCell; + if (!s["jointList"]->asAnyCell(jointPidsCell)) { + Log::getSingleton().error("Cannot retrieve string from jointList parameter."); + return false; + } - // Considered joint names - AnyCell jointPidsCell; - if (!s["jointList"]->asAnyCell(jointPidsCell)) { - Log::getSingleton().error("Cannot retrieve string from jointList parameter."); + // From AnyCell to vector + std::vector jointNamesFromParameters; + for (auto cell: jointPidsCell) { + std::string joint; + if (!cell->asString(joint)) { + Log::getSingleton().error("Failed to convert jointList from cell to strings."); return false; } + jointNamesFromParameters.push_back(joint); + } - // From AnyCell to vector - std::vector jointNamesFromParameters; - for (auto cell: jointPidsCell) { - std::string joint; - if (!cell->asString(joint)) { - Log::getSingleton().error("Failed to convert jointList from cell to strings."); - return false; - } - jointNamesFromParameters.push_back(joint); - } - - assert(Pvector.size() == Ivector.size() == Dvector.size() == jointNamesFromParameters.size()); - - // Store this data into a private member map - for (unsigned i = 0; i < jointNamesFromParameters.size(); ++i) { - // Check the processed joint is actually a controlledJoint - const auto& controlledJoints = getConfiguration().getControlledJoints(); - auto findElement = std::find(std::begin(controlledJoints), - std::end(controlledJoints), - jointNamesFromParameters[i]); - if (findElement != std::end(controlledJoints)) { - m_pidJointsFromParameters[jointNamesFromParameters[i]] = {Pvector[i], Ivector[i], Dvector[i]}; - } - else { - Log::getSingleton().warning("Attempted to set PID of joint " + jointNamesFromParameters[i] + - " non currently controlled. Skipping it."); - } + assert(Pvector.size() == Ivector.size() == Dvector.size() == jointNamesFromParameters.size()); + // Store this data into a private member map + for (unsigned i = 0; i < jointNamesFromParameters.size(); ++i) { + // Check the processed joint is actually a controlledJoint + const auto& controlledJoints = getConfiguration().getControlledJoints(); + auto findElement = std::find(std::begin(controlledJoints), + std::end(controlledJoints), + jointNamesFromParameters[i]); + if (findElement != std::end(controlledJoints)) { + m_pidJointsFromParameters[jointNamesFromParameters[i]] = {Pvector[i], Ivector[i], Dvector[i]}; } - - if (m_pidJointsFromParameters.size() != jointNamesFromParameters.size()) { - Log::getSingleton().warning("PID have been passed only for a subset of the controlled joints."); + else { + Log::getSingleton().warning("Attempted to set PID of joint " + jointNamesFromParameters[i] + + " non currently controlled. Skipping it."); } - return true; } - bool SetLowLevelPID::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; - - // Reading the control type - std::string controlType; - if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 2, controlType)) { - Log::getSingleton().error("Could not read control type parameter."); - return false; - } + if (m_pidJointsFromParameters.size() != jointNamesFromParameters.size()) { + Log::getSingleton().warning("PID have been passed only for a subset of the controlled joints."); + } - if (controlType == "Position") { - m_controlType = yarp::dev::VOCAB_PIDTYPE_POSITION; - } - else if (controlType == "Torque") { - m_controlType = yarp::dev::VOCAB_PIDTYPE_TORQUE; - } - else { - Log::getSingleton().error("Control type not recognized."); - return false; - } + return true; +} - // Reading the WBTPIDConfig matlab class - if (!readWBTPidConfigObject(blockInfo)) { - Log::getSingleton().error("Failed to parse the WBTPIDConfig object."); - return 1; - } +bool SetLowLevelPID::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - // Retain the RemoteControlBoardRemapper - if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to retain the control board remapper."); - return false; - } + // Reading the control type + std::string controlType; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 2, controlType)) { + Log::getSingleton().error("Could not read control type parameter."); + return false; + } - const unsigned& dofs = getConfiguration().getNumberOfDoFs(); + if (controlType == "Position") { + m_controlType = yarp::dev::VOCAB_PIDTYPE_POSITION; + } + else if (controlType == "Torque") { + m_controlType = yarp::dev::VOCAB_PIDTYPE_TORQUE; + } + else { + Log::getSingleton().error("Control type not recognized."); + return false; + } - // Initialize the vector size to the number of dofs - m_defaultPidValues.resize(dofs); + // Reading the WBTPIDConfig matlab class + if (!readWBTPidConfigObject(blockInfo)) { + Log::getSingleton().error("Failed to parse the WBTPIDConfig object."); + return 1; + } - // Get the interface - std::weak_ptr iPidControl; - if (!getRobotInterface()->getInterface(iPidControl)) { - Log::getSingleton().error("Failed to get IPidControl interface."); - return false; - } + // Retain the RemoteControlBoardRemapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to retain the control board remapper."); + return false; + } - // Store the default gains - if (!iPidControl.lock()->getPids(m_controlType, m_defaultPidValues.data())) { - Log::getSingleton().error("Failed to get default data from IPidControl."); - return false; - } + const unsigned& dofs = getConfiguration().getNumberOfDoFs(); - // Initialize the vector of the applied pid gains with the default gains - m_appliedPidValues = m_defaultPidValues; - - // Override the PID with the gains specified as block parameters - for (unsigned i = 0; i < dofs; ++i) { - const std::string jointName = getConfiguration().getControlledJoints()[i]; - // If the pid has been passed, set the new gains - if (m_pidJointsFromParameters.find(jointName) != m_pidJointsFromParameters.end()) { - PidData gains = m_pidJointsFromParameters[jointName]; - m_appliedPidValues[i].setKp(std::get(gains)); - m_appliedPidValues[i].setKi(std::get(gains)); - m_appliedPidValues[i].setKd(std::get(gains)); - } - } + // Initialize the vector size to the number of dofs + m_defaultPidValues.resize(dofs); - // Apply the new pid gains - if (!iPidControl.lock()->setPids(m_controlType, m_appliedPidValues.data())) { - Log::getSingleton().error("Failed to set PID values."); - return false; - } + // Get the interface + std::weak_ptr iPidControl; + if (!getRobotInterface()->getInterface(iPidControl)) { + Log::getSingleton().error("Failed to get IPidControl interface."); + return false; + } - return true; + // Store the default gains + if (!iPidControl.lock()->getPids(m_controlType, m_defaultPidValues.data())) { + Log::getSingleton().error("Failed to get default data from IPidControl."); + return false; } - bool SetLowLevelPID::terminate(BlockInformation* blockInfo) - { - bool ok = true; + // Initialize the vector of the applied pid gains with the default gains + m_appliedPidValues = m_defaultPidValues; - // Get the IPidControl interface - std::weak_ptr iPidControl; - ok = ok & getRobotInterface()->getInterface(iPidControl); - if (!ok) { - Log::getSingleton().error("Failed to get IPidControl interface."); + // Override the PID with the gains specified as block parameters + for (unsigned i = 0; i < dofs; ++i) { + const std::string jointName = getConfiguration().getControlledJoints()[i]; + // If the pid has been passed, set the new gains + if (m_pidJointsFromParameters.find(jointName) != m_pidJointsFromParameters.end()) { + PidData gains = m_pidJointsFromParameters[jointName]; + m_appliedPidValues[i].setKp(std::get(gains)); + m_appliedPidValues[i].setKi(std::get(gains)); + m_appliedPidValues[i].setKd(std::get(gains)); } + } - // Reset default pid gains - ok = ok & iPidControl.lock()->setPids(m_controlType, m_defaultPidValues.data()); - if (!ok) { - Log::getSingleton().error("Failed to set default PID values."); - } + // Apply the new pid gains + if (!iPidControl.lock()->setPids(m_controlType, m_appliedPidValues.data())) { + Log::getSingleton().error("Failed to set PID values."); + return false; + } - // Release the RemoteControlBoardRemapper - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); - if (!ok) { - Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); - } + return true; +} + +bool SetLowLevelPID::terminate(const BlockInformation* blockInfo) +{ + bool ok = true; + + // Get the IPidControl interface + std::weak_ptr iPidControl; + ok = ok & getRobotInterface()->getInterface(iPidControl); + if (!ok) { + Log::getSingleton().error("Failed to get IPidControl interface."); + } - return ok && WBBlock::terminate(blockInfo); + // Reset default pid gains + ok = ok & iPidControl.lock()->setPids(m_controlType, m_defaultPidValues.data()); + if (!ok) { + Log::getSingleton().error("Failed to set default PID values."); } - bool SetLowLevelPID::output(BlockInformation* blockInfo) - { - return true; + // Release the RemoteControlBoardRemapper + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); } + + return ok && WBBlock::terminate(blockInfo); +} + +bool SetLowLevelPID::output(const BlockInformation* blockInfo) +{ + return true; } diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 3858a55a5..c739b0e44 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -9,266 +9,265 @@ #define _USE_MATH_DEFINES #include -namespace wbt { +using namespace wbt; - const std::string SetReferences::ClassName = "SetReferences"; +const std::string SetReferences::ClassName = "SetReferences"; - SetReferences::SetReferences() - : m_resetControlMode(true) - {} +SetReferences::SetReferences() +: m_resetControlMode(true) +{} - void rad2deg(std::vector& v) - { - const double rad2deg = 180.0 / (2 * M_PI); - for (auto& element : v) { - element *= rad2deg; - } +void rad2deg(std::vector& v) +{ + const double rad2deg = 180.0 / (2 * M_PI); + for (auto& element : v) { + element *= rad2deg; } +} + +unsigned SetReferences::numberOfParameters() +{ + return WBBlock::numberOfParameters() + 1; +} + +bool SetReferences::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // Memory allocation / Saving data not allowed here - unsigned SetReferences::numberOfParameters() - { - return WBBlock::numberOfParameters() + 1; + if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + + // INPUTS + // ====== + // + // 1) Joint refereces (1xDoFs vector) + // + + // Number of inputs + if (!blockInfo->setNumberOfInputPorts(1)) { + Log::getSingleton().error("Failed to configure the number of input ports."); + return false; } - bool SetReferences::configureSizeAndPorts(BlockInformation* blockInfo) - { - // Memory allocation / Saving data not allowed here + // Size and type + bool success = blockInfo->setInputPortVectorSize(0, dofs); + blockInfo->setInputPortType(0, PortDataTypeDouble); - if (!WBBlock::configureSizeAndPorts(blockInfo)) return false; + if (!success) { + Log::getSingleton().error("Failed to configure input ports."); + return false; + } - const unsigned dofs = getConfiguration().getNumberOfDoFs(); + // OUTPUTS + // ======= + // + // No outputs + // - // INPUTS - // ====== - // - // 1) Joint refereces (1xDoFs vector) - // + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to configure the number of output ports."); + return false; + } - // Number of inputs - if (!blockInfo->setNumberOfInputPorts(1)) { - Log::getSingleton().error("Failed to configure the number of input ports."); - return false; - } + return true; +} - // Size and type - bool success = blockInfo->setInputPortVectorSize(0, dofs); - blockInfo->setInputPortType(0, PortDataTypeDouble); +bool SetReferences::initialize(const BlockInformation* blockInfo) +{ + if (!WBBlock::initialize(blockInfo)) return false; - if (!success) { - Log::getSingleton().error("Failed to configure input ports."); - return false; - } + // Reading the control type + std::string controlType; + if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, + controlType)) { + Log::getSingleton().error("Could not read control type parameter."); + return false; + } - // OUTPUTS - // ======= - // - // No outputs - // + // Initialize the std::vectors + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_controlModes.assign(dofs, VOCAB_CM_UNKNOWN); - if (!blockInfo->setNumberOfOutputPorts(0)) { - Log::getSingleton().error("Failed to configure the number of output ports."); - return false; - } + // IControlMode.h + if (controlType == "Position") { + m_controlModes.assign(dofs, VOCAB_CM_POSITION); + } + else if (controlType == "Position Direct") { + m_controlModes.assign(dofs, VOCAB_CM_POSITION_DIRECT); + } + else if (controlType == "Velocity") { + m_controlModes.assign(dofs, VOCAB_CM_VELOCITY); + } + else if (controlType == "Torque") { + m_controlModes.assign(dofs, VOCAB_CM_TORQUE); + } + else if (controlType == "PWM") { + m_controlModes.assign(dofs, VOCAB_CM_PWM); + } + else if (controlType == "Current") { + m_controlModes.assign(dofs, VOCAB_CM_CURRENT); + } + else { + Log::getSingleton().error("Control Mode not supported."); + return false; + } - return true; + // Retain the ControlBoardRemapper + if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + return false; } - bool SetReferences::initialize(BlockInformation* blockInfo) - { - if (!WBBlock::initialize(blockInfo)) return false; + m_resetControlMode = true; + return true; +} - // Reading the control type - std::string controlType; - if (!blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, - controlType)) { - Log::getSingleton().error("Could not read control type parameter."); - return false; - } +bool SetReferences::terminate(const BlockInformation* blockInfo) +{ + using namespace yarp::dev; + bool ok = true; - // Initialize the std::vectors - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_controlModes.assign(dofs, VOCAB_CM_UNKNOWN); + // Get the interface + std::weak_ptr icmd2; + ok = ok & getRobotInterface()->getInterface(icmd2); + if (!ok) { + Log::getSingleton().error("Failed to get the IControlMode2 interface."); + } - // IControlMode.h - if (controlType == "Position") { - m_controlModes.assign(dofs, VOCAB_CM_POSITION); - } - else if (controlType == "Position Direct") { - m_controlModes.assign(dofs, VOCAB_CM_POSITION_DIRECT); - } - else if (controlType == "Velocity") { - m_controlModes.assign(dofs, VOCAB_CM_VELOCITY); - } - else if (controlType == "Torque") { - m_controlModes.assign(dofs, VOCAB_CM_TORQUE); - } - else if (controlType == "PWM") { - m_controlModes.assign(dofs, VOCAB_CM_PWM); - } - else if (controlType == "Current") { - m_controlModes.assign(dofs, VOCAB_CM_CURRENT); - } - else { - Log::getSingleton().error("Control Mode not supported."); - return false; - } + // Set all the controlledJoints VOCAB_CM_POSITION + const unsigned dofs = getConfiguration().getNumberOfDoFs(); + m_controlModes.assign(dofs, VOCAB_CM_POSITION); - // Retain the ControlBoardRemapper - if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); - return false; - } + ok = ok & icmd2.lock()->setControlModes(m_controlModes.data()); + if (!ok) { + Log::getSingleton().error("Failed to set control mode."); + } - m_resetControlMode = true; - return true; + // Release the RemoteControlBoardRemapper + ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); } - bool SetReferences::terminate(BlockInformation* blockInfo) - { - using namespace yarp::dev; - bool ok = true; + return ok && WBBlock::terminate(blockInfo); +} + +bool SetReferences::initializeInitialConditions(const BlockInformation* /*blockInfo*/) +{ + // Simply reset the variable m_resetControlMode. + // It will be read at the first cycle of output. + m_resetControlMode = true; + return true; +} + +bool SetReferences::output(const BlockInformation* blockInfo) +{ + using namespace yarp::dev; + // Set the control mode at the first run + if (m_resetControlMode) { + m_resetControlMode = false; // Get the interface std::weak_ptr icmd2; - ok = ok & getRobotInterface()->getInterface(icmd2); - if (!ok) { + if (!getRobotInterface()->getInterface(icmd2)) { Log::getSingleton().error("Failed to get the IControlMode2 interface."); + return false; } - - // Set all the controlledJoints VOCAB_CM_POSITION - const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_controlModes.assign(dofs, VOCAB_CM_POSITION); - - ok = ok & icmd2.lock()->setControlModes(m_controlModes.data()); - if (!ok) { + // Set the control mode to all the controlledJoints + if (!icmd2.lock()->setControlModes(m_controlModes.data())) { Log::getSingleton().error("Failed to set control mode."); + return false; } - - // Release the RemoteControlBoardRemapper - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); - if (!ok) { - Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); - } - - return ok && WBBlock::terminate(blockInfo); } - bool SetReferences::initializeInitialConditions(BlockInformation* /*blockInfo*/) - { - // Simply reset the variable m_resetControlMode. - // It will be read at the first cycle of output. - m_resetControlMode = true; - return true; - } + // Get the signal + Signal references = blockInfo->getInputPortSignal(0); + unsigned signalWidth = blockInfo->getInputPortWidth(0); + std::vector referencesVector = references.getStdVector(signalWidth); - bool SetReferences::output(BlockInformation* blockInfo) - { - using namespace yarp::dev; - - // Set the control mode at the first run - if (m_resetControlMode) { - m_resetControlMode = false; + bool ok = false; + // TODO: here only the first element is checked + switch (m_controlModes.front()) { + case VOCAB_CM_UNKNOWN: + Log::getSingleton().error("Control mode has not been successfully set."); + return false; + break; + case VOCAB_CM_POSITION: { // Get the interface - std::weak_ptr icmd2; - if (!getRobotInterface()->getInterface(icmd2)) { - Log::getSingleton().error("Failed to get the IControlMode2 interface."); + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IPositionControl interface."); return false; } - // Set the control mode to all the controlledJoints - if (!icmd2.lock()->setControlModes(m_controlModes.data())) { - Log::getSingleton().error("Failed to set control mode."); + // Convert from rad to deg + rad2deg(referencesVector); + // Set the references + ok = interface.lock()->positionMove(referencesVector.data()); + break; + } + case VOCAB_CM_POSITION_DIRECT: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IPositionDirect interface."); return false; } + // Convert from rad to deg + rad2deg(referencesVector); + // Set the references + ok = interface.lock()->setPositions(referencesVector.data()); + break; } - - // Get the signal - Signal references = blockInfo->getInputPortSignal(0); - unsigned signalWidth = blockInfo->getInputPortWidth(0); - std::vector referencesVector = references.getStdVector(signalWidth); - - bool ok = false; - // TODO: here only the first element is checked - switch (m_controlModes.front()) { - case VOCAB_CM_UNKNOWN: - Log::getSingleton().error("Control mode has not been successfully set."); + case VOCAB_CM_VELOCITY: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IVelocityControl interface."); return false; - break; - case VOCAB_CM_POSITION: { - // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { - Log::getSingleton().error("Failed to get IPositionControl interface."); - return false; - } - // Convert from rad to deg - rad2deg(referencesVector); - // Set the references - ok = interface.lock()->positionMove(referencesVector.data()); - break; - } - case VOCAB_CM_POSITION_DIRECT: { - // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { - Log::getSingleton().error("Failed to get IPositionDirect interface."); - return false; - } - // Convert from rad to deg - rad2deg(referencesVector); - // Set the references - ok = interface.lock()->setPositions(referencesVector.data()); - break; - } - case VOCAB_CM_VELOCITY: { - // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { - Log::getSingleton().error("Failed to get IVelocityControl interface."); - return false; - } - // Convert from rad to deg - rad2deg(referencesVector); - // Set the references - ok = interface.lock()->velocityMove(referencesVector.data()); - break; } - case VOCAB_CM_TORQUE: { - // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { - Log::getSingleton().error("Failed to get ITorqueControl interface."); - return false; - } - ok = interface.lock()->setRefTorques(referencesVector.data()); - break; - } - case VOCAB_CM_PWM: { - // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { - Log::getSingleton().error("Failed to get IPWMControl interface."); - return false; - } - ok = interface.lock()->setRefDutyCycles(referencesVector.data()); - break; + // Convert from rad to deg + rad2deg(referencesVector); + // Set the references + ok = interface.lock()->velocityMove(referencesVector.data()); + break; + } + case VOCAB_CM_TORQUE: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get ITorqueControl interface."); + return false; } - case VOCAB_CM_CURRENT: { - // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { - Log::getSingleton().error("Failed to get ICurrentControl interface."); - return false; - } - ok = interface.lock()->setRefCurrents(referencesVector.data()); - break; + ok = interface.lock()->setRefTorques(referencesVector.data()); + break; + } + case VOCAB_CM_PWM: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get IPWMControl interface."); + return false; } + ok = interface.lock()->setRefDutyCycles(referencesVector.data()); + break; } - - if (!ok) { - Log::getSingleton().error("Failed to set references."); - return false; + case VOCAB_CM_CURRENT: { + // Get the interface + std::weak_ptr interface; + if (!getRobotInterface()->getInterface(interface)) { + Log::getSingleton().error("Failed to get ICurrentControl interface."); + return false; + } + ok = interface.lock()->setRefCurrents(referencesVector.data()); + break; } + } - return true; + if (!ok) { + Log::getSingleton().error("Failed to set references."); + return false; } + + return true; } diff --git a/toolbox/src/SimulatorSynchronizer.cpp b/toolbox/src/SimulatorSynchronizer.cpp index 741a48ad6..20f43456b 100644 --- a/toolbox/src/SimulatorSynchronizer.cpp +++ b/toolbox/src/SimulatorSynchronizer.cpp @@ -7,140 +7,139 @@ #include #include -namespace wbt { +using namespace wbt; - struct SimulatorSynchronizer::RPCData - { - struct { - std::string clientPortName; - std::string serverPortName; +struct SimulatorSynchronizer::RPCData +{ + struct { + std::string clientPortName; + std::string serverPortName; - unsigned numberOfSteps; - } configuration; + unsigned numberOfSteps; + } configuration; - yarp::os::Port clientPort; - gazebo::ClockServer clockServer; - }; + yarp::os::Port clientPort; + gazebo::ClockServer clockServer; +}; - const std::string SimulatorSynchronizer::ClassName = "SimulatorSynchronizer"; +const std::string SimulatorSynchronizer::ClassName = "SimulatorSynchronizer"; - const unsigned SimulatorSynchronizer::PARAM_PERIOD = 1; - const unsigned SimulatorSynchronizer::PARAM_GZCLK_PORT = 2; - const unsigned SimulatorSynchronizer::PARAM_RPC_PORT = 3; +const unsigned SimulatorSynchronizer::PARAM_PERIOD = 1; +const unsigned SimulatorSynchronizer::PARAM_GZCLK_PORT = 2; +const unsigned SimulatorSynchronizer::PARAM_RPC_PORT = 3; - SimulatorSynchronizer::SimulatorSynchronizer() - : m_period(0.01) - , m_firstRun(true) - , m_rpcData(0) - {} +SimulatorSynchronizer::SimulatorSynchronizer() +: m_period(0.01) +, m_firstRun(true) +, m_rpcData(0) +{} - unsigned SimulatorSynchronizer::numberOfParameters() { return 3; } +unsigned SimulatorSynchronizer::numberOfParameters() { return 3; } - std::vector SimulatorSynchronizer::additionalBlockOptions() - { - return std::vector(1, wbt::BlockOptionPrioritizeOrder); - } - - bool SimulatorSynchronizer::configureSizeAndPorts(BlockInformation* blockInfo) - { - // INPUTS - // ====== - // - // No inputs - // +std::vector SimulatorSynchronizer::additionalBlockOptions() +{ + return std::vector(1, wbt::BlockOptionPrioritizeOrder); +} - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to set input port number to 0."); - return false; - } +bool SimulatorSynchronizer::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // INPUTS + // ====== + // + // No inputs + // + + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to set input port number to 0."); + return false; + } - // OUTPUT - // ====== - // - // No outputs - // + // OUTPUT + // ====== + // + // No outputs + // - if (!blockInfo->setNumberOfOutputPorts(0)) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } - - return true; + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to set output port number."); + return false; } - bool SimulatorSynchronizer::initialize(BlockInformation* blockInfo) - { - std::string serverPortName; - std::string clientPortName; + return true; +} - bool ok = true; - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period); - ok = ok & blockInfo->getStringParameterAtIndex(PARAM_GZCLK_PORT, serverPortName); - ok = ok & blockInfo->getStringParameterAtIndex(PARAM_RPC_PORT, clientPortName); +bool SimulatorSynchronizer::initialize(const BlockInformation* blockInfo) +{ + std::string serverPortName; + std::string clientPortName; - if (!ok) { - Log::getSingleton().error("Error reading RPC parameters."); - return false; - } + bool ok = true; + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period); + ok = ok & blockInfo->getStringParameterAtIndex(PARAM_GZCLK_PORT, serverPortName); + ok = ok & blockInfo->getStringParameterAtIndex(PARAM_RPC_PORT, clientPortName); - yarp::os::Network::init(); - if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork()) { - Log::getSingleton().error("Error initializing Yarp network."); - return false; - } + if (!ok) { + Log::getSingleton().error("Error reading RPC parameters."); + return false; + } - m_rpcData = new struct RPCData(); - if (!m_rpcData) { - Log::getSingleton().error("Error creating RPC data structure."); - return false; - } + yarp::os::Network::init(); + if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork()) { + Log::getSingleton().error("Error initializing Yarp network."); + return false; + } + + m_rpcData = new struct RPCData(); + if (!m_rpcData) { + Log::getSingleton().error("Error creating RPC data structure."); + return false; + } - m_rpcData->configuration.clientPortName = clientPortName; - m_rpcData->configuration.serverPortName = serverPortName; + m_rpcData->configuration.clientPortName = clientPortName; + m_rpcData->configuration.serverPortName = serverPortName; - m_firstRun = true; + m_firstRun = true; - return true; - } + return true; +} - bool SimulatorSynchronizer::terminate(BlockInformation* /*S*/) - { - if (m_rpcData) { - if (m_rpcData->clientPort.isOpen()) { - m_rpcData->clockServer.continueSimulation(); - if (!yarp::os::Network::disconnect(m_rpcData->configuration.clientPortName, - m_rpcData->configuration.serverPortName)) { - Log::getSingleton().error("Error disconnecting from simulator clock server."); - } - m_rpcData->clientPort.close(); +bool SimulatorSynchronizer::terminate(const BlockInformation* /*S*/) +{ + if (m_rpcData) { + if (m_rpcData->clientPort.isOpen()) { + m_rpcData->clockServer.continueSimulation(); + if (!yarp::os::Network::disconnect(m_rpcData->configuration.clientPortName, + m_rpcData->configuration.serverPortName)) { + Log::getSingleton().error("Error disconnecting from simulator clock server."); } - delete m_rpcData; - m_rpcData = nullptr; + m_rpcData->clientPort.close(); } - yarp::os::Network::fini(); - return true; + delete m_rpcData; + m_rpcData = nullptr; } + yarp::os::Network::fini(); + return true; +} - bool SimulatorSynchronizer::output(BlockInformation* /*S*/) - { - if (m_firstRun) { - m_firstRun = false; - - if (!m_rpcData->clientPort.open(m_rpcData->configuration.clientPortName) || - !yarp::os::Network::connect(m_rpcData->configuration.clientPortName, - m_rpcData->configuration.serverPortName)) { - Log::getSingleton().error("Error connecting to simulator clock server."); - return false; - } - - m_rpcData->clockServer.yarp().attachAsClient(m_rpcData->clientPort); +bool SimulatorSynchronizer::output(const BlockInformation* /*S*/) +{ + if (m_firstRun) { + m_firstRun = false; - double stepSize = m_rpcData->clockServer.getStepSize(); - m_rpcData->configuration.numberOfSteps = static_cast(m_period / stepSize); - m_rpcData->clockServer.pauseSimulation(); + if (!m_rpcData->clientPort.open(m_rpcData->configuration.clientPortName) || + !yarp::os::Network::connect(m_rpcData->configuration.clientPortName, + m_rpcData->configuration.serverPortName)) { + Log::getSingleton().error("Error connecting to simulator clock server."); + return false; } - m_rpcData->clockServer.stepSimulationAndWait(m_rpcData->configuration.numberOfSteps); - return true; + m_rpcData->clockServer.yarp().attachAsClient(m_rpcData->clientPort); + + double stepSize = m_rpcData->clockServer.getStepSize(); + m_rpcData->configuration.numberOfSteps = static_cast(m_period / stepSize); + m_rpcData->clockServer.pauseSimulation(); } + m_rpcData->clockServer.stepSimulationAndWait(m_rpcData->configuration.numberOfSteps); + + return true; } diff --git a/toolbox/src/YarpClock.cpp b/toolbox/src/YarpClock.cpp index b504287df..67592823e 100644 --- a/toolbox/src/YarpClock.cpp +++ b/toolbox/src/YarpClock.cpp @@ -7,64 +7,63 @@ #include #include -namespace wbt { +using namespace wbt; - const std::string YarpClock::ClassName = "YarpClock"; +const std::string YarpClock::ClassName = "YarpClock"; - unsigned YarpClock::numberOfParameters() { return 0; } +unsigned YarpClock::numberOfParameters() { return 0; } - bool YarpClock::configureSizeAndPorts(BlockInformation* blockInfo) - { - // INPUTS - // ====== - // - // No inputs - // +bool YarpClock::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // INPUTS + // ====== + // + // No inputs + // - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to set input port number to 0."); - return false; - } - - // OUTPUT - // ====== - // - // 1) The yarp time. In short, it streams yarp::os::Time::now(). - // - - if (!blockInfo->setNumberOfOutputPorts(1)) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to set input port number to 0."); + return false; + } - blockInfo->setOutputPortVectorSize(0, 1); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + // OUTPUT + // ====== + // + // 1) The yarp time. In short, it streams yarp::os::Time::now(). + // - return true; + if (!blockInfo->setNumberOfOutputPorts(1)) { + Log::getSingleton().error("Failed to set output port number."); + return false; } - bool YarpClock::initialize(BlockInformation* blockInfo) - { - yarp::os::Network::init(); + blockInfo->setOutputPortVectorSize(0, 1); + blockInfo->setOutputPortType(0, PortDataTypeDouble); - if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork(5.0)) { - Log::getSingleton().error("YARP server wasn't found active!!"); - return false; - } + return true; +} - return true; - } +bool YarpClock::initialize(const BlockInformation* blockInfo) +{ + yarp::os::Network::init(); - bool YarpClock::terminate(BlockInformation* /*S*/) - { - yarp::os::Network::fini(); - return true; + if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork(5.0)) { + Log::getSingleton().error("YARP server wasn't found active!!"); + return false; } - bool YarpClock::output(BlockInformation* blockInfo) - { - Signal signal = blockInfo->getOutputPortSignal(0); - signal.set(0, yarp::os::Time::now()); - return true; - } + return true; +} + +bool YarpClock::terminate(const BlockInformation* /*S*/) +{ + yarp::os::Network::fini(); + return true; +} + +bool YarpClock::output(const BlockInformation* blockInfo) +{ + Signal signal = blockInfo->getOutputPortSignal(0); + signal.set(0, yarp::os::Time::now()); + return true; } diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 5542b9a42..683af090f 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -12,207 +12,206 @@ #include #include -namespace wbt { - - const std::string YarpRead::ClassName = "YarpRead"; - - const unsigned YarpRead::PARAM_IDX_PORTNAME = 1; // port name - const unsigned YarpRead::PARAM_IDX_PORTSIZE = 2; // Size of the port you're reading - const unsigned YarpRead::PARAM_IDX_WAITDATA = 3; // boolean for blocking reading - const unsigned YarpRead::PARAM_IDX_READ_TS = 4; // boolean to stream timestamp - const unsigned YarpRead::PARAM_IDX_AUTOCONNECT = 5; // Autoconnect boolean - const unsigned YarpRead::PARAM_IDX_ERR_NO_PORT = 6; // Error on missing port if autoconnect is on boolean - - YarpRead::YarpRead() - : m_autoconnect(false) - , m_blocking(false) - , m_shouldReadTimestamp(false) - , m_errorOnMissingPort(true) - , m_port(0) - {} - - unsigned YarpRead::numberOfParameters() { return 6; } - - bool YarpRead::configureSizeAndPorts(BlockInformation* blockInfo) - { - // INPUTS - // ====== - // - // No inputs - // - - if (!blockInfo->setNumberOfInputPorts(0)) { - Log::getSingleton().error("Failed to set input port number to 0."); - return false; - } +using namespace wbt; + +const std::string YarpRead::ClassName = "YarpRead"; + +const unsigned YarpRead::PARAM_IDX_PORTNAME = 1; // port name +const unsigned YarpRead::PARAM_IDX_PORTSIZE = 2; // Size of the port you're reading +const unsigned YarpRead::PARAM_IDX_WAITDATA = 3; // boolean for blocking reading +const unsigned YarpRead::PARAM_IDX_READ_TS = 4; // boolean to stream timestamp +const unsigned YarpRead::PARAM_IDX_AUTOCONNECT = 5; // Autoconnect boolean +const unsigned YarpRead::PARAM_IDX_ERR_NO_PORT = 6; // Error on missing port if autoconnect is on boolean + +YarpRead::YarpRead() +: m_autoconnect(false) +, m_blocking(false) +, m_shouldReadTimestamp(false) +, m_errorOnMissingPort(true) +, m_port(0) +{} + +unsigned YarpRead::numberOfParameters() { return 6; } + +bool YarpRead::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // INPUTS + // ====== + // + // No inputs + // + + if (!blockInfo->setNumberOfInputPorts(0)) { + Log::getSingleton().error("Failed to set input port number to 0."); + return false; + } - // OUTPUTS - // ======= - // - // 1) Vector with the data read from the port (1 x signalSize) - // 2) Optional: Timestamp read from the port - // 3) Optional: If autoconnect is disabled, this output becomes 1 when data starts arriving - // (and hence it means that the user connected manually the port) - // + // OUTPUTS + // ======= + // + // 1) Vector with the data read from the port (1 x signalSize) + // 2) Optional: Timestamp read from the port + // 3) Optional: If autoconnect is disabled, this output becomes 1 when data starts arriving + // (and hence it means that the user connected manually the port) + // - bool shouldReadTimestamp; - bool autoconnect; - double signalSize; + bool shouldReadTimestamp; + bool autoconnect; + double signalSize; - bool ok = false; + bool ok = false; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, shouldReadTimestamp); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, autoconnect); - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_PORTSIZE, signalSize); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, shouldReadTimestamp); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, autoconnect); + ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_PORTSIZE, signalSize); - if (!ok) { - Log::getSingleton().error("Failed to read input parameters."); - return false; - } + if (!ok) { + Log::getSingleton().error("Failed to read input parameters."); + return false; + } - if (signalSize < 0) { - Log::getSingleton().error("Signal size must be non negative."); - return false; - } + if (signalSize < 0) { + Log::getSingleton().error("Signal size must be non negative."); + return false; + } - int numberOfOutputPorts = 1; - numberOfOutputPorts += static_cast(shouldReadTimestamp); //timestamp is the second port - numberOfOutputPorts += static_cast(!autoconnect); //!autoconnect => additional port with 1/0 depending on the connection status + int numberOfOutputPorts = 1; + numberOfOutputPorts += static_cast(shouldReadTimestamp); //timestamp is the second port + numberOfOutputPorts += static_cast(!autoconnect); //!autoconnect => additional port with 1/0 depending on the connection status - if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } + if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { + Log::getSingleton().error("Failed to set output port number."); + return false; + } - blockInfo->setOutputPortVectorSize(0, static_cast(signalSize)); - blockInfo->setOutputPortType(0, PortDataTypeDouble); + blockInfo->setOutputPortVectorSize(0, static_cast(signalSize)); + blockInfo->setOutputPortType(0, PortDataTypeDouble); - int portIndex = 1; - if (shouldReadTimestamp) { - blockInfo->setOutputPortVectorSize(portIndex, 2); - blockInfo->setOutputPortType(portIndex, PortDataTypeDouble); - portIndex++; - } - if (!autoconnect) { - blockInfo->setOutputPortVectorSize(portIndex, 1); - blockInfo->setOutputPortType(portIndex, PortDataTypeInt8); //use double anyway. Simplifies simulink stuff - portIndex++; - } - return true; + int portIndex = 1; + if (shouldReadTimestamp) { + blockInfo->setOutputPortVectorSize(portIndex, 2); + blockInfo->setOutputPortType(portIndex, PortDataTypeDouble); + portIndex++; } + if (!autoconnect) { + blockInfo->setOutputPortVectorSize(portIndex, 1); + blockInfo->setOutputPortType(portIndex, PortDataTypeInt8); //use double anyway. Simplifies simulink stuff + portIndex++; + } + return true; +} - bool YarpRead::initialize(BlockInformation* blockInfo) - { - using namespace yarp::os; - using namespace yarp::sig; +bool YarpRead::initialize(const BlockInformation* blockInfo) +{ + using namespace yarp::os; + using namespace yarp::sig; - Network::init(); + Network::init(); - if (!Network::initialized() || !Network::checkNetwork(5.0)) { - Log::getSingleton().error("YARP server wasn't found active!!"); - return false; - } + if (!Network::initialized() || !Network::checkNetwork(5.0)) { + Log::getSingleton().error("YARP server wasn't found active!!"); + return false; + } - bool ok = true; + bool ok = true; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, m_shouldReadTimestamp); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_WAITDATA, m_blocking); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, m_errorOnMissingPort); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, m_shouldReadTimestamp); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_WAITDATA, m_blocking); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, m_errorOnMissingPort); - if (!ok) { - Log::getSingleton().error("Failed to read input parameters."); - return false; - } + if (!ok) { + Log::getSingleton().error("Failed to read input parameters."); + return false; + } - std::string portName; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_PORTNAME, portName)) { - Log::getSingleton().error("Cannot retrieve string from port name parameter."); - return false; - } + std::string portName; + if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_PORTNAME, portName)) { + Log::getSingleton().error("Cannot retrieve string from port name parameter."); + return false; + } - std::string sourcePortName; - std::string destinationPortName; + std::string sourcePortName; + std::string destinationPortName; - // Autoconnect: the block opens a temporary input port ..., and it connects to an existing - // port portName (which is streaming data). - if (m_autoconnect) { - sourcePortName = portName; - destinationPortName = "..."; - } - // Manual connection: the block opens an input port portName, and waits a manual connection to an - // output port. - else { - destinationPortName = portName; - } + // Autoconnect: the block opens a temporary input port ..., and it connects to an existing + // port portName (which is streaming data). + if (m_autoconnect) { + sourcePortName = portName; + destinationPortName = "..."; + } + // Manual connection: the block opens an input port portName, and waits a manual connection to an + // output port. + else { + destinationPortName = portName; + } - m_port = new BufferedPort(); + m_port = new BufferedPort(); - if (!m_port || !m_port->open(destinationPortName)) { - Log::getSingleton().error("Error while opening yarp port."); - return false; - } + if (!m_port || !m_port->open(destinationPortName)) { + Log::getSingleton().error("Error while opening yarp port."); + return false; + } - if (m_autoconnect) { - if (!Network::connect(sourcePortName, m_port->getName())) { - Log::getSingleton().warning("Failed to connect " + - sourcePortName + - " to " - + m_port->getName()); - if (m_errorOnMissingPort) { - Log::getSingleton().error("Failed connecting ports."); - return false; - } + if (m_autoconnect) { + if (!Network::connect(sourcePortName, m_port->getName())) { + Log::getSingleton().warning("Failed to connect " + + sourcePortName + + " to " + + m_port->getName()); + if (m_errorOnMissingPort) { + Log::getSingleton().error("Failed connecting ports."); + return false; } } - return true; } + return true; +} - bool YarpRead::terminate(BlockInformation* /*blockInfo*/) - { - if (m_port) { - m_port->close(); - delete m_port; - m_port = nullptr; - } - yarp::os::Network::fini(); - return true; +bool YarpRead::terminate(const BlockInformation* /*blockInfo*/) +{ + if (m_port) { + m_port->close(); + delete m_port; + m_port = nullptr; } + yarp::os::Network::fini(); + return true; +} - bool YarpRead::output(BlockInformation* blockInfo) - { - int timeStampPortIndex = 1; - int connectionStatusPortIndex = 1; +bool YarpRead::output(const BlockInformation* blockInfo) +{ + int timeStampPortIndex = 1; + int connectionStatusPortIndex = 1; - yarp::sig::Vector* v = m_port->read(m_blocking); // Read from the port. Waits until data arrives. + yarp::sig::Vector* v = m_port->read(m_blocking); // Read from the port. Waits until data arrives. - if (v) { - if (m_shouldReadTimestamp) { - connectionStatusPortIndex++; - yarp::os::Stamp timestamp; - m_port->getEnvelope(timestamp); + if (v) { + if (m_shouldReadTimestamp) { + connectionStatusPortIndex++; + yarp::os::Stamp timestamp; + m_port->getEnvelope(timestamp); - Signal pY1 = blockInfo->getOutputPortSignal(timeStampPortIndex); - pY1.set(0, timestamp.getCount()); - pY1.set(1, timestamp.getTime()); - } + Signal pY1 = blockInfo->getOutputPortSignal(timeStampPortIndex); + pY1.set(0, timestamp.getCount()); + pY1.set(1, timestamp.getTime()); + } - Signal signal = blockInfo->getOutputPortSignal(0); + Signal signal = blockInfo->getOutputPortSignal(0); - // Crop the buffer if it exceeds the OutputPortWidth. - signal.setBuffer(v->data(), std::min(blockInfo->getOutputPortWidth(0), (unsigned)v->size())); + // Crop the buffer if it exceeds the OutputPortWidth. + signal.setBuffer(v->data(), std::min(blockInfo->getOutputPortWidth(0), (unsigned)v->size())); - if (!m_autoconnect) { - Signal statusPort = blockInfo->getOutputPortSignal(connectionStatusPortIndex); - statusPort.set(0, 1); //somebody wrote in the port => the port is connected + if (!m_autoconnect) { + Signal statusPort = blockInfo->getOutputPortSignal(connectionStatusPortIndex); + statusPort.set(0, 1); //somebody wrote in the port => the port is connected - //TODO implement a sort of "timeout" paramter - //At the current state this is equal to timeout = inf - //Otherwise we can check the timeout and if nobody sent data in the last X secs - //we set the port to zero again - } + //TODO implement a sort of "timeout" paramter + //At the current state this is equal to timeout = inf + //Otherwise we can check the timeout and if nobody sent data in the last X secs + //we set the port to zero again } - - return true; } + + return true; } diff --git a/toolbox/src/YarpWrite.cpp b/toolbox/src/YarpWrite.cpp index f557eccbb..3deba6dcc 100644 --- a/toolbox/src/YarpWrite.cpp +++ b/toolbox/src/YarpWrite.cpp @@ -9,149 +9,148 @@ #include #include -namespace wbt { - - const std::string YarpWrite::ClassName = "YarpWrite"; - - const unsigned YarpWrite::PARAM_IDX_PORTNAME = 1; // Port name - const unsigned YarpWrite::PARAM_IDX_AUTOCONNECT = 2; // Autoconnect boolean - const unsigned YarpWrite::PARAM_IDX_ERR_NO_PORT = 3; // Error on missing port if autoconnect is true - - YarpWrite::YarpWrite() - : m_autoconnect(false) - , m_errorOnMissingPort(true) - , m_destinationPortName("") - , m_port(nullptr) - {} - - unsigned YarpWrite::numberOfParameters() { return 3; } - - bool YarpWrite::configureSizeAndPorts(BlockInformation* blockInfo) - { - // INPUT - // ===== - // - // 1) The signal to stream to the specified yarp port - // - - if (!blockInfo->setNumberOfInputPorts(1)) { - Log::getSingleton().error("Failed to set input port number to 0."); - return false; - } - blockInfo->setInputPortVectorSize(0, -1); - blockInfo->setInputPortType(0, PortDataTypeDouble); - - // OUTPUT - // ====== - // - // No outputs - // - - if (!blockInfo->setNumberOfOutputPorts(0)) { - Log::getSingleton().error("Failed to set output port number."); - return false; - } - - return true; +using namespace wbt; + +const std::string YarpWrite::ClassName = "YarpWrite"; + +const unsigned YarpWrite::PARAM_IDX_PORTNAME = 1; // Port name +const unsigned YarpWrite::PARAM_IDX_AUTOCONNECT = 2; // Autoconnect boolean +const unsigned YarpWrite::PARAM_IDX_ERR_NO_PORT = 3; // Error on missing port if autoconnect is true + +YarpWrite::YarpWrite() +: m_autoconnect(false) +, m_errorOnMissingPort(true) +, m_destinationPortName("") +, m_port(nullptr) +{} + +unsigned YarpWrite::numberOfParameters() { return 3; } + +bool YarpWrite::configureSizeAndPorts(BlockInformation* blockInfo) +{ + // INPUT + // ===== + // + // 1) The signal to stream to the specified yarp port + // + + if (!blockInfo->setNumberOfInputPorts(1)) { + Log::getSingleton().error("Failed to set input port number to 0."); + return false; + } + blockInfo->setInputPortVectorSize(0, -1); + blockInfo->setInputPortType(0, PortDataTypeDouble); + + // OUTPUT + // ====== + // + // No outputs + // + + if (!blockInfo->setNumberOfOutputPorts(0)) { + Log::getSingleton().error("Failed to set output port number."); + return false; } - bool YarpWrite::initialize(BlockInformation* blockInfo) - { - using namespace yarp::os; - using namespace yarp::sig; + return true; +} - Network::init(); +bool YarpWrite::initialize(const BlockInformation* blockInfo) +{ + using namespace yarp::os; + using namespace yarp::sig; - if (!Network::initialized() || !Network::checkNetwork(5.0)){ - Log::getSingleton().error("YARP server wasn't found active!!"); - return false; - } + Network::init(); - bool ok = true; + if (!Network::initialized() || !Network::checkNetwork(5.0)){ + Log::getSingleton().error("YARP server wasn't found active!!"); + return false; + } - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, - m_errorOnMissingPort); + bool ok = true; - if (!ok) { - Log::getSingleton().error("Failed to read input parameters."); - return false; - } + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); + ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, + m_errorOnMissingPort); - std::string portParameter; - if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_PORTNAME, portParameter)) { - Log::getSingleton().error("Error reading port name parameter."); - return false; - } - - std::string sourcePortName; + if (!ok) { + Log::getSingleton().error("Failed to read input parameters."); + return false; + } - // Autoconnect: the block opens a temporary output port ..., and it connects to an existing - // port portName (which will receive data). - if (m_autoconnect) { - sourcePortName = "..."; - m_destinationPortName = portParameter; - } - // Manual connection: the block opens an output port portName, and waits a manual connection to an - // input port. - else { - sourcePortName = portParameter; - } + std::string portParameter; + if (!blockInfo->getStringParameterAtIndex(PARAM_IDX_PORTNAME, portParameter)) { + Log::getSingleton().error("Error reading port name parameter."); + return false; + } - m_port = new BufferedPort(); + std::string sourcePortName; - if (!m_port || !m_port->open(sourcePortName)) { - Log::getSingleton().error("Error while opening yarp port."); - return false; - } + // Autoconnect: the block opens a temporary output port ..., and it connects to an existing + // port portName (which will receive data). + if (m_autoconnect) { + sourcePortName = "..."; + m_destinationPortName = portParameter; + } + // Manual connection: the block opens an output port portName, and waits a manual connection to an + // input port. + else { + sourcePortName = portParameter; + } - if (m_autoconnect) { - if (!Network::connect(m_port->getName(), m_destinationPortName)) { - Log::getSingleton().warning("Failed to connect " + - m_port->getName() + - " to " + - m_destinationPortName); - if (m_errorOnMissingPort) { - Log::getSingleton().error("Failed connecting ports."); - return false; - } - } - } + m_port = new BufferedPort(); - // Initialize the size of the internal buffer handled by m_port - yarp::sig::Vector& outputVector = m_port->prepare(); - outputVector.resize(blockInfo->getInputPortWidth(0)); - return true; + if (!m_port || !m_port->open(sourcePortName)) { + Log::getSingleton().error("Error while opening yarp port."); + return false; } - bool YarpWrite::terminate(BlockInformation* /*S*/) - { - if (m_port) { - if (m_autoconnect) { - yarp::os::Network::disconnect(m_port->getName(), m_destinationPortName); + if (m_autoconnect) { + if (!Network::connect(m_port->getName(), m_destinationPortName)) { + Log::getSingleton().warning("Failed to connect " + + m_port->getName() + + " to " + + m_destinationPortName); + if (m_errorOnMissingPort) { + Log::getSingleton().error("Failed connecting ports."); + return false; } - m_port->close(); - delete m_port; - m_port = nullptr; } - yarp::os::Network::fini(); - return true; } - bool YarpWrite::output(BlockInformation* blockInfo) - { - if (!m_port) return false; - yarp::sig::Vector& outputVector = m_port->prepare(); - outputVector.resize(blockInfo->getInputPortWidth(0)); //this should be a no-op - - Signal signal = blockInfo->getInputPortSignal(0); + // Initialize the size of the internal buffer handled by m_port + yarp::sig::Vector& outputVector = m_port->prepare(); + outputVector.resize(blockInfo->getInputPortWidth(0)); + return true; +} - for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - outputVector[i] = signal.get(i).doubleData(); +bool YarpWrite::terminate(const BlockInformation* /*S*/) +{ + if (m_port) { + if (m_autoconnect) { + yarp::os::Network::disconnect(m_port->getName(), m_destinationPortName); } + m_port->close(); + delete m_port; + m_port = nullptr; + } + yarp::os::Network::fini(); + return true; +} - m_port->write(); +bool YarpWrite::output(const BlockInformation* blockInfo) +{ + if (!m_port) return false; + yarp::sig::Vector& outputVector = m_port->prepare(); + outputVector.resize(blockInfo->getInputPortWidth(0)); //this should be a no-op - return true; + Signal signal = blockInfo->getInputPortSignal(0); + + for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { + outputVector[i] = signal.get(i).doubleData(); } + + m_port->write(); + + return true; } diff --git a/toolbox/src/base/Block.cpp b/toolbox/src/base/Block.cpp index b7d36396a..fd2e88731 100644 --- a/toolbox/src/base/Block.cpp +++ b/toolbox/src/base/Block.cpp @@ -1,15 +1,17 @@ #include "Block.h" #include "toolbox.h" -wbt::Block::~Block() {} -std::vector wbt::Block::additionalBlockOptions() { return std::vector(); } -void wbt::Block::parameterAtIndexIsTunable(unsigned /*index*/, bool &tunable) { tunable = false; } -bool wbt::Block::checkParameters(wbt::BlockInformation* /*blockInfo*/) { return true; } +using namespace wbt; -unsigned wbt::Block::numberOfDiscreteStates() { return 0; } -unsigned wbt::Block::numberOfContinuousStates() { return 0; } +Block::~Block() {} +std::vector Block::additionalBlockOptions() { return std::vector(); } +void Block::parameterAtIndexIsTunable(unsigned /*index*/, bool &tunable) { tunable = false; } +bool Block::checkParameters(const BlockInformation* /*blockInfo*/) { return true; } -bool wbt::Block::updateDiscreteState(wbt::BlockInformation* /*blockInfo*/) { return true; } -bool wbt::Block::stateDerivative(wbt::BlockInformation* /*blockInfo*/) { return true; } +unsigned Block::numberOfDiscreteStates() { return 0; } +unsigned Block::numberOfContinuousStates() { return 0; } -bool wbt::Block::initializeInitialConditions(wbt::BlockInformation* /*blockInfo*/) { return true; } +bool Block::updateDiscreteState(const BlockInformation* /*blockInfo*/) { return true; } +bool Block::stateDerivative(const BlockInformation* /*blockInfo*/) { return true; } + +bool Block::initializeInitialConditions(const BlockInformation* /*blockInfo*/) { return true; } diff --git a/toolbox/src/base/BlockInformation.cpp b/toolbox/src/base/BlockInformation.cpp index 5fa160eef..5e52eb899 100644 --- a/toolbox/src/base/BlockInformation.cpp +++ b/toolbox/src/base/BlockInformation.cpp @@ -2,5 +2,7 @@ const std::string wbt::BlockOptionPrioritizeOrder = "wbt.BlockOptionPrioritizeOrder"; -wbt::BlockInformation::~BlockInformation() {} -bool wbt::BlockInformation::optionFromKey(const std::string& key, double& option) const { return false; } +bool wbt::BlockInformation::optionFromKey(const std::string& key, double& option) const +{ + return false; +} diff --git a/toolbox/src/base/Signal.cpp b/toolbox/src/base/Signal.cpp index 9d5f6adbc..67e6d6b42 100644 --- a/toolbox/src/base/Signal.cpp +++ b/toolbox/src/base/Signal.cpp @@ -1,324 +1,320 @@ #include "Signal.h" - #include -namespace wbt { +using namespace wbt; - void Signal::initSignalType(wbt::PortDataType type, bool constPort) - { - this->portType = type; - this->isConstPort = constPort; - } +void Signal::initSignalType(wbt::PortDataType type, bool constPort) +{ + this->portType = type; + this->isConstPort = constPort; +} - void Signal::setContiguousBuffer(void* buffer) - { - contiguousData = buffer; - this->isContiguous = true; - } - void Signal::setContiguousBuffer(const void* buffer) - { - contiguousData = const_cast(buffer); - this->isContiguous = true; - } +void Signal::setContiguousBuffer(void* buffer) +{ + contiguousData = buffer; + this->isContiguous = true; +} +void Signal::setContiguousBuffer(const void* buffer) +{ + contiguousData = const_cast(buffer); + this->isContiguous = true; +} - void Signal::setNonContiguousBuffer(void** buffer) - { - nonContiguousData = buffer; - this->isContiguous = false; - } +void Signal::setNonContiguousBuffer(void** buffer) +{ + nonContiguousData = buffer; + this->isContiguous = false; +} - void Signal::setNonContiguousBuffer(const void* const* buffer) - { - nonContiguousData = const_cast(buffer); - this->isContiguous = false; - } +void Signal::setNonContiguousBuffer(const void* const* buffer) +{ + nonContiguousData = const_cast(buffer); + this->isContiguous = false; +} - const Data Signal::get(unsigned index) const - { - Data data; - switch (portType) { - case PortDataTypeDouble: - if (isContiguous) { - data.doubleData((static_cast(contiguousData))[index]); - } - else { - const double* buffer = static_cast(*nonContiguousData); - data.doubleData(static_cast(buffer[index])); - } - break; - case PortDataTypeSingle: - if (isContiguous) { - data.floatData((static_cast(contiguousData))[index]); - } - else { - const float* buffer = static_cast(*nonContiguousData); - data.floatData(static_cast(buffer[index])); - } - break; - case PortDataTypeInt8: - if (isContiguous) { - data.int8Data((static_cast(contiguousData))[index]); - } - else { - const int8_t* buffer = static_cast(*nonContiguousData); - data.int8Data(static_cast(buffer[index])); - } - break; - case PortDataTypeUInt8: - if (isContiguous) { - data.uint8Data((static_cast(contiguousData))[index]); - } - else { - const uint8_t* buffer = static_cast(*nonContiguousData); - data.uint8Data(static_cast(buffer[index])); - } - break; - case PortDataTypeInt16: - if (isContiguous) { - data.int16Data((static_cast(contiguousData))[index]); - } - else { - const int16_t* buffer = static_cast(*nonContiguousData); - data.int16Data(static_cast(buffer[index])); - } - break; - case PortDataTypeUInt16: - if (isContiguous) { - data.uint16Data((static_cast(contiguousData))[index]); - } - else { - const uint16_t* buffer = static_cast(*nonContiguousData); - data.uint16Data(static_cast(buffer[index])); - } - break; - case PortDataTypeInt32: - if (isContiguous) { - data.int32Data((static_cast(contiguousData))[index]); - } - else { - const int32_t* buffer = static_cast(*nonContiguousData); - data.int32Data(static_cast(buffer[index])); - } - break; - case PortDataTypeUInt32: - if (isContiguous) { - data.uint32Data((static_cast(contiguousData))[index]); - } - else { - const uint32_t* buffer = static_cast(*nonContiguousData); - data.uint32Data(static_cast(buffer[index])); - } - break; - case PortDataTypeBoolean: - if (isContiguous) { - data.booleanData((static_cast(contiguousData))[index]); - } - else { - const bool* buffer = static_cast(*nonContiguousData); - data.booleanData(static_cast(buffer[index])); - } - } - return data; +const Data Signal::get(unsigned index) const +{ + Data data; + switch (portType) { + case PortDataTypeDouble: + if (isContiguous) { + data.doubleData((static_cast(contiguousData))[index]); + } + else { + const double* buffer = static_cast(*nonContiguousData); + data.doubleData(static_cast(buffer[index])); + } + break; + case PortDataTypeSingle: + if (isContiguous) { + data.floatData((static_cast(contiguousData))[index]); + } + else { + const float* buffer = static_cast(*nonContiguousData); + data.floatData(static_cast(buffer[index])); + } + break; + case PortDataTypeInt8: + if (isContiguous) { + data.int8Data((static_cast(contiguousData))[index]); + } + else { + const int8_t* buffer = static_cast(*nonContiguousData); + data.int8Data(static_cast(buffer[index])); + } + break; + case PortDataTypeUInt8: + if (isContiguous) { + data.uint8Data((static_cast(contiguousData))[index]); + } + else { + const uint8_t* buffer = static_cast(*nonContiguousData); + data.uint8Data(static_cast(buffer[index])); + } + break; + case PortDataTypeInt16: + if (isContiguous) { + data.int16Data((static_cast(contiguousData))[index]); + } + else { + const int16_t* buffer = static_cast(*nonContiguousData); + data.int16Data(static_cast(buffer[index])); + } + break; + case PortDataTypeUInt16: + if (isContiguous) { + data.uint16Data((static_cast(contiguousData))[index]); + } + else { + const uint16_t* buffer = static_cast(*nonContiguousData); + data.uint16Data(static_cast(buffer[index])); + } + break; + case PortDataTypeInt32: + if (isContiguous) { + data.int32Data((static_cast(contiguousData))[index]); + } + else { + const int32_t* buffer = static_cast(*nonContiguousData); + data.int32Data(static_cast(buffer[index])); + } + break; + case PortDataTypeUInt32: + if (isContiguous) { + data.uint32Data((static_cast(contiguousData))[index]); + } + else { + const uint32_t* buffer = static_cast(*nonContiguousData); + data.uint32Data(static_cast(buffer[index])); + } + break; + case PortDataTypeBoolean: + if (isContiguous) { + data.booleanData((static_cast(contiguousData))[index]); + } + else { + const bool* buffer = static_cast(*nonContiguousData); + data.booleanData(static_cast(buffer[index])); + } } + return data; +} - void* Signal::getContiguousBuffer() - { - if (!isContiguous) return nullptr; - return this->contiguousData; - } +void* Signal::getContiguousBuffer() +{ + if (!isContiguous) return nullptr; + return this->contiguousData; +} - std::vector Signal::getStdVector(unsigned length) const - { - std::vector v(length); - for (unsigned i = 0; i < length; ++i) { - v[i] = get(i).doubleData(); - } - return v; +std::vector Signal::getStdVector(unsigned length) const +{ + std::vector v(length); + for (unsigned i = 0; i < length; ++i) { + v[i] = get(i).doubleData(); } + return v; +} - //the missing are cast - void Signal::set(unsigned index, double data) - { - if (isConstPort) return; +//the missing are cast +void Signal::set(unsigned index, double data) +{ + if (isConstPort) return; - switch (portType) { - case PortDataTypeDouble: - { - double* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeSingle: - { - float* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - default: - break; + switch (portType) { + case PortDataTypeDouble: + { + double* buffer = static_cast(contiguousData); + buffer[index] = data; + break; + } + case PortDataTypeSingle: + { + float* buffer = static_cast(contiguousData); + buffer[index] = data; + break; } + default: + break; } +} - void Signal::setBuffer(const double* data, const unsigned length, unsigned startIndex) - { - if (isConstPort) return; - unsigned dataSize = 0; - const void* address = data; +void Signal::setBuffer(const double* data, const unsigned length, unsigned startIndex) +{ + if (isConstPort) return; + unsigned dataSize = 0; + const void* address = data; - switch (portType) { - case PortDataTypeDouble: - { - dataSize = sizeof(double); - address = static_cast(address) + startIndex; - break; - } - case PortDataTypeSingle: - { - dataSize = sizeof(float); - address = static_cast(address) + startIndex; - break; - } - default: - break; + switch (portType) { + case PortDataTypeDouble: + { + dataSize = sizeof(double); + address = static_cast(address) + startIndex; + break; } + case PortDataTypeSingle: + { + dataSize = sizeof(float); + address = static_cast(address) + startIndex; + break; + } + default: + break; + } - memcpy(contiguousData, address, dataSize * length); + memcpy(contiguousData, address, dataSize * length); - } +} - void Signal::set(unsigned index, int32_t data) - { - //signed integer function - switch (portType) { - case PortDataTypeInt32: - { - int32_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeInt16: - { - int16_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeInt8: - { - int8_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - default: - break; +void Signal::set(unsigned index, int32_t data) +{ + //signed integer function + switch (portType) { + case PortDataTypeInt32: + { + int32_t* buffer = static_cast(contiguousData); + buffer[index] = data; + break; } + case PortDataTypeInt16: + { + int16_t* buffer = static_cast(contiguousData); + buffer[index] = data; + break; + } + case PortDataTypeInt8: + { + int8_t* buffer = static_cast(contiguousData); + buffer[index] = data; + break; + } + default: + break; } +} - void Signal::setBuffer(const int32_t* data, const unsigned length, unsigned startIndex) - { - if (isConstPort) return; - unsigned dataSize = 0; - const void* address = data; +void Signal::setBuffer(const int32_t* data, const unsigned length, unsigned startIndex) +{ + if (isConstPort) return; + unsigned dataSize = 0; + const void* address = data; - switch (portType) { - case PortDataTypeInt32: - { - dataSize = sizeof(int32_t); - address = static_cast(address) + startIndex; - break; - } - case PortDataTypeInt16: - { - dataSize = sizeof(int16_t); - address = static_cast(address) + startIndex; - break; - } - case PortDataTypeInt8: - { - dataSize = sizeof(int8_t); - address = static_cast(address) + startIndex; - break; - } - default: - break; + switch (portType) { + case PortDataTypeInt32: + { + dataSize = sizeof(int32_t); + address = static_cast(address) + startIndex; + break; } - - memcpy(contiguousData, address, dataSize* length); - } - - void Signal::set(unsigned index, uint32_t data) - { - //signed integer function - switch (portType) { - case PortDataTypeUInt32: - { - uint32_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeUInt16: - { - uint16_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeUInt8: - { - uint8_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - default: - break; + case PortDataTypeInt16: + { + dataSize = sizeof(int16_t); + address = static_cast(address) + startIndex; + break; } + case PortDataTypeInt8: + { + dataSize = sizeof(int8_t); + address = static_cast(address) + startIndex; + break; + } + default: + break; } - void Signal::setBuffer(const uint32_t* data, const unsigned length, unsigned startIndex) - { - if (isConstPort) return; - unsigned dataSize = 0; - const void* address = data; + memcpy(contiguousData, address, dataSize* length); +} - switch (portType) { - case PortDataTypeUInt32: - { - dataSize = sizeof(uint32_t); - address = data + startIndex; - break; - } - case PortDataTypeUInt16: - { - dataSize = sizeof(uint16_t); - address = data + startIndex; - break; - } - case PortDataTypeUInt8: - { - dataSize = sizeof(uint8_t); - address = data + startIndex; - break; - } - default: - break; +void Signal::set(unsigned index, uint32_t data) +{ + //signed integer function + switch (portType) { + case PortDataTypeUInt32: + { + uint32_t* buffer = static_cast(contiguousData); + buffer[index] = data; + break; } - - memcpy(contiguousData, address, dataSize* length); + case PortDataTypeUInt16: + { + uint16_t* buffer = static_cast(contiguousData); + buffer[index] = data; + break; + } + case PortDataTypeUInt8: + { + uint8_t* buffer = static_cast(contiguousData); + buffer[index] = data; + break; + } + default: + break; } +} + +void Signal::setBuffer(const uint32_t* data, const unsigned length, unsigned startIndex) +{ + if (isConstPort) return; + unsigned dataSize = 0; + const void* address = data; - void Signal::set(unsigned index, bool data) - { - bool* buffer = static_cast(contiguousData); - buffer[index] = data; + switch (portType) { + case PortDataTypeUInt32: + { + dataSize = sizeof(uint32_t); + address = data + startIndex; + break; + } + case PortDataTypeUInt16: + { + dataSize = sizeof(uint16_t); + address = data + startIndex; + break; + } + case PortDataTypeUInt8: + { + dataSize = sizeof(uint8_t); + address = data + startIndex; + break; + } + default: + break; } - void Signal::setBuffer(const bool* data, const unsigned length, unsigned startIndex) - { - if (isConstPort) return; - unsigned dataSize = sizeof(bool); - const void* address = static_cast(data) + startIndex; + memcpy(contiguousData, address, dataSize* length); +} - memcpy(contiguousData, address, dataSize* length); - } +void Signal::set(unsigned index, bool data) +{ + bool* buffer = static_cast(contiguousData); + buffer[index] = data; +} +void Signal::setBuffer(const bool* data, const unsigned length, unsigned startIndex) +{ + if (isConstPort) return; + unsigned dataSize = sizeof(bool); + const void* address = static_cast(data) + startIndex; + memcpy(contiguousData, address, dataSize* length); } diff --git a/toolbox/src/base/SimulinkBlockInformation.cpp b/toolbox/src/base/SimulinkBlockInformation.cpp index 48ccdde51..2b9688738 100644 --- a/toolbox/src/base/SimulinkBlockInformation.cpp +++ b/toolbox/src/base/SimulinkBlockInformation.cpp @@ -5,191 +5,191 @@ #include #include -namespace wbt { +using namespace wbt; - SimulinkBlockInformation::SimulinkBlockInformation(SimStruct* S) - : simstruct(S) - {} +SimulinkBlockInformation::SimulinkBlockInformation(SimStruct* S) +: simstruct(S) +{} - bool SimulinkBlockInformation::optionFromKey(const std::string& key, double& option) const - { - if (key == wbt::BlockOptionPrioritizeOrder) { - option = SS_OPTION_PLACE_ASAP; - return true; - } - - return false; +bool SimulinkBlockInformation::optionFromKey(const std::string& key, double& option) const +{ + if (key == wbt::BlockOptionPrioritizeOrder) { + option = SS_OPTION_PLACE_ASAP; + return true; } - //Parameters methods - bool SimulinkBlockInformation::getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) - { - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asString(stringParameter); - } + return false; +} - bool SimulinkBlockInformation::getStructAtIndex(unsigned parameterIndex, AnyStruct& map) - { - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asAnyStruct(map); - } +//Parameters methods +bool SimulinkBlockInformation::getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asString(stringParameter); +} +bool SimulinkBlockInformation::getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asAnyStruct(map); +} - bool SimulinkBlockInformation::getVectorAtIndex(unsigned parameterIndex, std::vector& vec) - { - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asVectorDouble(vec); - } - bool SimulinkBlockInformation::getScalarParameterAtIndex(unsigned parameterIndex, double& value) - { - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asDouble(value); - } +bool SimulinkBlockInformation::getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asVectorDouble(vec); +} - bool SimulinkBlockInformation::getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) - { - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asBool(value); - } - //Port information methods - bool SimulinkBlockInformation::setNumberOfInputPorts(unsigned numberOfPorts) - { - return ssSetNumInputPorts(simstruct, numberOfPorts); - } +bool SimulinkBlockInformation::getScalarParameterAtIndex(unsigned parameterIndex, double& value) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asDouble(value); +} - bool SimulinkBlockInformation::setNumberOfOutputPorts(unsigned numberOfPorts) - { - return ssSetNumOutputPorts(simstruct, numberOfPorts); - } +bool SimulinkBlockInformation::getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asBool(value); +} - bool SimulinkBlockInformation::setInputPortVectorSize(unsigned portNumber, int portSize) - { - if (portSize == -1) portSize = DYNAMICALLY_SIZED; - return ssSetInputPortVectorDimension(simstruct, portNumber, portSize); - } +//Port information methods +bool SimulinkBlockInformation::setNumberOfInputPorts(unsigned numberOfPorts) +{ + return ssSetNumInputPorts(simstruct, numberOfPorts); +} - bool SimulinkBlockInformation::setInputPortMatrixSize(unsigned portNumber, int rows, int columns) - { - if (rows == -1) rows = DYNAMICALLY_SIZED; - if (columns == -1) columns = DYNAMICALLY_SIZED; - return ssSetInputPortMatrixDimensions(simstruct, portNumber, rows, columns); - } +bool SimulinkBlockInformation::setNumberOfOutputPorts(unsigned numberOfPorts) +{ + return ssSetNumOutputPorts(simstruct, numberOfPorts); +} - bool SimulinkBlockInformation::setOutputPortVectorSize(unsigned portNumber, int portSize) - { - if (portSize == -1) portSize = DYNAMICALLY_SIZED; - return ssSetOutputPortVectorDimension(simstruct, portNumber, portSize); - } +bool SimulinkBlockInformation::setInputPortVectorSize(unsigned portNumber, int portSize) +{ + if (portSize == -1) portSize = DYNAMICALLY_SIZED; + return ssSetInputPortVectorDimension(simstruct, portNumber, portSize); +} - bool SimulinkBlockInformation::setOutputPortMatrixSize(unsigned portNumber, int rows, int columns) - { - if (rows == -1) rows = DYNAMICALLY_SIZED; - if (columns == -1) columns = DYNAMICALLY_SIZED; - return ssSetOutputPortMatrixDimensions(simstruct, portNumber, rows, columns); - } +bool SimulinkBlockInformation::setInputPortMatrixSize(unsigned portNumber, int rows, int columns) +{ + if (rows == -1) rows = DYNAMICALLY_SIZED; + if (columns == -1) columns = DYNAMICALLY_SIZED; + return ssSetInputPortMatrixDimensions(simstruct, portNumber, rows, columns); +} - bool SimulinkBlockInformation::setInputPortType(unsigned portNumber, PortDataType portType) - { - //for now force Direct feedthrough.. If needed create a separate method - ssSetInputPortDirectFeedThrough(simstruct, portNumber, 1); - int matlabDataType = -1; - switch (portType) { - case PortDataTypeDouble: - matlabDataType = SS_DOUBLE; - break; - case PortDataTypeSingle: - matlabDataType = SS_SINGLE; - break; - case PortDataTypeInt8: - matlabDataType = SS_INT8; - break; - case PortDataTypeUInt8: - matlabDataType = SS_UINT8; - break; - case PortDataTypeInt16: - matlabDataType = SS_INT16; - break; - case PortDataTypeUInt16: - matlabDataType = SS_UINT16; - break; - case PortDataTypeInt32: - matlabDataType = SS_INT32; - break; - case PortDataTypeUInt32: - matlabDataType = SS_UINT32; - break; - case PortDataTypeBoolean: - matlabDataType = SS_BOOLEAN; - break; - } - return ssSetInputPortDataType(simstruct, portNumber, matlabDataType); - } +bool SimulinkBlockInformation::setOutputPortVectorSize(unsigned portNumber, int portSize) +{ + if (portSize == -1) portSize = DYNAMICALLY_SIZED; + return ssSetOutputPortVectorDimension(simstruct, portNumber, portSize); +} - bool SimulinkBlockInformation::setOutputPortType(unsigned portNumber, PortDataType portType) - { - int matlabDataType = -1; - switch (portType) { - case PortDataTypeDouble: - matlabDataType = SS_DOUBLE; - break; +bool SimulinkBlockInformation::setOutputPortMatrixSize(unsigned portNumber, int rows, int columns) +{ + if (rows == -1) rows = DYNAMICALLY_SIZED; + if (columns == -1) columns = DYNAMICALLY_SIZED; + return ssSetOutputPortMatrixDimensions(simstruct, portNumber, rows, columns); +} + +bool SimulinkBlockInformation::setInputPortType(unsigned portNumber, PortDataType portType) +{ + //for now force Direct feedthrough.. If needed create a separate method + ssSetInputPortDirectFeedThrough(simstruct, portNumber, 1); + int matlabDataType = -1; + switch (portType) { + case PortDataTypeDouble: + matlabDataType = SS_DOUBLE; + break; case PortDataTypeSingle: - matlabDataType = SS_SINGLE; - break; - case PortDataTypeInt8: - matlabDataType = SS_INT8; - break; - case PortDataTypeUInt8: - matlabDataType = SS_UINT8; - break; - case PortDataTypeInt16: - matlabDataType = SS_INT16; - break; - case PortDataTypeUInt16: - matlabDataType = SS_UINT16; - break; - case PortDataTypeInt32: - matlabDataType = SS_INT32; - break; - case PortDataTypeUInt32: - matlabDataType = SS_UINT32; - break; - case PortDataTypeBoolean: - matlabDataType = SS_BOOLEAN; - break; - } - return ssSetOutputPortDataType(simstruct, portNumber, matlabDataType); - } + matlabDataType = SS_SINGLE; + break; + case PortDataTypeInt8: + matlabDataType = SS_INT8; + break; + case PortDataTypeUInt8: + matlabDataType = SS_UINT8; + break; + case PortDataTypeInt16: + matlabDataType = SS_INT16; + break; + case PortDataTypeUInt16: + matlabDataType = SS_UINT16; + break; + case PortDataTypeInt32: + matlabDataType = SS_INT32; + break; + case PortDataTypeUInt32: + matlabDataType = SS_UINT32; + break; + case PortDataTypeBoolean: + matlabDataType = SS_BOOLEAN; + break; + } + return ssSetInputPortDataType(simstruct, portNumber, matlabDataType); +} - //Port data - unsigned SimulinkBlockInformation::getInputPortWidth(unsigned portNumber) - { - return ssGetInputPortWidth(simstruct, portNumber); - } +bool SimulinkBlockInformation::setOutputPortType(unsigned portNumber, PortDataType portType) +{ + int matlabDataType = -1; + switch (portType) { + case PortDataTypeDouble: + matlabDataType = SS_DOUBLE; + break; + case PortDataTypeSingle: + matlabDataType = SS_SINGLE; + break; + case PortDataTypeInt8: + matlabDataType = SS_INT8; + break; + case PortDataTypeUInt8: + matlabDataType = SS_UINT8; + break; + case PortDataTypeInt16: + matlabDataType = SS_INT16; + break; + case PortDataTypeUInt16: + matlabDataType = SS_UINT16; + break; + case PortDataTypeInt32: + matlabDataType = SS_INT32; + break; + case PortDataTypeUInt32: + matlabDataType = SS_UINT32; + break; + case PortDataTypeBoolean: + matlabDataType = SS_BOOLEAN; + break; + } + return ssSetOutputPortDataType(simstruct, portNumber, matlabDataType); +} - unsigned SimulinkBlockInformation::getOutputPortWidth(unsigned portNumber) - { - return ssGetOutputPortWidth(simstruct, portNumber); - } +//Port data +unsigned SimulinkBlockInformation::getInputPortWidth(unsigned portNumber) const +{ + return ssGetInputPortWidth(simstruct, portNumber); +} - wbt::Signal SimulinkBlockInformation::getInputPortSignal(unsigned portNumber) - { - Signal signal; - InputPtrsType port = ssGetInputPortSignalPtrs(simstruct, portNumber); - bool isConstPort = true; - signal.initSignalType(PortDataTypeDouble, isConstPort); - signal.setNonContiguousBuffer(port); - return signal; - } +unsigned SimulinkBlockInformation::getOutputPortWidth(unsigned portNumber) const +{ + return ssGetOutputPortWidth(simstruct, portNumber); +} + +wbt::Signal SimulinkBlockInformation::getInputPortSignal(unsigned portNumber) const +{ + Signal signal; + InputPtrsType port = ssGetInputPortSignalPtrs(simstruct, portNumber); + bool isConstPort = true; + signal.initSignalType(PortDataTypeDouble, isConstPort); + signal.setNonContiguousBuffer(port); + return signal; +} - wbt::Signal SimulinkBlockInformation::getOutputPortSignal(unsigned portNumber) - { - Signal signal; - bool isConstPort = false; - signal.initSignalType(PortDataTypeDouble, isConstPort); - signal.setContiguousBuffer(ssGetOutputPortSignal(simstruct, portNumber)); - return signal; - } +wbt::Signal SimulinkBlockInformation::getOutputPortSignal(unsigned portNumber) const +{ + Signal signal; + bool isConstPort = false; + signal.initSignalType(PortDataTypeDouble, isConstPort); + signal.setContiguousBuffer(ssGetOutputPortSignal(simstruct, portNumber)); + return signal; } diff --git a/toolbox/src/base/ToolboxSingleton.cpp b/toolbox/src/base/ToolboxSingleton.cpp index a3d7981b5..19042b281 100644 --- a/toolbox/src/base/ToolboxSingleton.cpp +++ b/toolbox/src/base/ToolboxSingleton.cpp @@ -8,115 +8,103 @@ #include #include -// TODO: remove nesting -namespace wbt { +using namespace wbt; - // CONSTRUCTOR / DESTRUCTOR - // ======================== +// CONSTRUCTOR / DESTRUCTOR +// ======================== - ToolboxSingleton::ToolboxSingleton() {} - ToolboxSingleton::~ToolboxSingleton() {} +ToolboxSingleton::ToolboxSingleton() {} +ToolboxSingleton::~ToolboxSingleton() {} - // UTILITIES - // ========= +// UTILITIES +// ========= - int ToolboxSingleton::numberOfDoFs(const std::string& confKey) - { - if (!isKeyValid(confKey)) - return -1; - else - return m_interfaces[confKey]->getConfiguration().getNumberOfDoFs(); - } +int ToolboxSingleton::numberOfDoFs(const std::string& confKey) +{ + if (!isKeyValid(confKey)) + return -1; + else + return m_interfaces[confKey]->getConfiguration().getNumberOfDoFs(); +} - bool ToolboxSingleton::isKeyValid(const std::string& confKey) - { - if (m_interfaces.find(confKey) != m_interfaces.end()) { - if (m_interfaces[confKey]) - return true; - else - return false; - } - else { +bool ToolboxSingleton::isKeyValid(const std::string& confKey) +{ + if (m_interfaces.find(confKey) != m_interfaces.end()) { + if (m_interfaces[confKey]) + return true; + else return false; - } } + else { + return false; + } +} - // GET METHODS - // =========== +// GET METHODS +// =========== - ToolboxSingleton& ToolboxSingleton::sharedInstance() - { - static ToolboxSingleton instance; - return instance; - } +ToolboxSingleton& ToolboxSingleton::sharedInstance() +{ + static ToolboxSingleton instance; + return instance; +} + +const Configuration& ToolboxSingleton::getConfiguration(const std::string& confKey) +{ + return getRobotInterface(confKey)->getConfiguration(); +} - const Configuration& ToolboxSingleton::getConfiguration(const std::string& confKey) - { - return getRobotInterface(confKey)->getConfiguration(); +const std::shared_ptr ToolboxSingleton::getRobotInterface(const std::string& confKey) +{ + if (!isKeyValid(confKey)) { + return nullptr; } - const std::shared_ptr ToolboxSingleton::getRobotInterface(const std::string& confKey) - { - if (!isKeyValid(confKey)) { - return nullptr; - } + return m_interfaces[confKey]; +} - return m_interfaces[confKey]; +const std::shared_ptr ToolboxSingleton::getModel(const std::string& confKey) +{ + if (!isKeyValid(confKey)) { + return nullptr; } - const std::shared_ptr ToolboxSingleton::getModel(const std::string& confKey) - { - if (!isKeyValid(confKey)) { - return nullptr; - } + return m_interfaces[confKey]->getKinDynComputations(); +} - return m_interfaces[confKey]->getKinDynComputations(); - } +// TOOLBOXSINGLETON CONFIGURATION +// ============================== - // TOOLBOXSINGLETON CONFIGURATION - // ============================== +bool ToolboxSingleton::storeConfiguration(const std::string& confKey, const Configuration& config) +{ + if (!config.isValid()) { + return false; + } - bool ToolboxSingleton::storeConfiguration(const std::string& confKey, const Configuration& config) - { - if (!config.isValid()) { - return false; - } - - // Add the new Configuration object and override an existing key if it already exist. - // Note: Simulink doesn't flush memory unless Matlab is closed, and static objects stay in memory. - // This may cause problems if the config block's mask is changed after the first compilation. - if (m_interfaces.find(confKey) == m_interfaces.end()) { - m_interfaces[confKey] = std::make_shared(config); - return static_cast(m_interfaces[confKey]); - } - - if (!(m_interfaces[confKey]->getConfiguration() == config)) { - assert(m_interfaces[confKey]); - - // Check that at top there are 2 instances of the model: - // the private member of RobotInterface and the one returned - // by the model() called by the assert itself - assert(getModel(confKey).use_count() <= 2); - // TODO: and also m_robotDeviceCounter should be max 1 - // - // TODO: domani: quando finisce la simulazione (terminate) dovrei avere - // dentro tutti i Configuration al massimo 1 sia di model che di - // device (e le interfacce tutte chiuse?) - - // Delete the old configuration (calling the destructor for cleaning garbage) - m_interfaces[confKey].reset(); - m_interfaces.erase(confKey); - - // Allocate a new configuration - m_interfaces[confKey] = std::make_shared(config); - return static_cast(m_interfaces[confKey]); - } - - return true; + // Add the new Configuration object and override an existing key if it already exist. + // Note: Simulink doesn't flush memory unless Matlab is closed, and static objects stay in memory. + // This may cause problems if the config block's mask is changed after the first compilation. + if (m_interfaces.find(confKey) == m_interfaces.end()) { + m_interfaces[confKey] = std::make_shared(config); + return static_cast(m_interfaces[confKey]); } - void ToolboxSingleton::eraseConfiguration(const std::string& confKey) - { + if (!(m_interfaces[confKey]->getConfiguration() == config)) { + assert(m_interfaces[confKey]); + + // Delete the old configuration (calling the destructor for cleaning garbage) + m_interfaces[confKey].reset(); m_interfaces.erase(confKey); + + // Allocate a new configuration + m_interfaces[confKey] = std::make_shared(config); + return static_cast(m_interfaces[confKey]); } + + return true; +} + +void ToolboxSingleton::eraseConfiguration(const std::string& confKey) +{ + m_interfaces.erase(confKey); } diff --git a/toolbox/src/base/WBBlock.cpp b/toolbox/src/base/WBBlock.cpp index 27f9913f2..cf49a66de 100644 --- a/toolbox/src/base/WBBlock.cpp +++ b/toolbox/src/base/WBBlock.cpp @@ -30,7 +30,7 @@ iDynTreeRobotState::iDynTreeRobotState(const unsigned& dofs, const std::vector Date: Mon, 13 Nov 2017 08:52:47 +0000 Subject: [PATCH 40/92] Switched to std::array for storing the gravity vector --- toolbox/include/base/Configuration.h | 9 +++++---- toolbox/include/base/WBBlock.h | 3 ++- toolbox/src/base/Configuration.cpp | 6 +++--- toolbox/src/base/WBBlock.cpp | 8 ++++++-- 4 files changed, 16 insertions(+), 10 deletions(-) diff --git a/toolbox/include/base/Configuration.h b/toolbox/include/base/Configuration.h index 192656cdf..9b70142ac 100644 --- a/toolbox/include/base/Configuration.h +++ b/toolbox/include/base/Configuration.h @@ -2,6 +2,7 @@ #define WBT_TOOLBOXCONFIG_H #include +#include #include namespace wbt { @@ -25,7 +26,7 @@ class wbt::Configuration std::string m_localName; ///< Prefix appended to the opened ports std::vector m_controlledJoints; ///< Subset of controlled joints std::vector m_controlBoardsNames; ///< Names of the used ControlBoard names - std::vector m_gravityVector; ///< The gravity vector + std::array m_gravityVector; ///< The gravity vector size_t m_dofs; //< DoFs extracted my m_controlBoardsNames vector public: @@ -50,7 +51,7 @@ class wbt::Configuration std::vector controlledJoints, std::vector controlBoardsNames, std::string localName, - std::vector gravityVector); + std::array gravityVector); /** * Set the name of the robot @@ -88,7 +89,7 @@ class wbt::Configuration * Set the gravity vector * @param gravityVector The gravity vector */ - void setGravityVector(const std::vector& gravityVector); + void setGravityVector(const std::array& gravityVector); // GET METHODS // =========== @@ -133,7 +134,7 @@ class wbt::Configuration * * @return The gravity vector */ - const std::vector& getGravityVector() const; + const std::array& getGravityVector() const; /** * Get the configured number of DoFs diff --git a/toolbox/include/base/WBBlock.h b/toolbox/include/base/WBBlock.h index b3d5cf33c..227795a1c 100644 --- a/toolbox/include/base/WBBlock.h +++ b/toolbox/include/base/WBBlock.h @@ -3,6 +3,7 @@ #include "Block.h" #include +#include #include #include #include @@ -36,7 +37,7 @@ struct iDynTreeRobotState { iDynTreeRobotState() = default; ~iDynTreeRobotState() = default; - iDynTreeRobotState(const unsigned& dofs, const std::vector& gravity); + iDynTreeRobotState(const unsigned& dofs, const std::array& gravity); }; /** diff --git a/toolbox/src/base/Configuration.cpp b/toolbox/src/base/Configuration.cpp index d28857016..a963a3b41 100644 --- a/toolbox/src/base/Configuration.cpp +++ b/toolbox/src/base/Configuration.cpp @@ -14,7 +14,7 @@ void Configuration::setParameters(std::string robotName, std::vector controlledJoints, std::vector controlBoardsNames, std::string localName, - std::vector gravityVector) + std::array gravityVector) { setRobotName(robotName); setUrdfFile(urdfFile); @@ -50,7 +50,7 @@ void Configuration::setLocalName(const std::string& localName) m_localName = localName; } -void Configuration::setGravityVector(const std::vector& gravityVector) +void Configuration::setGravityVector(const std::array& gravityVector) { m_gravityVector = gravityVector; } @@ -83,7 +83,7 @@ const std::string& Configuration::getLocalName() const return m_localName; } -const std::vector& Configuration::getGravityVector() const +const std::array& Configuration::getGravityVector() const { return m_gravityVector; } diff --git a/toolbox/src/base/WBBlock.cpp b/toolbox/src/base/WBBlock.cpp index cf49a66de..0c344e33f 100644 --- a/toolbox/src/base/WBBlock.cpp +++ b/toolbox/src/base/WBBlock.cpp @@ -19,7 +19,7 @@ const unsigned WBBlock::ConfigurationParameterIndex = 1; // Struct from Simulink const unsigned WBBlock::ConfBlockNameParameterIndex = 2; // Absolute name of the block containing the // configuration -iDynTreeRobotState::iDynTreeRobotState(const unsigned& dofs, const std::vector& gravity) +iDynTreeRobotState::iDynTreeRobotState(const unsigned& dofs, const std::array& gravity) : m_gravity(gravity.data(), 3) , m_jointsVelocity(dofs) , m_jointsPosition(dofs) @@ -130,6 +130,10 @@ bool WBBlock::getWBToolboxParameters(Configuration& config, const BlockInformati Log::getSingleton().error("Cannot retrieve vector from GravityVector parameter."); return false; } + std::array gravityArray; + for (auto i : gravityVector) { + gravityArray[i] = i; + } // Create the ToolboxConfig object // =============================== @@ -140,7 +144,7 @@ bool WBBlock::getWBToolboxParameters(Configuration& config, const BlockInformati config.setControlledJoints(controlledJoints); config.setControlBoardsNames(controlBoardsNames); config.setLocalName(localName); - config.setGravityVector(gravityVector); + config.setGravityVector(gravityArray); return true; } From 8c61547526f4bcbfc782c4a18bb5bc0e9b2595cb Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 13 Nov 2017 08:55:21 +0000 Subject: [PATCH 41/92] Switched to std::unique_ptr for PolyDriver member The RemoteControlBoardRemapper is never shared, and it makes sense for RobotInterface being the only one maintaining its ownership --- toolbox/include/base/RobotInterface.h | 2 +- toolbox/src/base/RobotInterface.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/toolbox/include/base/RobotInterface.h b/toolbox/include/base/RobotInterface.h index 83da54cde..1c1fb4ab2 100644 --- a/toolbox/include/base/RobotInterface.h +++ b/toolbox/include/base/RobotInterface.h @@ -86,7 +86,7 @@ struct wbt::YarpDevices class wbt::RobotInterface { private: - std::shared_ptr m_robotDevice; + std::unique_ptr m_robotDevice; std::shared_ptr m_kinDynComp; wbt::YarpDevices m_yarpDevices; diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index 59633f63b..9c2d859fa 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -378,7 +378,8 @@ bool RobotInterface::initializeRemoteControlBoardRemapper() remoteCBOpts.put("writeStrict","on"); // Allocate the device driver - m_robotDevice = std::make_shared(); + assert(!m_robotDevice); + m_robotDevice = std::unique_ptr(new yarp::dev::PolyDriver()); if (!m_robotDevice) { return false; From a3c61c55870d6a4aa42bd0887d82fd0759f88944 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 13 Nov 2017 08:56:53 +0000 Subject: [PATCH 42/92] Changed the name of the getDevice template to getInterfaceFromTemplate Before the name was misleading --- toolbox/include/base/RobotInterface.h | 3 ++- toolbox/src/base/RobotInterface.cpp | 22 +++++++++++----------- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/toolbox/include/base/RobotInterface.h b/toolbox/include/base/RobotInterface.h index 1c1fb4ab2..6b85789d3 100644 --- a/toolbox/include/base/RobotInterface.h +++ b/toolbox/include/base/RobotInterface.h @@ -132,7 +132,8 @@ class wbt::RobotInterface * @return The dynamic(ally)_cast device * @tparam T The type of the retured device */ - template std::weak_ptr getDevice(std::shared_ptr device); + template + std::weak_ptr getInterfaceFromTemplate(std::shared_ptr device); /** * Creates the map between joints (specified as either names or idyntree indices) and diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index 9c2d859fa..4e1fccbb0 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -195,70 +195,70 @@ const std::shared_ptr RobotInterface::getKinDynCom template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iControlMode2); + interface = getInterfaceFromTemplate(m_yarpDevices.iControlMode2); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iPositionControl); + interface = getInterfaceFromTemplate(m_yarpDevices.iPositionControl); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iPositionDirect); + interface = getInterfaceFromTemplate(m_yarpDevices.iPositionDirect); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iVelocityControl); + interface = getInterfaceFromTemplate(m_yarpDevices.iVelocityControl); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iTorqueControl); + interface = getInterfaceFromTemplate(m_yarpDevices.iTorqueControl); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iPWMControl); + interface = getInterfaceFromTemplate(m_yarpDevices.iPWMControl); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iCurrentControl); + interface = getInterfaceFromTemplate(m_yarpDevices.iCurrentControl); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iEncoders); + interface = getInterfaceFromTemplate(m_yarpDevices.iEncoders); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iControlLimits2); + interface = getInterfaceFromTemplate(m_yarpDevices.iControlLimits2); return !interface.expired(); } template <> bool RobotInterface::getInterface(std::weak_ptr& interface) { - interface = getDevice(m_yarpDevices.iPidControl); + interface = getInterfaceFromTemplate(m_yarpDevices.iPidControl); return !interface.expired(); } @@ -399,7 +399,7 @@ bool RobotInterface::initializeRemoteControlBoardRemapper() // ============= template -std::weak_ptr RobotInterface::getDevice(std::shared_ptr device) +std::weak_ptr RobotInterface::getInterfaceFromTemplate(std::shared_ptr device) { if (!device) { // Blocks which require the RemoteControlBoardRemapper need to retain / release it From 1dd9789559789d12aca826525b8b118ed99a236d Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 13 Nov 2017 09:00:35 +0000 Subject: [PATCH 43/92] Removed Eigen from AnyType and MxAnyType This interface exposes vector and matrix data as std::vector. The C++11 std::vector::data() method might be used from the user to gather the raw buffer for initializing Eigen objects if needed. --- MxAnyType/CMakeLists.txt | 4 ---- MxAnyType/include/AnyType.h | 6 ------ MxAnyType/include/MxAnyType.h | 1 - MxAnyType/src/MxAnyType.cpp | 16 +++++----------- 4 files changed, 5 insertions(+), 22 deletions(-) diff --git a/MxAnyType/CMakeLists.txt b/MxAnyType/CMakeLists.txt index 8d3250642..4faaebad7 100644 --- a/MxAnyType/CMakeLists.txt +++ b/MxAnyType/CMakeLists.txt @@ -32,10 +32,6 @@ if (CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") set_target_properties(${VARS_PREFIX} PROPERTIES COMPILE_FLAGS "-fPIC") endif() -# Find Eigen -find_package(Eigen3 REQUIRED) -target_include_directories(${VARS_PREFIX} PUBLIC "${EIGEN3_INCLUDE_DIR}") - # Find Matlab resources find_package(Matlab REQUIRED MX_LIBRARY) # target_include_directories(${VARS_PREFIX} SYSTEM PUBLIC "${Matlab_INCLUDE_DIRS}") // TODO: when committing diff --git a/MxAnyType/include/AnyType.h b/MxAnyType/include/AnyType.h index 1637b38b8..a13d1d03a 100644 --- a/MxAnyType/include/AnyType.h +++ b/MxAnyType/include/AnyType.h @@ -1,7 +1,6 @@ #ifndef ANYTYPE_H #define ANYTYPE_H -#include #include #include #include @@ -15,13 +14,9 @@ typedef std::unordered_map AnyStruct; class AnyType { protected: - // void* m_AnyData; public: - // AnyType() : m_AnyData(nullptr) {}; AnyType() = default; - // virtual void* getAnyDataPtr() const = 0; - virtual ~AnyType() = default; // Integers @@ -60,7 +55,6 @@ class AnyType // virtual bool asMatrixDouble(Eigen::MatrixXd mat) = 0; // Vector - virtual bool asVectorDouble(Eigen::VectorXd& vec) = 0; virtual bool asVectorDouble(std::vector& vec) = 0; }; diff --git a/MxAnyType/include/MxAnyType.h b/MxAnyType/include/MxAnyType.h index 21fc7090f..b8990b741 100644 --- a/MxAnyType/include/MxAnyType.h +++ b/MxAnyType/include/MxAnyType.h @@ -92,7 +92,6 @@ class MxAnyType : public AnyType // VECTOR // ====== - bool asVectorDouble(Eigen::VectorXd& vec) override; bool asVectorDouble(std::vector& vec) override; }; diff --git a/MxAnyType/src/MxAnyType.cpp b/MxAnyType/src/MxAnyType.cpp index 77a2f10f4..55e7fe61c 100644 --- a/MxAnyType/src/MxAnyType.cpp +++ b/MxAnyType/src/MxAnyType.cpp @@ -184,8 +184,9 @@ bool MxAnyType::asAnyCell(AnyCell& cell) // VECTOR // ====== -// TODO tests with other types (uint8) https://it.mathworks.com/help/matlab/apiref/mxgetdata.html (Descriptio) -bool MxAnyType::asVectorDouble(Eigen::VectorXd& vec) +// TODO: +// Tests with other types (uint8) https://it.mathworks.com/help/matlab/apiref/mxgetdata.html (Description) +bool MxAnyType::asVectorDouble(std::vector& vec) { if (!mx) return false; if (!mxIsDouble(mx)) return false; @@ -200,14 +201,7 @@ bool MxAnyType::asVectorDouble(Eigen::VectorXd& vec) double* buffer = mxGetPr(mx); if (!buffer) return false; - vec = Eigen::Map(buffer, md.nElem); - return true; -} - -bool MxAnyType::asVectorDouble(std::vector& vec) -{ - Eigen::VectorXd vecEigen; - if (!asVectorDouble(vecEigen)) return false; - vec.assign(vecEigen.data(), vecEigen.data() + vecEigen.rows() * vecEigen.cols()); + vec.reserve(md.rows * md.cols); + vec.assign(buffer, buffer + md.rows * md.cols); return true; } From d4dd040fc443c44f691e98a119acef03337e9c6d Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 13 Nov 2017 09:32:24 +0000 Subject: [PATCH 44/92] Disabled InverseKinematics block The algorithm used by IK will be ported in another task from iKin to iDynTree --- toolbox/CMakeLists.txt | 32 ++++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 93f3a71b7..007f2d0e5 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -80,11 +80,11 @@ configure_block(BLOCK_NAME "Base" include/base/RobotInterface.h ) -configure_block(BLOCK_NAME "Inverse Kinematics" - GROUP "Model" - LIST_PREFIX WBT - SOURCES src/RemoteInverseKinematics.cpp - HEADERS include/RemoteInverseKinematics.h) +# configure_block(BLOCK_NAME "Inverse Kinematics" +# GROUP "Model" +# LIST_PREFIX WBT +# SOURCES src/RemoteInverseKinematics.cpp +# HEADERS include/RemoteInverseKinematics.h) option(WBT_USES_ICUB "Build models which need iCub library (e.g. Minimum Jerk Traj. Generator)" ON) if (WBT_USES_ICUB) @@ -97,17 +97,17 @@ if (WBT_USES_ICUB) SOURCES src/MinimumJerkTrajectoryGenerator.cpp HEADERS include/MinimumJerkTrajectoryGenerator.h) - if (${ICUB_USE_IPOPT}) - find_package(iDynTree REQUIRED) - add_definitions(-DWBT_USES_IPOPT) - configure_block(BLOCK_NAME "Inverse Kinematics" - GROUP "Model" - LIST_PREFIX WBT - SOURCES src/InverseKinematics.cpp - HEADERS include/InverseKinematics.h) - - include_directories(SYSTEM ${iKin_INCLUDE_DIRS}) - endif() + # if (${ICUB_USE_IPOPT}) + # find_package(iDynTree REQUIRED) + # add_definitions(-DWBT_USES_IPOPT) + # configure_block(BLOCK_NAME "Inverse Kinematics" + # GROUP "Model" + # LIST_PREFIX WBT + # SOURCES src/InverseKinematics.cpp + # HEADERS include/InverseKinematics.h) + # + # include_directories(SYSTEM ${iKin_INCLUDE_DIRS}) + # endif() include_directories(SYSTEM ${ctrlLib_INCLUDE_DIRS}) endif() From f2f31caaf43fd979448c56e1ee4b533cf5e8fd2c Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 13 Nov 2017 13:16:03 +0000 Subject: [PATCH 45/92] Switched to smart pointers for private members of all the blocks --- toolbox/include/CentroidalMomentum.h | 5 +++- toolbox/include/DotJNu.h | 5 +++- toolbox/include/ForwardKinematics.h | 3 ++ toolbox/include/GetLimits.h | 1 + toolbox/include/InverseDynamics.h | 9 ++++-- toolbox/include/Jacobian.h | 6 ++-- toolbox/include/MassMatrix.h | 5 ++-- .../include/MinimumJerkTrajectoryGenerator.h | 8 +++-- toolbox/include/ModelPartitioner.h | 1 + toolbox/include/SetReferences.h | 1 + toolbox/include/SimulatorSynchronizer.h | 3 +- toolbox/include/YarpClock.h | 3 ++ toolbox/include/YarpRead.h | 4 ++- toolbox/include/YarpWrite.h | 4 ++- toolbox/src/CentroidalMomentum.cpp | 13 ++------ toolbox/src/DotJNu.cpp | 13 ++------ toolbox/src/InverseDynamics.cpp | 30 +++++-------------- toolbox/src/Jacobian.cpp | 19 +++--------- toolbox/src/MassMatrix.cpp | 13 ++------ .../src/MinimumJerkTrajectoryGenerator.cpp | 24 ++++----------- toolbox/src/SimulatorSynchronizer.cpp | 5 +--- toolbox/src/YarpRead.cpp | 5 +--- toolbox/src/YarpWrite.cpp | 5 +--- 23 files changed, 72 insertions(+), 113 deletions(-) diff --git a/toolbox/include/CentroidalMomentum.h b/toolbox/include/CentroidalMomentum.h index 754e4249b..bfb620a60 100644 --- a/toolbox/include/CentroidalMomentum.h +++ b/toolbox/include/CentroidalMomentum.h @@ -2,6 +2,7 @@ #define WBT_CENTROIDALMOMENTUM_H #include "WBBlock.h" +#include namespace wbt { class CentroidalMomentum; @@ -14,7 +15,7 @@ namespace iDynTree { class wbt::CentroidalMomentum : public wbt::WBBlock { private: - iDynTree::SpatialMomentum* m_centroidalMomentum; + std::unique_ptr m_centroidalMomentum; static const unsigned INPUT_IDX_BASE_POSE; static const unsigned INPUT_IDX_JOINTCONF; @@ -24,7 +25,9 @@ class wbt::CentroidalMomentum : public wbt::WBBlock public: static const std::string ClassName; + CentroidalMomentum(); + ~CentroidalMomentum() override = default; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/DotJNu.h b/toolbox/include/DotJNu.h index 9c70fe864..409a185af 100644 --- a/toolbox/include/DotJNu.h +++ b/toolbox/include/DotJNu.h @@ -2,6 +2,7 @@ #define WBT_DOTJDOTQ_H #include "WBBlock.h" +#include #include #include @@ -13,7 +14,7 @@ class wbt::DotJNu : public wbt::WBBlock { private: // Output - iDynTree::Vector6* m_dotJNu; + std::unique_ptr m_dotJNu; // Other variables bool m_frameIsCoM; @@ -27,7 +28,9 @@ class wbt::DotJNu : public wbt::WBBlock public: static const std::string ClassName; + DotJNu(); + ~DotJNu() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/ForwardKinematics.h b/toolbox/include/ForwardKinematics.h index 4a683e761..4cf69167a 100644 --- a/toolbox/include/ForwardKinematics.h +++ b/toolbox/include/ForwardKinematics.h @@ -2,6 +2,7 @@ #define WBT_FORWARDKINEMATICS_H #include "WBBlock.h" +#include #include namespace wbt { @@ -20,7 +21,9 @@ class wbt::ForwardKinematics : public wbt::WBBlock public: static const std::string ClassName; + ForwardKinematics(); + ~ForwardKinematics() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/GetLimits.h b/toolbox/include/GetLimits.h index fcabddeb0..3a0310fe9 100644 --- a/toolbox/include/GetLimits.h +++ b/toolbox/include/GetLimits.h @@ -27,6 +27,7 @@ class wbt::GetLimits : public wbt::WBBlock public: static const std::string ClassName; + GetLimits() = default; ~GetLimits() override = default; diff --git a/toolbox/include/InverseDynamics.h b/toolbox/include/InverseDynamics.h index 63c8e8a3e..afb1d2ca5 100644 --- a/toolbox/include/InverseDynamics.h +++ b/toolbox/include/InverseDynamics.h @@ -2,6 +2,7 @@ #define WBT_INVERSEDYNAMICS_H #include "WBBlock.h" +#include #include namespace wbt { @@ -16,11 +17,11 @@ namespace iDynTree { class wbt::InverseDynamics : public wbt::WBBlock { private: - iDynTree::Vector6* m_baseAcceleration; - iDynTree::VectorDynSize* m_jointsAcceleration; + std::unique_ptr m_baseAcceleration; + std::unique_ptr m_jointsAcceleration; // Output - iDynTree::FreeFloatingGeneralizedTorques* m_torques; + std::unique_ptr m_torques; static const unsigned INPUT_IDX_BASE_POSE; static const unsigned INPUT_IDX_JOINTCONF; @@ -32,7 +33,9 @@ class wbt::InverseDynamics : public wbt::WBBlock public: static const std::string ClassName; + InverseDynamics(); + ~InverseDynamics() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/Jacobian.h b/toolbox/include/Jacobian.h index 5db8f6d95..a38a968c6 100644 --- a/toolbox/include/Jacobian.h +++ b/toolbox/include/Jacobian.h @@ -2,6 +2,7 @@ #define WBT_JACOBIAN_H #include "WBBlock.h" +#include #include namespace wbt { @@ -16,10 +17,10 @@ class wbt::Jacobian : public wbt::WBBlock { private: // Support variables - iDynTree::MatrixDynSize* m_jacobianCOM; + std::unique_ptr m_jacobianCOM; // Output - iDynTree::MatrixDynSize* m_jacobian; + std::unique_ptr m_jacobian; // Other variables bool m_frameIsCoM; @@ -32,6 +33,7 @@ class wbt::Jacobian : public wbt::WBBlock public: static const std::string ClassName; Jacobian(); + ~Jacobian() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/MassMatrix.h b/toolbox/include/MassMatrix.h index 4ebea06b8..cd048c74d 100644 --- a/toolbox/include/MassMatrix.h +++ b/toolbox/include/MassMatrix.h @@ -2,6 +2,7 @@ #define WBT_MASSMATRIX_H #include "WBBlock.h" +#include namespace wbt { class MassMatrix; @@ -14,7 +15,7 @@ namespace iDynTree { class wbt::MassMatrix : public wbt::WBBlock { private: - iDynTree::MatrixDynSize* m_massMatrix; + std::unique_ptr m_massMatrix; static const unsigned INPUT_IDX_BASE_POSE; static const unsigned INPUT_IDX_JOINTCONF; @@ -23,7 +24,7 @@ class wbt::MassMatrix : public wbt::WBBlock public: static const std::string ClassName; MassMatrix(); - ~MassMatrix() = default; + ~MassMatrix() override = default; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/MinimumJerkTrajectoryGenerator.h b/toolbox/include/MinimumJerkTrajectoryGenerator.h index 5d175e7ab..1e0250a25 100644 --- a/toolbox/include/MinimumJerkTrajectoryGenerator.h +++ b/toolbox/include/MinimumJerkTrajectoryGenerator.h @@ -1,4 +1,5 @@ #include "Block.h" +#include #ifndef WBT_MINJERKTRAJGENERATOR_H #define WBT_MINJERKTRAJGENERATOR_H @@ -25,6 +26,7 @@ class wbt::MinimumJerkTrajectoryGenerator : public wbt::Block { static const std::string ClassName; MinimumJerkTrajectoryGenerator(); + ~MinimumJerkTrajectoryGenerator() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; @@ -34,7 +36,7 @@ class wbt::MinimumJerkTrajectoryGenerator : public wbt::Block { private: - iCub::ctrl::minJerkTrajGen* m_generator; + std::unique_ptr m_generator; int m_outputFirstDerivativeIndex; int m_outputSecondDerivativeIndex; @@ -45,8 +47,8 @@ class wbt::MinimumJerkTrajectoryGenerator : public wbt::Block { bool m_explicitInitialValue; bool m_externalSettlingTime; bool m_resetOnSettlingTimeChange; - yarp::sig::Vector* m_initialValues; - yarp::sig::Vector* m_reference; + std::unique_ptr m_initialValues; + std::unique_ptr m_reference; static const unsigned PARAM_IDX_SAMPLE_TIME; // Sample Time (double) static const unsigned PARAM_IDX_SETTLING_TIME; // Settling Time (double) diff --git a/toolbox/include/ModelPartitioner.h b/toolbox/include/ModelPartitioner.h index 2a8b5c435..32c57c098 100644 --- a/toolbox/include/ModelPartitioner.h +++ b/toolbox/include/ModelPartitioner.h @@ -19,6 +19,7 @@ class wbt::ModelPartitioner : public wbt::WBBlock public: static const std::string ClassName; + ModelPartitioner() = default; ~ModelPartitioner() override = default; diff --git a/toolbox/include/SetReferences.h b/toolbox/include/SetReferences.h index d599a1410..74b5c4b19 100644 --- a/toolbox/include/SetReferences.h +++ b/toolbox/include/SetReferences.h @@ -19,6 +19,7 @@ class wbt::SetReferences : public wbt::WBBlock static const std::string ClassName; SetReferences(); + ~SetReferences() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; diff --git a/toolbox/include/SimulatorSynchronizer.h b/toolbox/include/SimulatorSynchronizer.h index f307c8fc7..7b7793870 100644 --- a/toolbox/include/SimulatorSynchronizer.h +++ b/toolbox/include/SimulatorSynchronizer.h @@ -2,6 +2,7 @@ #define WBT_SIMULATORSYNCHRONIZER_H #include "Block.h" +#include namespace wbt { class SimulatorSynchronizer; @@ -27,7 +28,7 @@ class wbt::SimulatorSynchronizer : public wbt::Block bool m_firstRun; struct RPCData; - RPCData* m_rpcData; + std::unique_ptr m_rpcData; static const unsigned PARAM_PERIOD; // Period static const unsigned PARAM_GZCLK_PORT; // Gazebo clock port diff --git a/toolbox/include/YarpClock.h b/toolbox/include/YarpClock.h index c4857e8e0..430c78838 100644 --- a/toolbox/include/YarpClock.h +++ b/toolbox/include/YarpClock.h @@ -12,6 +12,9 @@ class wbt::YarpClock : public wbt::Block public: static const std::string ClassName; + YarpClock() = default; + ~YarpClock() override = default; + unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; bool initialize(const BlockInformation* blockInfo) override; diff --git a/toolbox/include/YarpRead.h b/toolbox/include/YarpRead.h index 6fed985ad..33d9f6e64 100644 --- a/toolbox/include/YarpRead.h +++ b/toolbox/include/YarpRead.h @@ -2,6 +2,7 @@ #define WBT_YARPREAD_H #include "Block.h" +#include namespace wbt { class YarpRead; @@ -23,6 +24,7 @@ class wbt::YarpRead : public wbt::Block static const std::string ClassName; YarpRead(); + ~YarpRead() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; @@ -36,7 +38,7 @@ class wbt::YarpRead : public wbt::Block bool m_shouldReadTimestamp; bool m_errorOnMissingPort; - yarp::os::BufferedPort* m_port; + std::unique_ptr> m_port; static const unsigned PARAM_IDX_PORTNAME; // port name static const unsigned PARAM_IDX_PORTSIZE; // Size of the port you're reading diff --git a/toolbox/include/YarpWrite.h b/toolbox/include/YarpWrite.h index 4d9e8238b..206567dff 100644 --- a/toolbox/include/YarpWrite.h +++ b/toolbox/include/YarpWrite.h @@ -2,6 +2,7 @@ #define WBT_YARPWRITE_H #include "Block.h" +#include namespace wbt { class YarpWrite; @@ -23,6 +24,7 @@ class wbt::YarpWrite : public wbt::Block static const std::string ClassName; YarpWrite(); + ~YarpWrite() override = default; unsigned numberOfParameters() override; bool configureSizeAndPorts(BlockInformation* blockInfo) override; @@ -35,7 +37,7 @@ class wbt::YarpWrite : public wbt::Block bool m_errorOnMissingPort; std::string m_destinationPortName; - yarp::os::BufferedPort* m_port; + std::unique_ptr> m_port; static const unsigned PARAM_IDX_PORTNAME; // Port name static const unsigned PARAM_IDX_AUTOCONNECT; // Autoconnect boolean diff --git a/toolbox/src/CentroidalMomentum.cpp b/toolbox/src/CentroidalMomentum.cpp index 1294c7e19..58484cb9e 100644 --- a/toolbox/src/CentroidalMomentum.cpp +++ b/toolbox/src/CentroidalMomentum.cpp @@ -20,9 +20,7 @@ const unsigned CentroidalMomentum::INPUT_IDX_BASE_VEL = 2; const unsigned CentroidalMomentum::INPUT_IDX_JOINT_VEL = 3; const unsigned CentroidalMomentum::OUTPUT_IDX_CENTRMOM = 0; -CentroidalMomentum::CentroidalMomentum() -: m_centroidalMomentum(nullptr) -{} +CentroidalMomentum::CentroidalMomentum() {} bool CentroidalMomentum::configureSizeAndPorts(BlockInformation* blockInfo) { @@ -90,17 +88,12 @@ bool CentroidalMomentum::initialize(const BlockInformation* blockInfo) // OUTPUT // ====== - m_centroidalMomentum = new iDynTree::SpatialMomentum(); - return m_centroidalMomentum; + m_centroidalMomentum = std::unique_ptr(new iDynTree::SpatialMomentum()); + return static_cast(m_centroidalMomentum); } bool CentroidalMomentum::terminate(const BlockInformation* blockInfo) { - if (m_centroidalMomentum) { - delete m_centroidalMomentum; - m_centroidalMomentum = 0; - } - return WBBlock::terminate(blockInfo); } diff --git a/toolbox/src/DotJNu.cpp b/toolbox/src/DotJNu.cpp index 7c82c2c39..e984d7a96 100644 --- a/toolbox/src/DotJNu.cpp +++ b/toolbox/src/DotJNu.cpp @@ -20,8 +20,7 @@ const unsigned DotJNu::INPUT_IDX_JOINT_VEL = 3; const unsigned DotJNu::OUTPUT_IDX_DOTJ_NU = 0; DotJNu::DotJNu() -: m_dotJNu(nullptr) -, m_frameIsCoM(false) +: m_frameIsCoM(false) , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) {} @@ -127,20 +126,14 @@ bool DotJNu::initialize(const BlockInformation* blockInfo) // OUTPUT // ====== - m_dotJNu = new iDynTree::Vector6(); + m_dotJNu = std::unique_ptr(new iDynTree::Vector6()); m_dotJNu->zero(); - return m_dotJNu; + return static_cast(m_dotJNu); } bool DotJNu::terminate(const BlockInformation* blockInfo) { - // Output - if (m_dotJNu) { - delete m_dotJNu; - m_dotJNu = 0; - } - return WBBlock::terminate(blockInfo); } diff --git a/toolbox/src/InverseDynamics.cpp b/toolbox/src/InverseDynamics.cpp index 5aa635a93..e0303b97e 100644 --- a/toolbox/src/InverseDynamics.cpp +++ b/toolbox/src/InverseDynamics.cpp @@ -22,11 +22,7 @@ const unsigned InverseDynamics::INPUT_IDX_BASE_ACC = 4; const unsigned InverseDynamics::INPUT_IDX_JOINT_ACC = 5; const unsigned InverseDynamics::OUTPUT_IDX_TORQUES = 0; -InverseDynamics::InverseDynamics() -: m_baseAcceleration(nullptr) -, m_jointsAcceleration(nullptr) -, m_torques(nullptr) -{} +InverseDynamics::InverseDynamics() {} unsigned InverseDynamics::numberOfParameters() { @@ -106,34 +102,24 @@ bool InverseDynamics::initialize(const BlockInformation* blockInfo) // OUTPUT / VARIABLES // ================== + using namespace iDynTree; const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_baseAcceleration = new iDynTree::Vector6(); + m_baseAcceleration = std::unique_ptr(new Vector6()); m_baseAcceleration->zero(); - m_jointsAcceleration = new iDynTree::VectorDynSize(dofs); + m_jointsAcceleration = std::unique_ptr(new VectorDynSize(dofs)); m_jointsAcceleration->zero(); const auto& model = getRobotInterface()->getKinDynComputations()->model(); - m_torques = new iDynTree::FreeFloatingGeneralizedTorques(model); + m_torques = std::unique_ptr(new FreeFloatingGeneralizedTorques(model)); - return m_baseAcceleration && m_jointsAcceleration && m_torques; + return static_cast(m_baseAcceleration) && + static_cast(m_jointsAcceleration) && + static_cast(m_torques); } bool InverseDynamics::terminate(const BlockInformation* blockInfo) { - if (m_baseAcceleration) { - delete m_baseAcceleration; - m_baseAcceleration = nullptr; - } - if (m_jointsAcceleration) { - delete m_jointsAcceleration; - m_jointsAcceleration = nullptr; - } - if (m_torques) { - delete m_torques; - m_torques = nullptr; - } - return WBBlock::terminate(blockInfo); } diff --git a/toolbox/src/Jacobian.cpp b/toolbox/src/Jacobian.cpp index 4901c7ebc..901a0a822 100644 --- a/toolbox/src/Jacobian.cpp +++ b/toolbox/src/Jacobian.cpp @@ -18,9 +18,7 @@ const unsigned Jacobian::INPUT_IDX_JOINTCONF = 1; const unsigned Jacobian::OUTPUT_IDX_FW_FRAME = 0; Jacobian::Jacobian() -: m_jacobianCOM(nullptr) -, m_jacobian(nullptr) -, m_frameIsCoM(false) +: m_frameIsCoM(false) , m_frameIndex(iDynTree::FRAME_INVALID_INDEX) {} @@ -124,27 +122,18 @@ bool Jacobian::initialize(const BlockInformation* blockInfo) const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_jacobianCOM = new iDynTree::MatrixDynSize(3, 6 + dofs); + m_jacobianCOM = std::unique_ptr(new iDynTree::MatrixDynSize(3, 6 + dofs)); m_jacobianCOM->zero(); // Output - m_jacobian = new iDynTree::MatrixDynSize(6, 6 + dofs); + m_jacobian = std::unique_ptr(new iDynTree::MatrixDynSize(6, 6 + dofs)); m_jacobian->zero(); - return m_jacobianCOM && m_jacobian; + return static_cast(m_jacobianCOM) && static_cast(m_jacobian); } bool Jacobian::terminate(const BlockInformation* blockInfo) { - if (m_jacobianCOM) { - delete m_jacobianCOM; - m_jacobianCOM = nullptr; - } - if (m_jacobian) { - delete m_jacobian; - m_jacobian = nullptr; - } - return WBBlock::terminate(blockInfo); } diff --git a/toolbox/src/MassMatrix.cpp b/toolbox/src/MassMatrix.cpp index 96f841253..a14a9f78c 100644 --- a/toolbox/src/MassMatrix.cpp +++ b/toolbox/src/MassMatrix.cpp @@ -17,9 +17,7 @@ const unsigned MassMatrix::INPUT_IDX_BASE_POSE = 0; const unsigned MassMatrix::INPUT_IDX_JOINTCONF = 1; const unsigned MassMatrix::OUTPUT_IDX_MASS_MAT = 0; -MassMatrix::MassMatrix() -: m_massMatrix(nullptr) -{} +MassMatrix::MassMatrix() {} bool MassMatrix::configureSizeAndPorts(BlockInformation* blockInfo) { @@ -83,19 +81,14 @@ bool MassMatrix::initialize(const BlockInformation* blockInfo) const unsigned dofs = getConfiguration().getNumberOfDoFs(); // Output - m_massMatrix = new iDynTree::MatrixDynSize(6 + dofs, 6 + dofs); + m_massMatrix = std::unique_ptr(new iDynTree::MatrixDynSize(6 + dofs, 6 + dofs)); m_massMatrix->zero(); - return m_massMatrix; + return static_cast(m_massMatrix); } bool MassMatrix::terminate(const BlockInformation* blockInfo) { - if (m_massMatrix) { - delete m_massMatrix; - m_massMatrix = nullptr; - } - return WBBlock::terminate(blockInfo); } diff --git a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp index 80505a592..d550be5fd 100644 --- a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp +++ b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp @@ -26,15 +26,12 @@ const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_EXT_SETTLINGTIME = 6; const unsigned MinimumJerkTrajectoryGenerator::PARAM_IDX_RESET_CHANGEST = 7; MinimumJerkTrajectoryGenerator::MinimumJerkTrajectoryGenerator() -: m_generator(nullptr) -, m_outputFirstDerivativeIndex(-1) +: m_outputFirstDerivativeIndex(-1) , m_outputSecondDerivativeIndex(-1) , m_firstRun(true) , m_explicitInitialValue(false) , m_externalSettlingTime(false) , m_resetOnSettlingTimeChange(false) -, m_initialValues(nullptr) -, m_reference(nullptr) {} unsigned MinimumJerkTrajectoryGenerator::numberOfParameters() { return 7; } @@ -165,10 +162,11 @@ bool MinimumJerkTrajectoryGenerator::initialize(const BlockInformation* blockInf unsigned signalSize = blockInfo->getInputPortWidth(0); - m_generator = new iCub::ctrl::minJerkTrajGen(signalSize, sampleTime, settlingTime); + m_generator = std::unique_ptr + (new iCub::ctrl::minJerkTrajGen(signalSize, sampleTime, settlingTime)); m_previousSettlingTime = settlingTime; - m_initialValues = new yarp::sig::Vector(signalSize); - m_reference = new yarp::sig::Vector(signalSize); + m_initialValues = std::unique_ptr(new yarp::sig::Vector(signalSize)); + m_reference = std::unique_ptr(new yarp::sig::Vector(signalSize)); if (!m_generator || !m_initialValues || !m_reference) { Log::getSingleton().error("Could not allocate memory for trajectory generator."); @@ -181,18 +179,6 @@ bool MinimumJerkTrajectoryGenerator::initialize(const BlockInformation* blockInf bool MinimumJerkTrajectoryGenerator::terminate(const BlockInformation* blockInfo) { - if (m_generator) { - delete m_generator; - m_generator = nullptr; - } - if (m_initialValues) { - delete m_initialValues; - m_initialValues = nullptr; - } - if (m_reference) { - delete m_reference; - m_reference = nullptr; - } return true; } diff --git a/toolbox/src/SimulatorSynchronizer.cpp b/toolbox/src/SimulatorSynchronizer.cpp index 20f43456b..2f0c834fa 100644 --- a/toolbox/src/SimulatorSynchronizer.cpp +++ b/toolbox/src/SimulatorSynchronizer.cpp @@ -31,7 +31,6 @@ const unsigned SimulatorSynchronizer::PARAM_RPC_PORT = 3; SimulatorSynchronizer::SimulatorSynchronizer() : m_period(0.01) , m_firstRun(true) -, m_rpcData(0) {} unsigned SimulatorSynchronizer::numberOfParameters() { return 3; } @@ -89,7 +88,7 @@ bool SimulatorSynchronizer::initialize(const BlockInformation* blockInfo) return false; } - m_rpcData = new struct RPCData(); + m_rpcData = std::unique_ptr(new struct RPCData()); if (!m_rpcData) { Log::getSingleton().error("Error creating RPC data structure."); return false; @@ -114,8 +113,6 @@ bool SimulatorSynchronizer::terminate(const BlockInformation* /*S*/) } m_rpcData->clientPort.close(); } - delete m_rpcData; - m_rpcData = nullptr; } yarp::os::Network::fini(); return true; diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 683af090f..023fb7701 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -28,7 +28,6 @@ YarpRead::YarpRead() , m_blocking(false) , m_shouldReadTimestamp(false) , m_errorOnMissingPort(true) -, m_port(0) {} unsigned YarpRead::numberOfParameters() { return 6; } @@ -146,7 +145,7 @@ bool YarpRead::initialize(const BlockInformation* blockInfo) destinationPortName = portName; } - m_port = new BufferedPort(); + m_port = std::unique_ptr>(new BufferedPort()); if (!m_port || !m_port->open(destinationPortName)) { Log::getSingleton().error("Error while opening yarp port."); @@ -172,8 +171,6 @@ bool YarpRead::terminate(const BlockInformation* /*blockInfo*/) { if (m_port) { m_port->close(); - delete m_port; - m_port = nullptr; } yarp::os::Network::fini(); return true; diff --git a/toolbox/src/YarpWrite.cpp b/toolbox/src/YarpWrite.cpp index 3deba6dcc..6b50029d9 100644 --- a/toolbox/src/YarpWrite.cpp +++ b/toolbox/src/YarpWrite.cpp @@ -21,7 +21,6 @@ YarpWrite::YarpWrite() : m_autoconnect(false) , m_errorOnMissingPort(true) , m_destinationPortName("") -, m_port(nullptr) {} unsigned YarpWrite::numberOfParameters() { return 3; } @@ -98,7 +97,7 @@ bool YarpWrite::initialize(const BlockInformation* blockInfo) sourcePortName = portParameter; } - m_port = new BufferedPort(); + m_port = std::unique_ptr>(new BufferedPort()); if (!m_port || !m_port->open(sourcePortName)) { Log::getSingleton().error("Error while opening yarp port."); @@ -131,8 +130,6 @@ bool YarpWrite::terminate(const BlockInformation* /*S*/) yarp::os::Network::disconnect(m_port->getName(), m_destinationPortName); } m_port->close(); - delete m_port; - m_port = nullptr; } yarp::os::Network::fini(); return true; From e0e7a9263926c64ae59aadb4d046418e94b48241 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Mon, 13 Nov 2017 13:48:53 +0000 Subject: [PATCH 46/92] Forgot class scope for two static methods --- toolbox/src/GetMeasurement.cpp | 2 +- toolbox/src/SetReferences.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index 65cc1a49e..659c921d7 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -14,7 +14,7 @@ using namespace wbt; const std::string GetMeasurement::ClassName = "GetMeasurement"; -void deg2rad(std::vector& v) +void GetMeasurement::deg2rad(std::vector& v) { const double deg2rad = (2 * M_PI) / 180.0; for (auto& element : v) { diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index c739b0e44..6e20ed9db 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -17,7 +17,7 @@ SetReferences::SetReferences() : m_resetControlMode(true) {} -void rad2deg(std::vector& v) +void SetReferences::rad2deg(std::vector& v) { const double rad2deg = 180.0 / (2 * M_PI); for (auto& element : v) { From f64da6e3adfd1b5323a0bd3228f227cbda2bfe14 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 09:48:01 +0000 Subject: [PATCH 47/92] Follow links in Simulink model inspection for finding the Config Block When the Config block (which is a subsystem) is included into a library, for finding the blocks contained into its subsystem, `FollowLinks` must be enabled --- +WBToolbox/BlockInitialization.m | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/+WBToolbox/BlockInitialization.m b/+WBToolbox/BlockInitialization.m index 5783432e0..cc335147d 100644 --- a/+WBToolbox/BlockInitialization.m +++ b/+WBToolbox/BlockInitialization.m @@ -13,14 +13,14 @@ topLevel = blockNameSplit{1}; % Get all the blocks from the top level of the system - blocks_system = find_system(topLevel,'LookUnderMasks','on'); + blocks_system = find_system(topLevel,'LookUnderMasks','on','FollowLinks','on'); % Get the name of the block's subsystem %[blockScopeName,~] = fileparts(blockAbsoluteName); %blockScopeName = gcs; blockScopeName = currentSystem; catch - error('[%s::Initialization] Failed to process model''s tree',char(blockAbsoluteName)) + error('[%s::Initialization] Failed to process model''s tree', char(currentBlock)) end % Look a config block from the block's scope going up in the tree @@ -30,7 +30,7 @@ rule = strcat(strrep(analyzedScope,'/','\/'),'\/\w+\/ImConfig'); idx = cellfun(@(x) ~isequal(regexp(x,rule),[]), blocks_system); if (sum(idx) > 1) - error('[%s::Initialization] Found more than one configuration',char(blockAbsoluteName)); + error('[%s::Initialization] Found more than one configuration', char(currentBlock)); elseif (sum(idx) == 1) configBlock = blocks_system{idx}; configBlock = fileparts(configBlock); @@ -40,7 +40,7 @@ end if isempty(configBlock) - error('[%s::Initialization] No configuration found',char(blockAbsoluteName)); + error('[%s::Initialization] No configuration found', char(currentBlock)); end configSource = get_param(configBlock,'ConfigSource'); @@ -55,7 +55,7 @@ % Read the mask WBTConfig = WBToolbox.Mask2WBToolboxConfig(configBlock); else - error('[%s::Initialization] Read ConfigSource from Config block not recognized',char(blockAbsoluteName)); + error('[%s::Initialization] Read ConfigSource from Config block not recognized', char(currentBlock)); end end From eb0e1b751746f10fa8b0318aa122c345d9299212 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:06:34 +0000 Subject: [PATCH 48/92] Retaining the RemoteControlBoardRemapper needs a unique port prefix If there are two robot configurations in the same system which share some of the ControlBoards, the RemoteControlBoardRemapper devices cannot be allocated with the same port prefix. As a workaround, a new function to generate an unique identifier for every Configuration object has been included. Under the hood it uses the Simulink's block name (which is unique). Furthermore, the initialization of the Yarp Network was missing at this stage of the execution. --- toolbox/include/base/Configuration.h | 16 ++++- toolbox/src/base/Configuration.cpp | 26 ++++++- toolbox/src/base/RobotInterface.cpp | 100 ++++++++++++++++----------- toolbox/src/base/WBBlock.cpp | 5 +- 4 files changed, 101 insertions(+), 46 deletions(-) diff --git a/toolbox/include/base/Configuration.h b/toolbox/include/base/Configuration.h index 9b70142ac..b131ce81a 100644 --- a/toolbox/include/base/Configuration.h +++ b/toolbox/include/base/Configuration.h @@ -21,6 +21,7 @@ class wbt::Configuration { // TODO: check how localName is used private: + const std::string m_confKey; ///< Name of the block which this object refers to std::string m_robotName; ///< Name of the robot std::string m_urdfFile; ///< Name of the file containing the urdf model std::string m_localName; ///< Prefix appended to the opened ports @@ -30,7 +31,8 @@ class wbt::Configuration size_t m_dofs; //< DoFs extracted my m_controlBoardsNames vector public: - Configuration(); + Configuration() = delete; + Configuration(const std::string& confKey); ~Configuration() = default; // SET METHODS @@ -123,12 +125,22 @@ class wbt::Configuration const std::vector& getControlBoardsNames() const; /** - * Set the prefix appended to the opened ports + * Set the prefix appended to the opened ports. A leading "/" is always present. * * @return Prefix appended to the opened ports */ const std::string& getLocalName() const; + /** + * Get a string with a unique identifier, generated from the name of the config + * block from Simulink. It might be useful when yarp ports must have a unique prefix + * (e.g. two RemoteControlBoardRemappers which share a ControlBoard) + * + * @return the unique identifier + * @see setLocalName + */ + const std::string getUniqueId() const; + /** * Set the gravity vector * diff --git a/toolbox/src/base/Configuration.cpp b/toolbox/src/base/Configuration.cpp index a963a3b41..257a475f4 100644 --- a/toolbox/src/base/Configuration.cpp +++ b/toolbox/src/base/Configuration.cpp @@ -1,9 +1,11 @@ #include "Configuration.h" +#include using namespace wbt; -Configuration::Configuration() -: m_dofs(0) +Configuration::Configuration(const std::string& confKey) +: m_confKey(confKey) +, m_dofs(0) {} // SET METHODS @@ -48,6 +50,26 @@ void Configuration::setControlBoardsNames(const std::vector& contro void Configuration::setLocalName(const std::string& localName) { m_localName = localName; + + // Add the leading "/" if missing + if (m_localName.compare(0, 1, "/")) { + m_localName = "/" + m_localName; + } +} + +const std::string Configuration::getUniqueId() const +{ + std::string uniqueId(m_confKey); + + // Remove spaces + auto it = std::remove(uniqueId.begin(), uniqueId.end(), ' '); + uniqueId.erase(it , uniqueId.end()); + + // Remove '/' + it = std::remove(uniqueId.begin(), uniqueId.end(), '/'); + uniqueId.erase(it , uniqueId.end()); + + return uniqueId; } void Configuration::setGravityVector(const std::array& gravityVector) diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index 4e1fccbb0..05cfcb9c0 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -11,7 +11,6 @@ #include namespace wbt { - static std::string vectorToString(std::vector v, std::string prefix=""); // The declaration of the following template specializations are required only by GCC using namespace yarp::dev; @@ -318,6 +317,9 @@ bool RobotInterface::releaseRemoteControlBoardRemapper() m_robotDevice.reset(); } + // Initialize the network + yarp::os::Network::init(); + m_robotDeviceCounter = 0; return true; } @@ -367,32 +369,75 @@ bool RobotInterface::initializeModel() bool RobotInterface::initializeRemoteControlBoardRemapper() { - // Setup the RemoteControlBoardRemapper + // Initialize the network + yarp::os::Network::init(); + if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork(5.0)) { + Log::getSingleton().error("YARP server wasn't found active!!"); + return false; + } + + // Object where the RemoteControlBoardRemapper options will be stored yarp::os::Property options; + + // Name of the device options.put("device", "remotecontrolboardremapper"); - options.put("axesNames", vectorToString(m_config.getControlledJoints())); - std::string prefix = "/" + m_config.getRobotName() + "/"; - options.put("remoteControlBoards", vectorToString(m_config.getControlBoardsNames(), prefix)); - options.put("localPortPrefix", m_config.getLocalName()); + + // Controlled joints (axes) + yarp::os::Bottle axesNames; + yarp::os::Bottle& axesList = axesNames.addList(); + for (auto axis : m_config.getControlledJoints()) { + axesList.addString(axis); + } + options.put("axesNames",axesNames.get(0)); + + // ControlBoard names + yarp::os::Bottle remoteControlBoards; + yarp::os::Bottle& remoteControlBoardsList = remoteControlBoards.addList(); + for (auto cb : m_config.getControlBoardsNames()) { + remoteControlBoardsList.addString("/" + m_config.getRobotName() + "/" + cb); + } + options.put("remoteControlBoards", remoteControlBoards.get(0)); + + // Prefix of the openened ports + // In this case appending the unique id is necessary, since multiple configuration can + // share some ControlBoard in their RemoteControlBoardRemappers. In this case, it is not + // possible using the same prefix for all the RemoteControlBoardRemapper devices. + options.put("localPortPrefix", m_config.getLocalName() + "/" + m_config.getUniqueId()); + + // Misc options yarp::os::Property& remoteCBOpts = options.addGroup("REMOTE_CONTROLBOARD_OPTIONS"); - remoteCBOpts.put("writeStrict","on"); + remoteCBOpts.put("writeStrict", "on"); - // Allocate the device driver - assert(!m_robotDevice); + // If resources have been properly cleaned, there should be no allocated device. + // However, if blocks fail and they don't terminate, the state of the singleton + // could be not clean. + if (m_robotDevice) { + // Force the release + m_robotDeviceCounter = 1; + Log::getSingleton().warning("The ToolboxSingleton state is dirty. Trying to clean the state before proceeding."); + if (!releaseRemoteControlBoardRemapper()) { + Log::getSingleton().error("Failed to force the release of the RemoteControlBoardRemapper. "); + return false; + } + } + + // Allocate the interface driver m_robotDevice = std::unique_ptr(new yarp::dev::PolyDriver()); if (!m_robotDevice) { + Log::getSingleton().error("Failed to instantiante an empty PolyDriver class."); return false; } - // Open the device driver - if (m_robotDevice->open(options) && m_robotDevice->isValid()) { - return true; + // Open the interface driver + if (!m_robotDevice->open(options) && !m_robotDevice->isValid()) { + // Remove garbage if the opening fails + m_robotDevice.reset(); + Log::getSingleton().error("Failed to open the RemoteControlBoardRemapper with the options passed."); + return false; } - // Remove garbage if the opening fails - m_robotDevice.reset(); - return false; + return true; } // OTHER METHODS @@ -421,28 +466,3 @@ std::weak_ptr RobotInterface::getInterfaceFromTemplate(std::shared_ptr dev // Implicit conversion from shared_ptr to weak_ptr return device; } - -/** - * Converts a vector of strings into a string format \code (element1 element2 element3) \endcode. - * It optioanlly support appending a prefix to the elements. e.g. - * \code ({prefix}element1 {prefix}element2 {prefix}element3) - * - * @param v The vector of strings - * @param prefix The optional element prefix - * @return The serialized string - */ -std::string wbt::vectorToString(std::vector v, std::string prefix) -{ - // Add the prefix if specified - if (!prefix.empty()) { - for (auto& str : v) { - str = prefix + str; - } - } - - // Create a string in a format which YARP likes: (item1 item2 item3) - std::stringstream output; - std::ostream_iterator output_iterator(output, " "); - std::copy(v.begin(), v.end(), output_iterator); - return "(" + output.str() + ")"; -} diff --git a/toolbox/src/base/WBBlock.cpp b/toolbox/src/base/WBBlock.cpp index 0c344e33f..d4acfbb3f 100644 --- a/toolbox/src/base/WBBlock.cpp +++ b/toolbox/src/base/WBBlock.cpp @@ -181,8 +181,9 @@ bool WBBlock::configureSizeAndPorts(BlockInformation* blockInfo) return false; } - // Get the configuration struct from the block - Configuration config; + // Initialize the configuration block with the unique identifier of the conf block name + Configuration config(confKey); + // Populate the configuration object with data from the Simulink's struct parameter if (!getWBToolboxParameters(config, blockInfo)) { return false; } From 1f3f8a2eb5536ac914dbde49bc735642c0edff62 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:20:18 +0000 Subject: [PATCH 49/92] Switch from smart pointers to raw pointers for Yarp interfaces Using smart pointers on yarp interfaces is not possible because their allocation is handled internally by the device from which they are asked from. As minor edit, renamed YarpDevices variable to YarpInterfaces for the sake of clarity. --- toolbox/include/base/RobotInterface.h | 49 ++++++---- toolbox/src/base/RobotInterface.cpp | 127 +++++++++++++------------- 2 files changed, 94 insertions(+), 82 deletions(-) diff --git a/toolbox/include/base/RobotInterface.h b/toolbox/include/base/RobotInterface.h index 6b85789d3..489bf0f35 100644 --- a/toolbox/include/base/RobotInterface.h +++ b/toolbox/include/base/RobotInterface.h @@ -31,7 +31,7 @@ namespace iDynTree { namespace wbt { class RobotInterface; - struct YarpDevices; + struct YarpInterfaces; typedef int jointIdx_yarp; typedef int jointIdx_iDynTree; @@ -41,7 +41,7 @@ namespace wbt { } /** - * \struct wbt::YarpDevices RobotInterface.h + * \struct wbt::YarpInterfaces RobotInterface.h * * This struct contains shared_ptrs to the devices which are (lazy) asked from the blocks. * @@ -54,18 +54,31 @@ namespace wbt { * containing only the reduced set in a deeper-hierarchy Simulink's subsystem. * @see RobotInterface::getDevice */ -struct wbt::YarpDevices +struct wbt::YarpInterfaces { - std::shared_ptr iControlMode2; - std::shared_ptr iPositionControl; - std::shared_ptr iPositionDirect; - std::shared_ptr iVelocityControl; - std::shared_ptr iTorqueControl; - std::shared_ptr iPWMControl; - std::shared_ptr iCurrentControl; - std::shared_ptr iEncoders; - std::shared_ptr iControlLimits2; - std::shared_ptr iPidControl; + yarp::dev::IControlMode2* iControlMode2; + yarp::dev::IPositionControl* iPositionControl; + yarp::dev::IPositionDirect* iPositionDirect; + yarp::dev::IVelocityControl* iVelocityControl; + yarp::dev::ITorqueControl* iTorqueControl; + yarp::dev::IPWMControl* iPWMControl; + yarp::dev::ICurrentControl* iCurrentControl; + yarp::dev::IEncoders* iEncoders; + yarp::dev::IControlLimits2* iControlLimits2; + yarp::dev::IPidControl* iPidControl; + + YarpInterfaces() + : iControlMode2(nullptr) + , iPositionControl(nullptr) + , iPositionDirect(nullptr) + , iVelocityControl(nullptr) + , iTorqueControl(nullptr) + , iPWMControl(nullptr) + , iCurrentControl(nullptr) + , iEncoders(nullptr) + , iControlLimits2(nullptr) + , iPidControl(nullptr) + {} }; // TODO o pensare come evitare di avere due conf con es position e torque nei setref con lo stesso robot. @@ -80,7 +93,7 @@ struct wbt::YarpDevices * with the specified robot (real or model). * * @see wbt::Configuration - * @see wbt::YarpDevices + * @see wbt::YarpInterfaces * @see iDynTree::KinDynComputations */ class wbt::RobotInterface @@ -88,7 +101,7 @@ class wbt::RobotInterface private: std::unique_ptr m_robotDevice; std::shared_ptr m_kinDynComp; - wbt::YarpDevices m_yarpDevices; + wbt::YarpInterfaces m_yarpInterfaces; // Maps used to store infos about yarp's and idyntree's internal joint indexing std::shared_ptr m_jointsMapIndex; @@ -133,7 +146,7 @@ class wbt::RobotInterface * @tparam T The type of the retured device */ template - std::weak_ptr getInterfaceFromTemplate(std::shared_ptr device); + T* getInterfaceFromTemplate(T*& device); /** * Creates the map between joints (specified as either names or idyntree indices) and @@ -196,7 +209,7 @@ class wbt::RobotInterface * @tparam T The type of interface */ template - bool getInterface(std::weak_ptr& interface); + bool getInterface(T*& interface); // LAZY EVALUATION // =============== @@ -205,7 +218,7 @@ class wbt::RobotInterface * Handles the internal counter for using the RemoteControlBoardRemapper * * @attention All the blocks which need to use any of the interfaces provided by - * wbt::YarpDevices must call this function in their initialize() method. + * wbt::YarpInterfaces must call this function in their initialize() method. * @see releaseRemoteControlBoardRemapper * * @return True if success diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index 05cfcb9c0..bfda124ca 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -14,16 +14,16 @@ namespace wbt { // The declaration of the following template specializations are required only by GCC using namespace yarp::dev; - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); - template <> bool RobotInterface::getInterface(std::weak_ptr& interface); + template <> bool RobotInterface::getInterface(IControlMode2*& interface); + template <> bool RobotInterface::getInterface(IPositionControl*& interface); + template <> bool RobotInterface::getInterface(IPositionDirect*& interface); + template <> bool RobotInterface::getInterface(IVelocityControl*& interface); + template <> bool RobotInterface::getInterface(ITorqueControl*& interface); + template <> bool RobotInterface::getInterface(IPWMControl*& interface); + template <> bool RobotInterface::getInterface(ICurrentControl*& interface); + template <> bool RobotInterface::getInterface(IEncoders*& interface); + template <> bool RobotInterface::getInterface(IControlLimits2*& interface); + template <> bool RobotInterface::getInterface(IPidControl*& interface); } using namespace wbt; @@ -81,7 +81,7 @@ bool RobotInterface::mapDoFs() return false; } - // Get an IEncoders object from the device + // Get an IEncoders object from the interface // This is used to get how many joints the control board contains std::unique_ptr iEnc; yarp::dev::IEncoders* iEncPtr = iEnc.get(); @@ -192,73 +192,73 @@ const std::shared_ptr RobotInterface::getKinDynCom } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IControlMode2*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iControlMode2); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iControlMode2); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IPositionControl*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iPositionControl); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iPositionControl); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IPositionDirect*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iPositionDirect); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iPositionDirect); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IVelocityControl*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iVelocityControl); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iVelocityControl); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::ITorqueControl*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iTorqueControl); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iTorqueControl); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IPWMControl*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iPWMControl); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iPWMControl); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::ICurrentControl*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iCurrentControl); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iCurrentControl); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IEncoders*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iEncoders); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iEncoders); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IControlLimits2*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iControlLimits2); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iControlLimits2); + return interface; } template <> -bool RobotInterface::getInterface(std::weak_ptr& interface) +bool RobotInterface::getInterface(yarp::dev::IPidControl*& interface) { - interface = getInterfaceFromTemplate(m_yarpDevices.iPidControl); - return !interface.expired(); + interface = getInterfaceFromTemplate(m_yarpInterfaces.iPidControl); + return interface; } // LAZY EVALUATION @@ -300,18 +300,18 @@ bool RobotInterface::releaseRemoteControlBoardRemapper() // This should be executed by the last block which uses CB (m_robotDeviceCounter=1) assert(m_robotDevice); if (m_robotDevice) { - // Free all the drivers - m_yarpDevices.iControlMode2.reset(); - m_yarpDevices.iPositionControl.reset(); - m_yarpDevices.iPositionDirect.reset(); - m_yarpDevices.iVelocityControl.reset(); - m_yarpDevices.iTorqueControl.reset(); - m_yarpDevices.iPWMControl.reset(); - m_yarpDevices.iCurrentControl.reset(); - m_yarpDevices.iEncoders.reset(); - m_yarpDevices.iControlLimits2.reset(); - m_yarpDevices.iPidControl.reset(); - // Close the device + // Set to zero all the pointers to the interfaces + m_yarpInterfaces.iControlMode2 = nullptr; + m_yarpInterfaces.iPositionControl = nullptr; + m_yarpInterfaces.iPositionDirect = nullptr; + m_yarpInterfaces.iVelocityControl = nullptr; + m_yarpInterfaces.iTorqueControl = nullptr; + m_yarpInterfaces.iPWMControl = nullptr; + m_yarpInterfaces.iCurrentControl = nullptr; + m_yarpInterfaces.iEncoders = nullptr; + m_yarpInterfaces.iControlLimits2 = nullptr; + m_yarpInterfaces.iPidControl = nullptr; + // Close the device (which deletes the interfaces it allocated) m_robotDevice->close(); // Free the object m_robotDevice.reset(); @@ -444,25 +444,24 @@ bool RobotInterface::initializeRemoteControlBoardRemapper() // ============= template -std::weak_ptr RobotInterface::getInterfaceFromTemplate(std::shared_ptr device) +T* RobotInterface::getInterfaceFromTemplate(T*& interface) { - if (!device) { + if (!interface) { // Blocks which require the RemoteControlBoardRemapper need to retain / release it // in their initialization / terminate phase; - assert(m_robotDevice); + // assert(m_robotDevice); if (!m_robotDevice) { + Log::getSingleton().error("The RemoteControlBoardRemapper has not been initialized. "); + Log::getSingleton().errorAppend("You need to retain the CB device in the initialize() method."); // Return an empty weak pointer - return std::weak_ptr(); + return nullptr; } - T* ptr = nullptr; - if (!m_robotDevice->view(ptr)) { + // Ask the interface from the device + if (!m_robotDevice->view(interface)) { // Return an empty weak_ptr - return std::weak_ptr(); + return nullptr; } - // Store ptr into the smart pointer - device.reset(ptr); } - // Implicit conversion from shared_ptr to weak_ptr - return device; + return interface; } From 9b90b9e97529a074484db20e030d2945279114d4 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:30:34 +0000 Subject: [PATCH 50/92] Updated Blocks for using raw pointers to Yarp interfaces --- toolbox/src/GetLimits.cpp | 8 +++--- toolbox/src/GetMeasurement.cpp | 24 ++++++++-------- toolbox/src/SetLowLevelPID.cpp | 16 +++++------ toolbox/src/SetReferences.cpp | 52 ++++++++++++++++++---------------- 4 files changed, 51 insertions(+), 49 deletions(-) diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index 4923021e7..eec5fddc2 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -91,7 +91,7 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) // possible using i to point to the correct joint. // Get the RemoteControlBoardRemapper and IControlLimits2 interface if needed - std::weak_ptr iControlLimits2; + yarp::dev::IControlLimits2* iControlLimits2 = nullptr; if (limitType == "ControlBoardPosition" || limitType == "ControlBoardVelocity") { // Retain the control board remapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { @@ -99,7 +99,7 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) return false; } // Get the interface - if (!getRobotInterface()->getInterface(iControlLimits2)) { + if (!getRobotInterface()->getInterface(iControlLimits2) || !iControlLimits2) { Log::getSingleton().error("Failed to get IControlLimits2 interface."); return false; } @@ -107,7 +107,7 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) if (limitType == "ControlBoardPosition") { for (auto i = 0; i < dofs; ++i) { - if (!iControlLimits2.lock()->getLimits(i, &min, &max)) { + if (!iControlLimits2->getLimits(i, &min, &max)) { Log::getSingleton().error("Failed to get limits from the interface."); return false; } @@ -117,7 +117,7 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) } else if (limitType == "ControlBoardVelocity") { for (auto i = 0; i < dofs; ++i) { - if (!iControlLimits2.lock()->getVelLimits(i, &min, &max)) { + if (!iControlLimits2->getVelLimits(i, &min, &max)) { Log::getSingleton().error("Failed to get limits from the interface."); return false; } diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index 659c921d7..97b8f971c 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -120,49 +120,49 @@ bool GetMeasurement::output(const BlockInformation* blockInfo) switch (m_estimateType) { case ESTIMATE_JOINT_POS: { // Get the interface - std::weak_ptr iEncoders; - if (!getRobotInterface()->getInterface(iEncoders)) { + yarp::dev::IEncoders* iEncoders = nullptr; + if (!getRobotInterface()->getInterface(iEncoders) || !iEncoders) { Log::getSingleton().error("Failed to get IPidControl interface."); return false; } // Get the measurement - ok = iEncoders.lock()->getEncoders(m_estimate.data()); deg2rad(m_estimate); + ok = iEncoders->getEncoders(m_measurement.data()); break; } case ESTIMATE_JOINT_VEL: { // Get the interface - std::weak_ptr iEncoders; - if (!getRobotInterface()->getInterface(iEncoders)) { + yarp::dev::IEncoders* iEncoders = nullptr; + if (!getRobotInterface()->getInterface(iEncoders) || !iEncoders) { Log::getSingleton().error("Failed to get IEncoders interface."); return false; } // Get the measurement - ok = iEncoders.lock()->getEncoderSpeeds(m_estimate.data()); deg2rad(m_estimate); + ok = iEncoders->getEncoderSpeeds(m_measurement.data()); break; } case ESTIMATE_JOINT_ACC: { // Get the interface - std::weak_ptr iEncoders; - if (!getRobotInterface()->getInterface(iEncoders)) { + yarp::dev::IEncoders* iEncoders = nullptr; + if (!getRobotInterface()->getInterface(iEncoders) || !iEncoders) { Log::getSingleton().error("Failed to get IEncoders interface."); return false; } // Get the measurement - ok = iEncoders.lock()->getEncoderAccelerations(m_estimate.data()); deg2rad(m_estimate); + ok = iEncoders->getEncoderAccelerations(m_measurement.data()); break; } case ESTIMATE_JOINT_TORQUE: { // Get the interface - std::weak_ptr iTorqueControl; - if (!getRobotInterface()->getInterface(iTorqueControl)) { + yarp::dev::ITorqueControl* iTorqueControl = nullptr; + if (!getRobotInterface()->getInterface(iTorqueControl) || !iTorqueControl) { Log::getSingleton().error("Failed to get ITorqueControl interface."); return false; } // Get the measurement - ok = iTorqueControl.lock()->getTorques(m_estimate.data()); + ok = iTorqueControl->getTorques(m_measurement.data()); break; } default: diff --git a/toolbox/src/SetLowLevelPID.cpp b/toolbox/src/SetLowLevelPID.cpp index b2d9772c4..94f3c6685 100644 --- a/toolbox/src/SetLowLevelPID.cpp +++ b/toolbox/src/SetLowLevelPID.cpp @@ -171,14 +171,14 @@ bool SetLowLevelPID::initialize(const BlockInformation* blockInfo) m_defaultPidValues.resize(dofs); // Get the interface - std::weak_ptr iPidControl; - if (!getRobotInterface()->getInterface(iPidControl)) { + yarp::dev::IPidControl* iPidControl = nullptr; + if (!getRobotInterface()->getInterface(iPidControl) || !iPidControl) { Log::getSingleton().error("Failed to get IPidControl interface."); return false; } // Store the default gains - if (!iPidControl.lock()->getPids(m_controlType, m_defaultPidValues.data())) { + if (!iPidControl->getPids(m_controlType, m_defaultPidValues.data())) { Log::getSingleton().error("Failed to get default data from IPidControl."); return false; } @@ -199,7 +199,7 @@ bool SetLowLevelPID::initialize(const BlockInformation* blockInfo) } // Apply the new pid gains - if (!iPidControl.lock()->setPids(m_controlType, m_appliedPidValues.data())) { + if (!iPidControl->setPids(m_controlType, m_appliedPidValues.data())) { Log::getSingleton().error("Failed to set PID values."); return false; } @@ -212,14 +212,14 @@ bool SetLowLevelPID::terminate(const BlockInformation* blockInfo) bool ok = true; // Get the IPidControl interface - std::weak_ptr iPidControl; - ok = ok & getRobotInterface()->getInterface(iPidControl); - if (!ok) { + yarp::dev::IPidControl* iPidControl = nullptr; + ok = ok && getRobotInterface()->getInterface(iPidControl); + if (!ok || !iPidControl) { Log::getSingleton().error("Failed to get IPidControl interface."); } // Reset default pid gains - ok = ok & iPidControl.lock()->setPids(m_controlType, m_defaultPidValues.data()); + ok = ok && iPidControl->setPids(m_controlType, m_defaultPidValues.data()); if (!ok) { Log::getSingleton().error("Failed to set default PID values."); } diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 6e20ed9db..121a72261 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -129,19 +129,21 @@ bool SetReferences::terminate(const BlockInformation* blockInfo) bool ok = true; // Get the interface - std::weak_ptr icmd2; - ok = ok & getRobotInterface()->getInterface(icmd2); - if (!ok) { + IControlMode2* icmd2 = nullptr; + ok = ok && getRobotInterface()->getInterface(icmd2); + if (!ok || !icmd2) { Log::getSingleton().error("Failed to get the IControlMode2 interface."); + return false; } // Set all the controlledJoints VOCAB_CM_POSITION const unsigned dofs = getConfiguration().getNumberOfDoFs(); m_controlModes.assign(dofs, VOCAB_CM_POSITION); - ok = ok & icmd2.lock()->setControlModes(m_controlModes.data()); + ok = ok && icmd2->setControlModes(m_controlModes.data()); if (!ok) { Log::getSingleton().error("Failed to set control mode."); + return false; } // Release the RemoteControlBoardRemapper @@ -169,13 +171,13 @@ bool SetReferences::output(const BlockInformation* blockInfo) if (m_resetControlMode) { m_resetControlMode = false; // Get the interface - std::weak_ptr icmd2; - if (!getRobotInterface()->getInterface(icmd2)) { + IControlMode2* icmd2 = nullptr; + if (!getRobotInterface()->getInterface(icmd2) || !icmd2) { Log::getSingleton().error("Failed to get the IControlMode2 interface."); return false; } // Set the control mode to all the controlledJoints - if (!icmd2.lock()->setControlModes(m_controlModes.data())) { + if (!icmd2->setControlModes(m_controlModes.data())) { Log::getSingleton().error("Failed to set control mode."); return false; } @@ -195,71 +197,71 @@ bool SetReferences::output(const BlockInformation* blockInfo) break; case VOCAB_CM_POSITION: { // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { + IPositionControl* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { Log::getSingleton().error("Failed to get IPositionControl interface."); return false; } // Convert from rad to deg rad2deg(referencesVector); // Set the references - ok = interface.lock()->positionMove(referencesVector.data()); + ok = interface->positionMove(referencesVector.data()); break; } case VOCAB_CM_POSITION_DIRECT: { // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { + IPositionDirect* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { Log::getSingleton().error("Failed to get IPositionDirect interface."); return false; } // Convert from rad to deg rad2deg(referencesVector); // Set the references - ok = interface.lock()->setPositions(referencesVector.data()); + ok = interface->setPositions(referencesVector.data()); break; } case VOCAB_CM_VELOCITY: { // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { + IVelocityControl* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { Log::getSingleton().error("Failed to get IVelocityControl interface."); return false; } // Convert from rad to deg rad2deg(referencesVector); // Set the references - ok = interface.lock()->velocityMove(referencesVector.data()); + ok = interface->velocityMove(referencesVector.data()); break; } case VOCAB_CM_TORQUE: { // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { + ITorqueControl* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { Log::getSingleton().error("Failed to get ITorqueControl interface."); return false; } - ok = interface.lock()->setRefTorques(referencesVector.data()); + ok = interface->setRefTorques(referencesVector.data()); break; } case VOCAB_CM_PWM: { // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { + IPWMControl* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { Log::getSingleton().error("Failed to get IPWMControl interface."); return false; } - ok = interface.lock()->setRefDutyCycles(referencesVector.data()); + ok = interface->setRefDutyCycles(referencesVector.data()); break; } case VOCAB_CM_CURRENT: { // Get the interface - std::weak_ptr interface; - if (!getRobotInterface()->getInterface(interface)) { + ICurrentControl* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { Log::getSingleton().error("Failed to get ICurrentControl interface."); return false; } - ok = interface.lock()->setRefCurrents(referencesVector.data()); + ok = interface->setRefCurrents(referencesVector.data()); break; } } From a01cecfbed5b4098c7c4246021c0223311715c2b Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:36:03 +0000 Subject: [PATCH 51/92] Block which inherith from WBBlocks now terminate correctly The terminate() method of these blocks should not fail before the WBBlock::terminate() method is called, otherwise allocated resources are not properly cleaned. --- toolbox/src/GetLimits.cpp | 18 +++++++++++++++--- toolbox/src/GetMeasurement.cpp | 1 + toolbox/src/SetLowLevelPID.cpp | 3 +++ toolbox/src/SetReferences.cpp | 7 ++++--- 4 files changed, 23 insertions(+), 6 deletions(-) diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index eec5fddc2..60c665307 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -171,11 +171,23 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) bool GetLimits::terminate(const BlockInformation* blockInfo) { - // Release the RemoteControlBoardRemapper bool ok = true; - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + + // Read the control type + std::string limitType; + ok = ok && blockInfo->getStringParameterAtIndex(WBBlock::numberOfParameters() + 1, limitType); if (!ok) { - Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + Log::getSingleton().error("Could not read estimate type parameter."); + // Don't return false here. WBBlock::terminate must be called in any case + } + + // Release the RemoteControlBoardRemapper + if (limitType == "ControlBoardPosition" || limitType == "ControlBoardVelocity") { + ok = ok && getRobotInterface()->releaseRemoteControlBoardRemapper(); + if (!ok) { + Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + // Don't return false here. WBBlock::terminate must be called in any case + } } return ok && WBBlock::terminate(blockInfo); diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index 97b8f971c..6869424dd 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -109,6 +109,7 @@ bool GetMeasurement::terminate(const BlockInformation* blockInfo) ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); if (!ok) { Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + // Don't return false here. WBBlock::terminate must be called in any case } return ok && WBBlock::terminate(blockInfo); diff --git a/toolbox/src/SetLowLevelPID.cpp b/toolbox/src/SetLowLevelPID.cpp index 94f3c6685..c593f32ca 100644 --- a/toolbox/src/SetLowLevelPID.cpp +++ b/toolbox/src/SetLowLevelPID.cpp @@ -216,18 +216,21 @@ bool SetLowLevelPID::terminate(const BlockInformation* blockInfo) ok = ok && getRobotInterface()->getInterface(iPidControl); if (!ok || !iPidControl) { Log::getSingleton().error("Failed to get IPidControl interface."); + // Don't return false here. WBBlock::terminate must be called in any case } // Reset default pid gains ok = ok && iPidControl->setPids(m_controlType, m_defaultPidValues.data()); if (!ok) { Log::getSingleton().error("Failed to set default PID values."); + // Don't return false here. WBBlock::terminate must be called in any case } // Release the RemoteControlBoardRemapper ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); if (!ok) { Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + // Don't return false here. WBBlock::terminate must be called in any case } return ok && WBBlock::terminate(blockInfo); diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 121a72261..4255344b8 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -133,7 +133,7 @@ bool SetReferences::terminate(const BlockInformation* blockInfo) ok = ok && getRobotInterface()->getInterface(icmd2); if (!ok || !icmd2) { Log::getSingleton().error("Failed to get the IControlMode2 interface."); - return false; + // Don't return false here. WBBlock::terminate must be called in any case } // Set all the controlledJoints VOCAB_CM_POSITION @@ -143,13 +143,14 @@ bool SetReferences::terminate(const BlockInformation* blockInfo) ok = ok && icmd2->setControlModes(m_controlModes.data()); if (!ok) { Log::getSingleton().error("Failed to set control mode."); - return false; + // Don't return false here. WBBlock::terminate must be called in any case } // Release the RemoteControlBoardRemapper - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + ok = ok && getRobotInterface()->releaseRemoteControlBoardRemapper(); if (!ok) { Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); + // Don't return false here. WBBlock::terminate must be called in any case } return ok && WBBlock::terminate(blockInfo); From ed7dd9272b7c784cb1df20a37f55990e109ed40e Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:43:13 +0000 Subject: [PATCH 52/92] Switched ands from bitwise to logical Robustness matters --- toolbox/src/GetMeasurement.cpp | 2 +- .../src/MinimumJerkTrajectoryGenerator.cpp | 22 +++++++++---------- toolbox/src/SetLowLevelPID.cpp | 2 +- toolbox/src/SimulatorSynchronizer.cpp | 6 ++--- toolbox/src/YarpRead.cpp | 16 +++++++------- toolbox/src/YarpWrite.cpp | 5 ++--- 6 files changed, 26 insertions(+), 27 deletions(-) diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index 6869424dd..7271a65fd 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -106,7 +106,7 @@ bool GetMeasurement::terminate(const BlockInformation* blockInfo) { // Release the RemoteControlBoardRemapper bool ok = true; - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + ok = ok && getRobotInterface()->releaseRemoteControlBoardRemapper(); if (!ok) { Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); // Don't return false here. WBBlock::terminate must be called in any case diff --git a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp index d550be5fd..6c7e82e36 100644 --- a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp +++ b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp @@ -56,10 +56,10 @@ bool MinimumJerkTrajectoryGenerator::configureSizeAndPorts(BlockInformation* blo bool externalSettlingTime; bool ok = true; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, outputFirstDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, outputSecondDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, explicitInitialValue); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, externalSettlingTime); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, outputFirstDerivative); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, outputSecondDerivative); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, explicitInitialValue); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, externalSettlingTime); if (!ok) { Log::getSingleton().error("Failed to get input parameters."); @@ -132,13 +132,13 @@ bool MinimumJerkTrajectoryGenerator::initialize(const BlockInformation* blockInf bool outputSecondDerivative; bool ok = true; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_1ST_DERIVATIVE, outputFirstDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_OUTPUT_2ND_DERIVATIVE, outputSecondDerivative); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, m_explicitInitialValue); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, m_externalSettlingTime); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_RESET_CHANGEST, + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_INITIAL_VALUE, m_explicitInitialValue); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_EXT_SETTLINGTIME, m_externalSettlingTime); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_RESET_CHANGEST, m_resetOnSettlingTimeChange); if (!ok) { @@ -157,8 +157,8 @@ bool MinimumJerkTrajectoryGenerator::initialize(const BlockInformation* blockInf double sampleTime; double settlingTime; - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SAMPLE_TIME, sampleTime); - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_SETTLING_TIME, settlingTime); + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_SAMPLE_TIME, sampleTime); + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_SETTLING_TIME, settlingTime); unsigned signalSize = blockInfo->getInputPortWidth(0); diff --git a/toolbox/src/SetLowLevelPID.cpp b/toolbox/src/SetLowLevelPID.cpp index c593f32ca..6ce3a3aba 100644 --- a/toolbox/src/SetLowLevelPID.cpp +++ b/toolbox/src/SetLowLevelPID.cpp @@ -227,7 +227,7 @@ bool SetLowLevelPID::terminate(const BlockInformation* blockInfo) } // Release the RemoteControlBoardRemapper - ok = ok & getRobotInterface()->releaseRemoteControlBoardRemapper(); + ok = ok && getRobotInterface()->releaseRemoteControlBoardRemapper(); if (!ok) { Log::getSingleton().error("Failed to release the RemoteControlBoardRemapper."); // Don't return false here. WBBlock::terminate must be called in any case diff --git a/toolbox/src/SimulatorSynchronizer.cpp b/toolbox/src/SimulatorSynchronizer.cpp index 2f0c834fa..c46c528e1 100644 --- a/toolbox/src/SimulatorSynchronizer.cpp +++ b/toolbox/src/SimulatorSynchronizer.cpp @@ -73,9 +73,9 @@ bool SimulatorSynchronizer::initialize(const BlockInformation* blockInfo) std::string clientPortName; bool ok = true; - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period); - ok = ok & blockInfo->getStringParameterAtIndex(PARAM_GZCLK_PORT, serverPortName); - ok = ok & blockInfo->getStringParameterAtIndex(PARAM_RPC_PORT, clientPortName); + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_PERIOD, m_period); + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_GZCLK_PORT, serverPortName); + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_RPC_PORT, clientPortName); if (!ok) { Log::getSingleton().error("Error reading RPC parameters."); diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 023fb7701..9e5807cce 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -58,11 +58,11 @@ bool YarpRead::configureSizeAndPorts(BlockInformation* blockInfo) bool autoconnect; double signalSize; - bool ok = false; + bool ok = true; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, shouldReadTimestamp); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, autoconnect); - ok = ok & blockInfo->getScalarParameterAtIndex(PARAM_IDX_PORTSIZE, signalSize); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, shouldReadTimestamp); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, autoconnect); + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_PORTSIZE, signalSize); if (!ok) { Log::getSingleton().error("Failed to read input parameters."); @@ -114,10 +114,10 @@ bool YarpRead::initialize(const BlockInformation* blockInfo) bool ok = true; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, m_shouldReadTimestamp); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_WAITDATA, m_blocking); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, m_errorOnMissingPort); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_READ_TS, m_shouldReadTimestamp); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_WAITDATA, m_blocking); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, m_errorOnMissingPort); if (!ok) { Log::getSingleton().error("Failed to read input parameters."); diff --git a/toolbox/src/YarpWrite.cpp b/toolbox/src/YarpWrite.cpp index 6b50029d9..5c59fd035 100644 --- a/toolbox/src/YarpWrite.cpp +++ b/toolbox/src/YarpWrite.cpp @@ -68,9 +68,8 @@ bool YarpWrite::initialize(const BlockInformation* blockInfo) bool ok = true; - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); - ok = ok & blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, - m_errorOnMissingPort); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_AUTOCONNECT, m_autoconnect); + ok = ok && blockInfo->getBooleanParameterAtIndex(PARAM_IDX_ERR_NO_PORT, m_errorOnMissingPort); if (!ok) { Log::getSingleton().error("Failed to read input parameters."); From d4a64334d6f16c8252b94201ad343f29926d28ec Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:47:23 +0000 Subject: [PATCH 53/92] Check smart pointer status before using the KinDynComputations object --- toolbox/include/base/ToolboxSingleton.h | 2 +- toolbox/src/GetLimits.cpp | 15 ++++++++++++--- toolbox/src/InverseDynamics.cpp | 7 ++++++- toolbox/src/base/RobotInterface.cpp | 9 +++++---- toolbox/src/base/ToolboxSingleton.cpp | 2 +- 5 files changed, 25 insertions(+), 10 deletions(-) diff --git a/toolbox/include/base/ToolboxSingleton.h b/toolbox/include/base/ToolboxSingleton.h index 1140a2d76..78dcf47e2 100644 --- a/toolbox/include/base/ToolboxSingleton.h +++ b/toolbox/include/base/ToolboxSingleton.h @@ -110,7 +110,7 @@ class wbt::ToolboxSingleton { // TODO: wbt::ToolboxSingleton * @return A \c shared_ptr to the iDynTree::KinDynComputations of the requested * configuration */ - const std::shared_ptr getModel(const std::string& confKey); + const std::shared_ptr getKinDynComputations(const std::string& confKey); // TOOLBOXSINGLETON CONFIGURATION // ============================== diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index 60c665307..eada4afe8 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -4,8 +4,8 @@ #include "BlockInformation.h" #include "Signal.h" #include "RobotInterface.h" -#include "iDynTree/KinDynComputations.h" -#include "iDynTree/Model/Model.h" +#include +#include #include #include #include @@ -133,7 +133,16 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) else if (limitType == "ModelPosition") { iDynTree::IJointConstPtr p_joint; - const iDynTree::Model model = getRobotInterface()->getKinDynComputations()->model(); + + // Get the KinDynComputations pointer + const auto& kindyncomp = getRobotInterface()->getKinDynComputations(); + if (!kindyncomp) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + + // Get the model + const iDynTree::Model model = kindyncomp->model(); for (auto i = 0; i < dofs; ++i) { // Get the joint name diff --git a/toolbox/src/InverseDynamics.cpp b/toolbox/src/InverseDynamics.cpp index e0303b97e..514c96d2b 100644 --- a/toolbox/src/InverseDynamics.cpp +++ b/toolbox/src/InverseDynamics.cpp @@ -110,7 +110,12 @@ bool InverseDynamics::initialize(const BlockInformation* blockInfo) m_jointsAcceleration = std::unique_ptr(new VectorDynSize(dofs)); m_jointsAcceleration->zero(); - const auto& model = getRobotInterface()->getKinDynComputations()->model(); + // Get the KinDynComputations pointer + const auto& kindyncomp = getRobotInterface()->getKinDynComputations(); + + // Get the model from the KinDynComputations object + const auto& model = kindyncomp->model(); + m_torques = std::unique_ptr(new FreeFloatingGeneralizedTorques(model)); return static_cast(m_baseAcceleration) && diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index bfda124ca..bf96983f2 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -183,12 +183,13 @@ const std::shared_ptr RobotInterface::getKinDynCom } // Otherwise, initialize a new object - if (initializeModel()) { - return m_kinDynComp; + if (!initializeModel()) { + Log::getSingleton().error("Failed to initialize the KinDynComputations object."); + // Return an empty shared_ptr (implicitly initialized) + return nullptr; } - // Return an empty shared_ptr (implicitly initialized) - return nullptr; + return m_kinDynComp; } template <> diff --git a/toolbox/src/base/ToolboxSingleton.cpp b/toolbox/src/base/ToolboxSingleton.cpp index 19042b281..9eb76a4f3 100644 --- a/toolbox/src/base/ToolboxSingleton.cpp +++ b/toolbox/src/base/ToolboxSingleton.cpp @@ -63,7 +63,7 @@ const std::shared_ptr ToolboxSingleton::getRobotInterface(const return m_interfaces[confKey]; } -const std::shared_ptr ToolboxSingleton::getModel(const std::string& confKey) +const std::shared_ptr ToolboxSingleton::getKinDynComputations(const std::string& confKey) { if (!isKeyValid(confKey)) { return nullptr; From 9b3180aa0178be345ae1da76d1e5f2d6ced9db04 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:53:46 +0000 Subject: [PATCH 54/92] GetLimits: missing deg2rad conversion and typo for invalid joint check --- toolbox/include/GetLimits.h | 3 ++- toolbox/src/GetLimits.cpp | 30 ++++++++++++++++++++++-------- 2 files changed, 24 insertions(+), 9 deletions(-) diff --git a/toolbox/include/GetLimits.h b/toolbox/include/GetLimits.h index 3a0310fe9..e96a7ae59 100644 --- a/toolbox/include/GetLimits.h +++ b/toolbox/include/GetLimits.h @@ -24,10 +24,11 @@ class wbt::GetLimits : public wbt::WBBlock { private: std::unique_ptr m_limits; + static double deg2rad(const double& v); public: static const std::string ClassName; - + GetLimits() = default; ~GetLimits() override = default; diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index eada4afe8..44648995e 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -10,10 +10,18 @@ #include #include +#define _USE_MATH_DEFINES +#include + using namespace wbt; const std::string GetLimits::ClassName = "GetLimits"; +double GetLimits::deg2rad(const double& v) +{ + return v * M_PI / 180.0; +} + unsigned GetLimits::numberOfParameters() { return WBBlock::numberOfParameters() + 1; @@ -111,8 +119,8 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) Log::getSingleton().error("Failed to get limits from the interface."); return false; } - m_limits->min[i] = min; - m_limits->max[i] = max; + m_limits->min[i] = deg2rad(min); + m_limits->max[i] = deg2rad(max); } } else if (limitType == "ControlBoardVelocity") { @@ -121,8 +129,8 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) Log::getSingleton().error("Failed to get limits from the interface."); return false; } - m_limits->min[i] = min; - m_limits->max[i] = max; + m_limits->min[i] = deg2rad(min); + m_limits->max[i] = deg2rad(max); } } @@ -149,19 +157,25 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) std::string joint = getConfiguration().getControlledJoints()[i]; // Get its index - iDynTree::LinkIndex jointIndex = model.getLinkIndex(joint); + iDynTree::JointIndex jointIndex = model.getJointIndex(joint); + + if (jointIndex == iDynTree::JOINT_INVALID_INDEX) { + Log::getSingleton().error("Invalid iDynTree joint index."); + return false; + } // Get the joint from the model p_joint = model.getJoint(jointIndex); if (!p_joint->hasPosLimits()) { Log::getSingleton().warning("Joint " + joint + " has no model limits."); - // TODO: test how these values are interpreted by Simulink - min = -std::numeric_limits::infinity(); - max = std::numeric_limits::infinity(); + m_limits->min[i] = -std::numeric_limits::infinity(); + m_limits->max[i] = std::numeric_limits::infinity(); } else { p_joint->getPosLimits(0, min, max); + m_limits->min[i] = min; + m_limits->max[i] = max; } } } From 5c9912cd42de472d92442a57a79958f483377f53 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 10:55:27 +0000 Subject: [PATCH 55/92] GetMeasurement: changed some member names for clarity --- toolbox/include/GetMeasurement.h | 12 ++++++------ toolbox/src/GetMeasurement.cpp | 28 ++++++++++++++-------------- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/toolbox/include/GetMeasurement.h b/toolbox/include/GetMeasurement.h index 101aed7af..5caec2f71 100644 --- a/toolbox/include/GetMeasurement.h +++ b/toolbox/include/GetMeasurement.h @@ -5,10 +5,10 @@ namespace wbt { class GetMeasurement; - enum EstimateType { - ESTIMATE_JOINT_POS, - ESTIMATE_JOINT_VEL, - ESTIMATE_JOINT_ACC, + enum MeasuredType { + MEASUREMENT_JOINT_POS, + MEASUREMENT_JOINT_VEL, + MEASUREMENT_JOINT_ACC, ESTIMATE_JOINT_TORQUE }; } @@ -17,8 +17,8 @@ namespace wbt { class wbt::GetMeasurement : public wbt::WBBlock { private: - std::vector m_estimate; - wbt::EstimateType m_estimateType; + std::vector m_measurement; + wbt::MeasuredType m_measuredType; static void deg2rad(std::vector& v); public: diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index 7271a65fd..536ec00aa 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -16,7 +16,7 @@ const std::string GetMeasurement::ClassName = "GetMeasurement"; void GetMeasurement::deg2rad(std::vector& v) { - const double deg2rad = (2 * M_PI) / 180.0; + const double deg2rad = M_PI / 180.0; for (auto& element : v) { element *= deg2rad; } @@ -77,13 +77,13 @@ bool GetMeasurement::initialize(const BlockInformation* blockInfo) } if (informationType == "Joints Position") { - m_estimateType = wbt::ESTIMATE_JOINT_POS; + m_measuredType = wbt::MEASUREMENT_JOINT_POS; } else if (informationType == "Joints Velocity") { - m_estimateType = wbt::ESTIMATE_JOINT_VEL; + m_measuredType = wbt::MEASUREMENT_JOINT_VEL; } else if (informationType == "Joints Acceleration") { - m_estimateType = wbt::ESTIMATE_JOINT_ACC; + m_measuredType = wbt::MEASUREMENT_JOINT_ACC; } else if (informationType == "Joints Torque") { - m_estimateType = wbt::ESTIMATE_JOINT_TORQUE; + m_measuredType = wbt::ESTIMATE_JOINT_TORQUE; } else { Log::getSingleton().error("Estimate not supported."); return false; @@ -91,7 +91,7 @@ bool GetMeasurement::initialize(const BlockInformation* blockInfo) // Initialize the size of the output vector const unsigned dofs = getConfiguration().getNumberOfDoFs(); - m_estimate.reserve(dofs); + m_measurement.resize(dofs); // Retain the ControlBoardRemapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { @@ -118,8 +118,8 @@ bool GetMeasurement::terminate(const BlockInformation* blockInfo) bool GetMeasurement::output(const BlockInformation* blockInfo) { bool ok; - switch (m_estimateType) { - case ESTIMATE_JOINT_POS: { + switch (m_measuredType) { + case MEASUREMENT_JOINT_POS: { // Get the interface yarp::dev::IEncoders* iEncoders = nullptr; if (!getRobotInterface()->getInterface(iEncoders) || !iEncoders) { @@ -127,11 +127,11 @@ bool GetMeasurement::output(const BlockInformation* blockInfo) return false; } // Get the measurement - deg2rad(m_estimate); ok = iEncoders->getEncoders(m_measurement.data()); + deg2rad(m_measurement); break; } - case ESTIMATE_JOINT_VEL: { + case MEASUREMENT_JOINT_VEL: { // Get the interface yarp::dev::IEncoders* iEncoders = nullptr; if (!getRobotInterface()->getInterface(iEncoders) || !iEncoders) { @@ -139,11 +139,11 @@ bool GetMeasurement::output(const BlockInformation* blockInfo) return false; } // Get the measurement - deg2rad(m_estimate); ok = iEncoders->getEncoderSpeeds(m_measurement.data()); + deg2rad(m_measurement); break; } - case ESTIMATE_JOINT_ACC: { + case MEASUREMENT_JOINT_ACC: { // Get the interface yarp::dev::IEncoders* iEncoders = nullptr; if (!getRobotInterface()->getInterface(iEncoders) || !iEncoders) { @@ -151,8 +151,8 @@ bool GetMeasurement::output(const BlockInformation* blockInfo) return false; } // Get the measurement - deg2rad(m_estimate); ok = iEncoders->getEncoderAccelerations(m_measurement.data()); + deg2rad(m_measurement); break; } case ESTIMATE_JOINT_TORQUE: { @@ -177,7 +177,7 @@ bool GetMeasurement::output(const BlockInformation* blockInfo) } Signal signal = blockInfo->getOutputPortSignal(0); - signal.setBuffer(m_estimate.data(), blockInfo->getOutputPortWidth(0)); + signal.setBuffer(m_measurement.data(), blockInfo->getOutputPortWidth(0)); return true; } From 3a0d018acbfc7d85a29fa9afa0149bb01f850885 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 11:00:34 +0000 Subject: [PATCH 56/92] SetReferences: Position mode now calls setRefSpeeds() The speed, used internally by the yarp interface, must be initialized in order to obtain the wanted bahavior. In the future this might become a mask parameter. --- toolbox/src/SetReferences.cpp | 33 ++++++++++++++++++++++++++++++--- 1 file changed, 30 insertions(+), 3 deletions(-) diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 4255344b8..90edb1c6b 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -19,7 +19,7 @@ SetReferences::SetReferences() void SetReferences::rad2deg(std::vector& v) { - const double rad2deg = 180.0 / (2 * M_PI); + const double rad2deg = 180.0 / M_PI; for (auto& element : v) { element *= rad2deg; } @@ -113,6 +113,26 @@ bool SetReferences::initialize(const BlockInformation* blockInfo) return false; } + // The Position mode is used to set a discrete reference, and then the yarp interface + // is responsible to generate a trajectory to reach this setpoint. + // The generated trajectory takes an additional parameter: the speed. + // If not properly initialized, this contol mode does not work as expected. + if (controlType == "Position") { + // Get the interface + yarp::dev::IPositionControl* interface = nullptr; + if (!getRobotInterface()->getInterface(interface) || !interface) { + Log::getSingleton().error("Failed to get IPositionControl interface."); + return false; + } + // TODO: Set this parameter from the mask + std::vector speedInitalization(dofs, 10.0); + // Set the references + if (!interface->setRefSpeeds(speedInitalization.data())) { + Log::getSingleton().error("Failed to initialize speed references."); + return false; + } + } + // Retain the ControlBoardRemapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); @@ -158,8 +178,15 @@ bool SetReferences::terminate(const BlockInformation* blockInfo) bool SetReferences::initializeInitialConditions(const BlockInformation* /*blockInfo*/) { - // Simply reset the variable m_resetControlMode. - // It will be read at the first cycle of output. + // This function is called when a subsystem with Enable / Disable support is used. + // In this case all the blocks in this subsystem are configured and initialize, + // but if they are disabled, output() is not called. + // This initializeInitialConditions method is called when the block is enabled, + // and in this case the control mode should be set. + // + // It is worth noting that this toolbox disables parameters to be tunable for + // all the blocks + m_resetControlMode = true; return true; } From 9993d136d2abc76eab819582a661085ce6060f58 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 11:13:47 +0000 Subject: [PATCH 57/92] ModelPartitioner: fixed the forwarding of i/o data This block requires a lot of information for dynamically partitioning a vector containing controlledJoints data into multiple signals representing the control boards the joints belong to. Furthermore, this block is the only one which needs to retrieve the KinDynComputations model and RemoteControlBoardRemapper already from the configureSizeAndPorts() step. --- toolbox/include/ModelPartitioner.h | 4 +- toolbox/include/base/RobotInterface.h | 45 +++++++- toolbox/src/ModelPartitioner.cpp | 97 ++++++++++------- toolbox/src/base/RobotInterface.cpp | 145 +++++++++++++++++++------- 4 files changed, 216 insertions(+), 75 deletions(-) diff --git a/toolbox/include/ModelPartitioner.h b/toolbox/include/ModelPartitioner.h index 32c57c098..853c3f0c3 100644 --- a/toolbox/include/ModelPartitioner.h +++ b/toolbox/include/ModelPartitioner.h @@ -16,10 +16,12 @@ class wbt::ModelPartitioner : public wbt::WBBlock bool m_yarp2WBI; std::shared_ptr m_jointsMapString; + std::shared_ptr m_controlledJointsMapCB; + std::shared_ptr m_controlBoardIdxLimit; public: static const std::string ClassName; - + ModelPartitioner() = default; ~ModelPartitioner() override = default; diff --git a/toolbox/include/base/RobotInterface.h b/toolbox/include/base/RobotInterface.h index 489bf0f35..76d338de3 100644 --- a/toolbox/include/base/RobotInterface.h +++ b/toolbox/include/base/RobotInterface.h @@ -36,8 +36,12 @@ namespace wbt { typedef int jointIdx_yarp; typedef int jointIdx_iDynTree; typedef unsigned cb_idx; + typedef unsigned max_cb_idx; + typedef unsigned controlledJointIdxCB; typedef std::unordered_map> JointsMapIndex; typedef std::unordered_map> JointsMapString; + typedef std::unordered_map ControlledJointsMapCB; + typedef std::unordered_map ControlBoardIdxLimit; } /** @@ -106,7 +110,8 @@ class wbt::RobotInterface // Maps used to store infos about yarp's and idyntree's internal joint indexing std::shared_ptr m_jointsMapIndex; std::shared_ptr m_jointsMapString; - // std::unordered_map, joint_name> m_yarp2joint; + std::shared_ptr m_controlledJointsMapCB; + std::shared_ptr m_controlBoardIdxLimit; // Configuration from Simulink Block's parameters const wbt::Configuration m_config; @@ -159,6 +164,17 @@ class wbt::RobotInterface * @return True if the map has been created successfully */ bool mapDoFs(); + + /** + * Create a RemoteControlBoard object for a given remoteName + * + * @see mapDoFs + * + * @param remoteName [in] Name of the remote from which the remote control board is be initialized + * @param controlBoard [out] Smart pointer to the allocated remote control board + * @return True if success + */ + bool getSingleControlBoard(const std::string& remoteName, std::unique_ptr& controlBoard); public: // CONSTRUCTOR / DESTRUCTOR @@ -179,7 +195,7 @@ class wbt::RobotInterface const wbt::Configuration& getConfiguration() const; /** - * Get the map between model joint namesand the YARP representation (Control Board and + * Get the map between model joint names and the YARP representation (Control Board and * joint index) * * @return The joint map @@ -194,6 +210,31 @@ class wbt::RobotInterface */ const std::shared_ptr getJointsMapIndex(); + /** + * Get the map between model joint names and the index representing their relative ordering + * inside the controlledJoints vector relative to their ControlBoard. + * + * @note For example, if the joints are + * \verbatim j1_cb1 j2_cb1 j3_cb1 j1_cb2 j2_cb2 j1_cb3 \endverbatim, the map links them to + * \verbatim 0 1 2 0 1 0 \end + * + * @return The joint map + */ + const std::shared_ptr getControlledJointsMapCB(); + + /** + * Get the map between the ControlBoard index inside the RemoteControlBoardRemapper + * and the number of the controlled joints which belongs to it. + * + * @note For example, if the joints are + * \verbatim j1_cb1 j2_cb1 j3_cb1 j1_cb2 j2_cb2 j1_cb3 \endverbatim, the generated map is + * \verbatim {{0,3}{1,2}{2,1}} \endverbatim + * Note that the map key is 0-indexed. + * + * @return The control board limit map + */ + const std::shared_ptr getControlBoardIdxLimit(); + /** * Get the object to operate on the configured model * diff --git a/toolbox/src/ModelPartitioner.cpp b/toolbox/src/ModelPartitioner.cpp index 2c54458bd..e987604f8 100644 --- a/toolbox/src/ModelPartitioner.cpp +++ b/toolbox/src/ModelPartitioner.cpp @@ -5,6 +5,7 @@ #include "RobotInterface.h" #include "Signal.h" #include "Log.h" +#include using namespace wbt; @@ -12,7 +13,7 @@ const std::string ModelPartitioner::ClassName = "ModelPartitioner"; unsigned ModelPartitioner::numberOfParameters() { - return 1; + return WBBlock::numberOfParameters() + 1; } bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) @@ -25,8 +26,10 @@ bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) // 1) Boolean specifying if yarp2WBI (true) or WBI2yarp (false) // - bool yarp2WBI; - if (!blockInfo->getBooleanParameterAtIndex(1, yarp2WBI)) { + bool yarp2WBI = false; + unsigned yarp2WBIParameterIdx = WBBlock::numberOfParameters() + 1; + + if (!blockInfo->getBooleanParameterAtIndex(yarp2WBIParameterIdx, yarp2WBI)) { Log::getSingleton().error("Failed to get input parameters."); return false; } @@ -53,12 +56,14 @@ bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) numberOfInputs = 1; ok = blockInfo->setNumberOfInputPorts(numberOfInputs); blockInfo->setInputPortVectorSize(0, getConfiguration().getNumberOfDoFs()); + blockInfo->setInputPortType(0, PortDataTypeDouble); } else { numberOfInputs = controlBoardsNumber; ok = blockInfo->setNumberOfInputPorts(numberOfInputs); // Set the size as dynamic for (unsigned i = 0; i < numberOfInputs; ++i) { + blockInfo->setInputPortVectorSize(i, -1); blockInfo->setInputPortType(i, PortDataTypeDouble); } } @@ -100,6 +105,28 @@ bool ModelPartitioner::configureSizeAndPorts(BlockInformation* blockInfo) blockInfo->setOutputPortType(0, PortDataTypeDouble); } + // For some reason, the output ports widths in the yarp2WBI case are not detected + // properly by Simulink if set as DYNAMICALLY_SIZED (-1). + // Set them manually using the m_controlBoardIdxLimit map. + // + // Doing this now has the disadvantage of allocating the KinDynComputations and the + // RemoteControlBoardRemapper already at this early stage, but this happens only at the + // first execution of the model if the joint list doesn't change. + // + if (yarp2WBI) { + m_controlBoardIdxLimit = getRobotInterface()->getControlBoardIdxLimit(); + if (!m_controlBoardIdxLimit) { + Log::getSingleton().error("Failed to get the map CBIdx <--> CBMaxIdx."); + return false; + } + for (const auto& cb : *m_controlBoardIdxLimit) { + if (!blockInfo->setOutputPortVectorSize(cb.first, cb.second)) { + Log::getSingleton().error("Failed to set ouput port size reading them from cb map."); + return false; + } + } + } + if (!ok) { Log::getSingleton().error("Failed to set output port number."); return false; @@ -112,14 +139,22 @@ bool ModelPartitioner::initialize(const BlockInformation* blockInfo) { if (!WBBlock::initialize(blockInfo)) return false; - if (!blockInfo->getBooleanParameterAtIndex(1, m_yarp2WBI)) { + unsigned yarp2WBIParameterIdx = WBBlock::numberOfParameters() + 1; + if (!blockInfo->getBooleanParameterAtIndex(yarp2WBIParameterIdx, m_yarp2WBI)) { Log::getSingleton().error("Failed to get input parameters."); return false; } m_jointsMapString = getRobotInterface()->getJointsMapString(); + m_controlledJointsMapCB = getRobotInterface()->getControlledJointsMapCB(); if (!m_jointsMapString) { + Log::getSingleton().error("Failed to get the joint map iDynTree <--> Yarp."); + return false; + } + + if (!m_controlledJointsMapCB) { + Log::getSingleton().error("Failed to get the joint map iDynTree <--> controlledJointsIdx."); return false; } @@ -133,48 +168,38 @@ bool ModelPartitioner::terminate(const BlockInformation* blockInfo) bool ModelPartitioner::output(const BlockInformation* blockInfo) { - if (m_yarp2WBI) { - // Input - Signal jointListSignal = blockInfo->getInputPortSignal(0); + Signal dofsSignal; - // Outputs - Signal ithControlBoardSignal; + if (m_yarp2WBI) { + dofsSignal = blockInfo->getInputPortSignal(0); - for (unsigned ithJoint = 0; ithJoint < blockInfo->getInputPortWidth(0); ++ithJoint) { - // Get the ControlBoard number the ith joint belongs, and its index into the CB itself - std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; - const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); - cb_idx controlBoardOfJoint = mappedJointInfos.first; - jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; + for (unsigned ithJoint = 0; ithJoint < getConfiguration().getNumberOfDoFs(); ++ithJoint) { + const std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; + // Get the ControlBoard number the ith joint belongs + const cb_idx& controlBoardOfJoint = m_jointsMapString->at(ithJointName).first; + // Get the index of the ith joint inside the controlledJoints vector relative to + // its ControlBoard + const controlledJointIdxCB contrJointIdxCB = m_controlledJointsMapCB->at(ithJointName); // Get the data to forward - Data value = jointListSignal.get(ithJoint); - - // Forward the value to the correct output / output index - ithControlBoardSignal = blockInfo->getOutputPortSignal(controlBoardOfJoint); - ithControlBoardSignal.set(yarpIndexOfJoint, value.doubleData()); + Signal ithOutput = blockInfo->getOutputPortSignal(controlBoardOfJoint); + ithOutput.set(contrJointIdxCB, dofsSignal.get(ithJoint).doubleData()); } } else { - // Inputs - Signal ithControlBoardSignal; + dofsSignal = blockInfo->getOutputPortSignal(0); - // Output - Signal jointListSignal = blockInfo->getOutputPortSignal(0); - - for (unsigned ithJoint = 0; ithJoint < blockInfo->getOutputPortWidth(0); ++ithJoint) { - // Get the ControlBoard number the ith joint belongs, and its index into the CB itself - std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; - const auto& mappedJointInfos = m_jointsMapString->at(ithJointName); - cb_idx controlBoardOfJoint = mappedJointInfos.first; - jointIdx_yarp yarpIndexOfJoint = mappedJointInfos.second; + for (unsigned ithJoint = 0; ithJoint < getConfiguration().getNumberOfDoFs(); ++ithJoint) { + const std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; + // Get the ControlBoard number the ith joint belongs + const cb_idx& controlBoardOfJoint = m_jointsMapString->at(ithJointName).first; + // Get the index of the ith joint inside the controlledJoints vector relative to + // its ControlBoard + const controlledJointIdxCB contrJointIdxCB = m_controlledJointsMapCB->at(ithJointName); // Get the data to forward - ithControlBoardSignal = blockInfo->getInputPortSignal(controlBoardOfJoint); - Data value = ithControlBoardSignal.get(ithJoint); - - // Forward the value to the correct output index - jointListSignal.set(yarpIndexOfJoint, value.doubleData()); + const Signal ithInput = blockInfo->getInputPortSignal(controlBoardOfJoint); + dofsSignal.set(ithJoint, ithInput.get(contrJointIdxCB).doubleData()); } } return true; diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index bf96983f2..e637d40e5 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -2,6 +2,7 @@ #include "Log.h" #include #include +#include #include #include #include @@ -9,9 +10,9 @@ #include #include #include +#include namespace wbt { - // The declaration of the following template specializations are required only by GCC using namespace yarp::dev; template <> bool RobotInterface::getInterface(IControlMode2*& interface); @@ -51,28 +52,54 @@ RobotInterface::~RobotInterface() assert(m_robotDeviceCounter == 0); } +bool RobotInterface::getSingleControlBoard(const std::string& remoteName, std::unique_ptr& controlBoard) { + // Configure the single control board + yarp::os::Property options; + options.clear(); + options.put("device", "remote_controlboard"); + options.put("remote", remoteName); + options.put("local", m_config.getLocalName() + "/CBtmp"); + options.put("writeStrict", "on"); + + // Initialize the device + controlBoard = std::unique_ptr(new yarp::dev::PolyDriver()); + if (!controlBoard) { + Log::getSingleton().error("Failed to retain the RemoteControlBoard "); + Log::getSingleton().errorAppend("used for mapping iDynTree - YARP DoFs."); + return false; + } + + // Try to open the control board + if (!controlBoard->open(options) || !controlBoard->isValid()) { + Log::getSingleton().error("Unable to open RemoteControlBoard " + remoteName); + return false; + } + + return true; +} + bool RobotInterface::mapDoFs() { - std::unique_ptr controlBoard; + // Initialize the network + yarp::os::Network::init(); + if (!yarp::os::Network::initialized() || !yarp::os::Network::checkNetwork(5.0)) { + Log::getSingleton().error("YARP server wasn't found active!!"); + return false; + } + std::vector> iAxisInfos; - yarp::os::Property options; for (unsigned cbNum = 0; cbNum < m_config.getControlBoardsNames().size(); ++cbNum) { - // Configure the single control board - options.clear(); - options.put("device","remotecontrolboard"); + + std::unique_ptr controlBoard; const std::string prefix = "/" + m_config.getRobotName() + "/"; const std::string remoteName = prefix + m_config.getControlBoardsNames().at(cbNum); - options.put("remote", remoteName); - options.put("localPortPrefix", "WBTtmp"); - // Try to open the control board - if (!controlBoard->open(options) || !controlBoard->isValid()) { - Log::getSingleton().error("Unable to open RemoteControlBoard " + remoteName); + if (!getSingleControlBoard(remoteName, controlBoard)) { return false; } - // Get an IAxisInfo object from the device + // Get an IAxisInfo object from the interface std::unique_ptr iAxisInfo; yarp::dev::IAxisInfo* iAxisInfoPtr = iAxisInfo.get(); controlBoard->view(iAxisInfoPtr); @@ -92,6 +119,7 @@ bool RobotInterface::mapDoFs() return false; } + int found = -1; // Iterate all the joints in the selected Control Board for (unsigned axis = 0; axis < numAxes; ++axis) { std::string axisName; @@ -100,13 +128,18 @@ bool RobotInterface::mapDoFs() return false; } // Look if axisName is a controlledJoint - bool found = false; for (const auto& controlledJoint : m_config.getControlledJoints()) { if (controlledJoint == axisName) { - // Get the iDynTree index - const auto& model = getKinDynComputations()->model(); - iDynTree::LinkIndex iDynLinkIdx = model.getLinkIndex(axisName); - if (iDynLinkIdx == iDynTree::LINK_INVALID_INDEX) { + found++; + // Get the iDynTree index from the model + const auto& kinDynComp = getKinDynComputations(); + if (!kinDynComp) { + Log::getSingleton().error("Failed to get KinDynComputations."); + return false; + } + const auto& model = kinDynComp->model(); + iDynTree::JointIndex iDynJointIdx = model.getJointIndex(axisName); + if (iDynJointIdx == iDynTree::JOINT_INVALID_INDEX) { Log::getSingleton().error("Joint " + axisName + " exists in the " + remoteName + "control board but not in the model."); return false; @@ -118,27 +151,42 @@ bool RobotInterface::mapDoFs() if (!m_jointsMapString) { m_jointsMapString = std::make_shared(); } + if (!m_controlledJointsMapCB) { + m_controlledJointsMapCB = std::make_shared(); + } + if (!m_controlBoardIdxLimit) { + m_controlBoardIdxLimit = std::make_shared(); + } // Create a new entry in the map objects - m_jointsMapString->at(controlledJoint) = {cbNum, axis}; - m_jointsMapIndex->at(static_cast(iDynLinkIdx)) = {cbNum, axis}; - found = true; + m_jointsMapString->insert(std::make_pair(controlledJoint, std::make_pair(cbNum, axis))); + m_jointsMapIndex->insert(std::make_pair(static_cast(iDynJointIdx), + std::make_pair(cbNum, axis))); + m_controlledJointsMapCB->insert(std::make_pair(controlledJoint, found)); + (*m_controlBoardIdxLimit)[cbNum] = found + 1; break; } } - // Notify that the control board just checked is not used by any joint - // of the controlledJoints list - if (!found) { - Log::getSingleton().warning("No controlled joints found in " + - m_config.getControlBoardsNames().at(cbNum) + - " control board. It might be unsed."); - } + } - } - if (!controlBoard->close()) { - Log::getSingleton().error("Unable to close the device of the Control Board."); - return false; + // Notify that the control board just checked is not used by any joint + // of the controlledJoints list + if (found < 0) { + Log::getSingleton().warning("No controlled joints found in " + + m_config.getControlBoardsNames().at(cbNum) + + " control board. It might be unused."); + } + + // Close the ControlBoard device + if (!controlBoard->close()) { + Log::getSingleton().error("Unable to close the interface of the Control Board."); + return false; + } } + + // Initialize the network + yarp::os::Network::fini(); + return true; } @@ -152,22 +200,21 @@ const wbt::Configuration& RobotInterface::getConfiguration() const const std::shared_ptr RobotInterface::getJointsMapString() { - if (m_jointsMapString->empty()) { + if (!m_jointsMapString || m_jointsMapString->empty()) { if (!mapDoFs()) { - Log::getSingleton().error("Failed to create the Yarp - iDynTree joint map."); + Log::getSingleton().error("Failed to create the joint maps."); return nullptr; } } - assert (m_jointsMapString); return m_jointsMapString; } const std::shared_ptr RobotInterface::getJointsMapIndex() { - if (m_jointsMapIndex->empty()) { + if (!m_jointsMapIndex || m_jointsMapIndex->empty()) { if (!mapDoFs()) { - Log::getSingleton().error("Failed to create the Yarp - iDynTree joint map."); + Log::getSingleton().error("Failed to create the joint maps."); return nullptr; } } @@ -176,6 +223,32 @@ const std::shared_ptr RobotInterface::getJointsMapIndex() return m_jointsMapIndex; } +const std::shared_ptr RobotInterface::getControlledJointsMapCB() +{ + if (!m_controlledJointsMapCB || m_controlledJointsMapCB->empty()) { + if (!mapDoFs()) { + Log::getSingleton().error("Failed to create joint maps."); + return nullptr; + } + } + + assert (m_controlledJointsMapCB); + return m_controlledJointsMapCB; +} + +const std::shared_ptr RobotInterface::getControlBoardIdxLimit() +{ + if (!m_controlBoardIdxLimit || m_controlBoardIdxLimit->empty()) { + if (!mapDoFs()) { + Log::getSingleton().error("Failed to create joint maps."); + return nullptr; + } + } + + assert (m_controlBoardIdxLimit); + return m_controlBoardIdxLimit; +} + const std::shared_ptr RobotInterface::getKinDynComputations() { if (m_kinDynComp) { From 212ffaf7837d0af52929eb5c8f7086513bffae85 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 11:17:05 +0000 Subject: [PATCH 58/92] YarpRead: fixed indexing of signals This block has optional outputs, and the indexing in the output() method was not correct --- toolbox/src/YarpRead.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 9e5807cce..939446e05 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -178,8 +178,15 @@ bool YarpRead::terminate(const BlockInformation* /*blockInfo*/) bool YarpRead::output(const BlockInformation* blockInfo) { - int timeStampPortIndex = 1; - int connectionStatusPortIndex = 1; + int timeStampPortIndex = 0; + int connectionStatusPortIndex = 0; + + if (m_shouldReadTimestamp) { + timeStampPortIndex = 1; + } + if (!m_autoconnect) { + connectionStatusPortIndex = timeStampPortIndex + 1; + } yarp::sig::Vector* v = m_port->read(m_blocking); // Read from the port. Waits until data arrives. @@ -197,7 +204,9 @@ bool YarpRead::output(const BlockInformation* blockInfo) Signal signal = blockInfo->getOutputPortSignal(0); // Crop the buffer if it exceeds the OutputPortWidth. - signal.setBuffer(v->data(), std::min(blockInfo->getOutputPortWidth(0), (unsigned)v->size())); + signal.setBuffer(v->data(), + std::min(blockInfo->getOutputPortWidth(0), + static_cast(v->size()))); if (!m_autoconnect) { Signal statusPort = blockInfo->getOutputPortSignal(connectionStatusPortIndex); From 9cb9aa8531d29739ce477f92e32e7cd10e6732b5 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 15:59:40 +0000 Subject: [PATCH 59/92] Improved logging support and log messages --- toolbox/include/base/Log.h | 11 +++++++---- toolbox/src/GetLimits.cpp | 8 ++++++-- toolbox/src/GetMeasurement.cpp | 2 +- toolbox/src/SetLowLevelPID.cpp | 15 ++++++++++----- toolbox/src/SetReferences.cpp | 2 +- toolbox/src/YarpRead.cpp | 6 +++++- toolbox/src/base/Log.cpp | 25 +++++++++++++++++++++---- toolbox/src/base/RobotInterface.cpp | 4 +++- 8 files changed, 54 insertions(+), 19 deletions(-) diff --git a/toolbox/include/base/Log.h b/toolbox/include/base/Log.h index 699c431b6..e3f9d6764 100644 --- a/toolbox/include/base/Log.h +++ b/toolbox/include/base/Log.h @@ -18,16 +18,19 @@ class wbt::Log std::vector warnings; std::string prefix; - static std::string serializeVectorString(std::vector v, std::string prefix=""); + static std::string serializeVectorString(std::vector v, const std::string& prefix=""); public: static wbt::Log& getSingleton(); - void error(std::string errorMessage); - void warning(std::string warningMessage); + void error(const std::string& errorMessage); + void warning(const std::string& warningMessage); + + void errorAppend(const std::string& errorMessage); + void warningAppend(const std::string& warningMessage); void resetPrefix(); - void setPrefix(std::string prefixMessage); + void setPrefix(const std::string& prefixMessage); std::string getErrors() const; std::string getWarnings() const; diff --git a/toolbox/src/GetLimits.cpp b/toolbox/src/GetLimits.cpp index 44648995e..ca668fad3 100644 --- a/toolbox/src/GetLimits.cpp +++ b/toolbox/src/GetLimits.cpp @@ -103,7 +103,7 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) if (limitType == "ControlBoardPosition" || limitType == "ControlBoardVelocity") { // Retain the control board remapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + Log::getSingleton().error("Couldn't retain the RemoteControlBoardRemapper."); return false; } // Get the interface @@ -173,7 +173,11 @@ bool GetLimits::initialize(const BlockInformation* blockInfo) m_limits->max[i] = std::numeric_limits::infinity(); } else { - p_joint->getPosLimits(0, min, max); + if (!p_joint->getPosLimits(0, min, max)) { + Log::getSingleton().error("Failed to get joint limits from the URDF model "); + Log::getSingleton().errorAppend("for the joint " + joint + "."); + return false; + } m_limits->min[i] = min; m_limits->max[i] = max; } diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index 536ec00aa..a245105c6 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -95,7 +95,7 @@ bool GetMeasurement::initialize(const BlockInformation* blockInfo) // Retain the ControlBoardRemapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + Log::getSingleton().error("Couldn't retain the RemoteControlBoardRemapper."); return false; } diff --git a/toolbox/src/SetLowLevelPID.cpp b/toolbox/src/SetLowLevelPID.cpp index 6ce3a3aba..911b039d8 100644 --- a/toolbox/src/SetLowLevelPID.cpp +++ b/toolbox/src/SetLowLevelPID.cpp @@ -105,7 +105,12 @@ bool SetLowLevelPID::readWBTPidConfigObject(const BlockInformation* blockInfo) jointNamesFromParameters.push_back(joint); } - assert(Pvector.size() == Ivector.size() == Dvector.size() == jointNamesFromParameters.size()); + if (Pvector.size() != Ivector.size() || + Ivector.size() != Dvector.size() || + Dvector.size() != jointNamesFromParameters.size()) { + Log::getSingleton().error("Sizes of P, I, D, and jointList elements are not the same."); + return false; + } // Store this data into a private member map for (unsigned i = 0; i < jointNamesFromParameters.size(); ++i) { @@ -118,8 +123,8 @@ bool SetLowLevelPID::readWBTPidConfigObject(const BlockInformation* blockInfo) m_pidJointsFromParameters[jointNamesFromParameters[i]] = {Pvector[i], Ivector[i], Dvector[i]}; } else { - Log::getSingleton().warning("Attempted to set PID of joint " + jointNamesFromParameters[i] + - " non currently controlled. Skipping it."); + Log::getSingleton().warning("Attempted to set PID of joint " + jointNamesFromParameters[i]); + Log::getSingleton().warningAppend(" non currently controlled. Skipping it."); } } @@ -156,12 +161,12 @@ bool SetLowLevelPID::initialize(const BlockInformation* blockInfo) // Reading the WBTPIDConfig matlab class if (!readWBTPidConfigObject(blockInfo)) { Log::getSingleton().error("Failed to parse the WBTPIDConfig object."); - return 1; + return false; } // Retain the RemoteControlBoardRemapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to retain the control board remapper."); + Log::getSingleton().error("Couldn't retain the RemoteControlBoardRemapper."); return false; } diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 90edb1c6b..05317332e 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -135,7 +135,7 @@ bool SetReferences::initialize(const BlockInformation* blockInfo) // Retain the ControlBoardRemapper if (!getRobotInterface()->retainRemoteControlBoardRemapper()) { - Log::getSingleton().error("Failed to initialize the Robot Interface containing the Control Board Remapper."); + Log::getSingleton().error("Couldn't retain the RemoteControlBoardRemapper."); return false; } diff --git a/toolbox/src/YarpRead.cpp b/toolbox/src/YarpRead.cpp index 939446e05..a25dc31db 100644 --- a/toolbox/src/YarpRead.cpp +++ b/toolbox/src/YarpRead.cpp @@ -194,7 +194,11 @@ bool YarpRead::output(const BlockInformation* blockInfo) if (m_shouldReadTimestamp) { connectionStatusPortIndex++; yarp::os::Stamp timestamp; - m_port->getEnvelope(timestamp); + if (!m_port->getEnvelope(timestamp)) { + Log::getSingleton().error("Failed to read port envelope (timestamp)."); + Log::getSingleton().errorAppend("Be sure that the input port actually writes this data."); + return false; + } Signal pY1 = blockInfo->getOutputPortSignal(timeStampPortIndex); pY1.set(0, timestamp.getCount()); diff --git a/toolbox/src/base/Log.cpp b/toolbox/src/base/Log.cpp index 9ee6abdaa..47769393c 100644 --- a/toolbox/src/base/Log.cpp +++ b/toolbox/src/base/Log.cpp @@ -10,17 +10,34 @@ Log& Log::getSingleton() return logInstance; } -void Log::error(std::string errorMessage) +void Log::error(const std::string& errorMessage) { errors.push_back(errorMessage); } -void Log::warning(std::string warningMessage) +void Log::warning(const std::string& warningMessage) { warnings.push_back(warningMessage); } -void Log::setPrefix(std::string prefixMessage) +void Log::errorAppend(const std::string& errorMessage) +{ + if (errors.empty()) { + error(errorMessage); + return; + } + errors.back() += errorMessage; +} + +void Log::warningAppend(const std::string& warningMessage) +{ + if (warnings.empty()) { + warning(warningMessage); + } + warnings.back() += warningMessage; +} + +void Log::setPrefix(const std::string& prefixMessage) { prefix = prefixMessage; } @@ -30,7 +47,7 @@ void Log::resetPrefix() prefix.clear(); } -std::string Log::serializeVectorString(std::vector v, std::string prefix) +std::string Log::serializeVectorString(std::vector v, const std::string& prefix) { std::stringstream output; std::ostream_iterator output_iterator(output, "\n"); diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index e637d40e5..9755e4d7a 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -351,6 +351,7 @@ bool RobotInterface::retainRemoteControlBoardRemapper() } if (!initializeRemoteControlBoardRemapper()) { + Log::getSingleton().error("First initialization of the RemoteControlBoardRemapper failed."); return false; } @@ -433,7 +434,8 @@ bool RobotInterface::initializeModel() iDynTree::ModelLoader mdlLoader; if (!mdlLoader.loadReducedModelFromFile(urdf_file_path, controlledJoints)) { Log::getSingleton().error("ToolboxSingleton: impossible to load " + urdf_file + "."); - Log::getSingleton().error("Probably the joint list contains an entry not present in the urdf model."); + Log::getSingleton().errorAppend("\nPossible causes: file not found, or the joint "); + Log::getSingleton().errorAppend("list contains an entry not present in the urdf model."); return false; } From e210a17d10a3491b9d008762cca96f6243e0fb24 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 16:01:06 +0000 Subject: [PATCH 60/92] Initialize to nullptr the buffers of the Signal class --- toolbox/include/base/Signal.h | 2 +- toolbox/src/base/Signal.cpp | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/toolbox/include/base/Signal.h b/toolbox/include/base/Signal.h index 0fbe27f3c..21109b7c7 100644 --- a/toolbox/include/base/Signal.h +++ b/toolbox/include/base/Signal.h @@ -19,7 +19,7 @@ class wbt::Signal void* contiguousData; public: - Signal() = default; + Signal(); void initSignalType(wbt::PortDataType type, bool constPort); diff --git a/toolbox/src/base/Signal.cpp b/toolbox/src/base/Signal.cpp index 67e6d6b42..028daef88 100644 --- a/toolbox/src/base/Signal.cpp +++ b/toolbox/src/base/Signal.cpp @@ -3,6 +3,11 @@ using namespace wbt; +Signal::Signal() +: nonContiguousData(nullptr) +, contiguousData(nullptr) +{} + void Signal::initSignalType(wbt::PortDataType type, bool constPort) { this->portType = type; From 8ea9fe7d2ca6d5a25a16e048934636e2086eb21e Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 16:02:06 +0000 Subject: [PATCH 61/92] Use const arguments in Configuration::setParameters() --- toolbox/include/base/Configuration.h | 12 ++++++------ toolbox/src/base/Configuration.cpp | 12 ++++++------ 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/toolbox/include/base/Configuration.h b/toolbox/include/base/Configuration.h index b131ce81a..4f0884a67 100644 --- a/toolbox/include/base/Configuration.h +++ b/toolbox/include/base/Configuration.h @@ -48,12 +48,12 @@ class wbt::Configuration * @param localName Prefix appended to the opened ports * @param gravityVector The gravity vector */ - void setParameters(std::string robotName, - std::string urdfFile, - std::vector controlledJoints, - std::vector controlBoardsNames, - std::string localName, - std::array gravityVector); + void setParameters(const std::string& robotName, + const std::string& urdfFile, + const std::vector& controlledJoints, + const std::vector& controlBoardsNames, + const std::string& localName, + const std::array& gravityVector); /** * Set the name of the robot diff --git a/toolbox/src/base/Configuration.cpp b/toolbox/src/base/Configuration.cpp index 257a475f4..e4205ac9b 100644 --- a/toolbox/src/base/Configuration.cpp +++ b/toolbox/src/base/Configuration.cpp @@ -11,12 +11,12 @@ Configuration::Configuration(const std::string& confKey) // SET METHODS // =========== -void Configuration::setParameters(std::string robotName, - std::string urdfFile, - std::vector controlledJoints, - std::vector controlBoardsNames, - std::string localName, - std::array gravityVector) +void Configuration::setParameters(const std::string& robotName, + const std::string& urdfFile, + const std::vector& controlledJoints, + const std::vector& controlBoardsNames, + const std::string& localName, + const std::array& gravityVector) { setRobotName(robotName); setUrdfFile(urdfFile); From dc20f9a34dc479872f6f29956fb1bcb99cda0c6c Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 16:03:50 +0000 Subject: [PATCH 62/92] Fix passing booleans as mask parameters Sometimes the boolean are passed as double, and reading them using MxAnyType::asBool() fails --- toolbox/src/base/SimulinkBlockInformation.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/toolbox/src/base/SimulinkBlockInformation.cpp b/toolbox/src/base/SimulinkBlockInformation.cpp index 2b9688738..38c1060db 100644 --- a/toolbox/src/base/SimulinkBlockInformation.cpp +++ b/toolbox/src/base/SimulinkBlockInformation.cpp @@ -50,7 +50,18 @@ bool SimulinkBlockInformation::getScalarParameterAtIndex(unsigned parameterIndex bool SimulinkBlockInformation::getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) const { + double tmpValue = 0; const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + + // The Simulink mask often doesn't store boolean data from the mask as bool but as double. + // Calling asBool() will fail in this case. If this happens, asDouble() is used as fallback. + if (MxAnyType(blockParam).asBool(value)) { + return true; + } + else if (MxAnyType(blockParam).asDouble(tmpValue)) { + value = static_cast(tmpValue); + return true; + } return MxAnyType(blockParam).asBool(value); } From 3a1941c13bf5ced45f9c0231527572dd02319bdf Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 16:06:06 +0000 Subject: [PATCH 63/92] Added method for extractring a struct from Matlab's WBTPIDConfig class The struct is then used as S-Function parameter --- +WBToolbox/WBTPIDConfig.m | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/+WBToolbox/WBTPIDConfig.m b/+WBToolbox/WBTPIDConfig.m index 9d23b523f..51999e301 100644 --- a/+WBToolbox/WBTPIDConfig.m +++ b/+WBToolbox/WBTPIDConfig.m @@ -57,6 +57,18 @@ function removePID(obj, jointName) obj.I(:,idx) = []; obj.D(:,idx) = []; end + + function value = getSimulinkParameters(obj) + if isempty(obj.P) || isempty(obj.I) || isempty(obj.D) || ... + isempty(obj.jointList) + error('Trying to get parameters from an empty object') + end + value = struct(); + value.P = obj.P; + value.I = obj.I; + value.D = obj.D; + value.jointList = obj.jointList; + end end end From f20f521f70625413948c536ea757624b2b287a49 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 16:06:39 +0000 Subject: [PATCH 64/92] Typo in Mask2WBToolboxConfig.m script --- +WBToolbox/Mask2WBToolboxConfig.m | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/+WBToolbox/Mask2WBToolboxConfig.m b/+WBToolbox/Mask2WBToolboxConfig.m index 0396a46a3..b9850d12c 100644 --- a/+WBToolbox/Mask2WBToolboxConfig.m +++ b/+WBToolbox/Mask2WBToolboxConfig.m @@ -22,13 +22,13 @@ WBTConfig.LocalName = stripApices(char(get_param(configBlock,'LocalName'))); ControlledJointsChar = stripApices(char(get_param(configBlock,'ControlledJoints'))); -WBTConfig.ControlledJoints = eval('base',ControlledJointsChar); +WBTConfig.ControlledJoints = evalin('base',ControlledJointsChar); ControlBoardsNamesChar = stripApices(char(get_param(configBlock,'ControlBoardsNames'))); -WBTConfig.ControlBoardsNames = eval('base',ControlBoardsNamesChar); +WBTConfig.ControlBoardsNames = evalin('base',ControlBoardsNamesChar); GravityVectorChar = stripApices(char(get_param(configBlock,'GravityVector'))); -WBTConfig.GravityVector = eval('base',GravityVectorChar); +WBTConfig.GravityVector = evalin('base',GravityVectorChar); end From ed2d5de1cf0099862bf7168575a956d4d1c7d81f Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 21 Nov 2017 16:08:34 +0000 Subject: [PATCH 65/92] Disable IK blocks --- toolbox/include/base/toolbox.h | 4 ++-- toolbox/src/base/factory.cpp | 14 ++++++-------- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/toolbox/include/base/toolbox.h b/toolbox/include/base/toolbox.h index cc0750e51..14f5a3778 100644 --- a/toolbox/include/base/toolbox.h +++ b/toolbox/include/base/toolbox.h @@ -21,6 +21,6 @@ #include "MinimumJerkTrajectoryGenerator.h" #endif #ifdef WBT_USES_IPOPT -#include "InverseKinematics.h" -#include "RemoteInverseKinematics.h" +// #include "InverseKinematics.h" #endif +// #include "RemoteInverseKinematics.h" diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index 2d1d5f828..ab7d9f9be 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -45,14 +45,12 @@ Block* Block::instantiateBlockWithClassName(std::string blockClassName) } #endif #ifdef WBT_USES_IPOPT - else if (blockClassName == wbt::InverseKinematics::ClassName) { - block = new wbt::InverseKinematics(); - } + // else if (blockClassName == InverseKinematics::ClassName) { + // block = new InverseKinematics(); + // } #endif - else if (blockClassName == wbt::RemoteInverseKinematics::ClassName) { - block = new wbt::RemoteInverseKinematics(); - } - - + // else if (blockClassName == RemoteInverseKinematics::ClassName) { + // block = new RemoteInverseKinematics(); + // } return block; } From 33532320a824dcb4603281baec14f97033657c90 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 28 Nov 2017 15:50:48 +0000 Subject: [PATCH 66/92] Use system Matlab headers in MxAnyType library --- MxAnyType/CMakeLists.txt | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/MxAnyType/CMakeLists.txt b/MxAnyType/CMakeLists.txt index 4faaebad7..608670096 100644 --- a/MxAnyType/CMakeLists.txt +++ b/MxAnyType/CMakeLists.txt @@ -34,8 +34,7 @@ endif() # Find Matlab resources find_package(Matlab REQUIRED MX_LIBRARY) -# target_include_directories(${VARS_PREFIX} SYSTEM PUBLIC "${Matlab_INCLUDE_DIRS}") // TODO: when committing -target_include_directories(${VARS_PREFIX} PUBLIC "${Matlab_INCLUDE_DIRS}") +target_include_directories(${VARS_PREFIX} SYSTEM PUBLIC "${Matlab_INCLUDE_DIRS}") # Setup the include directories # TODO why in the how to was INTERFACE? From b695ad4509fbaf79d3b501e54fd6f4225fc75e80 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Tue, 28 Nov 2017 15:51:38 +0000 Subject: [PATCH 67/92] Moved +WBToolbox folder into toolbox/ --- {+WBToolbox => toolbox/+WBToolbox}/BlockInitialization.m | 0 {+WBToolbox => toolbox/+WBToolbox}/Mask2WBToolboxConfig.m | 0 {+WBToolbox => toolbox/+WBToolbox}/PID.m | 0 {+WBToolbox => toolbox/+WBToolbox}/WBTPIDConfig.m | 0 {+WBToolbox => toolbox/+WBToolbox}/WBToolboxConfig.m | 0 {+WBToolbox => toolbox/+WBToolbox}/WBToolboxConfig2Mask.m | 0 6 files changed, 0 insertions(+), 0 deletions(-) rename {+WBToolbox => toolbox/+WBToolbox}/BlockInitialization.m (100%) rename {+WBToolbox => toolbox/+WBToolbox}/Mask2WBToolboxConfig.m (100%) rename {+WBToolbox => toolbox/+WBToolbox}/PID.m (100%) rename {+WBToolbox => toolbox/+WBToolbox}/WBTPIDConfig.m (100%) rename {+WBToolbox => toolbox/+WBToolbox}/WBToolboxConfig.m (100%) rename {+WBToolbox => toolbox/+WBToolbox}/WBToolboxConfig2Mask.m (100%) diff --git a/+WBToolbox/BlockInitialization.m b/toolbox/+WBToolbox/BlockInitialization.m similarity index 100% rename from +WBToolbox/BlockInitialization.m rename to toolbox/+WBToolbox/BlockInitialization.m diff --git a/+WBToolbox/Mask2WBToolboxConfig.m b/toolbox/+WBToolbox/Mask2WBToolboxConfig.m similarity index 100% rename from +WBToolbox/Mask2WBToolboxConfig.m rename to toolbox/+WBToolbox/Mask2WBToolboxConfig.m diff --git a/+WBToolbox/PID.m b/toolbox/+WBToolbox/PID.m similarity index 100% rename from +WBToolbox/PID.m rename to toolbox/+WBToolbox/PID.m diff --git a/+WBToolbox/WBTPIDConfig.m b/toolbox/+WBToolbox/WBTPIDConfig.m similarity index 100% rename from +WBToolbox/WBTPIDConfig.m rename to toolbox/+WBToolbox/WBTPIDConfig.m diff --git a/+WBToolbox/WBToolboxConfig.m b/toolbox/+WBToolbox/WBToolboxConfig.m similarity index 100% rename from +WBToolbox/WBToolboxConfig.m rename to toolbox/+WBToolbox/WBToolboxConfig.m diff --git a/+WBToolbox/WBToolboxConfig2Mask.m b/toolbox/+WBToolbox/WBToolboxConfig2Mask.m similarity index 100% rename from +WBToolbox/WBToolboxConfig2Mask.m rename to toolbox/+WBToolbox/WBToolboxConfig2Mask.m From 00911ae1e8f52b2397911e591e6ed34566047589 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 07:20:06 +0000 Subject: [PATCH 68/92] Fixed DotJNu output variable --- toolbox/include/DotJNu.h | 2 +- toolbox/src/DotJNu.cpp | 10 ++++------ 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/toolbox/include/DotJNu.h b/toolbox/include/DotJNu.h index 409a185af..0bc8153ee 100644 --- a/toolbox/include/DotJNu.h +++ b/toolbox/include/DotJNu.h @@ -28,7 +28,7 @@ class wbt::DotJNu : public wbt::WBBlock public: static const std::string ClassName; - + DotJNu(); ~DotJNu() override = default; diff --git a/toolbox/src/DotJNu.cpp b/toolbox/src/DotJNu.cpp index e984d7a96..c6fcd7c2a 100644 --- a/toolbox/src/DotJNu.cpp +++ b/toolbox/src/DotJNu.cpp @@ -189,15 +189,13 @@ bool DotJNu::output(const BlockInformation* blockInfo) // OUTPUT // ====== - // Compute the dot{J}*\nu - Vector6 biasAcc; if (!m_frameIsCoM) { - biasAcc = model->getFrameBiasAcc(m_frameIndex); + *m_dotJNu = model->getFrameBiasAcc(m_frameIndex); } else { - Vector3 comBiasAcc = model->getCenterOfMassBiasAcc(); - toEigen(biasAcc).segment<3>(0) = iDynTree::toEigen(comBiasAcc); - toEigen(biasAcc).segment<3>(3).setZero(); + iDynTree::Vector3 comBiasAcc = model->getCenterOfMassBiasAcc(); + toEigen(*m_dotJNu).segment<3>(0) = iDynTree::toEigen(comBiasAcc); + toEigen(*m_dotJNu).segment<3>(3).setZero(); } // Forward the output to Simulink From e24edee09268a068d8812fde88bb7785f52945f4 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 08:02:52 +0000 Subject: [PATCH 69/92] Signal class rewritten - Added support to contiguous inputs (which are now the default setting) - For non-contiguous signals, an internal buffer is allocated with signal data, and data copy has been minimized as much as possible - When gathering a signal from Matlab, data type and signal are now read directly from the SimStruct - For the time being, only double signal are supported, which are the Simulink defaults. The structure for including the support of other data types is already present, and it will be included in the upcoming releases --- toolbox/include/base/BlockInformation.h | 48 +-- toolbox/include/base/Signal.h | 175 ++++++-- .../include/base/SimulinkBlockInformation.h | 22 +- toolbox/src/base/Signal.cpp | 394 ++++++------------ toolbox/src/base/SimulinkBlockInformation.cpp | 247 +++++++---- toolbox/src/base/toolbox.cpp | 9 + 6 files changed, 467 insertions(+), 428 deletions(-) diff --git a/toolbox/include/base/BlockInformation.h b/toolbox/include/base/BlockInformation.h index 06e2c37c1..43ef04306 100644 --- a/toolbox/include/base/BlockInformation.h +++ b/toolbox/include/base/BlockInformation.h @@ -3,7 +3,6 @@ #include "AnyType.h" #include -#include namespace wbt { class BlockInformation; @@ -21,37 +20,6 @@ namespace wbt { PortDataTypeBoolean, } PortDataType; - class Data - { - private: - double buffer; - public: - inline double doubleData() const { return buffer; } - inline void doubleData(const double& data) { buffer = data; } - inline float floatData() const { return static_cast(buffer); } - inline void floatData(const float& data) { buffer = static_cast(data); } - - inline int8_t int8Data() const { return static_cast(buffer); } - inline void int8Data(const int8_t& data) { buffer = static_cast(data); } - inline uint8_t uint8Data() const { return static_cast(buffer); } - inline void uint8Data(const uint8_t& data) { buffer = static_cast(data); } - - inline int16_t int16Data() const { return static_cast(buffer); } - inline void int16Data(const int16_t& data) { buffer = static_cast(data); } - inline uint16_t uint16Data() const { return static_cast(buffer); } - inline void uint16Data(const uint16_t& data) { buffer = static_cast(data); } - - inline int32_t int32Data() const { return static_cast(buffer); } - inline void int32Data(const int32_t& data) { buffer = static_cast(data); } - inline uint32_t uint32Data() const { return static_cast(buffer); } - inline void uint32Data(const uint32_t& data) { buffer = static_cast(data); } - - inline bool booleanData() const { return static_cast(buffer); } - inline void booleanData(const bool& data) { buffer = static_cast(data); } - - friend Signal; - }; - extern const std::string BlockOptionPrioritizeOrder; } @@ -61,7 +29,7 @@ class wbt::BlockInformation { BlockInformation() = default; virtual ~BlockInformation() = default; - // Block Options methods + // BLOCK OPTIONS METHODS // ===================== /** @@ -74,7 +42,7 @@ class wbt::BlockInformation { virtual bool optionFromKey(const std::string& key, double& option) const; - // Parameters methods + // PARAMETERS METHODS // ================== /** @@ -88,12 +56,10 @@ class wbt::BlockInformation { virtual bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) const = 0; virtual bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) const = 0; virtual bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) const = 0; - // virtual bool getAnyTypeAtIndex(unsigned parameterIndex, AnyType* data) = 0; - // virtual bool getCellAtIndex(unsigned parameterIndex, AnyCell& map) = 0; virtual bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const = 0; virtual bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const = 0; - // Port information methods + // PORT INFORMATION SETTERS // ======================== virtual bool setNumberOfInputPorts(unsigned numberOfPorts) = 0; @@ -114,13 +80,13 @@ class wbt::BlockInformation { virtual bool setInputPortType(unsigned portNumber, PortDataType portType) = 0; virtual bool setOutputPortType(unsigned portNumber, PortDataType portType) = 0; - // Port data - // ========= + // PORT INFORMATION GETTERS + // ======================== virtual unsigned getInputPortWidth(unsigned portNumber) const = 0; virtual unsigned getOutputPortWidth(unsigned portNumber) const = 0; - virtual wbt::Signal getInputPortSignal(unsigned portNumber) const = 0; - virtual wbt::Signal getOutputPortSignal(unsigned portNumber)const = 0; + virtual wbt::Signal getInputPortSignal(unsigned portNumber, int portWidth = -1) const = 0; + virtual wbt::Signal getOutputPortSignal(unsigned portNumber, int portWidth = -1) const = 0; }; #endif /* end of include guard: WBT_BLOCKINFORMATION_H */ diff --git a/toolbox/include/base/Signal.h b/toolbox/include/base/Signal.h index 21109b7c7..38f827a8b 100644 --- a/toolbox/include/base/Signal.h +++ b/toolbox/include/base/Signal.h @@ -2,50 +2,175 @@ #define WBT_SIGNAL_H #include "BlockInformation.h" -#include +#include +#include namespace wbt { class Signal; + enum SignalDataFormat { + NONCONTIGUOUS = 0, + CONTIGUOUS = 1, + CONTIGUOUS_ZEROCOPY = 2 + }; } class wbt::Signal { private: - PortDataType portType; - bool isContiguous; - bool isConstPort; + int m_width; + const bool m_isConst; + const PortDataType m_portDataType; + const SignalDataFormat m_dataFormat; - void** nonContiguousData; - void* contiguousData; + void* m_bufferPtr; + + void deleteBuffer(); + void allocateBuffer(const void* const bufferInput, void*& bufferOutput, unsigned length); + + template T* getCastBuffer() const; public: - Signal(); + // Ctor and Dtor + Signal(const SignalDataFormat& dataFormat = CONTIGUOUS_ZEROCOPY, + const PortDataType& dataType = PortDataTypeDouble, + const bool& isConst = true); + ~Signal(); + // Copy + Signal(const Signal& signal); + Signal& operator=(const Signal& signal) = delete; + // Move + Signal(Signal&& signal); + Signal& operator=(Signal&& signal) = delete; - void initSignalType(wbt::PortDataType type, bool constPort); + bool initializeBufferFromContiguous(const void* buffer); + bool initializeBufferFromContiguousZeroCopy(const void* buffer); + bool initializeBufferFromNonContiguous(const void* const* bufferPtrs); - void setContiguousBuffer(void* buffer); - void setContiguousBuffer(const void* buffer); - void setNonContiguousBuffer(void** buffer); - void setNonContiguousBuffer(const void* const* buffer); + bool isConst() const; + unsigned getWidth() const; + PortDataType getPortDataType() const; + SignalDataFormat getDataFormat() const; + template T* getBuffer() const; + template T get(const unsigned& i) const; - const Data get(unsigned index) const; - void* getContiguousBuffer(); - std::vector getStdVector(unsigned length) const; + void setWidth(const unsigned& width); + bool set(const unsigned& index, const double& data); + template bool setBuffer(const T* data, const unsigned& length); +}; - //the missing are cast - void set(unsigned index, double data); - void setBuffer(const double* data, const unsigned length, unsigned startIndex = 0); +template +T* wbt::Signal::getBuffer() const +{ + // Check the returned matches the same type of the portType. + // If this is not met, appliying pointer arithmetics on the returned + // pointer would show unknown behaviour. + switch(m_portDataType) { + case wbt::PortDataTypeDouble: + if (typeid(T).hash_code() != typeid(double).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeSingle: + if (typeid(T).hash_code() != typeid(float).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeInt8: + if (typeid(T).hash_code() != typeid(int8_t).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeUInt8: + if (typeid(T).hash_code() != typeid(uint8_t).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeInt16: + if (typeid(T).hash_code() != typeid(int16_t).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeUInt16: + if (typeid(T).hash_code() != typeid(uint16_t).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeInt32: + if (typeid(T).hash_code() != typeid(int32_t).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeUInt32: + if (typeid(T).hash_code() != typeid(uint32_t).hash_code()) { + return nullptr; + } + break; + case wbt::PortDataTypeBoolean: + if (typeid(T).hash_code() != typeid(bool).hash_code()) { + return nullptr; + } + break; + default: + return nullptr; + break; + } - void set(unsigned index, int32_t data); - void setBuffer(const int32_t* data, const unsigned length, unsigned startIndex = 0); + // Return the correct pointer + return static_cast(m_bufferPtr); +} - void set(unsigned index, uint32_t data); - void setBuffer(const uint32_t* data, const unsigned length, unsigned startIndex = 0); +template +bool wbt::Signal::setBuffer(const T* data, const unsigned& length) +{ + // Non contiguous signals follow the Simulink convention of being read-only + if (m_dataFormat == NONCONTIGUOUS || m_isConst) { + return false; + } - void set(unsigned index, bool data); - void setBuffer(const bool* data, const unsigned length, unsigned startIndex = 0); + if (m_dataFormat == CONTIGUOUS_ZEROCOPY && length > m_width) { + return false; + } -}; + if (typeid(getBuffer()).hash_code() != typeid(T*).hash_code()) { + return false; + } + switch (m_dataFormat) { + case CONTIGUOUS: + // Delete the current array + if (m_bufferPtr) { + delete getBuffer(); + m_bufferPtr = nullptr; + m_width = 0; + } + // Allocate a new empty array + m_bufferPtr = static_cast(new T[length]); + m_width = length; + // Fill it with new data + std::copy(data, data + length, getBuffer()); + break; + case CONTIGUOUS_ZEROCOPY: + // Reset current data + std::fill(getBuffer(), getBuffer() + m_width, 0); + // Copy new data + std::copy(data, data + length, getBuffer()); + // Update the width + m_width = length; + break; + case NONCONTIGUOUS: + return false; + } + + return true; +} + +template +T wbt::Signal::get(const unsigned& i) const +{ + T* buffer = getBuffer(); + assert(buffer); + + return buffer[i]; +} #endif /* end of include guard: WBT_SIGNAL_H */ diff --git a/toolbox/include/base/SimulinkBlockInformation.h b/toolbox/include/base/SimulinkBlockInformation.h index 0da7f51c5..dd79f9b31 100644 --- a/toolbox/include/base/SimulinkBlockInformation.h +++ b/toolbox/include/base/SimulinkBlockInformation.h @@ -15,20 +15,30 @@ class wbt::SimulinkBlockInformation : public wbt::BlockInformation private: SimStruct* simstruct; + PortDataType mapSimulinkToPortType(const DTypeId& typeId) const; + DTypeId mapPortTypeToSimulink(const PortDataType& dataType) const; + public: SimulinkBlockInformation(SimStruct* simstruct); ~SimulinkBlockInformation() override = default; + // BLOCK OPTIONS METHODS + // ===================== + bool optionFromKey(const std::string& key, double& option) const override; - //Parameters methods + // PARAMETERS METHODS + // ================== + bool getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) const override; bool getScalarParameterAtIndex(unsigned parameterIndex, double& value) const override; bool getBooleanParameterAtIndex(unsigned parameterIndex, bool& value) const override; bool getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const override; bool getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const override; - //Port information methods + // PORT INFORMATION SETTERS + // ======================== + bool setNumberOfInputPorts(unsigned numberOfPorts) override; bool setNumberOfOutputPorts(unsigned numberOfPorts) override; bool setInputPortVectorSize(unsigned portNumber, int portSize) override; @@ -38,11 +48,13 @@ class wbt::SimulinkBlockInformation : public wbt::BlockInformation bool setInputPortType(unsigned portNumber, PortDataType portType) override; bool setOutputPortType(unsigned portNumber, PortDataType portType) override; - //Port data + // PORT INFORMATION GETTERS + // ======================== + unsigned getInputPortWidth(unsigned portNumber) const override; unsigned getOutputPortWidth(unsigned portNumber) const override; - wbt::Signal getInputPortSignal(unsigned portNumber) const override; - wbt::Signal getOutputPortSignal(unsigned portNumber) const override; + wbt::Signal getInputPortSignal(unsigned portNumber, int portWidth = DYNAMICALLY_SIZED) const override; + wbt::Signal getOutputPortSignal(unsigned portNumber, int portWidth = DYNAMICALLY_SIZED) const override; }; #endif /* end of include guard: WBT_SIMULINKBLOCKINFORMATION_H */ diff --git a/toolbox/src/base/Signal.cpp b/toolbox/src/base/Signal.cpp index 028daef88..b55bb425f 100644 --- a/toolbox/src/base/Signal.cpp +++ b/toolbox/src/base/Signal.cpp @@ -1,325 +1,189 @@ #include "Signal.h" -#include using namespace wbt; -Signal::Signal() -: nonContiguousData(nullptr) -, contiguousData(nullptr) -{} - -void Signal::initSignalType(wbt::PortDataType type, bool constPort) +Signal::~Signal() { - this->portType = type; - this->isConstPort = constPort; + deleteBuffer(); } -void Signal::setContiguousBuffer(void* buffer) -{ - contiguousData = buffer; - this->isContiguous = true; -} -void Signal::setContiguousBuffer(const void* buffer) +Signal::Signal(const Signal& signal) +: m_width(signal.m_width) +, m_isConst(signal.m_isConst) +, m_portDataType(signal.m_portDataType) +, m_dataFormat(signal.m_dataFormat) +, m_bufferPtr(nullptr) { - contiguousData = const_cast(buffer); - this->isContiguous = true; + if (signal.m_bufferPtr) { + switch (signal.m_dataFormat) { + // Just copy the pointer to MATLAB's memory + case CONTIGUOUS_ZEROCOPY: + m_bufferPtr = signal.m_bufferPtr; + break; + // Copy the allocated data + case NONCONTIGUOUS: + case CONTIGUOUS: + allocateBuffer(signal.m_bufferPtr, m_bufferPtr, signal.m_width); + break; + } + } } -void Signal::setNonContiguousBuffer(void** buffer) +Signal::Signal(const SignalDataFormat& dataFormat, + const PortDataType& dataType, + const bool& isConst) +: m_isConst(isConst) +, m_portDataType(dataType) +, m_dataFormat(dataFormat) +, m_bufferPtr(nullptr) +{} + +Signal::Signal(Signal&& other) +: m_width(other.m_width) +, m_isConst(other.m_isConst) +, m_portDataType(other.m_portDataType) +, m_dataFormat(other.m_dataFormat) +, m_bufferPtr(other.m_bufferPtr) { - nonContiguousData = buffer; - this->isContiguous = false; + other.m_width = 0; + other.m_bufferPtr = nullptr; } -void Signal::setNonContiguousBuffer(const void* const* buffer) +void Signal::allocateBuffer(const void* const bufferInput, void*& bufferOutput, unsigned length) { - nonContiguousData = const_cast(buffer); - this->isContiguous = false; + // TODO: Implement other PortDataType + switch (m_portDataType) { + case PortDataTypeDouble: { + // Allocate the array + bufferOutput = static_cast(new double[m_width]); + // Cast to double + const double* const bufferInputDouble = static_cast(bufferInput); + double* bufferOutputDouble = static_cast(bufferOutput); + // Copy data + std::copy(bufferInputDouble, bufferInputDouble + length, bufferOutputDouble); + return; + } + default: + return; + } } - -const Data Signal::get(unsigned index) const +void Signal::deleteBuffer() { - Data data; - switch (portType) { + if (m_dataFormat == CONTIGUOUS_ZEROCOPY || !m_bufferPtr) { + return; + } + + // TODO: Implement other PortDataType + switch (m_portDataType) { case PortDataTypeDouble: - if (isContiguous) { - data.doubleData((static_cast(contiguousData))[index]); - } - else { - const double* buffer = static_cast(*nonContiguousData); - data.doubleData(static_cast(buffer[index])); - } - break; - case PortDataTypeSingle: - if (isContiguous) { - data.floatData((static_cast(contiguousData))[index]); - } - else { - const float* buffer = static_cast(*nonContiguousData); - data.floatData(static_cast(buffer[index])); - } - break; - case PortDataTypeInt8: - if (isContiguous) { - data.int8Data((static_cast(contiguousData))[index]); - } - else { - const int8_t* buffer = static_cast(*nonContiguousData); - data.int8Data(static_cast(buffer[index])); - } - break; - case PortDataTypeUInt8: - if (isContiguous) { - data.uint8Data((static_cast(contiguousData))[index]); - } - else { - const uint8_t* buffer = static_cast(*nonContiguousData); - data.uint8Data(static_cast(buffer[index])); - } - break; - case PortDataTypeInt16: - if (isContiguous) { - data.int16Data((static_cast(contiguousData))[index]); - } - else { - const int16_t* buffer = static_cast(*nonContiguousData); - data.int16Data(static_cast(buffer[index])); - } - break; - case PortDataTypeUInt16: - if (isContiguous) { - data.uint16Data((static_cast(contiguousData))[index]); - } - else { - const uint16_t* buffer = static_cast(*nonContiguousData); - data.uint16Data(static_cast(buffer[index])); - } - break; - case PortDataTypeInt32: - if (isContiguous) { - data.int32Data((static_cast(contiguousData))[index]); - } - else { - const int32_t* buffer = static_cast(*nonContiguousData); - data.int32Data(static_cast(buffer[index])); - } - break; - case PortDataTypeUInt32: - if (isContiguous) { - data.uint32Data((static_cast(contiguousData))[index]); - } - else { - const uint32_t* buffer = static_cast(*nonContiguousData); - data.uint32Data(static_cast(buffer[index])); - } - break; - case PortDataTypeBoolean: - if (isContiguous) { - data.booleanData((static_cast(contiguousData))[index]); - } - else { - const bool* buffer = static_cast(*nonContiguousData); - data.booleanData(static_cast(buffer[index])); - } + delete static_cast(m_bufferPtr); + m_bufferPtr = nullptr; + return; + default: + return; } - return data; } -void* Signal::getContiguousBuffer() +bool Signal::initializeBufferFromContiguousZeroCopy(const void* buffer) { - if (!isContiguous) return nullptr; - return this->contiguousData; + if (m_dataFormat != CONTIGUOUS_ZEROCOPY) { + return false; + } + + m_bufferPtr = const_cast(buffer); + return true; } -std::vector Signal::getStdVector(unsigned length) const +bool Signal::initializeBufferFromContiguous(const void* buffer) { - std::vector v(length); - for (unsigned i = 0; i < length; ++i) { - v[i] = get(i).doubleData(); + if (m_dataFormat != CONTIGUOUS || + m_width <= 0) { + return false; } - return v; -} -//the missing are cast -void Signal::set(unsigned index, double data) -{ - if (isConstPort) return; + if (m_portDataType == PortDataTypeDouble) { + // Allocate a new vector to store data from the non-contiguous signal + m_bufferPtr = static_cast(new double[m_width]); + const double* bufferInputDouble = static_cast(buffer); + double* bufferOutputDouble = static_cast(m_bufferPtr); - switch (portType) { - case PortDataTypeDouble: - { - double* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeSingle: - { - float* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - default: - break; + // Copy data from the input memory location + std::copy(bufferInputDouble, bufferInputDouble + m_width, bufferOutputDouble); } + return true; } -void Signal::setBuffer(const double* data, const unsigned length, unsigned startIndex) +bool Signal::initializeBufferFromNonContiguous(const void* const* bufferPtrs) { - if (isConstPort) return; - unsigned dataSize = 0; - const void* address = data; - - switch (portType) { - case PortDataTypeDouble: - { - dataSize = sizeof(double); - address = static_cast(address) + startIndex; - break; - } - case PortDataTypeSingle: - { - dataSize = sizeof(float); - address = static_cast(address) + startIndex; - break; - } - default: - break; + if (m_dataFormat != NONCONTIGUOUS || + m_width <= 0) { + return false; } - memcpy(contiguousData, address, dataSize * length); + if (m_portDataType == PortDataTypeDouble) { + // Allocate a new vector to store data from the non-contiguous signal + m_bufferPtr = static_cast(new double[m_width]); + double* bufferPtrDouble = static_cast(m_bufferPtr); + // Copy data from MATLAB's memory to the Signal object + for (auto i = 0; i < m_width; ++i) { + const double* valuePtr = static_cast(*bufferPtrs); + bufferPtrDouble[i] = valuePtr[i]; + } + } + return true; } -void Signal::set(unsigned index, int32_t data) +void Signal::setWidth(const unsigned& width) { - //signed integer function - switch (portType) { - case PortDataTypeInt32: - { - int32_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeInt16: - { - int16_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeInt8: - { - int8_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - default: - break; - } + m_width = width; } -void Signal::setBuffer(const int32_t* data, const unsigned length, unsigned startIndex) +unsigned Signal::getWidth() const { - if (isConstPort) return; - unsigned dataSize = 0; - const void* address = data; + return m_width; +} - switch (portType) { - case PortDataTypeInt32: - { - dataSize = sizeof(int32_t); - address = static_cast(address) + startIndex; - break; - } - case PortDataTypeInt16: - { - dataSize = sizeof(int16_t); - address = static_cast(address) + startIndex; - break; - } - case PortDataTypeInt8: - { - dataSize = sizeof(int8_t); - address = static_cast(address) + startIndex; - break; - } - default: - break; - } +PortDataType Signal::getPortDataType() const +{ + return m_portDataType; +} - memcpy(contiguousData, address, dataSize* length); +bool Signal::isConst() const +{ + return m_isConst; } -void Signal::set(unsigned index, uint32_t data) + +SignalDataFormat Signal::getDataFormat() const { - //signed integer function - switch (portType) { - case PortDataTypeUInt32: - { - uint32_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeUInt16: - { - uint16_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - case PortDataTypeUInt8: - { - uint8_t* buffer = static_cast(contiguousData); - buffer[index] = data; - break; - } - default: - break; - } + return m_dataFormat; } -void Signal::setBuffer(const uint32_t* data, const unsigned length, unsigned startIndex) +bool Signal::set(const unsigned& index, const double& data) { - if (isConstPort) return; - unsigned dataSize = 0; - const void* address = data; + if (m_isConst || m_width <= index) { + return false; + } - switch (portType) { - case PortDataTypeUInt32: - { - dataSize = sizeof(uint32_t); - address = data + startIndex; - break; - } - case PortDataTypeUInt16: + // TODO: Implement other PortDataType + switch (m_portDataType) { + case PortDataTypeDouble: { - dataSize = sizeof(uint16_t); - address = data + startIndex; + double* buffer = static_cast(m_bufferPtr); + buffer[index] = data; break; } - case PortDataTypeUInt8: + case PortDataTypeSingle: { - dataSize = sizeof(uint8_t); - address = data + startIndex; + float* buffer = static_cast(m_bufferPtr); + buffer[index] = data; break; } default: + return false; break; } - - memcpy(contiguousData, address, dataSize* length); -} - -void Signal::set(unsigned index, bool data) -{ - bool* buffer = static_cast(contiguousData); - buffer[index] = data; -} - -void Signal::setBuffer(const bool* data, const unsigned length, unsigned startIndex) -{ - if (isConstPort) return; - unsigned dataSize = sizeof(bool); - const void* address = static_cast(data) + startIndex; - - memcpy(contiguousData, address, dataSize* length); + return true; } diff --git a/toolbox/src/base/SimulinkBlockInformation.cpp b/toolbox/src/base/SimulinkBlockInformation.cpp index 38c1060db..f8825d0c8 100644 --- a/toolbox/src/base/SimulinkBlockInformation.cpp +++ b/toolbox/src/base/SimulinkBlockInformation.cpp @@ -11,6 +11,9 @@ SimulinkBlockInformation::SimulinkBlockInformation(SimStruct* S) : simstruct(S) {} +// BLOCK OPTIONS METHODS +// ===================== + bool SimulinkBlockInformation::optionFromKey(const std::string& key, double& option) const { if (key == wbt::BlockOptionPrioritizeOrder) { @@ -21,27 +24,15 @@ bool SimulinkBlockInformation::optionFromKey(const std::string& key, double& opt return false; } -//Parameters methods +// PARAMETERS METHODS +// ================== + bool SimulinkBlockInformation::getStringParameterAtIndex(unsigned parameterIndex, std::string& stringParameter) const { const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); return MxAnyType(blockParam).asString(stringParameter); } -bool SimulinkBlockInformation::getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const -{ - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asAnyStruct(map); -} - - -bool SimulinkBlockInformation::getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const -{ - const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); - return MxAnyType(blockParam).asVectorDouble(vec); -} - - bool SimulinkBlockInformation::getScalarParameterAtIndex(unsigned parameterIndex, double& value) const { const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); @@ -65,7 +56,22 @@ bool SimulinkBlockInformation::getBooleanParameterAtIndex(unsigned parameterInde return MxAnyType(blockParam).asBool(value); } -//Port information methods +bool SimulinkBlockInformation::getStructAtIndex(unsigned parameterIndex, AnyStruct& map) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asAnyStruct(map); +} + + +bool SimulinkBlockInformation::getVectorAtIndex(unsigned parameterIndex, std::vector& vec) const +{ + const mxArray* blockParam = ssGetSFcnParam(simstruct, parameterIndex); + return MxAnyType(blockParam).asVectorDouble(vec); +} + +// PORT INFORMATION SETTERS +// ======================== + bool SimulinkBlockInformation::setNumberOfInputPorts(unsigned numberOfPorts) { return ssSetNumInputPorts(simstruct, numberOfPorts); @@ -104,77 +110,20 @@ bool SimulinkBlockInformation::setOutputPortMatrixSize(unsigned portNumber, int bool SimulinkBlockInformation::setInputPortType(unsigned portNumber, PortDataType portType) { - //for now force Direct feedthrough.. If needed create a separate method ssSetInputPortDirectFeedThrough(simstruct, portNumber, 1); - int matlabDataType = -1; - switch (portType) { - case PortDataTypeDouble: - matlabDataType = SS_DOUBLE; - break; - case PortDataTypeSingle: - matlabDataType = SS_SINGLE; - break; - case PortDataTypeInt8: - matlabDataType = SS_INT8; - break; - case PortDataTypeUInt8: - matlabDataType = SS_UINT8; - break; - case PortDataTypeInt16: - matlabDataType = SS_INT16; - break; - case PortDataTypeUInt16: - matlabDataType = SS_UINT16; - break; - case PortDataTypeInt32: - matlabDataType = SS_INT32; - break; - case PortDataTypeUInt32: - matlabDataType = SS_UINT32; - break; - case PortDataTypeBoolean: - matlabDataType = SS_BOOLEAN; - break; - } - return ssSetInputPortDataType(simstruct, portNumber, matlabDataType); + ssSetInputPortDataType(simstruct, portNumber, mapSimulinkToPortType(portType)); + return true; } bool SimulinkBlockInformation::setOutputPortType(unsigned portNumber, PortDataType portType) { - int matlabDataType = -1; - switch (portType) { - case PortDataTypeDouble: - matlabDataType = SS_DOUBLE; - break; - case PortDataTypeSingle: - matlabDataType = SS_SINGLE; - break; - case PortDataTypeInt8: - matlabDataType = SS_INT8; - break; - case PortDataTypeUInt8: - matlabDataType = SS_UINT8; - break; - case PortDataTypeInt16: - matlabDataType = SS_INT16; - break; - case PortDataTypeUInt16: - matlabDataType = SS_UINT16; - break; - case PortDataTypeInt32: - matlabDataType = SS_INT32; - break; - case PortDataTypeUInt32: - matlabDataType = SS_UINT32; - break; - case PortDataTypeBoolean: - matlabDataType = SS_BOOLEAN; - break; - } - return ssSetOutputPortDataType(simstruct, portNumber, matlabDataType); + ssSetOutputPortDataType(simstruct, portNumber, mapSimulinkToPortType(portType)); + return true; } -//Port data +// PORT INFORMATION GETTERS +// ======================== + unsigned SimulinkBlockInformation::getInputPortWidth(unsigned portNumber) const { return ssGetInputPortWidth(simstruct, portNumber); @@ -185,22 +134,136 @@ unsigned SimulinkBlockInformation::getOutputPortWidth(unsigned portNumber) const return ssGetOutputPortWidth(simstruct, portNumber); } -wbt::Signal SimulinkBlockInformation::getInputPortSignal(unsigned portNumber) const +wbt::Signal SimulinkBlockInformation::getInputPortSignal(unsigned portNumber, int portWidth) const { - Signal signal; - InputPtrsType port = ssGetInputPortSignalPtrs(simstruct, portNumber); - bool isConstPort = true; - signal.initSignalType(PortDataTypeDouble, isConstPort); - signal.setNonContiguousBuffer(port); - return signal; -} + // Read if the signal is contiguous or non-contiguous + boolean_T isContiguous = ssGetInputPortRequiredContiguous(simstruct, portNumber); + SignalDataFormat sigDataFormat = isContiguous ? CONTIGUOUS_ZEROCOPY : NONCONTIGUOUS; + + // Check if the signal is dynamically sized (which means that the dimension + // cannot be read) + bool isDynamicallySized = (ssGetInputPortWidth(simstruct, portNumber) == DYNAMICALLY_SIZED); + + // Note that if the signal is DYNAMICALLY_SIZED (-1), portWidth is necessary + if (isDynamicallySized && portWidth == -1) { + return Signal(); + } + + // Read the width of the signal if it is not provided as input and the signal is not + // dynamically sized + if (!isDynamicallySized && portWidth == -1) { + portWidth = ssGetInputPortWidth(simstruct, portNumber); + } + // Get the data type of the Signal if set (default: double) + DTypeId dataType = ssGetInputPortDataType(simstruct, portNumber); + + switch (sigDataFormat) { + case CONTIGUOUS_ZEROCOPY: { + // Initialize the signal + bool isConstPort = true; + Signal signal(CONTIGUOUS_ZEROCOPY, mapSimulinkToPortType(dataType), isConstPort); + signal.setWidth(portWidth); + // Initialize signal's data + if (!signal.initializeBufferFromContiguousZeroCopy(ssGetInputPortSignal(simstruct, portNumber))) { + return Signal(); + } + return signal; + } + case NONCONTIGUOUS: { + // Initialize the signal + bool isConstPort = true; + Signal signal(NONCONTIGUOUS, mapSimulinkToPortType(dataType), isConstPort); + signal.setWidth(portWidth); + // Initialize signal's data + InputPtrsType port = ssGetInputPortSignalPtrs(simstruct, portNumber); + if (!signal.initializeBufferFromNonContiguous(static_cast(port))) { + return Signal(); + } + return signal; + } + default: + return Signal(); + } +} -wbt::Signal SimulinkBlockInformation::getOutputPortSignal(unsigned portNumber) const +wbt::Signal SimulinkBlockInformation::getOutputPortSignal(unsigned portNumber, int portWidth) const { - Signal signal; + // Check if the signal is dynamically sized (which means that the dimension + // cannot be read) + bool isDynamicallySized = (ssGetOutputPortWidth(simstruct, portNumber) == DYNAMICALLY_SIZED); + + // Note that if the signal is DYNAMICALLY_SIZED (-1), portWidth is necessary + if (isDynamicallySized && portWidth == -1) { + return Signal(); + } + + // Read the width of the signal if it is not provided as input and the signal is not + // dynamically sized + if (!isDynamicallySized && portWidth == -1) { + portWidth = ssGetOutputPortWidth(simstruct, portNumber); + } + + // Get the data type of the Signal if set (default: double) + DTypeId dataType = ssGetOutputPortDataType(simstruct, portNumber); + bool isConstPort = false; - signal.initSignalType(PortDataTypeDouble, isConstPort); - signal.setContiguousBuffer(ssGetOutputPortSignal(simstruct, portNumber)); + Signal signal(CONTIGUOUS_ZEROCOPY, mapSimulinkToPortType(dataType), isConstPort); + signal.setWidth(portWidth); + + if (!signal.initializeBufferFromContiguousZeroCopy(ssGetOutputPortSignal(simstruct, portNumber))) { + return Signal(); + } + return signal; } + +PortDataType SimulinkBlockInformation::mapSimulinkToPortType(const DTypeId& typeId) const +{ + switch (typeId) { + case SS_DOUBLE: + return PortDataTypeDouble; + case SS_SINGLE: + return PortDataTypeSingle; + case SS_INT8: + return PortDataTypeInt8; + case SS_UINT8: + return PortDataTypeUInt8; + case SS_INT16: + return PortDataTypeInt16; + case SS_UINT16: + return PortDataTypeUInt16; + case SS_INT32: + return PortDataTypeInt32; + case SS_UINT32: + return PortDataTypeUInt32; + case SS_BOOLEAN: + return PortDataTypeBoolean; + default: + return PortDataTypeDouble; + } +} + +DTypeId SimulinkBlockInformation::mapPortTypeToSimulink(const PortDataType& dataType) const +{ + switch (dataType) { + case PortDataTypeDouble: + return SS_DOUBLE; + case PortDataTypeSingle: + return SS_SINGLE; + case PortDataTypeInt8: + return SS_INT8; + case PortDataTypeUInt8: + return SS_UINT8; + case PortDataTypeInt16: + return SS_INT16; + case PortDataTypeUInt16: + return SS_UINT16; + case PortDataTypeInt32: + return SS_INT32; + case PortDataTypeUInt32: + return SS_UINT32; + case PortDataTypeBoolean: + return SS_BOOLEAN; + } +} diff --git a/toolbox/src/base/toolbox.cpp b/toolbox/src/base/toolbox.cpp index ba9c86cb5..74468baa9 100644 --- a/toolbox/src/base/toolbox.cpp +++ b/toolbox/src/base/toolbox.cpp @@ -177,6 +177,15 @@ static void mdlInitializeSizes(SimStruct* S) bool ok = block->configureSizeAndPorts(&blockInfo); catchLogMessages(ok, S, "\n[" + std::string(__func__) + "]"); + for (auto i = 0; i < ssGetNumInputPorts(S); ++i) { + // Set explicitly the inputs port to be SS_NOT_REUSABLE_AND_GLOBAL (which actually + // is already the default value). Since the toolbox supports contiguous input signals, + // this option should not be changed. + ssSetInputPortOptimOpts(S, i, SS_NOT_REUSABLE_AND_GLOBAL); + // Set input signals to be allocated in a contiguous memory storage + ssSetInputPortRequiredContiguous(S, i, true); + } + ssSetNumSampleTimes(S, 1); ssSetSimStateCompliance(S, USE_CUSTOM_SIM_STATE); //?? From 930b9e4e49eaa2c711fc885a7972242e941f35fa Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 08:03:41 +0000 Subject: [PATCH 70/92] Fixed the parsing of the gravity vector --- toolbox/src/base/WBBlock.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/toolbox/src/base/WBBlock.cpp b/toolbox/src/base/WBBlock.cpp index d4acfbb3f..82cf92a05 100644 --- a/toolbox/src/base/WBBlock.cpp +++ b/toolbox/src/base/WBBlock.cpp @@ -131,8 +131,8 @@ bool WBBlock::getWBToolboxParameters(Configuration& config, const BlockInformati return false; } std::array gravityArray; - for (auto i : gravityVector) { - gravityArray[i] = i; + for (auto i = 0; i < 3; ++i) { + gravityArray[i] = gravityVector[i]; } // Create the ToolboxConfig object From c9239060b3d2fe220b5b391e0613531e09d2ef6f Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 08:07:01 +0000 Subject: [PATCH 71/92] Moved the update of robot state into WBBlock This method avoids code duplication in all the child classes --- toolbox/include/base/WBBlock.h | 5 ++ toolbox/src/base/WBBlock.cpp | 102 +++++++++++++++++++++++++++++++++ 2 files changed, 107 insertions(+) diff --git a/toolbox/include/base/WBBlock.h b/toolbox/include/base/WBBlock.h index 227795a1c..bfd289f96 100644 --- a/toolbox/include/base/WBBlock.h +++ b/toolbox/include/base/WBBlock.h @@ -12,6 +12,7 @@ namespace wbt { class WBBlock; + class Signal; class Configuration; class BlockInformation; class RobotInterface; @@ -70,6 +71,10 @@ class wbt::WBBlock : public wbt::Block bool getWBToolboxParameters(Configuration& config, const BlockInformation* blockInfo); const std::shared_ptr getRobotInterface(); const Configuration& getConfiguration(); + bool setRobotState(const wbt::Signal* basePose, + const wbt::Signal* jointsPos, + const wbt::Signal* baseVelocity, + const wbt::Signal* jointsVelocity); public: WBBlock() = default; diff --git a/toolbox/src/base/WBBlock.cpp b/toolbox/src/base/WBBlock.cpp index 82cf92a05..c067c80e1 100644 --- a/toolbox/src/base/WBBlock.cpp +++ b/toolbox/src/base/WBBlock.cpp @@ -5,9 +5,13 @@ #include "ToolboxSingleton.h" #include "Configuration.h" #include "RobotInterface.h" +#include "Signal.h" #include "AnyType.h" +#include #include #include +#include "iDynTree/KinDynComputations.h" +#include #include #include #include @@ -28,6 +32,104 @@ iDynTreeRobotState::iDynTreeRobotState(const unsigned& dofs, const std::array Matrix4dSimulink; + + // Base pose + // --------- + + if (basePose) { + // Get the buffer + double* buffer = basePose->getBuffer(); + if (!buffer) { + Log::getSingleton().error("Failed to read the base pose from input port."); + return false; + } + // Fill the data + fromEigen(robotState.m_world_T_base, Matrix4dSimulink(buffer)); + } + + // Joints position + // --------------- + + if (jointsPos) { + // Get the buffer + double* buffer = jointsPos->getBuffer(); + if (!buffer) { + Log::getSingleton().error("Failed to read joints positions from input port."); + return false; + } + // Fill the data + for (auto i = 0; i < jointsPos->getWidth(); ++i) { + robotState.m_jointsPosition.setVal(i, buffer[i]); + } + + } + + // Base Velocity + // ------------- + + if (baseVelocity) { + // Get the buffer + double* buffer = baseVelocity->getBuffer(); + if (!buffer) { + Log::getSingleton().error("Failed to read the base velocity from input port."); + return false; + } + // Fill the data + robotState.m_baseVelocity = Twist(LinVelocity(buffer, 3), + AngVelocity(buffer+3, 3)); + } + + // Joints velocity + // --------------- + + if (jointsVelocity) { + // Get the buffer + double* buffer = jointsVelocity->getBuffer(); + if (!buffer) { + Log::getSingleton().error("Failed to read joints velocities from input port."); + return false; + } + // Fill the data + for (auto i = 0; i < jointsVelocity->getWidth(); ++i) { + robotState.m_jointsVelocity.setVal(i, buffer[i]); + } + } + + // UPDATE THE IDYNTREE ROBOT STATE WITH NEW DATA + // ============================================= + + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + + bool ok = model->setRobotState(robotState.m_world_T_base, + robotState.m_jointsPosition, + robotState.m_baseVelocity, + robotState.m_jointsVelocity, + robotState.m_gravity); + + if (!ok) { + Log::getSingleton().error("Failed to set the iDynTree robot state."); + return false; + } + + return true; +} + unsigned WBBlock::numberOfParameters() { return 2; } bool WBBlock::getWBToolboxParameters(Configuration& config, const BlockInformation* blockInfo) From fc50b088f15d3c93187559c0b5c12a188a3c6ed7 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 08:14:26 +0000 Subject: [PATCH 72/92] Updated all blocks to the new Signal class and WBBlock::setRobotState --- toolbox/include/SetReferences.h | 2 +- toolbox/src/CentroidalMomentum.cpp | 49 +++------- toolbox/src/DotJNu.cpp | 49 +++------- toolbox/src/ForwardKinematics.cpp | 41 ++++----- toolbox/src/GetMeasurement.cpp | 4 +- toolbox/src/InverseDynamics.cpp | 90 +++++++++---------- toolbox/src/Jacobian.cpp | 38 +++----- toolbox/src/MassMatrix.cpp | 37 +++----- .../src/MinimumJerkTrajectoryGenerator.cpp | 13 ++- toolbox/src/ModelPartitioner.cpp | 10 +-- toolbox/src/SetReferences.cpp | 43 +++++---- toolbox/src/YarpWrite.cpp | 2 +- 12 files changed, 152 insertions(+), 226 deletions(-) diff --git a/toolbox/include/SetReferences.h b/toolbox/include/SetReferences.h index 74b5c4b19..9ec5a385d 100644 --- a/toolbox/include/SetReferences.h +++ b/toolbox/include/SetReferences.h @@ -13,7 +13,7 @@ class wbt::SetReferences : public wbt::WBBlock private: std::vector m_controlModes; bool m_resetControlMode; - static void rad2deg(std::vector& v); + static const std::vector rad2deg(const double* buffer, const unsigned width); public: static const std::string ClassName; diff --git a/toolbox/src/CentroidalMomentum.cpp b/toolbox/src/CentroidalMomentum.cpp index 58484cb9e..126105c9c 100644 --- a/toolbox/src/CentroidalMomentum.cpp +++ b/toolbox/src/CentroidalMomentum.cpp @@ -8,7 +8,6 @@ #include #include #include -#include using namespace wbt; @@ -99,10 +98,6 @@ bool CentroidalMomentum::terminate(const BlockInformation* blockInfo) bool CentroidalMomentum::output(const BlockInformation* blockInfo) { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - const auto& model = getRobotInterface()->getKinDynComputations(); if (!model) { @@ -110,41 +105,23 @@ bool CentroidalMomentum::output(const BlockInformation* blockInfo) return false; } - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== - - unsigned signalWidth; + // GET THE SIGNALS POPULATE THE ROBOT STATE + // ======================================== - // Base pose Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Base velocity + Signal jointsPosSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); - double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); - robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), - AngVelocity(m_baseVelocityBuffer+3, 3)); - - // Joints velocity Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); - robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + + bool ok = setRobotState(&basePoseSig, + &jointsPosSig, + &baseVelocitySignal, + &jointsVelocitySignal); + + if (!ok) { + Log::getSingleton().error("Failed to set the robot state."); + return false; + } // OUTPUT // ====== diff --git a/toolbox/src/DotJNu.cpp b/toolbox/src/DotJNu.cpp index c6fcd7c2a..8beab3e06 100644 --- a/toolbox/src/DotJNu.cpp +++ b/toolbox/src/DotJNu.cpp @@ -7,7 +7,6 @@ #include #include #include -#include using namespace wbt; @@ -139,10 +138,6 @@ bool DotJNu::terminate(const BlockInformation* blockInfo) bool DotJNu::output(const BlockInformation* blockInfo) { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - const auto& model = getRobotInterface()->getKinDynComputations(); if (!model) { @@ -150,41 +145,23 @@ bool DotJNu::output(const BlockInformation* blockInfo) return false; } - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== - - unsigned signalWidth; + // GET THE SIGNALS POPULATE THE ROBOT STATE + // ======================================== - // Base pose Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Base velocity + Signal jointsPosSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); - double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); - robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), - AngVelocity(m_baseVelocityBuffer+3, 3)); - - // Joints velocity Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); - robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + + bool ok = setRobotState(&basePoseSig, + &jointsPosSig, + &baseVelocitySignal, + &jointsVelocitySignal); + + if (!ok) { + Log::getSingleton().error("Failed to set the robot state."); + return false; + } // OUTPUT // ====== diff --git a/toolbox/src/ForwardKinematics.cpp b/toolbox/src/ForwardKinematics.cpp index a34f5c72b..aca145cac 100644 --- a/toolbox/src/ForwardKinematics.cpp +++ b/toolbox/src/ForwardKinematics.cpp @@ -126,7 +126,6 @@ bool ForwardKinematics::terminate(const BlockInformation* blockInfo) bool ForwardKinematics::output(const BlockInformation* blockInfo) { - using namespace iDynTree; using namespace Eigen; typedef Matrix Matrix4dSimulink; typedef Matrix Matrix4diDynTree; @@ -138,31 +137,23 @@ bool ForwardKinematics::output(const BlockInformation* blockInfo) return false; } - // Get the signals and convert them to iDynTree objects - // ==================================================== + // GET THE SIGNALS POPULATE THE ROBOT STATE + // ======================================== - unsigned signalWidth; - - // Base pose Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Update the robot status - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); - - // Output + Signal jointsPosSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + + bool ok = setRobotState(&basePoseSig, + &jointsPosSig, + nullptr, + nullptr); + + if (!ok) { + Log::getSingleton().error("Failed to set the robot state."); + return false; + } + + // OUTPUT // ====== iDynTree::Transform world_H_frame; @@ -180,7 +171,7 @@ bool ForwardKinematics::output(const BlockInformation* blockInfo) // Allocate objects for row-major -> col-major conversion Map world_H_frame_RowMajor = toEigen(world_H_frame.asHomogeneousTransform()); - Map world_H_frame_ColMajor((double*)output.getContiguousBuffer(), + Map world_H_frame_ColMajor(output.getBuffer(), 4, 4); // Forward the buffer to Simulink transforming it to ColMajor diff --git a/toolbox/src/GetMeasurement.cpp b/toolbox/src/GetMeasurement.cpp index a245105c6..e95e31dad 100644 --- a/toolbox/src/GetMeasurement.cpp +++ b/toolbox/src/GetMeasurement.cpp @@ -16,9 +16,9 @@ const std::string GetMeasurement::ClassName = "GetMeasurement"; void GetMeasurement::deg2rad(std::vector& v) { - const double deg2rad = M_PI / 180.0; + const double Deg2Rad = M_PI / 180.0; for (auto& element : v) { - element *= deg2rad; + element *= Deg2Rad; } } diff --git a/toolbox/src/InverseDynamics.cpp b/toolbox/src/InverseDynamics.cpp index 514c96d2b..49b3e8386 100644 --- a/toolbox/src/InverseDynamics.cpp +++ b/toolbox/src/InverseDynamics.cpp @@ -5,10 +5,8 @@ #include "Signal.h" #include "RobotInterface.h" #include -#include #include #include -#include using namespace wbt; @@ -130,70 +128,64 @@ bool InverseDynamics::terminate(const BlockInformation* blockInfo) bool InverseDynamics::output(const BlockInformation* blockInfo) { - using namespace iDynTree; - using namespace Eigen; - typedef Matrix Matrix4dSimulink; - - const auto& model = getRobotInterface()->getKinDynComputations(); - - if (!model) { - Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); - return false; - } - - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== + // GET THE SIGNALS POPULATE THE ROBOT STATE + // ======================================== - unsigned signalWidth; - - // Base pose Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // Base velocity + Signal jointsPosSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); Signal baseVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_VEL); - double* m_baseVelocityBuffer = baseVelocitySignal.getStdVector(signalWidth).data(); - robotState.m_baseVelocity = Twist(LinVelocity(m_baseVelocityBuffer, 3), - AngVelocity(m_baseVelocityBuffer+3, 3)); - - // Joints velocity Signal jointsVelocitySignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_VEL); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_VEL); - robotState.m_jointsVelocity.fillBuffer(jointsVelocitySignal.getStdVector(signalWidth).data()); + + bool ok = setRobotState(&basePoseSig, + &jointsPosSig, + &baseVelocitySignal, + &jointsVelocitySignal); + + if (!ok) { + Log::getSingleton().error("Failed to set the robot state."); + return false; + } // Base acceleration + // ----------------- + Signal baseAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_BASE_ACC); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_ACC); - m_baseAcceleration->fillBuffer(baseAccelerationSignal.getStdVector(signalWidth).data()); + double* bufBaseAcc = baseAccelerationSignal.getBuffer(); + if (!bufBaseAcc) { + Log::getSingleton().error("Failed to read data from input port."); + return false; + } + for (auto i = 0; i < baseAccelerationSignal.getWidth(); ++i) { + m_baseAcceleration->setVal(i, bufBaseAcc[i]); + } // Joints acceleration - Signal jointsAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_ACC); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINT_ACC); - m_jointsAcceleration->fillBuffer(jointsAccelerationSignal.getStdVector(signalWidth).data()); + // ------------------- - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + Signal jointsAccelerationSignal = blockInfo->getInputPortSignal(INPUT_IDX_JOINT_ACC); + double* bufJointsAcc = jointsAccelerationSignal.getBuffer(); + if (!bufJointsAcc) { + Log::getSingleton().error("Failed to read data from input port."); + return false; + } + for (auto i = 0; i < jointsAccelerationSignal.getWidth(); ++i) { + m_jointsAcceleration->setVal(i, bufJointsAcc[i]); + } // OUTPUT // ====== + const auto& model = getRobotInterface()->getKinDynComputations(); + + if (!model) { + Log::getSingleton().error("Failed to retrieve the KinDynComputations object."); + return false; + } + // Calculate the inverse dynamics (assuming zero external forces) model->inverseDynamics(*m_baseAcceleration, *m_jointsAcceleration, - LinkNetExternalWrenches(model->getNrOfLinks()), // TODO + iDynTree::LinkNetExternalWrenches(model->getNrOfLinks()), *m_torques); // Forward the output to Simulink diff --git a/toolbox/src/Jacobian.cpp b/toolbox/src/Jacobian.cpp index 901a0a822..c7574974c 100644 --- a/toolbox/src/Jacobian.cpp +++ b/toolbox/src/Jacobian.cpp @@ -139,9 +139,7 @@ bool Jacobian::terminate(const BlockInformation* blockInfo) bool Jacobian::output(const BlockInformation* blockInfo) { - using namespace iDynTree; using namespace Eigen; - typedef Matrix Matrix4dSimulink; typedef Matrix MatrixXdSimulink; typedef Matrix MatrixXdiDynTree; @@ -152,31 +150,21 @@ bool Jacobian::output(const BlockInformation* blockInfo) return false; } - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== + // GET THE SIGNALS POPULATE THE ROBOT STATE + // ======================================== - unsigned signalWidth; - - // Base pose Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); + Signal jointsPosSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - // TODO: what about the other inputs of setRobotState? + bool ok = setRobotState(&basePoseSig, + &jointsPosSig, + nullptr, + nullptr); - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + if (!ok) { + Log::getSingleton().error("Failed to set the robot state."); + return false; + } // OUTPUT // ====== @@ -184,7 +172,7 @@ bool Jacobian::output(const BlockInformation* blockInfo) iDynTree::Transform world_H_frame; // Compute the jacobian - bool ok = false; + ok = false; if (!m_frameIsCoM) { world_H_frame = model->getWorldTransform(m_frameIndex); ok = model->getFrameFreeFloatingJacobian(m_frameIndex, *m_jacobian); @@ -203,7 +191,7 @@ bool Jacobian::output(const BlockInformation* blockInfo) // Allocate objects for row-major -> col-major conversion Map jacobianRowMajor = toEigen(*m_jacobian); - Map jacobianColMajor((double*)output.getContiguousBuffer(), + Map jacobianColMajor(output.getBuffer(), 6, 6 + dofs); // Forward the buffer to Simulink transforming it to ColMajor diff --git a/toolbox/src/MassMatrix.cpp b/toolbox/src/MassMatrix.cpp index a14a9f78c..6a6aa50fc 100644 --- a/toolbox/src/MassMatrix.cpp +++ b/toolbox/src/MassMatrix.cpp @@ -96,7 +96,6 @@ bool MassMatrix::output(const BlockInformation* blockInfo) { using namespace Eigen; using namespace iDynTree; - typedef Matrix Matrix4dSimulink; typedef Matrix MatrixXdSimulink; typedef Matrix MatrixXdiDynTree; @@ -107,29 +106,21 @@ bool MassMatrix::output(const BlockInformation* blockInfo) return false; } - // GET THE SIGNALS AND CONVERT THEM TO IDYNTREE OBJECTS - // ==================================================== + // GET THE SIGNALS POPULATE THE ROBOT STATE + // ======================================== - unsigned signalWidth; - - // Base pose Signal basePoseSig = blockInfo->getInputPortSignal(INPUT_IDX_BASE_POSE); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_BASE_POSE); - fromEigen(robotState.m_world_T_base, - Matrix4dSimulink(basePoseSig.getStdVector(signalWidth).data())); - - // Joints position - Signal jointsPositionSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); - signalWidth = blockInfo->getInputPortWidth(INPUT_IDX_JOINTCONF); - robotState.m_jointsPosition.fillBuffer(jointsPositionSig.getStdVector(signalWidth).data()); - - // UPDATE THE ROBOT STATUS - // ======================= - model->setRobotState(robotState.m_world_T_base, - robotState.m_jointsPosition, - robotState.m_baseVelocity, - robotState.m_jointsVelocity, - robotState.m_gravity); + Signal jointsPosSig = blockInfo->getInputPortSignal(INPUT_IDX_JOINTCONF); + + bool ok = setRobotState(&basePoseSig, + &jointsPosSig, + nullptr, + nullptr); + + if (!ok) { + Log::getSingleton().error("Failed to set the robot state."); + return false; + } // OUTPUT // ====== @@ -143,7 +134,7 @@ bool MassMatrix::output(const BlockInformation* blockInfo) // Allocate objects for row-major -> col-major conversion Map massMatrixRowMajor = toEigen(*m_massMatrix); - Map massMatrixColMajor((double*)output.getContiguousBuffer(), + Map massMatrixColMajor(output.getBuffer(), 6 + dofs, 6 + dofs); // Forward the buffer to Simulink transforming it to ColMajor diff --git a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp index 6c7e82e36..05aa56527 100644 --- a/toolbox/src/MinimumJerkTrajectoryGenerator.cpp +++ b/toolbox/src/MinimumJerkTrajectoryGenerator.cpp @@ -154,8 +154,8 @@ bool MinimumJerkTrajectoryGenerator::initialize(const BlockInformation* blockInf m_outputSecondDerivativeIndex = outputFirstDerivative ? 2 : 1; } - double sampleTime; - double settlingTime; + double sampleTime = 0; + double settlingTime = 0; ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_SAMPLE_TIME, sampleTime); ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_SETTLING_TIME, settlingTime); @@ -190,7 +190,7 @@ bool MinimumJerkTrajectoryGenerator::output(const BlockInformation* blockInfo) unsigned portIndex = 1; if (m_explicitInitialValue) portIndex++; Signal externalTimePort = blockInfo->getInputPortSignal(portIndex); - double externalTime = externalTimePort.get(0).doubleData(); + double externalTime = externalTimePort.get(0); if (std::abs(m_previousSettlingTime - externalTime) > 1e-5) { m_previousSettlingTime = externalTime; @@ -204,14 +204,13 @@ bool MinimumJerkTrajectoryGenerator::output(const BlockInformation* blockInfo) if (m_firstRun) { m_firstRun = false; - Signal initialValues; unsigned portIndex = 0; if (m_explicitInitialValue) { portIndex = 1; } - initialValues = blockInfo->getInputPortSignal(portIndex); + Signal initialValues = blockInfo->getInputPortSignal(portIndex); for (unsigned i = 0; i < blockInfo->getInputPortWidth(portIndex); ++i) { - (*m_initialValues)[i] = initialValues.get(i).doubleData(); + (*m_initialValues)[i] = initialValues.get(i); } m_generator->init(*m_initialValues); } @@ -219,7 +218,7 @@ bool MinimumJerkTrajectoryGenerator::output(const BlockInformation* blockInfo) Signal references = blockInfo->getInputPortSignal(0); for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - (*m_reference)[i] = references.get(i).doubleData(); + (*m_reference)[i] = references.get(i); } m_generator->computeNextValues(*m_reference); diff --git a/toolbox/src/ModelPartitioner.cpp b/toolbox/src/ModelPartitioner.cpp index e987604f8..21f872c9c 100644 --- a/toolbox/src/ModelPartitioner.cpp +++ b/toolbox/src/ModelPartitioner.cpp @@ -168,10 +168,8 @@ bool ModelPartitioner::terminate(const BlockInformation* blockInfo) bool ModelPartitioner::output(const BlockInformation* blockInfo) { - Signal dofsSignal; - if (m_yarp2WBI) { - dofsSignal = blockInfo->getInputPortSignal(0); + Signal dofsSignal = blockInfo->getInputPortSignal(0); for (unsigned ithJoint = 0; ithJoint < getConfiguration().getNumberOfDoFs(); ++ithJoint) { const std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; @@ -183,11 +181,11 @@ bool ModelPartitioner::output(const BlockInformation* blockInfo) // Get the data to forward Signal ithOutput = blockInfo->getOutputPortSignal(controlBoardOfJoint); - ithOutput.set(contrJointIdxCB, dofsSignal.get(ithJoint).doubleData()); + ithOutput.set(contrJointIdxCB, dofsSignal.get(ithJoint)); } } else { - dofsSignal = blockInfo->getOutputPortSignal(0); + Signal dofsSignal = blockInfo->getOutputPortSignal(0); for (unsigned ithJoint = 0; ithJoint < getConfiguration().getNumberOfDoFs(); ++ithJoint) { const std::string ithJointName = getConfiguration().getControlledJoints()[ithJoint]; @@ -199,7 +197,7 @@ bool ModelPartitioner::output(const BlockInformation* blockInfo) // Get the data to forward const Signal ithInput = blockInfo->getInputPortSignal(controlBoardOfJoint); - dofsSignal.set(ithJoint, ithInput.get(contrJointIdxCB).doubleData()); + dofsSignal.set(ithJoint, ithInput.get(contrJointIdxCB)); } } return true; diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 05317332e..5aca71d0a 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -17,12 +17,17 @@ SetReferences::SetReferences() : m_resetControlMode(true) {} -void SetReferences::rad2deg(std::vector& v) +const std::vector SetReferences::rad2deg(const double* buffer, const unsigned width) { - const double rad2deg = 180.0 / M_PI; - for (auto& element : v) { - element *= rad2deg; + const double Rad2Deg = 180.0 / M_PI; + + std::vector vectorDeg(width); + + for (auto i = 0; i < width; ++i) { + vectorDeg[i] = buffer[i] * Rad2Deg; } + + return vectorDeg; } unsigned SetReferences::numberOfParameters() @@ -125,7 +130,7 @@ bool SetReferences::initialize(const BlockInformation* blockInfo) return false; } // TODO: Set this parameter from the mask - std::vector speedInitalization(dofs, 10.0); + std::vector speedInitalization(dofs, 50.0); // Set the references if (!interface->setRefSpeeds(speedInitalization.data())) { Log::getSingleton().error("Failed to initialize speed references."); @@ -214,7 +219,12 @@ bool SetReferences::output(const BlockInformation* blockInfo) // Get the signal Signal references = blockInfo->getInputPortSignal(0); unsigned signalWidth = blockInfo->getInputPortWidth(0); - std::vector referencesVector = references.getStdVector(signalWidth); + + double* bufferReferences = references.getBuffer(); + if (!bufferReferences) { + Log::getSingleton().error("Failed to get the buffer containing references."); + return false; + } bool ok = false; // TODO: here only the first element is checked @@ -231,9 +241,9 @@ bool SetReferences::output(const BlockInformation* blockInfo) return false; } // Convert from rad to deg - rad2deg(referencesVector); + auto referencesDeg = rad2deg(bufferReferences, signalWidth); // Set the references - ok = interface->positionMove(referencesVector.data()); + ok = interface->positionMove(referencesDeg.data()); break; } case VOCAB_CM_POSITION_DIRECT: { @@ -244,9 +254,9 @@ bool SetReferences::output(const BlockInformation* blockInfo) return false; } // Convert from rad to deg - rad2deg(referencesVector); + auto referencesDeg = rad2deg(bufferReferences, signalWidth); // Set the references - ok = interface->setPositions(referencesVector.data()); + ok = interface->setPositions(referencesDeg.data()); break; } case VOCAB_CM_VELOCITY: { @@ -257,9 +267,9 @@ bool SetReferences::output(const BlockInformation* blockInfo) return false; } // Convert from rad to deg - rad2deg(referencesVector); + auto referencesDeg = rad2deg(bufferReferences, signalWidth); // Set the references - ok = interface->velocityMove(referencesVector.data()); + ok = interface->velocityMove(referencesDeg.data()); break; } case VOCAB_CM_TORQUE: { @@ -269,7 +279,8 @@ bool SetReferences::output(const BlockInformation* blockInfo) Log::getSingleton().error("Failed to get ITorqueControl interface."); return false; } - ok = interface->setRefTorques(referencesVector.data()); + // Set the references + ok = interface->setRefTorques(bufferReferences); break; } case VOCAB_CM_PWM: { @@ -279,7 +290,8 @@ bool SetReferences::output(const BlockInformation* blockInfo) Log::getSingleton().error("Failed to get IPWMControl interface."); return false; } - ok = interface->setRefDutyCycles(referencesVector.data()); + // Set the references + ok = interface->setRefDutyCycles(bufferReferences); break; } case VOCAB_CM_CURRENT: { @@ -289,7 +301,8 @@ bool SetReferences::output(const BlockInformation* blockInfo) Log::getSingleton().error("Failed to get ICurrentControl interface."); return false; } - ok = interface->setRefCurrents(referencesVector.data()); + // Set the references + ok = interface->setRefCurrents(bufferReferences); break; } } diff --git a/toolbox/src/YarpWrite.cpp b/toolbox/src/YarpWrite.cpp index 5c59fd035..bb445a405 100644 --- a/toolbox/src/YarpWrite.cpp +++ b/toolbox/src/YarpWrite.cpp @@ -143,7 +143,7 @@ bool YarpWrite::output(const BlockInformation* blockInfo) Signal signal = blockInfo->getInputPortSignal(0); for (unsigned i = 0; i < blockInfo->getInputPortWidth(0); ++i) { - outputVector[i] = signal.get(i).doubleData(); + outputVector[i] = signal.get(i); } m_port->write(); From b922c549f47b9f7d5cf88dbbdb5f4a090a0c61f9 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 15:32:00 +0000 Subject: [PATCH 73/92] New SetReferences mask param to set the reference speed (Position mode) The YARP iPositionControl interface needs to find the reference speed initialized in order to produce the wanted trajectory. Before this commit, this value was hardcoded, --- toolbox/include/SetReferences.h | 1 + toolbox/src/SetReferences.cpp | 13 ++++++++++--- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/toolbox/include/SetReferences.h b/toolbox/include/SetReferences.h index 9ec5a385d..16e2eba7a 100644 --- a/toolbox/include/SetReferences.h +++ b/toolbox/include/SetReferences.h @@ -13,6 +13,7 @@ class wbt::SetReferences : public wbt::WBBlock private: std::vector m_controlModes; bool m_resetControlMode; + double m_refSpeed; static const std::vector rad2deg(const double* buffer, const unsigned width); public: diff --git a/toolbox/src/SetReferences.cpp b/toolbox/src/SetReferences.cpp index 5aca71d0a..e8681fc33 100644 --- a/toolbox/src/SetReferences.cpp +++ b/toolbox/src/SetReferences.cpp @@ -15,6 +15,7 @@ const std::string SetReferences::ClassName = "SetReferences"; SetReferences::SetReferences() : m_resetControlMode(true) +, m_refSpeed(0) {} const std::vector SetReferences::rad2deg(const double* buffer, const unsigned width) @@ -32,7 +33,7 @@ const std::vector SetReferences::rad2deg(const double* buffer, const uns unsigned SetReferences::numberOfParameters() { - return WBBlock::numberOfParameters() + 1; + return WBBlock::numberOfParameters() + 2; } bool SetReferences::configureSizeAndPorts(BlockInformation* blockInfo) @@ -90,6 +91,13 @@ bool SetReferences::initialize(const BlockInformation* blockInfo) return false; } + // Reading the refSpeed + if (!blockInfo->getScalarParameterAtIndex(WBBlock::numberOfParameters() + 2, + m_refSpeed)) { + Log::getSingleton().error("Could not read reference speed parameter."); + return false; + } + // Initialize the std::vectors const unsigned dofs = getConfiguration().getNumberOfDoFs(); m_controlModes.assign(dofs, VOCAB_CM_UNKNOWN); @@ -129,8 +137,7 @@ bool SetReferences::initialize(const BlockInformation* blockInfo) Log::getSingleton().error("Failed to get IPositionControl interface."); return false; } - // TODO: Set this parameter from the mask - std::vector speedInitalization(dofs, 50.0); + std::vector speedInitalization(dofs, m_refSpeed); // Set the references if (!interface->setRefSpeeds(speedInitalization.data())) { Log::getSingleton().error("Failed to initialize speed references."); From 7ca1c9c5d51041aac3395ad9949a54b482c81949 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 29 Nov 2017 12:21:35 +0000 Subject: [PATCH 74/92] Cleaned CMakeLists.txt and folder structure, updated library - The library is now exported only in R2014B_SLX format - Removed yarpWholeBodyInterface - Use default FindMatlab.cmake (cmake > 3.3) and Eigen3Config.cmake --- CMakeLists.txt | 10 +- cmake/FindEigen3.cmake | 90 - cmake/FindMatlab.cmake | 1467 ------ toolbox/CMakeLists.txt | 88 +- toolbox/WBToolboxLibrary.mdl | 4383 ----------------- toolbox/WBToolboxLibrary.slx | Bin 38548 -> 0 bytes .../+WBToolbox/BlockInitialization.m | 0 .../+WBToolbox/Mask2WBToolboxConfig.m | 0 toolbox/{ => matlab}/+WBToolbox/PID.m | 0 .../{ => matlab}/+WBToolbox/WBTPIDConfig.m | 0 .../{ => matlab}/+WBToolbox/WBToolboxConfig.m | 0 .../+WBToolbox/WBToolboxConfig2Mask.m | 0 toolbox/{ => matlab}/export_library.m | 28 +- .../library}/WBToolboxLibrary_repository.mdl | 2709 +++++----- .../library/exported/WBToolboxLibrary.slx | Bin 0 -> 535297 bytes .../setupForMatlabDebug.m.in} | 0 toolbox/matlab/slblocks.m | 8 + .../startup_wbitoolbox.m.in} | 0 toolbox/slblocks.m | 54 - 19 files changed, 1301 insertions(+), 7536 deletions(-) delete mode 100644 cmake/FindEigen3.cmake delete mode 100644 cmake/FindMatlab.cmake delete mode 100644 toolbox/WBToolboxLibrary.mdl delete mode 100644 toolbox/WBToolboxLibrary.slx rename toolbox/{ => matlab}/+WBToolbox/BlockInitialization.m (100%) rename toolbox/{ => matlab}/+WBToolbox/Mask2WBToolboxConfig.m (100%) rename toolbox/{ => matlab}/+WBToolbox/PID.m (100%) rename toolbox/{ => matlab}/+WBToolbox/WBTPIDConfig.m (100%) rename toolbox/{ => matlab}/+WBToolbox/WBToolboxConfig.m (100%) rename toolbox/{ => matlab}/+WBToolbox/WBToolboxConfig2Mask.m (100%) rename toolbox/{ => matlab}/export_library.m (56%) rename toolbox/{ => matlab/library}/WBToolboxLibrary_repository.mdl (74%) create mode 100644 toolbox/matlab/library/exported/WBToolboxLibrary.slx rename toolbox/{.setupForMatlabDebug.m.in => matlab/setupForMatlabDebug.m.in} (100%) create mode 100644 toolbox/matlab/slblocks.m rename toolbox/{.startup_wbitoolbox.m.in => matlab/startup_wbitoolbox.m.in} (100%) delete mode 100644 toolbox/slblocks.m diff --git a/CMakeLists.txt b/CMakeLists.txt index 034310442..7b99e7077 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,11 +1,13 @@ -# Copyright (C) 2013-2015 Instituto Italiano di Tecnologia -# Author: Jorhabib Eljaik, Francesco Romano +# Copyright (C) 2013-2017 iCub Facility - Istituto Italiano di Tecnologia +# Author: Jorhabib Eljaik, Francesco Romano, Diego Ferigo # CopyPolicy: Released under the terms of the GNU GPL v2.0. -cmake_minimum_required(VERSION 2.8.11) - +cmake_minimum_required(VERSION 3.3) project(WB-Toolbox) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + find_package(YCM REQUIRED) include(YCMDefaultDirs) diff --git a/cmake/FindEigen3.cmake b/cmake/FindEigen3.cmake deleted file mode 100644 index 82846c3ad..000000000 --- a/cmake/FindEigen3.cmake +++ /dev/null @@ -1,90 +0,0 @@ - -# - Try to find Eigen3 lib -# -# This module supports requiring a minimum version, e.g. you can do -# find_package(Eigen3 3.1.2) -# to require version 3.1.2 or newer of Eigen3. -# -# Once done this will define -# -# EIGEN3_FOUND - system has eigen lib with correct version -# EIGEN3_INCLUDE_DIR - the eigen include directory -# EIGEN3_VERSION - eigen version -# -# This module reads hints about search locations from -# the following enviroment variables: -# -# EIGEN3_ROOT -# EIGEN3_ROOT_DIR - -# Copyright (c) 2006, 2007 Montel Laurent, -# Copyright (c) 2008, 2009 Gael Guennebaud, -# Copyright (c) 2009 Benoit Jacob -# Redistribution and use is allowed according to the terms of the 2-clause BSD license. - -if(NOT Eigen3_FIND_VERSION) - if(NOT Eigen3_FIND_VERSION_MAJOR) - set(Eigen3_FIND_VERSION_MAJOR 2) - endif(NOT Eigen3_FIND_VERSION_MAJOR) - if(NOT Eigen3_FIND_VERSION_MINOR) - set(Eigen3_FIND_VERSION_MINOR 91) - endif(NOT Eigen3_FIND_VERSION_MINOR) - if(NOT Eigen3_FIND_VERSION_PATCH) - set(Eigen3_FIND_VERSION_PATCH 0) - endif(NOT Eigen3_FIND_VERSION_PATCH) - - set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") -endif(NOT Eigen3_FIND_VERSION) - -macro(_eigen3_check_version) - file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) - - string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") - set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") - set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") - set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") - - set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) - if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) - set(EIGEN3_VERSION_OK FALSE) - else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) - set(EIGEN3_VERSION_OK TRUE) - endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) - - if(NOT EIGEN3_VERSION_OK) - - message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " - "but at least version ${Eigen3_FIND_VERSION} is required") - endif(NOT EIGEN3_VERSION_OK) -endmacro(_eigen3_check_version) - -if (EIGEN3_INCLUDE_DIR) - - # in cache already - _eigen3_check_version() - set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) - -else (EIGEN3_INCLUDE_DIR) - - find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library - HINTS - ENV EIGEN3_ROOT - ENV EIGEN3_ROOT_DIR - PATHS - ${CMAKE_INSTALL_PREFIX}/include - ${KDE4_INCLUDE_DIR} - PATH_SUFFIXES eigen3 eigen - ) - - if(EIGEN3_INCLUDE_DIR) - _eigen3_check_version() - endif(EIGEN3_INCLUDE_DIR) - - include(FindPackageHandleStandardArgs) - find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) - - mark_as_advanced(EIGEN3_INCLUDE_DIR) - -endif(EIGEN3_INCLUDE_DIR) diff --git a/cmake/FindMatlab.cmake b/cmake/FindMatlab.cmake deleted file mode 100644 index 373aa38a3..000000000 --- a/cmake/FindMatlab.cmake +++ /dev/null @@ -1,1467 +0,0 @@ -#.rst: -# FindMatlab -# ---------- -# -# Finds Matlab installations and provides Matlab tools and libraries to cmake. -# -# This package first intention is to find the libraries associated with Matlab -# in order to be able to build Matlab extensions (mex files). It can also be -# used: -# -# * run specific commands in Matlab -# * declare Matlab unit test -# * retrieve various information from Matlab (mex extensions, versions and -# release queries, ...) -# -# The module supports the following components: -# -# * ``MX_LIBRARY`` and ``ENG_LIBRARY`` respectively the MX and ENG libraries of -# Matlab -# * ``MAIN_PROGRAM`` the Matlab binary program. -# -# .. note:: -# -# The version given to the :command:`find_package` directive is the Matlab -# **version**, which should not be confused with the Matlab *release* name -# (eg. `R2014`). -# The :command:`matlab_get_version_from_release_name` and -# :command:`matlab_get_release_name_from_version` allow a mapping -# from the release name to the version. -# -# The variable :variable:`Matlab_ROOT_DIR` may be specified in order to give -# the path of the desired Matlab version. Otherwise, the behaviour is platform -# specific: -# -# * Windows: The installed versions of Matlab are retrieved from the -# Windows registry -# * OS X: The installed versions of Matlab are given by the MATLAB -# paths in ``/Application``. If no such application is found, it falls back -# to the one that might be accessible from the PATH. -# * Unix: The desired Matlab should be accessible from the PATH. -# -# Additional information is provided when :variable:`MATLAB_FIND_DEBUG` is set. -# When a Matlab binary is found automatically and the ``MATLAB_VERSION`` -# is not given, the version is queried from Matlab directly. -# On Windows, it can make a window running Matlab appear. -# -# The mapping of the release names and the version of Matlab is performed by -# defining pairs (name, version). The variable -# :variable:`MATLAB_ADDITIONAL_VERSIONS` may be provided before the call to -# the :command:`find_package` in order to handle additional versions. -# -# A Matlab scripts can be added to the set of tests using the -# :command:`matlab_add_unit_test`. By default, the Matlab unit test framework -# will be used (>= 2013a) to run this script, but regular ``.m`` files -# returning an exit code can be used as well (0 indicating a success). -# -# Module Input Variables -# ^^^^^^^^^^^^^^^^^^^^^^ -# -# Users or projects may set the following variables to configure the module -# behaviour: -# -# :variable:`Matlab_ROOT_DIR` -# the root of the Matlab installation. -# :variable:`MATLAB_FIND_DEBUG` -# outputs debug information -# :variable:`MATLAB_ADDITIONAL_VERSIONS` -# additional versions of Matlab for the automatic retrieval of the installed -# versions. -# -# Variables defined by the module -# ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -# -# Result variables -# """""""""""""""" -# -# ``Matlab_FOUND`` -# ``TRUE`` if the Matlab installation is found, ``FALSE`` -# otherwise. All variable below are defined if Matlab is found. -# ``Matlab_ROOT_DIR`` -# the final root of the Matlab installation determined by the FindMatlab -# module. -# ``Matlab_MAIN_PROGRAM`` -# the Matlab binary program. Available only if the component ``MAIN_PROGRAM`` -# is given in the :command:`find_package` directive. -# ``Matlab_INCLUDE_DIRS`` -# the path of the Matlab libraries headers -# ``Matlab_MEX_LIBRARY`` -# library for mex, always available. -# ``Matlab_MX_LIBRARY`` -# mx library of Matlab (arrays). Available only if the component -# ``MX_LIBRARY`` has been requested. -# ``Matlab_ENG_LIBRARY`` -# Matlab engine library. Available only if the component ``ENG_LIBRARY`` -# is requested. -# ``Matlab_LIBRARIES`` -# the whole set of libraries of Matlab -# ``Matlab_MEX_COMPILER`` -# the mex compiler of Matlab. Currently not used. -# Available only if the component ``MEX_COMPILER`` is asked -# -# Cached variables -# """""""""""""""" -# -# ``Matlab_MEX_EXTENSION`` -# the extension of the mex files for the current platform (given by Matlab). -# ``Matlab_ROOT_DIR`` -# the location of the root of the Matlab installation found. If this value -# is changed by the user, the result variables are recomputed. -# -# Provided macros -# ^^^^^^^^^^^^^^^ -# -# :command:`matlab_get_version_from_release_name` -# returns the version from the release name -# :command:`matlab_get_release_name_from_version` -# returns the release name from the Matlab version -# -# Provided functions -# ^^^^^^^^^^^^^^^^^^ -# -# :command:`matlab_add_mex` -# adds a target compiling a MEX file. -# :command:`matlab_add_unit_test` -# adds a Matlab unit test file as a test to the project. -# :command:`matlab_extract_all_installed_versions_from_registry` -# parses the registry for all Matlab versions. Available on Windows only. -# The part of the registry parsed is dependent on the host processor -# :command:`matlab_get_all_valid_matlab_roots_from_registry` -# returns all the possible Matlab paths, according to a previously -# given list. Only the existing/accessible paths are kept. This is mainly -# useful for the searching all possible Matlab installation. -# :command:`matlab_get_mex_suffix` -# returns the suffix to be used for the mex files -# (platform/architecture dependant) -# :command:`matlab_get_version_from_matlab_run` -# returns the version of Matlab, given the full directory of the Matlab -# program. -# -# -# Known issues -# ^^^^^^^^^^^^ -# -# **Symbol clash in a MEX target** -# By default, every symbols inside a MEX -# file defined with the command :command:`matlab_add_mex` have hidden -# visibility, except for the entry point. This is the default behaviour of -# the MEX compiler, which lowers the risk of symbol collision between the -# libraries shipped with Matlab, and the libraries to which the MEX file is -# linking to. This is also the default on Windows platforms. -# -# However, this is not sufficient in certain case, where for instance your -# MEX file is linking against libraries that are already loaded by Matlab, -# even if those libraries have different SONAMES. -# A possible solution is to hide the symbols of the libraries to which the -# MEX target is linking to. This can be achieved in GNU GCC compilers with -# the linker option ``-Wl,--exclude-libs,ALL``. -# -# **Tests using GPU resources** -# in case your MEX file is using the GPU and -# in order to be able to run unit tests on this MEX file, the GPU resources -# should be properly released by Matlab. A possible solution is to make -# Matlab aware of the use of the GPU resources in the session, which can be -# performed by a command such as ``D = gpuDevice()`` at the beginning of -# the test script (or via a fixture). -# -# -# Reference -# ^^^^^^^^^ -# -# .. variable:: Matlab_ROOT_DIR -# -# The root folder of the Matlab installation. If set before the call to -# :command:`find_package`, the module will look for the components in that -# path. If not set, then an automatic search of Matlab -# will be performed. If set, it should point to a valid version of Matlab. -# -# .. variable:: MATLAB_FIND_DEBUG -# -# If set, the lookup of Matlab and the intermediate configuration steps are -# outputted to the console. -# -# .. variable:: MATLAB_ADDITIONAL_VERSIONS -# -# If set, specifies additional versions of Matlab that may be looked for. -# The variable should be a list of strings, organised by pairs of release -# name and versions, such as follows:: -# -# set(MATLAB_ADDITIONAL_VERSIONS -# "release_name1=corresponding_version1" -# "release_name2=corresponding_version2" -# ... -# ) -# -# Example:: -# -# set(MATLAB_ADDITIONAL_VERSIONS -# "R2013b=8.2" -# "R2013a=8.1" -# "R2012b=8.0") -# -# The order of entries in this list matters when several versions of -# Matlab are installed. The priority is set according to the ordering in -# this list. - -#============================================================================= -# Copyright 2014-2015 Raffi Enficiaud, Max Planck Society -# -# Distributed under the OSI-approved BSD License (the "License"); -# see accompanying file Copyright.txt for details. -# -# This software is distributed WITHOUT ANY WARRANTY; without even the -# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. -# See the License for more information. -#============================================================================= -# (To distribute this file outside of CMake, substitute the full -# License text for the above reference.) - -set(_FindMatlab_SELF_DIR "${CMAKE_CURRENT_LIST_DIR}") - -include(FindPackageHandleStandardArgs) -include(CheckCXXCompilerFlag) - - -# The currently supported versions. Other version can be added by the user by -# providing MATLAB_ADDITIONAL_VERSIONS -if(NOT MATLAB_ADDITIONAL_VERSIONS) - set(MATLAB_ADDITIONAL_VERSIONS) -endif() - -set(MATLAB_VERSIONS_MAPPING - "R2016b=9.1" - "R2016a=9.0" - "R2015b=8.6" - "R2015a=8.5" - "R2014b=8.4" - "R2014a=8.3" - "R2013b=8.2" - "R2013a=8.1" - "R2012b=8.0" - "R2012a=7.14" - - "R2011b=7.13" - "R2011a=7.12" - "R2010b=7.11" - - ${MATLAB_ADDITIONAL_VERSIONS} - ) - - -# temporary folder for all Matlab runs -set(_matlab_temporary_folder ${CMAKE_BINARY_DIR}/Matlab) - -if(NOT EXISTS "${_matlab_temporary_folder}") - file(MAKE_DIRECTORY "${_matlab_temporary_folder}") -endif() - -#.rst: -# .. command:: matlab_get_version_from_release_name -# -# Returns the version of Matlab (17.58) from a release name (R2017k) -macro (matlab_get_version_from_release_name release_name version_name) - - string(REGEX MATCHALL "${release_name}=([0-9]+\\.?[0-9]*)" _matched ${MATLAB_VERSIONS_MAPPING}) - - set(${version_name} "") - if(NOT _matched STREQUAL "") - set(${version_name} ${CMAKE_MATCH_1}) - else() - message(WARNING "The release name ${release_name} is not registered") - endif() - unset(_matched) - -endmacro() - - - - - -#.rst: -# .. command:: matlab_get_release_name_from_version -# -# Returns the release name (R2017k) from the version of Matlab (17.58) -macro (matlab_get_release_name_from_version version release_name) - - set(${release_name} "") - foreach(_var IN LISTS MATLAB_VERSIONS_MAPPING) - string(REGEX MATCHALL "(.+)=${version}" _matched ${_var}) - if(NOT _matched STREQUAL "") - set(${release_name} ${CMAKE_MATCH_1}) - break() - endif() - endforeach(_var) - - unset(_var) - unset(_matched) - if(${release_name} STREQUAL "") - message(WARNING "The version ${version} is not registered") - endif() - -endmacro() - - - - - -# extracts all the supported release names (R2017k...) of Matlab -# internal use -macro(matlab_get_supported_releases list_releases) - set(${list_releases}) - foreach(_var IN LISTS MATLAB_VERSIONS_MAPPING) - string(REGEX MATCHALL "(.+)=([0-9]+\\.?[0-9]*)" _matched ${_var}) - if(NOT _matched STREQUAL "") - list(APPEND ${list_releases} ${CMAKE_MATCH_1}) - endif() - unset(_matched) - unset(CMAKE_MATCH_1) - endforeach(_var) - unset(_var) -endmacro() - - - -# extracts all the supported versions of Matlab -# internal use -macro(matlab_get_supported_versions list_versions) - set(${list_versions}) - foreach(_var IN LISTS MATLAB_VERSIONS_MAPPING) - string(REGEX MATCHALL "(.+)=([0-9]+\\.?[0-9]*)" _matched ${_var}) - if(NOT _matched STREQUAL "") - list(APPEND ${list_versions} ${CMAKE_MATCH_2}) - endif() - unset(_matched) - unset(CMAKE_MATCH_1) - endforeach(_var) - unset(_var) -endmacro() - - -#.rst: -# .. command:: matlab_extract_all_installed_versions_from_registry -# -# This function parses the registry and founds the Matlab versions that are -# installed. The found versions are returned in `matlab_versions`. -# Set `win64` to `TRUE` if the 64 bit version of Matlab should be looked for -# The returned list contains all versions under -# ``HKLM\\SOFTWARE\\Mathworks\\MATLAB`` or an empty list in case an error -# occurred (or nothing found). -# -# .. note:: -# -# Only the versions are provided. No check is made over the existence of the -# installation referenced in the registry, -# -function(matlab_extract_all_installed_versions_from_registry win64 matlab_versions) - - if(NOT CMAKE_HOST_WIN32) - message(FATAL_ERROR "This macro can only be called by a windows host (call to reg.exe") - endif() - - - if(${win64} AND ${CMAKE_HOST_SYSTEM_PROCESSOR} MATCHES "64") - set(APPEND_REG "/reg:64") - else() - set(APPEND_REG "/reg:32") - endif() - - # /reg:64 should be added on 64 bits capable OSs in order to enable the - # redirection of 64 bits applications - execute_process( - COMMAND reg query HKEY_LOCAL_MACHINE\\SOFTWARE\\Mathworks\\MATLAB /f * /k ${APPEND_REG} - RESULT_VARIABLE resultMatlab - OUTPUT_VARIABLE varMatlab - ERROR_VARIABLE errMatlab - INPUT_FILE NUL - ) - - - set(matlabs_from_registry) - if(${resultMatlab} EQUAL 0) - - string( - REGEX MATCHALL "MATLAB\\\\([0-9]+(\\.[0-9]+)?)" - matlab_versions_regex ${varMatlab}) - - foreach(match IN LISTS matlab_versions_regex) - string( - REGEX MATCH "MATLAB\\\\(([0-9]+)(\\.([0-9]+))?)" - current_match ${match}) - - set(_matlab_current_version ${CMAKE_MATCH_1}) - set(current_matlab_version_major ${CMAKE_MATCH_2}) - set(current_matlab_version_minor ${CMAKE_MATCH_4}) - if(NOT current_matlab_version_minor) - set(current_matlab_version_minor "0") - endif() - - list(APPEND matlabs_from_registry ${_matlab_current_version}) - unset(_matlab_current_version) - endforeach(match) - - endif() - - if(matlabs_from_registry) - list(REMOVE_DUPLICATES matlabs_from_registry) - list(SORT matlabs_from_registry) - list(REVERSE matlabs_from_registry) - endif() - - set(${matlab_versions} ${matlabs_from_registry} PARENT_SCOPE) - -endfunction() - - - -# (internal) -macro(extract_matlab_versions_from_registry_brute_force matlab_versions) - # get the supported versions - set(matlab_supported_versions) - matlab_get_supported_versions(matlab_supported_versions) - - - # this is a manual population of the versions we want to look for - # this can be done as is, but preferably with the call to - # matlab_get_supported_versions and variable - - # populating the versions we want to look for - # set(matlab_supported_versions) - - # # Matlab 7 - # set(matlab_major 7) - # foreach(current_matlab_minor RANGE 4 20) - # list(APPEND matlab_supported_versions "${matlab_major}.${current_matlab_minor}") - # endforeach(current_matlab_minor) - - # # Matlab 8 - # set(matlab_major 8) - # foreach(current_matlab_minor RANGE 0 5) - # list(APPEND matlab_supported_versions "${matlab_major}.${current_matlab_minor}") - # endforeach(current_matlab_minor) - - # # taking into account the possible additional versions provided by the user - # if(DEFINED MATLAB_ADDITIONAL_VERSIONS) - # list(APPEND matlab_supported_versions MATLAB_ADDITIONAL_VERSIONS) - # endif() - - - # we order from more recent to older - if(matlab_supported_versions) - list(REMOVE_DUPLICATES matlab_supported_versions) - list(SORT matlab_supported_versions) - list(REVERSE matlab_supported_versions) - endif() - - - set(${matlab_versions} ${matlab_supported_versions}) - - -endmacro() - - - - -#.rst: -# .. command:: matlab_get_all_valid_matlab_roots_from_registry -# -# Populates the Matlab root with valid versions of Matlab. -# The returned matlab_roots is organized in pairs -# ``(version_number,matlab_root_path)``. -# -# :: -# -# matlab_get_all_valid_matlab_roots_from_registry( -# matlab_versions -# matlab_roots) -# -# ``matlab_versions`` -# the versions of each of the Matlab installations -# ``matlab_roots`` -# the location of each of the Matlab installations -function(matlab_get_all_valid_matlab_roots_from_registry matlab_versions matlab_roots) - - # The matlab_versions comes either from - # extract_matlab_versions_from_registry_brute_force or - # matlab_extract_all_installed_versions_from_registry. - - - set(_matlab_roots_list ) - foreach(_matlab_current_version ${matlab_versions}) - get_filename_component( - current_MATLAB_ROOT - "[HKEY_LOCAL_MACHINE\\SOFTWARE\\MathWorks\\MATLAB\\${_matlab_current_version};MATLABROOT]" - ABSOLUTE) - - if(EXISTS ${current_MATLAB_ROOT}) - list(APPEND _matlab_roots_list ${_matlab_current_version} ${current_MATLAB_ROOT}) - endif() - - endforeach(_matlab_current_version) - unset(_matlab_current_version) - set(${matlab_roots} ${_matlab_roots_list} PARENT_SCOPE) - unset(_matlab_roots_list) -endfunction() - -#.rst: -# .. command:: matlab_get_mex_suffix -# -# Returns the extension of the mex files (the suffixes). -# This function should not be called before the appropriate Matlab root has -# been found. -# -# :: -# -# matlab_get_mex_suffix( -# matlab_root -# mex_suffix) -# -# ``matlab_root`` -# the root of the Matlab installation -# ``mex_suffix`` -# the variable name in which the suffix will be returned. -function(matlab_get_mex_suffix matlab_root mex_suffix) - - # todo setup the extension properly. Currently I do not know if this is - # sufficient for all win32 distributions. - # there is also CMAKE_EXECUTABLE_SUFFIX that could be tweaked - set(mexext_suffix "") - if(WIN32) - list(APPEND mexext_suffix ".bat") - endif() - - # we first try without suffix, since cmake does not understand a list with - # one empty string element - find_program( - Matlab_MEXEXTENSIONS_PROG - NAMES mexext - PATHS ${matlab_root}/bin - DOC "Matlab MEX extension provider" - NO_DEFAULT_PATH - ) - - foreach(current_mexext_suffix IN LISTS mexext_suffix) - if(NOT DEFINED Matlab_MEXEXTENSIONS_PROG OR NOT Matlab_MEXEXTENSIONS_PROG) - # this call should populate the cache automatically - find_program( - Matlab_MEXEXTENSIONS_PROG - "mexext${current_mexext_suffix}" - PATHS ${matlab_root}/bin - DOC "Matlab MEX extension provider" - NO_DEFAULT_PATH - ) - endif() - endforeach(current_mexext_suffix) - - - # the program has been found? - if((NOT Matlab_MEXEXTENSIONS_PROG) OR (NOT EXISTS ${Matlab_MEXEXTENSIONS_PROG})) - if(MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Cannot found mexext program. Matlab root is ${matlab_root}") - endif() - unset(Matlab_MEXEXTENSIONS_PROG CACHE) - return() - endif() - - set(_matlab_mex_extension) - - set(devnull) - if(UNIX) - set(devnull INPUT_FILE /dev/null) - elseif(WIN32) - set(devnull INPUT_FILE NUL) - endif() - - execute_process( - COMMAND ${Matlab_MEXEXTENSIONS_PROG} - OUTPUT_VARIABLE _matlab_mex_extension - ERROR_VARIABLE _matlab_mex_extension_error - ${devnull}) - string(STRIP ${_matlab_mex_extension} _matlab_mex_extension) - - unset(Matlab_MEXEXTENSIONS_PROG CACHE) - set(${mex_suffix} ${_matlab_mex_extension} PARENT_SCOPE) -endfunction() - - - - -#.rst: -# .. command:: matlab_get_version_from_matlab_run -# -# This function runs Matlab program specified on arguments and extracts its -# version. -# -# :: -# -# matlab_get_version_from_matlab_run( -# matlab_binary_path -# matlab_list_versions) -# -# ``matlab_binary_path`` -# the location of the `matlab` binary executable -# ``matlab_list_versions`` -# the version extracted from Matlab -function(matlab_get_version_from_matlab_run matlab_binary_program matlab_list_versions) - - set(${matlab_list_versions} "" PARENT_SCOPE) - - - if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Determining the version of Matlab from ${matlab_binary_program}") - endif() - - if(EXISTS "${_matlab_temporary_folder}/matlabVersionLog.cmaketmp") - if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Removing previous ${_matlab_temporary_folder}/matlabVersionLog.cmaketmp file") - endif() - file(REMOVE "${_matlab_temporary_folder}/matlabVersionLog.cmaketmp") - endif() - - - # the log file is needed since on windows the command executes in a new - # window and it is not possible to get back the answer of Matlab - # the -wait command is needed on windows, otherwise the call returns - # immediately after the program launches itself. - if(WIN32) - set(_matlab_additional_commands "-wait") - endif() - - set(devnull) - if(UNIX) - set(devnull INPUT_FILE /dev/null) - elseif(WIN32) - set(devnull INPUT_FILE NUL) - endif() - - # timeout set to 30 seconds, in case it does not start - # note as said before OUTPUT_VARIABLE cannot be used in a platform - # independent manner however, not setting it would flush the output of Matlab - # in the current console (unix variant) - execute_process( - COMMAND "${matlab_binary_program}" -nosplash -nojvm ${_matlab_additional_commands} -logfile "matlabVersionLog.cmaketmp" -nodesktop -nodisplay -r "version, exit" - OUTPUT_VARIABLE _matlab_version_from_cmd_dummy - RESULT_VARIABLE _matlab_result_version_call - ERROR_VARIABLE _matlab_result_version_call_error - TIMEOUT 30 - WORKING_DIRECTORY "${_matlab_temporary_folder}" - ${devnull} - ) - - - if(${_matlab_result_version_call}) - if(MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Unable to determine the version of Matlab. Matlab call returned with error ${_matlab_result_version_call}.") - endif() - return() - elseif(NOT EXISTS "${_matlab_temporary_folder}/matlabVersionLog.cmaketmp") - if(MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Unable to determine the version of Matlab. The log file does not exist.") - endif() - return() - endif() - - # if successful, read back the log - file(READ "${_matlab_temporary_folder}/matlabVersionLog.cmaketmp" _matlab_version_from_cmd) - file(REMOVE "${_matlab_temporary_folder}/matlabVersionLog.cmaketmp") - - set(index -1) - string(FIND ${_matlab_version_from_cmd} "ans" index) - if(index EQUAL -1) - - if(MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Cannot find the version of Matlab returned by the run.") - endif() - - else() - set(matlab_list_of_all_versions_tmp) - - string(SUBSTRING ${_matlab_version_from_cmd} ${index} -1 substring_ans) - string( - REGEX MATCHALL "ans[\r\n\t ]*=[\r\n\t ]*([0-9]+(\\.[0-9]+)?)" - matlab_versions_regex - ${substring_ans}) - foreach(match IN LISTS matlab_versions_regex) - string( - REGEX MATCH "ans[\r\n\t ]*=[\r\n\t ]*(([0-9]+)(\\.([0-9]+))?)" - current_match ${match}) - - list(APPEND matlab_list_of_all_versions_tmp ${CMAKE_MATCH_1}) - endforeach() - if(matlab_list_of_all_versions_tmp) - list(REMOVE_DUPLICATES matlab_list_of_all_versions_tmp) - endif() - set(${matlab_list_versions} ${matlab_list_of_all_versions_tmp} PARENT_SCOPE) - - endif() - -endfunction() - - -#.rst: -# .. command:: matlab_add_unit_test -# -# Adds a Matlab unit test to the test set of cmake/ctest. -# This command requires the component ``MAIN_PROGRAM``. -# The unit test uses the Matlab unittest framework (default, available -# starting Matlab 2013b+) except if the option ``NO_UNITTEST_FRAMEWORK`` -# is given. -# -# The function expects one Matlab test script file to be given. -# In the case ``NO_UNITTEST_FRAMEWORK`` is given, the unittest script file -# should contain the script to be run, plus an exit command with the exit -# value. This exit value will be passed to the ctest framework (0 success, -# non 0 failure). Additional arguments accepted by :command:`add_test` can be -# passed through ``TEST_ARGS`` (eg. ``CONFIGURATION ...``). -# -# :: -# -# matlab_add_unit_test( -# NAME -# UNITTEST_FILE matlab_file_containing_unittest.m -# [UNITTEST_PRECOMMAND matlab_command_to_run] -# [TIMEOUT timeout] -# [ADDITIONAL_PATH path1 [path2 ...]] -# [MATLAB_ADDITIONAL_STARTUP_OPTIONS option1 [option2 ...]] -# [TEST_ARGS arg1 [arg2 ...]] -# [NO_UNITTEST_FRAMEWORK] -# ) -# -# The function arguments are: -# -# ``NAME`` -# name of the unittest in ctest. -# ``UNITTEST_FILE`` -# the matlab unittest file. Its path will be automatically -# added to the Matlab path. -# ``UNITTEST_PRECOMMAND`` -# Matlab script command to be ran before the file -# containing the test (eg. GPU device initialisation based on CMake -# variables). -# ``TIMEOUT`` -# the test timeout in seconds. Defaults to 180 seconds as the -# Matlab unit test may hang. -# ``ADDITIONAL_PATH`` -# a list of paths to add to the Matlab path prior to -# running the unit test. -# ``MATLAB_ADDITIONAL_STARTUP_OPTIONS`` -# a list of additional option in order -# to run Matlab from the command line. -# ``TEST_ARGS`` -# Additional options provided to the add_test command. These -# options are added to the default options (eg. "CONFIGURATIONS Release") -# ``NO_UNITTEST_FRAMEWORK`` -# when set, indicates that the test should not -# use the unittest framework of Matlab (available for versions >= R2013a). -# -function(matlab_add_unit_test) - - if(NOT Matlab_MAIN_PROGRAM) - message(FATAL_ERROR "[MATLAB] This functionality needs the MAIN_PROGRAM component (not default)") - endif() - - set(options NO_UNITTEST_FRAMEWORK) - set(oneValueArgs NAME UNITTEST_PRECOMMAND UNITTEST_FILE TIMEOUT) - set(multiValueArgs ADDITIONAL_PATH MATLAB_ADDITIONAL_STARTUP_OPTIONS TEST_ARGS) - - set(prefix _matlab_unittest_prefix) - cmake_parse_arguments(${prefix} "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN} ) - - if(NOT ${prefix}_NAME) - message(FATAL_ERROR "[MATLAB] The Matlab test name cannot be empty") - endif() - - add_test(NAME ${${prefix}_NAME} - COMMAND ${CMAKE_COMMAND} - -Dtest_name=${${prefix}_NAME} - -Dadditional_paths=${${prefix}_ADDITIONAL_PATH} - -Dtest_timeout=${${prefix}_TIMEOUT} - -Doutput_directory=${_matlab_temporary_folder} - -DMatlab_PROGRAM=${Matlab_MAIN_PROGRAM} - -Dno_unittest_framework=${${prefix}_NO_UNITTEST_FRAMEWORK} - -DMatlab_ADDITIONNAL_STARTUP_OPTIONS=${${prefix}_MATLAB_ADDITIONAL_STARTUP_OPTIONS} - -Dunittest_file_to_run=${${prefix}_UNITTEST_FILE} - -Dcmd_to_run_before_test=${${prefix}_UNITTEST_PRECOMMAND} - -P ${_FindMatlab_SELF_DIR}/MatlabTestsRedirect.cmake - ${${prefix}_TEST_ARGS} - ${${prefix}_UNPARSED_ARGUMENTS} - ) -endfunction() - - -#.rst: -# .. command:: matlab_add_mex -# -# Adds a Matlab MEX target. -# This commands compiles the given sources with the current tool-chain in -# order to produce a MEX file. The final name of the produced output may be -# specified, as well as additional link libraries, and a documentation entry -# for the MEX file. Remaining arguments of the call are passed to the -# :command:`add_library` command. -# -# :: -# -# matlab_add_mex( -# NAME -# SRC src1 [src2 ...] -# [OUTPUT_NAME output_name] -# [DOCUMENTATION file.txt] -# [LINK_TO target1 target2 ...] -# [...] -# ) -# -# ``NAME`` -# name of the target. -# ``SRC`` -# list of tje source files. -# ``LINK_TO`` -# a list of additional link dependencies. The target links to ``libmex`` -# by default. If ``Matlab_MX_LIBRARY`` is defined, it also -# links to ``libmx``. -# ``OUTPUT_NAME`` -# if given, overrides the default name. The default name is -# the name of the target without any prefix and -# with ``Matlab_MEX_EXTENSION`` suffix. -# ``DOCUMENTATION`` -# if given, the file ``file.txt`` will be considered as -# being the documentation file for the MEX file. This file is copied into -# the same folder without any processing, with the same name as the final -# mex file, and with extension `.m`. In that case, typing ``help `` -# in Matlab prints the documentation contained in this file. -# -# The documentation file is not processed and should be in the following -# format: -# -# :: -# -# % This is the documentation -# function ret = mex_target_output_name(input1) -# -function(matlab_add_mex ) - - if(NOT WIN32) - # we do not need all this on Windows - # pthread options - check_cxx_compiler_flag(-pthread HAS_MINUS_PTHREAD) - # we should use try_compile instead, the link flags are discarded from - # this compiler_flag function. - #check_cxx_compiler_flag(-Wl,--exclude-libs,ALL HAS_SYMBOL_HIDING_CAPABILITY) - - endif() - - set(oneValueArgs NAME DOCUMENTATION OUTPUT_NAME) - set(multiValueArgs LINK_TO SRC) - - set(prefix _matlab_addmex_prefix) - cmake_parse_arguments(${prefix} "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN} ) - - if(NOT ${prefix}_NAME) - message(FATAL_ERROR "[MATLAB] The MEX target name cannot be empty") - endif() - - if(NOT ${prefix}_OUTPUT_NAME) - set(${prefix}_OUTPUT_NAME ${${prefix}_NAME}) - endif() - - add_library(${${prefix}_NAME} - SHARED - ${${prefix}_SRC} - ${${prefix}_DOCUMENTATION} - ${${prefix}_UNPARSED_ARGUMENTS}) - target_include_directories(${${prefix}_NAME} PRIVATE ${Matlab_INCLUDE_DIRS}) - - if(DEFINED Matlab_MX_LIBRARY) - target_link_libraries(${${prefix}_NAME} ${Matlab_MX_LIBRARY}) - endif() - - target_link_libraries(${${prefix}_NAME} ${Matlab_MEX_LIBRARY} ${${prefix}_LINK_TO}) - set_target_properties(${${prefix}_NAME} - PROPERTIES - PREFIX "" - OUTPUT_NAME ${${prefix}_OUTPUT_NAME} - SUFFIX ".${Matlab_MEX_EXTENSION}") - - - # documentation - if(NOT ${${prefix}_DOCUMENTATION} STREQUAL "") - get_target_property(output_name ${${prefix}_NAME} OUTPUT_NAME) - add_custom_command( - TARGET ${${prefix}_NAME} - PRE_BUILD - COMMAND ${CMAKE_COMMAND} -E copy_if_different ${${prefix}_DOCUMENTATION} $/${output_name}.m - COMMENT "Copy ${${prefix}_NAME} documentation file into the output folder" - ) - endif() # documentation - - # entry point in the mex file + taking care of visibility and symbol clashes. - if(WIN32) - set_target_properties(${${prefix}_NAME} - PROPERTIES - DEFINE_SYMBOL "DLL_EXPORT_SYM=__declspec(dllexport)") - else() - - if(HAS_MINUS_PTHREAD AND NOT APPLE) - # Apparently, compiling with -pthread generated the proper link flags - # and some defines at compilation - target_compile_options(${${prefix}_NAME} PRIVATE "-pthread") - endif() - - - # if we do not do that, the symbols linked from eg. boost remain weak and - # then clash with the ones defined in the matlab process. So by default - # the symbols are hidden. - # This also means that for shared libraries (like MEX), the entry point - # should be explicitly declared with default visibility, otherwise Matlab - # cannot find the entry point. - # Note that this is particularly meaningful if the MEX wrapper itself - # contains symbols that are clashing with Matlab (that are compiled in the - # MEX file). In order to propagate the visibility options to the libraries - # to which the MEX file is linked against, the -Wl,--exclude-libs,ALL - # option should also be specified. - - set_target_properties(${${prefix}_NAME} - PROPERTIES - CXX_VISIBILITY_PRESET "hidden" - C_VISIBILITY_PRESET "hidden" - VISIBILITY_INLINES_HIDDEN ON - ) - - # get_target_property( - # _previous_link_flags - # ${${prefix}_NAME} - # LINK_FLAGS) - # if(NOT _previous_link_flags) - # set(_previous_link_flags) - # endif() - - # if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "GNU") - # set_target_properties(${${prefix}_NAME} - # PROPERTIES - # LINK_FLAGS "${_previous_link_flags} -Wl,--exclude-libs,ALL" - # # -Wl,--version-script=${_FindMatlab_SELF_DIR}/MatlabLinuxVisibility.map" - # ) - # elseif("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") - # # in this case, all other symbols become hidden. - # set_target_properties(${${prefix}_NAME} - # PROPERTIES - # LINK_FLAGS "${_previous_link_flags} -Wl,-exported_symbol,_mexFunction" - # #-Wl,-exported_symbols_list,${_FindMatlab_SELF_DIR}/MatlabOSXVisilibity.map" - # ) - # endif() - - - - set_target_properties(${${prefix}_NAME} - PROPERTIES - DEFINE_SYMBOL "DLL_EXPORT_SYM=__attribute__ ((visibility (\"default\")))" - ) - - - endif() - -endfunction() - - -# (internal) -# Used to get the version of matlab, using caching. This basically transforms the -# output of the root list, with possible unknown version, to a version -# -function(_Matlab_get_version_from_root matlab_root matlab_known_version matlab_final_version) - - # if the version is not trivial, we query matlab for that - # we keep track of the location of matlab that induced this version - #if(NOT DEFINED Matlab_PROG_VERSION_STRING_AUTO_DETECT) - # set(Matlab_PROG_VERSION_STRING_AUTO_DETECT "" CACHE INTERNAL "internal matlab location for the discovered version") - #endif() - - if(NOT ${matlab_known_version} STREQUAL "NOTFOUND") - # the version is known, we just return it - set(${matlab_final_version} ${matlab_known_version} PARENT_SCOPE) - set(Matlab_VERSION_STRING_INTERNAL ${matlab_known_version} CACHE INTERNAL "Matlab version (automatically determined)" FORCE) - return() - endif() - - # - set(_matlab_current_program ${Matlab_MAIN_PROGRAM}) - - # do we already have a matlab program? - if(NOT _matlab_current_program) - - set(_find_matlab_options) - if(matlab_root AND EXISTS ${matlab_root}) - set(_find_matlab_options PATHS ${matlab_root} ${matlab_root}/bin NO_DEFAULT_PATH) - endif() - - find_program( - _matlab_current_program - matlab - ${_find_matlab_options} - DOC "Matlab main program" - ) - endif() - - if(NOT _matlab_current_program OR NOT EXISTS ${_matlab_current_program}) - # if not found, clear the dependent variables - if(MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Cannot find the main matlab program under ${matlab_root}") - endif() - set(Matlab_PROG_VERSION_STRING_AUTO_DETECT "" CACHE INTERNAL "internal matlab location for the discovered version" FORCE) - set(Matlab_VERSION_STRING_INTERNAL "" CACHE INTERNAL "internal matlab location for the discovered version" FORCE) - unset(_matlab_current_program) - unset(_matlab_current_program CACHE) - return() - endif() - - # full real path for path comparison - get_filename_component(_matlab_main_real_path_tmp "${_matlab_current_program}" REALPATH) - unset(_matlab_current_program) - unset(_matlab_current_program CACHE) - - # is it the same as the previous one? - if(_matlab_main_real_path_tmp STREQUAL Matlab_PROG_VERSION_STRING_AUTO_DETECT) - set(${matlab_final_version} ${Matlab_VERSION_STRING_INTERNAL} PARENT_SCOPE) - return() - endif() - - # update the location of the program - set(Matlab_PROG_VERSION_STRING_AUTO_DETECT ${_matlab_main_real_path_tmp} CACHE INTERNAL "internal matlab location for the discovered version" FORCE) - - set(matlab_list_of_all_versions) - matlab_get_version_from_matlab_run("${Matlab_PROG_VERSION_STRING_AUTO_DETECT}" matlab_list_of_all_versions) - - list(GET matlab_list_of_all_versions 0 _matlab_version_tmp) - - # set the version into the cache - set(Matlab_VERSION_STRING_INTERNAL ${_matlab_version_tmp} CACHE INTERNAL "Matlab version (automatically determined)" FORCE) - - # warning, just in case several versions found (should not happen) - list(LENGTH matlab_list_of_all_versions list_of_all_versions_length) - if((${list_of_all_versions_length} GREATER 1) AND MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Found several versions, taking the first one (versions found ${matlab_list_of_all_versions})") - endif() - - # return the updated value - set(${matlab_final_version} ${Matlab_VERSION_STRING_INTERNAL} PARENT_SCOPE) - -endfunction() - - - - - - - -# ################################### -# Exploring the possible Matlab_ROOTS - -# this variable will get all Matlab installations found in the current system. -set(_matlab_possible_roots) - - - -if(Matlab_ROOT_DIR) - # if the user specifies a possible root, we keep this one - - if(NOT EXISTS ${Matlab_ROOT_DIR}) - # if Matlab_ROOT_DIR specified but erroneous - if(MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] the specified path for Matlab_ROOT_DIR does not exist (${Matlab_ROOT_DIR})") - endif() - else() - # NOTFOUND indicates the code below to search for the version automatically - if("${Matlab_VERSION_STRING_INTERNAL}" STREQUAL "") - list(APPEND _matlab_possible_roots "NOTFOUND" ${Matlab_ROOT_DIR}) # empty version - else() - list(APPEND _matlab_possible_roots ${Matlab_VERSION_STRING_INTERNAL} ${Matlab_ROOT_DIR}) # cached version - endif() - endif() - - -else() - - # if the user does not specify the possible installation root, we look for - # one installation using the appropriate heuristics - - if(WIN32) - - # On WIN32, we look for Matlab installation in the registry - # if unsuccessful, we look for all known revision and filter the existing - # ones. - - # testing if we are able to extract the needed information from the registry - set(_matlab_versions_from_registry) - matlab_extract_all_installed_versions_from_registry(CMAKE_CL_64 _matlab_versions_from_registry) - - # the returned list is empty, doing the search on all known versions - if(NOT _matlab_versions_from_registry) - - if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Search for Matlab from the registry unsuccessful, testing all supported versions") - endif() - - extract_matlab_versions_from_registry_brute_force(_matlab_versions_from_registry) - endif() - - # filtering the results with the registry keys - matlab_get_all_valid_matlab_roots_from_registry("${_matlab_versions_from_registry}" _matlab_possible_roots) - unset(_matlab_versions_from_registry) - - elseif(APPLE) - - # on mac, we look for the /Application paths - # this corresponds to the behaviour on Windows. On Linux, we do not have - # any other guess. - matlab_get_supported_releases(_matlab_releases) - if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Matlab supported versions ${_matlab_releases}. If more version should be supported " - "the variable MATLAB_ADDITIONAL_VERSIONS can be set according to the documentation") - endif() - - foreach(_matlab_current_release IN LISTS _matlab_releases) - set(_matlab_full_string "/Applications/MATLAB_${_matlab_current_release}.app") - if(EXISTS ${_matlab_full_string}) - set(_matlab_current_version) - matlab_get_version_from_release_name("${_matlab_current_release}" _matlab_current_version) - if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Found version ${_matlab_current_release} (${_matlab_current_version}) in ${_matlab_full_string}") - endif() - list(APPEND _matlab_possible_roots ${_matlab_current_version} ${_matlab_full_string}) - unset(_matlab_current_version) - endif() - - unset(_matlab_full_string) - endforeach(_matlab_current_release) - - unset(_matlab_current_release) - unset(_matlab_releases) - - endif() - -endif() - - - -list(LENGTH _matlab_possible_roots _numbers_of_matlab_roots) -if(_numbers_of_matlab_roots EQUAL 0) - # if we have not found anything, we fall back on the PATH - - - # At this point, we have no other choice than trying to find it from PATH. - # If set by the user, this wont change - find_program( - _matlab_main_tmp - NAMES matlab) - - - if(_matlab_main_tmp) - # we then populate the list of roots, with empty version - if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] matlab found from PATH: ${_matlab_main_tmp}") - endif() - - # resolve symlinks - get_filename_component(_matlab_current_location "${_matlab_main_tmp}" REALPATH) - - # get the directory (the command below has to be run twice) - # this will be the matlab root - get_filename_component(_matlab_current_location "${_matlab_current_location}" DIRECTORY) - get_filename_component(_matlab_current_location "${_matlab_current_location}" DIRECTORY) # Matlab should be in bin - - list(APPEND _matlab_possible_roots "NOTFOUND" ${_matlab_current_location}) - - unset(_matlab_current_location) - - endif() - unset(_matlab_main_tmp CACHE) - -endif() - - - - - -if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Matlab root folders are ${_matlab_possible_roots}") -endif() - - - - - -# take the first possible Matlab root -list(LENGTH _matlab_possible_roots _numbers_of_matlab_roots) -set(Matlab_VERSION_STRING "NOTFOUND") -if(_numbers_of_matlab_roots GREATER 0) - list(GET _matlab_possible_roots 0 Matlab_VERSION_STRING) - list(GET _matlab_possible_roots 1 Matlab_ROOT_DIR) - - # adding a warning in case of ambiguity - if(_numbers_of_matlab_roots GREATER 2 AND MATLAB_FIND_DEBUG) - message(WARNING "[MATLAB] Found several distributions of Matlab. Setting the current version to ${Matlab_VERSION_STRING} (located ${Matlab_ROOT_DIR})." - " If this is not the desired behaviour, provide the -DMatlab_ROOT_DIR=... on the command line") - endif() -endif() - - -# check if the root changed against the previous defined one, if so -# clear all the cached variables -if(DEFINED Matlab_ROOT_DIR_LAST_CACHED) - - if(NOT Matlab_ROOT_DIR_LAST_CACHED STREQUAL Matlab_ROOT_DIR) - set(_Matlab_cached_vars - Matlab_INCLUDE_DIRS - Matlab_MEX_LIBRARY - Matlab_MEX_COMPILER - Matlab_MAIN_PROGRAM - Matlab_MX_LIBRARY - Matlab_ENG_LIBRARY - Matlab_MEX_EXTENSION - - # internal - Matlab_MEXEXTENSIONS_PROG - Matlab_ROOT_DIR_LAST_CACHED - #Matlab_PROG_VERSION_STRING_AUTO_DETECT - Matlab_VERSION_STRING_INTERNAL - ) - foreach(_var IN LISTS _Matlab_cached_vars) - if(DEFINED ${_var}) - unset(${_var} CACHE) - endif() - endforeach() - endif() -endif() - -set(Matlab_ROOT_DIR_LAST_CACHED ${Matlab_ROOT_DIR} CACHE INTERNAL "last Matlab root dir location") -set(Matlab_ROOT_DIR ${Matlab_ROOT_DIR} CACHE PATH "Matlab installation root path" FORCE) - -# Fix the version, in case this one is NOTFOUND -_Matlab_get_version_from_root( - "${Matlab_ROOT_DIR}" - ${Matlab_VERSION_STRING} - Matlab_VERSION_STRING -) - - - - -if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] Current version is ${Matlab_VERSION_STRING} located ${Matlab_ROOT_DIR}") -endif() - - - -if(Matlab_ROOT_DIR) - file(TO_CMAKE_PATH ${Matlab_ROOT_DIR} Matlab_ROOT_DIR) -endif() - -if(CMAKE_SIZEOF_VOID_P EQUAL 4) - set(_matlab_64Build FALSE) -else() - set(_matlab_64Build TRUE) -endif() - -if(APPLE) - set(_matlab_bin_prefix "mac") # i should be for intel - set(_matlab_bin_suffix_32bits "i") - set(_matlab_bin_suffix_64bits "i64") -elseif(UNIX) - set(_matlab_bin_prefix "gln") - set(_matlab_bin_suffix_32bits "x86") - set(_matlab_bin_suffix_64bits "xa64") -else() - set(_matlab_bin_prefix "win") - set(_matlab_bin_suffix_32bits "32") - set(_matlab_bin_suffix_64bits "64") -endif() - - - -set(MATLAB_INCLUDE_DIR_TO_LOOK ${Matlab_ROOT_DIR}/extern/include) -if(_matlab_64Build) - set(_matlab_current_suffix ${_matlab_bin_suffix_64bits}) -else() - set(_matlab_current_suffix ${_matlab_bin_suffix_32bits}) -endif() - -set(Matlab_BINARIES_DIR - ${Matlab_ROOT_DIR}/bin/${_matlab_bin_prefix}${_matlab_current_suffix}) -set(Matlab_EXTERN_LIBRARY_DIR - ${Matlab_ROOT_DIR}/extern/lib/${_matlab_bin_prefix}${_matlab_current_suffix}) - -if(WIN32) - set(_matlab_lib_dir_for_search ${Matlab_EXTERN_LIBRARY_DIR}/microsoft) - set(_matlab_lib_prefix_for_search "lib") -else() - set(_matlab_lib_dir_for_search ${Matlab_BINARIES_DIR}) - set(_matlab_lib_prefix_for_search "lib") -endif() - -unset(_matlab_64Build) - - -if(NOT DEFINED Matlab_MEX_EXTENSION) - set(_matlab_mex_extension "") - matlab_get_mex_suffix("${Matlab_ROOT_DIR}" _matlab_mex_extension) - - # This variable goes to the cache. - set(Matlab_MEX_EXTENSION ${_matlab_mex_extension} CACHE STRING "Extensions for the mex targets (automatically given by Matlab)") - unset(_matlab_mex_extension) -endif() - - -if(MATLAB_FIND_DEBUG) - message(STATUS "[MATLAB] [DEBUG]_matlab_lib_prefix_for_search = ${_matlab_lib_prefix_for_search} | _matlab_lib_dir_for_search = ${_matlab_lib_dir_for_search}") -endif() - - - -# internal -# This small stub around find_library is to prevent any pollution of CMAKE_FIND_LIBRARY_PREFIXES in the global scope. -# This is the function to be used below instead of the find_library directives. -function(_Matlab_find_library _matlab_library_prefix) - set(CMAKE_FIND_LIBRARY_PREFIXES ${CMAKE_FIND_LIBRARY_PREFIXES} ${_matlab_library_prefix}) - find_library(${ARGN}) -endfunction() - - -set(_matlab_required_variables) - - -# the MEX library/header are required -find_path( - Matlab_INCLUDE_DIRS - mex.h - PATHS ${MATLAB_INCLUDE_DIR_TO_LOOK} - NO_DEFAULT_PATH - ) -list(APPEND _matlab_required_variables Matlab_INCLUDE_DIRS) - -_Matlab_find_library( - ${_matlab_lib_prefix_for_search} - Matlab_MEX_LIBRARY - mex - PATHS ${_matlab_lib_dir_for_search} - NO_DEFAULT_PATH -) - - -list(APPEND _matlab_required_variables Matlab_MEX_LIBRARY) - -# the MEX extension is required -list(APPEND _matlab_required_variables Matlab_MEX_EXTENSION) - -# the matlab root is required -list(APPEND _matlab_required_variables Matlab_ROOT_DIR) - - -# component Mex Compiler -list(FIND Matlab_FIND_COMPONENTS MEX_COMPILER _matlab_find_mex_compiler) -if(_matlab_find_mex_compiler GREATER -1) - find_program( - Matlab_MEX_COMPILER - "mex" - PATHS ${Matlab_BINARIES_DIR} - DOC "Matlab MEX compiler" - NO_DEFAULT_PATH - ) - - if(Matlab_MEX_COMPILER) - set(Matlab_MEX_COMPILER_FOUND TRUE) - endif() -endif() -unset(_matlab_find_mex_compiler) - -# component Matlab program -list(FIND Matlab_FIND_COMPONENTS MAIN_PROGRAM _matlab_find_matlab_program) -if(_matlab_find_matlab_program GREATER -1) - - find_program( - Matlab_MAIN_PROGRAM - matlab - PATHS ${Matlab_ROOT_DIR} ${Matlab_ROOT_DIR}/bin - DOC "Matlab main program" - NO_DEFAULT_PATH - ) - - if(Matlab_MAIN_PROGRAM) - set(Matlab_MAIN_PROGRAM_FOUND TRUE) - endif() - -endif() -unset(_matlab_find_matlab_program) - -# Component MX library -list(FIND Matlab_FIND_COMPONENTS MX_LIBRARY _matlab_find_mx) -if(_matlab_find_mx GREATER -1) - _Matlab_find_library( - ${_matlab_lib_prefix_for_search} - Matlab_MX_LIBRARY - mx - PATHS ${_matlab_lib_dir_for_search} - NO_DEFAULT_PATH - ) - - if(Matlab_MX_LIBRARY) - set(Matlab_MX_LIBRARY_FOUND TRUE) - endif() -endif() -unset(_matlab_find_mx) - - -# Component ENG library -list(FIND Matlab_FIND_COMPONENTS ENG_LIBRARY _matlab_find_eng) -if(_matlab_find_eng GREATER -1) - _Matlab_find_library( - ${_matlab_lib_prefix_for_search} - Matlab_ENG_LIBRARY - eng - PATHS ${_matlab_lib_dir_for_search} - NO_DEFAULT_PATH - ) - if(Matlab_ENG_LIBRARY) - set(Matlab_ENG_LIBRARY_FOUND TRUE) - endif() -endif() -unset(_matlab_find_eng) - - - - - -unset(_matlab_lib_dir_for_search) - - -set(Matlab_LIBRARIES ${Matlab_MEX_LIBRARY} ${Matlab_MX_LIBRARY} ${Matlab_ENG_LIBRARY}) - - -find_package_handle_standard_args( - Matlab - FOUND_VAR Matlab_FOUND - REQUIRED_VARS ${_matlab_required_variables} - VERSION_VAR Matlab_VERSION_STRING - HANDLE_COMPONENTS) - -unset(_matlab_required_variables) -unset(_matlab_bin_prefix) -unset(_matlab_bin_suffix_32bits) -unset(_matlab_bin_suffix_64bits) -unset(_matlab_current_suffix) -unset(_matlab_lib_dir_for_search) -unset(_matlab_lib_prefix_for_search) - -if(Matlab_INCLUDE_DIRS AND Matlab_LIBRARIES) - mark_as_advanced( - #Matlab_LIBRARIES - Matlab_MEX_LIBRARY - Matlab_MX_LIBRARY - Matlab_ENG_LIBRARY - Matlab_INCLUDE_DIRS - Matlab_FOUND - #Matlab_ROOT_DIR - #Matlab_VERSION_STRING - Matlab_MAIN_PROGRAM - #Matlab_MEX_EXTENSION - Matlab_MEXEXTENSIONS_PROG - Matlab_MEX_EXTENSION - #Matlab_BINARIES_DIR - ) -endif() diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 007f2d0e5..62cf9590d 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -1,5 +1,5 @@ -# Copyright (C) 2013-2015 Instituto Italiano di Tecnologia -# Author: Jorhabib Eljaik, Francesco Romano +# Copyright (C) 2013-2017 iCub Facility - Istituto Italiano di Tecnologia +# Author: Jorhabib Eljaik, Francesco Romano, Diego Ferigo # CopyPolicy: Released under the terms of the GNU GPL v2.0. find_package(YARP REQUIRED) @@ -14,18 +14,17 @@ set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${YARP_MODULE_PATH}) include(YarpInstallationHelpers) yarp_configure_external_installation(codyco) -find_package(Matlab REQUIRED - MX_LIBRARY - ENG_LIBRARY - MAIN_PROGRAM) +find_package(Matlab REQUIRED MX_LIBRARY + ENG_LIBRARY + MAIN_PROGRAM) if(NOT Matlab_FOUND) message(FATAL_ERROR "Matlab not found") endif() -#### Settings for rpath +# Settings for rpath if(NOT MSVC) - #add the option to enable RPATH + # Add the option to enable RPATH option(WB-TOOLBOX_ENABLE_RPATH "Enable RPATH installation" TRUE) mark_as_advanced(WB-TOOLBOX_ENABLE_RPATH) endif(NOT MSVC) @@ -37,22 +36,8 @@ add_install_rpath_support(BIN_DIRS ${CMAKE_INSTALL_PREFIX}/bin USE_LINK_PATH) find_package(Eigen3 REQUIRED) -find_package(wholeBodyInterface 0.2.5 REQUIRED) -find_package(yarpWholeBodyInterface 0.3.2 REQUIRED) find_package(iDynTree 0.7.2 REQUIRED) -#On new versions of Clang, MATLAB requires C++11. -#I enable it on all Clangs -if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin") - if(${CMAKE_CXX_COMPILER_ID} MATCHES "Clang") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") - if (${CMAKE_GENERATOR} MATCHES "Xcode") - #this should set explictly the option in xcode. Unfortunately it does not work. - set(XCODE_ATTRIBUTE_CLANG_CXX_LANGUAGE_STANDARD "C++11") - endif(${CMAKE_GENERATOR} MATCHES "Xcode") - endif(${CMAKE_CXX_COMPILER_ID} MATCHES "Clang") -endif(${CMAKE_SYSTEM_NAME} MATCHES "Darwin") - include(Utilities) configure_block(BLOCK_NAME "Base" @@ -64,7 +49,7 @@ configure_block(BLOCK_NAME "Base" src/base/Log.cpp src/base/ToolboxSingleton.cpp src/base/factory.cpp - src/base/SimulinkBlockInformation.cpp #this is temp + src/base/SimulinkBlockInformation.cpp src/base/Signal.cpp src/base/Configuration.cpp src/base/RobotInterface.cpp @@ -74,7 +59,7 @@ configure_block(BLOCK_NAME "Base" include/base/WBBlock.h include/base/Log.h include/base/ToolboxSingleton.h - include/base/SimulinkBlockInformation.h #this is temp + include/base/SimulinkBlockInformation.h include/base/Signal.h include/base/Configuration.h include/base/RobotInterface.h @@ -195,8 +180,8 @@ configure_block(BLOCK_NAME "Set Low-Level PIDs" LIST_PREFIX WBT SOURCES src/SetLowLevelPID.cpp HEADERS include/SetLowLevelPID.h) - -configure_block(BLOCK_NAME "Get Estimate" +# +configure_block(BLOCK_NAME "Get Measurement" GROUP "State" LIST_PREFIX WBT SOURCES src/GetMeasurement.cpp @@ -216,10 +201,11 @@ include_directories(include) include_directories(include/base) include_directories(SYSTEM ${Matlab_INCLUDE_DIRS} "${Matlab_ROOT_DIR}/simulink/include") -include_directories(SYSTEM ${YARP_INCLUDE_DIRS} ${yarpWholeBodyInterface_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR}) +include_directories(SYSTEM ${YARP_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR}) -list(APPEND LINKED_LIBRARIES ${YARP_LIBRARIES} ${yarpWholeBodyInterface_LIBRARIES}) +list(APPEND LINKED_LIBRARIES ${YARP_LIBRARIES}) list(APPEND LINKED_LIBRARIES ${iDynTree_LIBRARIES}) + if (WBT_USES_ICUB) list(APPEND LINKED_LIBRARIES ctrlLib) if (${ICUB_USE_IPOPT}) @@ -227,7 +213,7 @@ if (WBT_USES_ICUB) endif() endif() -#Adding files used for the generation of the dynamic library +# Adding files used for the generation of the dynamic library matlab_add_mex( NAME WBToolbox SRC ${ALL_HEADERS} ${ALL_SOURCES} @@ -236,46 +222,40 @@ matlab_add_mex( # Link with MxAnyType library # TODO: this will become an external project sooner or later -target_link_libraries(WBToolbox PUBLIC MxAnyType) +target_link_libraries(WBToolbox MxAnyType) # Link with ClockServer library add_subdirectory(autogenerated/) -target_link_libraries(WBToolbox PUBLIC ClockServer) - -# Remote Inverse Kinematics requires C++11 -if (CMAKE_VERSION VERSION_LESS "3.1") - if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" OR - CMAKE_CXX_COMPILER_ID STREQUAL "Clang") - target_compile_options(WBToolbox PUBLIC "-std=c++11") - endif() -else() - set(CXX_STANDARD_REQUIRED ON) - set_property(TARGET WBToolbox PROPERTY CXX_STANDARD 11) -endif() +target_link_libraries(WBToolbox ClockServer) install(TARGETS WBToolbox DESTINATION ${CMAKE_INSTALL_PREFIX}/mex) -## if you export the mdl / slx library, remeber to call this command in matlab before saving it -## set_param(gcs, 'EnableLBRepository','on'); - # The following line is to properly configure the installation script of the toolbox -configure_file(${CMAKE_CURRENT_SOURCE_DIR}/.startup_wbitoolbox.m.in ${CMAKE_BINARY_DIR}/startup_wbitoolbox.m) -configure_file(${CMAKE_CURRENT_SOURCE_DIR}/.setupForMatlabDebug.m.in ${CMAKE_BINARY_DIR}/setupForMatlabDebug.m) +configure_file(${CMAKE_CURRENT_SOURCE_DIR}/matlab/startup_wbitoolbox.m.in + ${CMAKE_BINARY_DIR}/startup_wbitoolbox.m) # Custom script to generate the library to be committed on the repository # This target is excluded from the normal build and must be called explicitly by the # developer who modifies the library -add_custom_target(export_libraries ${Matlab_MAIN_PROGRAM} -nosplash -r export_library WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}) +add_custom_target(export_libraries ${Matlab_MAIN_PROGRAM} -nosplash -nodesktop -r export_library WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/matlab) set_target_properties(export_libraries PROPERTIES EXCLUDE_FROM_DEFAULT_BUILD 1) # Install configuration files install(FILES ${CMAKE_BINARY_DIR}/startup_wbitoolbox.m DESTINATION ${WB-TOOLBOX_SHARE_DIR}) -install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/slblocks.m DESTINATION ${WB-TOOLBOX_SHARE_DIR}) +install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/matlab/slblocks.m DESTINATION ${WB-TOOLBOX_SHARE_DIR}) + +# Install the package folder +install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/matlab/+WBToolbox + DESTINATION ${WB-TOOLBOX_SHARE_DIR}) + #if MAJOR >= 2014 && MINOR >= b # Note: We had issues with Matlab 2014b and .mdl models. # But this issue seems to have been disappeared in 2015b. We have to check if we need to enable this if again -if (${Matlab_VERSION_STRING} GREATER "8.3") - install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/WBToolboxLibrary.slx DESTINATION ${WB-TOOLBOX_SHARE_DIR}) -else() - install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/WBToolboxLibrary.mdl DESTINATION ${WB-TOOLBOX_SHARE_DIR}) -endif() +# TODO: check if the mdl support is still required +# if (${Matlab_VERSION_STRING} GREATER "8.3") + # install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/WBToolboxLibrary.slx DESTINATION ${WB-TOOLBOX_SHARE_DIR}) +# else() + # install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/WBToolboxLibrary.mdl DESTINATION ${WB-TOOLBOX_SHARE_DIR}) +# endif() +install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/matlab/library/exported/WBToolboxLibrary.slx + DESTINATION ${WB-TOOLBOX_SHARE_DIR}) diff --git a/toolbox/WBToolboxLibrary.mdl b/toolbox/WBToolboxLibrary.mdl deleted file mode 100644 index a0e924d52..000000000 --- a/toolbox/WBToolboxLibrary.mdl +++ /dev/null @@ -1,4383 +0,0 @@ -Library { - Name "WBToolboxLibrary" - Version 7.9 - LibraryType "BlockLibrary" - SavedCharacterEncoding "US-ASCII" - ScopeRefreshTime 0.035000 - OverrideScopeRefreshTime on - DisableAllScopes off - FPTRunName "Run 1" - MaxMDLFileLineLength 120 - Created "Thu Feb 06 02:21:39 2014" - Creator "jorhabib" - UpdateHistory "UpdateHistoryNever" - ModifiedByFormat "%" - LastModifiedBy "makaveli" - ModifiedDateFormat "%" - LastModifiedDate "Wed Aug 23 12:36:18 2017" - RTWModifiedTimeStamp 425392578 - ModelVersionFormat "1.%" - ConfigurationManager "none" - SampleTimeColors off - SampleTimeAnnotations off - LibraryLinkDisplay "disabled" - WideLines off - ShowLineDimensions off - ShowPortDataTypes off - ShowDesignRanges off - ShowLoopsOnError on - IgnoreBidirectionalLines off - ShowStorageClass off - ShowTestPointIcons on - ShowSignalResolutionIcons on - ShowViewerIcons on - SortedOrder off - ExecutionContextIcon off - ShowLinearizationAnnotations on - BlockNameDataTip off - BlockParametersDataTip off - BlockDescriptionStringDataTip off - ToolBar on - StatusBar on - BrowserShowLibraryLinks off - BrowserLookUnderMasks off - SimulationMode "normal" - LinearizationMsg "none" - Profile off - ParamWorkspaceSource "MATLABWorkspace" - RecordCoverage off - CovSaveName "covdata" - CovMetricSettings "dw" - CovNameIncrementing off - CovHtmlReporting on - CovForceBlockReductionOff on - CovSaveCumulativeToWorkspaceVar on - CovSaveSingleToWorkspaceVar on - CovCumulativeReport off - CovReportOnPause on - CovModelRefEnable "Off" - CovExternalEMLEnable off - ExtModeBatchMode off - ExtModeEnableFloating on - ExtModeTrigType "manual" - ExtModeTrigMode "normal" - ExtModeTrigPort "1" - ExtModeTrigElement "any" - ExtModeTrigDuration 1000 - ExtModeTrigDurationFloating "auto" - ExtModeTrigHoldOff 0 - ExtModeTrigDelay 0 - ExtModeTrigDirection "rising" - ExtModeTrigLevel 0 - ExtModeArchiveMode "off" - ExtModeAutoIncOneShot off - ExtModeIncDirWhenArm off - ExtModeAddSuffixToVar off - ExtModeWriteAllDataToWs off - ExtModeArmWhenConnect on - ExtModeSkipDownloadWhenConnect off - ExtModeLogAll on - ExtModeAutoUpdateStatusClock on - ShowModelReferenceBlockVersion off - ShowModelReferenceBlockIO off - Array { - Type "Handle" - Dimension 1 - Simulink.ConfigSet { - $ObjectID 7 - Version "1.12.0" - Array { - Type "Handle" - Dimension 9 - Simulink.SolverCC { - $ObjectID 8 - Version "1.12.0" - StartTime "0.0" - StopTime "10.0" - AbsTol "auto" - FixedStep "auto" - InitialStep "auto" - MaxNumMinSteps "-1" - MaxOrder 5 - ZcThreshold "auto" - ConsecutiveZCsStepRelTol "10*128*eps" - MaxConsecutiveZCs "1000" - ExtrapolationOrder 4 - NumberNewtonIterations 1 - MaxStep "auto" - MinStep "auto" - MaxConsecutiveMinStep "1" - RelTol "1e-3" - SolverMode "Auto" - EnableConcurrentExecution off - ConcurrentTasks off - Solver "ode45" - SolverName "ode45" - SolverJacobianMethodControl "auto" - ShapePreserveControl "DisableAll" - ZeroCrossControl "UseLocalSettings" - ZeroCrossAlgorithm "Nonadaptive" - AlgebraicLoopSolver "TrustRegion" - SolverResetMethod "Fast" - PositivePriorityOrder off - AutoInsertRateTranBlk off - SampleTimeConstraint "Unconstrained" - InsertRTBMode "Whenever possible" - } - Simulink.DataIOCC { - $ObjectID 9 - Version "1.12.0" - Decimation "1" - ExternalInput "[t, u]" - FinalStateName "xFinal" - InitialState "xInitial" - LimitDataPoints on - MaxDataPoints "1000" - LoadExternalInput off - LoadInitialState off - SaveFinalState off - SaveCompleteFinalSimState off - SaveFormat "Array" - SignalLoggingSaveFormat "ModelDataLogs" - SaveOutput on - SaveState off - SignalLogging on - DSMLogging on - InspectSignalLogs off - SaveTime on - ReturnWorkspaceOutputs off - StateSaveName "xout" - TimeSaveName "tout" - OutputSaveName "yout" - SignalLoggingName "logsout" - DSMLoggingName "dsmout" - OutputOption "RefineOutputTimes" - OutputTimes "[]" - ReturnWorkspaceOutputsName "out" - Refine "1" - } - Simulink.OptimizationCC { - $ObjectID 10 - Version "1.12.0" - Array { - Type "Cell" - Dimension 8 - Cell "BooleansAsBitfields" - Cell "PassReuseOutputArgsAs" - Cell "PassReuseOutputArgsThreshold" - Cell "ZeroExternalMemoryAtStartup" - Cell "ZeroInternalMemoryAtStartup" - Cell "OptimizeModelRefInitCode" - Cell "NoFixptDivByZeroProtection" - Cell "UseSpecifiedMinMax" - PropName "DisabledProps" - } - BlockReduction on - BooleanDataType on - ConditionallyExecuteInputs on - InlineParams off - UseIntDivNetSlope off - UseFloatMulNetSlope off - UseSpecifiedMinMax off - InlineInvariantSignals off - OptimizeBlockIOStorage on - BufferReuse on - EnhancedBackFolding off - StrengthReduction off - ExpressionFolding on - BooleansAsBitfields off - BitfieldContainerType "uint_T" - EnableMemcpy on - MemcpyThreshold 64 - PassReuseOutputArgsAs "Structure reference" - ExpressionDepthLimit 2147483647 - LocalBlockOutputs on - RollThreshold 5 - StateBitsets off - DataBitsets off - ZeroExternalMemoryAtStartup on - ZeroInternalMemoryAtStartup on - InitFltsAndDblsToZero off - NoFixptDivByZeroProtection off - EfficientFloat2IntCast off - EfficientMapNaN2IntZero on - OptimizeModelRefInitCode off - LifeSpan "inf" - MaxStackSize "Inherit from target" - BufferReusableBoundary on - SimCompilerOptimization "Off" - AccelVerboseBuild off - } - Simulink.DebuggingCC { - $ObjectID 11 - Version "1.12.0" - RTPrefix "error" - ConsistencyChecking "none" - ArrayBoundsChecking "none" - SignalInfNanChecking "none" - SignalRangeChecking "none" - ReadBeforeWriteMsg "UseLocalSettings" - WriteAfterWriteMsg "UseLocalSettings" - WriteAfterReadMsg "UseLocalSettings" - AlgebraicLoopMsg "warning" - ArtificialAlgebraicLoopMsg "warning" - SaveWithDisabledLinksMsg "warning" - SaveWithParameterizedLinksMsg "warning" - CheckSSInitialOutputMsg on - UnderspecifiedInitializationDetection "Classic" - MergeDetectMultiDrivingBlocksExec "none" - CheckExecutionContextPreStartOutputMsg off - CheckExecutionContextRuntimeOutputMsg off - SignalResolutionControl "UseLocalSettings" - BlockPriorityViolationMsg "warning" - MinStepSizeMsg "warning" - TimeAdjustmentMsg "none" - MaxConsecutiveZCsMsg "error" - MaskedZcDiagnostic "warning" - IgnoredZcDiagnostic "warning" - SolverPrmCheckMsg "warning" - InheritedTsInSrcMsg "warning" - MultiTaskDSMMsg "error" - MultiTaskCondExecSysMsg "error" - MultiTaskRateTransMsg "error" - SingleTaskRateTransMsg "none" - TasksWithSamePriorityMsg "warning" - SigSpecEnsureSampleTimeMsg "warning" - CheckMatrixSingularityMsg "none" - IntegerOverflowMsg "warning" - Int32ToFloatConvMsg "warning" - ParameterDowncastMsg "error" - ParameterOverflowMsg "error" - ParameterUnderflowMsg "none" - ParameterPrecisionLossMsg "warning" - ParameterTunabilityLossMsg "warning" - FixptConstUnderflowMsg "none" - FixptConstOverflowMsg "none" - FixptConstPrecisionLossMsg "none" - UnderSpecifiedDataTypeMsg "none" - UnnecessaryDatatypeConvMsg "none" - VectorMatrixConversionMsg "none" - InvalidFcnCallConnMsg "error" - FcnCallInpInsideContextMsg "Enable All" - SignalLabelMismatchMsg "none" - UnconnectedInputMsg "warning" - UnconnectedOutputMsg "warning" - UnconnectedLineMsg "warning" - SFcnCompatibilityMsg "none" - FrameProcessingCompatibilityMsg "error" - UniqueDataStoreMsg "none" - BusObjectLabelMismatch "warning" - RootOutportRequireBusObject "warning" - AssertControl "UseLocalSettings" - ModelReferenceIOMsg "none" - ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" - ModelReferenceVersionMismatchMessage "none" - ModelReferenceIOMismatchMessage "none" - UnknownTsInhSupMsg "warning" - ModelReferenceDataLoggingMessage "warning" - ModelReferenceSymbolNameMessage "warning" - ModelReferenceExtraNoncontSigs "error" - StateNameClashWarn "warning" - SimStateInterfaceChecksumMismatchMsg "warning" - SimStateOlderReleaseMsg "error" - InitInArrayFormatMsg "warning" - StrictBusMsg "ErrorLevel1" - BusNameAdapt "WarnAndRepair" - NonBusSignalsTreatedAsBus "none" - BlockIODiagnostic "none" - SFUnusedDataAndEventsDiag "warning" - SFUnexpectedBacktrackingDiag "warning" - SFInvalidInputDataAccessInChartInitDiag "warning" - SFNoUnconditionalDefaultTransitionDiag "warning" - SFTransitionOutsideNaturalParentDiag "warning" - SFUnconditionalTransitionShadowingDiag "warning" - ModelReferenceCSMismatchMessage "none" - } - Simulink.HardwareCC { - $ObjectID 12 - Version "1.12.0" - ProdBitPerChar 8 - ProdBitPerShort 16 - ProdBitPerInt 32 - ProdBitPerLong 32 - ProdBitPerFloat 32 - ProdBitPerDouble 64 - ProdBitPerPointer 32 - ProdLargestAtomicInteger "Char" - ProdLargestAtomicFloat "None" - ProdIntDivRoundTo "Undefined" - ProdEndianess "Unspecified" - ProdWordSize 32 - ProdShiftRightIntArith on - ProdHWDeviceType "32-bit Generic" - TargetBitPerChar 8 - TargetBitPerShort 16 - TargetBitPerInt 32 - TargetBitPerLong 32 - TargetBitPerFloat 32 - TargetBitPerDouble 64 - TargetBitPerPointer 32 - TargetLargestAtomicInteger "Char" - TargetLargestAtomicFloat "None" - TargetShiftRightIntArith on - TargetIntDivRoundTo "Undefined" - TargetEndianess "Unspecified" - TargetWordSize 32 - TargetPreprocMaxBitsSint 32 - TargetPreprocMaxBitsUint 32 - TargetHWDeviceType "Specified" - TargetUnknown off - ProdEqTarget on - } - Simulink.ModelReferenceCC { - $ObjectID 13 - Version "1.12.0" - UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" - CheckModelReferenceTargetMessage "error" - EnableParallelModelReferenceBuilds off - ParallelModelReferenceErrorOnInvalidPool on - ParallelModelReferenceMATLABWorkerInit "None" - ModelReferenceNumInstancesAllowed "Multi" - PropagateVarSize "Infer from blocks in model" - ModelReferencePassRootInputsByReference on - ModelReferenceMinAlgLoopOccurrences off - PropagateSignalLabelsOutOfModel off - SupportModelReferenceSimTargetCustomCode off - } - Simulink.SFSimCC { - $ObjectID 14 - Version "1.12.0" - SFSimEcho on - SimCtrlC on - SimIntegrity on - SimUseLocalCustomCode off - SimParseCustomCode on - SimBuildMode "sf_incremental_build" - } - Simulink.RTWCC { - $BackupClass "Simulink.RTWCC" - $ObjectID 15 - Version "1.12.0" - Array { - Type "Cell" - Dimension 13 - Cell "IncludeHyperlinkInReport" - Cell "GenerateTraceInfo" - Cell "GenerateTraceReport" - Cell "GenerateTraceReportSl" - Cell "GenerateTraceReportSf" - Cell "GenerateTraceReportEml" - Cell "GenerateWebview" - Cell "GenerateCodeMetricsReport" - Cell "GenerateCodeReplacementReport" - Cell "PortableWordSizes" - Cell "GenerateMissedCodeReplacementReport" - Cell "GenerateErtSFunction" - Cell "CreateSILPILBlock" - PropName "DisabledProps" - } - SystemTargetFile "grt.tlc" - TLCOptions "" - GenCodeOnly off - MakeCommand "make_rtw" - GenerateMakefile on - TemplateMakefile "grt_default_tmf" - PostCodeGenCommand "" - GenerateReport off - SaveLog off - RTWVerbose on - RetainRTWFile off - ProfileTLC off - TLCDebug off - TLCCoverage off - TLCAssert off - RTWUseLocalCustomCode off - RTWUseSimCustomCode off - IncludeHyperlinkInReport off - LaunchReport off - TargetLang "C" - IncludeBusHierarchyInRTWFileBlockHierarchyMap off - GenerateTraceInfo off - GenerateTraceReport off - GenerateTraceReportSl off - GenerateTraceReportSf off - GenerateTraceReportEml off - GenerateWebview off - GenerateCodeMetricsReport off - GenerateCodeReplacementReport off - RTWCompilerOptimization "Off" - RTWCustomCompilerOptimizations "" - CheckMdlBeforeBuild "Off" - Array { - Type "Handle" - Dimension 2 - Simulink.CodeAppCC { - $ObjectID 16 - Version "1.12.0" - Array { - Type "Cell" - Dimension 25 - Cell "IgnoreCustomStorageClasses" - Cell "IgnoreTestpoints" - Cell "InsertBlockDesc" - Cell "InsertPolySpaceComments" - Cell "SFDataObjDesc" - Cell "MATLABFcnDesc" - Cell "SimulinkDataObjDesc" - Cell "DefineNamingRule" - Cell "SignalNamingRule" - Cell "ParamNamingRule" - Cell "InlinedPrmAccess" - Cell "CustomSymbolStr" - Cell "CustomSymbolStrGlobalVar" - Cell "CustomSymbolStrType" - Cell "CustomSymbolStrField" - Cell "CustomSymbolStrFcn" - Cell "CustomSymbolStrFcnArg" - Cell "CustomSymbolStrBlkIO" - Cell "CustomSymbolStrTmpVar" - Cell "CustomSymbolStrMacro" - Cell "ReqsInCode" - Cell "InternalIdentifier" - Cell "CustomSymbolStrModelFcn" - Cell "CustomSymbolStrUtil" - Cell "CustomUserTokenString" - PropName "DisabledProps" - } - ForceParamTrailComments off - GenerateComments on - IgnoreCustomStorageClasses on - IgnoreTestpoints off - IncHierarchyInIds off - MaxIdLength 31 - PreserveName off - PreserveNameWithParent off - ShowEliminatedStatement off - IncAutoGenComments off - SimulinkDataObjDesc off - SFDataObjDesc off - MATLABFcnDesc off - IncDataTypeInIds off - MangleLength 1 - CustomSymbolStrGlobalVar "$R$N$M" - CustomSymbolStrType "$N$R$M_T" - CustomSymbolStrField "$N$M" - CustomSymbolStrFcn "$R$N$M$F" - CustomSymbolStrFcnArg "rt$I$N$M" - CustomSymbolStrBlkIO "rtb_$N$M" - CustomSymbolStrTmpVar "$N$M" - CustomSymbolStrMacro "$R$N$M" - DefineNamingRule "None" - ParamNamingRule "None" - SignalNamingRule "None" - InsertBlockDesc off - InsertPolySpaceComments off - SimulinkBlockComments on - MATLABSourceComments off - EnableCustomComments off - InlinedPrmAccess "Literals" - ReqsInCode off - UseSimReservedNames off - } - Simulink.GRTTargetCC { - $BackupClass "Simulink.TargetCC" - $ObjectID 17 - Version "1.12.0" - Array { - Type "Cell" - Dimension 18 - Cell "GeneratePreprocessorConditionals" - Cell "IncludeMdlTerminateFcn" - Cell "SupportNonInlinedSFcns" - Cell "SuppressErrorStatus" - Cell "ERTCustomFileBanners" - Cell "GenerateSampleERTMain" - Cell "GenerateTestInterfaces" - Cell "ModelStepFunctionPrototypeControlCompliant" - Cell "CPPClassGenCompliant" - Cell "PortableWordSizes" - Cell "PurelyIntegerCode" - Cell "SupportComplex" - Cell "SupportAbsoluteTime" - Cell "SupportContinuousTime" - Cell "MultiInstanceERTCode" - Cell "RemoveResetFunc" - Cell "ExistingSharedCode" - Cell "RemoveDisableFunc" - PropName "DisabledProps" - } - TargetFcnLib "ansi_tfl_table_tmw.mat" - TargetLibSuffix "" - TargetPreCompLibLocation "" - CodeReplacementLibrary "None" - UtilityFuncGeneration "Auto" - ERTMultiwordTypeDef "System defined" - ERTMultiwordLength 256 - MultiwordLength 2048 - GenerateFullHeader on - GenerateSampleERTMain off - GenerateTestInterfaces off - ModelReferenceCompliant on - ParMdlRefBuildCompliant on - CompOptLevelCompliant on - ConcurrentExecutionCompliant on - IncludeMdlTerminateFcn on - GeneratePreprocessorConditionals "Disable all" - CombineOutputUpdateFcns off - CombineSignalStateStructs off - SuppressErrorStatus off - ERTFirstTimeCompliant off - IncludeFileDelimiter "Auto" - ERTCustomFileBanners off - SupportAbsoluteTime on - LogVarNameModifier "rt_" - MatFileLogging on - MultiInstanceERTCode off - SupportNonFinite on - SupportComplex on - PurelyIntegerCode off - SupportContinuousTime on - SupportNonInlinedSFcns on - SupportVariableSizeSignals off - ParenthesesLevel "Nominal" - ModelStepFunctionPrototypeControlCompliant off - CPPClassGenCompliant on - AutosarCompliant off - GRTInterface on - UseMalloc off - ExtMode off - ExtModeStaticAlloc off - ExtModeTesting off - ExtModeStaticAllocSize 1000000 - ExtModeTransport 0 - ExtModeMexFile "ext_comm" - ExtModeIntrfLevel "Level1" - RTWCAPISignals off - RTWCAPIParams off - RTWCAPIStates off - RTWCAPIRootIO off - GenerateASAP2 off - } - PropName "Components" - } - } - hdlcoderui.hdlcc { - $ObjectID 19 - Version "1.12.0" - Description "HDL Coder custom configuration component" - Name "HDL Coder" - Array { - Type "Cell" - Dimension 1 - Cell " " - PropName "HDLConfigFile" - } - HDLCActiveTab "0" - } - PropName "Components" - } - Name "Configuration" - CurrentDlgPage "Solver" - ConfigPrmDlgPosition [ 963, 135, 1843, 765 ] - } - PropName "ConfigurationSets" - } - ExplicitPartitioning off - BlockDefaults { - ForegroundColor "black" - BackgroundColor "white" - DropShadow off - NamePlacement "normal" - FontName "Helvetica" - FontSize 10 - FontWeight "normal" - FontAngle "normal" - ShowName on - BlockRotation 0 - BlockMirror off - } - AnnotationDefaults { - HorizontalAlignment "center" - VerticalAlignment "middle" - ForegroundColor "black" - BackgroundColor "white" - DropShadow off - FontName "Helvetica" - FontSize 10 - FontWeight "normal" - FontAngle "normal" - UseDisplayTextAsClickCallback off - } - LineDefaults { - FontName "Helvetica" - FontSize 9 - FontWeight "normal" - FontAngle "normal" - } - BlockParameterDefaults { - Block { - BlockType Clock - DisplayTime off - Decimation "10" - } - Block { - BlockType Constant - Value "1" - VectorParams1D on - SamplingMode "Sample based" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Inherit from 'Constant value'" - LockScale off - SampleTime "inf" - FramePeriod "inf" - PreserveConstantTs off - } - Block { - BlockType Demux - Outputs "4" - DisplayOption "none" - BusSelectionMode off - } - Block { - BlockType Gain - Gain "1" - Multiplication "Element-wise(K.*u)" - ParamMin "[]" - ParamMax "[]" - ParamDataTypeStr "Inherit: Same as input" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as input" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType Inport - Port "1" - OutputFunctionCall off - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: auto" - LockScale off - BusOutputAsStruct off - PortDimensions "-1" - VarSizeSig "Inherit" - SampleTime "-1" - SignalType "auto" - SamplingMode "auto" - LatchByDelayingOutsideSignal off - LatchInputForFeedbackSignals off - Interpolate on - } - Block { - BlockType Outport - Port "1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: auto" - LockScale off - BusOutputAsStruct off - PortDimensions "-1" - VarSizeSig "Inherit" - SampleTime "-1" - SignalType "auto" - SamplingMode "auto" - SourceOfInitialOutputValue "Dialog" - OutputWhenDisabled "held" - InitialOutput "[]" - } - Block { - BlockType Product - Inputs "2" - Multiplication "Element-wise(.*)" - CollapseMode "All dimensions" - CollapseDim "1" - InputSameDT on - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as first input" - LockScale off - RndMeth "Zero" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType S-Function - FunctionName "system" - SFunctionModules "''" - PortCounts "[]" - } - Block { - BlockType SubSystem - ShowPortLabels "FromPortIcon" - Permissions "ReadWrite" - PermitHierarchicalResolution "All" - TreatAsAtomicUnit off - SystemSampleTime "-1" - RTWFcnNameOpts "Auto" - RTWFileNameOpts "Auto" - RTWMemSecFuncInitTerm "Inherit from model" - RTWMemSecFuncExecute "Inherit from model" - RTWMemSecDataConstants "Inherit from model" - RTWMemSecDataInternal "Inherit from model" - RTWMemSecDataParameters "Inherit from model" - SimViewingDevice off - DataTypeOverride "UseLocalSettings" - DataTypeOverrideAppliesTo "AllNumericTypes" - MinMaxOverflowLogging "UseLocalSettings" - SFBlockType "NONE" - GeneratePreprocessorConditionals off - PropagateVariantConditions off - TreatAsGroupedWhenPropagatingVariantConditions on - } - Block { - BlockType Sum - IconShape "rectangular" - Inputs "++" - CollapseMode "All dimensions" - CollapseDim "1" - InputSameDT on - AccumDataTypeStr "Inherit: Inherit via internal rule" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as first input" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType Terminator - } - } - System { - Name "WBToolboxLibrary" - Location [747, 53, 2027, 774] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "black" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "273" - ReportName "simulink-default.rpt" - SIDHighWatermark "1773" - Block { - BlockType SubSystem - Name "Utilities" - SID "192" - Ports [] - Position [364, 17, 462, 114] - ZOrder -1 - ForegroundColor "white" - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('utilities.png'))" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "Utilities" - Location [551, 44, 1831, 765] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "166" - Block { - BlockType SubSystem - Name "DampPinv" - SID "104" - Ports [2, 1] - Position [435, 153, 505, 197] - ZOrder -1 - BackgroundColor "[0.848000, 0.128048, 0.320035]" - RequestExecContextInheritance off - Variant off - MaskPromptString "Tolerance" - MaskStyleString "edit" - MaskVariables "tol=@1;" - MaskTunableValueString "on" - MaskEnableString "on" - MaskVisibilityString "on" - MaskToolTipString "on" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "1e-4" - System { - Name "DampPinv" - Location [0, 29, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "mat" - SID "105" - Position [50, 53, 80, 67] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "sigma" - SID "106" - Position [50, 93, 80, 107] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Damped Pseudo Inverse" - SID "107" - Ports [2, 1] - Position [105, 39, 200, 121] - ZOrder -4 - LibraryVersion "1.32" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - MaskType "Stateflow" - MaskDescription "Embedded MATLAB block" - MaskSelfModifiable on - MaskDisplay "bgColor = Simulink.Root.ColorString2Rgb(get_param(gcbh, 'BackgroundColor')); image(imread('p" - "rivate/eml_membrane_16.png','png','BackgroundColor',bgColor(1:3)),'center'); disp([10 10 'fcn']);" - MaskIconFrame on - MaskIconOpaque off - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "normalized" - System { - Name "Damped Pseudo Inverse" - Location [12, 45, 1279, 3773] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "1773" - Block { - BlockType Inport - Name "mat" - SID "107::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "sigma" - SID "107::25" - Position [20, 136, 40, 154] - ZOrder 11 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "107::1618" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 98 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "107::1617" - Tag "Stateflow S-Function WBToolboxLibrary 6" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 97 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport off - Port { - PortNumber 2 - Name "DPinv" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "107::1619" - Position [460, 241, 480, 259] - ZOrder 99 - } - Block { - BlockType Outport - Name "DPinv" - SID "107::5" - Position [460, 101, 480, 119] - ZOrder -6 - IconDisplay "Port number" - } - Line { - SrcBlock "mat" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - SrcBlock "sigma" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "DPinv" - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "DPinv" - DstPort 1 - } - Line { - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType Outport - Name "DPinv" - SID "108" - Position [225, 73, 255, 87] - ZOrder -5 - IconDisplay "Port number" - } - Line { - SrcBlock "sigma" - SrcPort 1 - DstBlock "Damped Pseudo Inverse" - DstPort 2 - } - Line { - SrcBlock "Damped Pseudo Inverse" - SrcPort 1 - DstBlock "DPinv" - DstPort 1 - } - Line { - SrcBlock "mat" - SrcPort 1 - DstBlock "Damped Pseudo Inverse" - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType S-Function - Name "DoFs converter" - SID "1771" - Ports [1, 5] - Position [240, 241, 385, 309] - ZOrder 81 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend\n" - FunctionName "WBToolbox" - Parameters "'YARPWBIConverter',robotName,localName,wbiFile,wbiList,yarp2WBIOption" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "DoFs converter" - MaskDescription "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on " - "its configuration.\nThe DoFs configuration is automatically currently taken from the WBI list option.\nThe robot na" - "me is taken from the environment variable YARP_ROBOT_NAME.\n\nParameters:\n\n- Conversion direction: specify if you" - " want to convert from YARP to the current DoFs serialization or viceversa.\n\nWBI parameters:\n\n- Robot Port Name:" - " Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name s" - "pecified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the por" - "ts opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of" - " the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Conversion Direction|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "popup(From YARP to WBI|From WBI to YARP),edit,edit,edit,edit" - MaskVariables "yarp2WBIOption=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" - MaskTunableValueString "on,on,on,on,on" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "robotName = getenv('YARP_ROBOT_NAME');\n\ncurrentSelection = get_param(gcb,'yarp2WBIoption');\n\nif" - " strcmp(currentSelection,'From YARP to WBI')\n direction = 'YARP -> DoFs';\nelse\n direction = 'DoFs -> YARP'" - ";\nend\n\nfprintf('%s\\n\\n%s', robotName, direction);" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "From YARP to WBI|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block Parameters,WBI Parameters,WBI Parameters,WBI Parameters,WBI Parameters" - } - Block { - BlockType S-Function - Name "Minimum Jerk Trajectory Generator" - SID "1747" - Ports [1, 3] - Position [450, 73, 605, 127] - ZOrder 78 - FunctionName "WBToolbox" - Parameters "'MinimumJerkTrajectoryGenerator',sampleTime, settlingTime, firstDerivatives, secondDerivatives, expl" - "icitInitialValue, externalSettlingTime,resetOnSettlingTime" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "Minimum Jerk Trajectory Generator" - MaskDescription "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk T" - "rajectory Generator is approximated using a \n3rd order LTI dynamical system \n(for more details see [1]). \nPositi" - "on, velocity and acceleration trajectories are computed.\n The main advantage with respect to the standard polynomi" - "al \nform is that if the reference value yd changes \nthere is no need to recompute the filter coefficients.\n\n[1]" - " Pattacini, U.; Nori, F.; Natale, L.; Metta, G.; Sandini, G., \"An experimental evaluation of a novel minimum-jerk " - "cartesian controller for humanoid robots,\" in Intelligent Robots and Systems (IROS), 2010 IEEE/RSJ International C" - "onference on , vol., no., pp.1668-1674, 18-22 Oct. 2010\ndoi: 10.1109/IROS.2010.5650851\nURL: http://ieeexplore.iee" - "e.org/stamp/stamp.jsp?tp=&arnumber=5650851&isnumber=5648787" - MaskPromptString "External Settling Time|Settling Time|Sample Time|Reset on Settling Time Changes|Output First De" - "rivative|Output Second Derivative|Explicit Initial Value" - MaskStyleString "checkbox,edit,edit,checkbox,checkbox,checkbox,checkbox" - MaskVariables "externalSettlingTime=@1;settlingTime=@2;sampleTime=@3;resetOnSettlingTime=@4;firstDerivatives=@5;" - "secondDerivatives=@6;explicitInitialValue=@7;" - MaskTunableValueString "on,on,on,on,on,on,on" - MaskCallbackString "externalSettlingTime = get_param(gcb, 'externalSettlingTime');\nvisibility = get_param(gcb, '" - "MaskVisibilities');\nif(strcmp(externalSettlingTime, 'on'))\n visibility{2} = 'off';\n visibility{4} = 'on';\n" - "else\n visibility{2} = 'on';\n visibility{4} = 'off';\nend\nset_param(gcb, 'MaskVisibilities',visibility);\nc" - "lear externalSettlingTime||||||" - MaskEnableString "on,on,on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on,on,off" - MaskToolTipString "on,on,on,on,on,on,on" - MaskDisplay "firstDer = get_param(gcb, 'firstDerivatives');\nsecondDer = get_param(gcb, 'secondDerivatives');\ni" - "nitialValues = get_param(gcb, 'explicitInitialValue');\nexternalSettlingTimeParam = get_param(gcb, 'externalSettlin" - "gTime');\n\n%Inputs\nportIndex = 2;\nport_label('input', 1, 'Reference')\nif(strcmp(initialValues, 'on'))\n port" - "_label('input', portIndex, 'Initial Value')\n portIndex = portIndex + 1;\nend\n\nif(strcmp(externalSettlingTimeP" - "aram, 'on'))\n port_label('input', portIndex, 'Settling Time')\n portIndex = portIndex + 1;\nend\n\n%Outputs\n" - "port_label('output', 1, 'Signal')\nsecondDerPortIndex = 2;\nif(strcmp(firstDer, 'on'))\n port_label('output', 2," - " 'First Derivative')\n secondDerPortIndex = secondDerPortIndex + 1;\nend\nif(strcmp(secondDer, 'on'))\n port_" - "label('output', secondDerPortIndex, 'Second Derivative')\nend\n\n\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "off|3|0.01|off|on|on|off" - MaskTabNameString "Trajectory Parameters,Trajectory Parameters,Trajectory Parameters,Trajectory Parameters,Input/" - "Output,Input/Output,Input/Output" - } - Block { - BlockType S-Function - Name "Real Time Synchronizer" - SID "1657" - Ports [] - Position [155, 14, 280, 51] - ZOrder 23 - ForegroundColor "white" - BackgroundColor "gray" - ShowName off - FunctionName "WBToolbox" - Parameters "'RealTimeSynchronizer',period" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "Real Time Synchronizer" - MaskDescription "This block slows down the simulation trying to match the period specified \nas parameter (in sec" - "onds).\nThe bigger the period the more probable \nis that Simulink can remain synched with it.\n" - MaskPromptString "Controller Period (in seconds)" - MaskStyleString "edit" - MaskVariables "period=@1;" - MaskTunableValueString "on" - MaskEnableString "on" - MaskVisibilityString "on" - MaskToolTipString "on" - MaskDisplay "disp('Real Time Synchronizer')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "0.01" - } - Block { - BlockType S-Function - Name "Simulator Synchronizer" - SID "1658" - Ports [] - Position [335, 14, 465, 51] - ZOrder 24 - ForegroundColor "[0.490196, 0.000000, 0.000000]" - ShowName off - FunctionName "WBToolbox" - Parameters "'SimulatorSynchronizer',period, serverPortName, clientPortName" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "Simulator Synchronizer" - MaskDescription "This block synchronizes with the external simulation on a simulator \n(only Gazebo is supported " - "at the moment).\n\n" - MaskPromptString "Controller Period (in seconds)|Server Port Name|Client Port Name" - MaskStyleString "edit,edit,edit" - MaskVariables "period=@1;serverPortName=@2;clientPortName=@3;" - MaskTunableValueString "on,on,on" - MaskCallbackString "||" - MaskEnableString "on,on,on" - MaskVisibilityString "on,on,on" - MaskToolTipString "on,on,on" - MaskDisplay "disp('Simulator Synchronizer')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "0.01|'/clock/rpc'|'/WBT_synchronizer/rpc:o'" - } - Block { - BlockType SubSystem - Name "TruncPinv" - SID "109" - Ports [2, 1] - Position [335, 153, 405, 197] - ZOrder -3 - BackgroundColor "[0.534601, 0.470279, 1.000000]" - RequestExecContextInheritance off - Variant off - MaskPromptString "Tolerance" - MaskStyleString "edit" - MaskVariables "tol=@1;" - MaskTunableValueString "on" - MaskEnableString "on" - MaskVisibilityString "on" - MaskToolTipString "on" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "1e-4" - System { - Name "TruncPinv" - Location [0, 29, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "S" - SID "110" - Position [50, 53, 80, 67] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "tol" - SID "111" - Position [50, 93, 80, 107] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Truncated PseudoInverse" - SID "112" - Ports [2, 1] - Position [105, 39, 200, 121] - ZOrder -4 - LibraryVersion "1.32" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - MaskType "Stateflow" - MaskDescription "Embedded MATLAB block" - MaskSelfModifiable on - MaskDisplay "bgColor = Simulink.Root.ColorString2Rgb(get_param(gcbh, 'BackgroundColor')); image(imread('p" - "rivate/eml_membrane_16.png','png','BackgroundColor',bgColor(1:3)),'center'); disp([10 10 'fcn']);" - MaskIconFrame on - MaskIconOpaque off - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "normalized" - System { - Name "Truncated PseudoInverse" - Location [12, 45, 1279, 3773] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "1773" - Block { - BlockType Inport - Name "mat" - SID "112::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "tol" - SID "112::25" - Position [20, 136, 40, 154] - ZOrder 11 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "112::1609" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 98 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "112::1608" - Tag "Stateflow S-Function WBToolboxLibrary 7" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 97 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport off - Port { - PortNumber 2 - Name "TPinv" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "112::1610" - Position [460, 241, 480, 259] - ZOrder 99 - } - Block { - BlockType Outport - Name "TPinv" - SID "112::5" - Position [460, 101, 480, 119] - ZOrder -6 - IconDisplay "Port number" - } - Line { - SrcBlock "mat" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - SrcBlock "tol" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "TPinv" - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "TPinv" - DstPort 1 - } - Line { - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType Outport - Name "Tpinv" - SID "113" - Position [225, 73, 255, 87] - ZOrder -5 - IconDisplay "Port number" - } - Line { - SrcBlock "S" - SrcPort 1 - DstBlock "Truncated PseudoInverse" - DstPort 1 - } - Line { - SrcBlock "Truncated PseudoInverse" - SrcPort 1 - DstBlock "Tpinv" - DstPort 1 - } - Line { - SrcBlock "tol" - SrcPort 1 - DstBlock "Truncated PseudoInverse" - DstPort 2 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType S-Function - Name "Yarp Clock" - SID "1773" - Ports [0, 1] - Position [335, 76, 405, 124] - ZOrder 85 - ForegroundColor "[0.490196, 0.000000, 0.000000]" - FunctionName "WBToolbox" - Parameters "'YarpClock'" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "YARP Clock" - MaskDescription "This block outputs the current YARP Time\nIn a nutshell, this block outputs the equivalent of th" - "e C++ function call\nyarp::os::Time::now()" - MaskSelfModifiable on - MaskDisplay "disp('YARP Time')\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - } - Block { - BlockType S-Function - Name "Yarp Read" - SID "1632" - Ports [0, 2] - Position [105, 74, 165, 121] - ZOrder 22 - ForegroundColor "[0.490196, 0.000000, 0.000000]" - FunctionName "WBToolbox" - Parameters "'YarpRead',portName,signalSize,blocking,timestamp,autoconnect,errorOnConnection" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "YARP Read" - MaskDescription "This block behaves as the command 'yarp read'. \nBy default it has the option 'Autoconnect' acti" - "ve, which means that the user \ncan only specify the name of the port ('Source Port Name') from which readings are " - "desired,\nalong with the size of the expected data (e.g. 3 when reading the torso state).\nWhen the user unchecks '" - "Autoconnect' 'Opened Port Name' field shows up \ncorresponding to the name of the port the block will create \nbut " - "won't connect to anything. \nAt this point the output will be always zero, until the user connects it\nto some othe" - "r port from command line by issuing 'yarp connect [from] [dest]'.\nIn this case an additional output, called 'signa" - "l' will be added which will output\n1 if the port has received at least one data, or 0 otherwise.\n" - MaskPromptString "Source Port Name|Port Size|Blocking Read|Read Timestamp|Autoconnect|Error on missing connection" - MaskStyleString "edit,edit,checkbox,checkbox,checkbox,checkbox" - MaskVariables "portName=@1;signalSize=@2;blocking=@3;timestamp=@4;autoconnect=@5;errorOnConnection=@6;" - MaskTunableValueString "on,on,on,on,on,on" - MaskCallbackString "||||autoconnect_val = get_param(gcb, 'Autoconnect');\nprompt_string = get_param(gcb, 'MaskPro" - "mpts');\nif(strcmp(autoconnect_val, 'on'))\n prompt_string{1} = 'Source Port Name';\n set_param(gcb, 'MaskVis" - "ibilities',{'on';'on';'on';'on';'on';'on'});\nelse\n prompt_string{1} = 'Opened Port Name';\n set_param(gcb, " - "'MaskVisibilities',{'on';'on';'on';'on';'on';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear au" - "toconnect_val prompt_string|" - MaskEnableString "on,on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on,on" - MaskToolTipString "on,on,on,on,on,on" - MaskSelfModifiable on - MaskDisplay "port_label('output', 1, 'signal');\nportNumber = 1;\nif (timestamp)\n portNumber = portNumber + " - "1;\n port_label('output', portNumber, 'timestamp');\nend\n\nif (~autoconnect)\n portNumber = portNumber + 1;\n" - " port_label('output', portNumber, 'status');\nend\n\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'/portname'|1|off|on|on|on" - } - Block { - BlockType S-Function - Name "Yarp Write" - SID "1659" - Ports [1] - Position [230, 76, 290, 124] - ZOrder 27 - ForegroundColor "[0.490196, 0.000000, 0.000000]" - FunctionName "WBToolbox" - Parameters "'YarpWrite',portName,autoconnect,errorOnConnection" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "YARP Write" - MaskDescription "This block behaves as the command 'yarp write'. \n\nBy default this block opens a port names as " - "the \"Opened Port Name\" parameter\nand stream the input signal to that port.\nIf the option \"Autoconnect\" is spe" - "cified, the first parameter become the\nname of the target port to which the data will be stramed, \ne.g. like \"ya" - "rp write ... /destinationPort\"\n" - MaskPromptString "Opened Port Name|Autoconnect|Error on missing connection" - MaskStyleString "edit,checkbox,checkbox" - MaskVariables "portName=@1;autoconnect=@2;errorOnConnection=@3;" - MaskTunableValueString "on,on,on" - MaskCallbackString "|autoconnect_val = get_param(gcb, 'Autoconnect');\nprompt_string = get_param(gcb, 'MaskPrompt" - "s');\nif(strcmp(autoconnect_val, 'on'))\n prompt_string{1} = 'Destination Port Name';\n set_param(gcb, 'MaskV" - "isibilities',{'on';'on';'on'});\nelse\n prompt_string{1} = 'Opened Port Name';\n set_param(gcb, 'MaskVisibili" - "ties',{'on';'on';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val prompt_string|" - MaskEnableString "on,on,on" - MaskVisibilityString "on,on,off" - MaskToolTipString "on,on,on" - MaskSelfModifiable on - MaskDisplay "disp('Yarp Write')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'/portname'|off|on" - } - Block { - BlockType SubSystem - Name "errors" - SID "714" - Ports [2, 2] - Position [200, 153, 260, 197] - ZOrder -9 - BackgroundColor "[0.300000, 0.580000, 1.000000]" - RequestExecContextInheritance off - Variant off - MaskType "Errors" - MaskDescription "Computes two kinds of errors. The first is just the difference between x\nand y while the second" - " is the ratio (x-y)/y." - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "errors" - Location [0, 29, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "x" - SID "715" - Position [30, 28, 60, 42] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y" - SID "716" - Position [25, 103, 55, 117] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Sum - Name "Add" - SID "717" - Ports [2, 1] - Position [95, 27, 125, 58] - ZOrder -3 - Inputs "+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Product - Name "Divide" - SID "718" - Ports [2, 1] - Position [165, 37, 195, 68] - ZOrder -4 - Inputs "*/" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - RndMeth "Floor" - SaturateOnIntegerOverflow off - } - Block { - BlockType Outport - Name "x-y" - SID "719" - Position [225, 13, 255, 27] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "(x-y)./y" - SID "720" - Position [220, 48, 250, 62] - ZOrder -6 - Port "2" - IconDisplay "Port number" - } - Line { - SrcBlock "Add" - SrcPort 1 - Points [10, 0] - Branch { - DstBlock "Divide" - DstPort 1 - } - Branch { - Points [0, -25] - DstBlock "x-y" - DstPort 1 - } - } - Line { - SrcBlock "x" - SrcPort 1 - DstBlock "Add" - DstPort 1 - } - Line { - SrcBlock "y" - SrcPort 1 - Points [15, 0] - Branch { - Points [0, -60] - DstBlock "Add" - DstPort 2 - } - Branch { - Points [60, 0; 0, -50] - DstBlock "Divide" - DstPort 2 - } - } - Line { - SrcBlock "Divide" - SrcPort 1 - DstBlock "(x-y)./y" - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "holder\n" - SID "1296" - Ports [1, 1] - Position [105, 152, 165, 198] - ZOrder 14 - BackgroundColor "[0.537255, 0.721569, 1.000000]" - RequestExecContextInheritance off - Variant off - MaskType "Holder" - MaskDescription "This block holds the first input value during the simulation." - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "holder\n" - Location [12, 45, 1340, 980] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "s" - SID "1297" - Position [145, 43, 175, 57] - ZOrder 13 - IconDisplay "Port number" - } - Block { - BlockType Clock - Name "Clock" - SID "1298" - Position [45, 65, 65, 85] - ZOrder 11 - } - Block { - BlockType Reference - Name "Compare\nTo Constant" - SID "1299" - Ports [1, 1] - Position [90, 60, 120, 90] - ZOrder 10 - LibraryVersion "1.388" - SourceBlock "simulink/Logic and Bit\nOperations/Compare\nTo Constant" - SourceType "Compare To Constant" - relop "==" - const "0" - OutDataTypeStr "boolean" - ZeroCross on - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "1300" - Ports [2, 1] - Position [235, 37, 305, 88] - ZOrder 15 - LibraryVersion "1.32" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - MaskType "Stateflow" - MaskDescription "Embedded MATLAB block" - MaskSelfModifiable on - MaskDisplay "bgColor = Simulink.Root.ColorString2Rgb(get_param(gcbh, 'BackgroundColor')); image(imread('p" - "rivate/eml_membrane_16.png','png','BackgroundColor',bgColor(1:3)),'center'); disp([10 10 'fcn']);" - MaskIconFrame on - MaskIconOpaque off - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "normalized" - System { - Name "MATLAB Function" - Location [12, 45, 1135, 3068] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "1773" - Block { - BlockType Inport - Name "s" - SID "1300::24" - Position [20, 101, 40, 119] - ZOrder 10 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "unused" - SID "1300::26" - Position [20, 136, 40, 154] - ZOrder 12 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "1300::1609" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 86 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "1300::1608" - Tag "Stateflow S-Function WBToolboxLibrary 1" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 85 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport off - Port { - PortNumber 2 - Name "s0" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "1300::1610" - Position [460, 241, 480, 259] - ZOrder 87 - } - Block { - BlockType Outport - Name "s0" - SID "1300::25" - Position [460, 101, 480, 119] - ZOrder 11 - IconDisplay "Port number" - } - Line { - SrcBlock "s" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - SrcBlock "unused" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "s0" - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "s0" - DstPort 1 - } - Line { - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType Outport - Name "s(0)" - SID "1301" - Position [330, 58, 360, 72] - ZOrder 14 - IconDisplay "Port number" - } - Line { - SrcBlock "Clock" - SrcPort 1 - DstBlock "Compare\nTo Constant" - DstPort 1 - } - Line { - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "s(0)" - DstPort 1 - } - Line { - SrcBlock "s" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 1 - } - Line { - SrcBlock "Compare\nTo Constant" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 2 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "wholeBodyActuators" - SID "224" - Ports [] - Position [250, 16, 348, 113] - ZOrder -17 - ForegroundColor "white" - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('wholeBodyActuators.png'),'center')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "wholeBodyActuators" - Location [425, 373, 1725, 1134] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "667" - Block { - BlockType SubSystem - Name "Set LowLevel PIDs" - SID "1752" - Ports [] - Position [745, 230, 820, 280] - ZOrder 41 - BackgroundColor "[0.827500, 0.576500, 0.603900]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" - RequestExecContextInheritance off - Variant off - MaskType "Set Low Level PIDs" - MaskDescription "This block sets the low level PID values for the robot actuators.\n\nIf only one gain file is sp" - "ecified, those gains are loaded at startup.\nOtherwise an additional port to this block is added which accept an in" - "teger\nrepresenting the index in the list of gains to be loaded (also at runtime)\n\nAssuming DoFs is the number of" - " degrees of freedom of the robot,\nParameters:\n- PID Parameter: String specifying either a file containing the PID" - "s for the\n low level control, or a list of files (in yarp Bottle format).\n\n- Robot Port Name: Na" - "me of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name spec" - "ified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports " - "opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of th" - "e Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "PID parameter|PID Type|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "edit,popup(Position|Torque),edit,edit,edit,edit" - MaskVariables "pidParameters=@1;pidType=&2;robotName=@3;localName=@4;wbiFile=@5;wbiList=@6;" - MaskTunableValueString "off,on,off,off,off,off" - MaskCallbackString "|% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(" - "gcb,'pidType');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0" - "]');\nelseif strcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0" - "]');\nelseif strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\ne" - "lseif strcmp(maskStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear" - " maskStr||||" - MaskEnableString "on,on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on,on" - MaskToolTipString "on,on,on,on,on,on" - MaskDisplay "pidType = get_param(gcb,'pidType');\ndescription = sprintf('Set Low Level\\n%s PIDs', pidType);\ndi" - "sp(description);\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "''|Torque|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" - System { - Name "Set LowLevel PIDs" - Location [0, 29, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "1000" - Block { - BlockType S-Function - Name "S-Function" - SID "1753" - Ports [] - Position [125, 39, 185, 71] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'SetLowLevelPID',robotName,localName,wbiFile,wbiList,pidParameters,pidType" - SFunctionDeploymentMode off - EnableBusSupport off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Set References" - SID "1767" - Ports [1] - Position [645, 230, 720, 280] - ZOrder 43 - BackgroundColor "[0.513700, 0.851000, 0.670600]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" - RequestExecContextInheritance off - Variant off - MaskType "Set References" - MaskDescription "This block sets the references for the robot actuators.\nThe type of control mode is specified a" - "s a parameter in the block.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Reference" - "s: Vector of size DoFs, representing the references to be sent \n to the robot controlled joints.\n\n" - "Parameters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the p" - "orts opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in th" - "e \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by t" - "he underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Bod" - "y Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Control Mode|Control Type|Controlled Joint List|Robot Port Name|Model Name|WBI filename|WBI lis" - "t name" - MaskStyleString "popup(Position|Position Direct|Velocity|Torque|Open Loop),popup(Full|Sublist),edit,edit,edit,edi" - "t,edit" - MaskVariables "controlType=&1;fullOrSubControl=@2;controlledJoints=@3;robotName=@4;localName=@5;wbiFile=@6;wbiLi" - "st=@7;" - MaskTunableValueString "on,on,on,off,off,off,off" - MaskCallbackString "% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(g" - "cb,'controlType');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, " - "1.0]');\nelseif strcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, " - "1.0]');\nelseif strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');" - "\nelseif strcmp(maskStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nelseif " - "strcmp(maskStr, 'Open Loop')\n set_param(gcb,'BackgroundColor', '[0.98, 0.98, 0.98, 1.0]');\nend\nclear maskStr" - "|subOrFull = get_param(gcb, 'fullOrSubControl');\nif(strcmp(subOrFull, 'Sublist'))\n set_param(gcb, 'MaskVisibil" - "ities',{'on';'on';'on';'on';'on';'on';'on'});\nelse\n set_param(gcb, 'MaskVisibilities',{'on';'on';'off';'on';'o" - "n';'on';'on'});\nend\nclear subOrFull |||||" - MaskEnableString "on,on,on,on,on,on,on" - MaskVisibilityString "on,on,off,on,on,on,on" - MaskToolTipString "on,on,on,on,on,on,on" - MaskDisplay "disp(get_param(gcb,'controlType'))\n%port_label('input',1,'References')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "Position|Full|''|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,Block parameters,Block parameters,WBI parameters,WBI parameters,WBI parameter" - "s,WBI parameters" - System { - Name "Set References" - Location [535, 41, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "521" - Block { - BlockType Inport - Name "References" - SID "1768" - Position [55, 48, 85, 62] - ZOrder 24 - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1769" - Ports [1] - Position [125, 39, 185, 71] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'SetReferences',robotName,localName,wbiFile,wbiList,controlType,fullOrSubControl,controlledJo" - "ints" - SFunctionDeploymentMode off - EnableBusSupport off - } - Line { - SrcBlock "References" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "wholeBodyModel" - SID "209" - Ports [] - Position [133, 16, 231, 113] - ZOrder -3 - ForegroundColor "white" - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('wholeBodyModel.png'),'center')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "wholeBodyModel" - Location [425, 373, 1725, 1134] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "309" - Block { - BlockType SubSystem - Name "Dynamics" - SID "369" - Ports [] - Position [364, 21, 471, 128] - ZOrder -1 - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('Dynamics.png'))" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "Dynamics" - Location [425, 373, 1725, 1134] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "219" - Block { - BlockType SubSystem - Name "Centroidal Momentum" - SID "1694" - Ports [4, 1] - Position [495, 101, 680, 164] - ZOrder 72 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Centroidal Momentum" - MaskDescription "This block computed the 6 element centroidal momentum, as defined in:\n\"Centroidal dyna" - "mics of a humanoid robot\" - DE Orin, A Goswami, SH Lee - \nAutonomous Robots 35 (2-3), 161-176\n\nAssuming DoF" - "s is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenou" - "s transformation between\n the base frame and the world frame.\n- Joint configuration: Vector of si" - "ze DoFs, representing the configuration \n of the joints.\n- Base velocity: Vector of siz" - "e 6 representing the linear and angular velocity\n of the base frame.\n- Joints velocity: Vecto" - "r of size DoFs, representing the velocity \n of the joints.\n\nOutput:\n- Centroidal Momentum" - ": 6-element vector containg the centroidal momentum \n (3 value for linear momentum and 3 for an" - "gular momentum)\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n " - " Set an empty string ('') to use the name specified in the \n Whole Body Interface" - " configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- " - "WBI filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Name: name " - "of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "edit,edit,edit,edit" - MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;" - MaskTunableValueString "off,off,off,off" - MaskCallbackString "|||" - MaskEnableString "on,on,on,on" - MaskVisibilityString "on,on,on,on" - MaskToolTipString "on,on,on,on" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - System { - Name "Centroidal Momentum" - Location [0, 23, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "248" - Block { - BlockType Inport - Name "Base Pose" - SID "1695" - Position [20, 18, 50, 32] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1696" - Position [20, 53, 50, 67] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Base velocity" - SID "1697" - Position [20, 88, 50, 102] - ZOrder 26 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joints velocity" - SID "1698" - Position [20, 123, 50, 137] - ZOrder 27 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1699" - Ports [4, 1] - Position [180, 11, 255, 144] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'CentroidalMomentum',robotName,localName,wbiFile,wbiList" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Centroidal Momentum" - SID "1700" - Position [315, 73, 345, 87] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Centroidal Momentum" - DstPort 1 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - DstBlock "S-Function" - DstPort 2 - } - Line { - SrcBlock "Base velocity" - SrcPort 1 - DstBlock "S-Function" - DstPort 3 - } - Line { - SrcBlock "Joints velocity" - SrcPort 1 - DstBlock "S-Function" - DstPort 4 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Get Bias Forces" - SID "1724" - Ports [4, 1] - Position [400, 202, 540, 303] - ZOrder 73 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Get Generalized Bias Forces" - MaskDescription "This block retrieves the generalied bias forces of the robot.\n\nParameter:\n- Explicit " - "Gravity. If True, an additional port (explicit Gravity) is added.\n Otherwise the vector [0;" - " 0; -9.81] is used.\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 " - "matrix representing the homogenous transformation between\n the base frame and the world frame.\n- J" - "oint configuration: Vector of size DoFs, representing the configuration \n of the joints.\n-" - " Base velocity: Vector of size 6 representing the linear and angular velocity\n of the base fra" - "me.\n- Joints velocity: Vector of size DoFs, representing the velocity of the joints.\n\nOutput:\n- Bias Forces" - ": a Dofs + 6 vector representing the generalized bias forces\n of the robot\n\nParameters:\n- Robot " - "Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to " - "use the name specified in the \n Whole Body Interface configuration file." - "\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name o" - "f the file containing the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joint" - "s used to configure the Whole Body Interface\n" - MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name|Explicit Gravity" - MaskStyleString "edit,edit,edit,edit,checkbox" - MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;explicitGravity=@5;" - MaskTunableValueString "off,off,off,off,on" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskInitialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on'," - " ...\n'Name', 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb" - ",'/S-Function']);\n add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S" - "-Function/7', 'autorouting','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gra" - "vity/1','S-Function/7');\n delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function'])" - ";\n end\nend\n" - MaskSelfModifiable on - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList|off" - System { - Name "Get Bias Forces" - Location [354, 32, 1634, 747] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "255" - SIDHighWatermark "1748" - Block { - BlockType Inport - Name "Base Pose" - SID "1724:1725" - Position [35, 38, 65, 52] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1724:1726" - Position [35, 68, 65, 82] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Base velocity" - SID "1724:1727" - Position [35, 98, 65, 112] - ZOrder 26 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joints velocity" - SID "1724:1728" - Position [35, 128, 65, 142] - ZOrder 27 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Constant - Name "Constant" - SID "1724:1742" - Position [20, 157, 75, 173] - ZOrder 30 - ShowName off - Value "zeros(6,1)" - } - Block { - BlockType Gain - Name "Gain" - SID "1724:1743" - Position [135, 180, 165, 210] - ZOrder 31 - ShowName off - Gain "0" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType S-Function - Name "S-Function" - SID "1724:1731" - Ports [6, 1] - Position [205, 24, 265, 216] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Bias Forces" - SID "1724:1732" - Position [325, 113, 355, 127] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Bias Forces" - DstPort 1 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - DstBlock "S-Function" - DstPort 2 - } - Line { - SrcBlock "Base velocity" - SrcPort 1 - DstBlock "S-Function" - DstPort 3 - } - Line { - SrcBlock "Joints velocity" - SrcPort 1 - Points [44, 0] - Branch { - Points [0, 60] - DstBlock "Gain" - DstPort 1 - } - Branch { - DstBlock "S-Function" - DstPort 4 - } - } - Line { - SrcBlock "Constant" - SrcPort 1 - DstBlock "S-Function" - DstPort 5 - } - Line { - SrcBlock "Gain" - SrcPort 1 - DstBlock "S-Function" - DstPort 6 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Get Gravity Forces" - SID "1733" - Ports [2, 1] - Position [605, 200, 745, 300] - ZOrder 74 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Gravity bias" - MaskDescription "This block compute the generalized bias forces due to the gravity\n\nParameter:\n- Expli" - "cit Gravity. If True, an additional port (explicit Gravity) is added.\n Otherwise the vector" - " [0; 0; -9.81] is used.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose" - ": 4x4 matrix representing the homogenous transformation between\n the base frame and the world fram" - "e.\n- Joint configuration: Vector of size DoFs, representing the configuration \n of the " - "joints.\n\nOutput:\n- Gravity: a Dofs + 6 vector representing the torques due to the gravity.\n\nParameters:\n-" - " Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (" - "'') to use the name specified in the \n Whole Body Interface configuration file.\n- Model Nam" - "e: Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file co" - "ntaining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to con" - "figure the Whole Body Interface\n" - MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name|Explicit Gravity" - MaskStyleString "edit,edit,edit,edit,checkbox" - MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;explicitGravity=@5;" - MaskTunableValueString "off,off,off,off,on" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskInitialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on'," - " ...\n'Name', 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb" - ",'/S-Function']);\n add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S" - "-Function/7', 'autorouting','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gra" - "vity/1','S-Function/7');\n delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function'])" - ";\n end\nend\n" - MaskSelfModifiable on - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList|off" - System { - Name "Get Gravity Forces" - Location [354, 32, 1634, 747] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "255" - SIDHighWatermark "1748" - Block { - BlockType Inport - Name "Base Pose" - SID "1733:1734" - Position [10, 38, 40, 52] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1733:1735" - Position [10, 68, 40, 82] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Constant - Name "Constant" - SID "1733:1744" - Position [0, 97, 55, 113] - ZOrder 32 - ShowName off - Value "zeros(6,1)" - } - Block { - BlockType Gain - Name "Gain" - SID "1733:1745" - Position [100, 120, 130, 150] - ZOrder 33 - ShowName off - Gain "0" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType S-Function - Name "S-Function" - SID "1733:1740" - Ports [6, 1] - Position [180, 24, 240, 216] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Gravity Torques" - SID "1733:1741" - Position [300, 113, 330, 127] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Gravity Torques" - DstPort 1 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - Points [41, 0] - Branch { - Points [0, 60] - DstBlock "Gain" - DstPort 1 - } - Branch { - DstBlock "S-Function" - DstPort 2 - } - } - Line { - SrcBlock "Constant" - SrcPort 1 - Points [4, 0] - Branch { - Points [0, 60] - DstBlock "S-Function" - DstPort 5 - } - Branch { - DstBlock "S-Function" - DstPort 3 - } - } - Line { - SrcBlock "Gain" - SrcPort 1 - Points [13, 0] - Branch { - Points [0, 60] - DstBlock "S-Function" - DstPort 6 - } - Branch { - DstBlock "S-Function" - DstPort 4 - } - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType S-Function - Name "Inverse Dynamics" - SID "1748" - Ports [6, 1] - Position [190, 199, 355, 331] - ZOrder 75 - FunctionName "WBToolbox" - Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" - SFunctionDeploymentMode off - EnableBusSupport off - MaskType "Inverse Dynamics" - MaskDescription "This block compute the inverse dynamics of the robot.\n\nParameter:\n- Explicit Gravity." - " If True, an additional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.8" - "1] is used.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix" - " representing the homogenous transformation between\n the base frame and the world frame.\n- Joint " - "configuration: Vector of size DoFs, representing the configuration \n of the joints.\n- B" - "ase velocity: Vector of size 6 representing the linear and angular velocity\n of the base frame" - ".\n- Joints velocity: Vector of size DoFs, representing the velocity \n of the joints.\n- Bas" - "e acceleration: Vector of size 6 representing the linear and angular acceleration\n of the base" - " frame.\n- Joints acceleration: Vector of size DoFs, representing the acceleration \n of the " - "joints.\n- Gravity: Vector of size 3, denoting the acceleration vector w.r.t. the world frame.\n\n\nOutput:\n- " - "Torques: a Dofs + 6 vector representing the corresponding torques required\n to achive the desired ac" - "celerations given the robot state\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot. (e." - "g. icub).\n Set an empty string ('') to use the name specified in the \n Wh" - "ole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole B" - "ody Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n- WB" - "I List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name|Explicit Gravity" - MaskStyleString "edit,edit,edit,edit,checkbox" - MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;explicitGravity=@5;" - MaskTunableValueString "on,on,on,on,on" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "port_label('output', 1, 'Torques')\n\nport_label('input', 1, 'Base pose')\nport_label('input" - "', 2, 'Joints configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joints velocity" - "')\nport_label('input', 5, 'Base acceleration')\nport_label('input', 6, 'Joints acceleration')\n\n\ngravity = g" - "et_param(gcb, 'explicitGravity');\nif(strcmp(gravity, 'on'))\n port_label('input', 7, 'Gravity')\nend\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList|off" - } - Block { - BlockType SubSystem - Name "Mass Matrix" - SID "1633" - Ports [2, 1] - Position [250, 104, 390, 171] - ZOrder 32 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Mass Matrix" - MaskDescription "This block retrieves the robot mass matrix.\n\nAssuming DoFs is the number of degrees of" - " freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n " - " the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the con" - "figuration \n of the joints.\n\nOutput:\n- Mass Matrix: a (Dofs + 6) x (Dofs + 6) matrix " - "representing the mass matrix \n of the robot\n\nParameters:\n- Robot Port Name: Name of the ports" - " opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in th" - "e \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened " - "by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the W" - "hole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "edit,edit,edit,edit" - MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;" - MaskTunableValueString "off,off,off,off" - MaskCallbackString "|||" - MaskEnableString "on,on,on,on" - MaskVisibilityString "on,on,on,on" - MaskToolTipString "on,on,on,on" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - System { - Name "Mass Matrix" - Location [589, 68, 1869, 783] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "248" - Block { - BlockType Inport - Name "Base Pose" - SID "1634" - Position [20, 23, 50, 37] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1635" - Position [20, 63, 50, 77] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1636" - Ports [2, 1] - Position [125, 37, 185, 68] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'MassMatrix',robotName,localName,wbiFile,wbiList" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Mass Matrix" - SID "1637" - Position [245, 48, 275, 62] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Mass Matrix" - DstPort 1 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - Points [36, 0; 0, 15] - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - Points [33, 0; 0, -10] - DstBlock "S-Function" - DstPort 2 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Jacobians" - SID "202" - Ports [] - Position [217, 20, 324, 127] - ZOrder -3 - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('jacobian.png'))" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "Jacobians" - Location [425, 373, 1725, 1134] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "322" - Block { - BlockType SubSystem - Name "DotJ Nu" - SID "1683" - Ports [4, 1] - Position [590, 170, 755, 265] - ZOrder 67 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "DotJ Nu" - MaskDescription "This block computes the product between the time derivative of the\n Jacobian of" - " the specified frame and the state (base and joints)\n velocity vector.\n\nAssuming DoFs is the number o" - "f degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation " - "between\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, repr" - "esenting the configuration \n of the joints.\n- Base velocity: Vector of size 6 represent" - "ing the linear and angular velocity\n of the base frame.\n- Joints velocity: Vector of size DoF" - "s, representing the velocity \n of the joints.\n\nOutput:\n- dotJ nu: a 6-d vector representi" - "ng the product between the time derivative of the\n Jacobian of the specified frame and the state veloc" - "ity vector\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- " - "Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('" - "') to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name" - ": Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file con" - "taining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to conf" - "igure the Whole Body Interface\n" - MaskPromptString "Frame name|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "edit,edit,edit,edit,edit" - MaskVariables "frameName=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" - MaskTunableValueString "on,off,off,off,off" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('dot J_{'," - "escapedFrameName,'} \\nu'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\np" - "ort_label('input', 2, 'Joint configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, '" - "Joint velocity')\n\nclear escapedFrameName;" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'frame'|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" - System { - Name "DotJ Nu" - Location [0, 29, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "391" - Block { - BlockType Inport - Name "Base Pose" - SID "1684" - Position [20, 13, 50, 27] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1685" - Position [20, 43, 50, 57] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Base velocity" - SID "1686" - Position [20, 73, 50, 87] - ZOrder 26 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joints velocity" - SID "1687" - Position [20, 103, 50, 117] - ZOrder 27 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1688" - Ports [4, 1] - Position [125, 4, 190, 126] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'DotJNu',robotName,localName,wbiFile,wbiList,frameName" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "dotJ dotnu" - SID "1689" - Position [245, 43, 275, 57] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - DstBlock "S-Function" - DstPort 2 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "S-Function" - SrcPort 1 - Points [20, 0; 0, -15] - DstBlock "dotJ dotnu" - DstPort 1 - } - Line { - SrcBlock "Base velocity" - SrcPort 1 - DstBlock "S-Function" - DstPort 3 - } - Line { - SrcBlock "Joints velocity" - SrcPort 1 - DstBlock "S-Function" - DstPort 4 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Jacobian" - SID "1663" - Ports [2, 1] - Position [380, 190, 540, 245] - ZOrder 39 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Jacobian" - MaskDescription "This block retrieves the Jacobian of the specified frame.\n\nAssuming DoFs is the number" - " of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformatio" - "n between\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, re" - "presenting the configuration \n of the joints.\n\nOutput:\n- Jacobian: a 6x6+dofs matrix " - "representing the Jacobian of\n the specified frame written in the world frame.\n\nParameters:\n- Fr" - "ame name: the name of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the po" - "rts opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in" - " the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports open" - "ed by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of th" - "e Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Frame name|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "edit,edit,edit,edit,edit" - MaskVariables "frameName=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" - MaskTunableValueString "on,off,off,off,off" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world" - "} J_{',escapedFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n" - "port_label('input', 2, 'Joint configuration')\n\nclear escapedFrameName;" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'frame'|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" - System { - Name "Jacobian" - Location [208, 105, 1008, 627] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "237" - Block { - BlockType Inport - Name "Base Pose" - SID "1664" - Position [20, 23, 50, 37] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1665" - Position [20, 63, 50, 77] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1666" - Ports [2, 1] - Position [125, 37, 185, 68] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'Jacobian',robotName,localName,wbiFile,wbiList,frameName" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Forward Kinematics" - SID "1667" - Position [245, 48, 275, 62] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Forward Kinematics" - DstPort 1 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - Points [36, 0; 0, 15] - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - Points [33, 0; 0, -10] - DstBlock "S-Function" - DstPort 2 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Kinematics" - SID "176" - Ports [] - Position [70, 20, 177, 127] - ZOrder -17 - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('forwardKinematics.png'))" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "Kinematics" - Location [425, 373, 1725, 1134] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "326" - Block { - BlockType SubSystem - Name "Forward Kinematics" - SID "1647" - Ports [2, 1] - Position [350, 103, 500, 167] - ZOrder 34 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Forward Kinematics" - MaskDescription "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is " - "the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous tra" - "nsformation between\n the the base frame and the world frame.\n- Joint configuration: Vector of siz" - "e DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Forward Kinematics" - ": a 4x4 matrix representing the homogenous transformation between\n the specified frame and the wor" - "ld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- R" - "obot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (''" - ") to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name:" - " Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file cont" - "aining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to confi" - "gure the Whole Body Interface\n" - MaskPromptString "Frame name|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "edit,edit,edit,edit,edit" - MaskVariables "frameName=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" - MaskTunableValueString "on,off,off,off,off" - MaskCallbackString "||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world" - "} H_{',escapedFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n" - "port_label('input', 2, 'Joint configuration')\n\nclear escapedFrameName;" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'frame'|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" - System { - Name "Forward Kinematics" - Location [0, 29, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "391" - Block { - BlockType Inport - Name "Base Pose" - SID "1648" - Position [20, 23, 50, 37] - ZOrder 22 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Joint configuration" - SID "1649" - Position [20, 63, 50, 77] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1650" - Ports [2, 1] - Position [125, 37, 185, 68] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'ForwardKinematics',robotName,localName,wbiFile,wbiList,frameName" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Forward Kinematics" - SID "1651" - Position [245, 48, 275, 62] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Forward Kinematics" - DstPort 1 - } - Line { - SrcBlock "Base Pose" - SrcPort 1 - Points [36, 0; 0, 15] - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Joint configuration" - SrcPort 1 - Points [33, 0; 0, -10] - DstBlock "S-Function" - DstPort 2 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Inverse Kinematics" - SID "1754" - Ports [3, 2] - Position [350, 198, 525, 262] - ZOrder 35 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Forward Kinematics" - MaskDescription "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is " - "the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous tra" - "nsformation between\n the the base frame and the world frame.\n- Joint configuration: Vector of siz" - "e DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Forward Kinematics" - ": a 4x4 matrix representing the homogenous transformation between\n the specified frame and the wor" - "ld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- R" - "obot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (''" - ") to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name:" - " Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file cont" - "aining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to confi" - "gure the Whole Body Interface\n" - MaskPromptString "Base Frame|End Effector frame|Optimization Option|Robot Port Name|Model Name|WBI filena" - "me|WBI list name" - MaskStyleString "edit,edit,popup(Full Constraint (Position and Orientation)|Position only constraint),edi" - "t,edit,edit,edit" - MaskVariables "baseFrame=@1;endEffFrame=@2;optOption=@3;robotName=@4;localName=@5;wbiFile=@6;wbiList=@7;" - MaskTunableValueString "on,on,on,off,off,off,off" - MaskCallbackString "||||||" - MaskEnableString "on,on,on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on,on,on" - MaskToolTipString "on,on,on,on,on,on,on" - MaskDisplay "escapedBaseFrameName = strrep(baseFrame, '_', '\\_');\nescapedEndEffFrameName = strrep(endEf" - "fFrame, '_', '\\_');\n\n%port_label('output', 1, strcat('{}^{world} H_{',escapedFrameName,'}'), 'texmode','on')" - "\n\n%port_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n%port_label('input', 2, 'Joint configuratio" - "n')\n\n%clear escapedFrameName;\n\n\n% if strcmp(robotPart, 'left')\n% prefix = 'l';\n% else\n% prefix " - "= 'r';\n% end\n% \nport_label('input', 1, strcat('{}^{',escapedBaseFrameName,'} H_{',escapedEndEffFrameName,'}^" - "d'), 'texmode','on');\n\nport_label('input', 2, '{}^{world} H_{base}', 'texmode','on')\nport_label('input', 3, " - "'q_j', 'texmode','on');\n% \n% \nport_label('output', 1, '{}^{world} H_{base}^d', 'texmode','on')\nport_label('" - "output', 2, 'q_j^d', 'texmode','on');\n\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'root_link'|'l_sole'|Full Constraint (Position and Orientation)|WBT_robotName|WBT_modelN" - "ame|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,Block parameters,Block parameters,WBI parameters,WBI parameters,WBI p" - "arameters,WBI parameters" - System { - Name "Inverse Kinematics" - Location [0, 23, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "312" - Block { - BlockType Inport - Name "Desired frame pose" - SID "1759" - Position [10, 13, 40, 27] - ZOrder 26 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Current Base Pose" - SID "1755" - Position [10, 43, 40, 57] - ZOrder 22 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Current Joint configuration" - SID "1756" - Position [10, 73, 40, 87] - ZOrder 24 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1757" - Ports [3, 2] - Position [145, 4, 225, 96] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'InverseKinematics',robotName,localName,wbiFile,wbiList,baseFrame, endEffFrame,optOption" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Desired Base Pose" - SID "1758" - Position [280, 23, 310, 37] - ZOrder 25 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "Desired Joint Configuration" - SID "1760" - Position [280, 68, 310, 82] - ZOrder 27 - Port "2" - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Desired Base Pose" - DstPort 1 - } - Line { - SrcBlock "Current Base Pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 2 - } - Line { - SrcBlock "Current Joint configuration" - SrcPort 1 - DstBlock "S-Function" - DstPort 3 - } - Line { - SrcBlock "Desired frame pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "S-Function" - SrcPort 2 - DstBlock "Desired Joint Configuration" - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Remote Inverse Kinematics" - SID "1761" - Ports [2, 1] - Position [560, 105, 720, 165] - ZOrder 66 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - MaskType "Forward Kinematics" - MaskDescription "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is " - "the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous tra" - "nsformation between\n the the base frame and the world frame.\n- Joint configuration: Vector of siz" - "e DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Forward Kinematics" - ": a 4x4 matrix representing the homogenous transformation between\n the specified frame and the wor" - "ld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- R" - "obot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (''" - ") to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name:" - " Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file cont" - "aining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to confi" - "gure the Whole Body Interface\n" - MaskPromptString "Solver Name|#Dofs|Optimization Option" - MaskStyleString "edit,edit,popup(Full Constraint (Position and Orientation)|Position only constraint)" - MaskVariables "solverName=@1;dofs=@2;optOption=@3;" - MaskTunableValueString "on,off,on" - MaskCallbackString "||" - MaskEnableString "on,on,on" - MaskVisibilityString "on,on,on" - MaskToolTipString "on,on,on" - MaskDisplay "disp(solverName)\n\n\n\n% escapedBaseFrameName = strrep(baseFrame, '_', '\\_');\n% escapedEn" - "dEffFrameName = strrep(endEffFrame, '_', '\\_');\n% \n% %port_label('output', 1, strcat('{}^{world} H_{',escape" - "dFrameName,'}'), 'texmode','on')\n% \n% %port_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n% %port" - "_label('input', 2, 'Joint configuration')\n% \n% %clear escapedFrameName;\n% \n% \n% % if strcmp(robotPart, 'le" - "ft')\n% % prefix = 'l';\n% % else\n% % prefix = 'r';\n% % end\n% % \n\nport_label('input', 1, 'H^d', 't" - "exmode','on');\n% port_label('input', 1, strcat('{}^{',escapedBaseFrameName,'} H_{',escapedEndEffFrameName,'}^d" - "'), 'texmode','on');\n% \n% port_label('input', 2, '{}^{world} H_{base}', 'texmode','on')\nport_label('input', " - "2, 'q_j(0)', 'texmode','on');\n% % \n% % \n% port_label('output', 1, '{}^{world} H_{base}^d', 'texmode','on')\n" - "port_label('output', 1, 'q_j^d', 'texmode','on');\n\n" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "'/cartesianSolver'|12|Full Constraint (Position and Orientation)" - MaskTabNameString "Block parameters,Block parameters,Block parameters" - System { - Name "Remote Inverse Kinematics" - Location [853, 51, 2214, 1013] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "375" - Block { - BlockType Inport - Name "Desired frame pose" - SID "1762" - Position [10, 23, 40, 37] - ZOrder 26 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Current Joint configuration" - SID "1763" - Position [10, 68, 40, 82] - ZOrder 24 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType S-Function - Name "S-Function" - SID "1764" - Ports [2, 1] - Position [145, 6, 225, 99] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'RemoteInverseKinematics',solverName, dofs, optOption" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Desired Joint Configuration" - SID "1765" - Position [285, 48, 315, 62] - ZOrder 27 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Desired Joint Configuration" - DstPort 1 - } - Line { - SrcBlock "Desired frame pose" - SrcPort 1 - DstBlock "S-Function" - DstPort 1 - } - Line { - SrcBlock "Current Joint configuration" - SrcPort 1 - DstBlock "S-Function" - DstPort 2 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "wholeBodyStates" - SID "206" - Ports [] - Position [16, 17, 114, 114] - ZOrder -4 - ForegroundColor "white" - DropShadow on - RequestExecContextInheritance off - Variant off - MaskDisplay "image(imread('wholeBodyStates.png'),'center');" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - System { - Name "wholeBodyStates" - Location [425, 373, 1725, 1134] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "576" - Block { - BlockType SubSystem - Name "Get Estimate" - SID "1671" - Ports [0, 1] - Position [360, 212, 440, 248] - ZOrder 53 - BackgroundColor "[0.513700, 0.851000, 0.670600]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" - RequestExecContextInheritance off - Variant off - MaskType "Get Estimate" - MaskDescription "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of f" - "reedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParameter" - "s:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports open" - "ed by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " - " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underl" - "ying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interfa" - "ce\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Estimate Type|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "popup(Joints Position|Joints Velocity|Joints Acceleration|Joints Torque),edit,edit,edit,edit" - MaskVariables "estimateType=&1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" - MaskTunableValueString "on,off,off,off,off" - MaskCallbackString "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param" - "(gcb,'estimateType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510" - ", 0.6706, 1.0]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745" - ", 1.0000, 1.0]');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0." - "8706, 0.1333, 1.0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.57" - "65, 0.6039, 1.0]');\nend\nclear maskStr||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "%disp(get_param(gcb,'estimateType'))\nport_label('output',1,get_param(gcb,'estimateType'))" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "Joints Position|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" - System { - Name "Get Estimate" - Location [653, 318, 2086, 1271] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "1000" - Block { - BlockType S-Function - Name "S-Function" - SID "1672" - Ports [0, 1] - Position [125, 39, 185, 71] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'GetEstimate',robotName,localName,wbiFile,wbiList,estimateType" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Estimate" - SID "1673" - Position [210, 48, 240, 62] - ZOrder 25 - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Estimate" - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Block { - BlockType SubSystem - Name "Get Limits" - SID "1690" - Ports [0, 2] - Position [475, 211, 570, 249] - ZOrder 68 - BackgroundColor "[0.513700, 0.851000, 0.670600]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" - RequestExecContextInheritance off - Variant off - MaskType "Get Estimate" - MaskDescription "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of f" - "reedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParameter" - "s:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports open" - "ed by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " - " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underl" - "ying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interfa" - "ce\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - MaskPromptString "Limits Type|Robot Port Name|Model Name|WBI filename|WBI list name" - MaskStyleString "popup(Position),edit,edit,edit,edit" - MaskVariables "limitsType=&1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" - MaskTunableValueString "on,off,off,off,off" - MaskCallbackString "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param" - "(gcb,'limitsType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, " - "0.6706, 1.0]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, " - "1.0000, 1.0]');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.87" - "06, 0.1333, 1.0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765" - ", 0.6039, 1.0]');\nend\nclear maskStr||||" - MaskEnableString "on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on" - MaskToolTipString "on,on,on,on,on" - MaskDisplay "disp(get_param(gcb,'limitsType'))\nport_label('output',1,'Min')\nport_label('output',2,'Max')" - MaskIconFrame on - MaskIconOpaque on - MaskIconRotate "none" - MaskPortRotate "default" - MaskIconUnits "autoscale" - MaskValueString "Position|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" - MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" - System { - Name "Get Limits" - Location [0, 23, 1280, 744] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "411" - Block { - BlockType S-Function - Name "S-Function" - SID "1691" - Ports [0, 2] - Position [115, 33, 175, 102] - ZOrder 19 - FunctionName "WBToolbox" - Parameters "'GetLimits',robotName,localName,wbiFile,wbiList,limitsType" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Outport - Name "Min" - SID "1692" - Position [220, 43, 250, 57] - ZOrder 25 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "Max" - SID "1693" - Position [220, 78, 250, 92] - ZOrder 26 - Port "2" - IconDisplay "Port number" - } - Line { - SrcBlock "S-Function" - SrcPort 1 - DstBlock "Min" - DstPort 1 - } - Line { - SrcBlock "S-Function" - SrcPort 2 - DstBlock "Max" - DstPort 1 - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - } - RTWSystemCode "Auto" - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - FunctionWithSeparateData off - Opaque off - MaskHideContents off - } - Annotation { - SID "1213" - Name "WHOLE BODY TOOLBOX" - Position [241, 157] - ForegroundColor "white" - BackgroundColor "black" - FontName "Sans Serif" - FontSize 12 - } - Annotation { - SID "1214" - Name "Copyright 2013-2016 iCub Facility Department, Istituto Italiano di Tecnologia\nThis software was s" - "upported by the FP7 EU Project CoDyCO (No. 600716 ICT 2011.2.1 Cognitive Systems and Robotics (b))\nhttp://www.c" - "odyco.eu" - Position [240, 192] - ForegroundColor "white" - BackgroundColor "black" - FontSize 5 - } - } -} -#Finite State Machines -# -# Stateflow 80000010 -# -# -Stateflow { - machine { - id 1 - name "WBToolboxLibrary" - created "06-Feb-2014 11:51:26" - isLibrary 1 - sfVersion 76014001.0004 - firstTarget 26 - } - chart { - id 2 - machine 1 - name "Utilities/holder\n/MATLAB Function" - windowPosition [1152 -205 -179 985] - viewLimits [0 156.75 0 153.75] - screen [1 1 3046 1050 1.25] - treeNode [0 3 0 0] - viewObj 2 - toolbarMode LIBRARY_TOOLBAR - ssIdHighWaterMark 9 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 1 - disableImplicitCasting 1 - eml { - name "fcn" - } - firstData 4 - firstTransition 8 - firstJunction 7 - } - state { - id 3 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 2 - treeNode [2 0 0 0] - superState SUBCHART - subviewer 2 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function s0 = fcn(s, ~)\npersistent state\n%#codegen\n\nif isempty(state)\n state = s;\nend\n\n" - "s0 = state;" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 4 - ssIdNumber 7 - name "s" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [2 0 5] - } - data { - id 5 - ssIdNumber 8 - name "s0" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [2 4 6] - } - data { - id 6 - ssIdNumber 9 - name "unused" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [2 5 0] - } - junction { - id 7 - position [23.5747 49.5747 7] - chart 2 - subviewer 2 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [2 0 0] - } - transition { - id 8 - labelString "{eML_blk_kernel();}" - labelPosition [76.125 85.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 7 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 2 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 2 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [2 0 0] - } - instance { - id 9 - machine 1 - name "Utilities/holder\n/MATLAB Function" - chart 2 - } - chart { - id 10 - machine 1 - name "Utilities/DampPinv/Damped Pseudo Inverse" - windowPosition [699 -205 167 985] - viewLimits [0 156.75 0 153.75] - screen [1 1 3046 1050 1.25] - treeNode [0 11 0 0] - viewObj 10 - toolbarMode LIBRARY_TOOLBAR - ssIdHighWaterMark 8 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 6 - disableImplicitCasting 1 - eml { - name "fcn" - } - firstData 12 - firstTransition 16 - firstJunction 15 - } - state { - id 11 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 10 - treeNode [10 0 0 0] - superState SUBCHART - subviewer 10 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function DPinv = fcn(mat,sigma)\n% Economody size svd of mat\n[U,S,V] = svd(mat,'econ');\n% Damp" - "ed version of S with sigma\nS(S>sigma)=S(S>sigma)./((S(S>sigma)).^2+sigma^2);\n% Damped pseudoinverse\nDPinv = V" - "*pinv(S)*U';" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 12 - ssIdNumber 4 - name "mat" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [10 0 13] - } - data { - id 13 - ssIdNumber 5 - name "DPinv" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [10 12 14] - } - data { - id 14 - ssIdNumber 8 - name "sigma" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [10 13 0] - } - junction { - id 15 - position [23.5747 49.5747 7] - chart 10 - subviewer 10 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [10 0 0] - } - transition { - id 16 - labelString "{eML_blk_kernel();}" - labelPosition [80.125 91.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 15 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 10 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 10 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [10 0 0] - } - instance { - id 17 - machine 1 - name "Utilities/DampPinv/Damped Pseudo Inverse" - chart 10 - } - chart { - id 18 - machine 1 - name "Utilities/TruncPinv/Truncated PseudoInverse" - windowPosition [649 -205 167 985] - viewLimits [0 156.75 0 153.75] - screen [1 1 3046 1050 1.25] - treeNode [0 19 0 0] - viewObj 18 - toolbarMode LIBRARY_TOOLBAR - ssIdHighWaterMark 8 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 7 - disableImplicitCasting 1 - eml { - name "fcn" - } - firstData 20 - firstTransition 24 - firstJunction 23 - } - state { - id 19 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 18 - treeNode [18 0 0 0] - superState SUBCHART - subviewer 18 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function TPinv = fcn(mat,tol)\n%#codegen\n[U,S,V] = svd(mat,'econ');\n% Setting to zero value\n%" - " Setting to 1/S(i,i) singular values greater than tol\n S(S>tol)=1./S(S>tol);\n TPinv = V*pinv(S)*U';" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 20 - ssIdNumber 4 - name "mat" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [18 0 21] - } - data { - id 21 - ssIdNumber 5 - name "TPinv" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [18 20 22] - } - data { - id 22 - ssIdNumber 8 - name "tol" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [18 21 0] - } - junction { - id 23 - position [23.5747 49.5747 7] - chart 18 - subviewer 18 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [18 0 0] - } - transition { - id 24 - labelString "{eML_blk_kernel();}" - labelPosition [80.125 91.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 23 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 18 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 18 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [18 0 0] - } - instance { - id 25 - machine 1 - name "Utilities/TruncPinv/Truncated PseudoInverse" - chart 18 - } - target { - id 26 - machine 1 - name "sfun" - description "Default Simulink S-Function Target." - linkNode [1 0 0] - } -} diff --git a/toolbox/WBToolboxLibrary.slx b/toolbox/WBToolboxLibrary.slx deleted file mode 100644 index e19fa448e9e24bc18e7446db8c43a6dec97ec0eb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 38548 zcmaHyLy#^^u%_F_Y1_7K+qP}H`?PJ_`r5W_+qTU!|J}`viI_!2R1_9(zO~4BGD}eg z6buyz2nY(u%@jk%tNC-*5*P?*00amK=f71uGgl*1BUd8^69;EAMP~;`GiO&TGZ%VK zJ6k{H1^Gcn)SuMSJDn|fq--W+HeMlP)Z&L4*K{SVt)B zepSrt!ETG^R7FTaz?MeNmC;n*dNV`NFga)3XQc~_V(^@((~YXCvY4<6tEz@QU>MEf zn@mb_3#(sIM%TmWs2)mH^K>0d>P~z5c7ZhX?%hDRD9ocUymK9A?JRIr14wvuE=-#0 z2Cdid&Vhws;F~oz+TKje~$6FF_OCVn&7I?-pOmkd6>hD*vwNSrWoxM??W z%18>C2LV;D=N=aR?5KJEsQrg_Ezb&&d#3d5cjM1aY{+--1nS-cUrJ-V`v5%f3euOr zft@6|QBF0b(F8nB>>P3)+$R|NYoktUjQ9lU1uUZC7=Z_q&uypv+cz{f-2L3DnSkQ| zGRUc@+jjInVSeqBK=EznPjjv{v` z>f|}Smkb__)!BUF;#;@NXZ(kQ_8R5Id8ejCuyMkx^ZD_v`QLj=5KTgG0+bIIkxT;% z_pTlFyNdFtGGC)5{-HiX%PB+YIs#^37nECjIkU5ciYnGM6ozW{ig$5ZH|r)jK=Osv zj5WdK9^G1|)c)8U|MdZzH&#y;Az0nTx^^8S{&?^i9%<$d7CAg%{!qS60C-jc4l3q! zJ;;7eo372ypT;5Ye+NJd3l zdbNjzh{1-T;PX+uv)O`t4!MyXVZDK31DCmUt-Y@A1HP&I}~9@ZIVv58Ha_ z-U!~0s2y40S-dBQSXfTYjYV{Y_AmP5W1Q%ZYjbX#6DQqpF-|NK-H`2vsfq2d5@Oy@ zQE8WkVcjD@m$;1qe1UTm5&wm#MqsKuQ8eyhrd8>d{+M6<3-rIW*-<7!PwTp#KzRh$imsk?tkRm^!RveaVBwm_X&WK`WL3(CKxu zNe102JMp7r!#|78)!)&b!~O35LFc#h?i~+(aCP$ax86A3b{^+)x()ieY4fIG8lKt` z7^j@C<@K1n#LXh08*?S_D|v4n^%vlQFm|w!Xg&Dy{aiIQ*O@&VJ#cE|wNYEHEm=ux zS5xO+F*Vk=_#L3E$A_x>T57%7)gl=R>kwm+sjK2Cszy;`+`&rl{JL@Yk?&jBUg@;^ z)^LE&df)Sh<-B@xRq23MYUO=4lpmg&1<>WG)k<&s8`t+~_l5>f$<=0JDA#iw`WUC_@fPUqwa>HezVYZ|)!1t+N<;iS zv9#>YcZi40#qBZdI=fmSZr<|=B}e1fgX`cyR$N?q0;+OyyR17-@+@b5bnA1P!K-IHyvB0;oGj&@e`V!E2dyER!bakR_$@Y13 zsxNWJ!9%D7`6I8eI)37Loh-;0Vs0|;;Nf$V#&3DY2I*~~amDs*U%s=l<)dfWTj%k- z2aCb|<8fL?vWBJOfe~i1jpQI11cZPt0Kh`H8(L-sd7OPTN}F@MCH?1%Sam=K@dwt9 zvvd@l2{B*cBC_r0HJspP|7C#IF`ye(A482R>@<}|Z_gL*>OhMXE@r~@%dULI?yjYi zDv9EYh+V*M$p2Y7@*brsSUtxsVnL%SgWn+DB@`sXQUN2&jO`>{J z!Mt-pne^rR>OM+=QZ50Y9@uo7) zVWa(lIO;05qt4etq7#fia0Al}l>KPf;s8s9iH(qSNd2Ghfxy&G#&6pTjyh5119-k^ z%7>FdV(Oql>#v$%<4JV*qsfd9RZYP?J*B|6rU|+S`mv$EvOmuUI38!1D*txj5iE|F z68b-3JD0P?$mafDbVGV)!A^ztSS>M3uQpCpG8C{u0xq3(TU`6|W06H&em0*a0wWcmvfkb*jlxbPwB5coK|2ab{;qmn>YU6629h>IIYBK)?^ z#$=(I79^~!crZM$bYeMb`6dVxMGSlx#9`kI)i=pOT*n@wv~{U=sK1^QO*tg3%k6rH z+AM_z-hSQ)?a>u%o%LRu-i;xjTwj9c3HziFMI(q}mL~8hR~3p@R%Ki1T`~)ZLC&sW(rns}Smx(h*@Y+pikPH>I=M65gI6G!CEr*jpo( zs(WCKO$I!W@HXG0r$t5Nu&;+aPRQMoW~(LK!AwiOop#x8)U@AoEnw{K3c#U%$`!%_ zE(IsT{5~$B0W>J0fXO|T;>|U4l_?s0uz}MDdEj1=Jp%8Xr@W>>BlwRU{K<&I z)*alKD5#7p!KanZzpgyib0-;TTjmP~ikdF(a-xQk2L8gPW@s{j<_T0*;&M}2pGtMn zBW%hzoAb?rZCpGvY}u-%g~Iu9Yz=0zp(Y^)Dy%$LEZ{U64{JUol$DLgB8xaQ&9EBv z_d!pPmX|^2cEC5YO~qu|DMz!tQbRzT{q2Gx0&<%#SU)0v&njO+0R9JO%suB?cEFlW zaNkh7^k|Abu}8=;puhDsrgEy;kiSq~3A}8hk0Kse*IkG-q-~tpn5q`IxOdT*tPER? z23Jf}_OVfKyfNixW5Gp{8KD-gYu55K@Ef|w$4k975k~Cd{HDxs2m*3b}SXE1jE+Y^^sG0xAx; zX)AXeq5}-_Vj~KY!$N-2vR)lSO1WVd*f_$MKgL>chQFRUqf4!0;t{a7hGL&VTA==> zHbS2Qo)8=mu&#>J0#EhqU|hv1L~8AKs|5RIa(R5B&Jd{OEz-r#W|^?Gk`;OA6Kz!W zxLnFu3I-eoYT2i>A5_rf=^znd3fQ-}6rN#Ahrlldy?!l}VqI*El}xBw=*;CDIt~es zl0v6Mxwr+Gm*@{LsuT0XsDk+tG8Cmpl)M_G`m3~(Vep)`c-6vTU{!EvEjv93*^}5R z%_B%d_FzV!)jM;*W6Vd8f#guERV3p8)f-0#p~h0{B`WLcN>?Y4V|8hW82VQXAj=y0 zrn5~9lpbQen^0b|wn9)rvvNee$Z@lvFbiNa+FeRQcNE>LU<vv$i;U0a#{BQH}DdsuQ+XosVZlZJBLtZ*=}N83`%@LoFvI=K$KTcCFNNn42u0d zn$*`dc!Uiqxj)KIU>wx8%@Rj}P%TwAuy98+%lo{WoiXQcV1OmKN%T5-0zov@N^j8I zn(3*_A-<=_{Jif=F^zDjxgu!P?Xl^h_Z%c}PwGq=nogm3e~0$LmDFH1XC9TreTOj0 zonHH@T(HU2!95lvxC|a+wsNSrU@&fwW67>zJ97UARqgjF+6m)@x}?s~R0*L)`8>3? zI<6|qk}BS5i7`HQ@mzU*2l#ImuM1|e59M3a%`SF>T$L|#wQ%SFJZL<~MUt-m z_Q=E%Y6o8j*$ zI-rVJ;2poBg3beVb-Jm0gJv)GYZMFigRL04E1%2yrF)=GnSlsrJG2~kvt~-p!%6U3 zw4BYrfc=cIw$^|nW1Z5cGy<~|A6wp5adamTYEK=;Ymy;`zA>>Cdbs(FT@yb3#lee- zxSL0xVm1gWyMABV@_NFSufTVcgdmo)JWut4SU!)U0hsMX;ZW8z^Y#`INQ+9tCUVbl zE%t{bYx4^$4@PVy)%BXI7O#XYtR6|!Oukx&TETHmM|5N`vDA$O zIsqW3XJ1zZ@%+kySs?1iWC^zj<#mm^VT4T9zOtn79zJ z+H~kN3kL)dqk|u=)X61PGD*#krKkL+0<~r`(9T(!(HbC*V?SQqkzhBMGON=11gaVQ zt4$l$)h=AbUeEY3f0b^x$7&>T?NsMIL)19Mp43LwcRbkFNKG&hzS;z_+2|}TuZSP8 zbD}G8mH@svAYM`~;VezYom-K4l?gf+S<#jRj=jp9%|eRbCi>6XsV)98%b5Wd#$|;X zb=3No=?PR+AfjLIL%&g;R=Y~|mgqMw;~y@b&S>t@XCRw0HsMgBdfgZ=u*PmkZ7ns| zJGA69&cA6aZxXXf63F80b5GAg$+&t5eU8MBusJ{ooK09B+bSb=%6`N zKv;JrZACRtH+>!_KjmS=S8-BGCnLz5_u#>tEy-oK?Ygejh=h{KmY?d`--4Y^r%HcF znWqA6hNR&LV5~spidIUcmSxVBDkU%66`EoxRrrwOh%EeBJ%f+&2T(enq3IN91b~1wz=zCgRE@z~EEnFSq_txJ&97>79haKn z4H&;cbVSH5CpjChw;RTVj)B3Mh;>)xR45Tz7EK%I5upoOO7lF> z@SCFqC7?gEl5y{N+LSGC&6QH-braI^a^^~XV-d)^)4i%2sx5Oadg{q?MBmryFH@Mbh% zZ=s8gMS@-vAj_j>b+yX&>}!rZKxyfTek*1P*Wb;Y(&>=#b@Qpu4GvrE8l?by;2!ji$?Ne)1q^{%D zbBKhixCPXNEXL1%lGe^GP@-DtN+lneUtE~=t;SB$iaHZ<2R9e8kVH&Fd=7nDh^C8l z7ttvL8M^7I>ghSB&uO~HAQP2ObXvWmOyhf7^id~mrCvO2g0fQZM*D&g_pxNNa!SPt zd*FM5ms8xcg@^#+VI0fZX4f|oTA`Y(aPGGu2X~o!(CgnWUUeHA%_x{m%nL*GSMv_+ zHSXY#FY(tvq^*-#3x8+c#Ps(`Gv=<&(LVMOV?QS1pI$9j|hG?dqArcS9pNpy9MCP{87ud;uHkST0!D$YhlBfp%T-!`uEc4&P+mtZcW2LjG*s^E2@9%oJ~QFYH!n#d7sD zFAa**kn12@j7qGfAu}`OF%miq9%?gXmU|Pr zw>8j5?Zughi<)sPin~5|D{Hpp5zv(0(_!H9;%}vYp=~MduSr6kpL2vQf`m8bBh1dQXU1+mdmzp(PBvyT@W@?}b|LLaaa7g2_onDmD&9w%V&Ww0%(fX%!@ zvXH^epRt;2>#_CvK*vfF2uw=;)^ro0Xx^BH3j!3#S^oILkdK^oU8&>{kU{5{PF@cu zsy$9w@*1uOE;-T!4d2QJwb_s$y>;q}9EKucwsdLCEUg z9SpjhvIiYmRe!k9isNMyz^&`UqRf+fK~reD*RUjV3!ByNRBtJP>9akmHtD%Xy#ke@tqnN=#!e1kbGP)IJ|l{*4K@9cZo z5pL!z(p`{Um~(xE=wlKoT5ct?+Q|cmtxNXNT1t%HS8t|=F$+zir+GYCk7j$a2tZ`4 z_o-}wYq@u0zcTL``ybg!SHVA3JPnsL%T@LNo|qo^V4B`CXjZW!I$ zPMJuRT8|@&rv5gT7c347Zpd41SU3yF16KdTiRNJwoSVe^ngCBsGMInL)&g3A0%AoE zENB4Z<9-wzQ~^jk8dMz)r5Ycu5i$3kp!F+e;=@Ph~Jks?hmo zYTLj%!6H(+QXEldAp5?bt(U#se>X+Oey2=fQELHRe|j+(0J4aD+FjOdf-8>w0X#MO z7;zmpZTk0ZP1t%%C1OE zHpa~ox<;BZ>(Qv>MaoR7mn=MXa(@j*o(7xbU*+@N$x=!rJqp!WjCd6 z(#@i6kzppjdg9vj2ve1xUO9MQj50qFUUx+e4JNKxpjN6gbYBsbk5%|sLqmipVWWe1 znpQ_=zae+X7I|!hKLBeKBDW1#am)K4?LC{8z)gc^^1@5OipKbOUl9gEh&sm)8Wvw? zk)aQxj9kFv_X^riHkD*cmZE$5tFc4Bx043-}{K>%=@OffYkpBH|zg|SsY3I7XK79R&i1T|lD9)h)ha2Qr@ItWGsKXw@Wr6|Y0l+EZylarpL z{cMi1m0Y)}hNALhayt<{8TKz4}k( z_O4K&^vHnE5?hi(gi{)TBb6kpC&a-qjIc;A=>5erfz}Q;uq`D5Oih7q3?_v#Wi=or zL{$9<(D>I%tb7oN*2&}szdgeOu_6G1L})Dju6l-T_#P9_eXjSm<<747eqA;@+8#3bA>y& zL%gdrDhAQ*NIKjB0=i&v4>DgDb3Hu^$~@B>kRk@`5Q_kC5A+rV&L}S_XY?{`qKZ>z zxLyD~$p#ittco7${HV$)sEbjk_Q9jh8m)E~h3gJKn#nj^f-`ivoRt;TZt! zQHK8%KW;>>!iPhw)waGgx-1dS4V<_~nNT6>@RRk#Q}I7nO5#7h6-?!lt%)J@M*xoyG2TB3JL5f%jYUn%%l) zb7$?{1^W+<`@UiC%DT^{()@9v9t8!eiOa$zxCcp>rKDqqQKE~j5oG-e7*AW?dC@*< z%V&tbiMLy%H<`vnx?5&0N+^?EcmF4m3C%)k400%qJd;!sD2JKCbZ9P&g`}y#^e_iqRI`UpHMw!|W zZRhbZwIqfUZJ9X_DJcb%JdHEU=yc~8hDom4o>^yrXM6%c0sDagV2AH4o8k_!3uo8D zljt|_Gad|k@n{r1Z82PZUa17fIB?$7cy9^oCgxL=(`+%BM^>0z8@B@>=_*Hana#s5 z(}jhLdRc3~Ss8gmXGGe=W>hI9k-bd3xC}!CY!g|BW5{`q{P?KQK_`_W(CFcdDN47; z1N9c-v((50a!rhWP4{PS8Eo(d#^YA~dPj>OnC9Bgs&q%G9A+W~kU72~@3`lq(qnxV z&q;s6@wA*L7xLLY8P+T}t}->zqD$cRYSN$})8>~^ympnDL!^#^;y&_V%bu1k-({SZ?7#g9XM^je zjQQT&Yfs4C zIU7zLQqGZu^QIzA|K$(r>XmQtlWB%_VhCu;aLW0k@Z{cJnYU^Iyr(*ZAU zyM6=1f+g&%8@K$?){*TDv)A!1iWJ8D9eyBa%i%7PZoyEw#v-jbWq@%VT@O;J>w4Qh zvWt!v6DJ@YH`;NgCALz*^VfcBb=opE+6IV0aw8W3Exz;!=VPG$`N=Ux|2;G}Ducut z9%1BQ>fRLPLGm4^EAVSMha5{t6II>cyqGNEqEAfw9?gw)u41YdTL;miZMu~Lo0UyQ zc!|~({hXkn@MzD|C>0J2iHaXX)bp#DDja4K;vgHZ8EeGKh;l5tYGHi}l0Q21JrF`N z`7y$HzdpqKPJW?t=IASYZ0CCQj5TSG$r2cC!prX|5zSn`0ylzG>)urq3qsYuue!tx zCAEmiMU3ApMyCDeb)aQh;a$OrE^9AD7Jgf`eI&Z|Y-S9W5DLpkFQpqweUemRN+KCW z2oA?YZ}_#*n&b08mU3Sy z0r3vL1XrAqL-V!(WCa-FGd`d?chDJVP|x`X(PKN<%o2TXJd2}=%wkca?6W#rh!Cu( z$V6N<{2x)%WaASfAd?VWBQxO2pMkm{pWyJu{r%UG{>V#o4{A|+N@dV^nE)e!QbGQuYJNLa~QL&(dLZ`SkOS-MiA z(zE`nS0D%vK`>!QV@`NNc6Kft4CUCuc*#a(Bv+S6Au}aRr`&h*8bbwz(Vc2$j>SjY ze^qHLN7L|KY*rr7?`3>J#ltEX1%fF)%BZ!OJZd;3C2QI>5pnFA|;2*gV)>JPQ~ zg`B9Y%r_|&Kvc}JQ+Yp%X+(<6jv1c0#a6|Fw{Nk}v3{N_pSOU@?gLP~2vbOvxAP`CRl9`Tr<08#+`KPZ*DBiCwre!O zqu4>YK7Rgl(#55Q(6XuMy>ynA#ge@pm z5pHT7OHB}^e2uKs`!F@{EbuZh7e`jAG>|PVauF0)#8deDifZm*m%E*I zEk!7CHRx{%^~6VNtw_rxwxx2{^x+Z)c^1zNw4?02AE9uxK5Ar6+ENDnmVGzx6>uWq z1Jny1@~*L5Hc5xzG!{9S)gn^wA45>1aoM#1k@DTk^Y)BY2CjydPFtH}BEzjaoeJNS zi>C42BNmobo7m^FB+wYbcWTovSqDbF>$Mn zkQNgrIawM=0wem$X==g5hxyFOo(dc`3-WWje!KWb;M%2}pUKEbuQ2&!<<#U!JBJv! zkeFfdNqDyH2BuH7&B@5@Lyi<924-!G`rw&67epi;_t(O`_HI?U`aX+It&`irtkRMf zDNJDIswYrIOGXk81)o~ggdFIet%R*QPNsaJM^5LlidMqt?+hO3*EG2mw1%XXftGzr zgewgMA-R9Ye;K9{-G}P0ToiN<+T$s9F9EZ>0*G1?PctH7yeAYp^b9yfaQ-T~?O-1J zA&IguC9xCBdIQ?g3|Ws>aMm@iyD;X9H7$f{7R(ha$@gB`b~56H?dTW1!eXu99<%(N z6`l7+1-83LDDH`AIM6H37->nc{5m`O1D&UNV7J zE-n~E7+jubI*hF2>W0@ou;Nyya6H{wey`ga8N8nBD!tcy$e|+y-c3_L!E16F*kR8u zaa;$Pb=IM`YE~SKxZF`&;a*2|_LvT=kU^ZVL}ZbY##|W3kLTT>-56Uw39IIiGi_+x z+yPFge1qol!OO|P$xM0n)YZSQgX5)zldtTnsV9X#-MpSYEOMWeI*U(atephd44S}h zW4-UWftQuBp{C-5#1Gsew%rk4WmhS8t{L|aR`*1Gx{9g1y>XrzSKu1Y2UT~l$;CGq zyg=}{&gWJJX96-4Wm8_qx3oFt@i4j%xPRuB&0hJQX+}?y{M!42Z|$;~cL&lDf}E~Y zm|0R~{nU;QEBhEU_e)F+*g70Xdrdq`_zy(5^Pwv7FH%xq2F827*u>7{6A(K`-DMXqk1Au;!Rr^@QFbjq`+k+B*|9y)gP=Efvw4?1q_bw zEcx@|RBFZ3dl^=keP}H*W@%x2MOT3pLjP!y0os6d5WVc>aZe$orEW87=Do8l^J&i2--0zA((DPXpjP?g z8FYJXqG2+x!yVvaPDGxDXW4odgV8k|ogCm|iSX(}ib*RTkK(PJ_i-VlNp>||ymwqo zQ`XE|Q=CIIg=Abrc+&VR%RNy@c)It;v95i#9i)W=<1bO=V0&D3P#TK(;+h9kO%6;K zI~TUp zU7lu;3V}ns0tP}5bT94O8)&td%IWH3H=r#IsUO6b%HSkBLK7GHR)P_tQsbXT32Kwr z$OFocCCEEC(j?s!8Dh4v)!_S7WyZ}q)<}#l$}5F>(uMi?j>P+8%1{`Ur7chx`N3{h z=sT*X<(cbLtzcPB;JxT0Nfy3(S!DEjPbzZPfAtVn6u~Ry*Z>vNQtTH%)FUS-xH{KV zRPi5~0v>XoF2Vd86{(GlWbP_xDmVYrXvOwlI|TN!kZH=4-f!blB;;aRLGA|})2L!4 zB*3vc@=AXoAzBN5t3UDEdR$MgkxqG+Sx-!BN$pi%2QHh6TvhVHPaq>Rtt-AYN@OTH zwHNkq8ogm2+10*%e)I;ZD;|oev$@SX8|;VFa7U@_*?|b?h8MbjJ5a{3a;X_`DSat z=^EtTprdjQg-#e39!Km&71VI9n{b?l$*cFrhv|@sH}sE7oI+9p2q?4pVGfUNQO7YY~5d!@^9Ov&y2hL z8d}B#d+St=%h{57I>%DU$4;S0L!swnt&6P(aS_mzXxjSuQQF`5`nph#rMsl1!Xtkf zl`YTv3PD1Steo*}&cxYN-(q3I$kgWP<64@wXqPMM6E|VvY_7>=TFz_7Uyuc1o)FK6 zT<~8C2w0eJ9n@>C;`@^ki^gjcW@0^RDQcTnD+N1vpb0j*kAzL?2Vr7qYsL8r4aGgf zNC5Z8%R|(sImibd(?05IT92N8j;~Zs?`y+}qQ7<%J;p{@PvlMf?<~$G9rO}%gJRfb zQzh^~F3-6atp8gD!-NxCIAe6L#Jizzyzt+|9X)3Jq1k>(C_#e^>T@L_!(udPvEwQCK_K@{0Q)_8CvgSwXa9{EF7MG`}=Xh@DVs5qY9es zinryAhN^hw~ac~TTy=I)tGr(Dx^QuE9?fG(WV=c1gf8IQ_5YNYi6hiED zJkAS>(0TLep+v~vH)l6qPVT{b_ZPA^Hzp<~s;&+gun{{3gjovGX-SD=;MG@KjF97C z|H+oa_pIS`FZ=j?O23*_mFmR>LD)G=xz_l}Ik3C-biBdvSnsdJ+ShI2y1vvPuAO~t z`u&l8Gw5lA5_$mDUFna9U+eM#kLJy648RF^U;2koCh!B5Z-9dzy#GCnQ)Hm+|7>P4 zPY@Azj@&0hN#e4La$7n+IX@nV9I31|lT#fF(1upJngT>0J1+-G@-7{T>}vN4U&DR| zhGwn{NBW#*97AVW^^^tpHzE;^<1w)Y37>~947C=M8Wx6+W8XQhDO;BreT>77_)3lR zh>F12xOiJi1&Q8-1jh^f6Itp|pu$g0@s7qaTCYwcY+Qs2*smjh4Dq-?9nP@cfWJ1RpQ}11(d<;I_dy z=0xT1o7PL>CL5&>6lU(ED4rv>V^&cs_=;}tOFQ`p;V3D^?2UugCi_vrOzZJwZZX{# zNm&t6$6Mo?{4pdO@hUV-WOUiy>(luc>3b*`F^`x>wJe3|?7ZtHWfLcC;uPPGv@Vs1>hH`|hPD&4wcf z?cD~`01#n6P3We6vp}0%Af2p8Enk=8G1kZtgV~pEu8y@78W$<#(o z>29kN?!O!lG`MUb-+AHPCHTcNcxoI!kyfeM1l2jd;f>i zHUHF6UA zy^5v3P>cH3F%0_Cbg-R(yys5fH{(jM(Ix*m%r|U2Kb96)CC6xi>60NvmFJ1jY4-lm zq-Hnf+#Ws?Fra_BtL@=&FH%G=R!1mmdfCzTOn0jeH4PP691AD$1O@K%&Z%`CA zWMa6MEO}MUuBM{hwxz4>;jO1;l`G*hRr=yEBW_VwdH2HD>%}r@zBg^wG{@S^-GPgw zO`Wl@b<4-7!PDAU6>AG79U4&Av9GUM0>LCP%g}x_>PwDiRUbURllSNNUV!8qN4%ls zi2Jqawdnz)!wu=^l*KtP0UT?3m_-?v^xbz*o%aF6sEd#{^gN8L9a;75a>X?eef*eA z@fcf`tK|YzZz1v zD*K89ml{m!$MXj4R9cc$S`jP~q;>hsPn%L(P@RgWxMGAe*h zwklPsa;ak3#fhuOfhc>WGP5d;9HR=6T9hz_B#4M=Wx} zCZFn@%o?&E^WSmm66r$P`fF9H!g2j_RVrDX$~0$Uu6VODX)1Ju4=DyZHEGrZ=}P5u za^3&73yah&T3$}MOQoggB-MIrQlHHhDwXZaq@3uUBO_5a?ugZ3?z5bY5qny4;7I?w zR^ajy*xF|ZK~lg#gwYc9Mj*s1%^8+z)1QZ*psAXihsU1EmiMu5hkzA1C~p*=KShddbqo6g59!}W z(b@wW8uBup&vG?T-$1Rv@Aw=aV0m=k8Jo${${2C-+k16)XEOBl75CLn0;VGhD}K#X zoxoNW$)u{U10WGBf(~n7eU$0sJjU4BSsP{~sn_7Kslu?cAMn$)E-p`u@z#rs^K>s>)^m=JjcR7x-|_NXg_?$&BCZr6xrhTU6o~KH+L`43Ur^dX?Vu# zUKHx)zlNQ`Jb;bXyLs5f-myV3=EU`sd8&FJUTXd0C39e8RF+K%E=$ZNlR;;GKHH5H zi9}@diisT_=N1$U(P}iXEqkbg&*aetx8-(gJfDS#i{2XVG$(%U#}eDWUunBJkLfhn zYT3~L;)`L@1AZ)Kaz*lsD`$KJ>%>)y2p6c>wsU|J~5N}Cr57w3YW&qs2+)}Q!Ll^1$R6qDlw z<`b`~vo!qS{oFG#nU9&czZ^Br5(RYWs=qyvz@5oPIeF%8;ZceS+xLJX+j_X>_}ic! z%4*sj@Dl=DW7x}+h#6a~E+&Q?Fb||@6c|){M16o+gmCESNZXs)`qT$K(NlfvWHI~g zxUxNvgd-jNe=0@6!=>_XpfEM7ee+&tvOnP{7hQ@3uQmryGCQXwWR&6Bz* z+`jzn3c%O5ii094v{#Q-4)1Q1jixGHB`yMa(ZDvMLXK^L3Ue*;z%C_ELme#ZTV#}u zd@4epKv=%gD9|WMBfT{+-p=3OrH$T5SNZcWUH0@o+(d#7_GN;CKJqd3OdqY0d40a; zjq9RNt=n|eE)CQhU@`bjcRTm5TM`T-Wmcrxyl#Ydup;cAmlE91FP-2$FJ_m-f~M}Uw_s>9LU?^L}wq^gzPDQ4EY;50zMkThpWNGGvKH)(&g=l;6V#(pfdYyuDwgGc3x)A4y`nesY_D86 zmom(?ix=kg3uA|k3-6s?tLLrhkfn5dNaI#dLd^oqDv{1Q?Jcl8V{5m_q+t8#==$6} z@9MN?1mZ%+quh?&RQLMGV|^8o10KIt#*IPpp*IIl;$B5lw=Gnu?9%X~LM;uc$|J;^bgXz3 z81fCez3nLj37hY(CT>)kzeLmIh&KQGT-Pt^+odh>SV7#^()*sgb!J&4oS!NgMz~u7 zO&kIdvD6oc(U!Q+$2b##J4nk3GNE&zccYJyZ+y_(k0}SLHkb;8uZ3NG)ArA^QqdlY zAl?CWH&=fa#CI}?6dMA6l&W;m)8L4p8FK1x7fbx@(F|#&<`KLt7|S1?m%;Npx2bOhGRF^_PBt6mf0)M zn+y!n_C0?e>#jk#BpR(JxK><*M#}*)4^^s0UBtwbqT$LzHC_J3Zrj%9ZTs%1vTfy9 zn1#VLo?KvgtRrDc0_DRqd7AWXSkdiZPmO`_vAewEI*VOg?}DOTj9u<1rdO$%Kfo7+ z&BuuBe>szW0dS(&OdK388Shi-ZO^3w1fByjC>#A}K5&Y}Dj&ued~cKTg?%|1uw=%; zh|Ln-~CEd4!x_6-+Ctx7`$&f2rSWiI~HCg z=kS{5Fmx9(PsY5KAU@&PIj!GV=8&mC1Y$Ct*dQ)E=#Ux+v#wIswt zZ67j>_IELX-I4cyh@>zw{*A^P6`a?U;jXN%9?WdK!r*(c(HrATUp{{n%8s3t(Qm~p zRV|sbQT(#{C{!SwQ832%qdXM&Ro4oxJ&S;tr16KRm^+>>w|knzS>wM7(QF5Hi&`bd z0!FM_QVWu$zi9uU*Hu$#lnt&!*YZ9ZCQ3lGGNRSa;WzADyl&| z`(JgkGf5A6{v>$vNj~hY|SKnnc`(jRn6Fu+wpcn0@zV{MD2D( zQ@+TFCofWXvY1t}4i9qjPBhSzW)*CEe}2+v&2rXDHF%10T-#sbe6;KQMLRNCo+2~J zLoiLX1tYSQPEdt&s{K^Cq#M`}XgCxjvYx>QCqqqjOm(?N2ty4BYjX&DMQX3fYjscB zoqKhY$Q5oKxGQk?B&(vSITAMiokmcfaV$~HPX?`bZsABtDs$R#t;Pi&UH6jv z1sRMf5V47C4_zg)2>aI|2n?3JiL%eFtEWQ-D$Gg5lxp)+s?J4Px`!mhnsvUQxr;=}$QcC}n~UDUuVSDXjfLxSTBwXt z+-ap`seJv?xP}JaN{}ST<3TVt0ou?~)pRs2zkZiCnxx`V`nCWh0}l;qy@OE( zuxBX;yLgEaSDNtH*?p{VxhC!9{paKTA>`N|9#L#bAuZe1ml#b3T!?(MV`S>xal#g2`ljuP?Z+k zVb@7wrG#(70a5div+N_-zs3(DnGO?vT+2^(?D;sOFM5Qjp#*1?M`N3-{x=I0+p~4P zm!UBl+4NCySxyJ&LIu;&`vF&qgC%R}%AJ~Zl(xQ?BxTl5a|4`4i8S7NLVr?pcvTBV z>L6r-e##-MeeVB5)i*|G5;fh%wrx8TXJXs7ohO-0Jh3scZJSSQ+jb_lo!q?dch_C_ zTdP<1sne(b)Q_rjc6IF?N*~vKJaEQoLaSnJ#Z8{h+HB1If_TO?An$&b>?SaQSl5m1aK9u0(6caOV14&L==A{@mIXERF!YUG z8(n^M?P5%*Wg~QGbB3K#qt{8?O+bFJ$GF;K=QIal^%3!cbFdj(oR{&L*p^-1UzE_N z2DwCmR?8l{)#sX7cq6uCHl_ZYJ`w1B78VN?laKM2-jWRhehqU*WBg|?!Py!3U(bF? zP^0*j3_#`?(rjsM?_a50u`J3fq4ik*t{&mD�*dev2vNW1)Q7De*T?FJw&>_72y- z2Rty-28tv67PI@=Pqeq+Y7pcBN1vMY%{ zU7*XZm07d$%^vq}_KJA&-WDBk{N*$(kqxWPNjjzv4%P zkOtKK<7Vzj6VYHyf(*w2L!m6)Y8apnDNZQjZc9336a`XCaTH~dci4QP8d$Z^u9A85 zovC|uKDsF@akRVeXziYkIq3t3hktbn73e-(!n0UPym*|h)MJ)ZayH!4%H#o_2Wbgg zbl_SDRg}EC3efz`2-pq? zS*%dSBaH2*z%=XDw=hgT_KxRr58=#JGAtdFZ3OJK7Jd^d)W)4i&C)F@|76S>fJpin zipD{r`DcRlYL<8PsCX5ZyYxYsOz}FsUQtUs`h2{-9IOjjsHOyv)HLlJlU;qD39U)B zRvtc#3|2Fpd<-)kSFKFt#im*y9Bf?Zg(TmeX1YON016b<9OiJry>R%wyczZ2?4Br| z-z|1Z4eHnQWb@DgolOB2^;zGrYPl(Wd&tC3&N_vB&SsM;@2xn@$XO2zy@xnP3)OLB zH*-^(bHg$RT(7$7Ta54z9lS)RL^0B6a*pPQD8`b<)Sq8ylrQoyCp6L#^nosB5rfF$ zG^dc(96fse<~1DTa(Ud^?f*Q&`2Kl%YPHs$iJ}FKBv&+;0`?<=?f?{UZmm132kTy3 zMbYP2S;r6CX=*;EWCOpLm~x?buk)7=Sz$_3IHV6-#94DCm_{7k4YXRcf5igFn#3?XLik{`XP)<2jBCu9+9XV+Tq-Ega z6w}!>`Ihc@aB8iP+(TUvw)8OCVL?a=d8%~A~^fG(D z#k36t+(Yim1tndd=4Z8EI`2LwLhLU&!BHOA5#}g$IB%1vP%>k3S|uUs6d_cput!Lt zO#F=P1a&3;YPak8yH$y_`CiZ6H=ky&i81e}4lKL*)hptOAliDL>%wGz6u;nt8vK{2 z$*fASz4N}diy>0kH2~HcxA;fI8qAraiR393k{Q2K4A#L99Rr>G)=(V#SNB$|+KY<* zP+Jk*y`Q_x_f#y?RK1au_Ts9b6%+7V269AXtS?;L;x`>BAqR7my#<^?g9l1~0@d_r zJ1J4KIF$w+Aj(V6&H~gI9uT#D85@b~8(KEzSNmo;itDGMC`2`%`DtR@iOqVcgGSz& z+>K4fE7Ly+NxYUTg+#bLd6ckefyFm|Qp$RBp21`<1bg&5fxlwSB($*@raHE9TzVV&gT=ld%|KDN^vCuGBO1Dz5m2jGU!Ri@feX6j#`7|c zYT~mbCulxgaU|=Lm5pjfPy3d`sagfs1GYyL-F>2yknMX4hr67>I{m6oZ8SSFhQ6%T=9cohE*bH(5Mk->+{b(kL zaN6E}y_rtK?@&OP_@{z_ni}FNn1O@z-lOzXS^KE+Q(%^fe|&WjsWC_Y3zhENrr&Li zhxB?Mi)!`PM)=P=+_vrIHGTV%hx!jNVCN^={W_#T2sgXez}%ae;TfMxV>qh&lIkbq z06)TUG&eU*`tMkAFmaeeMpz=@=VDF&uJxYeVRy>>6ZV@5$>j$5M?#YuTrbMtI!*7m zIH<#MIc~41-8XoFb!epJiHF7UC-993NAgU+-Hl1RX9A6Bx3Ts}Y9jf$6gRpwBP|1N z;6z8W7T%B7Vv26b$EL0E*b-u`?e`>bYV+*ryR6Gb4{&nKKmYd};qEZ3Oy)qBBxq6?NM-JS;rL|H!S)~2?+lA#`Y<}_5cFEGtw)a1^vajA>GC4Z}~AIUarkCy!^(H1k45`nsE>-WiN?t|ibD z@X+le~>jmEb|tFOW;@OZGDrbsG3)B7tEVZ@D!Tf30V;;J;|gz0o(3Z?#$$v zYB!#WX0L;)X$VQ7?I#AHiJ_7>Q$*_LnG^W5dEA_8SfowM!Q95jf6LV0Fq1`AI=z}I z8I>b;Q!BE!wd~So3hiFgTL2FG4Hc#i_s+BXcCjhRlaLK1at09$dBA_wu!vT9Jv;Sm z#n&SpZ6xC;?aln~x>$IKcW+$!p_h!)nY(D`|2Qi=*uARZqMc09xY@$cAI-@$9^B5b z{tBj_+_LFIg>-|k{u-G&S_MQ|E|LVBCPNN-`MPvhJT~fy9%?K|JYvQTLik{%R#aUN zcnf}Pu;lCED9Fo-YQlGra1}4ZbdxH6j-=_%pP?@p4981TjP%U$vF%#g@nwF(1OITd z1NnfD;&8LB4wSspb+jDQPYLg=tHGU_Sy}!BP1w;(u)Srft3f;OqD%!lh^-mLq06KxQX`B(Zg@#?bW4^m<-DSdSuae4 z@aG7~Z8Tr8Qrp+{Ovnp=)<=6CP9&4L>|mKp*wL7&IZ-(%nQ6z!ac-wdQx;oEYaX=h zUR2T*CHYXEL-m&xd=xaI4O0ZqZQks_J6`}pyjys%G*zZHMks88t8c*0#rgoNRt?0AwL8(9-YFtE3AKuDQ##FNDTqNY5W?W5G49*!!hDp`;ONNeb|?V zwJ1$P-5Z?|Q6{^NS9*PzG}UHzQi&(C`__?ul@1)-#fry#v#UdwWpi(Tv zYSRJDyf<70(#Buxrd%#gt?iDY+V*Y(fN&_VlIU{GRVv}vR=o04C!i9G9*_?guFKJ z{^A>X{>a*@W*YNQO0yBf*MLwl&QV>6*Dnr|lW6@*rWiY^(?&uYmuWy}@M&|OKkrdd zi?jgaXa@lmZ-&!j)ly>lKUmldL*r`Res2cm2CGSv5f($oWFG3yizpKzJINO6)vdp~ zX+{@@0m2V)S_`OysAh&Kr76kvicmwF-3FT>>CT5i<}99C2m#n_I!&0eyz)d}b0exc zW@6mph-3SCK5$-VAN0riA}MW;Y zs__-_!I{cEL6G~p2-_q5+Hfz$^X1*3g~_SGa$>^%((;A+zGU^0H#WPzdf;O=h$5N_ z3hj34A|Q|Hsl`pwhQh`h*vf|sYMU^iT39`RK#&Dam>#tcNHP%0Unys#ATI#Xpg9o| zUp^gaR0tV1OA0xOF;K`e_&43}sho|_j`7$QJ^@JY9 zHbyazKFu~p2a!%?OPrw%{4h{!X7e4TCbMnoL76eZACd6~9Sn18HPgcUlM?g#IyfR? z&B#Tw4b)UuYJm;yv7sDKO-<^u(pb`sY}O;#jjT36hdX3+kC1|m+8c3qjI*Uk9mFhGi$7{CA_D+C zaz6ejgC&PWgTIoZ^;2T&Fn9Q5s)VrAfT2 zo-G3TVp3klNCmIn+FygB=aI7!!Pkw8`{RXx`XXVjt{-07E(k+o`y$@_D0Qa;mDuYi zKZQNisgK6yDSbGEs!kg#Lnk(ks-7J%>ogv6MEj&qY_adV2+iSihJKD5f?JBexl zd-T@Cw|b)PSrvGH{LAycdz4^TCOo5v^qoG{%#3157e@PZpXq$hRd1UM${pKOlhp-c z9(bE6WK~#^$V+4z<07=u{Ms^+WYFdP;Q(U%Ia6^nkh_Ug@}WYD=Wes5-e05vRviHc4@akU{(tFtNXwfRC$`j`jzqH2 zL`d_VSk*|odM~96@D4QY%zb!F_dNd#LEf7i2-r;U9U5?`*3_o~*UO9!8GC!R(D$Ri zA;=gUDz55}Ud>8YL~`WLk#1c~`X#g?okAtI73D37Bbms~#fz|Jzj$7K`6R6JS^GSV z@}8Yxz;)!K4_1~lIHj9f)4+!QVUWlmn(%s6wwTNzP8YR;V%;xE`wiv#*T~q!@?UcCEr{%Up1VoCh0u_wujd(% zzenS4?_1fS8l~-;cOwz6c)s>_sb_ljbzAOXIa(aApLMbq;hY_?IfvLcAoZ&11bYC< zmi3Nz^9$#vz$UxhEPGghU^SbeXZxyAGCrwaL%q+Pyf~2@nke@}iK&UJEde05Fzv>c z1U{Jgu7XA6wx4IJ5XelS{^Xu3Ffpzx{%g!RpOd~*(SA91U$dVF6Yj{yDUJx_f|1}J zbOmEyA30x74s;e@1)XpA4jAHJ($keK8FV=J%<#g~>RWiLH02E#zMTR)XP0BMRj3)u zuI~c@ZPm-6Rmg;}Z!JQCYhyQ6_?Eu+6-GQ7L>;dC=gR~1b+;`|_?Cii9Nk!*%&4v3 zlh{AsAdf!l%vUZ6*M#|&r*b~1K3Z=Yj;4y!3JgO^QCa=LkYrl0{sZ$I(-syF5?_J6 zoY2;{nH?n)D9hS;?A~>fD*8K*j0GyB>c|WkOw6tzMIUR59{LwBVgM#@iH`BGU6j4A z=s~=LFc4Bqw~;N14=xKbUS_UM2pSe?jNN)M0!3U?;ODP0^qR)Wo(Z1EbJUo+)m1e=_?)6;}rK2rECrI*Q>} zMjQXYGYXX?rGbLPD*pr0YBj=R5*wuo4Uiy^eyBG8AY+COt`1?QYBb6m?N2nK)(OW= zf*VH*g;$|0r(_$oUrBDZ{~<^C)uHP%`Z5+fvtWw+#SQD8D%YM2p0`c_qc8953odl* z|D!OO+!Q*HcVxw;UlUpcnNC9SsNWD&Pbd=+k`tFn6 zs#%c!#5JbtZ|--Ws@?J9hBmb)QYc!qBoT1iU`;Wy@HHa#m)X@K4;kKaskP?k^9>Sf zE-9VwI7({$hUTllNMYYHjRjUDFX=+-j|#Z1f)Bq#Q%M68&hh+WVQq~33ldH_s>lI< z=LK((1B3s~J2 zBQi)yS_xt_$Z1*`;M?k9e1ns^U+iOii*KpGZ#e+lO$LW7eMkw_MY^xS2k_8TD@&Xm z^f5xm^I7A!m`7(zmnY?6cFVUEVUUt%dQQGcFDQ8XH+ z4II$nF%T~{AfNcjcNO%nX0PQgzItE-kXE?IT@+slq@u�HT492Eo;)mk401{p7SHY)0z9?p3I$e|?(~)1Kswr7narzz zm0VM*q5Y({t$?5i12>vl&)ysAiG6P7u{!+jfgVNvaJcjoYmfB&m9xazZOIOb!6^naK%Gx`fJjS0taol>ZhAUFgAajLMS!k@*Ui|^X3m-jdHR&SF&aWwfIk}_HrBhZMN+VjJ`{;v6@(BD zW#{MJJTaz@cs@LB_B!Vr&o^lwPo%SC)c`vk2f}!*8A0K_M`_P?-7UpnTu)V0cwTv? z6S@;Y;Za*{&n%>+vC=oe@WD$6x}>6geZb$@T-4(D=p*WykI_&zui3`MvjgPpw)xdY zD}mLjPOTlvPP=rDWD9?6d0+qAPqgl>N-;ff(P0Cl5)lFJL)rBtrt?l$vQN8ef! zUd);k;Tvv@;+E_$RZ4+Qvf|$*pan|y$^ED3XUxS)>#>(SvMjMtA^D2E%)}Qjf+6!;kyQ>N~gYQtXjNtvOZOL)Sc7!Z2%7k z>uX?se;5arOpz$XADkj=J$Db4$sQ=WjJWHrKBmL|t3^-T#%Jsw%Vv8}V)X7b^XSGHbRD@E;R}G8(Yw}r z>xt{^fAZ=8anHS<{fBuIhk1W1Klg~n8Yuw9lcH(=@4EWT`}_UB>T@+>8wA#$I&ork zhVvJ>g#{C$nVDsfv%4^fADIVyg|uf<2egRzwdXvDe{4Y^7l;=V`76SSmJ<1^V2PJ| zK-9<$x+|W+_MtD%JX=JUO$dpuC=5H#*$vewcr9sX^}1&0iM+iHZ$?N!$dFIRh%*O< z#q3j$VmVo{AJeJ^D^N!$_WC*eIa-gYsV_Vg6%KQ&Pog80@CThgYD@>$$RcDu;!akX zh?_U6pPEhXrX)`fwma^^rEV}uf$MNFIvSB103g@MMG^V8S;N`I=hVKb598FXl0ta} z^>^Lm`H?Jd#SkWp(IjOL=GKK=ml-UGABZ)Yp)7g{E2aA0X5=s2E!)`aaimOu+eP=! zlhx0b()~A2x)Z39EhNPO6b&t|0~ig@vB{1$;jFkPbe5OrAN$&PZ(KYhq)Icz@(Af3 zdqyNcMM#~tY^53MaSe5ofYfmSOooEF-y{&Dwq-lv#13=gLIsWdxCT4m^Kl9Lei#Mz z$FZT;&XtY3-lfepLw*fPj|ODI2Hv&Npna!PtqCN=bld)%XI8{azJXg*0A@d^s>^d0 z2OKZLkx8|bISFY#T^1Dbp`SP4xuz(Vx5t(j*F4D%a7nnRXFyc0l{w+JlbIt4LgB4o zJ_v5+%KRUpL&v{u(BGHroF81fVXL_C1FN^pay&mQYG`5nx`7l_N9I11nC26)d4$?V zcC!_K()n$+MCNvk7RN#^zVLM)9&fs|$yyCh^OqQkBPb202lZRO;*#2A{w}V{@;6jJ!nypKFqDbP8$&jrfHL0Y~fyd*HK-?Jy zQ=t-{m`~uc-IX~s_$yoBo{bm99+1h2D@Ld?QvR8P)K>gQ3B##EU5|34lrD{vTK?=3 zM2$Lm>obZj*yuPI3}!+H`>7pm(>U2wbJnU>xonv}k-978Jr*>W zHc}@%7;n;iJA-E>T(3G*EslvSdne^SqBuN5v`#%vrZHurW(fsFDS>H=k=L%*N}mYB zFkk97i?qf&uaO6LpN#A#V>C&*AE}=3KTS~eB3R3DYh73it*F$<$Z?({$^@=@95oHp z`wEOCO071sAoG`#{I+l8teiI8Mq6ys#npH>EXw`E_T^`)h&q1NjeS46(;r*#xfMV5CD=kz zSo1DWYli74#=l`5--F1t#oi+P*de}q1KiW^RWn@>QlhtG@9=)?o|Ln`oFq|nZ_N;T z59Y#noqNwBw(xVuqw&Xy^R6BwQCoXtFB2{`|Kuwv#R`~XT3@P!*`1i}isq~G7A5T$ z!0}-s4uouqmeo_ZDL;>HX|lt}k5`y=ozUj);H^nisQ$mvDS zgg@ptBh5r5>|!(hw@P(5Rv6&>iIK zneM{gzPO_Ww4--l+8JT#0Ezjle=&hvX@u3Xrfsy6yxWp)ZOvu&4}|rS!8DS0)60#3 z507Y;2rV3YV%k>tNSzhhxyD*;dkCQ19#j7o`;FnOi5+aGXz@aGDCCW%kfZ*c5(~w@%6u@D*j;j&$UB=fRM3+fMEUq zQWd|Qjh)Rc>>S+wt5c!-$6-whLG&dM(WCEsyawr*5ky=i0zvYD0h zmPz{f^`YMMbnm21VwJ@qKd1?S|>3xuF*qepS#5Q3zZVM10DFX4-C zR+M*pPUBUIq9(~cLSXE^SartMnQW+7TYU3hy=b1Y(S()QDfSMhnisU9d9fewMy)7v zm%)$jSoLb)dC=Hq!Pg9YHNO~>tF_=Mv0z`T@)p}Dz#j3>8nlD?aCDSdB)3B(T*;gy zWEUv}7>i6#A@OALAZz~gXC<<4HHe=IF|$Kx5}O`MehfS+!ETt5C%SPP)Vim zIRl`$X58`;MkSmjRu1!w=mWeI=1yRX1K)?uvg?k}z`gUvm7C1yI#NY*O3>?U?x$V( zYsLA^dIz5j<*DHLJZG;KphL9T@JAD2XXAUC4w}CC!L1?e-#pg6vW-f8m&+jNbHPf1 zY|k+737CfrKw~g{uokXh&F+~Ec0Vdn_>sm*KwD%V1z`9KFUmR#eQJ+@;hc9I=|XO0?h9Cq|;tgn-FAlf!W1 z#6_6gDps8asm{v3{X(rl@|f1T)su(GUXRJji_^@vErP4cxm$1BR(^b}iGo}1C3Po; z-)Z6tMB!{w#Y7(wY)nv-Q|9~S)|^w&hi_W|1o4$a0okErET^eEz*prWw;!T0xV+wD z5*{$JQ2!UY+n6R;%{tfoNM!v- zV%+kHz^{>{B~qXxcB;KW`jvst0>5<^dDj6H$0Qv@Qy^SlcQbw8e0PE@^%U-@2%LxX zqO;OM5t%)mns~xJf&IOc3T@8YwmI3O>p4BN%{{sTeIUDSF)2}J%8&d+sgKE zMh#bp6ni-|^*VWs3hKA_Zga$jf82Ho3h)Bx=c}`yj!UtdccspB&Wy4J8R_HLPv>-z zVe%ywD6Su=fgnOy^)vi^qYvUF2h3lEKSoj@P*x#>{=0a(Wd#aVr%S$(G14}#4+8}Ehzl6G*?eBt9cY@XL3T6LKz z#X%T+?*2Q%%DX$l((=85*w94hv{9!A(&|N~?;K1Yt zzgZ7;&L77x=Agys@WZ#@WC&F6#%#o~Wd|xEk|6ZwerYPolswKJbd?MW$^pl`hGw$Y zB1&Lv;;<@-M*QfZXfqSZR6!WzQmg?O3?sJFYlQDce;DGRGgssmfX?@2LVC)J`m96*I7HKSUz>)?S7|=O5YjWEQ>S0-E*Y z5iv66n|XnHAz|6ncd-O0DP`)Y_h33|ZUwWQbG_)EbXM1~2{&w0#@5n&7q5XXlu`Ki zvp|)O%GOSJ?uFAB#IRXB!~v0}+sPW7K>?Ap830Es8|!xM4zyp%iyhdTtG867p2dFh z(zEyp-k&|51-qB2;Y_(e?4l)7V^nlSbli=jYSLMJZdYX_SUeJ?z*>RhG2gnF?K?u< z9ATFaj@HlyKEWR2gEOdfVnTi3o?Aovv7np^%mKTp?D1kr(ili6kUpq(?&^@Ju{kLwI%w*+<6sx-CB)pb6dLlS-{N z0rzWuYKaRw_l?`b?MZ8NF9IZT z5Rfm5|JjlKKj}Vat8aY@fU&h5lOw?L!t+QKU17!EO4#$NlNKf{Oo-(^S|(vjlo^zi zgb+4ND3MA11ZIx(9x0EUQ22zAy(|x?RNei?ywS>b73y}x^Ol*Fwd#GCnf6gXO-;zi z@x#R8Td_>2IPY7U!jR}08QJga&}l!S(l>lWbaMb6ge30;ncL3+_b&(twUDT`@HVrl zAlppLrQ5tW^u1oHe?pi_R)Q=M&o#c`otsdde5O2Clo#>x@+71e*T`g9)ceF}yUpEAU~4@e<+5i(*vh4NH|>J4S(ybdJ$g6i z*`C;|nL~~J+O3)MbDQ_F$t$fNrXlEdu|1yDYM^<(Pj1f$uFMPSk?-gi8!Y1*(QN`1 zF`S?13tLm$*^_c={G7^4hps5VoHAtgFVop2lRN3L*+6%JX-VOI*}7g;Rl=q6nK5?w zue+Z|vsDl-?{xe8xD?&a=XjR4<5BCBpU)?P^?72>02!3UXMYK6qx_78bq&LaK-Y87 z@_NB&^6DSx^!z@YS(=0itmK1+4VsdYEY@-{@wX$A&`PBXS3Uo@M##j)|Bp(pCZ!KIJLn2wInkqCxUZ@w;gSG z%+%R;CoNnO7{2*5Qm5?^!_`el0uVkBhk|R~LCj042jvG{jM7JV5z=!_I4b=GSw9q} zcvgsCuuOk*#Mwxtl@pGe2Z*GQJ+11p>8|&b!^E}SFnfAie+)#pkvax8jn7d$-ch~i z1d7ryN@HZtL^D*08RcR<%h__I_j!boc|xVHI^n0Nxnfs!!W z)Os7`3c0)evWe(?)aj=`CaO*C5jLM<8yx(*cH7?36ljfrXLObeo(I_FSeW?txpW}b zt2Sz#7~(h|j3wKs{|;`skB@)gKXLti24%n3I{+~n!f(yS)@)nC_>+SQ>L>(w{10H* zYyat&DqxJzph%`(jAeMr0))e@ztlZ?ab-N7p5N#2+Naxp&c~YvC{5yT`+`rFZFkl z(09?MGacU9UY20~AgijNB^YaUqY&jYgCkcV-ztPUNoDKzajl^j+o#6?RKa+Ii{1vv z`P;P?Wz*-1$2|lcE<1(eWke&V^=iUo^&Dt=of={8Kf4QwXx)EKS5=5r~3iUANLia{)Y< zr+uV)5j@E~e=dK^Q3!mIAhBNrytL*0bnXefTRmH{w7fXX*n>B^1hnIx6qb-Rx{6gO z94xGcw}8N|voPqsf*xA;?3Pe}UTe~X0(rplB@SXAz3@oF?Y z$63F)8&moIsdX3&bTcjBT95N~n{FX$9ITKIg}R7DCH(a0=oq{Ei;0RzQ=p>*$Z3`! zhdy&R`7K)0CdV3Ogj@QztfLIYy5yVQ1ZLMFUUG(z)~(Af zYNUw#FY-WzKU&Ttr%@P@-*_qdKfJ`OwsVJO{uWLrK}ns7uSZuhw)vTRi^2Hy;5WP< z2fw3IE}5ZDUkGJPDtwD}hUVrI0Acv(X$VDLuS)60j&*iZO(+mYECRbaMDTl`VtAay zi}a6`55LvCISCb@1jTY^rhM^)a3r>jQf$Ahu0~uwJ#zVaHJkrTD-UnBmvp-&46Vu> zEg#pnz}_BeWeA@Yjo#ke`X!-{-c6F^z-Jfp4j5Neb5g&IBGI75WRpwbnYJL#8@Tsd z`*a(KEFS@$N?hw5@3qz=0m9q26G|w(Um9r zi-7(6FgzuLrD$e;SA+^X3~$IT5Db3Er)YwiujvZ6YH?$5v+VaCIX>88{nNHX`dT;_ zb0Lwn4j$47n9)j~B2J>dyQ}|qyy|F}r5@1X=T|Qgg0T;>%X~*;0{C>9E>C&HxM#-@ zyOEuz-Gj0CFb?ZLkcYc@qE#y0mI&Wf+9L~X`OP(_1~ zIaBa+_u4RR``kiXI)0@&^|i_SI9VP97QOqdV^cHYEG*nCG*Fos_fJQ@K>b;QjyV_W zwXr3Z`o6jFsNVtGng*touuo*;lRs8no6R5Z>)`;8Fm4{J(M z`Q&)LeH)J4ORPqyw-L0c_b)@#O=*kB`31&!oh@&H61T;?d-o+Sr?zkv5X)AD&}ZD} z>Auk#@KaW0&nsq_{#r7k9kdDYGx@i!mEGXs$01udxeU*spBh%t#fym#uPHf??n zkyT;?k0|FI@^#V#DV<{Jc| zNQiXqQcco&q!nQP`A3OGoqU72{d6~1A5IU+?*L`yo)X#)cQuxl9d2zG$7`FCt!MTv z7d5~-|F{0ibQKiX8nD&_t3n`AP?QJi9W$du6I#{outf#$!LUvc9d}X}?dY$g9RE(t z^1wst(MDkq(j%WhJ_EUZVQ+&=h;~!HXd-EQV)ov!lR#r>k$yT*6vI6hZG2&x zhqQBBq}I_cOKZ)HItB}{-*R(83Ped05P#h*DV`ME2a@0+`4Qk+@ed>vVhJ+nX)oXL zVrnVN?S3=3+ptm3t%6vJG_TN)#s@-G2=I2l-sf4H*SC+sT0oEj+!DlBh0u1{H=Ibj zQy>GGIXf|Nktc#j3EkjHSbxnZ_N@<@5OubWL9q=-(7rE?WeMVmaMby`y=*!0i|KN~ zvvO#<1<^!gRIj(2gp2~Mw_HEm>4VOR&F9_hD1o3V;y$Qq!7m*Lep zQZ1jUgryFI#zE?Z_lTJB>U(EM)+uC_=P_6O;h_sJ#64N6O$O*L1IAgOtyp>K?|cfF z_bdjzDL*bopeX9ZWN0Xgt!WpRZ^z$<7Qh3$H#09$AqT`E>O}HJpr?B-$C~t>N}>y_ z2$?)}!Hgujh}4(H|F)Pg&)f9BUfw~tKz9AHEfIn^{=EN3bY*d)OijMEGIcb`nXDnM zPZ6ji*38~Esf^v49Na)4wsl&Nd6s$?d(fc##@SUbO86KYc`JZ9<>dH$Uj&XS)OhYW zNAq6zcjDILN#Q!sl>w#abnRh_ot^_s+tXe4*L@vBzXz}h2^-GUB@4US9n0PB0>B|< zf-iP>+Ps_)-Y?U$r=D$4HZHRv5>Nf5j3ZLRkoKl6?Cz`A?Ef79F95f*Pf(#AG`gU= zj1zVkxK+a9ot{|s{>I^H?3{!=oQ9`DveYKd;Xdr^5!+>ix920v%VvHRSC(|vQvZ*> zi}y3n{!gdes<~jj**?SBD8uH5$9ht8HFMw%W2RA7xbrG`|11nN&Bf`Ltu2IN&AF#! z7#X_KnvAr@yn#ur-RN4^dSk@ngW5lTqWjWVh_2y|tL^cBT&^n7`llgPC(OwJHK|E< z0_V5QM;VSZyZr-Pjgjuc;_k}S1>mYBV%{euPf+T0wfOx~!OkkpSi_Q8lIVUNyfG^I3e=v9(AGT57}np+VFp zI!BMPyox2~9FMf*emqR{8Wkb(>|oyA*2&cZJf8SJQ^xPw$UBvDG5M4S*LJx1oN8PGe4jra2@C7gnn8RX~Bf6;pcZ`T9 zC?4Db%v)7`CaWG-6bD9`VT6n}Z zvbG~l{c;i*^HNURGN#kY=6^ZDwrBHkDg;^8(tQL&F_m_Fey@|Q0>SqW>OZKKqR19@ z6_M@Rj&$Usu#>t)RSN)w{?&c`+ z);ZWjDd>ub3+|QZ_CX~{xh8Av=vrE(nTUIWr^p~}yG!8QSBK}G65 zYBxNG3t5&#y>Qh4Ql++`Tt$kKjr~+|pAF{j>WKVTv;1S5q2hPfYfCOj;M}n;npzmr z=EJ0g+j4>nNbe~`rT>6SoPEco66TFK_2Ap=i-fg+F&_|3^<)~JS;wz zrM8dF-d)g=B(=+TQCy-j)92{BfT~-}AbMjBfQ3 z=c^vBnKWd|pQ+9HA%y=^$XQ24*{utFKpK>8L6B}q>68>4Mg*jDU;u}a7(z-K2`TAL zL6Ghc5b4gLTe^gy>x}n1>zwns&b@cP>s{~Kd#&fU_Vetu|NFg9I{FsI$gb%Rk!ZMG zm*1*2`xU#<{<=1z7eIF%tc)RwT%j&VeT`c?pZBo#fPRU1X+r1fCVhbIFzfKu%aXV6 zyi7Rthc@GRAoSy}zo7c+ihAH07f*bf{ngv>6^EFRu59m^vYz{H#~H&u+?6XkT+E2k z%{|Rxi_{jS7*aNUjW`bJK8$}LW`-0C-IHqTH;K+-pD7j!ue*9#foRjq{wTe0G#yKq z`f`)Df6akif!IjtQ2I^{Qn9-B+WNk<(|hX59x!X^pr9Gl4Ef%`G+{m`Xe=YTvHnAR zJuIHWnFrjh^NSoL5SR1dJjR4`wuxu0?_#c#_O66Qr}1{i0G`fjTXff4^wElopx{dK zKwZcijcMxR`VwQoIohg^S#unYLDixUEne6(9;d zz0`hKhwXU>Dn4jYYY>6foFo;)q!maMyC;-6Q`k#b!VR5?S=bgKwdb!3h16?t5=P+z zF8$;!NSz|~_PSbJ`Pyn?AzK|9bh|RbyCWs`8odF%++ecjGZ0)BWW!Lbp$&)}htaak zm9|?9lG4APLt&O?Ioz2wK3kYHrfcgo=lHoo4=tgziO>60JI!M(4TPd! zqZdq-*CI=WGA}e|vf4gH)VMm{ffm&#N4n2XCB=byR%rdY{AC{ZwMAIfN7h%bD=Z&W^Az7!(<&xcrV%6D(4CXeLkGKz zN!W;Q!jc4vQ=3t!8y}=55S|3adh_G8^sSR>BA?C4i0U1WgW1OUWOn31iFeE4R&iZ2 zhQC<6^v+}wa75xpn-cS@0`nQe5FA&WiaL6pnXOvlWM$a=o!uIKC-PvvyFG9>qTy-R z%1m97Cf9bAk^-$ao&>>Ero|N2u0L z$i9A$m+*uP(QG(!On{lEC&2QgMtLCM-V@wgg?Wy+^}GhHzUH;A^q*mv)*~1K3W8dJ z>{f1beAc8=_{YO^4sfwmVFM1N4Cs*{OhB1BZGE5$Q;GiwL9yA8xFuvp%;PtLf7@%< z+}AeFmG%y+H}g|ve-97w&#sHryp||S(xc17(sf`9Ap%XdxP2TO9SO&`mjfnaNK@+j zoi9HJiS;*4fonboT7W=3SK`kzp~bVHZPBa)3u^ldy~*^}tzj$$aeriI!?!A<_eRop zjosfD@ujE1D;GfAQq`Np1hNZL71sDw)Q|iLWt@W1As7C_HiW9lSNZgP`hQaatK*n3qVJx#)v>GBBQIo6d=o^=U*(_$SkbD-{ z;U(Z_pIRa2S|1hl%OSu@xi2ZacwAMHjl50KZ%)o9AU`5vqNyDuc{1Wp`xZTWGOv?` zml~HoBJsu54d_!s2kD$Plj!6<6_PG~vO_K?1b8OzWx#X^5}rBf0;Trhl-SUVs4f*j z5m5%cbM6KjEp+h|XA;H7H8Cq*(~(ts65fmfJ6kVrj63k2`jq9UF$Rxc^W#KO(_>iXo)B`PZFL9R=gsHY?w z|G}>=)1S(gKlHhk9>QB0r}R_lsYOyr0xOj_jp-}aKb7D&48#m2Jpg^lInqv}`6#vL zP>!E|VdEqR&NySEr(cttLNh3E+p&%|B7qRm+jGWfKCX5xYbDq~n$};AV6~(O9ZG1A z-D6)BVF+Z}*FdMnXStdsYO=7gGHkt!kMB`lHsoGf{$>^vWK|SPTzV+)JJUc#Pup?I zc<2ZZ03s|(yn zDq+KqMX+Lgg%0}`$Mww~m0iKmIe8P-?8Q&z)PI>*eddQy3iGvyRF;YsPG=>?w!GlS zdLEr@HFf=B*`)EaGq}9+$$3K2m|VWKvI8+Z_7vN**nK!#;X}nx3}KDsHFxqg0C!)&B2tDeHGf>(K>axEfMM%b>Uez zGx=?A`vR>vm77B{wdN+Ry1A+N=b5_eR-QqN)XC!W+-!huNSBoIkc*|n{NfE*NBXqt za>U(}pqtremtle}6S^_Dl^&#VJ<~y-dCH7lD*w{^ztB?nbEh^ z4KIq)A-~H3cz?kO5-}YnEkqH|gF{jOOn{!J&Eg zUx6{tHCm*ac52r2rXIvOi7r-2(F_=Jct3v0J10-t^;t3PvtTR2=3C3FfHn>19SG)S zC+l-bZYDCwbIw{cLR4b7f*=E%w+E>1_m$n8{e$);YXQ(r^My z4lx%)?v*|Zc>^l<3!@onX6GPlSKNT!LVz+VP^qI}75sJqL&oDU?_{9H zWuwVk&35}NpOr(|Z3I)JT$&#VoCfahy(&+Kv~Dfl-MSej%ub^Zop~G2&!vW+u+i#y zziZ~uiYX3perWMDxTPfptb3m&LRi)Ab(;@@VHEC3sx#~+WVRSmYz{AN`r+>A#E?G; zr1g((^tNxPEF#@yzVK6OQYp#~v*5V*OD#-H?Zej?CtQplxhnb+iIPWV*fUihwjW`T zGy=h0M*a^X#r&93RA&?lLSfc3Lp;WP>BCmYGS~auEo|CFQwNW6okx}#gqrjiUkx3R zfUT^82JScR&i89=v>qzwy})v?g7GzX7Dw_uI^e;SAvz0+!_2(MU+R(@0l8U8Tc`R| zkOz;`XM?hu1hJF1lXo*79<(_Bawxmu!e6+Eu+~5ZQwE0VWmJ3M65+!hCsMp?bL8`N z>4r@6r*bk6?cii9VlVhGd>Y<8-Y`&alprxMliKX#%v?IU^_Q5qQ&VmVP2P(G4vG+F zEE+d2EN6#~YIMgi@ub~HGr|<9Oa5fm6KrKYkiIBF$8nPAcBx&MJ{BvRyz(|@BBc1~ zCGYZ=w{#8-mhc*Y`F)AXbF z9{FZJw#YiRPjkW^A~>SzGdLH*mayg$cLi9W>)C4X*>dig1Y)dtiL3K3Bt!^?crx85 z9-N*h^~2ZlQ*G2#lhfqE@w=}HZnmhN(OBn^I?=jGBliiaU@mtT%}Fr(R=;0rR`A`l? zl^+@^eZx-ybStU7i1@MG^!x3BQyFF2(jG)@Dag>$#L+f;7?Nl43%BZr8e>lY9K^Ea6L2I_vgU3lZ-t z4fqFxZApxaSv=Z<+P=+|ADE7S`^&ct_)bIRL_e@F9?bJO&hfAHdd=VoG)m2b%+8t* zQVE6{YIw{=IQ!lmu!@pFMJB`T(8V4LJ(o~ro|P82rpyw5woc^ay24vnH@7k0B{0&uG1o-zJ|Lk0t|2icxx4`NwO8mB z(uvTUc^=pM-@6RgCG1UU?4!gL4JW5PAUShmSFvv6g&Xn9P{o3y;U+um3nLYv>9_Od42otiZ=|_>@htyU!GL93rBwgHtsg(G!z6^b4?Iu#)!^##_D}#$S{cq zC%4~V!S~$*$z_S_X}&y5z_)`{K`n|P&-|%_1w>+`VL6WVf*&QhDgl9=6w z`rpXL55=a9E(xI##2r;8KqKC=M$RrgTQjC;N-!t{tvJ`&W#Rs`A-`{aIAg9Hs4wGp zEw1}($3L7$$Xy%Lh|b5yjt_L~urmCt^Gr1~#1O|9y>Kw8}k^c7~B^fMfKO3y{-DL zM>{y!RbmY;E5k0!?K4G}^2_VbcFTIG?h5W5%H+f?-4V(G773qly1Rc!N>1M1+*-ab zRr4y$$e+8m<*7YBQASFNf~v!~&T@NiF`ArbVK%V>P+vt@SXfuUO`w`xmaS7>_I+%l zM+-DHobxGS{#2I#xE6{0P*@mw8QF1R2DqS1`f?`^j9j0sg|%8@1?mKyU|(Qjp57A> zFev{1{kz&CJx5uL+n_^eSXj}u)s2lZ4-=EWvxTZ=*W%Qa=0={q&+UnDSxE_RF=L>h z&MQ3KrC|BVonX?+$_y-Qlhdh?b)a}tR$2O256GH@4Di;wQR?ShvlrtP3Ix3zI3Qb+R< zQ;!DL23;(`N0OfLqHCmLeI1Y{-An(bAA4@@1+|c2xM{jzyPcR^nr>G&`^zMW*^r5iP1RZLvz^)kE)$o}!Y{ zQh&~0kz^0oX2Yw0+5_Q=Ori;MaArj^D(nIxJB9#(Gqm`Sb;d1WSkd8;6vt0_?$j1TOXGs($>eu;L;5+QeVS!j0Q)lvoxgSp*AOTgU*u!%&Uw5`Q=jP^! zZtOygX(iv07>shR-kJOOEaKvUFIpyVQ@?g(5x_WjSud?sK<;9*W*zOVVg3s~U82+@ znUz{=3LL-c9h;)hCmGK}KebBK^V{ZRq(+S~x3*+uW#<`Y;anX00RC>!+*|D2Z9+Ln zY$zWICD8z!Y@qNrHuiRWe@RK^Z(tU7mNsVAj%Lu`!q@*uO5jL2+aFH|6idykV4pbh zK9N|v1oB#Gl%v;^m`0z=nRih{T)9<<{Gb^K)Mwp~8H zK0QQNqV19A$2X`e_Y)f&!&bKS%8@1$rh9DLR;y!7JmLN#SAmzixqdCV;H0wTbvLw1 zK>FjV;G_rEZqm9}`EW-BAHPXkYGKLTes)%@hbPzd&@A*ec_-h$4_7$1l*&@#XP^b; zqx4hrYlZag3kCvFVBHn$7Ud72p#uP9s7!GHa7)VP?p2qA5LE7Ms8w3j>hFP?{&W1x zC$fM!f;AmsZ^4evHejdUmG~3nklpmA6BVY6il+N#_+Owb)aPFysO$fa(xY4!NJJq< zQ7`M?P}!(m{;w!SH{WCOGRZ`*^iYsxyKq$O*=djRUcF}+b1+P_Zy&-4B>%Rd$P z-=x2?a8Zvx>Oikzf6x8_BRKf# diff --git a/toolbox/+WBToolbox/BlockInitialization.m b/toolbox/matlab/+WBToolbox/BlockInitialization.m similarity index 100% rename from toolbox/+WBToolbox/BlockInitialization.m rename to toolbox/matlab/+WBToolbox/BlockInitialization.m diff --git a/toolbox/+WBToolbox/Mask2WBToolboxConfig.m b/toolbox/matlab/+WBToolbox/Mask2WBToolboxConfig.m similarity index 100% rename from toolbox/+WBToolbox/Mask2WBToolboxConfig.m rename to toolbox/matlab/+WBToolbox/Mask2WBToolboxConfig.m diff --git a/toolbox/+WBToolbox/PID.m b/toolbox/matlab/+WBToolbox/PID.m similarity index 100% rename from toolbox/+WBToolbox/PID.m rename to toolbox/matlab/+WBToolbox/PID.m diff --git a/toolbox/+WBToolbox/WBTPIDConfig.m b/toolbox/matlab/+WBToolbox/WBTPIDConfig.m similarity index 100% rename from toolbox/+WBToolbox/WBTPIDConfig.m rename to toolbox/matlab/+WBToolbox/WBTPIDConfig.m diff --git a/toolbox/+WBToolbox/WBToolboxConfig.m b/toolbox/matlab/+WBToolbox/WBToolboxConfig.m similarity index 100% rename from toolbox/+WBToolbox/WBToolboxConfig.m rename to toolbox/matlab/+WBToolbox/WBToolboxConfig.m diff --git a/toolbox/+WBToolbox/WBToolboxConfig2Mask.m b/toolbox/matlab/+WBToolbox/WBToolboxConfig2Mask.m similarity index 100% rename from toolbox/+WBToolbox/WBToolboxConfig2Mask.m rename to toolbox/matlab/+WBToolbox/WBToolboxConfig2Mask.m diff --git a/toolbox/export_library.m b/toolbox/matlab/export_library.m similarity index 56% rename from toolbox/export_library.m rename to toolbox/matlab/export_library.m index 9044fda4d..c452b7fd1 100644 --- a/toolbox/export_library.m +++ b/toolbox/matlab/export_library.m @@ -1,4 +1,4 @@ -addpath(genpath('../images')); +addpath(genpath('../../images')); fprintf('\nWhole Body toolbox exporting library to multiple versions\n'); @@ -7,27 +7,35 @@ quit; end +addpath(genpath('library')); libraryName = 'WBToolboxLibrary_repository'; try + % Load the library open_system(libraryName,'loadonly'); fprintf('\nLibrary loaded\n'); + + % Enable library capabilities if (strcmp(get_param(libraryName, 'EnableLBRepository'), 'off')) set_param(libraryName, 'Lock', 'off'); set_param(libraryName, 'EnableLBRepository', 'on'); set_param(libraryName, 'Lock', 'on'); - end; + end + + % Export the library fprintf('\nExporting for 2014b\n'); - % This does not completely work: images are not saved. - % Instad if saved form the GUI it works.. save_system(libraryName, 'WBToolboxLibrary', 'ExportToVersion', 'R2014B_SLX'); - fprintf('\nExporting for 2012a\n'); - save_system(libraryName, 'WBToolboxLibrary', 'ExportToVersion', 'R2012A_MDL'); + movefile('WBToolboxLibrary.slx', 'library/exported/WBToolboxLibrary.slx'); + % TODO: Check if mdl support is still required + % fprintf('\nExporting for 2012a\n'); + % save_system(libraryName, 'WBToolboxLibrary', 'ExportToVersion', 'R2012A_MDL'); + % movefile('WBToolboxLibrary.mdl', 'library/exported/WBToolboxLibrary.mdl'); + + % Unload the library close_system(libraryName); -catch ex; +catch + error('Failed to export WBToolbox library') end - + fprintf('\nDone\n'); exit(0) - - diff --git a/toolbox/WBToolboxLibrary_repository.mdl b/toolbox/matlab/library/WBToolboxLibrary_repository.mdl similarity index 74% rename from toolbox/WBToolboxLibrary_repository.mdl rename to toolbox/matlab/library/WBToolboxLibrary_repository.mdl index 357430b63..8e4a391ca 100644 --- a/toolbox/WBToolboxLibrary_repository.mdl +++ b/toolbox/matlab/library/WBToolboxLibrary_repository.mdl @@ -1,19 +1,21 @@ Library { Name "WBToolboxLibrary_repository" - Version 8.8 + Version 8.9 SavedCharacterEncoding "US-ASCII" LogicAnalyzerGraphicalSettings "" LogicAnalyzerPlugin "on" LogicAnalyzerSignalOrdering "" DiagnosticSuppressor "on" - SuppressorTable "22 serialization::archive 11 0 3 0 0 0 0 0" + SuppressorTable "22 serialization::archive 11 0 6 0 0 0 11 0" + SLCCPlugin "on" LibraryType "BlockLibrary" + LockLinksToLibrary on ScopeRefreshTime 0.035000 OverrideScopeRefreshTime on DisableAllScopes off FPTRunName "Run 1" MaxMDLFileLineLength 120 - LastSavedArchitecture "maci64" + LastSavedArchitecture "glnxa64" Object { $PropName "BdWindowsInfo" $ObjectID 1 @@ -23,7 +25,7 @@ Library { $ObjectID 2 $ClassName "Simulink.WindowInfo" IsActive [1] - Location [747.0, 53.0, 1280.0, 721.0] + Location [2245.0, 90.0, 1595.0, 866.0] Object { $PropName "ModelBrowserInfo" $ObjectID 3 @@ -40,20 +42,32 @@ Library { $ClassName "Simulink.ExplorerBarInfo" Visible [1] } - Object { - $PropName "EditorsInfo" - $ObjectID 5 - $ClassName "Simulink.EditorInfo" - IsActive [1] - ViewObjType "SimulinkTopLevel" - LoadSaveID "0" - Extents [1246.0, 559.0] - ZoomFactor [2.7309417040358746] - Offset [10.873563218390814, 6.1543513957307141] + Array { + Type "Simulink.EditorInfo" + Dimension 2 + Object { + $ObjectID 5 + IsActive [0] + ViewObjType "SimulinkSubsys" + LoadSaveID "369" + Extents [1557.0, 693.0] + ZoomFactor [2.6923076923076925] + Offset [178.33132569815649, 95.800000000000011] + } + Object { + $ObjectID 6 + IsActive [1] + ViewObjType "SimulinkTopLevel" + LoadSaveID "0" + Extents [1557.0, 693.0] + ZoomFactor [3.428251121076233] + Offset [11.916285153695213, 10.428057553956833] + } + PropName "EditorsInfo" } Object { $PropName "DockComponentsInfo" - $ObjectID 6 + $ObjectID 7 $ClassName "Simulink.DockComponentInfo" Type "GLUE2:PropertyInspector" ID "Property Inspector" @@ -65,26 +79,27 @@ Library { Width [640] Height [480] } - WindowState "AAAA/wAAAAD9AAAAAgAAAAAAAAC9AAAB+PwCAAAAA/sAAAAWAEQAbwBjAGsAVwBpAGQAZwBlAHQAMwEAAAAxAAAB+AAAA" + WindowState "AAAA/wAAAAD9AAAAAgAAAAAAAAC9AAACivwCAAAAA/sAAAAWAEQAbwBjAGsAVwBpAGQAZwBlAHQAMwEAAAAxAAAB+AAAA" "AAAAAAA+wAAABYARABvAGMAawBXAGkAZABnAGUAdAA0AAAAAAD/////AAAAAAAAAAD7AAAAUgBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0Ac" - "ABvAG4AZQBuAHQALwBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0AcABvAG4AZQBuAHQAAAAAAP////8AAABvAP///wAAAAEAAAAAAAAAAPwCA" + "ABvAG4AZQBuAHQALwBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0AcABvAG4AZQBuAHQAAAAANQAAAooAAABbAP///wAAAAEAAAAAAAAAAPwCA" "AAAAfsAAABUAEcATABVAEUAMgA6AFAAcgBvAHAAZQByAHQAeQBJAG4AcwBwAGUAYwB0AG8AcgAvAFAAcgBvAHAAZQByAHQAeQAgAEkAbgBzAHAAZ" - "QBjAHQAbwByAAAAAAD/////AAAAKgD///8AAAUAAAACZgAAAAEAAAACAAAAAQAAAAL8AAAAAQAAAAIAAAAP/////wAAAAAA/////wAAAAAAAAAA/" + "QBjAHQAbwByAAAAAAD/////AAAAKwD///8AAAY7AAAC9gAAAAEAAAACAAAAAQAAAAL8AAAAAQAAAAIAAAAP/////wAAAAAA/////wAAAAAAAAAA/" "////wEAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" - "////wEAAACE/////wAAAAAAAAAA/////wEAAAD2/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" - "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wEAAAFL/////wAAAAAAAAAA/" + "////wEAAAB6/////wAAAAAAAAAA/////wEAAADe/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" + "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wEAAAEt/////wAAAAAAAAAA/" "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA" } } + HideAutomaticNames off Created "Thu Feb 06 02:21:39 2014" Creator "jorhabib" UpdateHistory "UpdateHistoryNever" ModifiedByFormat "%" - LastModifiedBy "makaveli" + LastModifiedBy "dferigo" ModifiedDateFormat "%" - LastModifiedDate "Wed Aug 23 12:33:30 2017" - RTWModifiedTimeStamp 425392371 - ModelVersionFormat "1.%" + LastModifiedDate "Wed Nov 29 15:45:34 2017" + RTWModifiedTimeStamp 433871066 + ModelVersionFormat "1.%" ConfigurationManager "none" SampleTimeColors off SampleTimeAnnotations off @@ -92,6 +107,7 @@ Library { WideLines off ShowLineDimensions off ShowPortDataTypes off + PortDataTypeDisplayFormat "AliasTypeOnly" ShowEditTimeErrors on ShowEditTimeWarnings on ShowEditTimeAdvisorChecks off @@ -118,6 +134,7 @@ Library { FunctionConnectors off BrowserLookUnderMasks off SimulationMode "normal" + VisualizeLoggedSignalsWhenLoggingToFile off PauseTimes "5" NumberOfSteps 1 SnapshotBufferSize 10 @@ -149,20 +166,21 @@ Library { ExtModeAutoUpdateStatusClock on ShowModelReferenceBlockVersion off ShowModelReferenceBlockIO off + OrderedModelArguments on Array { Type "Handle" Dimension 1 Simulink.ConfigSet { - $ObjectID 7 - Version "1.16.5" + $ObjectID 8 + Version "1.17.0" DisabledProps [] Description "" Array { Type "Handle" Dimension 10 Simulink.SolverCC { - $ObjectID 8 - Version "1.16.5" + $ObjectID 9 + Version "1.17.0" DisabledProps [] Description "" StartTime "0.0" @@ -201,8 +219,8 @@ Library { SampleTimeProperty [] } Simulink.DataIOCC { - $ObjectID 9 - Version "1.16.5" + $ObjectID 10 + Version "1.17.0" DisabledProps [] Description "" Decimation "1" @@ -237,12 +255,13 @@ Library { ReturnWorkspaceOutputsName "out" Refine "1" LoggingToFile off + DatasetSignalFormat "timeseries" LoggingFileName "out.mat" LoggingIntervals "[-inf, inf]" } Simulink.OptimizationCC { - $ObjectID 10 - Version "1.16.5" + $ObjectID 11 + Version "1.17.0" Array { Type "Cell" Dimension 8 @@ -297,10 +316,13 @@ Library { BufferReusableBoundary on SimCompilerOptimization "off" AccelVerboseBuild off + OptimizeBlockOrder "off" + OptimizeDataStoreBuffers on + BusAssignmentInplaceUpdate on } Simulink.DebuggingCC { - $ObjectID 11 - Version "1.16.5" + $ObjectID 12 + Version "1.17.0" Array { Type "Cell" Dimension 1 @@ -387,6 +409,7 @@ Library { SymbolicDimMinMaxWarning "warning" LossOfSymbolicDimsSimulationWarning "warning" LossOfSymbolicDimsCodeGenerationWarning "error" + SymbolicDimsDataTypeCodeGenerationDiagnostic "error" BlockIODiagnostic "none" SFUnusedDataAndEventsDiag "warning" SFUnexpectedBacktrackingDiag "warning" @@ -405,10 +428,11 @@ Library { AllowedUnitSystems "all" UnitsInconsistencyMsg "warning" AllowAutomaticUnitConversions on + UnitDatabase "" } Simulink.HardwareCC { - $ObjectID 12 - Version "1.16.5" + $ObjectID 13 + Version "1.17.0" DisabledProps [] Description "" ProdBitPerChar 8 @@ -455,8 +479,8 @@ Library { UseSimulinkCoderFeatures on } Simulink.ModelReferenceCC { - $ObjectID 13 - Version "1.16.5" + $ObjectID 14 + Version "1.17.0" DisabledProps [] Description "" UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" @@ -474,8 +498,8 @@ Library { SupportModelReferenceSimTargetCustomCode off } Simulink.SFSimCC { - $ObjectID 14 - Version "1.16.5" + $ObjectID 15 + Version "1.17.0" DisabledProps [] Description "" SimCustomSourceCode "" @@ -499,11 +523,13 @@ Library { ModelFunctionsGlobalVisibility "on" CompileTimeRecursionLimit 50 EnableRuntimeRecursion on + MATLABDynamicMemAlloc on + MATLABDynamicMemAllocThreshold 65536 } Simulink.RTWCC { $BackupClass "Simulink.RTWCC" - $ObjectID 15 - Version "1.16.5" + $ObjectID 16 + Version "1.17.0" Array { Type "Cell" Dimension 13 @@ -585,11 +611,11 @@ Library { Type "Handle" Dimension 2 Simulink.CodeAppCC { - $ObjectID 16 - Version "1.16.5" + $ObjectID 17 + Version "1.17.0" Array { Type "Cell" - Dimension 25 + Dimension 27 Cell "IgnoreCustomStorageClasses" Cell "IgnoreTestpoints" Cell "InsertBlockDesc" @@ -615,6 +641,8 @@ Library { Cell "CustomSymbolStrModelFcn" Cell "CustomSymbolStrUtil" Cell "CustomUserTokenString" + Cell "CustomSymbolStrEmxType" + Cell "CustomSymbolStrEmxFcn" PropName "DisabledProps" } Description "" @@ -646,6 +674,8 @@ Library { CustomSymbolStrTmpVar "$N$M" CustomSymbolStrMacro "$R$N$M" CustomSymbolStrUtil "$N$C" + CustomSymbolStrEmxType "emxArray_$M$N" + CustomSymbolStrEmxFcn "emx$M$N" CustomUserTokenString "" CustomCommentsFcn "" DefineNamingRule "None" @@ -668,8 +698,8 @@ Library { } Simulink.GRTTargetCC { $BackupClass "Simulink.TargetCC" - $ObjectID 17 - Version "1.16.5" + $ObjectID 18 + Version "1.17.0" Array { Type "Cell" Dimension 18 @@ -701,8 +731,7 @@ Library { TargetLangStandard "C89/C90 (ANSI)" CodeReplacementLibrary "None" UtilityFuncGeneration "Auto" - ERTMultiwordTypeDef "System defined" - ERTMultiwordLength 256 + MultiwordTypeDef "System defined" MultiwordLength 2048 GenerateFullHeader on InferredTypesCompatibility off @@ -746,6 +775,8 @@ Library { UseToolchainInfoCompliant on GenerateSharedConstants on CoderGroups [] + AccessMethods [] + LookupTableObjectStructAxisOrder "1,2,3,4,..." UseMalloc off ExtMode off ExtModeStaticAlloc off @@ -766,8 +797,8 @@ Library { } } SlCovCC.ConfigComp { - $ObjectID 18 - Version "1.16.5" + $ObjectID 19 + Version "1.17.0" DisabledProps [] Description "Simulink Coverage Configuration Component" Name "Simulink Coverage" @@ -803,10 +834,11 @@ Library { CovUseTimeInterval off CovStartTime 0 CovStopTime 0 + CovMcdcMode "Masking" } hdlcoderui.hdlcc { - $ObjectID 19 - Version "1.16.5" + $ObjectID 20 + Version "1.17.0" DisabledProps [] Description "HDL Coder custom configuration component" Name "HDL Coder" @@ -823,7 +855,7 @@ Library { Name "Configuration" ExtraOptions "" CurrentDlgPage "Solver" - ConfigPrmDlgPosition [ 963, 135, 1843, 765 ] + ConfigPrmDlgPosition [ 963, 135, 1843, 765 ] } PropName "ConfigurationSets" } @@ -838,6 +870,7 @@ Library { FontWeight "normal" FontAngle "normal" ShowName on + HideAutomaticName on BlockRotation 0 BlockMirror off } @@ -863,7 +896,7 @@ Library { SelfModifiable "off" IconFrame "on" IconOpaque "opaque" - RunInitForIconRedraw "off" + RunInitForIconRedraw "analyze" IconRotate "none" PortRotate "default" IconUnits "autoscale" @@ -955,6 +988,7 @@ Library { SourceOfInitialOutputValue "Dialog" OutputWhenDisabled "held" InitialOutput "[]" + MustResolveToSignalObject off } Block { BlockType Product @@ -1031,8 +1065,9 @@ Library { } System { Name "WBToolboxLibrary_repository" - Location [747, 53, 2027, 774] + Location [2245, 90, 3840, 956] Open on + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "black" @@ -1043,9 +1078,9 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "273" + ZoomFactor "343" ReportName "simulink-default.rpt" - SIDHighWatermark "1773" + SIDHighWatermark "1789" Block { BlockType SubSystem Name "Utilities" @@ -1059,14 +1094,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 20 + $ObjectID 21 $ClassName "Simulink.Mask" Display "image(imread('utilities.png'))" } System { Name "Utilities" - Location [551, 44, 1831, 765] + Location [2245, 90, 3840, 956] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -1077,7 +1113,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "166" + ZoomFactor "213" Block { BlockType SubSystem Name "DampPinv" @@ -1090,11 +1126,11 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 21 + $ObjectID 22 $ClassName "Simulink.Mask" Object { $PropName "Parameters" - $ObjectID 22 + $ObjectID 23 $ClassName "Simulink.MaskParameter" Type "edit" Name "tol" @@ -1106,6 +1142,7 @@ Library { Name "DampPinv" Location [0, 29, 1280, 744] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -1152,6 +1189,7 @@ Library { Name "Damped Pseudo Inverse" Location [12, 45, 1279, 3773] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -1163,7 +1201,7 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "1619" + SIDHighWatermark "1622" Block { BlockType Inport Name "mat" @@ -1184,20 +1222,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "107::1618" + SID "107::1621" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 98 + ZOrder 101 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "107::1617" + SID "107::1620" Tag "Stateflow S-Function WBToolboxLibrary_repository 6" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 97 + ZOrder 100 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -1206,16 +1244,14 @@ Library { Port { PortNumber 2 Name "DPinv" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" } } Block { BlockType Terminator Name " Terminator " - SID "107::1619" + SID "107::1622" Position [460, 241, 480, 259] - ZOrder 99 + ZOrder 102 } Block { BlockType Outport @@ -1226,7 +1262,7 @@ Library { IconDisplay "Port number" } Line { - ZOrder 61 + ZOrder 66 SrcBlock "mat" SrcPort 1 Points [120, 0] @@ -1234,7 +1270,7 @@ Library { DstPort 1 } Line { - ZOrder 62 + ZOrder 67 SrcBlock "sigma" SrcPort 1 DstBlock " SFunction " @@ -1242,7 +1278,7 @@ Library { } Line { Name "DPinv" - ZOrder 63 + ZOrder 68 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 @@ -1250,14 +1286,14 @@ Library { DstPort 1 } Line { - ZOrder 64 + ZOrder 69 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 65 + ZOrder 70 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -1300,90 +1336,56 @@ Library { BlockType S-Function Name "DoFs converter" SID "1771" - Ports [1, 5] + Ports [1, 3] Position [240, 241, 385, 309] ZOrder 81 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend\n" FunctionName "WBToolbox" - Parameters "'YARPWBIConverter',robotName,localName,wbiFile,wbiList,yarp2WBIOption" + Parameters "'ModelPartitioner',WBTConfigParameters,configBlockAbsName,yarp2WBI" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 23 + $ObjectID 24 $ClassName "Simulink.Mask" Type "DoFs converter" Description "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on" - " its configuration.\nThe DoFs configuration is automatically currently taken from the WBI list option.\nThe robot" - " name is taken from the environment variable YARP_ROBOT_NAME.\n\nParameters:\n\n- Conversion direction: specify i" - "f you want to convert from YARP to the current DoFs serialization or viceversa.\n\nWBI parameters:\n\n- Robot Por" - "t Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use t" - "he name specified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name" - " of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the con" - "figuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole B" - "ody Interface\n" + " its configuration.\nThe robot name is taken from the environment variable YARP_ROBOT_NAME.\n\nParameters:\n\n- C" + "onversion direction: specify if you want to convert from YARP to the current DoFs serialization or viceversa.\n" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig" + "] = WBToolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n " + " clear WBTConfig;\ncatch\nend\n\n% ModelPartitioner Initialization\n% ===============================\n\nswitch" + " get_param(gcb, 'yarp2WBIOption')\n case 'From YARP to WBI'\n yarp2WBI = true;\n case 'From WBI to Y" + "ARP'\n yarp2WBI = false;\n otherwise\nend" Display "robotName = getenv('YARP_ROBOT_NAME');\n\ncurrentSelection = get_param(gcb,'yarp2WBIoption');\n\nif" " strcmp(currentSelection,'From YARP to WBI')\n direction = 'YARP -> DoFs';\nelse\n direction = 'DoFs -> YAR" "P';\nend\n\nfprintf('%s\\n\\n%s', robotName, direction);" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 24 - Type "popup" - Array { - Type "Cell" - Dimension 2 - Cell "From YARP to WBI" - Cell "From WBI to YARP" - PropName "TypeOptions" - } - Name "yarp2WBIOption" - Prompt "Conversion Direction" - Value "From YARP to WBI" - } - Object { - $ObjectID 25 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - } - Object { - $ObjectID 26 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - } - Object { - $ObjectID 27 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - } - Object { - $ObjectID 28 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" + RunInitForIconRedraw "off" + Object { + $PropName "Parameters" + $ObjectID 25 + $ClassName "Simulink.MaskParameter" + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "From YARP to WBI" + Cell "From WBI to YARP" + PropName "TypeOptions" } - PropName "Parameters" + Name "yarp2WBIOption" + Prompt "Conversion Direction" + Value "From YARP to WBI" } Array { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 29 + $ObjectID 26 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 30 + $ObjectID 27 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1391,55 +1393,33 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 31 + $ObjectID 28 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 32 - $ClassName "Simulink.dialog.TabContainer" - Array { - Type "Simulink.dialog.Tab" - Dimension 2 - Object { - $ObjectID 33 - Prompt "Block Parameters" - Object { - $PropName "DialogControls" - $ObjectID 34 + Array { + Type "Simulink.dialog.Control" + Dimension 2 + Object { + $ObjectID 29 $ClassName "Simulink.dialog.parameter.Popup" Name "yarp2WBIOption" - } - Name "Container4" - } - Object { - $ObjectID 35 - Prompt "WBI Parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 36 - Name "robotName" - } - Object { - $ObjectID 37 - Name "localName" - } - Object { - $ObjectID 38 - Name "wbiFile" - } + } + Object { + $ObjectID 30 + $ClassName "Simulink.dialog.Group" Object { - $ObjectID 39 - Name "wbiList" - } - PropName "DialogControls" - } - Name "Container7" + $PropName "DialogControls" + $ObjectID 31 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" } - PropName "DialogControls" + Name "ToggleButtonContainer" } - Name "Container3" + PropName "DialogControls" } Name "ParameterGroupVar" } @@ -1462,7 +1442,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 40 + $ObjectID 32 $ClassName "Simulink.Mask" Type "Minimum Jerk Trajectory Generator" Description "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk " @@ -1485,7 +1465,7 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 41 + $ObjectID 33 Type "checkbox" Name "externalSettlingTime" Prompt "External Settling Time" @@ -1496,42 +1476,42 @@ Library { "SettlingTime" } Object { - $ObjectID 42 + $ObjectID 34 Type "edit" Name "settlingTime" Prompt "Settling Time" Value "3" } Object { - $ObjectID 43 + $ObjectID 35 Type "edit" Name "sampleTime" Prompt "Sample Time" Value "0.01" } Object { - $ObjectID 44 + $ObjectID 36 Type "checkbox" Name "resetOnSettlingTime" Prompt "Reset on Settling Time Changes" Value "off" } Object { - $ObjectID 45 + $ObjectID 37 Type "checkbox" Name "firstDerivatives" Prompt "Output First Derivative" Value "on" } Object { - $ObjectID 46 + $ObjectID 38 Type "checkbox" Name "secondDerivatives" Prompt "Output Second Derivative" Value "on" } Object { - $ObjectID 47 + $ObjectID 39 Type "checkbox" Name "explicitInitialValue" Prompt "Explicit Initial Value" @@ -1544,11 +1524,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 48 + $ObjectID 40 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 49 + $ObjectID 41 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1556,38 +1536,38 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 50 + $ObjectID 42 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 51 + $ObjectID 43 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 52 + $ObjectID 44 Prompt "Trajectory Parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 4 Object { - $ObjectID 53 + $ObjectID 45 $ClassName "Simulink.dialog.parameter.CheckBox" Name "externalSettlingTime" } Object { - $ObjectID 54 + $ObjectID 46 $ClassName "Simulink.dialog.parameter.Edit" Name "settlingTime" } Object { - $ObjectID 55 + $ObjectID 47 $ClassName "Simulink.dialog.parameter.Edit" Name "sampleTime" } Object { - $ObjectID 56 + $ObjectID 48 $ClassName "Simulink.dialog.parameter.CheckBox" Name "resetOnSettlingTime" } @@ -1596,21 +1576,21 @@ Library { Name "Tab1" } Object { - $ObjectID 57 + $ObjectID 49 Prompt "Input/Output" Array { Type "Simulink.dialog.parameter.CheckBox" Dimension 3 Object { - $ObjectID 58 + $ObjectID 50 Name "firstDerivatives" } Object { - $ObjectID 59 + $ObjectID 51 Name "secondDerivatives" } Object { - $ObjectID 60 + $ObjectID 52 Name "explicitInitialValue" } PropName "DialogControls" @@ -1634,7 +1614,7 @@ Library { Ports [] Position [155, 14, 280, 51] ZOrder 23 - ForegroundColor "white" + ForegroundColor "[0.917647, 0.917647, 0.917647]" BackgroundColor "gray" ShowName off FunctionName "WBToolbox" @@ -1644,7 +1624,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 61 + $ObjectID 53 $ClassName "Simulink.Mask" Type "Real Time Synchronizer" Description "This block slows down the simulation trying to match the period specified \nas parameter (in se" @@ -1652,7 +1632,7 @@ Library { Display "disp('Real Time Synchronizer')" Object { $PropName "Parameters" - $ObjectID 62 + $ObjectID 54 $ClassName "Simulink.MaskParameter" Type "edit" Name "period" @@ -1661,6 +1641,247 @@ Library { } } } + Block { + BlockType SubSystem + Name "Robot" + SID "1774" + Ports [] + Position [435, 260, 510, 290] + ZOrder 95 + InitFcn "source = get_param(gcb,'ConfigSource');\n\nif strcmp(source, 'Workspace')\n object = get_param(gcb,'" + "ConfigObject');\n WBToolbox.WBToolboxConfig2Mask(gcb, object);\nend\n\nWBToolbox.Mask2WBToolboxConfig(gcb);\n\nc" + "lear object source" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 55 + $ClassName "Simulink.Mask" + SelfModifiable "on" + Display "disp('Config')" + RunInitForIconRedraw "off" + Array { + Type "Simulink.MaskParameter" + Dimension 8 + Object { + $ObjectID 56 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Workspace" + Cell "Mask" + PropName "TypeOptions" + } + Name "ConfigSource" + Prompt "Configuration from" + Value "Mask" + Callback "% Get the Workspace/Mask menu\nh = Simulink.Mask.get(gcb);\ncurrentConfigSource = get_param(gcb,'ConfigSo" + "urce');\n\nif strcmp(currentConfigSource,'Workspace')\n % Switch the visibility of the GUI elements\n set_para" + "m(gcb,'MaskVisibilities',{'on';'on';'on';'on';'on';'on';'on';'on';});\n h.Parameters(3).ReadOnly = 'on';\n h.P" + "arameters(4).ReadOnly = 'on';\n h.Parameters(5).ReadOnly = 'on';\n h.Parameters(6).ReadOnly = 'on';\n h.Par" + "ameters(7).ReadOnly = 'on';\n h.Parameters(8).ReadOnly = 'on';\n \n % Parse the object inserted in the Conf" + "igObject field\n currentConfigObject = get_param(gcb,'ConfigObject');\n WBToolbox.WBTConfig2Mask(gcb,currentCo" + "nfigObject);\n clear currentConfigObject;\nelseif strcmp(currentConfigSource,'Mask')\n % Switch the visibility" + " of the GUI elements\n set_param(gcb,'MaskVisibilities',{'on';'off';'on';'on';'on';'on';'on';'on';});\n h.Para" + "meters(3).ReadOnly = 'off';\n h.Parameters(4).ReadOnly = 'off';\n h.Parameters(5).ReadOnly = 'off';\n h.Par" + "ameters(6).ReadOnly = 'off';\n h.Parameters(7).ReadOnly = 'off';\n h.Parameters(8).ReadOnly = 'off';\n h.Pa" + "rameters(3).Enabled = 'on';\n h.Parameters(4).Enabled = 'on';\n h.Parameters(5).Enabled = 'on';\n h.Paramet" + "ers(6).Enabled = 'on';\n h.Parameters(7).Enabled = 'on';\n h.Parameters(8).Enabled = 'on';\nend\n\nclear h cur" + "rentConfigSource" + } + Object { + $ObjectID 57 + Type "edit" + Name "ConfigObject" + Prompt "Name of the object" + Value "'WBTConfigRobot'" + Tunable "off" + Visible "off" + Callback "% This code get called whatsoever\nif strcmp(char(get_param(gcb,'ConfigSource')),'Mask')\n return\nend" + "\n\n% Parse the object inserted in the ConfigObject field\ncurrentConfigObject = get_param(gcb,'ConfigObject');\nWBT" + "oolbox.WBTConfig2Mask(gcb,currentConfigObject);\n\nclear currentConfigObject;" + } + Object { + $ObjectID 58 + Type "edit" + Name "RobotName" + Prompt "Robot Name" + Value "'icub'" + } + Object { + $ObjectID 59 + Type "edit" + Name "UrdfFile" + Prompt "Urdf File" + Value "'model.urdf'" + } + Object { + $ObjectID 60 + Type "edit" + Name "ControlledJoints" + Prompt "Controlled Joints" + Value "{'l_elbow','l_shoulder_pitch','torso_roll'}" + } + Object { + $ObjectID 61 + Type "edit" + Name "ControlBoardsNames" + Prompt "Control Boards Names" + Value "{'left_arm','right_arm','torso'}" + } + Object { + $ObjectID 62 + Type "edit" + Name "LocalName" + Prompt "Local Name" + Value "'WBT'" + } + Object { + $ObjectID 63 + Type "edit" + Name "GravityVector" + Prompt "Gravity Vector" + Value "[0,0,-9.81]" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 64 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 65 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 66 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 67 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 68 + Prompt "From" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 2 + Object { + $ObjectID 69 + $ClassName "Simulink.dialog.parameter.Popup" + Name "ConfigSource" + } + Object { + $ObjectID 70 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "ConfigObject" + } + PropName "DialogControls" + } + Name "TabFrom" + } + Object { + $ObjectID 71 + Prompt "Data" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 6 + Object { + $ObjectID 72 + PromptLocation "left" + Name "RobotName" + } + Object { + $ObjectID 73 + PromptLocation "left" + Name "UrdfFile" + } + Object { + $ObjectID 74 + PromptLocation "left" + Name "ControlledJoints" + } + Object { + $ObjectID 75 + PromptLocation "left" + Name "ControlBoardsNames" + } + Object { + $ObjectID 76 + PromptLocation "left" + Name "LocalName" + } + Object { + $ObjectID 77 + PromptLocation "left" + Name "GravityVector" + } + PropName "DialogControls" + } + Name "TabData" + } + PropName "DialogControls" + } + Name "TabContainer" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Robot" + Location [550, 86, 1677, 725] + Open off + PortBlocksUseCompactNotation off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "600" + SIDHighWatermark "70" + Block { + BlockType Constant + Name "ImConfig" + SID "1774:67" + Position [20, 20, 50, 50] + ZOrder 81 + Value "0" + } + Block { + BlockType Terminator + Name "Terminator" + SID "1774:68" + Position [95, 25, 115, 45] + ZOrder 80 + } + Line { + ZOrder 1 + SrcBlock "ImConfig" + SrcPort 1 + DstBlock "Terminator" + DstPort 1 + } + } + } Block { BlockType S-Function Name "Simulator Synchronizer" @@ -1677,7 +1898,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 63 + $ObjectID 78 $ClassName "Simulink.Mask" Type "Simulator Synchronizer" Description "This block synchronizes with the external simulation on a simulator \n(only Gazebo is supported" @@ -1687,21 +1908,21 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 64 + $ObjectID 79 Type "edit" Name "period" Prompt "Controller Period (in seconds)" Value "0.01" } Object { - $ObjectID 65 + $ObjectID 80 Type "edit" Name "serverPortName" Prompt "Server Port Name" Value "'/clock/rpc'" } Object { - $ObjectID 66 + $ObjectID 81 Type "edit" Name "clientPortName" Prompt "Client Port Name" @@ -1723,11 +1944,11 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 67 + $ObjectID 82 $ClassName "Simulink.Mask" Object { $PropName "Parameters" - $ObjectID 68 + $ObjectID 83 $ClassName "Simulink.MaskParameter" Type "edit" Name "tol" @@ -1739,6 +1960,7 @@ Library { Name "TruncPinv" Location [0, 29, 1280, 744] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -1785,6 +2007,7 @@ Library { Name "Truncated PseudoInverse" Location [12, 45, 1279, 3773] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -1796,7 +2019,7 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "1610" + SIDHighWatermark "1613" Block { BlockType Inport Name "mat" @@ -1817,20 +2040,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "112::1609" + SID "112::1612" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 98 + ZOrder 101 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "112::1608" + SID "112::1611" Tag "Stateflow S-Function WBToolboxLibrary_repository 7" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 97 + ZOrder 100 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -1839,16 +2062,14 @@ Library { Port { PortNumber 2 Name "TPinv" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" } } Block { BlockType Terminator Name " Terminator " - SID "112::1610" + SID "112::1613" Position [460, 241, 480, 259] - ZOrder 99 + ZOrder 102 } Block { BlockType Outport @@ -1859,7 +2080,7 @@ Library { IconDisplay "Port number" } Line { - ZOrder 61 + ZOrder 66 SrcBlock "mat" SrcPort 1 Points [120, 0] @@ -1867,7 +2088,7 @@ Library { DstPort 1 } Line { - ZOrder 62 + ZOrder 67 SrcBlock "tol" SrcPort 1 DstBlock " SFunction " @@ -1875,7 +2096,7 @@ Library { } Line { Name "TPinv" - ZOrder 63 + ZOrder 68 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 @@ -1883,14 +2104,14 @@ Library { DstPort 1 } Line { - ZOrder 64 + ZOrder 69 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 65 + ZOrder 70 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -1944,11 +2165,11 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 69 + $ObjectID 84 $ClassName "Simulink.Mask" Type "YARP Clock" - Description "This block outputs the current YARP Time\nIn a nutshell, this block outputs the equivalent of t" - "he C++ function call\nyarp::os::Time::now()" + Description "This block outputs the current YARP Time.\nIn a nutshell, this block outputs the equivalent of " + "the C++ function call yarp::os::Time::now()" SelfModifiable "on" Display "disp('YARP Time')\n" } @@ -1968,7 +2189,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 70 + $ObjectID 85 $ClassName "Simulink.Mask" Type "YARP Read" Description "This block behaves as the command 'yarp read'. \nBy default it has the option 'Autoconnect' act" @@ -1986,35 +2207,35 @@ Library { Type "Simulink.MaskParameter" Dimension 6 Object { - $ObjectID 71 + $ObjectID 86 Type "edit" Name "portName" Prompt "Source Port Name" Value "'/portname'" } Object { - $ObjectID 72 + $ObjectID 87 Type "edit" Name "signalSize" Prompt "Port Size" Value "1" } Object { - $ObjectID 73 + $ObjectID 88 Type "checkbox" Name "blocking" Prompt "Blocking Read" Value "off" } Object { - $ObjectID 74 + $ObjectID 89 Type "checkbox" Name "timestamp" Prompt "Read Timestamp" Value "on" } Object { - $ObjectID 75 + $ObjectID 90 Type "checkbox" Name "autoconnect" Prompt "Autoconnect" @@ -2026,7 +2247,7 @@ Library { "t_string" } Object { - $ObjectID 76 + $ObjectID 91 Type "checkbox" Name "errorOnConnection" Prompt "Error on missing connection" @@ -2051,7 +2272,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 77 + $ObjectID 92 $ClassName "Simulink.Mask" Type "YARP Write" Description "This block behaves as the command 'yarp write'. \n\nBy default this block opens a port names as" @@ -2064,14 +2285,14 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 78 + $ObjectID 93 Type "edit" Name "portName" Prompt "Opened Port Name" Value "'/portname'" } Object { - $ObjectID 79 + $ObjectID 94 Type "checkbox" Name "autoconnect" Prompt "Autoconnect" @@ -2082,7 +2303,7 @@ Library { "';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val prompt_string" } Object { - $ObjectID 80 + $ObjectID 95 Type "checkbox" Name "errorOnConnection" Prompt "Error on missing connection" @@ -2105,7 +2326,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 81 + $ObjectID 96 $ClassName "Simulink.Mask" Type "Errors" Description "Computes two kinds of errors. The first is just the difference between x\nand y while the secon" @@ -2115,6 +2336,7 @@ Library { Name "errors" Location [0, 29, 1280, 744] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2248,7 +2470,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 82 + $ObjectID 97 $ClassName "Simulink.Mask" Type "Holder" Description "This block holds the first input value during the simulation." @@ -2257,6 +2479,7 @@ Library { Name "holder\n" Location [12, 45, 1340, 980] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2290,9 +2513,11 @@ Library { Ports [1, 1] Position [90, 60, 120, 90] ZOrder 10 - LibraryVersion "1.388" + LibraryVersion "1.391" SourceBlock "simulink/Logic and Bit\nOperations/Compare\nTo Constant" SourceType "Compare To Constant" + SourceProductName "Simulink" + SourceProductBaseCode "SL" ContentPreviewEnabled off relop "==" const "0" @@ -2317,6 +2542,7 @@ Library { Name "MATLAB Function" Location [12, 45, 1135, 3068] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2328,7 +2554,7 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "1610" + SIDHighWatermark "1619" Block { BlockType Inport Name "s" @@ -2349,20 +2575,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "1300::1609" + SID "1300::1612" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 86 + ZOrder 89 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "1300::1608" + SID "1300::1611" Tag "Stateflow S-Function WBToolboxLibrary_repository 1" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 85 + ZOrder 88 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -2371,16 +2597,14 @@ Library { Port { PortNumber 2 Name "s0" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" } } Block { BlockType Terminator Name " Terminator " - SID "1300::1610" + SID "1300::1613" Position [460, 241, 480, 259] - ZOrder 87 + ZOrder 90 } Block { BlockType Outport @@ -2391,7 +2615,7 @@ Library { IconDisplay "Port number" } Line { - ZOrder 61 + ZOrder 66 SrcBlock "s" SrcPort 1 Points [120, 0] @@ -2399,7 +2623,7 @@ Library { DstPort 1 } Line { - ZOrder 62 + ZOrder 67 SrcBlock "unused" SrcPort 1 DstBlock " SFunction " @@ -2407,7 +2631,7 @@ Library { } Line { Name "s0" - ZOrder 63 + ZOrder 68 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 @@ -2415,14 +2639,14 @@ Library { DstPort 1 } Line { - ZOrder 64 + ZOrder 69 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 65 + ZOrder 70 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -2483,14 +2707,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 83 + $ObjectID 98 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyActuators.png'),'center')" } System { Name "wholeBodyActuators" - Location [425, 373, 1725, 1134] + Location [2245, 90, 3840, 956] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2501,50 +2726,50 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "667" + ZoomFactor "300" Block { BlockType SubSystem Name "Set LowLevel PIDs" SID "1752" Ports [] - Position [745, 230, 820, 280] + Position [760, 230, 835, 280] ZOrder 41 - BackgroundColor "[0.827500, 0.576500, 0.603900]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + BackgroundColor "[0.513700, 0.851000, 0.670600]" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 84 + $ObjectID 99 $ClassName "Simulink.Mask" Type "Set Low Level PIDs" - Description "This block sets the low level PID values for the robot actuators.\n\nIf only one gain file is s" - "pecified, those gains are loaded at startup.\nOtherwise an additional port to this block is added which accept an" - " integer\nrepresenting the index in the list of gains to be loaded (also at runtime)\n\nAssuming DoFs is the numb" - "er of degrees of freedom of the robot,\nParameters:\n- PID Parameter: String specifying either a file containing " - "the PIDs for the\n low level control, or a list of files (in yarp Bottle format).\n\n- Robot Port" - " Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use th" - "e name specified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name " - "of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the conf" - "iguration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Bo" - "dy Interface\n" + Description "This block sets the low level PID values for the robot actuators.\n\nThe PIDs can be stored in " + "a WBToolbox.WBTPIDConfig object, each of them constructed from a WBToolbox.PID class.\nThe number of PIDs must ma" + "tch the DoFs of the Config block pointed by this SetLowLevelPID block.\n\nParameters:\n- WBTPIDConfig Object Name" + ": The name of the object which store the PIDs. It must be loaded in the workspace before the simulation runs\n- P" + "ID Type: the type of the target PIDs to set" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig" + "] = WBToolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n " + " clear WBTConfig;\ncatch\nend\n\n% SetLowLevelPIDs Initialization\n% ==============================\n\ntry\n " + " PIDObjectName = WBTPIDConfigObjectName;\n \n % Remove the apices if present\n if (PIDObjectName(1) == \"" + "'\" && ...\n PIDObjectName(end) == \"'\")\n PIDObjectName = PIDObjectName(2:end-1);\n end\n " + "\n % Get the struct from the class\n PIDs = evalin('base', PIDObjectName);\n if (isa(PIDs,'WBToolbox.WBT" + "PIDConfig'))\n WBTPIDConfigStruct = PIDs.getSimulinkParameters;\n end\nend\n" Display "pidType = get_param(gcb,'pidType');\ndescription = sprintf('Set Low Level\\n%s PIDs', pidType);\ndi" "sp(description);\n" + RunInitForIconRedraw "off" Array { Type "Simulink.MaskParameter" - Dimension 6 + Dimension 2 Object { - $ObjectID 85 + $ObjectID 100 Type "edit" - Name "pidParameters" - Prompt "PID parameter" + Name "WBTPIDConfigObjectName" + Prompt "WBTPIDConfig Object Name" Value "''" Tunable "off" } Object { - $ObjectID 86 + $ObjectID 101 Type "popup" Array { Type "Cell" @@ -2555,57 +2780,26 @@ Library { } Name "pidType" Prompt "PID Type" - Value "Torque" + Value "Position" Evaluate "off" Callback "% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(gcb,'pidType'" - ");\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]');\nelseif s" - "trcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0]');\nelseif st" - "rcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\nelseif strcmp(mas" - "kStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear maskStr" - } - Object { - $ObjectID 87 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 88 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 89 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 90 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" + ");\n\nswitch maskStr\n case 'Position'\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]')" + ";\n case 'Position Direct'\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0]');\n case " + "'Velocity'\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\n case 'Torque'\n s" + "et_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\n otherwise\n error('PID Type not recogn" + "ized');\nend\n\nclear maskStr" } PropName "Parameters" } Array { Type "Simulink.dialog.Group" - Dimension 2 + Dimension 3 Object { - $ObjectID 91 + $ObjectID 102 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 92 + $ObjectID 103 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -2613,75 +2807,49 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 93 + $ObjectID 104 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 94 - $ClassName "Simulink.dialog.TabContainer" - Array { - Type "Simulink.dialog.Tab" - Dimension 2 - Object { - $ObjectID 95 - Prompt "Block parameters" - Array { - Type "Simulink.dialog.parameter.Control" - Dimension 2 - Object { - $ObjectID 96 + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 2 + Object { + $ObjectID 105 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" - Name "pidParameters" - } - Object { - $ObjectID 97 + Name "WBTPIDConfigObjectName" + } + Object { + $ObjectID 106 $ClassName "Simulink.dialog.parameter.Popup" Name "pidType" - } - PropName "DialogControls" - } - Name "Container8" - } - Object { - $ObjectID 98 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 99 - Name "robotName" - } - Object { - $ObjectID 100 - Name "localName" - } - Object { - $ObjectID 101 - Name "wbiFile" - } - Object { - $ObjectID 102 - Name "wbiList" - } - PropName "DialogControls" - } - Name "Container5" - } - PropName "DialogControls" } - Name "Container4" + PropName "DialogControls" } Name "ParameterGroupVar" } + Object { + $ObjectID 107 + Object { + $PropName "DialogControls" + $ObjectID 108 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" + "ock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system(confi" + "gBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block name: %s'" + ",gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } PropName "DialogControls" } } System { Name "Set LowLevel PIDs" - Location [0, 29, 1280, 744] + Location [114, 82, 1709, 948] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2692,7 +2860,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "1000" + ZoomFactor "600" Block { BlockType S-Function Name "S-Function" @@ -2701,7 +2869,7 @@ Library { Position [125, 39, 185, 71] ZOrder 19 FunctionName "WBToolbox" - Parameters "'SetLowLevelPID',robotName,localName,wbiFile,wbiList,pidParameters,pidType" + Parameters "'SetLowLevelPID',WBTConfigParameters,configBlockAbsName,WBTPIDConfigStruct,pidType" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -2716,121 +2884,76 @@ Library { Position [645, 230, 720, 280] ZOrder 43 BackgroundColor "[0.513700, 0.851000, 0.670600]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 103 + $ObjectID 109 $ClassName "Simulink.Mask" Type "Set References" Description "This block sets the references for the robot actuators.\nThe type of control mode is specified " - "as a parameter in the block.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Refere" - "nces: Vector of size DoFs, representing the references to be sent \n to the robot controlled joint" - "s.\n\nParameters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name " - "of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name speci" - "fied in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports" - " opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of" - " the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface" - "\n" + "as a parameter in the block.\n\nAssuming DoFs is the number of degrees of freedom configured in the Config block " + "associated:\n\nInput:\n- References: Vector of size DoFs, representing the references to be sent to the robot con" + "trolled joints.\n- Reference Speed (Position): Set the reference speed used by the trajectory generator of the IP" + "ositionControl interface\n\nParameters:\n- Control Mode: The control mode. Choose one of the supplied mode." + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig" + "] = WBToolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n " + " clear WBTConfig;\ncatch\nend" Display "disp(get_param(gcb,'controlType'))\n%port_label('input',1,'References')" + RunInitForIconRedraw "off" Array { Type "Simulink.MaskParameter" - Dimension 7 + Dimension 2 Object { - $ObjectID 104 + $ObjectID 110 Type "popup" Array { Type "Cell" - Dimension 5 + Dimension 7 Cell "Position" Cell "Position Direct" Cell "Velocity" Cell "Torque" Cell "Open Loop" + Cell "PWM" + Cell "Current" PropName "TypeOptions" } Name "controlType" Prompt "Control Mode" Value "Position" Evaluate "off" - Callback "% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(gcb,'controlT" - "ype');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]');\nelse" - "if strcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0]');\nelsei" - "f strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\nelseif strcmp" - "(maskStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nelseif strcmp(maskStr, " - "'Open Loop')\n set_param(gcb,'BackgroundColor', '[0.98, 0.98, 0.98, 1.0]');\nend\nclear maskStr" - } - Object { - $ObjectID 105 - Type "popup" - Array { - Type "Cell" - Dimension 2 - Cell "Full" - Cell "Sublist" - PropName "TypeOptions" - } - Name "fullOrSubControl" - Prompt "Control Type" - Value "Full" - Callback "subOrFull = get_param(gcb, 'fullOrSubControl');\nif(strcmp(subOrFull, 'Sublist'))\n set_param(gcb, 'Ma" - "skVisibilities',{'on';'on';'on';'on';'on';'on';'on'});\nelse\n set_param(gcb, 'MaskVisibilities',{'on';'on';'off'" - ";'on';'on';'on';'on'});\nend\nclear subOrFull " - } - Object { - $ObjectID 106 - Type "edit" - Name "controlledJoints" - Prompt "Controlled Joint List" - Value "''" - Visible "off" - } - Object { - $ObjectID 107 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 108 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 109 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" + Callback "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param(gcb,'contro" + "lType');\n\nswitch maskStr\n case 'Position'\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, " + "1.0]');\n set_param(gcb,'MaskVisibilities', {'on';'on'});\n case 'Position Direct'\n set_param(gcb," + "'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0]');\n set_param(gcb,'MaskVisibilities', {'on';'off'});\n " + "case 'Velocity'\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\n set_param(gcb,'" + "MaskVisibilities', {'on';'off'});\n case 'Torque'\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6" + "039, 1.0]');\n set_param(gcb,'MaskVisibilities', {'on';'off'});\n case 'Open Loop'\n set_param(gcb," + "'BackgroundColor', '[0.98, 0.98, 0.98, 1.0]');\n set_param(gcb,'MaskVisibilities', {'on';'off'});\n case '" + "PWM'\n set_param(gcb,'BackgroundColor', '[1, 1, 1, 1.0]');\n set_param(gcb,'MaskVisibilities', {'on';'" + "off'});\n case 'Current'\n set_param(gcb,'BackgroundColor', '[0.96, 0.77, 0.46, 1.0]');\n set_param" + "(gcb,'MaskVisibilities', {'on';'off'});\n otherwise\n error('Control Type not recognized.')\nend\n\nclear " + " maskStr" } Object { - $ObjectID 110 + $ObjectID 111 Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" + Name "refSpeed" + Prompt "Reference Speed" + Value "50" } PropName "Parameters" } Array { Type "Simulink.dialog.Group" - Dimension 2 + Dimension 3 Object { - $ObjectID 111 + $ObjectID 112 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 112 + $ObjectID 113 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -2838,79 +2961,49 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 113 + $ObjectID 114 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 114 - $ClassName "Simulink.dialog.TabContainer" - Array { - Type "Simulink.dialog.Tab" - Dimension 2 - Object { + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 2 + Object { $ObjectID 115 - Prompt "Block parameters" - Array { - Type "Simulink.dialog.parameter.Control" - Dimension 3 - Object { - $ObjectID 116 $ClassName "Simulink.dialog.parameter.Popup" Name "controlType" - } - Object { - $ObjectID 117 - $ClassName "Simulink.dialog.parameter.Popup" - Name "fullOrSubControl" - } - Object { - $ObjectID 118 + } + Object { + $ObjectID 116 $ClassName "Simulink.dialog.parameter.Edit" - Name "controlledJoints" - } - PropName "DialogControls" - } - Name "Container8" - } - Object { - $ObjectID 119 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 120 - Name "robotName" - } - Object { - $ObjectID 121 - Name "localName" - } - Object { - $ObjectID 122 - Name "wbiFile" - } - Object { - $ObjectID 123 - Name "wbiList" - } - PropName "DialogControls" - } - Name "Container5" - } - PropName "DialogControls" + PromptLocation "left" + Name "refSpeed" } - Name "Container4" + PropName "DialogControls" } Name "ParameterGroupVar" } + Object { + $ObjectID 117 + Object { + $PropName "DialogControls" + $ObjectID 118 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" + "ock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system(confi" + "gBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block name: %s'" + ",gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } PropName "DialogControls" } } System { Name "Set References" - Location [535, 41, 1280, 744] + Location [2245, 90, 3840, 956] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2938,8 +3031,7 @@ Library { Position [125, 39, 185, 71] ZOrder 19 FunctionName "WBToolbox" - Parameters "'SetReferences',robotName,localName,wbiFile,wbiList,controlType,fullOrSubControl,controlledJo" - "ints" + Parameters "'SetReferences',WBTConfigParameters,configBlockAbsName,controlType,refSpeed" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -2968,14 +3060,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 124 + $ObjectID 119 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyModel.png'),'center')" } System { Name "wholeBodyModel" - Location [425, 373, 1725, 1134] + Location [2245, 90, 3840, 956] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -2986,7 +3079,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "309" + ZoomFactor "381" Block { BlockType SubSystem Name "Dynamics" @@ -2999,14 +3092,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 125 + $ObjectID 120 $ClassName "Simulink.Mask" Display "image(imread('Dynamics.png'))" } System { Name "Dynamics" - Location [425, 373, 1725, 1134] - Open off + Location [2245, 90, 3840, 956] + Open on + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -3017,7 +3111,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "219" + ZoomFactor "269" Block { BlockType SubSystem Name "Centroidal Momentum" @@ -3025,71 +3119,64 @@ Library { Ports [4, 1] Position [495, 101, 680, 164] ZOrder 72 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 126 + $ObjectID 121 $ClassName "Simulink.Mask" Type "Centroidal Momentum" Description "This block computed the 6 element centroidal momentum, as defined in:\n\"Centroidal dynamics of a huma" "noid robot\" - DE Orin, A Goswami, SH Lee - \nAutonomous Robots 35 (2-3), 161-176\n\nAssuming DoFs is the number of " - "degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" - "\n the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the con" - "figuration \n of the joints.\n- Base velocity: Vector of size 6 representing the linear and an" - "gular velocity\n of the base frame.\n- Joints velocity: Vector of size DoFs, representing the veloci" - "ty \n of the joints.\n\nOutput:\n- Centroidal Momentum: 6-element vector containg the centroidal m" - "omentum \n (3 value for linear momentum and 3 for angular momentum)\n\nParameters:\n- Robot Port Name" - ": Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name s" - "pecified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the port" - "s opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of t" - "he Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - Array { - Type "Simulink.MaskParameter" - Dimension 4 - Object { - $ObjectID 127 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 128 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 129 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 130 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" + "degrees of freedom of the robot:\n\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation betwe" + "en the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration o" + "f the joints.\n- Base velocity: Vector of size 6 representing the linear and angular velocity of the base frame.\n- " + "Joints velocity: Vector of size DoFs, representing the velocity of the joints.\n\nOutput:\n- Centroidal Momentum: 6-" + "element vector containg the centroidal momentum (3 value for linear momentum and 3 for angular momentum)" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" + RunInitForIconRedraw "on" + Object { + $PropName "DialogControls" + $ObjectID 122 + $ClassName "Simulink.dialog.Group" + Prompt "%" + Array { + Type "Simulink.dialog.Control" + Dimension 2 + Object { + $ObjectID 123 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Object { + $ObjectID 124 + $ClassName "Simulink.dialog.Group" + Object { + $PropName "DialogControls" + $ObjectID 125 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } + PropName "DialogControls" } - PropName "Parameters" + Name "DescGroupVar" } } System { Name "Centroidal Momentum" - Location [0, 23, 1280, 744] + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -3100,7 +3187,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "248" + ZoomFactor "347" Block { BlockType Inport Name "Base Pose" @@ -3144,7 +3231,7 @@ Library { Position [180, 11, 255, 144] ZOrder 19 FunctionName "WBToolbox" - Parameters "'CentroidalMomentum',robotName,localName,wbiFile,wbiList" + Parameters "'CentroidalMomentum',WBTConfigParameters,configBlockAbsName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -3201,84 +3288,63 @@ Library { Ports [4, 1] Position [400, 202, 540, 303] ZOrder 73 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 131 + $ObjectID 126 $ClassName "Simulink.Mask" Type "Get Generalized Bias Forces" - Description "This block retrieves the generalied bias forces of the robot.\n\nParameter:\n- Explicit Gravity. If Tr" - "ue, an additional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.81] is used." - "\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the " - "homogenous transformation between\n the base frame and the world frame.\n- Joint configuration: Vector of" - " size DoFs, representing the configuration \n of the joints.\n- Base velocity: Vector of size 6 r" - "epresenting the linear and angular velocity\n of the base frame.\n- Joints velocity: Vector of size " - "DoFs, representing the velocity of the joints.\n\nOutput:\n- Bias Forces: a Dofs + 6 vector representing the general" - "ized bias forces\n of the robot\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot." - " (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " - " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the unde" - "rlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interf" - "ace\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - Initialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on', ...\n'Name'," - " 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb,'/S-Function']);\n" - " add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S-Function/7', 'autorouti" - "ng','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gravity/1','S-Function/7');\n " - " delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function']);\n end\nend\n" - SelfModifiable "on" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 132 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 133 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 134 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 135 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" - } - Object { - $ObjectID 136 - Type "checkbox" - Name "explicitGravity" - Prompt "Explicit Gravity" - Value "off" + Description "This block retrieves the generalied bias forces of the robot.\n\nAssuming DoFs is the number of degree" + "s of freedom of the robot:\n\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between the" + " base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration of the " + "joints.\n- Base velocity: Vector of size 6 representing the linear and angular velocity of the base frame.\n- Joints" + " velocity: Vector of size DoFs, representing the velocity of the joints.\n\nOutput:\n- Bias Forces: a Dofs + 6 vecto" + "r representing the generalized bias forces of the robot." + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" + RunInitForIconRedraw "on" + Object { + $PropName "DialogControls" + $ObjectID 127 + $ClassName "Simulink.dialog.Group" + Prompt "%" + Array { + Type "Simulink.dialog.Control" + Dimension 2 + Object { + $ObjectID 128 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Object { + $ObjectID 129 + $ClassName "Simulink.dialog.Group" + Object { + $PropName "DialogControls" + $ObjectID 130 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } + PropName "DialogControls" } - PropName "Parameters" + Name "DescGroupVar" } } System { Name "Get Bias Forces" - Location [354, 32, 1634, 747] + Location [215, 73, 1810, 939] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -3289,12 +3355,11 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "255" - SIDHighWatermark "1748" + ZoomFactor "318" Block { BlockType Inport Name "Base Pose" - SID "1724:1725" + SID "1776" Position [10, 38, 40, 52] ZOrder 22 IconDisplay "Port number" @@ -3302,7 +3367,7 @@ Library { Block { BlockType Inport Name "Joint configuration" - SID "1724:1726" + SID "1777" Position [10, 68, 40, 82] ZOrder 24 Port "2" @@ -3311,7 +3376,7 @@ Library { Block { BlockType Inport Name "Base velocity" - SID "1724:1727" + SID "1778" Position [10, 98, 40, 112] ZOrder 26 Port "3" @@ -3320,7 +3385,7 @@ Library { Block { BlockType Inport Name "Joints velocity" - SID "1724:1728" + SID "1779" Position [10, 128, 40, 142] ZOrder 27 Port "4" @@ -3329,7 +3394,7 @@ Library { Block { BlockType Constant Name "Constant" - SID "1724:1742" + SID "1780" Position [-5, 157, 50, 173] ZOrder 30 ShowName off @@ -3338,7 +3403,7 @@ Library { Block { BlockType Gain Name "Gain" - SID "1724:1743" + SID "1781" Position [110, 180, 140, 210] ZOrder 31 ShowName off @@ -3350,12 +3415,12 @@ Library { Block { BlockType S-Function Name "S-Function" - SID "1724:1731" + SID "1782" Ports [6, 1] Position [180, 24, 240, 216] ZOrder 19 FunctionName "WBToolbox" - Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + Parameters "'InverseDynamics',WBTConfigParameters,configBlockAbsName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -3363,7 +3428,7 @@ Library { Block { BlockType Outport Name "Bias Forces" - SID "1724:1732" + SID "1783" Position [300, 113, 330, 127] ZOrder 25 IconDisplay "Port number" @@ -3436,82 +3501,61 @@ Library { Ports [2, 1] Position [605, 200, 745, 300] ZOrder 74 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 137 + $ObjectID 131 $ClassName "Simulink.Mask" Type "Gravity bias" - Description "This block compute the generalized bias forces due to the gravity\n\nParameter:\n- Explicit Gravity. I" - "f True, an additional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.81] is u" - "sed.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representin" - "g the homogenous transformation between\n the base frame and the world frame.\n- Joint configuration: Ve" - "ctor of size DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Gravity: a D" - "ofs + 6 vector representing the torques due to the gravity.\n\nParameters:\n- Robot Port Name: Name of the ports ope" - "ned by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " - " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underly" - "ing Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface" - "\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - Initialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on', ...\n'Name'," - " 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb,'/S-Function']);\n" - " add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S-Function/7', 'autorouti" - "ng','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gravity/1','S-Function/7');\n " - " delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function']);\n end\nend\n" - SelfModifiable "on" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 138 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 139 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 140 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 141 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" - } - Object { - $ObjectID 142 - Type "checkbox" - Name "explicitGravity" - Prompt "Explicit Gravity" - Value "off" + Description "This block compute the generalized bias forces due to the gravity\n\nAssuming DoFs is the number of de" + "grees of freedom of the robot:\n\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" + " the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration of " + "the joints.\n\nOutput:\n- Gravity: a Dofs + 6 vector representing the torques due to the gravity." + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" + RunInitForIconRedraw "off" + Object { + $PropName "DialogControls" + $ObjectID 132 + $ClassName "Simulink.dialog.Group" + Prompt "%" + Array { + Type "Simulink.dialog.Control" + Dimension 2 + Object { + $ObjectID 133 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Object { + $ObjectID 134 + $ClassName "Simulink.dialog.Group" + Object { + $PropName "DialogControls" + $ObjectID 135 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } + PropName "DialogControls" } - PropName "Parameters" + Name "DescGroupVar" } } System { Name "Get Gravity Forces" - Location [354, 32, 1634, 747] + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -3522,12 +3566,11 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "255" - SIDHighWatermark "1748" + ZoomFactor "285" Block { BlockType Inport Name "Base Pose" - SID "1733:1734" + SID "1784" Position [10, 38, 40, 52] ZOrder 22 IconDisplay "Port number" @@ -3535,7 +3578,7 @@ Library { Block { BlockType Inport Name "Joint configuration" - SID "1733:1735" + SID "1785" Position [10, 68, 40, 82] ZOrder 24 Port "2" @@ -3544,7 +3587,7 @@ Library { Block { BlockType Constant Name "Constant" - SID "1733:1744" + SID "1786" Position [0, 97, 55, 113] ZOrder 32 ShowName off @@ -3553,7 +3596,7 @@ Library { Block { BlockType Gain Name "Gain" - SID "1733:1745" + SID "1787" Position [100, 120, 130, 150] ZOrder 33 ShowName off @@ -3565,12 +3608,12 @@ Library { Block { BlockType S-Function Name "S-Function" - SID "1733:1740" + SID "1788" Ports [6, 1] Position [180, 24, 240, 216] ZOrder 19 FunctionName "WBToolbox" - Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + Parameters "'InverseDynamics',WBTConfigParameters,configBlockAbsName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -3578,7 +3621,7 @@ Library { Block { BlockType Outport Name "Gravity Torques" - SID "1733:1741" + SID "1789" Position [300, 113, 330, 127] ZOrder 25 IconDisplay "Port number" @@ -3658,73 +3701,63 @@ Library { Position [190, 199, 355, 331] ZOrder 75 FunctionName "WBToolbox" - Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + Parameters "'InverseDynamics',WBTConfigParameters,configBlockAbsName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 143 + $ObjectID 136 $ClassName "Simulink.Mask" Type "Inverse Dynamics" - Description "This block compute the inverse dynamics of the robot.\n\nParameter:\n- Explicit Gravity. If True, an a" - "dditional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.81] is used.\n\nAssu" - "ming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homoge" - "nous transformation between\n the base frame and the world frame.\n- Joint configuration: Vector of size" - " DoFs, representing the configuration \n of the joints.\n- Base velocity: Vector of size 6 rep" - "resenting the linear and angular velocity\n of the base frame.\n- Joints velocity: Vector of size Do" - "Fs, representing the velocity \n of the joints.\n- Base acceleration: Vector of size 6 representin" - "g the linear and angular acceleration\n of the base frame.\n- Joints acceleration: Vector of size Do" - "Fs, representing the acceleration \n of the joints.\n- Gravity: Vector of size 3, denoting the acc" - "eleration vector w.r.t. the world frame.\n\n\nOutput:\n- Torques: a Dofs + 6 vector representing the corresponding t" - "orques required\n to achive the desired accelerations given the robot state\n\nParameters:\n- Robot Port N" - "ame: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the nam" - "e specified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the p" - "orts opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration o" - "f the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Description "This block compute the inverse dynamics of the robot.\n\nAssuming DoFs is the number of degrees of fre" + "edom of the robot:\n\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between the base fr" + "ame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration of the joints.\n" + "- Base velocity: Vector of size 6 representing the linear and angular velocity of the base frame.\n- Joints velocity" + ": Vector of size DoFs, representing the velocity of the joints.\n- Base acceleration: Vector of size 6 representing " + "the linear and angular acceleration of the base frame.\n- Joints acceleration: Vector of size DoFs, representing the" + " acceleration of the joints.\n\nOutput:\n- Torques: a Dofs + 6 vector representing the corresponding torques require" + "d to achive the desired accelerations given the robot state" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" Display "port_label('output', 1, 'Torques')\n\nport_label('input', 1, 'Base pose')\nport_label('input', 2, 'Joints" " configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joints velocity')\nport_label('in" - "put', 5, 'Base acceleration')\nport_label('input', 6, 'Joints acceleration')\n\n\ngravity = get_param(gcb, 'explicit" - "Gravity');\nif(strcmp(gravity, 'on'))\n port_label('input', 7, 'Gravity')\nend\n" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 144 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - } - Object { - $ObjectID 145 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - } - Object { - $ObjectID 146 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - } - Object { - $ObjectID 147 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - } - Object { - $ObjectID 148 - Type "checkbox" - Name "explicitGravity" - Prompt "Explicit Gravity" - Value "off" + "put', 5, 'Base acceleration')\nport_label('input', 6, 'Joints acceleration')\n" + RunInitForIconRedraw "on" + Object { + $PropName "DialogControls" + $ObjectID 137 + $ClassName "Simulink.dialog.Group" + Prompt "%" + Array { + Type "Simulink.dialog.Control" + Dimension 2 + Object { + $ObjectID 138 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Object { + $ObjectID 139 + $ClassName "Simulink.dialog.Group" + Object { + $PropName "DialogControls" + $ObjectID 140 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } + PropName "DialogControls" } - PropName "Parameters" + Name "DescGroupVar" } } } @@ -3735,68 +3768,61 @@ Library { Ports [2, 1] Position [250, 104, 390, 171] ZOrder 32 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 149 + $ObjectID 141 $ClassName "Simulink.Mask" Type "Mass Matrix" Description "This block retrieves the robot mass matrix.\n\nAssuming DoFs is the number of degrees of freedom of th" - "e robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n the base " - "frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration \n " - " of the joints.\n\nOutput:\n- Mass Matrix: a (Dofs + 6) x (Dofs + 6) matrix representing the mass matrix " - "\n of the robot\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot. (e.g. icub)." - "\n Set an empty string ('') to use the name specified in the \n Whole Body Inter" - "face configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- W" - "BI filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Name: name of the" - " list of joints used to configure the Whole Body Interface\n" - Array { - Type "Simulink.MaskParameter" - Dimension 4 - Object { - $ObjectID 150 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 151 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 152 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 153 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" + "e robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between the base frame and the " + "world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration of the joints.\n\nOutput:\n" + "- Mass Matrix: a (Dofs + 6) x (Dofs + 6) matrix representing the mass matrix of the robot" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" + RunInitForIconRedraw "on" + Object { + $PropName "DialogControls" + $ObjectID 142 + $ClassName "Simulink.dialog.Group" + Prompt "%" + Array { + Type "Simulink.dialog.Control" + Dimension 2 + Object { + $ObjectID 143 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Object { + $ObjectID 144 + $ClassName "Simulink.dialog.Group" + Object { + $PropName "DialogControls" + $ObjectID 145 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } + PropName "DialogControls" } - PropName "Parameters" + Name "DescGroupVar" } } System { Name "Mass Matrix" - Location [589, 68, 1869, 783] + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -3807,7 +3833,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "248" + ZoomFactor "455" Block { BlockType Inport Name "Base Pose" @@ -3833,7 +3859,7 @@ Library { Position [125, 37, 185, 68] ZOrder 19 FunctionName "WBToolbox" - Parameters "'MassMatrix',robotName,localName,wbiFile,wbiList" + Parameters "'MassMatrix',WBTConfigParameters,configBlockAbsName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -3885,14 +3911,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 154 + $ObjectID 146 $ClassName "Simulink.Mask" Display "image(imread('jacobian.png'))" } System { Name "Jacobians" - Location [425, 373, 1725, 1134] + Location [325, 44, 1920, 910] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -3903,95 +3930,55 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "322" - Block { - BlockType SubSystem - Name "DotJ Nu" - SID "1683" - Ports [4, 1] - Position [590, 170, 755, 265] - ZOrder 67 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 155 - $ClassName "Simulink.Mask" - Type "DotJ Nu" - Description "This block computes the product between the time derivative of the\n Jacobian of the specified" - " frame and the state (base and joints)\n velocity vector.\n\nAssuming DoFs is the number of degrees of freedo" - "m of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n th" - "e the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration \n" - " of the joints.\n- Base velocity: Vector of size 6 representing the linear and angular velocit" - "y\n of the base frame.\n- Joints velocity: Vector of size DoFs, representing the velocity \n " - " of the joints.\n\nOutput:\n- dotJ nu: a 6-d vector representing the product between the time derivative o" - "f the\n Jacobian of the specified frame and the state velocity vector\n\nParameters:\n- Frame name: the name" - " of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opened by the robot" - ". (e.g. icub).\n Set an empty string ('') to use the name specified in the \n Wh" - "ole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body I" - "nterface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Nam" - "e: name of the list of joints used to configure the Whole Body Interface\n" - Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('dot J_{',escapedFrameN" - "ame,'} \\nu'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input'," - " 2, 'Joint configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joint velocity')\n\ncle" - "ar escapedFrameName;" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 156 - Type "edit" - Name "frameName" - Prompt "Frame name" - Value "'frame'" - } - Object { - $ObjectID 157 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 158 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 159 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 160 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" - } - PropName "Parameters" + ZoomFactor "397" + Block { + BlockType SubSystem + Name "DotJ Nu" + SID "1683" + Ports [4, 1] + Position [590, 170, 755, 265] + ZOrder 67 + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 147 + $ClassName "Simulink.Mask" + Type "DotJ Nu" + Description "This block computes the product between the time derivative of the Jacobian of the specified frame and" + " the state (base and joints) velocity vector.\n\nAssuming DoFs is the number of degrees of freedom of the robot:\n\n" + "Input:\n- Base pose: 4x4 matrix representing the homogenous transformation between the the base frame and the world " + "frame.\n- Joint configuration: Vector of size DoFs, representing the configuration of the joints.\n- Base velocity: " + "Vector of size 6 representing the linear and angular velocity of the base frame.\n- Joints velocity: Vector of size " + "DoFs, representing the velocity of the joints.\n\nOutput:\n- dotJ nu: a 6-d vector representing the product between " + "the time derivative of the\n Jacobian of the specified frame and the state velocity vector\n\nParameters:\n-" + " Frame name: the name of the frame. It should be specified in the URDF model." + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" + Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('dot J_{',escapedFrameN" + "ame,'} \\nu'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input'," + " 2, 'Joint configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joint velocity')\n\ncle" + "ar escapedFrameName;" + RunInitForIconRedraw "on" + Object { + $PropName "Parameters" + $ObjectID 148 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "frameName" + Prompt "Frame name" + Value "'frame'" } Array { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 161 + $ObjectID 149 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 162 + $ObjectID 150 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -3999,56 +3986,34 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 163 + $ObjectID 151 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 164 - $ClassName "Simulink.dialog.TabContainer" Array { - Type "Simulink.dialog.Tab" + Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 165 - Prompt "Block parameters" - Object { - $PropName "DialogControls" - $ObjectID 166 + $ObjectID 152 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } - Name "Container8" - } - Object { - $ObjectID 167 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 168 - Name "robotName" - } - Object { - $ObjectID 169 - Name "localName" - } Object { - $ObjectID 170 - Name "wbiFile" - } + $ObjectID 153 + $ClassName "Simulink.dialog.Group" Object { - $ObjectID 171 - Name "wbiList" - } - PropName "DialogControls" + $PropName "DialogControls" + $ObjectID 154 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" } - Name "Container5" + Name "ToggleButtonContainer" } PropName "DialogControls" } - Name "Container4" - } Name "ParameterGroupVar" } PropName "DialogControls" @@ -4056,8 +4021,9 @@ Library { } System { Name "DotJ Nu" - Location [0, 29, 1280, 744] + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -4068,7 +4034,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "391" + ZoomFactor "428" Block { BlockType Inport Name "Base Pose" @@ -4112,7 +4078,7 @@ Library { Position [125, 4, 190, 126] ZOrder 19 FunctionName "WBToolbox" - Parameters "'DotJNu',robotName,localName,wbiFile,wbiList,frameName" + Parameters "'DotJNu',WBTConfigParameters,configBlockAbsName,frameName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -4121,7 +4087,7 @@ Library { BlockType Outport Name "dotJ dotnu" SID "1689" - Position [245, 43, 275, 57] + Position [245, 58, 275, 72] ZOrder 25 IconDisplay "Port number" } @@ -4143,7 +4109,6 @@ Library { ZOrder 3 SrcBlock "S-Function" SrcPort 1 - Points [20, 0; 0, -15] DstBlock "dotJ dotnu" DstPort 1 } @@ -4170,83 +4135,43 @@ Library { Ports [2, 1] Position [380, 190, 540, 245] ZOrder 39 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 172 + $ObjectID 155 $ClassName "Simulink.Mask" Type "Jacobian" Description "This block retrieves the Jacobian of the specified frame.\n\nAssuming DoFs is the number of degrees of" - " freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n " - " the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configura" - "tion \n of the joints.\n\nOutput:\n- Jacobian: a 6x6+dofs matrix representing the Jacobian of\n" - " the specified frame written in the world frame.\n\nParameters:\n- Frame name: the name of the frame. It" - " should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n " - " Set an empty string ('') to use the name specified in the \n Whole Body Interfac" - "e configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI " - "filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Name: name of the li" - "st of joints used to configure the Whole Body Interface\n" + " freedom of the robot:\n\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between the the" + " base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration of the " + "joints.\n\nOutput:\n- Jacobian: a 6x6+dofs matrix representing the Jacobian of the specified frame written in the wo" + "rld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world} J_{',escape" "dFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input" "', 2, 'Joint configuration')\n\nclear escapedFrameName;" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 173 - Type "edit" - Name "frameName" - Prompt "Frame name" - Value "'frame'" - } - Object { - $ObjectID 174 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 175 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 176 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 177 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" - } - PropName "Parameters" + RunInitForIconRedraw "on" + Object { + $PropName "Parameters" + $ObjectID 156 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "frameName" + Prompt "Frame name" + Value "'frame'" } Array { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 178 + $ObjectID 157 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 179 + $ObjectID 158 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4254,56 +4179,34 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 180 + $ObjectID 159 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 181 - $ClassName "Simulink.dialog.TabContainer" Array { - Type "Simulink.dialog.Tab" + Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 182 - Prompt "Block parameters" - Object { - $PropName "DialogControls" - $ObjectID 183 + $ObjectID 160 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } - Name "Container8" - } - Object { - $ObjectID 184 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 185 - Name "robotName" - } - Object { - $ObjectID 186 - Name "localName" - } Object { - $ObjectID 187 - Name "wbiFile" - } + $ObjectID 161 + $ClassName "Simulink.dialog.Group" Object { - $ObjectID 188 - Name "wbiList" - } - PropName "DialogControls" + $PropName "DialogControls" + $ObjectID 162 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" } - Name "Container5" + Name "ToggleButtonContainer" } PropName "DialogControls" } - Name "Container4" - } Name "ParameterGroupVar" } PropName "DialogControls" @@ -4311,8 +4214,9 @@ Library { } System { Name "Jacobian" - Location [208, 105, 1008, 627] + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -4323,7 +4227,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "237" + ZoomFactor "430" Block { BlockType Inport Name "Base Pose" @@ -4349,7 +4253,7 @@ Library { Position [125, 37, 185, 68] ZOrder 19 FunctionName "WBToolbox" - Parameters "'Jacobian',robotName,localName,wbiFile,wbiList,frameName" + Parameters "'Jacobian',WBTConfigParameters,configBlockAbsName,frameName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -4401,14 +4305,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 189 + $ObjectID 163 $ClassName "Simulink.Mask" Display "image(imread('forwardKinematics.png'))" } System { Name "Kinematics" - Location [425, 373, 1725, 1134] + Location [325, 44, 1920, 910] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -4419,7 +4324,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "326" + ZoomFactor "338" Block { BlockType SubSystem Name "Forward Kinematics" @@ -4427,83 +4332,43 @@ Library { Ports [2, 1] Position [350, 103, 500, 167] ZOrder 34 - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" - ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" - "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" - "nd" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 190 + $ObjectID 164 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " - "degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" - "\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the" - " configuration \n of the joints.\n\nOutput:\n- Forward Kinematics: a 4x4 matrix representing t" - "he homogenous transformation between\n the specified frame and the world frame.\n\nParameters:\n- Frame " - "name: the name of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opene" - "d by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " - " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlyin" - "g Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n" - "- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + "degrees of freedom of the robot:\n\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation betwe" + "en the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configurati" + "on of the joints.\n\nOutput:\n- Forward Kinematics: a 4x4 matrix representing the homogenous transformation between " + "the specified frame and the world frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified" + " in the URDF model." + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig] = WB" + "Toolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n clear " + "WBTConfig;\ncatch\nend" Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world} H_{',escape" "dFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input" "', 2, 'Joint configuration')\n\nclear escapedFrameName;" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 191 - Type "edit" - Name "frameName" - Prompt "Frame name" - Value "'frame'" - } - Object { - $ObjectID 192 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 193 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 194 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 195 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" - } - PropName "Parameters" + Object { + $PropName "Parameters" + $ObjectID 165 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "frameName" + Prompt "Frame name" + Value "'frame'" } Array { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 196 + $ObjectID 166 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 197 + $ObjectID 167 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4511,56 +4376,34 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 198 + $ObjectID 168 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 199 - $ClassName "Simulink.dialog.TabContainer" Array { - Type "Simulink.dialog.Tab" + Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 200 - Prompt "Block parameters" - Object { - $PropName "DialogControls" - $ObjectID 201 + $ObjectID 169 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } - Name "Container8" - } Object { - $ObjectID 202 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 203 - Name "robotName" - } - Object { - $ObjectID 204 - Name "localName" - } - Object { - $ObjectID 205 - Name "wbiFile" - } + $ObjectID 170 + $ClassName "Simulink.dialog.Group" Object { - $ObjectID 206 - Name "wbiList" - } - PropName "DialogControls" + $PropName "DialogControls" + $ObjectID 171 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" + "igBlock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system" + "(configBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block n" + "ame: %s',gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" } - Name "Container5" + Name "ToggleButtonContainer" } PropName "DialogControls" } - Name "Container4" - } Name "ParameterGroupVar" } PropName "DialogControls" @@ -4568,8 +4411,9 @@ Library { } System { Name "Forward Kinematics" - Location [0, 29, 1280, 744] + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -4580,7 +4424,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "391" + ZoomFactor "430" Block { BlockType Inport Name "Base Pose" @@ -4606,7 +4450,7 @@ Library { Position [125, 37, 185, 68] ZOrder 19 FunctionName "WBToolbox" - Parameters "'ForwardKinematics',robotName,localName,wbiFile,wbiList,frameName" + Parameters "'ForwardKinematics',WBTConfigParameters,configBlockAbsName,frameName" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off @@ -4651,6 +4495,7 @@ Library { Ports [3, 2] Position [350, 198, 525, 262] ZOrder 35 + Commented "on" InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" @@ -4659,7 +4504,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 207 + $ObjectID 172 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4683,21 +4528,21 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 208 + $ObjectID 173 Type "edit" Name "baseFrame" Prompt "Base Frame" Value "'root_link'" } Object { - $ObjectID 209 + $ObjectID 174 Type "edit" Name "endEffFrame" Prompt "End Effector frame" Value "'l_sole'" } Object { - $ObjectID 210 + $ObjectID 175 Type "popup" Array { Type "Cell" @@ -4711,7 +4556,7 @@ Library { Value "Full Constraint (Position and Orientation)" } Object { - $ObjectID 211 + $ObjectID 176 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -4719,7 +4564,7 @@ Library { Tunable "off" } Object { - $ObjectID 212 + $ObjectID 177 Type "edit" Name "localName" Prompt "Model Name" @@ -4727,7 +4572,7 @@ Library { Tunable "off" } Object { - $ObjectID 213 + $ObjectID 178 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -4735,7 +4580,7 @@ Library { Tunable "off" } Object { - $ObjectID 214 + $ObjectID 179 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -4748,11 +4593,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 215 + $ObjectID 180 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 216 + $ObjectID 181 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4760,34 +4605,34 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 217 + $ObjectID 182 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 218 + $ObjectID 183 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 219 + $ObjectID 184 Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 220 + $ObjectID 185 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "baseFrame" } Object { - $ObjectID 221 + $ObjectID 186 $ClassName "Simulink.dialog.parameter.Edit" Name "endEffFrame" } Object { - $ObjectID 222 + $ObjectID 187 $ClassName "Simulink.dialog.parameter.Popup" Name "optOption" } @@ -4796,25 +4641,25 @@ Library { Name "Container8" } Object { - $ObjectID 223 + $ObjectID 188 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 224 + $ObjectID 189 Name "robotName" } Object { - $ObjectID 225 + $ObjectID 190 Name "localName" } Object { - $ObjectID 226 + $ObjectID 191 Name "wbiFile" } Object { - $ObjectID 227 + $ObjectID 192 Name "wbiList" } PropName "DialogControls" @@ -4834,6 +4679,7 @@ Library { Name "Inverse Kinematics" Location [0, 23, 1280, 744] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -4945,6 +4791,7 @@ Library { Ports [2, 1] Position [560, 105, 720, 165] ZOrder 66 + Commented "on" InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" @@ -4953,7 +4800,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 228 + $ObjectID 193 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4979,14 +4826,14 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 229 + $ObjectID 194 Type "edit" Name "solverName" Prompt "Solver Name" Value "'/cartesianSolver'" } Object { - $ObjectID 230 + $ObjectID 195 Type "edit" Name "dofs" Prompt "#Dofs" @@ -4994,7 +4841,7 @@ Library { Tunable "off" } Object { - $ObjectID 231 + $ObjectID 196 Type "popup" Array { Type "Cell" @@ -5013,11 +4860,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 232 + $ObjectID 197 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 233 + $ObjectID 198 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5025,33 +4872,33 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 234 + $ObjectID 199 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 235 + $ObjectID 200 $ClassName "Simulink.dialog.TabContainer" Object { $PropName "DialogControls" - $ObjectID 236 + $ObjectID 201 $ClassName "Simulink.dialog.Tab" Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 237 + $ObjectID 202 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "solverName" } Object { - $ObjectID 238 + $ObjectID 203 $ClassName "Simulink.dialog.parameter.Edit" Name "dofs" } Object { - $ObjectID 239 + $ObjectID 204 $ClassName "Simulink.dialog.parameter.Popup" Name "optOption" } @@ -5070,6 +4917,7 @@ Library { Name "Remote Inverse Kinematics" Location [853, 51, 2214, 1013] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -5159,14 +5007,15 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 240 + $ObjectID 205 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyStates.png'),'center');" } System { Name "wholeBodyStates" - Location [425, 373, 1725, 1134] + Location [2245, 90, 3840, 956] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -5177,102 +5026,93 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "576" + ZoomFactor "600" Block { BlockType SubSystem - Name "Get Estimate" - SID "1671" - Ports [0, 1] - Position [360, 212, 440, 248] - ZOrder 53 + Name "Get Limits" + SID "1690" + Ports [0, 2] + Position [395, 218, 515, 247] + ZOrder 68 BackgroundColor "[0.513700, 0.851000, 0.670600]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 241 + $ObjectID 206 $ClassName "Simulink.Mask" - Type "Get Estimate" - Description "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of " - "freedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParame" - "ters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports" - " opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the " - "\n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by t" - "he underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole B" - "ody Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - Display "%disp(get_param(gcb,'estimateType'))\nport_label('output',1,get_param(gcb,'estimateType'))" + Type "Get Limits" + Description "This block provides the joint limits gathering data from either the Robot's Control Board or UR" + "DF model.\n\nOutput:\n\n* Max: 1xDoFs vector containing the maximum limit\n* Min: 1xDoFs vector containing the m" + "aximum limit\n\nMeasures are in radians." + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig" + "] = WBToolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n " + " clear WBTConfig;\ncatch\nend\n\n% GetLimits Initialization\n% =========================\n\nsourceLimit = get_p" + "aram(gcb,'limitsSource');\ntypeLimit = get_param(gcb,'limitsType');\nnotifyError = false;\n\nswitch sourceLimit\n" + " case 'ControlBoard'\n switch typeLimit\n case 'Position'\n limitsType = 'Con" + "trolBoardPosition';\n case 'Velocity'\n limitsType = 'ControlBoardVelocity';\n " + " otherwise\n notifyError = true;\n end\n case 'URDF'\n switch typeLimit\n " + " case 'Position'\n limitsType = 'ModelPosition';\n otherwise\n noti" + "fyError = true;\n end\nend\n\nif notifyError\n error('Limit Type not recognized');\nend\n\nclear source" + "Limit typeLimit notifyError" + SelfModifiable "on" + Display "fprintf('%s\\n(%s)',get_param(gcb,'limitsType'),get_param(gcb,'limitsSource'))\n\nport_label('outpu" + "t',1,'Min')\nport_label('output',2,'Max')" + RunInitForIconRedraw "off" Array { Type "Simulink.MaskParameter" - Dimension 5 + Dimension 2 Object { - $ObjectID 242 + $ObjectID 207 Type "popup" Array { Type "Cell" - Dimension 4 - Cell "Joints Position" - Cell "Joints Velocity" - Cell "Joints Acceleration" - Cell "Joints Torque" + Dimension 2 + Cell "ControlBoard" + Cell "URDF" PropName "TypeOptions" } - Name "estimateType" - Prompt "Estimate Type" - Value "Joints Position" - Evaluate "off" - Callback "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param(gcb,'estima" - "teType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0" - "]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]" - "');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.8706, 0.1333, 1" - ".0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]" - "');\nend\nclear maskStr" - } - Object { - $ObjectID 243 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 244 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 245 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" + Name "limitsSource" + Prompt "Limits Source" + Value "ControlBoard" + Callback "sourceLimit = get_param(gcb,'limitsSource');\nblockParameters = Simulink.Mask.get(gcb).Parameters;\nlimit" + "sTypeBlockParam = blockParameters(2);\n\nswitch sourceLimit\n case 'ControlBoard'\n limitsTypeBlockParam.T" + "ypeOptions = {'Position','Velocity'};\n %limitsTypeBlockParam.Value = limitsTypeBlockParam.TypeOptions{1};\n " + " case 'URDF'\n limitsTypeBlockParam.TypeOptions = {'Position'};\n %limitsTypeBlockParam.Value = limi" + "tsTypeBlockParam.TypeOptions{1};\n otherwise\n error('Limit Source not recognized');\nend\n\nclear sourceL" + "imit blockParameters limitsTypeBlockParam" } Object { - $ObjectID 246 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" + $ObjectID 208 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Position" + Cell "Velocity" + PropName "TypeOptions" + } + Name "limitsType" + Prompt "Limits Type" + Value "Position" + Evaluate "off" + Callback "% Get the mask parameter values. This is a cell array of strings.\n% \nmaskStr = get_param(gcb,'limitsT" + "ype');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]');\nelse" + "if strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\nelseif strcm" + "p(maskStr, 'Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.8706, 0.1333, 1.0]');\nelseif strcmp(ma" + "skStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear maskStr" } PropName "Parameters" } Array { Type "Simulink.dialog.Group" - Dimension 2 + Dimension 3 Object { - $ObjectID 247 + $ObjectID 209 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 248 + $ObjectID 210 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5280,65 +5120,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 249 + $ObjectID 211 Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 250 - $ClassName "Simulink.dialog.TabContainer" - Array { - Type "Simulink.dialog.Tab" - Dimension 2 - Object { - $ObjectID 251 - Prompt "Block parameters" - Object { - $PropName "DialogControls" - $ObjectID 252 - $ClassName "Simulink.dialog.parameter.Popup" - Name "estimateType" - } - Name "Container8" - } - Object { - $ObjectID 253 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 254 - Name "robotName" - } - Object { - $ObjectID 255 - Name "localName" - } - Object { - $ObjectID 256 - Name "wbiFile" - } - Object { - $ObjectID 257 - Name "wbiList" - } - PropName "DialogControls" - } - Name "Container5" - } - PropName "DialogControls" + Array { + Type "Simulink.dialog.parameter.Popup" + Dimension 2 + Object { + $ObjectID 212 + Name "limitsSource" + } + Object { + $ObjectID 213 + Name "limitsType" } - Name "Container4" + PropName "DialogControls" } Name "ParameterGroupVar" } + Object { + $ObjectID 214 + Object { + $PropName "DialogControls" + $ObjectID 215 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" + "ock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system(confi" + "gBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block name: %s'" + ",gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "ToggleButtonContainer" + } PropName "DialogControls" } } System { - Name "Get Estimate" - Location [653, 318, 2086, 1271] + Name "Get Limits" + Location [300, 122, 1706, 880] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -5349,129 +5170,111 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "1000" + ZoomFactor "692" + SIDHighWatermark "1773" Block { BlockType S-Function Name "S-Function" - SID "1672" - Ports [0, 1] - Position [125, 39, 185, 71] + SID "1690:1691" + Ports [0, 2] + Position [115, 33, 175, 102] ZOrder 19 FunctionName "WBToolbox" - Parameters "'GetEstimate',robotName,localName,wbiFile,wbiList,estimateType" + Parameters "'GetLimits',WBTConfigParameters,configBlockAbsName,limitsType" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off } Block { BlockType Outport - Name "Estimate" - SID "1673" - Position [210, 48, 240, 62] + Name "Min" + SID "1690:1692" + Position [220, 43, 250, 57] ZOrder 25 IconDisplay "Port number" } + Block { + BlockType Outport + Name "Max" + SID "1690:1693" + Position [220, 78, 250, 92] + ZOrder 26 + Port "2" + IconDisplay "Port number" + } Line { ZOrder 1 SrcBlock "S-Function" SrcPort 1 - DstBlock "Estimate" + DstBlock "Min" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "S-Function" + SrcPort 2 + DstBlock "Max" DstPort 1 } } } Block { BlockType SubSystem - Name "Get Limits" - SID "1690" - Ports [0, 2] - Position [475, 211, 570, 249] - ZOrder 68 + Name "Get Measurement" + SID "1671" + Ports [0, 1] + Position [395, 156, 515, 184] + ZOrder 53 BackgroundColor "[0.513700, 0.851000, 0.670600]" - InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" - "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" - "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" RequestExecContextInheritance off Variant off Object { $PropName "MaskObject" - $ObjectID 258 + $ObjectID 216 $ClassName "Simulink.Mask" - Type "Get Estimate" - Description "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of " - "freedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParame" - "ters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports" - " opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the " - "\n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by t" - "he underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole B" - "ody Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" - Display "disp(get_param(gcb,'limitsType'))\nport_label('output',1,'Min')\nport_label('output',2,'Max')" - Array { - Type "Simulink.MaskParameter" - Dimension 5 - Object { - $ObjectID 259 - Type "popup" - Array { - Type "Cell" - Dimension 1 - Cell "Position" - PropName "TypeOptions" - } - Name "limitsType" - Prompt "Limits Type" - Value "Position" - Evaluate "off" - Callback "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param(gcb,'limits" - "Type');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]'" - ");\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]')" - ";\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.8706, 0.1333, 1.0" - "]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]')" - ";\nend\nclear maskStr" - } - Object { - $ObjectID 260 - Type "edit" - Name "robotName" - Prompt "Robot Port Name" - Value "WBT_robotName" - Tunable "off" - } - Object { - $ObjectID 261 - Type "edit" - Name "localName" - Prompt "Model Name" - Value "WBT_modelName" - Tunable "off" - } - Object { - $ObjectID 262 - Type "edit" - Name "wbiFile" - Prompt "WBI filename" - Value "WBT_wbiFilename" - Tunable "off" - } - Object { - $ObjectID 263 - Type "edit" - Name "wbiList" - Prompt "WBI list name" - Value "WBT_wbiList" - Tunable "off" + Type "Get Measurement" + Description "This block gathers the measurement of the specified type.\n\nAssuming DoFs is the number of deg" + "rees of freedom of the robot,\n\nOutput:\n* References: Vector of size DoFs, representing the requested measureme" + "nt.\n\nParameters:\n* Control Mode: The control mode. Choose one of the supplied mode.\n" + Initialization "% WBBlock Initialization\n% ======================\n\ntry\n [configBlockAbsName, WBTConfig" + "] = WBToolbox.BlockInitialization(gcb, gcs);\n \n WBTConfigParameters = WBTConfig.getSimulinkParameters;\n " + " clear WBTConfig;\ncatch\nend" + Display "port_label('output', 1, get_param(gcb,'measuredType'))" + RunInitForIconRedraw "off" + Object { + $PropName "Parameters" + $ObjectID 217 + $ClassName "Simulink.MaskParameter" + Type "popup" + Array { + Type "Cell" + Dimension 4 + Cell "Joints Position" + Cell "Joints Velocity" + Cell "Joints Acceleration" + Cell "Joints Torque" + PropName "TypeOptions" } - PropName "Parameters" + Name "measuredType" + Prompt "Estimate Type" + Value "Joints Position" + Evaluate "off" + Callback "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param(" + "gcb,'measuredType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8" + "510, 0.6706, 1.0]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137," + " 0.6745, 1.0000, 1.0]');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '" + "[0.9255, 0.8706, 0.1333, 1.0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor'," + " '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear maskStr" } Array { Type "Simulink.dialog.Group" - Dimension 2 + Dimension 3 Object { - $ObjectID 264 + $ObjectID 218 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 265 + $ObjectID 219 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5479,65 +5282,39 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 266 + $ObjectID 220 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 267 - $ClassName "Simulink.dialog.TabContainer" - Array { - Type "Simulink.dialog.Tab" - Dimension 2 - Object { - $ObjectID 268 - Prompt "Block parameters" - Object { - $PropName "DialogControls" - $ObjectID 269 - $ClassName "Simulink.dialog.parameter.Popup" - Name "limitsType" - } - Name "Container8" - } - Object { - $ObjectID 270 - Prompt "WBI parameters" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 4 - Object { - $ObjectID 271 - Name "robotName" - } - Object { - $ObjectID 272 - Name "localName" - } - Object { - $ObjectID 273 - Name "wbiFile" - } - Object { - $ObjectID 274 - Name "wbiList" - } - PropName "DialogControls" - } - Name "Container5" - } - PropName "DialogControls" - } - Name "Container4" + $ObjectID 221 + $ClassName "Simulink.dialog.parameter.Popup" + Name "measuredType" } Name "ParameterGroupVar" } + Object { + $ObjectID 222 + Object { + $PropName "DialogControls" + $ObjectID 223 + $ClassName "Simulink.dialog.Button" + Prompt "Toggle Config Block Highlighting" + Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" + "ock,'HiliteAncestors'),'none'))\n hilite_system(configBlock,'find');\n else\n hilite_system(confi" + "gBlock,'none');\n end\ncatch\n error('[%s:ShowConfigBlock:Callback] Failed to process config block name: %s'" + ",gcb,configBlock);\nend\n\nclear configBlock" + Name "toggleHighlighting" + } + Name "Container8" + } PropName "DialogControls" } } System { - Name "Get Limits" - Location [0, 23, 1280, 744] + Name "Get Measurement" + Location [109, 127, 1339, 823] Open off + PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 ScreenColor "white" @@ -5548,49 +5325,33 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "411" + ZoomFactor "600" Block { BlockType S-Function Name "S-Function" - SID "1691" - Ports [0, 2] - Position [115, 33, 175, 102] + SID "1672" + Ports [0, 1] + Position [125, 39, 185, 71] ZOrder 19 FunctionName "WBToolbox" - Parameters "'GetLimits',robotName,localName,wbiFile,wbiList,limitsType" + Parameters "'GetMeasurement',WBTConfigParameters,configBlockAbsName,measuredType" SFunctionDeploymentMode off EnableBusSupport off SFcnIsStateOwnerBlock off } Block { BlockType Outport - Name "Min" - SID "1692" - Position [220, 43, 250, 57] + Name "Estimate" + SID "1673" + Position [210, 48, 240, 62] ZOrder 25 IconDisplay "Port number" } - Block { - BlockType Outport - Name "Max" - SID "1693" - Position [220, 78, 250, 92] - ZOrder 26 - Port "2" - IconDisplay "Port number" - } Line { ZOrder 1 SrcBlock "S-Function" SrcPort 1 - DstBlock "Min" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "S-Function" - SrcPort 2 - DstBlock "Max" + DstBlock "Estimate" DstPort 1 } } @@ -5600,7 +5361,7 @@ Library { Annotation { SID "1213" Name "WHOLE BODY TOOLBOX" - Position [172, 149, 311, 166] + Position [172, 149, 319, 165] InternalMargins [0, 0, 0, 0] FixedHeight off FixedWidth off @@ -5612,10 +5373,10 @@ Library { } Annotation { SID "1214" - Name "Copyright 2013-2016 iCub Facility Department, Istituto Italiano di Tecnologia\nThis software was s" + Name "Copyright 2013-2017 iCub Facility Department, Istituto Italiano di Tecnologia\nThis software was s" "upported by the FP7 EU Project CoDyCO (No. 600716 ICT 2011.2.1 Cognitive Systems and Robotics (b))\nhttp://www.c" "odyco.eu" - Position [102, 184, 379, 201] + Position [102, 184, 380, 207] InternalMargins [0, 0, 0, 0] FixedHeight off FixedWidth off @@ -5628,7 +5389,7 @@ Library { } #Finite State Machines # -# Stateflow 80000010 +# Stateflow 80000011 # # Stateflow { @@ -5637,7 +5398,7 @@ Stateflow { name "WBToolboxLibrary_repository" created "06-Feb-2014 11:51:26" isLibrary 1 - sfVersion 80000010 + sfVersion 80000011 firstTarget 26 } chart { diff --git a/toolbox/matlab/library/exported/WBToolboxLibrary.slx b/toolbox/matlab/library/exported/WBToolboxLibrary.slx new file mode 100644 index 0000000000000000000000000000000000000000..fbd2f293d35231ab7ea5dedd07e4f4cf08ac03aa GIT binary patch literal 535297 zcmaHSLy#{_@Z{LG{l>P9H@0otwr$(C^~Sbs&-}*Le*e?%#zyR+FMZ3(?uv@cECp#$ zFfAV5I4|J~Y}x)_=mx)?GT+dG*mIN3XxI=NVyI@5dD z+W0Ch$OSW^eWNeBQ<^$2L1+}2$!i;-72nsU@Ti5RwYbLgV`A;=VC-!=%gynhI{Ub6*5AP|`vGiE10yw?h~naExI(|n_P)?xG&eG&k=r@xOvJC$MD!QxUqfefF9oljeB zulodnJ*FTCy@(^j8|2?w+8_(At{-!pxfw)1qv|*(Gg*wBTvcaXpZDCwE--MrH6y)O zMPtH2jd0FNXhy8w70E%eBEvz<4>?rGd4i)w>%58bgyw6qYlavK32 zPETy-ke-0ctv|odyKgZMIq!h9Q#Uf4%@Evo2j=?K5Owdo=Cb)n>XNmWUmEQXr0{?7 z<5<*VGx{Gd68~|8|9|ph>;C^TWEwwZ2f_p==Kp814^@!1iW=4Jx`J9t;2#+Vs_dbt zqsR1KGI%t0SIddBPyH^R5fTUOHR`j|PHl-`(}ZW&)5C4c?^{X`O+s)2ls6Z#bR!G* zt}XSOveKv$Uy}vFp&ml(DMRTx0#;x*lxs&hvy-{93idS=rb_mTS8-Yo>n3^C-)B}+ z)&%D}3@hnUyJItgmwO!ESX~)}U^Qo}x^>L>6B zAiFs&x^`PX8vDHey8y8VsdgFv0bl&@kpKS*Am-s>YUgZeZ}&fMRX1)5A&3!4%)d0V zmrlMoY)op6e)(I2T(E%df;GsWVHBO-UJfupbvY7qD3<4KE*)VC7F6RVYrlm8XrBTA z1%YltNSIfKa4qk|9!sj8&}t0b0DB3 z2~Z&H|FAh*+Pd0U+F3Ig+1MLfn^+o}I~m&k51gA`OZP3#CdRLwevmQuMT$&EG{x>5 z7r_1IJ+I^SniKbJZl0f$1#%Nt;a@gM&kHVR|4(J`03N}hlxxn&vuP6(=+IIHN;E6q z$Gvvva2;iV2ENxb+2WO5vgKT_v>Uyjo=!M(28rz7Z?~hFMsvlp@m$ZJZMZ_JcQ*J3 zx8MYh+Z))ur`tQ0FIOr44Cjx>)8U@7)!o#K?4^Vc$fB#6c0vjUcXDqD346WVQzB7; zGk4gocel0sGW}tWq_S&?S7`@8Bzv|!U;DZp^E1X%%&ZTNPVScTdHar)`{#{Y_xcN1 z!od~>-Qc*_Zae7XU?ET3&?e-(6*~<(4=W~3^G^p&~aTG7v!oC$`seS!Tba5EUnj7w7w6ad5(@s@8%c-Ffm|Ehoo ztGW=uPUJF7=zbsj`v)n0(_njsuvG@~_paxin9*yF;c3AVel*w48|!yV-QAfv8=N&o z#+cK}wOhP>i7-Y&+;V7IVXt* z*CaDjwsxmmgdEeh&-W!6wQpB5Y*#-0;EFlH_goM6{Q657EIetPjP)#froGqBos~6a zL4ygwH6#Wj*0|*`F>bq3KCnM@tJjc%U zted8E@d4*w)^1DETVln19Kno1&`oR3QK6-jkDMLDCtWIC8hhCr9@^9|Aq(pibH6CG z(^R=0(*7{9@$R#Gx7VZk$-*4&ZWBJkI9JTFiPd z%u>+*0;Aifc9V_(S!t|dU}W%fy&kB3s)VAz?17p*A4C(BJ~O5n2Xt~eZf;T^CP9PP zx%c4qeSC^95ly9tum1+_KPw!eRq^C@F4eks7h3~hZ*;)U@`hTNDF>zH6{_B`U5ie| zd1{9z*nh_}#hqfL%W$*&C|N}&$#+Ti4ri(liM>z{pqXeo7lpt4*5Jz3b8e_^`BxK; z?&j~OnPD(v=X^hts%K8ix>Ft(RhFpRvaP%(D`Y3tm1`03+{`%kvH-ebOW&n)sl4{^ zBM?$J6c&s^VYNVBXIvOON2$HanggB=4iUxYM{3xUv4_bHsmd@VAC^<%-I* zE&f?z?!t|UN?VXkH#P`$3xA<&RmiEe^E%!vwB`1Sji1p*(vG)PkC}SfzIaE^k_iOa*qB_yO&OK4^rcCH4|iBbIhX=`ltm?c+1U>_$l_&b4v++In>839mRLF667e`l3v_T^Wh&V;zb$s4Hk0b~Q}9!s-CmAJ(@0)lOehu;@+#r;iPg1{Y^_TT9#d{dYedZjS} z%v%`IQ#Vl_1Fv_PHnT7hrQ{?iOfl#9b2lIV^41yH$mnr7VM+@Q+8Lz+HIhN1tV>!swl0q z$s(1m;FV&Ahk;DztzrG8Jj>)&+039a6k6^D>q`tXDIzXH@}oJSfO2Vqk+1iB=D zN=wL7Rc-%FHl9gykivARJKU|dkJG;a((8H2M{B6>9}hAPFWJF{Pw&I6w(vN^QO7=H zP>kF0no`1;gyV6%YA9mM7hU|REAlnV=8OQxNuDFcI2AskIeK}=OhBTd{UY}RyHWI5H_I0+ z7FK@)3vtt=xvx9pT6PJ}HCRJ1XLqF)6kuNp;t!oOcfp1_2E3)uFIe5(;}(i@P=bua zJ8{2$b>}AVO{GO=^)k}!OZ7&4mn+e#s?;FV9|i^GkkDADIw#D~W@ppp^8Dx(TzA!_K*s5C z@}+2URb|rdgCtnO(!4_A$l=)!*d3Wtf>k6>5@cxIdt8X_rxpX2GCN&_%}`*AYX340 z?ch^G%-9;9WZ=qm95rt{dj{1 zX;?NJzI~>e3AClq%j5IR8gF10=@wC#w5m-$juVa7<@KDbNfJt_5*s?(P0LD6wkwONOo$9c#=ob`=9=Rjw;uWFsPZ>nm3 z*Xe=}e9U0{Y$7IKK~AQn#godqn@jg%K2UnwK`)#37GmWu;Ljs| za0vkV^G(9EkG-4$B)w&&V3q?5?`C3Xb5i4mbI-9&_=hD^^F!NKrd+1>dMM`nPHF6z zco?{?W=C=LV*#f0O9G{`cTR3TNOI!=eaShxYN=>jFw*+M&MtbcpJ5F5nWCZ&Z-Syvl)PkA2Bi0hZX43)xV$*#_A zE`eN%-+B*uVX;rA+vxHYMgFa!I}+~lp_$;Bo%B$T#;rfCaKbMB37+og5);~uSSo+^ zL?C&szKy%=v(xJ^Lta#@gSHb}`0+Tvb3UBgy1UMiIEY$jgGt>F`3lq0WQecLgHnRvYZEvsz5cH_GUlAW-NgMq?^lTDldQdF%h?c!0v~C6r-i_ zvkUF_4xiHFuo3mxY>8WpWVWa8?VhNJuH9z&$oB?Tb*=_SaedD(B+I64U&}0ygY8fH`T@AeEUMia&G>~Ed!eibFlcVWV?W*4}uO@-8^feM%($g6xm$ z;st70DLQ^K8T^>+Ip*Z2gkEY2)=Z3iZWpxF2t*cr}z##;tslrGtD zj1o92mVKeci($Mu%Hk(^C5NP@+8!Jaz{CWgrTncUm%e!wbJH<28F9Dab-0lucYlPP z8_>^s9l*=t_wayFM8!LYqEB2P)JInzk75-=w3{;PD$V37UHCCySB{O7!-L&RM_>c3 za(BD;bvbStvL>W6pqAEBd$-#>y{~cN@A#ESj6^OC9V#Qmcy&D4(v$5~0m2mF83$VDJJ+I6RokmS0q2%s7hoM}gq!UqFPxLlShMVf zX1+eRD;oc6RgK)8Wi{+xWTli5gXN{m}*ceH?&Liy~;ENnryT#``BkbRI3A|g}#{=aqY;PwI-fG)75?cXI zh4EB)`3J&5!lSN!PNCWxP)JxX!pke=3xo^+nvJ_qib?!FAMNU(u8_~OcVzQtqbFB? zq2(Q-#bX@9f7+{Agk|Q9*hvQu{R_P7yIH>WqJov(m79*~_SdhF{&`9@{A`-F&{t`3 zrgc^dNARenB>O5S-N!o@H92g7o5d2SS2;Oso|gl!WMd-npH&_{f@Z$>NQ7%eN-!%| z1zyvS;)z37cxpTU^94v=#@H!cmLEkM{e;;8ztxcG+>NNe<{?$_2p+=EKI5Y9N?)FL z)|#`N6lG_LCy`nkUp|%1!vb7Mdop&}IOjbnB-m15^S+*1HnU0YsFBo(ad5S@g5(+J z@Sh;h$0$J77}YRqxhHt4_ghIe?@69M{MV9q9h3l>q2X^V%A`Ige<5K$8W# zjRRwEl}pAyKjFQNC5tft6)U+#OKggUYQ}`{05OyWM2Quio78(R+BE-`A_?%)yH8-h zieT`*3#)#^HraT_0aH~$$pieb`Lh%8Hv17DH_tB^Ps;92;3>dqd~i6s3u!2rW)Cy5 zGmD^8+1zr$eLg<^k<-ajD-dV5N(SYmtchx5+Dg_?9XC@%J_r54yn29eI$LHRwYQ_~ zLKgHdFEj70_&k>HIwTNJ0~D`B>*v5S@ZXd~R<*Hc-mIZUe6VFLS8_#r$cDsl>Grz4 zXM&|m*|^<&f?jj(ZZo^JpwRg7|!oZ({q;zyr+r~c(j3aR%Jt7+PmE{ya0fHMWk=<^{1FIvv(wkeS;rVyv7d&uE| zl%|vndZ^C^AMlTEev8_gR}D-idtMH`*{`jt8@ zPjR*HFu|v>S>2qc7QF9hgSVgtPd%cn&(f-L4;_qgtj3`U6ohvFa9a6pP#@rTX>trJ zPg>AABSbY>*D-I@Y=Gtb7=YQse5mlTT-{w_;obZb#oyNk!)XxRiv~*TnTWMgmRf}^ zD2pu+1Xv1JCPH@e26j-1Zam1KXy^dv-GMY`KT_-*<~_jrFKsw(LI|YChzDwd-`#_m zRxl&d08iyV*y5eUOHtf1kBjkL@{#a+1)g8HzxdIi$M0mhB>>bamXsF?e{rT)=|0Pg zryMKIjuujx?M{P(2iE~jKrrXC3F*1=TxYhyG98R+%MTuTxCKL)uMHz;-6wZW7rX(f zmj(X^|B^arD$sL29lq&yxf4i*nHAjZ7X+@z%Sr*X6NdZ1;nmADnGzPh9U#9Eml>V3&ENG>` z9{^z`ycBkY@#D*QRMeo0DS=JqsbU}Xmvr?nYd}P#Q6?{&AXE53ASg;jv=qVVF~?dc zpXNTfx1S`22Re$Qcc`62b_JPm0KvAQZbVE)QFqC>L?42t0jHD>ZN)h>A6yrpAz;N~(4VUY5%%@wR9oO{N-?-_Lp6FHGe3Jj zdZ#INb((%HY%8Q41y`jkb{yzbOsCX{5;PT6_Br6;uz^4Y0AB3bP;#551s5EvaYlW3 zmTzue&t{b3p~HLk3>=Mu+`~1m7(JP5MXCmHo8W#RO&+&V*#Zawh4@W$w+? z_`v;7b@G{E=<)8uH*8JajXfr5703$E5^9%vP?Ckr6ftAt{xai6a$sj#q zX$V4mCU$`$A?5eT0J1B^pdLP!EnX%mQ*;=`;11(U_zC*3kAQ3F`;zht2WA3}YoTqs z>Hvf9>{wrfGmhF$ zD(MuG3sCNT=&RB$JLrFvb4o$LIy%}-C@3#+XW%SDG{}3<94q0;&Q4E(J~?<6a_Gm- z`%W24;3hl03vVmC9kO}1J{fqu6@D{jH875W%J^K+V*ETkL%OJ<;~2G%Wa4fSfB+5$ zKqxF)4#a7T;4*!8CcV+yx#6PatI6z%XGrsqQ-@2A`|>e#2+avC6-|Aq!8o%+ue$o` z9Gg)C_anF_ww+-BdfLfKd4;y2BUsj0 zI}w2;1GBs7rOo|+QqXS8n`R2-)4k_cr^LCVyBiXm7)KSCw$B!`g3eN~{<=+$|>250ziJFl>;os@v z><49}Yhi_@>(+`5B3bL3`NkPQmg+gMYS{ScTs?fqj#s;UocqAJk9^_I8zYS`8V&Tm z%H_08?p|EV0Z5b*DIJiiF=#8KHti?xx22>XL}JeBsJaQpUQ@lW7q)MnmosNs4uZ%( zGC7K-aJ~>oy((^U@s|ytz)E=^>fBIz=dDB<%M+4xN;{d?Ic`tGL({UM%%EonkWu@j ztwquwb&K%$7b<8a9Zfk@(^LAJbYGlw)e^{SR69POcE5ZB&u=D^8YG!zJER8;2gk~% zO2acsj`G~IBJ&xahRh#y3r!bd>A`XelPlG-v`f@ovx$h7V%T9&$ z+|aWnA`aEVs>X?|sg>9v5oDzF@N?Kcp_GgQuuaOYUbVYb z&jAAIlwK}glK}J=CRW@ksxX++S|YfKwyX4&lrv=5iV$z=JV=u1Em{6ebU!cYm>ant zXd~E=Q~LUxvjoe=cVzmNiUgJk?g@TQ`s~L$EI|zfuDCNgp=S$ z{pE>KWi=V6#87@gH;SC?=b3d@YHHb7{=cG32HjQ-_$_ehY{Jz0EYwuKzNcd465RN! zr|TGE(=3o0O}h3dEd5S|d!BvY6sKbDZg>g!oLc3}s(8#D`x(jpRrlL%v=UwU`jO%U zd#lY&&;x@^x3fY>+t4oo`2IrZXQ5o*Nqc`+%6bQe?f;xLo)(S0HlA|SMv~g;8(LQ&b8E>&zy_aQ$X`sfZn<%LvjJY@$ z#X==1x&Ep9({ljQL#YHsV-!wID>+j+xINH%K|2#9N7k8@rpRY;F-O<{hb!(@;YdWg zJqeM~riJm5#!{zUMb!W+$0q{Ez}?>b{>0UXHh!Rr;{Nx zn}yUapcyt+F)^naH2D>0sx0Lfzg!Vm(W0)wunL=bb_8*t7J;C0X7#Mq_r{&SbBd@YpZokjLi$m;G7U^?SX;r zOX_yQ23k6noGLA?sV;kiW!XUEIo+cFuCnq1$IEG2w5iqrmsTJuruM2e*;MgPJ)|1muEOJZ}iZc>UmI*tD zfgp+#E4y^~_Bq?FB$q8J{pG088 z%LJvXAXQ^U3xehcFdA6hj)&^MN@TCL!pZU`FDnx<-KKfd%&t5k8O@0L9_gld;L;Eh z{QlYY^%cbl2F$%@Z7oUv7(Fq!AT|5Hb^+tzbiG*G{;E3Bchj!ZVuE5q4r9b>J!2F5Ino&_rslWv-kyt<4mQ*Yrf=PAcg6k-<{*x(ic;cr$%c#S^rQG*SU5+RmwG;6Q z9`oWn8DI-$xGfsQUkr#w>yO#M?h5wfOyH<~@u4|^QLGbt+Kd>O3;@gi7Gh00CvRoz6`>pStWlr;w%!mJsLfWJY$*K;AiSjgS(B%sAisc{vA5!#4m# zo%y>Q*4ZYn9}=PZUr+){>}8%jX<-7#;nCq)n6d7|rD&#Zhp?DKVThT3S1+DEv`w~m zNp=(wfAC)+m8`EOf-t^v4+(z{JRe1zC(Sl)Tu)%EPd&y$Sr5Ellqvw)Kf+ag`FJ<| z%?$PYz)jzs7yiIn1aZux$tac5PXjwc3jk?yT28BNMLyF<61~&2_1XfSb6aHN4l%D_ z1Rq8(m<0cvx9LXhKecGIE}q@mA5xOqyJ)OoEAAFZWg)bVqB8AIS*Uo*i^3fnWN}m; z?h%XpmS?yki6q!s=DaEoAFDGp`B8iv3>VJc2-iDav!)NGEuOWZ-V^;^iQX&dISNj! zdkFvTN@^FdX1DJMVc>Yic@K07$br)kmiBH@&M%=jOEj4Mo3ox7t!0qREhar z{AL+#g^<3~qs7Gc_wgRaoTu6PvL>X}RZL)B;BMP^!x{}r)~MkeYZdQZ=IVur{a;_b z)HI-lp>4P$&^?CYh-FK_kkLKuQ4wTPa!zj12dnvJp$=}NJqCy5_Q{tpU@arn)+HTh zJ>8i_@48^rXw0ZlT-&>~=@6U?BWsPHA4;mkCSU8AwLp3bbOYC#ZxKtn3CuR@H2|g% zVi!o4lMUZwRlFRARlM?Ar#${o{0-`Emji*;A`A)@)T#7z&rRkdi_|9FDPr7ej2f12 zm4;@e6s_T0)OHrS7IP=XFLk>*1pgz_*#Q1=18t1NEx?%WM2EH86q#OC{to}fdql~y{N4b3@!`|W8VEXcsr!0G9nuMA;E6K zc44Iqf3z2w=ugEWC^}vm;Xok4{iz8)YJ*5Jp2IOskioYph2uk>G|HAGu)U#f$u%zg z_clr-xp%xo-_@?`(SArz(sZa7B@6VkR@n{>fhk#(%LwtzE;O=2#tv4flj)0KCar3t zX(!oeSzX*(x8rAp1XEC`%!0J?y&lUtK|MiJULa=(I^%jru14XtyY#=-fjPa za> zV4Om0^q>@LCAZ>Q=dXq6S!LrbJ_OdjudMHKS9CKI-szrslY6EpED4`L?_ayCIEC)j zv~ezQxOk~+8qEm-zqJ$@@)PEv8%x?4wm7*m{$DrP4-~@{reTbDKl8u;DGcnP)-S!TcJBh_cHIS{?nwB5!p){%IIGfsG>0 zFf5-8h24?5*4yqG3zZ&gnRFNy`|zP;=!|euIZdWZUBCQfemja>OpjZ6s&oB9t|Vf;6#f7En`d*%Sac;3K*Jz687iT=bdwJQ4JG~ zyLu}bD41ZKn98RgTDyk3XVAC*ClX9ew61uB1f8Vs%$!B%+*ZSkD66msQlGB?(OC>2_>XmHIWBT7s+!RBoZK zS+ATL*fKqs&({MV^G#*ePk7_w+wG4ml*JE})O&P5Lo%h& zr(SrmAusoa6NzaaOd<0;Pm>e><)nm)JvkSlL43+qq0*K*%l4-xMW!?7Ujt&!M17f7 zb(xf--VV!_nCjX}=aOppeqLy;eEjLVflC4^TlC7hBhfz_vr9%781H*pP8PIVL0Atu{Q0{uiU+aZu)_N|1B>1adhpvcsW%zltj$_fDKS`t7&`v>asmj>Fa|wjbN{@y z=wF6@KG-&u!Ol(-V7@ zzo9vwr~MkM@jN7hIz6In%TwLDwFNkrg`l`qYLK=7z2ZV_91J=H>lHXhQ6d5q)?p2# zF_H*U+_wFDf-tP)>0hIJtk1i=es-ovgMj`au102k#Y6)61{!ka!*<>rlOzDrV{izC z-ADIWt?T8g6E?l)oQl%%WK;$2o(`A{E=&84#ZaL)vlviabK`3o=GNBIyn9=FbFCJx z%#aF~tO{=?tU+6QMi->UEwf;5sw8{Yer+A1yR2!?5VMABt^0 zdB)+}nqWu(y}@zZib?|*&NWi{lXgVjvNsc~r)jr_eHoauTh73BVi2Uh!m;Lpg@VPMu-f6lASf8AX3e=YSc)EurLTLt{-lN0FV9@c) zK%S5XUNxCD_TX3tK0)F|AiLu!{{wM3S%H#3Tca*zauHxTXuGi$C%djZTgP0%h7k#( z013Egr+pNW+Fk6=L|dq}Wys_Ag^h`0aPBl5TPGI>hr3Ig2X_)9AcBW0bA&YqZ13|j4t`)+kt>V7M z`}^x}_D-0gk(X+9_R?{`fGVxG#*_E-dV}OM*dO~V{ei>&p^-U(fwQ%;Iawuv=(zQC zHzfZJTzCoQV)xKXs>4KZaFj^0Qd-2=le~=7Dk9h(c8FHx8g_-isW+$X;26H z`uenZ6nUy3j5i|7kl}C9WO@GISS(>V8MD&iT`w~%S81ict62vu2UF^zJ!5{926+_J zkzoo=X!q$7-`B8iXVps2`F{#-Xm| zszi0{64i1pS0Od|tQCyE#UN3)H+G%kq9h42_2*B~GFj7sQYQY`&+4wEzWRg_aeu@1 ztGkje$Xu&X#`6!FMpzF6*BrYH(K!LmIVtOM&5uf>MMS42J^t=LsM+8^$ca=$YZd8M z#~5&MQM)>^vq{MJtY9BBds5tBWOwQv?6xb4SZr!;=(32h)m> z+D`3rpa0ap?rg$n@=}|r$~Ngj-F@gxRI#vDr#xME=eRSB#Xc0M=Mr!?j^uM(nfJ9i zQgq#3!=`$4cA*k=c1b)v%a9?^%R0EBY8Yc`Fatx+CaAG!|7z&Nh8~5dmPE<7ge9Tf zMwk$Aypl+m?>u+gJqwnwVBb#*c>_?d2gVUSgUogqlXVk8?1HH z-T2$iU3PTCpcWY^g3gHHYqUk3oYVe2Vrn@Qp3JpcZBM9jpNyKq;=@b4=qGwwQ!x^* z%R{;&bA5^pOYDh|?F38Dj!cnd`tw3VpSa879_7Y7m3M5#`>gd@1$8;-l`Rl(SckLV zrjL$O&myveIU1#`q93%PTthr?HRrSfs){433z$@8ciO0E941*4V8etZY%iX`4sFL+ z%9R0ZU!>l4zT`{pFBIrs=oX!68X45&Eo_m{eyaA@m#u~D zB_?;8@~6hGNx%i5B2wu^@PmYiad#n`yZ9*ndQSlP}5Yx)Sy>X-WS-TxOdL)z~Qz|TDfB=O!wLF7j51t&ptrL5`;A+;%u zC?x59K}BiFzz6Z?ru3|!gl}I$MRVa8iB0R(x|LwrimztHOJ$WCoyARz%-q8C$W+KW zrCW3DEFkq1A$A!0i|P<0PmP1wQFyx-IoWuQ=|@-9UNI5i{bD$eY@Oj{a;b@y$(t$6 zq9Ul1X}E9rlHBqJj5Nn~l7^A(5h+Dl&6z`!`-x51FS-q)vA@t*{_PP|WO^ip$o0;5 z^!R!8R~zfwuJiC;-+PwXGm^?py_5G45Unn5qAO^=YrdFcv3OxR@42HB`PsbFJJ4w5 z?`al}jD4pK)=Qil9BHH1QxxDYCtmftpRxAH{GRNo#W9q75`5}PFuZMlQS-h!>0nb@ z!Sy^QC=8BrNQ8WZ!cXze=kp9%aKStfmk!XFQ{!=EOoVwbYslo zghDO=_79CzW%o)~jK}~AUs7C<(yX{Nl8MBEEnh({BkTK^ZF?XIF*Tv;yZ2 z>8O6ov1DC~ufhpzzkj~U#*qvO9)AXU%kYxkRzUf!wSHl_zBEYALU5)~GhPWY0!0n% z;AL{H8Lk)GNb>8XzRa2l2@YR|P;=1Z<-TLQYa<5lVCW;)NWYKhMcW!sr8UCy)L2B$ zrvsuXHQ*#uT*&AAZ!}-EScD(umBmqcquk|r`X6M!(0{y0Bp*AwKv&H{oJ=;&o44Yv zNcSs8RN}47jMn0Mu~LUu1gsC#PdN~V>SqMxVs5H+VW#D?1q{(mn4g43r(>nX-3X*VS zNfX1bS_9WgdccFbo+{8g=yPYzdYAJ@-*zx(;kT!!+&Mq%K&}DR%h~&5K@8PY^}Y(i zT^+*D2@7@Xbn7Vh@s+2W%qv#SaW^SDzBT1>{yOcC&+>VJQ^ZON(Be5lcv2J^*EzFY zmToD6#EhVd^U5_4cxn+7V~QmS_4@KQT=G$SZ!L3SRZ3Kkpzrs`6ApOMnnr#fL^Z(R z=DF+dIRY5U$0Dv~AecyXU2m4V09M<}g^wpLadbof-!KaZrCD8#h>D*gg8?ZxM8(UC zK>^*eQG!df$au#Zk3@5vXtG=CR9jga^yf0N)y|UzHP7wYnW<%8p`^ZK19nGLWX($O z5ptl{tK}`Q;ApZ1Ijmr>>;gqG{%Ur3v;5$Vrjh_HFG=q^`lG8wEj2oL3t%mI)T{s@ z)OYz#F&~4m*6W%xeSZ77`}Z1xk5sE`tz(^*`Gn(YUcPD{4imB!T+z^e@4q^^ez~y2 z7S(qu){Y(z%9sP5T7-epRnDjl&v%~=D!;;byp+-D*$pKuxE9kfTTNK-DH%;p5zX(J zYzdWD4yblO(OBh^V591FTKcu2){M(02f2NK$>=ME)W5y3lWIl2Ml3WJteTP2Xfyq5DwM|? z&m=Q-rDar^ypaH44b_HV$^HM4u8c?uWxClY6;>}a3|gLZVV1k8_9S;A)hIufC1FqfCnEM}2hGZ*l0{Oc*3mW`%R=rtDTG)wXTPn0K-pvl9e zdznTm&q@D13EnRWwDEw~jfQBGudRh&y5F7}_M`=ZiT)UKYF2Iu(loP3I%{#=AkjUK z=~C3M!H#AbL+K{=UD$jJ5g3cs=&FⅅNg-6=2mWXr<%v&T9w(Q_pa5>jaAN;Kz7* z){#EWN;Lu#h*%tFcQ~NJNub>5&LNak&kc>Tc+Y%}rqW0_XpH=YQZ9 ztEq;Sk~tggfgR6Zer+>wExaL%M%RT9gutD*-9H#^uwu-|+=`0G2pBc|uWKO${h=op z(^;7I6A9Rxuy0U3xDDF8b2CEC$pV&vxFXPQtLUCG??NvvI6xArnm2EPnlj?DN}yhM z$8#Bqm?Ua`C;9W~A{F>wl)FG=1}HjQQ5;cw_)#*u{&p0>!n1Ctb))DZDLm+?3JRV0U z@|LB;U}`9a(%$}YA(-8zS9i>rVO&ka*>k|VozY$k;CM5b7(`hpMux!#xD=GyNmn0T z2w5MAHEEK{+`t&5qA5q#x}q85@mUb}WU#RdV;x5JTDEj`lurg8eZpWg{$n6|`PJKjk$sT3RPP&edTuU^@Q9hsh>#3w9&)Phwxz#$dUGTP=YSsE3UUgsB zE77z(@YOp5GSvygfM*Uy0?#a}cJ^@IPJPpl3_r^LTTEIco2*}y)mKiR#*X|K1L2MsUW(Dnn%Ag7el+T`VC)wCPQY~vg zrbUbH0mhZ={1P;IWaUvDu{!bZ)uyrAlLiU?7-Cw4L+P1YUI5{ov$swn?%ik718(`y zPua-VcSs~}L(CV}$g8~+Nji@pzvMA?g;wQlzfuR?kS$TkTcM(6k}QCPKJ`e`0A2jN zanmNNu}v(zyCar%wGB7=_8a;4iEel^4n1_hI(j;$%=BWCb@+sjlXMD6bn|YMRNrO| zMnU8FX`bY)(FU6NtUnEyV>a-Oy_g@IHLwF~SK%^AoBVjU@bAUlA{4JGNMmQoG_^tE zSv$k6UQd^`C6`bFAJHIb;9kpxwpjdnxR9ZQHi(WHOo9b~3ST+qP}n_}x7B z+;#r*7u;7 ztAfLihYR7!(GC^9|tP|BM_KXEgSyo`FdiOi={=4lM(>cRPvKm6iP88sa8$s@ffsowt;^4lwqqOSX%3~)`HDmRlcW}vxlyg;B~e*K@TNdv#eE}$hh!0VX1pJJ zCpiv`-@;EUIUR40Zv~pV2@1S|x$mN)(W_=!(xw5d0oDgyA<9$kSK28ecb zk&;MEvuKW?*dg|i`ZA9=LVuXWO1#sf={CK5``3!jV_+uUPe)am}Tp@S)k zZ~xJrB)XH%fT%;~Z?jvm$AT>SE82WVG^;ZNpP5HR_7)xGULj)oIvw#b1&oQ9jrvk%C~Lj4zh`= zwNS+Eayy5ED3JI(mdy&q+XyI^SRWQ4;r!$%UCOvBcT`Vsb%M@|JHJrv(L3%=8tfW zuq{tv9jbYMweVfoTVT^GT}CycXGitt-wuxDSe|v%&)_rng3j^`F}B0R4ca+VIw*$G z&|3Q=tA1=7JDX`w;*BM@l$F_3EGJoI-nmv>lTE}!n69}zB=EPKq*X|QnWMGTH90bf zxsIX(090bJj9R9+?Mf#qk@%=9w_mN1Jt?;MDKO1%`Gk7IuOh2$-3LQIEPZ-VX=7E8!9NSA zZ_}K%7bPu4%vQDy(&G)kk}aPs z>2U>3gOL9PZIn5(-e01-NjCsiOj*FZVMHw1?kF!e@~xtd{DoDS(hz6c5N&a2aTdVN zE)0l)f7(bg3KP1~Wdzv~-gFxLlJ}RtBDYDx3xxcqCm)2t`yBm+5=6n%|FO5zY`8Xu zB(3e}iJyng;n&3^cE1~5pL4{{KdWcwv;;II1+p@6f{r3{51NT=1Bl9+Yx9`mSkqlq z;naSPqV>h@MH|X6gsGElnTf_=BtRmax?w~r|4QUC=rjiy4!U+8Xjy93gM0_$f~3S> zA*k8f2gdwAvN}v=FqF?rk z%7X19r?Mo= z#k1UdELzoLk{GhtmRjm!~Z zFXJ^&l_VVeImpy_&17F~I|-sKfk+5xJa#1d$;FLhE2+4OaOCBH!5-B@QpTk3z5n?@ z`R0QpkCVRdJK~3%2NN0_h9grEWYdlQn-)bb_`VyzO_)eTd#f!+-ioxjN?8F->2F|i zt+Gwr4-TNwS0Oy(dSMRpBm)H8Nr!Di&A|q~b$#P2h%<4{HV{}aYg!>}Ih71_+Dni; z1Ge;cD02sDP!CCXI(0}uAViMS<|7VLlY<_DnnLm8qz?oS6a1vZTI%i3G&S(QQz_iaySe7q4>x6f0n>a zGnQZ4WaVCHy+ueMR1(J`5X%U#wVwR{0qh7CO_x( zXT%*M|5@6=Z4mB8`zY5~(8Zp3Z%->{jta8imYvF^f0NgTsV=&yXo)#bA#04pP(nFG z)via|^LYm2H23!@WwWyKR0;3TRw}DzVTHrE%jBQYQExSm+m{^UCpLAF6>a~zfQ1(; z(!=FQUY&<{lc_qbsB+3kofsW77-_a1J{Z|U=}lx11JXe=hnY~`29Ab2Tj&dn~V ztKE-`YL{q0b+1zl)_*R{d5d1DfytcDxQYt08zX)| zh^~Pm=Fdqzm~n>LwaglyV=_v(vCbhqkaZrrB)br98)Oy05^8o4`?fWu@&zW>2 zGjDxQK{tPiJHr^NE_97zV9!C5KChLubE?1sVa_}KP&lu!l4Lr^QN9)mWC%#CQVGme zXfoEu{!e0evXY|~<0h#*NaA)bNs{d+kY=0QCEi&q#W zwA@FG+ekS_;Z-1Z)Um!exk!cNB<1<`Iqkz>K_t`bIzWsmQ-2_Tm_%3l{zgL+VH2N* zVbD+vrDr-1$z$z@_kpH_RqwLUA+eoeAlqif+>S!FJeHESHNGs>_FHpjpdhaVzO#1q zp(1`V&ZnOZ3FkfHlO%R4r2~>cQGqufk3Gd6l{=vZuK#qmsj$Kt9C( zmVI_%y@9@l$rESpMl^8aiuH^GYLmTP55INm3|l*JL+|ZoM{cv(=yZKm18UP;=XC(g zF7}>6Dro)XM(|gC$=uR1UF~Z~-ujjhq9tCU3_QI0j&zBywp5`zG+mAGj5q6)_Sw8! z$=0BUXl8Q(yo{3DT=Qoav^}0xH3|Ivc7Z42MoKujc&AF;-{jIaI=Xpn!WaFj%dRdb z15!1d+Cpp4pC=0B3Xz6+x-w&;nVY1F-4BQDl!pZ}{9ChLKyR z50!^v!L+pv(;k-ZA1zF*`f*)jS07253QEIZxX476RCS8WLNGyVVmwr;ztl70Xt+a% zj%n!UJ~#(Ztr+>usE_pC2z;gCg|~|XRvZf$tYnKqj)%Ux0bw*IgAl6qz73gg(5meG zwQ7eYE$}iB;^wv;;seI(v)x?iIgGihlwKB^%n9$qC)W(zuVe|+YQxnvxM01MEL~D` zN7`?^chxVvt_tH3hUK7Y91RFcZH4`+A#`WDsKQ`=$f57w$XZ{TX{BfS^mwnhff8L5 z7vU%Pr6Y=yJUdpbNANkR$#0%$Qa+h*`r?J2QzPm3EA74F@w{UX)uq6J{{F^Zcd@P0 z^dDr}c8`gZJCrU_Ih%vjzg(MLovaBR4}3nNw7b0u^u$_X{?so}sVO?U%t<#V!3-#v z_z3dR{8k;*7r z8}7l`^0c?mn2U?7rjA+tp`~#bBx_EnHxi{{Pb~H<($LMB*&E~Go3ZsqkSv+);FmUw zwv<%rXynyfIFs;BSl+KzBw}ZxNn+Z?^H1y;kkGlG&}i_D8VeDpQoNSxFy`+Zy<$?1 zn~dENwU{0bdx0GhlOCdkze0~ERbRj)MT0?OU1_rx#`k6&$f{*NULffZ_GL_}s)w-s zf(Bo2Z<3TFdEt`Cgpk{&Sa+qh1GV~U=+_>9QlTb&sK*Q`J+XbXUJ95S<+ zCGC9nIKf<6QBp%o*qw4_gFF5+JjCniQSG&@MHw0#1z}k0YTaBAfluHnh@|SPx%@2z zEz)|xq%>B&#=fJ%rn_vk9}qUl0Ry=#evGr3X`qSO7_J{=LBOU^rgBkby}&4b*5;ZF$t!aU(3R z+(&bRof&tz4jglmB5oz-Iv}+bv4i>_N<=dJPwwT*$fbPbq zV`<*ej3GR!aA31OU85gOb39+=;$QC=$;og4IwsE2oO_SxgLnXCrIbi8y+lM^wLG74 z9ARs;$b@F^!>`V-#CQE$-&!+DzQ=RION`bW6EUn0T%z)NX`hTnOgpBAUq3#$RE4su zq9C9ql)5>g1zV>VzwyJ|l9-*GXi~g%sX6>r@TX$@WY0w|^i@V;fbxfhva)?L2zQr} zM{#S9a7Ol|P+cbAqRBbnZ7Z&gZE3D?X}AhWL2NZBi110Xh8C;a>n~WK z89^{#O1V%LYw9Ig-ztlRl712wxI9STk?GIqLX2CSaXdH&sye^SPVr~ez~enS!eS?p z3#sr?d?A4JSTrsTM-C95h9cy;l>JSG;y>34p&^oPSa*?m{U}{#L7AoUv|2xRm#)s- z4z@Gyy_Nq}Q4hVMAFaKv6fX>2l`Lz=_cvdeUoy>9E86vGUp1*U=gdYDXYMgtd_kj2 zg<#qCJJLbFz>Ush!lNky(bZaO8q#i(JQf*vLSQYK%yXu9IOQS26eD)Td0Wq7*QAln zGG8~cOjndQWnHj}ELyqH;QlUm@(A3;Yy6p(U25VQx4yB28CO6nGgCX$M(f)Dkh1++ z1r^VD54hm8T|voJA!MII@88^hpxdPy9`6MsroA{;p)BO&q$XYDq-@nICc@bK zrO;9ngegS9$l5-#c zRs9nV*?;r52iTCM!%;51u_E5L$}-ly?dB_V#9)n^e&I{e-_$W(sue!gAXgR%vysoT z4V(O`y+zx&Iwx->7(XkGXZ?yxaCM<-4+N`nXw|bAb;D&(2mVqAYcsQ$0m;Vpu((z9 zBN*+mAd(@MF2x@d)@&nKZ#`EQ5d(|!8}+_t=Yf@=YYTDt#76v2LXP&z&~iEd+S;${ zSls3vKbQ>(T3*9d{~Ib>z!=WKPvdzSw!8*|k76bqxzs}`S?)xR+2-!bRr#n-d2wM^zzjg2bb|XX)_Ys(eA?p6P?>32G~Y$J_IeEQ5wc$h zC{@qscY&}_V5mnkFhwMJY`Ko&yW@ zYmmnfF9G2je*Hw{=} z$UN>nPa7ScnI`>sCQ+H3DFi@tUhO%wbjbxBCR!lUKjG3#e@`Of#A{CCF$ImHXIBP+ zUv-_t7;^R_Hz;^4ZQO@oj@kp$`8C?|t9ZLl9mU0?&%yd@@Qs#?ro6Tg{<@1R=>3(= zze^izsx*>jj4wRe)5RPkqqs`u>^6w_6WOVl9jB|8$U%n44k|wVns$nr_Tyv`T2fVy zaQ5gv8JV;AVg+~Twv~b&+$K9)(i_yQ6C%((Y6fw)*OJq;f^ghm($@Qw+7pbkK3o2c zSc{KPQv?RI6RM@juhu?b1{RD(W1iqELwuoAP%6G$F$1w}tz41-x^DpB6Zb-m9|NBmnl3s!H z(m!=+X3;gpf3~WyW;<$oKjXp7E;pONm*EP~*SnMZ)wHj1-rqVF(c#b%(mx;?UKob~ zVGAC4U%LbKDHp@)@MHrmdxL$h3%9YE^>#~ATSLB_@9~Huw-OI~vkG`*QSV1*G5G7D z1@`;ZeFf5+Y^9m(cDKK*78+@8;2syG%xVFW)IV1ZxMsyQ{WAk!NpJ7nEx5AFuX@`aGU7F z$+6=w$hoOjq+R2Hi_a^jYcZ)1R1$WvPTtX{GRW2)8f<+A$+6yd@HPBMcOS5uAk<`( zz~|5C3DdjGZU}e2ZU7NW4dipH2)r63f%covvli&GuLbqD-XZwFXR=Z&^&@dD6LE6e zG+gL9@T&Nn0eRmw2TCBH;;VKI6^PI9nrFR>fGVZC#<5?S&?#A}fr9&6mG#IKg}%wF z)xS8QNL)Gk0DfVfYr(z4ozWPb%^aWF(}+Zo?!h45HTTSQ_eh)&_3b5$QW!CRN}rp= zwih4Pmu?^C7wdE%H@c=EWP%(DnJW&nGPUxs?u;ULMSb6+F=ZVepta_TthXK;89Ohz z)Ded=yp+t072BWFMsO}|lS0b+&#c5Ec8(o_8D*NPu1u`Ak@`hymH}QZ>*SPm|Bo?c zoKF79i{@O}X6mXYX2hAqv1Y^1ix!&<+mB%r=C$WWP;?E}HIN+q__1aVf67EUgO{!h z+omX0B`5cAwPuC~2%1g!THm2Hb)2%{Ui5do6z*0S_H7X^1xb99ZCotsrX(dIEWh_X zRCCbSNAdAUxTYB_;<2V;%&klXHqp1Xjz4UuKGh35-bJdUW2 zVF%DV^lI$m<9`0XBZ(DEise?ki`i!k{CZxFOP2>dO9Y%FSpUd|5j=7 zZ!b+>4nH5>#?}BYce@YUW1$ZXi7&YTf9J4MvUf z?R`Y+VOrxon+;Zue?2Vfs!3z!1ezrT%6R#s(0@S~9Det-%7hh)1Aes7*9{aRy>;;nyL(qMObl?(C~7LaJJ`r@GO3o6Ek4*>gv?|q zBiYGbp+CtlZB?75h(QoCP3emoXk?m;NkCS+F=k4&=Z_&SW!v%k@TP3M%v6 zRK2A4uXX?n!(^SF2MnXl&Wrn(BaM>INH)cH z)`qTSPbivYF?QDWab-kee;ZUxi}zI5pLyU9788_!0}dW~tREvJQ;j;|cZZSc!9phb_xxKSzfH(JSMyjZV%W+#^ z9qM!!>sCz&C@!^7a=ZA>7we}?J~kh$!*>Kz3DpkpUU-#N8J*t1wj~K2_jVYzJB3fR zvq${As$D`?N-&E$E6`|Nw}}rit!15|_%YP2@^@0Bj?e$O+clQ%sW)!B;9va4F5rC; zw~n}u5|%DWd>~_?IFu@#{H5f>!+P&j>A{2RV9iZqCvjh`V@6^8wPmsf4L?%xbp2P6 zmVG<)QN}YlTat>CU_#%rkVfl6e|I6EsLN3L51VbswdisO5?Si`iqmhrGTIw8A14Qd z+5+dE4hqQCb;Yy`6DP z>q-dCk^J!ij0Cal{SKcYwX;r^i>k8yIUT;DG@`Qe!o~DhxE^a@ZVs*@u%|e<;CTC# zOw~KlxB8{}a?>;Toe?L2sj+}c^peNpvIj@q5#A-Y%g1A_uS)F^+6f2UDlPTVwh2^N4ky2dF~|oa<*UUS&zX2?Q?yL4+Hu)b)Kgl@I@l}!4BNKn6?7X&6j+;GWdc{ZL6)JmHNW`*3RGu-}zYK4DG9EfI# z(C3?tnJi_XuyyvSccj~n3b(Awb3t}AZ$$=&$$Tr+dzU0P9rX&_N0$bM`A>=ex)kzJ zNnl$JBAF?%U_viOSqBGOrZ)R%7W)(2k@VJ|55)onZU+zsyN{8z9$&}@cmj@w8)5bP z$TlqBUvzGzgFXw+Y(ncyivxNF3znxSEq~Hfk!Oh5;7C;hX~$91U2zEsX&HgC;EE*M zKdAW+(3IC`H8#`m9amUS_(O+~lC+GHH0<{@W9wnJdL8rQTU3>Y|J|}j7Bz3L9(r8_ zFMG`y*fl?g)`{)*tCvx120$S36*{AhxnEFRRM_I=7vXbjsqaHV%>+TeUNg&~vN$11 zs9`7~1_Gf^k1KpNSTql?-kOblSM_;AICEWpPd+?HW=LX?lIcunz`QcyJM_kmyGfYa z`rWQ39cEZwB5@n(RUVR0z3eZcdLqN`ruTN}dbp0aYPpWXtPXh(MBlv|d}PcrM^VeA zt}Si%gg&%tVGgTE#?2G$Qjt=M4{;nG^7*?yS&k??S>Ei7`Ft*&&n*)M%Xjcr)Kn*W zR1wh#!%f0=J&s)5u76AOZ-_acHBQJZEI&%A8h z#y%Oeh_d)L=mJWh)%%(=cD|~9Qo!-wB0uHrpJ~pn^={4`74pNppSqpl^td?z$6s%d zF$6UMgdX~eUeM$i-{^f8&XK+?(*Z@@_D$5nv7#`C)k-|z^&t&2CLTr$3?JBScaH>0 zFs7}B=kh%-Vaiwoe6yDC20dZ6-AdJgAvnu&ht@36Q*q+c8rkmJOj^5_YXekAhoH37 zzyOo`s3lSmJbR+MmV=h%&Qspn8f2HAKcW4QB zn&@1qZfnt)t}wUX2GKwEMTY`@fhz;8caohlJR3-m&CTzKchIi&3aoUs9wvJVrO%Au z7Zg;_DtBEOOTqpDXiH-e%92nChNxg{6ICui+hA-gi4a~`6PhoD3F!JVT)U2eN~?+Qog5GmjS@7FT-Cqrx@$H`*C)<(*~bQynb$32fF@%a3vmYptIUrE2AMAuSzAK> zxk9S)Q*b;N%zcvnseNb$THHj_lzE+)kFv>@}-Hc*atqKH3fjizZTN7`6zj zGiccqpnyQzDUkFqdOx&u!i1UM4n1sfj_~DmDGPkVii0xiN`D~VGvnCrIA@QgS7}iq zkm@o6Fp<*89tv9u1Dk~VUm0Ca0a#knDNZURmC_+1G+M*xoIvJ=iYS_it%2nOB+Ute ziBd;k6(7**H55lShF;~GNVQIYwO(@wZ_~z?*Jssb-*9$xhIflQT(oZU6h6G#HFy1( zWs;ngb05d!nO3NX65n~^2g9NXgK6PVnuMBo4XbHT(MiLW67bQq1 zSInL;tZ&h@-XUudF*?m}6iO_JHRIk_K0GVQWTbED2+GSO7?3l0yJ`kv2$>z3hRcpE zMFVZ~cD3}dmWV?%!p!iy@SwnNvq0hY^!B6}0G`(`lBf8oC$|#sborIzi8M1O!on$)09Q-{(r?L%2-42rWYLJU-q{4)!=S>-} zdUBwggjv-6os5b&QeF^ksL;k!olU>ND^sW85jao#!I5;CcbUvMn4%)3<(M0(z>#F$ zg=K<^ORO?~aDnRN2z4%XTt(*kxRB=z=2D7W4>&&EwPm`nNw=!8OXlwvo|m|6(*SR1 zijzfnL*@L?;3?wY$Z)2FLNI#64uejYZV3z&lWcnOvS{74nZG`XjvR?z^A1c4NZ1N1 zai^5-+;22o1uW+(sKah7aBsc@M(kx}$Ma90Z0_EDkxrRe4^fPlIIg}{@m(}Cu#~`S zJo;q1;Ry5zY;k7jp3aitxXR}^T@@~Zqe&CSp;bxVTGo#AS-p)zTz(*EM{M=#r^xL3 z6N~e+v-yg^s8?hGCsN_%Rdm*x@QIPg>{VU%ATw;!)RJylYGVzIatvs~3607&zt&wm z;mYLrib8Vw{gWd0pDOumnx7aa=FyA@sx3C>2N z)t(f!bE0?0`0q^#-j1(G(6Dgumnn@K?~ZQ_d-X7ae=A93%=*4Jt;xqNqgcRt6yr#-Olb5Anc&{0EkR0$Zy}| zd;*g9hG<_GPZ95avB)@TAQ?{9i**#c*uJMW(_jX_)_@$&b{8%4M6`%Yi89(ejWzdI z)QhwAr^0H#!j4RC`3==tiLh1UIB&|!auA}NZ;WHL?+tz@9y=TN)1f&StyMoScC??+ zUHgg>6J`Gd9MAx`@UE6lAS$B>kTE>qVUu?v<{Ua_FbjU&KZlN}f1=FV@#}1zqpYFg)IOj zh|8CTGQw*crz3GJ-yWF*>%ItHFg+0`%$%3qIgVFt^SOShk0na!R39&M>?o|UTpk{ zx~Q76D9~2C1&N0;5{9X-F6xe2aJ>*M$ViNb1{x6MOywME+b_b*dP?HVf(E|XI`dlM z7+=Y7ySnnjScctOO_fDl#if?^clC+XqiuAqemd4ix&SKmrL7K6Up!0-^+*^1G}2PZ zXr13FM5^l_&2KPd`;~Bd5Dzlry$G9xI7^)U_}JsWumYhbHhaGe|E={4UBffRFrZ(D zZGn-eQrkT$V>$n`a^cI+_W!4$cHqh+GiaSl2#Ew%$NPkf^ZsYEI=yNgOS1x|42o%o zXyy6Z8(%!Iia=Fu1!zkH54R#1nG)?O_AaXhYP)F`4oS8R_20Qy**{Qr&b%Nn@^+eE z&TN9<6w>sFs$wO)3C#*}93MV`_)F`a9^4O~y^JB&CQLGNZ)s5ZDn*|u7f!Ra0 zP+yLY;yn6EmDzB?O1jnpLUgDUztN7}1o*~U2U-|hn=;ENy5!0Ny6J$`oya}Zy zQ|it%k=zoLI_t+7cfMLNKGVLT7XvwRSYGeBn?=YFEf$=yB-ln6bFw(zPV0Ir~ z8@@S)r2#8tU^M?gN?TZ7p*|DQj%izrK=eRbIf6BMW;bCeX3@Y{A)p47{=1l97F1Cmt&LUZi{}sVP4>2`uc2I7`J`H*Nv2710wtCDjGkl8f zJpEt~s9fUw4Q~W0r~90Y-SYRABlu*4?o@s>DdE^86{n>(v`}Iu1oQ?;%Ng`y%e`jl z^}#6oL)iB6K~;Q>zS{a~7{9n4_h2{_MOtL|@TBcbJ}-7u$8Z*>w?C8Ngf84H{f=}< z&k4n2Tmz(LgJWSdvi>V6e&vkcX*7A6sKpT@%}zh#M&Eyt&#IfG`v`(M-5o5|P8M0MP7bw#;^VW&48Gxz(^g&{mLKJEZSLD~Id1Er z)Ro$mPNpC;V*=ylk~%U>uB4tdrL8cX0IbKzGyptHI^h{QR; zRaAItW;nfQx8e5c1LKkU$-ZQvG;``=c$Z_nIc>_`!UD_2XTWa{;gIM-oDCt25)VW) zOQ*pLv8}}y$ZmGP(a7iD8M7=Dewf6eOc79w;zRJsUvW}Gh}b{ksJZCTqZFkIb72I3 z#gn?-`vX8&_p`EnYlTV8f8I5g%nkMZG_#mq)f^9(WQI+oy)Epw!@m=t2;L=z=bj`& zxHs3c&YHwD9Hlk(Aqp<3&}yYAXiU?YaCQ;msdlNsNK86&;uZuA$ehW>(q&DFY5eB> zj|LR9HJ`Ies8LO+i8N)vb$ikmgoa1E&mfO^J#7XL-%^$gq5I#-DT2_yg|gb3>N7H zT_};}^zN0oEQ>|^eM@i`wAnC-*w{ZYgovDyvJWW$C9oP%g&F$|_8Qn0P4H`GEF{N> z^A`;xp^*|q7-YBL4rohC!|ypSHFoAxC^O(<6xfk_P+~apPa_tBxUwTnwQw-Tst8n;XUs3rD)fMHW7%$>(pFCkq3imA;eXuS_>a50aEdx$`cWWE z2L%E``EhqTA`bRHYJ08*s$Py}E_(m@x+aye|Fj3ck|{MM8GBiiabgf7c7(^g zsZG$4RhAttSYtOtmUS;nz*F*6q+Y_)mMlU%^<;jT198IALHnmK7-GJP-dbH1BLRT ztcJbmzzQl1p@?`8OocAarz2BmoGLBPPVwV~SM!!Fly)Zc_lFr|JFlWj9G*+VO|hDP zM;9cq5qT7d=4mw5mC&KF2^Fz8`S!;JymFu4?0K&CtXBYMKE4y*z%fZSiMOFdSvWn% z`de0^7~2LM8Wg8}GFSe~uPFax;s2xnYZAG$iGC~`_hVt$9}62eo7uWB(EryLE$m1S zFrq@-YCyLcETALByLBiTc@RGVPbZk*WCW0=Z)|U?)-~vG40pm2yiLb~T6Aw(iSf@t zTFHq;(w2b1w+Lqx=ifX{Tm~lm>Vr~THWYioq|~B6b|@t*7RXDckNe?Sh;3kQk(dOw zloFXP=Shu)K4BYszlU(`;<1j7^Y&PLJ3!)jBqWzwZrMMs|5i;}+{KAPTf!6)1VayK zm`o=>@(Bfi)-G6&lPlVodA*S4-TgzXCVUc?TBy6x{2bK6_76!Byjp&zH{G;m|D=B) z7BG%JmJ4isI_;FB;oVZs?J9=zOTwi0wAWSJ5pWs!E%k#?HU3lFqH!=h!QC2hKgwp$ zTS8Sc%X>qd@l9!Ow54YXztj~QjbL>L{y&zS`LSdpS*M#_BqY#!3grK(nCW6GYh~**FC{yqY94(~DaIB%_cy?+?&1%!ORr#g?H{_0{gH2`44Ug!n5Apkr(H26UR9xiv5O*{#x0*+WQh5~pWpEZup?q7QB zcS!Um0B8OjEe?Y9FFGLsaOsFw_bp^!3ugfYF9I`0`tzMzHvv&EHxF+!4Idi;ytl(1 z1`Add$8Mh=1|zNp8y7vj0I)8=_uaR_PTzObed_*A0NeIVz}ybyx6cE_0|WQt4g6#3 zNkCV-LHfZ1=wtN%m{FQzW8rX0JiS{sKq9D-xGkl*loZ?kHiJw_xIg;? z_t-*T6YwvI-G2c-fSt6s#Q=OH@^5H=$lpen0gbo0TcqC-GT#6Uf%Bek0Dmtaz7pWk zG#cXvFt8k2y*_#;cmdp5S?(O8jRGu2_W;4lUjaKoJzX;2I8lJLP5kEZ6_6r$|=?z=ps(XlmIv!1PQV zc~zi^VA)wgGVwg!%b*y8Ramh{Bl)3w?AOSk!^Ficf@J{yF0nc^$w8NJpTJB|30zY} zarX)v3EZCtr@FEB2oM3#7R}$zviL zX#lr`8HI}F#Y)0@+e79*Zc{I-EP;%`|yfc?kRA}zB8edd}I32ZCpT4ct{(_U-2O3?a zFhg)#F?*wA^B9*RkFB+=zcqayZ0}k-8=#0$;0 z6v~E$6i6FZ|5^|ysW?lDbxZK$CWKq#5KA1ndt$Ed5@)mP<_FP9xcnCdr4eaZDY~~J zVD6gphF;B5J|0e5bB7-sC7s#U;h09sKGM!<{3xc9;?z>CcbWhu(@{Kn>-~PIH=KvH z%pp!>I8#&9v&SxH48FP#irCuVufav&x=lI+D35cOaw#KR>V{-l8c|$yVOSufu`*5r zJEL3JF4ly`VA$2{^w4yYxn=LRgDeK#xl7h_wrL2Q5I=lt4)ZBZCQ5l=WdZ7XuAt>sIU+c(jQ zYw}t0!=hWU$9>z5tma~Jm120>rW2Lie>HsKjb_F0B>c;u;*pSWM6C=2JNHaQIa_vV z4F$D^JTc+(yOWB3h;iYr8%0K30Eu*a_+1N#@Vs0p@b*uy&A5vly(sG8<`4t4V`U2bv@j_*dnEB zFWYEr8Z`Kn(Uk<-n>^=<>h}6Kbx&KV7D(}G3nHxR#3Snj>85Z6B~9JP50U&l#43PF zsNV@bLtmkwR94hC!t>1(<0=Gu!_dIj!pl2WQ)|B~JDmFkW*m5%-;>O@%C-Hei(^O5 z?CfO{xLW0&b(2~jk|j|yjXqv*I#2uQ&J@@dUh_Hp&6KP`n}IxWmVQd$P!d12xM>)8 zHyC?;nz%J{96P-47}h9Q$45w6BPqb)JmaIrDCQvVviH}kjx~0vzv$GnfKVa{ktZuo z4-L;Ny~#AavCm3D>QCJdfjpYt1=rUN0{wh~Wc-G(qu?ps1#DqVT`OS&L3@ z$fY96gV8dXkL>q4q|_0|3jC@oK}RIJ_mL>B4>U0_nVNsS%T7IF>iKF({TI9P51&u8 z<#(BP=OJ7@zJCpi!PkgNv$`+dqLgg&illqBFwyxWr2EE@$F7zu^fi@nB9eGW8~_uJ zqjT+*;j7HzQ&?Tfd4uHZS$&VZp@XX@{l?u!n&BFZ)=_-i2Mvp(06H$of-$MUUZxDu z8ogcP?#wbori&J$S%4N#RSyvN6!T41VT4%Eby~4GP`AumwpE=7n)xH1#g8M-dsyva zh5zGLx*Sb+UVfKC$_Wr4kYaZ2W}gc^D5J}I`3;3qH-r=Sr$0gOc6vgIPCEbMm%H+D zME;>#7u0$~!u`=ypSx}~h&AOoUD0y)PQ3~$Gn0Ph8+`b9tu@x_pISxJsE>1A_C`}+ zi|J{*$EQ+?30Yu2>6&W@aE38OcA4B2YpUH9f3Px{+>*pXFB7f=o>QQF7inyIIS{c- zb*2`oTDk6+`F&&rJc&7a3P!0@FIK~;X;!fzx`0o?hYBelp*J#RjC7VSP+lxoki>@` zFoUoPHEQz9KsbDok-|p;&|8|~N(vKOTa=;A3G#BjWSMtpRWfkZMLDkZ*RR;c! zd5;Ca32v0!{gbVlJZcO)JH1KN?Ku2V5r^;m+7}4BsEVGnt0lWplY8oJf{d z(?O}Wk;fC`AOC3LjDS5RxPszo^M9(AggbCeeaHH^z%I&;Yy)fPc^3Yu2)fPY>@7$A zDo((HaZ?|Fyu21!G1i83+E2XyRF0&NIa^Rj#yZA?^g6!fm-&Op)>x-cRLXkW>+da+ zBy_DvI%AB){qGZfolasC|B9@awYLa`ZE+dZGp1Z8Poz8`Y3T8K&5*$WRer$UPWV^2 z1Mp6}3W^$GF`HjMuZJi|GTSQO_M^gN_adyt3m8xCF$zgYd&|D4gZzai(7~2VM4b7-7r+@4C^#bPPOV& ziAR_CZCfwhQNV4uic7%w&X=G6^pbEEC9_@*)C8)m@65_O&I+-#WWn_ zJ^JIhGs-;BMA(zF=;yei({I-Bm>zpJk}~`Aj?~#(pucNk68Mwf=sUk;KTxw{^=c9s(~Y(7q0Jo8tHB7o3{8=G z7Ez4!USBI=;8Yzbkancv02{AcWP=FY3g>Ix0Cex(T_9FVGS**b(nfNbbcRb7r9|S( z+IC{FLh@fKEZb*FIW#Y__QtZ)aSxHTjPQp9mSCMYG71^ij=9Vv>uovqt|3z?9Ej&u zz;z4B7VV_n#&VvJF`}j-^J(;oX(N83>5T&Byr~{WOe#|j#4nDShZf9r)d;vY1aJ4~ zA9Ba|h;m-d6j-l@?X(QZ8jHu2g{43crcLSp13N&(zk-%u{aPHjSa3jyw&E8GHx~+x zO8OY%Np1MhimY+18p3a7dW8-a``j~)=9?AlMPr{e2aY-KpZuu5QLB})It61(d+ksWb z%R9q94=07Hh39ruC|9>y$7!j@gY{YI#XE0#dJA<9Bolu9D)gQ1$FOW2PaF8jO8gfR z{BZ$!3y%*3f&c*jERB-EDfxbg25jB}ew|4`=vs7xJP!EYEz+eDHCXpGK&a`)L$(#s zJY+qM6nBo(G9Xx^eJkScac>hzV5Oz2;WW+3D1RC}pH$XN{j)XNy!Hw=C0DShH3R?YsJ~mnIRq+ zf4+<8=TJ-vgru2YynXBEnV?w5cLOQ<$$mQzcLxqtM3CC;uua>8XZgv8aGN`2pzrrF z_0E0*-%%wt^g^uddwO-FWPU*5Zs_KgRq^WW zw=chf*^+QeZE)_BW($B({H6WR?DpAg``{ijE{r4c0f7Z97y?oSNpmL*#qbXtHGmH6 zPWl@bvmh=ROz3pxEF$%uAX^E!D8z<29WMSJZ#b5D61U-jvV#&<6 z4CC^%{X{mrX~J)LBCnz17Q=PpZE|0`4-~;HNWiFJDycZB*&V|mH0FbdNAr+p8VTa+ zPJlKEiD5Hy>wyHIzb%I(Fz0q=OFmx*<+%w^${D!68c9UU?^AC@l~K}mxZ|(=$N1dPjV|j zf7t9f|L6e*=Nk9vfeaQ|4cF-}2K&gFO1-}bptH^_=Ju*R+h;6hr8}Pxsk!OqNdm(#9Z`c`F4BiIxE(9q}f`I@ANh ztbz1?WvyYauVApOv_ikIRDTR_5xwyAqW5~R$z8)NTt!;6q8JP%UI86$5fRibAT`A4 zomIwjwH(zA2fbBWZtKTlkm-6=O#$7z0bR366pvP8TF?$SF3RfsB|Z3ImAc7Q263i#H_|AmP8>@@3=~M75M0R~@BT8s)`ugeNwfWjocO$R!+>39Cv(~cumHO%7Gyt(RcRqxBle~2B zVpZ;Lb{PgkH;hUY2Fi;N_-h%72C}Lba`Cd7$Zdb5s z`E&wPAry&mg#DvNUGuPzrySJ-Kyv?@4W-H3y@-HoW^q4h&+F&6BTT-mDCxgv?Z7cW z8xHw!nj|YVr&0!LP5bfLhPpW&n`p&fO0;Ip-cXVH@>B@=uDSdro;9XS%DwSa5iG6I z)5;|ot9!q0Sblkw=v{LN+jyNPmq|W>p3>B~M@M}uL*ldvGo7@apq zX|<`{KvTi?iShe!MF9tL%i$M?r+AyDi{htc7q_$~PP+9dlWnnMp=-<-FffYW*Mr}E z1mq7@5#kuQSF=E_%u|cEt43Wi@KTrk+M9DD)g_XfV3yjm!51bx-ds(A5jI9P(H)lb zo@hicyhF2T9`;M;R+yv3D$TQ}VAZ3>#$h<*@cFtf@{^<%m1?KLmMB0Zzm=JD=~9a5Xyk0DKwX2f=j=%n0;5J}vP zheaVc*b+wZ8Xd{h(P@_I{kl+BzTJ|8=_dSsL@)}1?AL}h;-yh7SI#j4NtLGsfZha? zmp-FyV51~NN#+mkjqAMC@;2M!1lBwyjkSqzg6S#J1D+uhQ*;3x`;LFIo7Z zm$Up+i>z+N-#Yb+-I_2l+*;a>ozu*x(Cn?7GY0Jb=UW)ZO@?PwmJ?gg`>p~@D~2kP zVsNNVKG&5`#%pJ061giVzRxDl#W@=lzhqeJYjk&&oTH> z-)5;p`ne@MxL$83%O_Q_cX6MeMA!7$g)GPr+G=W5LGa2xv#7QXD(H6CU9m;ts#HsHoknr-&jVnW=7yt zb&-}I5upW;vQO+@(1ASBmZ}uo!Whk*=0zkivBT5~(VXzenuF!w1VlZ!tOM#@=dDVM z;R9C{3|I~RJ z6cE#h_4)$zm<7=0B!b+SMkdwZS52p&eRudz9pi8uU;ZosX+#C8YA9$kBqAr~BN`H3 z$`FRljwrE*{^%q^3VcN``ThVNhzG6uv-Ct8iL3zm2!DYFLm3*rbC=FbQ$t$MPWsMc z0o{ML`^d098Z%W$qS2Lj2tALOb0E{;(k3zbY|t=vAN90d^74GR;lA*&qn$t^|@;(Ato&QuhjFo7jhs_lm)3FDT@K%*w;PNV* z8LCbqdVO*PGw}&da#>yr&|U~^?;S#@hCOp1n(l!L#4iyCm04V=M>Y`>f5EoJLg8dj z|A0ZDa7v&^s}*h`Hb;b@(&BnorC#PVe;ABAfv#L^403|#KkK=vBTN+e7g;04iRu)V ziP04<9cq+E_$h)>FRHmJnV%lP&rA2D>~tKf8;|)DeSj6Cp1_psNDkK%xv%kMbNk74Hy0(YS4Qx%<1Zg_TDy z-D_t*!kVvT^$Qq?2KiwpT^jTpOCUb)(Xw^~UnCriEahR0Nl?IYSzNG%f>T3c&`9;@ zuw;<&YES;$n>@U7g%7%WR}$Y`5UO8#0C|!@nR8t^@=-#X=fYvsK}h0> zE2ssyRi*ZmP{}V;I-nlY9coK(Y2k%@m70Mx2NM%OV`jm10y?&9KG&iX1zOC2P^**D zJ1qFdJ$)`+L_XliVDdpzpZUf1PAs`sbSKlvS4iJtQ%?ndul0U!c;`l(+M$I|EGzt*kie8R1dUv_|$|T26p91-0q8Xm}+c)_bKJOsE zN^DIMC9PlDAr6=+7hKrGC@GygW>;QSyQJq-_KA1y#uK*H8KMHVQ~a2pYzKkWZ(nj= z$jJo3M(@ks%;iimWrJ+b{Rh^_ZUn3bYlJ$v6smLM7cdJkNq+>~2R@rKJ`g4^;*{wPBm5c;2VCMP5e5!EID!EUP5oqU^@92H zxHdy^69q39#!v8XS>xo>(n|bd05U=o2P!N`N~tyaF3qOLc_$*v%P}o^Z12SATtjmva-EZ4^hM{v>k z;F*z-l8dhj=K)5)=fc|Kt6qWc?xXj;Db#Adl@!rk+KxOBaX(hP-JAsGz~RC$pDwv% zSIgHx2Eqm+hZ&zr!L(bb5gVj_$UjEI&$3>Nm+TO8J{b zgq~j)mf@rEDUXyYuFPGyv1M+via}xR9)vVzSacRIys8nqb5*g{;RdSoPT~$U-HqcZ z*B-+ z{=?&@Xhb~b)fg$I1?rMo(U7d!&I>1a2G-=Ea2C=>dPRKa-NTh*Tw9b#_#;w>;3O)P zFQS2v-(TG~_{=L^X|6fdpueMvZT)&9+iP;gR_S?S_^wEq+2&wZoOac6vN4_M@K?1PE=LAi+gsW7eL(@~rW?Y&@oMXv(%| z^F^@|!?y@rt3QgGQhw7%7rsM-#=Tp;UM2Xg#r=5>P%-8^*T=L$?H@qXX!T2de*pjw zdH&2h`i-^F?~%G=Wr8ox_hLwwPBd@|tXHxq=t}g;zZVLGEj8q=&Kb*t1priLlM$d4 zu7Kc{!4*9?{HJF>cXDQ$Or!{hJY|$2&l@a=k8PL1%@as>BYOZUOxx#pI6@QO5)W73 z)Ed%&$%q7oioo*1BPa)RDzsSZC&y%LhRgxSA%W7DYY`N(p8xO)U=>66-Ii@OtTOOz zc0+EaDJm?d;)mnprV?C@(CF5+3SW)Pq4K|r39VWPnPnBLs_qW;#>~> z2r$=GSD_ARC$Qu4ihDWrFKGVe4>6fk0 zxcqUy7QXOlb>V${+$!TIO$P|>+dt1O^hH5A!n$-{mBV$0F$`8}3HS2ZE>H$dkKNd` zO;b4UrdaTgi!0{bq;D;JPL#S}FmX(;h@x&LsVLr;{ZXpuzzGGS98sEi}GNahRht-pQ~v&pL! zCfsa_FLW!B|B1U6jK1Y*cm$)rrD7| zjutC^nwX2qxZ9@(1wUZkazO$Zf+zk=An(E1sjO-PJM4SEdNQi9KX@t{V%%fQj2J4@ zZ4lQ!;*2tsLN$e-m>*o0f3oPC?n*k4PT$SmkK-S4xLNlUf8>Y9TX16UHPc6eIcQn) zL$qd{1nsVjy*dKzCKZly%MZir=%AEQ32b#fqncwf^i~!un`S5{^wcezoE*rQT_z`f zghD6bi1USo0xU^BsXOjUWZ=f^A&z!+fAFhenv3Evu@JcZrWR!+jb|-@;<->rcQk0?u6)&SqqYOV&Uu;e54t-s&M#X(&-WSJF3#ZWILTxWar>YK2rc-tt>;rhB7 z@yvOb40^v6QR}PZk}xBxrG%qR=BLpN&ZK221@zW@x?(0Rl+ZmXehmkr?dI!+;n3KrfTOkwNYmVb-MQ!ACgRpqe zqEXWE5s&d2t!!;(iAIgd>4-!`o?T|xG=7${+QIoG^oyxX`~q?K%rHOuz;itnJTYZ# z{(Dgm>gmC$)hTekuYVi*1^)GrM-EVUg#agiHr!?;kGr~W`~!i3Z#I;L484e#OmCap zj~ux0*Q3nSsUYT2%7!iL@{@XnVdko2o>2A@hxx8k^ub{B`|i_OglQ2E9_H1Y+&lEF z(0nkJFM~6?$A*ak47);)i<6UY?`JgbT>>iZ85Bx@yfk~xf#*pmDWh=GgpcrB>^rw! z*S%6$a`3E(&kxlGx2UB?@sBe%abp7kprkzMv9tz9fo$l~(Q~W#3?{Uy(sPy_m*f1> z*Pn+^{DL1cGy2!<{b79s5d1N*(tQy__lOaON&>bAN8OOtaj%=Nxb?hNtBuB( z<`D^Tvy4>&)6#EgAW**!OgQ8+XMVpLXpYZXH^L0BLwz4C4hZ`!Uf~ zMa}FDBF|}(fK-;Tp1!7TrFI!a`JuD0Oa^B81n`^hxXZaFs+A6Gj|epmeDKS4a)igw zDFE>}yvN*GAUhIT!(P)A?HlR2I$kBztn;7xU>c(lfwZId!^CX_7mEN!0Fg~1dHBw0 zMfoK4ku8{_=6Y6I@>7S;HC;z+r@%M!?^tbn!uoxwr@8oT28F}avxkrN82(ImmwD2i zLn%5*fSy7sr9oF-mrUe#!ZsR3MdaU{Q5ZREwRFjFf_TWdeu_#SQXuQ-E*{A}3X+Yd zY+1?PGijZYlHN^y!w9oDNPTR#`5f1XrBZAg=#;q{=mSWytL~4+&uW|I(sk%-#X$ix zUfg=YQ7!9Hxvva7V&NykPABe$?_hbnU9pLTq#^Js=Y96+BE3ydZfc8ATogmgH3?^2 z=l*vWW>k13D)^Xasv15$PFp8>3AU`#z}ScX;jagPbNgphmGnAU^=!d-sR&KtAJG2w zz!3dD6HVd|V|Viir`z|ut>F+5MS5wpK`TAS4(AK(9U`+n85HW{cQW*8wJ)}xj-U4- zSY+GtED~W9DfY(kc5V%DVAJAcnc`S}^e!sKy)fq$E_sHQ`6O#&-R9-7heY;JdT|tn z!`q4zr1w$WETW1jCr#aT^}F1%|*8MYA0+zkB80MQ(e2Wcd=Jylf(+e#UVe0nm}=2myh#ggX~ zl9LCEREF2Xp1;(Gh1mU`#BtQW-j(>?h~9pA1%YLCY7f}}dVQR$0gt!tF5o_W#+!m@ zTxuLyh(=Q4+#+h_L?cwF(FY{a@cc81kJ%Hd<6Bt+$-kc{_`@?@dt!T!P38n^8Q~|G z+5&tRMHxi?3CUP;5ft8j7=^rEoHy?Bc-3|Kpg&17B}z?LV)W|Q4~43c_01XIlmPKo zf97L1Ch5lHQg+G+Q|VIl@k!6u3`MU(Mh{=FGfj}uu4!PMqBdR2XGq;&HS8C|zsWiV z&sdp1Om%_OM_g;ttr%eg9{=*JcciL)y;_Thc={TLtsbJOOib%6nT4h-e{x7nCh77M znq3`&iB?L#aVeDhy8;HVFh|N5h!u^RpZ!9RGc^LM`2ba?rU9IDJ0ooa--;uCLJ9ir zt?7Sv-^RVITLW0OOy~szs~>uF!A;jn0~v!NR`g%xo$DIFge=@`AD@O+_r|?nkF)aU zkdgYhkUVR2bhWo} zYt)E|bYBgFRK$72Kbj;C-}6F+=4bLt)3X3wsX!z(XixXQB z5%X*EC;(`Cf9hqHEnh?i(aHdapIwN#?mmir*6sP|pFQGVm#5?VeP2ZU@(CRrj>*l9$^0AE;qo5-$|$|UP3`1eIzsr$N61E$9{@w{ zwMw#;pAA7NI6pXyz-uGGMbS5~@=ECp%sgRFXb$kS|K#lE?rUMZOi*p`&P6Mt@b)y^ zxPg(-o|vu2&%oBINjCpbr9jkjOS-n_?AVc40yS62k9mPz_biQxSM*AjjLW+B;-R9#FY+E($A6u2hM--@p?!fzl}w&V#&MSr8*g5g0I)yR4I;YV)^OJ5@0tZt^mXB=TRM#S=rEtA!zKqzNi(5yC~H%=N?8)%^(KU=Z@%FIzid zvu^-7DfG`&g=x)ViEP~Y$S0=S5;u+J1|D?D^5#AML)>q^6SA6HE<^$eqR6dak6~b; zCg~@Lb@-HYkx?!7sF|lv2`ROeuTJN-RcfvDN6rkd40w%?mmc&~xE+`TdHMbIcLYng zhc@h^kwZsfjYS*b4ly(^`z<(pRV=)D_4T6Go*$A0hfam@+-p&A4ds;6OEv-KVDnQ8 z?pK0B!;VpOAhTygxU0Iwb7^Z4=0!b=1d>9Tp-bNcqO zL^v#@gP+e9p%T^}y=1r;q^gO#XTrgzc^g^--u-g_qSW>*!|@%SPF+Q!5pF~7ZXGpC z{3@y}Xr0bT|Kbhgm5+kau?B$g3y|U*fTSfqQ%X6xmwI|nmGxCW(8EzsK*tqN1HUKgB; zuI#yKvLSD=I?J2ax4Ed{TOjwjXTN@<;N;hsHRo3z(^^T$OPg}*Z+NAAb~G@pl~kGP z-M2WA=-C)$U3y|l^R6*%AN5yzvDV{iA~eg;H#58$1;RV9hB~rmD(~`m&h~=Fis|0^ z$~v|qv9KwVtxajt)_4;${rE-ZiGPDu+vvDKyM}7gi&F>|p?D1Dmcjm~_7Wfl^ zaW}F=6DkJy^OtI9X1R0e+`>NG<}Bt5fK4rkE@7b0C5hhO6GaCA2Zz*?94p=5Qc--!g zKpyX!_MXP%mY7WW;OO7_B&Zg43$qfqbnm7S)#v^61hbTR$jjgX66$-TB0r*YWJoo{ zGehaH#40^FW5oeZ7ir+9`qs%omBJ?r#FN9d*~tcAUMq89Kk_LKO4O(KOp2a=wBCLT z`q#46A|59*pJ?J_hQfVeNf~YbxWz{br=*BdfDHRFr;Vl0=)6~}N~Om9=i;pQkr^&S zDjE>IFonB2U2EN#53Od#4rOIRHp0u~yzoso0f?--;gY0Y)kCY0saih<#s^s$=2LKs z9IQlxW*bs23h%cU%D}zZAolX7Zsr{c27<0&HUR?j*ZbZ#5lD;(K)oN$E<^Bq{yp8< zSOg6QvLAA#eG8^rX9snZG00+nd|^y&U)M~_tvwgbv~n(qXfz%!@nyGnyiu=)^|cyQ zP#@k^PBP8G;LFuzYcaN-do24 z>D5Fal64VfFh)ixf0chQgF`D~_O|Nm!7hKs&X%Jn5nhjQ%z0<2usF`I>Gm%aKV6-1 z0zsb=1U6heBA%*Gr06JbAjdcc&zJM_bl-V`L-#=0GMmI%QtIi2>8p0KJuz<1U%q}k z;pM$B27N%KLqhiR1FtZPK4jC) z@YCq> zjlcfWQ>XZD%?6R3Wj7_@AK!8I$QO zLRbBIwZk&9$TS4+mNmcz6)yoVk9-=;H~jqPDMDxOkZ{Jn1ov)!5BhkKpGzF`{Un@= zaX-@`R7;7`r(2H3Lm3fzq+?S6L%_Y~1HKx05TE**iGs^W8hIsiqkd^7j73J6QE*gx zd{WEzR3G2OrjJvBvf%YPtPmf)AE-+>ohElW(+~JVkyZa|Y&)I1t9E;i{Ykw~W)pTY zczVKy$S18yBfx?6e z@p@SSN9xkoMqX*_j3uq@{wvEKlLA*6c)j0neF|FSSA%M5YZN=50Gd0mpHm8u5Ecy2 z+pH8kW=aD&Kv4Q6@AXW!Lw=c`^zf{rIOdF^ATJ(_E(Z}1r|*UhUJpsMb?0$N#Npv; z1s^HoF{l^MPLa$6VvKh(k{z|dRX_buIhGZ|@^EIA5db*>qr?VI=~A`9F=KDg7^W@A zn?aIs@$I@MrsI*fYIoTx(71pQAA4l6MK%!JAk@erF}`A~iJMOrASOm&)t_sA3R1CH zOom5D6Eu-5Wtv>;OyJ8U{gHHL9KBk=m6p)RxY>R+1&JLA?svHaWWL}}wG2}({YbQ0brlYRj*=^YS z>*v!CG43fin0)1B3PMRBm%bR2DIIdvR&C-5KfON%OyFbAg=vVYMuuAkC;WmZN;D*v zV=C(AskKDYjQpmU$)qe@Z}(_cvvy_cq7Y44{x6QsV#`$^ilQIH0JmX~;O@+DcM0(I zkABmvZb+(box67e#eS@l8}`(m@_x&mtN97IY0^lo^I-nyHTP8Rj6N4Ep{>ZhhS|Uc z?pk=$3Z-Qpi@E%SJjzRXd`0)5GvA9HiOu<7@g{gvYI{{d|GEyZlGZ3|Wcm9E`@vH= zbpmIZu2M)C);)sOu~y%VmkHew|1%=YLd2mjRy`e|TrdJ)kB7!=q;tkutiUZ(#cF}f z+IS|^!ki(7nxetnjh69n;m!nl2SpW!WZRs6{|Zy90UoDd@Z%}6$7 z>({R@kAa$BjXs=FDz7GdI*g8f)i`D#Lk=?!9hfZ#O zmyWsLTf$xj@xzbLA=I}O3;6Q60ntXoidbsmS$;@l1m_U9+NYw;9}pS)nzI<21Q=(Y z)UIL8 zDXu@i_a8|icJsD-;I{@CtFWy6dLqf)L-hCLD(#ZEFM1EdlINE5 z@>sP#?0a*G9U(O4`49{UJJ~Dl(ughJz)zKbJ8ub$;~KzC51yb+j|KQc)+}Rw3+1Ox zh8$?cJs!pingmj9^mayEBS&rkbym}!LoM>~vuYl!4VKdjN|8eA zdXEowN_#>o9W$eA@H`EJeI2iMehl@ZT5IbF3q^Ew zx8TjX%l|N)gVJp@b?E#!iKDqJb@w`3Q-YRYLY|c3Ag?(WI=Htdl2(?Znc_iD0k(zn zgU598DS#~VWM(PBls?nfT#5e2b{Q;pS(NV3@nEyVOo?uMxmRljHB%3g!f)iYtKau1 zx|gLtw2Y9ZD2+me_J2RyZZAa37<#|?x_n^%xtoMmEkD7f@r{FmEBe3d`ipUQ4Vslb zFo;`Rj~kX_zc9bmAB#_oGa07wCYf|GSXIq;0i=UYpaTt+RT9nV{*;BW64Bw{Aj=i{0}7s=SsZ)t=-o;!!rg-aGs+Lz z5~nckRAfd%?*x>h!^Aokt?vbU(m0e=gm>f>Ngx*1JSU@TI|l+ zE&obY4SMv{dsd&JH9a9-;MQuwaOCH_RQc|@ahP_1Pnsjzr!{%mJ+OXd24Djjw@n?Q zd%#EONtoobuj6Lo)Gw_w%b|m?3S#{t2cZ0<*3C&wrxyi(S_qbL@GgU&IJ1Ut``F# zvZwI+B5E6vTWyN&xDYY5aKI?ZW?dxgwv(oi#V&Ylvwqxt1abGtF5KOiJM7`xxsF0? z-}l*9J`)h#U8sF)6H#MiWZ7Rxt#m(r{$3wg6Hw{*VY0ga5a#va<@U3<7yIVGcKr&w zzTpIB@E;KkhC(ldJQ_f<9#Y;9V(yJYERv1bTGj_IG10YjC}{-t9iqUX&X3tja`@em z`|tYcg>eTj5zjr;9H|)gEcqa*`5+<)B<^nUcu_ks=C<(!zmD#_?IF*Ot1YjKb|YLR ztV0U2a~{i@q_}>I;5FJ#?fkGfCx7m4%BvZN)%($e2CzlFhDh1-flXcK?d#yEIU){3 zN}*we)MRRadsEiiL}!4YC-TX!%5__ie5kcrDNyCHg4B_0_(p-4ru!bNxTJ2QgT!N@ zSWU5(pV#-(ezxLS9xWS+DyjBhHFrt-Lwa?*^V_qLp4!~ynOL`FvygI|awxooXH22F z7sv^j2oV((_AbLQr0LjD4$ro`L4L=H$b4*V>C?@Yol73u&yKVLs>%LN0pTB)Ub(Ta{s?gDkCkQ;Z@{D5L6d?nyGM+s$Ddvyy z-2y^>Vbk1^41Kt7m$s$l^3`{6&2Sd%gZ#=nNO|NPv?=7Qi_1TO!6;^%(L<+brmdDxp{z@Tlk)@1H zHhP-EeK~3pidY19Q>dQG0f5qoshP=ku zHYfbWhmok_5|6fJ#x!TtuN+>UXkgCN%F#TKanmI@9Vd&0a7;JLJRQb z+U!UP1|k=AGZ=H0*jy(td;l9Qa=^iiVYy5V3;HIy+>Qg!hFZI3Ge`_9r`<0Bu~7~Fh920DVTFHT1dbDC5HYE}LqBSm3R%XPINJ>Ond zh-SL2#&vzk>=;f-jXt$AS#OFncO43Nh2xrK(Ox9I>D+fwjRHdZCgQA)0UAC4WJMD^ z<~YpQsl}eEpB#LHz{}uy2EdY2_RC2^f4`sezqq$?;RIOT+AnHc-yA-i1AKmDt^P-Z+PC`0S6OEptXSd_4YM%vgX{wXL3y35n6qlIY4mG=N+l z{>+EPTe%>{<_2Ws`IP#we6ZKB$%Bza=-4)~mhn;Tmry1S2N6cj`&gRoa~4FnEkKP6 z^wJEpKp;w2?@*I%=VAdyTT1eXbi{9Z$kHhOGxQ77b^MPXPy{s3qqR@V3GOtXN3E8| z4Cdw_4?&aZ3)Y6CSBv*mPEAbh6lUCgjZln_;cS(^LI^ZQ4rgd#cf0&<@`Rv@D>j+& z9#9|Fmwxb<2;5FF4&G)?$>L%;?6qf6FE2A6@(>ld$^Y3rp11vr(l%VhH z>pfq{`#m9;_O@|?$7Grp;0+5ztCGWIU=~P9`n=;&>S^Zx?P*X$0xd=(bEKfi>u?&7 z#Dip+mbh)j$}oa`9^;nSP&NokZXC|H(pVPHhvV1m@qr7AGCjrLw}gkEP-%{-U#)|% z)If84IUiIP{njjrOR)oGzfzT`it4t3-vnds)WN`BL3scC|4pJkd#h;TFL0Ioyrx z3+I9@MAm?h(P0PFanrWp>Kv5s6c!pc3!cT*_87^CCwQuXRafAC4A5HG4n$rZupeux zZMDMn-_?zzq%^JYy7by<|JJy~O>JeCgVCc~8Na=Vg7cqLlrN0De! zsS>;BJ;txbia!6lcM3lTde97{=D+h%3vv6C+>8^9n2bCKT~bl+3g7RAuWl6dM%^v* zNKl~n^iK`QXdCJ5V|Zemyb<6*?bOYK8Ub)dzfl--527F6^>DSgxiZG(W z%c2(-p{OF`Z_J}UquBF4U8oFyMcGzf`-R=+ow>bh`bJshlKFOYH59Sr&qP!8IlK!K z{rS)kph&;S?7rajI3id1@Bd`nFa&XW(U^#bau+hkigY1fIGf zI6~onGM>89uVx0GvD|N?G~wgM_N)Jr1q#B%nC7~B5w0r$rSeviMq>9c(kF&kc>ozGwnZbeiJ`S5|FKs2CpypA@76b>XBFr6czvxWt2;+X z?53E@-9Z9!;m~+ag0ay*J!8mIk>c?>Ic_K_mx(A|8h9S!CS2NNsQ0O#PkwUd6ZcH1JSZkI-&CcTiQ_S)E+X;Dt;?UBAbIdIM7Qq^N8{F2QMEU6jsIcGDAp0i_aDt;sD%}c0XbI`VZ7~b677tQM_6yQ-PZ$FQ zxT4A<=oz7FpAl84cMOUhc!o$}Bi^tNTVvC73Bs>D?{`i=(pc+78XO!$#wl~K5+>sb z@79T@4a*hWirhnfM-DUgIzmdDh|{UCBn@km@3%-XPR2lya)5P zaGAAXllZUCUpC$b0uUpKnny{NhEUgFbsss;cLoaAud9Tn@-$)n@jEZIqHL>oVbcX}+>RY%ULCc3wDAl}-D zb|0=hc2o5fMdq_CJ!AA=|NN@5Cty9XPW&xPZ7Rb<6Bk~f<|jF< z3NeOA4>`k&@8(!r{xfoJX~aHXXD_nmlf5LDUe0aOmapweJyB1jjPhgN3|-!F-A5Eb z>^a(UzKomA_TWNa&@VlV(0_z#K7I-7u!S4O1>@^AS@CYScn#0#-~JR~SSUv$KOeb* zb+FV(zsR(kul2nG6nGp}`!>yqI`svfRrSzIFKvWFhOcQkn~4 z(Y1X|W5aS8U4ic(0HHChRPxh{O^8P9Y$8I-oW8ivz--LIa3Tb`gN-7aqa#qdx)^xz zDykbUOtq5JCwx#qzpRc}?9NxkBv#ja>X*b|-E_U%k7D33Sx*1bluz~%y}8A}{^488IRIhiKH zizx9g-#z;`KR%LWm<~lD4J$E<3QdhvQ^<)~lwF2Vaun=-_H|Mh&V)7E;tdS0t}pR2 zx3I@O_>>7>BF^mPSxMPy*2&fYzLEm9x;1eo3$&#IPMo!*W#V9Dxxw&18(h5 zHNg-%Bp5c!nSeZ?+vYWU)r&DoAxM2y@!9CTN1zd^f(^1*y>YM3tnh$0SV~#zWNEbg z5Yw=JcFH2Vr$aTppUIO`Q8nNBJsi^}M@CL?0UB;-kukv$>MQTBl(E)d;|xs9oYk3N zA=w;kEbRmrBp;DeP!Jp=KCZB%&4_CTU&%#5if@@1FHc{h}Aix%XBCnT9JZOKOPe5GzSVt#riB76eB zbLNM$n^pJA{->j*p9nW#;TpY1y7fnLh_XC~ELL0iF?khZ$?{Bp`CZd2O85jT++Zo8 z->&1D4a~{tiz~jwy``E~9pJj2p}2x7HIVvo-ZKyx8CWmy_}|mlcZ}8-{q*l5SB}{_ z?``zu6H{jnmp=rL1ErBr?7;WFyM?%0F22M3I=dH;@ak;r+KeA68Fh$q{G)f~sC!U2 zTvIHKbe++1c@e5k*JX%UYt8B(bu+g)xAeP-!|#U3ztpl26da*5f2aL*g3a-U+>Jkn zHvv)iTSct`?W`xi`nGrTmyJ7Qoby(Ry59H1^1c)mQ2Gw{Z667#D45!uuw`BfbJw!2 zd+uavT9fLQ1Yr#oN0v4Cr9s3M!E3M8hx$J>seA23*&{bkA?i*S&f zJPRB+4^o;|r-%#SYO!C=-AKB#ZE5ODGqjNh-E)*Z4ZzZ9gXFd@v(Z$stp;&*tVzz6 zs2q!~l8cU?_OAeptiZ`2#u>GPwJFpHlPO6O5!(|^TfxR-0;x5wicc1^%(z+xsoF8d zB2669>-<5{UAnD7SCT)_N?V+xH2c?{tci|U?RGXQf?NuSp&b2Yp0GP4clzt6;xVmu(VS-$>qTi*>qwRTkK_019*N4j?Jpf3)c)AcLnB+UvlV4ZA@$|(h**IUXk zxzavF%J!wi2p+O!U%|iD3Ap8MF4}dw9p#u6&wg61-~_q^b0C_E48vK>g`J zfVy7ZXDK?lC4mEe#xS~Z=|sP$4QA?MHPy?3tmkugYWN4q+TprmwDXv3R+0JZtMYYp z5Fg9tUcyMD$-=tk)n&ul^o^0k$q@p+@NM^q%yB?wB|mo!rHs;i64a7+S|hC_12m|o zW2RHr*_;vEK%+z0c8N8`5&cEA&^=kS)iCY_EXo%og+J8U-aCjt$Ru!kQ@p1j2T~JK z41`AH!EoF4=0cO;-NET?a+>mpcYsbAlLvkV=NP?wP4SiYHEfmP@(&FQpp!#bTp9=4 zZ7J!sx!oiY)tvn^N_hvIRtI5Vx{McRiNUe%}_s|Ga!;(qe*N^Yp5e21=?6ZNhH}XJmp~zgcb%FLI z2?sgkb+1hhZT)i*AaQXJ8Nk$6YMkJn=`a5Sb4XpfRp^>5fs!x4L_Ey-04G4$zrIi) zIstk~p|nEzILdVaU1xS;mV{p_j&VxOC62ECOiHN!0Ld5QT^fG`ZC1n( zugs5&(2QmEBz!jNxsf`2{Y;lZzk>oB2%;?ZVaeXMr1IZ)hz-i)0s=u2ASM&c26mpN zLvo!s0rl#R_DoMadfpvT9~VC(7Hy)d3s3$zQmKx%*m-Fm&4~mNGx)L+|NFS|D_sHs zz1ZFrVOvXfRqZFQRh6)dx@fS@RNnc6nO2IBuN$p2WlFhYe}6tA0HaZoIA+_|sy8WW zP~`lZ2^Rp2qyh8IAX&@jWGQszz&1Rh8J|!##!MA_x8q+9j8%B6JKt~?oTGCUk!!?A zMpFir0aFYi{i7@StZl=plTK}F)F6ExMRZr{QPNe~`%Au#^?rsINZOY+tqz^XbTK=R zwe=wE(cfD)FOV1l256VeDuS@3fI6*iG&-E@pCF#^M}Pq%*>*MMM2Hn4(5OwW2U?4R z(L1|GhL~td1$?Clf)l9ap$@zK-8xc1%oe3hTgBO- zRC<3UiTn*q4}3kw?;~d6Fz^SzC-6D8^q#XTA8!=DvoH4!!e$xr))E0bzJ;Q9-#@Sf zS97SV_e&4^cn?=l06ds|PVE*=R5UI;tj^1;xTGo|E_cGN*og{A9> zUX?u?N4@BPq^J>GJ9-)k=3x|+7p_JzI@2$ROIwAtNqkHYy)QT>8!{O z01a#Vnj~xi`rrNxw3or~w|?6^p7UU|yh5E^v-SIYsMGk|uTG6Ooqw}pq4TjfNw7hc z4kIZ*IIyUR7-6P>%mYYeCb3iK2emtBk)T$>iuP_`ngz2qdl2xGGIe- z>*b^k+vbcn=bCdex0#VqU;T3PV<`BLF(F z<;&rmuoEzy*B`P0!n-YlX@wCyr^YyO^&yy!gY~%`Rm5EJ0_JxO8TK4k+!QCV$mP;F~N%dotm2wDg(J1Cp!mxT7o3?kIn zv-pa)owS1mGit`q{E|Wt`A?|ppT|#TL&D$Aob*N|5N?Qx5h9^dc5fO@V`# zb7Oxca-wDxrjX*ImLjkA;3+{r%slvKOw(`H1dg^E!~96|KQ2K zY{lJ|esr$$9>AmT>Q3DbwPz9Kt2{&RFxaK&|&Lw{?tB!Y$(0w@onq zU>^pcp0DsOT}LvEqLX1g#tRB(F0ihPgp^(ZGRW|u77qW*sW=TRV>i8-zq|B-Vv{sZ zt$0ayF6A}iYsY8sbi~O>6FOM+1)*~amTTVjSvzn|G^$Gd-F#{Kxsu9a*h8VGx8A)a z!k|ydFn?{oE1d36j$%r9{A1ewu3Q4+3~@@v&qaWQrT1hsH<4=0)3fNkElvx;a#hPu z_MER^qZwLNIm36>e)~s^fNMVs*m~zdmIke2BV-w&LF}hnaySb<2nDcyD1y$RUX0D&A&qA#R0{ z{QzkcPii$}53UbGw4Ymbn&qbCEqL(7HK!AEL=%0Hjha>kOFpmaD$$9K?JdiW|J|fc zQa#CNEn-qMP^ctWNUTGu%K_1(SnAbEa`g3_2_*G(Rn+zn9=N&L-11)F=vX8{q03+* ziTWGC`WCtUCLrMQHrXU=)a0nWaR&jI99cvIxqXM!%{M`<`sINX)gNlLcHaPSX8h5B zdI#s;TlP9%yz-@$0f>Agp3&ZZT6}yo*VnMhT-hE)2=+zhNSi5 z9ewIt;F>xpi6l5wEIz)$BjaJ4_s{Y$V_17gn)Q^MG9rA-+CW=s0ij173~n*#)%lyF z@&1But9@B+DZ^vK{4WxYm37CoPSb!!kftHpBm+b@eDgL49JB*-DEg^fKibjy;jz8E5m)mvj zdPC3_LLDeZ_FaKVa$%$gg%>k_h}9N!SNnK*LlX48pHdl0CHY!BN2aqsE11+UC5(~} zEwgwRq!-j7QF+>2pb7-L4*aiDDq`0SMN}^_-hARk+5@J3V3CER+xa?7!xmqn@TX^x z3DacJGr`kMjv=P@;KSkL{ctmA1{i4K1S`5%@pTKou9oW ztGzF+O}FhAKckZeQLFX_K0bYAKY()vzF?ly1+pr%AyS|H^3W>Gk&MuMr9cw(t3x|h zu)yuC|LV-jpm~-ztqJHdkKee_WfA5USNvkw=_vtXn|Tt)%5CAm)-|ksr6pzxkNC7c zc)?u(V(C#TwV=*E2h;Tz_bj-r(UJ{ogNzbD4qfJo+04V6GLz8wUE&~=XPVnXtr8ddVKldI8rZ2*E$Df@67G#7!#IZ=_?wkrM1kk1b|(I;S?j*w z)V)dd2EWp>r2DkN7U+g{;B;1DMG;`1NjO@`Al=_UVvI<3}$mmn+LYR|AqHk%a;bY}h}k=gXdwF!K-j<4DFI zTdJ6%{AA5|P;VI;Q;hD^@meGOMA|Y7qbx2#tknICzZK$aAP#+~T;Am}l9{5q<9F7Q zR(_f2m%#OQn&IT+N9)VsSE#~@afgPG!%$(jkDN*%Kud}6ZJ!I901N}Zcwo9~JXs&R z`t3jL;tD{GK4i)4JEBkj8$S#_W1JW#O*Xsq&_VD)a;Tnsvvcat?i8)8uf@tx<~Q0H zRYV>pE$O_?z>#^(pNykX3D00ChKJ1mqTNNcd5mnO)B@2>;xSB)#qj>%hdT*m`SrqR zPRWTAV3j`NuP}|mJANqQ!w^8rerEkBMKwj+ab6r(Kyva|b?;0d9E6b$KIq>yw1||d zInrdl2ygiuBlrLd$owM-v&1HT{1VLV+&UY`dD#hTjqT zLavKHPb9{u3)Hht=Ii*k=dFRTK28eJ#)7X3e1?mT+ag#iKr5fGyX}A5Xo%xs8^3D{ zz^3IjC-2aq+d2*irAkXWbf@eK?7b69aWTI2G}9ZXRIi_d4bP7L?m^wAx)sIv!0z)Q z)12a6`Xa<7)`UF1p^i;RmF$MMen({W^u^tNX9kjGiynno9pl*dygw(|O#|1B3@)&+ z3I#?V-xP%%Kxe2)4LXjwxaxC>{6I*IxX)5Ew3wl53O+;WA0|7XAjhqAKSv!j=Jgp0 zClyY8z#> z0mf_-|!HMHcPUy^5&Jb}^={J)n!X@L1z55^VsP}b9r-SFVB z59%&g`2#jieJVeRrZ4O(M428Z*gfl`)(yFgq_V#WC3v7Lown5ofGtJ=&jTQ?J3aAi zT_LD=C^wJ6H=YJammcW&9RuV>zYD2ZYVf6R_qv{$91eRjs7}Vd_s)1d{yo<$?zD)M zW44#m4!fw()xP+Q;VS?vF(gojWTZ$0eG10N&LP#|vwVX5Y0;)Ge$nX#Gc)5}z)>4p zBLvekNh%0iE$Ol2e}r@|r$yKT-YCbK*GQYbQhyGw_+5|AgBekpFf{_x96h!kF2eS%6<{gM?6Q0GR_+FChdUE#SHvRJO41i znM>ONZNq45z34`Wn@=~5oOm(ae`QCNd!!Q8Dx;~Ly3erg$`JK58+Yjy6>uWntHTrsiR=7gC?eds24i>dY zipmU6tdK8$q@^m|1O>qtcQJx4m;nHu@x{uF)jtqM#Fc%Rqe2vIFuN7^I(=sr?dLax z0VdsVvHN3qr)cat3A0?-a^3V!`i445!iv+m>Ok|w`XFj=FMoQuoP}F~Z1Uu!w8&0( zz1y%@wxvUZ?N)EVrA=@^peXOCGofQI_vRT?XQQ}JIpGSVOatcHwbRQ#%40wqpOgYB zlBS36KgxMk;E-~H{@XqfQL#pE)n6OG5l6 z8iDmZ^P1mE(#*_(|7u7;{`i z2%U%fp>_(KR*wfPWI(m{cfJ4<=cpV^ImrJOjek5!rgOXz zj0DfZMFEalXqqWKO|=HgpiT`6#Y=JF2k!yc4wZ(HdrH!U7--X-+tAJF32NrY>F$a1 zZT#h)`>ReSG#E;{yPiK?coOkEl`8tO;5xPd78pN*!e}geys^jbn4(~P4Xc+#Mhr+u zloFP=%K2wPT{~lU&-kqCM(l>@4Q7R9;l3&jF(bYGI=eNgw zA@CTU(!=OX4k>LS&HKyagDRe#kCA7@2%N|VpGamk^jK!va|`p{9m_37C0HI0x<=6k z3G^KY`rHPZXrznFd>$az5%|atRl{FPCxgeYsgL65kJ5o@7U~ZtQ8e)M$6@^4mVef( zLkrUOQFq*}{#cB(HMh|MW*(xv_25rL8pb>%)n@los;f4vD@Yn(40|ffuab1z3b$`l zE%29(4mmx^%6~o*i^gl&V4}G~%;e70s5SsQRa9A3t%+Q7WrHvKvxx$q!cj_x?RDu& z9H)%NAflM~yXN-fcz_!vBY(2sZ_Su_c38S$B=U-NFHZE}Q|FAo3xSUZvw{9_anO%C zDg`C3FA8o|YUgZ93{)%2rE5aDle3EEV5>6j4KlRZtPxrI@A*N8wHHc$CT|sk;aNF4 zO}=ML>8*~BDHuPPirFMLVQd9YGN1~0WyiwL);l%OtXCQNidU$|^S+kycl-3MBAl_= z22-u^O1bUp6%zJ6e{YUAV>74}5LvTflqN(ABbcLWC12H)usiY#PUA03OO5b7DswYr z2lO3&&EBXV&?G7ljM)>&zZHs#xi4N;C^#_|{9W{@o+O<|7>VLgj5!CB z_a?@-4UrhG9hBkc1(^YV9og_x*>qmzpC=;6WJ72l%Usnbl-Yx=XWYh7cVsR}(6gXd-W%5}8$$ zq&UX~iggU_7oha!6wYhHg&Na4o?VL49>PDIBjgA2#Ki0qz8dor@E83-ZZ^?_;=dmpnsWeX$#brua9(8m3M+%Qf6u4- z|C}c$-32YYM@5_=C}-&nOOMgfrdt447TJ*N6xX|Lf>pZFGbW$@YKw74lt5a%Uw{zF z+EP8QZu&D+wG;NA&!_tEJ#YC|`G1dJ@hEBcZ5y1W=P*q2CQeYD9qr-Y4gKKO5fraC z*jQ1|*XGH6g=@dDC?JR|(*z+~M4wxtlY;{zlzB%7y&{opH`czOo2yNcJLFADuPO7? zO>tychQ9YG$G{W3{AH|QaZ&YF=cIeDqJx&Gjl3sk{iu8E4=V10;Q+!|M3QW&@FX!G z`ZDg9D(x>pvIq|L_F}({llY;)n=LAAn&Yd3Wpt!Z{`VcBVSr%Rng9h&cXAv~q_dKZ zDHHew)Q11j@rIY$v-&v%GX4znw88`?0^{^Y@JEUo5(7cC2(ewA?|{ zmKqtU=ink%d;&`SO$xyIyVgM23j<3kzJeY1CV3TeL*{96 z%@_Wze@unr=Hi?DVH$^f={KpsVzgjKM`Xl>;qtUPKAlMr?epqoQx`^<=gPYmN+R8Y zu)j?c*Os7pl}ZT>9M#UBT1x~=^<%>in&Dh0OuiAk*X0&qc#R@pLF(-(@z9TO8F(|T?WUmL+3U2kEiq2a+TSF z@B3zOjy-n*y&nRC~=$s`(Kn!T&O5)Dlx+x)?k2ADTG`OWFJBA>aZ8~1df zFPnW8W*_{+NwKUTbddk-P5DLzf~Fw}49l@9ak?OQl-?lsxsd8(E2%Q%2B|H{UVmH_ zs*7F5vX!%7IM|mp2QD74-WpqN<;c!mrfPHmS__?y9w=-`2$I8k>xb!Ufu7+M#2>S# z9}eZKJ~>WwFV*5pBkIoCR;gZ3+>4SOW!H2eCE`wIwG5eqgI_V6^g7|?a8*I$=3b=fp53g`;g1p=E;B$ zZocJjlH%iSUahsJ0V!0S)lr7h$-#{}EKp&XXO6JDe#H6B3F)YPYfv7y#k6J)4x0-s z9!l86T>(GmMSVqyM|~-l!HvJoiKgf4u#OGjLKM&f5vw6GacWnml=?_4Z1Z^TVe4Lh zg$gC~h#IHuTbD%i_#3eAQJFMx@rDcF2@fE=)b4t_SItxu+V%CJ0Au7CT~_Dy&Uw#1Z3wc=`+i-3j7F4TB^UE^3~(>P1|3r@+IquT z)DfMKen1qUP+J8}fVZlq3&Ou6^@0{s23$9G9^VvMfVs3RcE4?@^wB(czkdOrj@tgQ zz!(X&s3OW9qvwZfL}L^>@OXaGoRonU9J84CiFI_A7N)uDVUAgHnYlby@|G1KTSfBy zoUh=^ie)LN)&=C0wq!;;?rRbsYZJIV|Ne4B+$OyDXJAPwy>K2tc}O~LYNqC8Z~J>& zqXTYDcR{+s2V{H_^>kwuxt%GzoBISl_-%yXikA7?U|w1_akji#8*2Utmc>*Szp5P_ z+y08aZwrF&_@H2~0V{k(!{q|)$Bm8K1?G>YQT25Bq2hP4DmL&#Q{|5K!P6p+oA)pqlv92ve;W2*U)VT^Tu1(YIA*c=hQX1ofQ_r!Y0vmmj*` z0=%6VlAe%r%;>)oz+Y+MO5x#8$O(;#F_CNW#p*IuCISL6J0NPpX&1Dsu2Rg9?g1 zfi*tdnLdUJEnO7K4YMKkUV|K-#*FrT`k1+~-}xqwyWK@t@!PD#A1Cq=o<(Vej#rE6 zKxeGtA5%T1MP;QAC_xDG4TH(DvQ|vli_I9=MCYQBiG-hTO{Zo{T!*BDjpJ6`14qJ; zEZ&BwTqMHH!t%kGticqp>f(=asWmu&Vu`Gpeyx1@?Du>U-brgTympqO{LaTQA04fv3u@dp5{`_OVV#KAuo1{sj0fX9_m!&u#I3WX{gYB8G7CDpAn- zr)<-1!D7sOGI&I(TcB6iNW|1)rG0!=IY--X64zSfGpliRJR_Jo#y~uP9zVd&HByIN zDP#bvHV9|Y;mV?EP^kdgxxYW)sNY~5g;;5c$Vf>al9f3&1_dP@IcvG7T!(9?dBPul zQ_DRpJ87een_JLJ+PuW8cbY=MHFje$mmilO%LX7leg>-CyjO`xQ!MSpV3!nxmhPmE zm+;QGyl|Hthp9T_Mp;+GH$i+cr{YNWP+c%cze^*iGi5_;uwW>J9wp!f}a{ZO4B4=xvJxy2ix`sC403`d)XUA z^VnSC`gI#M8IO>+lKd^^Tr z0NZ-WLe($+W-gzK-t_JyFN2mAts$LR8l?ccg?Hv{-6b+SdmEao`G!6d?!Lm2L1hka z_cxc#G*0^sWVV+elXGC3k!l9kSArWY#vi_W3S=@$g9v6BjLX+a^@jV2GFwmAZPzMe^eERB1SY=uVJevDf+f}( zPYlQU4Qb9rZ%F2(-G*;D=W7AAK5cLi zR=;jhP&6vd5`)Mre+&~c%d;TMR^*jwMQZu2t{aLD#e*6W38LdM!tYLG?r5Q8QCA50 z>NG|gW=(vKxcM7rRbNnfK6ADB47|5}@Eg1pvbb`3+HoMXfyku}#uew)On&+>iGs7* zXRqFgzWIfM$iqGq2@VAnI9WAU=pGA}chuo!{a9VQ(I@JY`U%As2x+P+=6K;%ZLxcq z5W~5QmFV@|RYPPUmQkXX`mpCz^8+=SRkr7dT-$Ycw;4962SSSkA%@v5ehFbhlETVy zjmD{OJ;w{(B|k&*GHCfuJXbkq6O=W%w*m1mccNBMATfbT#s!NMduyKC3@>Asm(V4- zN)^9DX1b43;ilXxKv1ipwVMSF1D5*S82=`WlHu6LH4Tn+(64#7V8e1ntJk@^WBY~KQBk4&N8C$?>GSO-fP8GS8Y>`vC4f-q^V~S)(H8Q|sxjr4&}*#S`W}wx zM-xVBZE{bs#O0+>vAtC0$JK2`TOS1bDR$lOX;BF@cqqmOfIZ(!mFnZfjp^txC4HZP zM$F4Ce*G=oDAm<^8v3^mMt>_1n+TS)&zozy!Bs{r_M2!uYp+gyLpT=B>J$zdU?tNn z+WE9B4X_*99#~&BhV)cKsF*umQQax;v38sbhH;k%ur&cYEX2n)*qwu?8;$4zYUi#D zj=bR6ppQ$*Gd_3~xWI>ek-R#@?sjU0`eqVy(}hl%WQa_3!&l7Fq4MfV0K`IrD1 z14_CEZyonPzpjy$&R*jSi)?nMWgja}mMS2`&B107~)jKfGEJ_g(h9(I? z84m!YyHuybv~UsW4Z8xXLEQV+2q?R-(y2%GGgI%j;^)mzYj>+ z(sE)9_6nvP7JblvUIP&zAg;ed)`MBnWg0ju2o_9~{UHFj_{;^UdaV-l1!`xhnb}WW zvi!m*6vKFK!?2?Q-Rfhgb^L=h;RC=S!Ce4logS}=SsAULom~r>bo%g7>E@N5R;TJk zF*H9_B1~FH0OXn;S9ODHTzg^g$?EF~A7gxB~PF8vtfQJZlZk0rr)E1UC^XnX+ zHroafR6fYaV80}k%(V0OLiRjarkEvGz??&7InR@}d|(0NIjf%*l!T)baYbvg%fs$0 zx=8B`M5iRCWRArqo1{nH@_mCchD~;j;#mkJmUc+$sOfN>BB$Szw39WUBzkO4J@wB9 z33>8;1pCEIPYF#a@pg_^q2s#lLvwffclEPpT6-Gb6YrKFNi!Cimt9m1k1Evlex@yf zSwCodd&a$bo^r@G0xtna*WXuyf@ph3nW}#2WfTQUvRVq`>L=JyyywX=SJX5agXZsn z+iw5Bq;`<#mt>_1fSY2{(5!nTnbn530wj{WIq z&)?UT_`jr}4ukl@-=0x-qh-3y@cVtGxg_M$`Ixh~WM*Gg;hyr(Q&w-#LxDN5LelwF z3eX(%u-a0Dyk@krOAEBKID(9BhNTXIEv1pnZTD1GsTj?A^_#RXi>dFtSx&;oQy1k4*UA}m&dJ2Y#5qK$!nwgFgB5jrL2#Ap*plMg~ozk|)Q_?h9_ z#rf63$`1t)s<2F+0Jz*Oatq%A#PwjPt`A9(wVfX|1CXJmn|0hnCx`M_ib-HFVX$6# z+^A)7g)s1^bOHKiz9Lfp-t+W+-^eg?o{3__XQj_*uJVTlDhOTrfxY9zsfO9{*+E2; zH%H&o`qq!kYsCDEvyWXE4iv);c?G0K)Pg-w%bwB8E+=a z+tn7~V;p$&jN}wpe%!r<+Uf$)AJ~Hc1RFbjy<%D(no#s^)+3;-huAlIp{3?00s-Q0 zLuO2Y4TuEo{dw9PDTmF}!p<7j%rHLQ6x_Ai5*((Yw!aAY0OKN+^81+P2Mz${_S=(B zdHiUQK1?QIxxh9O7>^f=E~I@zK6r8<7&^I9E4lF~%$m|ia|fw?YH1vSE#AunpORK` z$4ZpC(Ynw*>=h6em`u!fu-fQeE&05_3*?F-7y}AX&d-h0rfqzpFbtDutr}`m z`-=Xc2r`KxF0}mGXF;TZKSXL6`o1jbcy>D+Ykb{-yRmw(2*Fc;D&^%I=pI#};;vB4- zUw6gspzG?Fw7IiX&D+;zz|qTqtKY41znY;qlzZjXyt5K|Yi@&{Jph(31l73vlJo4F z%Bg-8T+(5Rbj#o7h{V9_l-c`EW|^yGit8SYI&4%rwrl8cr;+|Eb`O9yWRfA!JM+wnx^scpnM8xzV-uCOAuJ5 z8iAI;r;Vj;2msaDkfLA7%AK?lu?OnaF}~DAfg1`fdt_OQ2;>!f7ItlE2Jvr5gq;hW zMdVA7lae#}VPfgVGdN3hnT2cH*d^-cK#RW&`tSfxPGeB)ftrI~;L(mN?OD@71a13P zy2G}KB%M8Y&{A)T58)94(bJs8oaLWG7uYr*e45bQ_t!T%7*ISQ-*BzVtYL-?!0J@O zP4OSrBaKYa&a+xXOLJbDB`sI-%S@oo7VUhblMpplr0%dy(i-z9*5YPO~WfPW(zaC)>vsmQK8(n9pW=`PjKq&f#e@ zPidU^I^1b?Zibkn(dGI#AI-d25Q`@TfF}DZdHfPP5GqX9fDJc>Yv9|#@Z5cc1;92) zHy4bcgT`M>SZ(1ENglR0*M686$MqL1gr{)fFM_P??KAe)=^qcG-muxo z5cq`+*K`gv=N*spPT~!+a{eQDz}+9}Gmn}W&OY>v9G%YvI{0oxrvlsV;WG`A#EIwp zRmy1C^D_wT>kL;C1a4>;Q=zK9e(3Ib1K*#F&iJNq3+07x(G?C577JFxT4)We=nZ@L zQz%}zIEc(;)aNp*0l0-9$^{P94#g%~A6WI=I-$d;!yO)`KYVQXaO0C5B@2BxU{M-^ z`lbpMB)o}YHcljm?Wy2(6f{p`ZAOF*l$2VDNVwMpIBpy9{9+8RX0o{K#PpR2v_0>jm8dYJI*-#Z#F*(bDYbf zuAyHgr=;iz7LVz~hfN>y+Bg>ehF?lx(ET_9HFWTo>=7(4z+H-$!q@tjepi zqp%w9)>AtQW23*HUc&o?JMK@TabXxM*Ua`syhz*R)=IE9*L%P1*u!C{oCL%)eU|e! zjM4&uAotDO^z6Q`5ogC_s`*0~bv=Cs$`!O6tf1-JYFrNUl_!6Fy}NBcT=J^(H4*x1 z^c%nOmrgDDWw_a{=+aK2i9N(CH)6#g;W zlm7t}&;)L~gJ*o7B5p=s%sB7_mJa&8pup$NqFjBt!RP*ov)Xa^diG4jjvMGlpv~KF zHb}P`W-JiR@^v=>F;xLMF8v_UpOh*1(Tw-LOgc?^cI#zNLjR5*76izI_4HH8VFY~3 z97afm)Giw`oB&GVTqobpCHLdGAD8YqU6C5E*-o6NGp{|rw;*CV?Yd7jq~q@`jAJ^v zbjj&^+(Z4`zhXa~Nb*Dg@v@-Qk<^amrr+blgB_*Dx$PM0B-`OvmmOi8j=Vbc{KHip zxe>aP>=+nB5>0&?1tyM5I$Kt=xAIG73u73p*3nZwZ$&p=FG@@SiJyM3Y|?JvPt58M zHSzi+GdzII>o$MG9kdMn3%sS-nPl~3?k!Cy;{KtMtQ*6+iW2PANmszw=BL7$(cp5WX1GzUMei`QaO-HK*)0r+~l+GC}<0)Ta{3oZl;Vua_wI>=H%@%@Q()$Po|X1_4YU znS!Mj%fSN*_wNF4l!>G4nOjL=|27HlT92Z1_3sx$a5dGE8{=OvBQ&bLC;yFr(%5|m zBE3}l7`RaDz>4HICkmIuw#hI{+)Bf@+f_ zkX1rM&U-M#dUMpB;Xi+d=iD4o54qC)Q~#z!Q|{EQ*w%ZoV|ydpBk}fR7%jDpCp&x( zhjs=T+mVE*4q7VkIR{#<*Djn8$DWo~vUk4L*EX5s`SuoGE`pq0P(n;a8M~_#(f!F| zWU5i4jC_KRibsLq)FY8q&ZZJgw*&TukPRYER1WfETstVzw7D9O76zdqb=19d#zht* ztHu@9igWk;6%kB1PuB8`!y!MT6b-*BIBVDux*ScgBCn}U5DSun_*Ml!)Es|YlCS?Q z4|1)^d8{LMr@u-qcl@+jD0N}Wu4o}oR~HkW>awZ+R+Wb)>-lEH9PV#CE z?TLh9ArK)8jsYg*iKt@0M%0<1HzCN+@uAR1^IkUrovm%1-(1e|6h(LXTHi!E(%2_M z@m~%J{tu#E5|8cey)f-c!eesjajuf`6cU8juQR~;m@nr2S(bU6M7~l;CbVl44f8wB zlrKBIph-Rsg^kLm&X<`#pyD;8IJ0`G6GWE_Y29DCat~zw^1ZEDV*=H_lo=nKvcu}) z!5!bbZ|I?3ObtLgbxtMT1qJ-_AB!Q zDF)hLj2T8d_C`{tCsu@oK2qJ~gNs+qB1%vis9a|+(55luCAaeHl`4cex^leSoX=lG zT>K9quA8i@k+HF9iZVG`*cMi)Y}MwBoNgV_Au6RmvbRAWLG+^U+Y%o-ZJq_i`6`5Z zS?BxUVaH3tya4p+fA^X?795f;C`QE(|K}A;SqbMrlQNi)1%D*-!x4wT&=dGFv1z+N z9k%<8xK^_K0J}g|P}bb9rp!3xrA+%W!VOvSGoT@73;4++re()_yQ(JAPuC(AoiKVnQCm)hZSwc5DjGuQ)am-ptc z{gcjODE`#ET{R7-s@v_6l03LtgI|PiV4(d2hzmIg`UfVSF(nw% zviC`FbZ3uRl@ud0a{`JbH{Gb!xH3lVNRJ5Nr*m;;9D!`9c{jo1+7pk6{Y0}K-(9)~ zlWZ{K@R@6eHH2eMYsD~W*x;VSX=q4Lb% zj5FWM*2rt%iOTFsLv%<+5g|h(%#{oy-+b!nKoj4-ffH`s=6tygA^{+Ow9UZ>7 zweIR~#BwQhKF!8+*f3R1>vIW>LgOc#d=e9@{@V=7LCG-%ObTI0rqR6~t}@XAX(6P) zJ94J0X!URvUXcnW2?{y$^Wof=)8n+|W${oHD}KY8OHw&J>@femSbZ1Dz1L`**!o%} z4ATVkK32=b%gL_pyr@JoOG@-v@O-Ze_R!h4)098F{d;9Xs#z|Uj=b`hg2Z&Lp&%(n zAy?C9Y4Mc<{T3w4Yr{+rX87mPs~p;I%fdb2bV<_3m`O~|1yK6ewDAO^7SnAEc7y*Hxe&ijU=bo zfp%|ZZg@qF8jHJxV{iH*DOX=BQJNmFWpbNpC|vpl-S9|{>@K(ZzelZ=CtEIegA=>t zjZYB{^MlYDz)^9&YzVszz^}&9-t~`Q_Q}g?C4UQdSaFMC9&)e2=1}j2tvs4GQcttqg*R$x4U9PUV$tK6(O3FDi`hQiH(6#yDJB&c&}c4^Tpbq18~f**RpfN&!jcrs(mrQr4fFsTHYr$ z!Q#-TY~sTO7q}Sxb=jgmS&^l5sU|STC}r16lX{?U?Rr*^Pjk4`8YX<*HGz`E$;~_t zeI1ocZR}eAzyg5N%o6_uLmp1*?GTbszNkSHpiuTEJioXA;!(>ly8eeeiQ?I=ziGak*GZdm zA7^IY2+|9~^k|rQzD98m8_w$4czamU7Xu71>;-~?b^wUBndhkpB=umD*W*QoHLHh< zh+*Uq)8$&>jtD`uNGv5w4*?LX`r9m!+G0vYPfzZbW_BCSCCCe>Nl@d&>fXUjj*o_O zXn%`Cj^x;%wKQDIW#Bc&AU_|`y7CO2cxlgn58lncLu+J=-I@JiF$Y`VP7$%sY0|Uh%>tc_&sB;+Va5(I}$>b&tRF_@!;?+f05c5 zdutH2?WWX}jrcMcu9clz7q5wdtI|7r^p6%GRZ{?KJ zjmO4)JY-PkrJylcuz zPblf%^-A^gGXb1>jbz9OVz1y_tWp@(zR!}dt?1oE<=D&0oZ!OF=xAHa&t4H!jd0Z0 z&E%7Wg$2djGs7(p&WJqOAk61vk-2a|nm(MlNBa2%1pA}F$W!ftgWhlZXZeE4+*b8< zf4hvY1cMmMH8Z}aIyePY1z~2Kj46>z2B!zb+9yx))z7<>7nutI07pQ$zg-fQ3#iv& zDZ+!gCbQ-rI17X-+k36vi1nhvOy>~yg)~`lObv%03aIA%>BjK0E5#Oeb@Wnp=#?XM z`oHkN9P&jl;&C|9o^^ogD6Uk#=|RqzUBr!8-F8|3+LJ?0?5o9#E8edq*!V+MtGdZ7aRll4-P5DSD7UXaGy26woww@=CZFbKCEDN3 z2JK`Kfk-$pL}Ma(c2@HT-m1Cw(|sD7a9F=)aS(}!&rbMWU;qd>lm~4k?z|3~O=s~*AARkJwpB{9dtbliA^mIL+C0*#_^ZQ7njnk(WjJFsXc zV<~U>4q4?a-+TSE)CeAawMN?8VbaXXKW^Q=8faYP(b^s_!T_(x+)v;uw$xP<;FJt> z&6Xw`wLzV-p2zUl6>BRg^@wVWrea^@ba0eb&EFXkI5ZgOei zoc3;+uRpt{ksGu0nD_BkQmCnwtL4A_V63{TJSQ#sP9sz}?H3kEo9cINc0#~A zc>D0u6mZTtfzj3h`Hvc4oLk<^`!n&a6u?=I_jHxTg5`AH%38{L)6$nro8RB70toS{ z?ve9>SLM#7qFB7K3Kp=qwLfg38oXAp?3fx9dn%`jTS~;a3Nq;LFX@# zDwl6SUZrby?yI3qa)`Z&K7-7tCU|>O5g*>H{b9h72BLB4m`0`x?JBFT&2&5Smj`G3 zc1kM5{2`Sws}CuiN{>b4M*?&bhA=U0ZoU3pWL6NUh9dYjH5(+Z(>ekiU^;%R&P8L6 zwYFNvbd(EP$b#<)Wg6&|mISAdJ+B;xO3bbAm0RosGlp6?waM2p>pZBk;Lj^w5)uP_ z23mdrAE67r4(jb%oj_5&p-}n5-BLkD7NoD@O_o;d3RCy@{Lo>DV(?4&2$YHUaJU(X zV8ujvD)!tARUwHSvsz!3Asd~iHnzTV$2LEPIWw%a4M@F{|E{sBykUAyw#@iCLaL zxwjH^h(?XH6>pKQ<&O-f(zi!ty=vRVQcD_2IAYu$QkXEn!tDXPLofC){D$*`1Q=-1}pM1!HMHz z%^31?yd zs2mBVccCUFq;wBj*AU;aFMsk`$t1kmhYgK_Q)-S4i`l=jg?zPv_wh?|n=pzBjO9rt zt6eN$J9oMjdOQumh0Bi?S}gmUmQp@os=SO+4r^H5{6H(G&s3Depc|B!7|^m!et85P zOz}hT_Q}E8@o8q!qKO-)ZiqxhKXrPm>TT^icDKQN;Y4#C=ugMR(wokYnEBbovM0Yk zvd^3~EnQb+etoWbdSTZXyXa$$Ckk^d|kk0b;aKssv#jBJ;#p zBZE#)l~H&0hL293tf`+CiQuEN^pUpaJNV%6_xk|cSX3j*^r5zk?E>InDo>iLdn~L_ z{PjHnkzP=;f;W51{CNDW(nY4<8IOigkYtG+(b-(Gku1`THk*;s?L`(~nWtemS~u9i z3W8e-_^jTBW3cio47o@(%6c=+4<6YdN0m8>j-~fXwH+CFL^wlsUe_$J@610oZoG+0 zzCtR9KI9S=jTav01t-(b(V*F>cr6vva=A(7#=(xWUpmb}L;W0HSb=CT>ILeIj{8}~ zqqpwwFNcbtaaV2`heBow`o_aAl0$qO!NL}YsQ0TXL@b7~&QNEQqtP~Q9zchUgO6q# z(|yavY2x>6M?x9R=nf+-KSPD)8rt!vVj#;Cs}7mur7L$a{MLl=2?zY%WeH*ab4 z33ipeH4^8wPX^H8>FbC+AB89S@=tG@H)Ita`6h=#AI9?vU!aoL@Fpf9qICm0T2iT_f^qX47_9jLqlf z^F7(0TMydU3%x;oKCUsxhFl~)Tt&TelJ8~HfEq-gxl?HFxv|fYJ1*%<(_W*tT6(Un zw~+#mFmB-pvr!UDX}@q0={7}=m2H7ip}rSj@Gyq$wYI7GdKK*m#xAHjV{*Q}GDd!a zxWd<8q>kI(P+caK4D3iOpPf$%wZ83YJzjvH=CwV6!VBbT0rHx*r$3Org^a9nO8siH zH)xh|@$bH0`TFdsfnpv7nmqOCD@W*c?$7K7A=7U47VEP>{_ayfM3Zc7pJfwb+FTZ`{A967qrNFc>XS6JifIM1ouK6Q8x;zgoD3jw zjmD(c~k|ziP47g9ymn1y`YK-E|1?k6- zS@t)#ygal8@s2A7(<#^O_DsmhhkxOq{dV}6d#_cs1S!3QfDJ&qs)3MfS)DDn#b);B?4 z5z=IU^j`kxYehw^+G0b^A=K~-quVkc=@t#z>Zch3w`(>lr^ujTi zi}u2Cn4_0UgatDvwMpjFKsY@p3jU7k4#xT*&J%JPLuk-gn=r47PC&zecUb z{HZ|tkuf|g)t>^r`Fo;_CkT|p#uv# z7O}bZV&bS}pc^mJ-`*UKExA6%Z^Xvpgd_(nm^6SZ#2l-?ofs1>d zrHli*K2jHn!KVmD?)Nre{7I&g%_thSbDmusnNH^2m8aH$*Sr6FQhX82SqubB>cPZKJ{M=;(lek6Nqk2p?@X_L`l74ws|Xa`qP`bQ)bDK!INx~ zXew)cMV6x<@Ph8Fvvs4wokPRln_8C#auo09?61tz502A4&cFIiL%jUgdwy7(5Y7+@ z4A{TVgOVgLsA;keQ5sR5c>hP!dF;lj1yS^a7?48`$vMYnM$R-jef`BxdNa#Xx8P8< zYb|3q!%Qi;iGFzr1g$#gzgy-0-OZA-e(>5>LVnm6sil`q!eu@sde1f_HcJ-?FL;*q zkwLjnO1Fol`&kkTIKeCLQCZ{;FZQaWclY(pZ%}iUk8L=Ij?t^963y8^AKDC&tRnj1 z6T&l}qQFrSH>Bc8C@!91;;gWnq(n%U@|7zO5-kr8^UzF-U;-k~ zmqXbR-pGG!8fWTfG;*}Sy}!RDVPN@i5w2Y5HL-oPSGviY;=pTjK#JGvbE4?Hvm?TB zilf!oB=(}f7{gTn=tr?_J$J$3L$SLNdK9s^nq8DGDF(4PE?&MfsBTOkO?EzPpl+Iu4 zuIO!mQ?AlT1M_*P>4x0q2udAWlqBl=^0Y6w=BdaHt4O-~VAf}8m3X3GZ+^W!xx}2T zb0o*z1%G#kqL?^~m?iQ1o(akrGaPV#jLN?Op-1?a(cM1NaNuH)d6n4j_2tHTpWMC8 zYWU{&mjkXar_+-9rWzQ)U4>NI+&|Pukcm6Of495=;#h>@6`Lny5LD!#KfILnGijRc zZ*Lh;#y{B|6C1Wl8yHm`GfUdNo#Bca=cLC=J-u@lB{zApesh&l-gLSm= zBp0zBMTvd>?2G}EGmhW0(z$cTkF#ZF!u{>3R1O|uh)5>UGNE`3$7%xN{vRYm-i(kFX7dmWc z9RrBCIv!gHxcuWe(CdTTJybSk_C{-M7o?IE0HrhhH!?cx-f^6WteiQ^kg2dE?vCZdZ?}%m$(TztXP#>NQg;X{ z9+;41#RCcTSc2dOh*z?ltS88zu4D?IhS;kgIQwnPYn>J`A6b_j48Eo|oKq@)xGru` zi$4sb`hIYhl)LG$z80upN@{~oc}bm&Io^?7q_%#p({5{7`aE_tJ2m!<){;}3wR4Hq z>vPmlPP&|=*vsRG%8QWy)Fei0FQeTw4Q0FBtYix;z~pMW_%<)2 zru-MSMQ4Vea(`LAz%c>cW+)BTr8&tP;opRo96H`7D*MC>y3q0l?ZI9cv^7~$Ue5G6 zEl5E;VJeN4HR?sulPEuc?PQhXPv3WH=NR-W4R8W?8dr?`$=ilXp}v>>nrsEAULW(C zAn;cx15B&r0Ky6Q?-^k@64&Mh$|`rDZ?4%t=PA7#(0m&ps&zO~xE!tBP`{rCb^JPy zg*f#jARkgZV&ilpIp!ChtGz$9f46ceV5UT%+t{ zVs%P~=b&@IXg1$A%%%G7p1jBZ5H)CN3MvN{S`$2^aC8Q;lfR1c)}j9He%?8WrHA!l zHzOZvfw%Xqm4|qZSdLFAebi1TCm?6HiHnVblUrF>Ba66#8Q}vMhJ!n1iwUtvNaBzO zLPC#n+dV5Dbq82PD|CH^9&h{4A9Hco83(MG@wWh<7|#>a6m@EhjU?#PvL{QG^oGnM z)VY-LVwFO=dJLiJd;3v3D-H!RI6oMfXl@};rTvYe#(|n+{4Jx&6~C~~(d~0YcF$^A z0%=5i7!r!^hH$eVd-wU|%W4^f1cufyk80`In`hRbOiUV4YIa!HN?_tmnzu{=T{ zsuumF_pP}X)W?CbzMJPSu5ZQ%cN-NheDYT(f!MZk_!2(Wt2oZkILnUiM;3QQ<2Uze z$GwrK>ZQ|bFn+^l1Z;8K`C5%5x^@0GhS6(oai_tP)}5J%#FhfaEoxSBvPr{!;H{O? zl`tP21k^(HgIfya`~IA>adX`F<$UIyte=Fto_!t+TS?xsF^}TgAI$H)wpNCU!QIg_ zTdf+K7q&jNl~_D7RYNbIhn?PDlOWor&arW8wbWr}oZPr;xC$LDK*Z-sfKm8`Z^VWp zeMnp*jyKOlj3M_q`y-2WxDeZ32S?Nzj@wFz1svY}+G&as3*k9grRm3pzsYw#$`9bR zlk?y}84D`)d2a2tC?yAEi3E{Q=KE|^%Inek zyGy`+%0_$+gEMD=DsYz<2xfyf=p%rhTn$9ka~?pQXfqaMzIY zQJPD3%UWUy|C4K2c&s5o2~yh>#2u1Sgc z#aKM|GU*QN{8SE%NawhdkA5&G<%kO=Oq#FC;sJcF2;q%7$yMF;3#Tj$+{3TPV15?B zsmP^TzXrBF2~H0ew+`OhZ>C$6ooj~lgz4Fkoea|_+TRYJMfGd|1vBMOLXJ9v;R2z( zy)Di;J9;RB@5V7^)SHI$+x!ABU#FB3{i^=j!Y&G}Wct=scE6+ozEF*We zJ4wqBdAzhoeAGTAeOm}e0UAK@%X4KvUw&8(Y`@ky4vw?0lsb|h77l>4ivXLFdn1a~ zC67gfk$YF-<3@aOsScUJKDs`pNu*3Nkkec$+IA#CLJ?c$$s$Od{veKA0LJg_+;^4j zkV;;V13asz5X4}ssppX)_$c=fIMYefGR-IsFZgSf8AFx_&8pq$^>#zi;49si3`|fY z#QzvYt^8GbCU#GzD(TRbWE)9(Ts+cgmwwcfvaGg?A`m&nP}!8Zyap!9Ub+E%hzb7o zxqpFttHzBq8qO!u&o9tlrkFZzAHALP+?~fXJOzzwbQo)0FI#W8dI=boZ~V4J@qCe5 z`0v*LaIr<{zl15XEskj|_PA*qw7?TF{<1gFaOu(zDe~yk)uDSP^L=BU4+0t^^8L3c zDS^}H-%|`?%K4cLmoz|*Z|lN%+C1M^VSoTp*2=9w<^$!U(h%Tp@JZ5ysw%^n3lKgO z_-h7wC4O6(;OsNkGq%e*{Q@rRD|{%@18VOg=)JE7-EYidk;K?ivGQ$~ z`6(9T@b;AD>5ejb9{gQ^%6;*WNk!r~SKRIr5WB(Zvsz7b1P%190CV)0?f`oCI`#)#IVpRJDx^w+F!n_)7bN}7 zp_lB}%cB#V_qb|AOGUfWDD1~Ab7trgyI;Ei0Gu@^;e=lB?~3H4N%X7r$=XXDR3HSU z-zet1!G3->+fiYIsw~IU6=`cpsggVQHO3O9$Pu^Ik7JPB@upVCR2iXEr*_3pv)y44Hh;dC;juEvnGN^Wp)~yoxZ)$Wwi%=1{ zax>@W&X1QQjplw(+A-F+p{j|`VXAjfvhm!;Xn5i+*an{k#CPl%ZZH7L} zY|eSF>MuoRjyn0P*qL8eVIrazx1B@~v~bXS&0aJ$MiC>aEz>4nYrfy_8jAvNoT(Uo zudj(_?p%9bfWlq;z5d?C_#R7ay>)MEp;~!pc_1U#9PLEiJP!>FC^2ep7#YyozXD_V zM4GlEOVaFSd)ZFxTJ`FG0` zwI-zf!LP;~c%s`p0B0XQ|8cEyC|qt@wL0-Qg6vAxAdwdX@A?3Cpyjg?4o`N*<#L!3 zcqy~E8tdPC1d|<=sUgZq=BxwqWKf>xmvaP+&oW+Sji|G`5}|=4w2YI?ukATVeFOh< zR546Hd3#ipHaJ8C^c5C;*CwTazUyl_Jz2qZ;R3y7LF&1UozO2*0Cqp;aDk70re;?0 zz_?KUEC{_3n$}p6hC_u8Wczhk;Y=%3K!93)#VO~>8PR89ieh8FFW}A!WRUXJLP+j$ z8F5EL*X}dDQt_M#D&oJN&G+Y`PB{Aq$u;aR4q{2fCjO#CUoAbUzni6Tyf){HqK@j# z;;^}NpUL){Z>wLRb)>R>!&ofk6I=T{v=dD!y8B>Sg>=`w4Us40BPW$sETX{6l! z>KnKu;8qmI9DGDwb&?y?H~TcV=B#N?5aeP-lWN^D*v~;+>a0AUzZw)^huMkudvRDq z3tVSl$JR;V0#A08c@&E}zDK648UkkQAHCi6AdtuAh?u$TX?n7s2Uw z4LIcLbaJrIx0XgZ{2uqWG@i#f*CJxq2n}?k&W=-2(PrJ}$Wq?VOg-?7cpWuy_e0b^ z)a9D?tduV;=_j02N>#F>fn8>zox8+acv8Q7^wT_Kl3K)Nh8MhTiI97sld^Tw#;-bz z!*?T0+Smfn+al?(p@ka1=p>`C~-Cgsw~tk-vn-QKp&kPED22VRhuia}#4ooa34q z0ElqsJ)BMH_J~N!%%T+t*2YPJH%oyVYJ^rH?3=ZS6>45uua#}W!e^^1l>vZ+d^2wy z;^bXQygV|KQS=P;u8a~370;mqw1LWX3fK)9xd+$grwxmCGsRmtP zH>BJTjd_pqXY1FzyT5y_lpyJP@3p0`-MNlesfH6|Q!aM-bj+WfN&NP=N9kbPaPILA z7B>BxYqPRHK{JA<+XpmxA}=FDXvJ~d=mrRcRahx4GG}lfCtP9R`fge)Y|-pOee0`Y zBsGG`{Vwrqy`fWbUm6z7<2->N9S_(<=#-bGLluyklCBNCIAOvm%NYbGU+jaVp!281 z8oX)yHOxOfdyu>acFXQR25s}7?=Hy%U==IwV~&s4ih{<&xEiduUm(D32O3RY?oF1` z$eFb13c6l@ukf|M>!_=g*?c8X8c`ze;A@ZxBY7|F_b8dPzkjy(Y_l`Kg?x}naTPy9 z0XZom3On024-O$je0>6)V~qUu=C0)<{Yk%`oP0)E)1z|Nf{Wy4eOUa!@%PyQKqZ$A z6*$HP|Bz|Sa?0FYr|MJ$SS)gVwb0iaIYaY4kXeYqB~(ca0K!xP0D*BW8urtVr#-ntA5)YLoPH5OKz6dnUafrrz zyi)77t_va7R`=FrGk>oxcy#^|q`^-fW=4 zB)R*M!n|7*IwJil=Cs5J%0q7-mL2o#dFGYkiiNrTfg5L^K&n%ZfV=xo0I+5fu@w}~ zk4OxWF}Y-pHmTQ7BQLhRcVxE(Aa!Dus{yK7;t?QiwEUMV#u!Ni*u3tnC6buxL-1oR z(svb4h}hyr%b+!30V(E`F@4GdqycX133Cyjavm3VJh22>=!gu4`kdXc zuYZzm~5Olp#06YdZ7y{N`e8Me|NU7cK*IaTq4KO1(be`PBqy>;v#InA5ZU4 zYI0HWn@`_;;M}c7v9Hq5b^AbGML2ZOX~P1_Vhf{E*@%IB`0uDEcrmI!{rSy2n6s8N z$IF@{E#ON@2MKa9?G2ua$T(I6e=lGKaPeIiHh_fD-3I5#Aw1^xp|q4Y9;iG!F*uz< zFog>~|Cm$8lhh%~zZ(jYJ75t7ruljYXS4zHnpC`?+4l8(!1LDWFtnr%qp)@^<2$&< z{b-7KM`;4A(_KuzK8)*+kUEL@OCdIsRPPgd5M5A%41wEzd{i51&foO~hb{w-_d0om z$112LeuT)cwRu8=C>mUyoMHj~ln|{1I0t&_#svRXyr>L=tSFVsY`gZH!khBr7#Y1(H7BT>*MNRoel4la~14xdsh@;O!>ukXt| z`hb=8UWmMT^2RMhACpH_zePI6;yAr|71fN|Yk*Jm(oM;ZsDMsqyGFw48HFtKlz_ol zTj7mxN)&@HAJ=;-Az&3qi0b@v{NmdxckB~!nt6OnvfhR2e$N^1KcBC>5*D5BOLEkM z0a{;FVxIh(s+yAN+Y+ZR^$+z{9cGei!Pg7Wl@H7t3Tp_^_srz$2Va=4 zCydu^p+xqvId(DdToA|f=c+5h+Hbp~VFd*kUc(=B>Ap?{?G+f50c7YCBXytC=i5=v zSR~Q*4(|$(pKwR4Q_*QOqRS@btKJaqyYv!q5XTQ5JX9wRJlI&hg0^qy@ zxYkFl6CF#uYm`Z^o)fY`d>8Z8I1~tr&&YQKQM2w-U2sr4u{z$Ago`~&k&b=OKQf`7 zW)DKwY@Qj86Q!NDK_&ZTunH(dtQD%x3uZy_C!B*b!GrS=wr^8>Jr$$%Q0cT^Syne?Im*_?M{T|bii!V>f?))A1 z6~DiiFQ-0l62K36z7ScV9KsA z>hB<*^Z`y8v0V?;+i)d;`|i!%QmZu$DDUrJylFtgT!H6HuVXe{5>jZN?ijb^iO27* zO7A@C>k(Kx#(Py)p7_x!$!{o;^KpRMfZ5-)DywUkHaUz1Sz;wCaKQwOqSOAupHu-> z;MEd|`RNRf=7zn&No0hmz=R})U%Ec#tH_*KURjoRblL@xWjB63bG%t|3tlI51|xD- zEdH5KQU+O!c`f}&cc;$;wH$Rij;Y%GraPI0vI5u!{{{4iBB}?)Ao24<1tRiIiW+TU z;GxdMDl@%b(_WKQBV!5Fl94i)&$9->U@D+04K)^FdRmi+=}547(!h>Rfb9rFnQke* zp+AU`zx67zv0cV$@Lo7^Ec}#vc`V(+J{5nZ-|FVRNxw#gr8*;CPP|{@%t{Xh_Vx?a z;acM#uV&EPHDt4Ln`4Yz6PSo!zL#NqKMMI=pxk2R_wz9>6KjiK z%|#Sb(F|6ibX6YtS9meKd09D|gW;ZdQYO*Z`6cyjTaSRCb$czJFOcO^;uWn;n!kwS z-QWZOdNi-^Wp2%c_)05R*n3J?<&ESLb{>Bb@x6sFd%Yc?6T!=%d!On>1DR#IVgOM# zD7?vF28SEAZXGr64Q^Oh6j?w*-@n*c3EO3Zt1S=PeXWCgH4)NVs|7aLrSzM6IbMN{ z^nNWk*d#Iez&5&taL7)8CLzR2uR&}lx+M#ryt(q(D{9t|b?0EQwEmTAYLmE6uJbYK zZ_$>dxWwgkPFvbZH2%ihkh8Uz3f(g;A6pFdLfa1?l@z7#z$9pmeSa*2CF4gxFPhMC zNG>wW<{7nz+8=7J#C>JHe$*En!qmaiF?dIF_LROo!?R!3SW;&cGy!C~bgti&9rI)$ ze%%@@?Xo%bQH6tT^V~=?XUde4<-}<|Bs-LSM zxuQfqomVl96W^U#wBW6kjC)JF<}Ea*z83W+yih%(-*%WFULBdPrFV=1hr}zWj}cEw z4yc>oO;T5wMCX#ZW)l#Zow@X zS6BPwv`0X$u5Y*&4`C-CcsW((*hkHju8CQ0#HY4F*)6V5xbxend)?^n?^g zih+ZxJrf%eZr+;p5f}Cppb;*d5e#{;gv??Yel8rem_iJUL#7TMKaDt|e`z>Ayw%bf z|D{OiDkXg7U7}Lj6PasjXhVXDPgFSr42XoeC!^t5#^(4@K(tj!+o9YiSTd_( zJe0TagXiRD(YqB#%7*lqfi82%*M^{F9NPnpE-YO9QNUV%+Fy4^KErZBL4_Oi-`2n# z54$^0lNRm7FR_Q7`L`2ppp8fKIS~ldZvJh*tE`C8|EvmadQUBvwmkW{CmOft(2=YMs|CIbm)-HgGBo(fs{Ij(sTYSKBlBByN>S&F&Z;CInf zQL0ibD4w-+rO}|cT-s+=;chVwptWyf{r!&)luSxkdcVKr zAPGSDG;sSZSkWu}Dh`0R-iq}s5J&}37mi%$uyQFDy@3aCzdms^Pjqt_uLJxZ`jNF(Ru2jL~t8qu@?T7Ht5HbYyk?Zckb`RiUaAp0Kn_hMo36Eb@hMVuBAwO_WMSjX>+ z`}>;u)}YNQmK*=DDN<0?h%Nc%8a&>-py+k_8tQFJ-FT52H@h$w@&qe7LL3MXL{+vR zy&B*o+`9O+h+Z%4V-L=p$ZnQ~7)znFHuB6eBzi@GpP={@{*rM~lS6MVOp|p{j_wco znwQ1!b-W&x&v@V?<^Bw^{;*z$bvSFdpYkqE1(%$uadc#UhiGm&Dm+7B<-Ny67&0Ps z=-fxbtzsgE<}!}IINLo7y4^-T!d?g!Bx-E{w>@OeIuJ3L+DFaN>smb%Q^M1ACq#X7 zq~qS)zhCcyAy9X_bU?En%fZ|r89cvaw?oy630#%)!^qe~^Z3M0V(1Xx2t%h(0p#I^ zEZ7yH{uS@ea~mxThZw$dmFRcBa&XNJ^K9gtFST`Phv%zP-UB)qkEd6=(+>jow-)ah zP&*}d2&1($UP+uFeJj2FnT22x+)D1QTv{>o0Y} zAe-O5o!yA?B|;^>zD?0~?po@LYW9cc%!!zKaKE zCsmR{axP+?4?S<7?B_If*T}*&qR3s${O%Z!;63to^N9Bn@HzX)JT*p9q`mr>Unc1o zC+JY{RlXL%mww_BWhNt=>>ByDXF*JY+w`|V=R_I&m;Cs#esUi z{k=jswpS9g=0P~x8-?)@qBvu|rN(#hal}B)t8b~qHn`iQDO<+p*lC+I} znQ?ug#XR9k#`to^*@_&kcS;{rnyb^>rD!NK^9~HY8m|3a4_46~Z$N53NHjhaLYb0R zrLQ*T=fthupkgmBbL|KBFFdslYJ6TJQSM=#tj#c(z#cpn%{>Dc0M_0?X|V!AU;Or- zbXJ*QXJ)NC=U_o#0a?U^W142R`FmzY+mpE2&tkblqf-zl9Kvc1bDYiIW)LCNArb%{ zZ-(WDQJ{{!c(UYdwIFGll2Stk(o4YiXQ3t?Ut@&A(>j&b?6Ez0+?1}~zSbDdFTB0b zV`r9Y`rK}%5KaCdxm6Q6F54RtZjO8>qmsX$?+u*&@` zv?5p%oT%d(P-~3w&L-{D_jIo^_eekZ!6<>c!t$iy(dDdPAI~Dj_{1-%9D2veqev|? z@4ueVXA4XDJ4X1%A;AuMW~Y>W@^+v>VSA{WBaKB^W_m4o?^l7UcH?0=D)IFk_D#K= z;rb~N_5CK+YWsz+EEVYnz6jm0k4}hct+|;OmB{BkOfy0(@%${XNQ}?MASd$nFtyXd zB$gAEUFeMMRNj+P_jxSySlvKwr2Llr(3yE?zVG^u$5=a0;2wW ziLYvAjQ80@u6%!2Sba!B9IRq4-4%j{R?Jd$_b6`#s}KS^r^ZSIdl)P(1-hT2r`LrX({-Mo7D zI*ESI26huWpR}J~opv~v=8V2>F#4>2hzuz5%0?60_I}WOGGk6azQ)pp@7#+_sB*VI zGfb-0ciLC@=s1t}3!}_kQQ-zYTbxAaoY(l#6|`;KG{v%M>A**q_H+r* zM?M7PX%B;NVU{e!Tp#$9=^UH-tsiIojJM{J6eSm#vWYdOo{XEdD#*sQ2K)DeO1eqj(7 zg7!-S^z{C+Tsz?Df1BlAdXsfn5kCC5sYvJVDbmoVSO8o5k;HplFg;UbCd?oj*M!I(eR!|rbFNBjmHIEUc`}IMrgeEIzQRhN1vI8QB);0Du z50YG3Qf+1s%r_LdZz2x)oRQt|r$D|!&tCD45k}yBpBE;!Y8t+B_<&6+emPv0Qe72b z#j0^@o_1aN9W$)ZulTkWphaRNjFS`*X8`e`fMq2Q7_gS@z>hDP0U(Z!);`3&K!9vZ z!8qRuG?VxD0{}j>l#@pFhcSNZZk#u%xarOEQu)_Cq{qF1SVJBW?EDI1>b@l2#=b+8 zf;r@(ThcjyEWvX>e{fjO>WvW}9KEE3S4h8S z)!7^8d#j(SYQY6-%ky((5miDn|4IW0xfw;6`L9g1q-b#r6w;RB%Jle&;y498xlXjq zlF~H%1u!m4&~Vd>bE#OXB5~0xi{7Rh>&Oj%bK17z!Bx$-U;fafNNDeTv%umOQ?}rK zA$mK-2RI|xwPuNIAU$YpM_IQ`7YrgTX4mclY|4l4dNjS?DWi0ne|vFZTMO>H^{W&{W40fbq06?W#m`L4%WF;x5r6q1wWsoYJ|HJfi@F}ULUVLW z;iOpVK$w`k%W0|wc=E;3(f!Ve7g*l8fZ0Q2!H`$+=egBM18A>o@`5v&>Mf~`S<%{u zh83nGwvXhhkpg$7rNUUaOrMMQKi0%dUZ)sY;N~cMX4K#Q2OrfZ!N=KU{{AgI+E!O* zIUDrZ%*IP&B)^{%kVwu@zc`B0G+ohr&)b2`7`Z>`srP&s5yNNYbARqe;J(lXnBNgR zy|jRGRwkX^jgXE_MAzX7>Yl6thC6`LZwj7zaqmsa9bM|@4UZgxOgV}@Q_;D21VpYP zO|P$YQ)RG`w^Wihrc3A$N5JY8*K7^=?!>U?XJhs`cu26*Son>)8^DP^mB`|EY4)hF ziXc~F8__}vV5E?)TqXQ7i9d&Z)GWZv?B_#AWcBllL<0e(Iz3Mz0E{Xs2!Bt5SJeVH zpA6Pyn=l_J17khXrJMmdLMqk>k07bEHeW^+i%v`ZjO|S#w7w!tT5OpyV8sQWRbV-f zVI%|1oQ9|>GFpjAf_~t5z3G=dX|9jhJWcgBvq4FTEUgIuQ%32=*%MgzfusK^<`%s@ zgV@>+z2&h_KBOlj`=Hv03AdMi9$avB$q6kO zn0H{1y5a}CJWY}KgW5&C0x1%%w>ch^qA9msB+y1-K13h$gXV=Y+d zj37gE_MD-Cn7hi@^I8BU7yV37^i#db`AyCPLFIe{qbgDNCbGVgzaM#MlgR=yHFbYT`R5IZg6a&eJ4j zDMTxyA^|mKH{(eSIl#UOY*`(Hq7)1M?A|q{{`UPG1NW|Z@cH=2DwQJ{mlq?A)||gh z0OOqF#0VCZ7&4@sSm7qRa9fQJ%LgQXfQMPp=d%mxch|n)9!!#Km62tXhn2n@!1WF5 za6i?Jwt4#kBc8k6%37?%(poRbbm621rF{X(P|Ys4_hlgXDd z%Z;+(-7@`Tty9XDU>6yToiA$L@}HeK5u)*}!3q>4 zF6nqpY0! z?&lQ8H&p6NN4{|W8?;5REoY|;O7HLJI+;eQ5#1UvPr(4ArGtT3m|={{YN!T->3k~z zOARV~yn9;o4*l~Es01@+%4qEMR&z$$Y%)!KELk2ChCsV(ale%q%N(c7(p?3TrQ4&U z?gUgCt(7DK8w4X_RO!ib8p92g_&QhPEgvF+kKANa-Z5OHuQx|l4ngVmo-ga5u14~@SJQ%9!X-&Od|jt7kH58K zjwR~E-gY(gm-*Nc~wht9;#X z05k26D9ttOGd)Y-sfy{z^%TZrEEE#!BwQ7}r>gL+u@iiGEbN~$y17)*uwqS9yq46p zTzNO~8ZH=aCb?R3^N*vm*pd{8g6Idaz-@^Z?uG4eE8O||p=aHFkmS9HxCNQnLDrId zv7ukMkyC8Ve&|UG@e&j)4?}L~U{tr*96HZHz7_jL;0ygFb0!37=rzx_dAaUYF5z#U zc(XkmIa(jI4Wn$88J78FfyfODxYhvnu;H?sn)vnFpq|q;FG+B{Jk-6&b{X^3oBu)T_R$AEe=5}w?80k*ROOVBKECs*EI}+NtI%pp6H%#m*EQiQ5 zBfi6Au=-)}-A~wkAiLjC6f0~xmxG=c3H`Uv?{4?sA?6;b28}`$7JwjL{|EAqMtJ5p zDEHq>2#bb0Lxu8lZ*dnNA{CtW86KV()@2ersQ#BEwkQr@(5iVEj&ICi3J#;n&!rN5 zg{z-Vo)E@Og<%-~9bS1+ZjWtbcai#r86t1~cGNzlY=647AV2h9aB$ zk+f(u)@ttUc`VQs*V)rA7PlC!m^y|^vV z0Co0e4lk{6oB9p)Ye$LCqc&YBQ6$;!%E!6bxl(Hlgnw zP3z(Uq04`>?0exO>e%WLljLQX;>&}53QLib^S83?e0k5DxoxNElhd z!zzg3-&YNAALlr7WyIu6)*-hcUu1^kFy;|z3!pJSUa1$nv?-(jhljHhf-2$wZ9_wn zQ1akD(HOt1`lh1v<(;qiT7cLrlG8?G)P!6j?8@DQ-X)b+ z(Q58uh*3i(Wiv>2N%|ZkvR-2M<=Nd1zxqnD#qSF8EKhfl)x(GZqaQhL`3Yi%&ZeB5 zi*FwCb3k>dP)eG5`|vwp*kG3T59Z+`%V2}E4rnVVpOfCp^Pu1XN<5wNZhwq7jKAB* zew0w3vlM?^Y7u+SJfl=s%5Hm`A9n2?HB$ef{q5qytng6Vv8$4+PERd7(ID}OLO;w_ zn>jgt?p1@MxZi*z>_I_a0;d|8tmAlyh$ z7Jx3bb3UxP$3#-&dLHtCEWLJgk_|E+B4-6>DtH$<9TBtFO|6n(5Z4o7KVcW1)nMkP zAm#@Lnz2X>L<#CfxAG@qxv*!Dtq%~~C;KXzo{1!$m$vszgfPd3pMz`s`j9hdXzhR0 zA4k&27mFYjeEYV-qT(K%>4F}``!?UD>PwLa!HZWH<`MGxXmJ6<-Z+aE>bT4cQ%M*s zn1unaj){->b>O$KmS)gtzu7B|5eX)OFGNuuEVITEq$iVj{$|Vf{@xSl%j*R6D-Z;L zs%wHbSBgJ4tm^jb-Fc77|JpfJ*vf`|S~I^2=61uO1_I44UIIMr!Rz`0;+8B4Lt4w*mStM?0${kTn{l3l~YtbtD9o0yBK2% zRJ9A1Q{N+plwVx-I|;VV;fwz4EjSRBbIHFIhX=|K$3M47XKZe}SjFl%SO-(Z^JEzP zmb-?VU>$MXC2iC&%U~zI1ULnjQG0;lpOOhe9kRw}EO=mm+{6p?A4asLn!2|BL*>84 zt#&O~a>6@|o6HMH!F3Z?TEwGJ>GwuoXzggIK@w@U*8_kQET2vo;%K8E$uANZQXVkb zE}${=NF(!sIRUI#S=%N_%u3jCy}OOA+zb6eAsq<)&=`@lN@5IQ4U+w$51O9nK(U_d z6VD(I)G$z)QF^R5)fJl`Vnxj>I~Q7XS71vH-b0ERu(%!K-v0$M}ps#UZ*dv=@kbk*ylyd2)U zhf#Nbn+?lfe0iocX$lq}%hVtODx^R2K>RIYUfH6CsU5j~*2uSvm17|Ixsz`cGCBQC}m zwHX=prGYq0-%pY=G+vG=Vu)z z+dDg!qQUYk9o8a|uN7z>!$*<>wAQ7q7-gRtabV`^K}^K){uzIGkm6grDYFjO9Z_hlH?O^(`k>DZL0;(pIiVa1UgyS1i1sgeeQl;=}2EQ zs*4h=PDu)7KzYcZZ@(}c*1zUJE`w!ryG7e`a%<~&%_qhlueE`THA^~HzK@9bEQREc za25VpPA?QMoJ7M?e=*boH%ndeBQsnjZhd?J=jH%TA+J-1Dej;H?M=TU!E(wmmew8F4u8_0c&aS zJkv}B@LIh3Vi-WbrCkme;SQUKwk}|K=>8O&dRf0>1qXX1bj{rFHN1%QE z1(ewA{sC^@DS3fl+TIh#hSQ5n=bXqnkc|5L;?Tp`#vbC$jcq^>0^Qt@dYO^U-H{x> zEc9g{n5g9U@zgH0mBg1N0>rB`T-L&BHN;9Q5tQoc2-s5pb%dK5NDh?M@@b1^+jR7o z6od^L3JOlQfodbLFCPxrw^6mMGz2~I7YzXE)seEJ@buB&dS4>BBU6KprN)%_(ATS0 z(@qmXs4u;3tz+5%KF)OoEcSv+doalNB}A|JsCWdc!Gyb|`;J{rd&V8(T-WxY2kjNA zRqQ9+GPKjyo;Ik^rt`sISh9F^CX<2bO$56=D14~6{FH|qyV$foUGulghe;K=8URaL zG$@v)q0!4*bTmj5Ir)k^lMY^NtLlQ%h%ryR0}iCH-Q7-+N|O#B$RE{ZBdt=3%D4w) zeEdcVN{~_x`~oluLu>%$gGF(&q+-GlgQ$SSfRN;2q2O>U(ZG@|IjGa(r{icyTXw8l zjsfQ9W>-fza*<)^?Wl>Rc-TVamh?e*+8!*vvz_xG19HoCx!&U%^SP=}+-G-NtkFZH z{St$mZwkT&tRzS%^>s=>)8{4kE!ggKOt|w9x72PcwWC6+Tk?r1KzB|;oF0eD0soPVjjSA7+C(vHos5{gfi{GvQs3jr-wgYy)}RN1SV zyB3x*));rD6bw8X+A!bpSip81qGN9&T8ZHN*~irK+?xi>kKA2!99TC4;!n1F4S$Z4 zf&cW<%Z7l1u=BufV-91`-m%YzADz9id}jTfHLzwZ{}rOjd@A_40->L!AAx9XU;x1v z&fN}77x*S^DK`LMq5yhHOpr6aAYlN}Yb_5_IA0)=Vi=f`F*D&39>S$}Y{KIiDzttzkYZi+#*Ld|gd&({{pdvcqu{@3E}Nwuinl4jy*H4eSr z*T2inlB?y-58qGF3|Q=mGa`A>ZR#`Dwr`?N1U`yY?aiz^-?t_%+>2g4LZFyLv0i%J zu|eX~xv_pqP(4s8pTOhfMeiml2}=*Ex=qXaf^sS!;)>C+J-XbN#8kQr8QPF62r}^x zZcv{E|E$GfXn2HR?=gIXvJV<^qV0D#H7%6mFI=*W9P?YdHqr;AJ0s$hZVdF`#nvxU z?3ZT1_3RG}C?$y!?2&@BxnWA@jk5jiIwgai0|N*!R2bvQ_yb1RN6_t9vlK2Pk`MU` zS^cRQKuFIMPAvS4DNdbq;2Y7%j@hnkXm8fN8>h#B=1`lH>2nw7zF})6A>P!C!+x_F zR0GuCKS+&d6+czjQ~^Ly@I7b6Z{li!$i_Qi9I8EhvhdMP8uYXV+8Q`+-y5D6dTZe- zax1?y#rwUau=7=#MLHswhMod^M;2V1Bt~ZV1NY)IzQiLz;J$%U` zbnX`VH6nKKbb5{EK9x-Mlvb{lWe$527z!m3I6%!`F(#QY`XM0mS^ zvEUg^?-hRoKHnQ5m#~{o`of@YnS|%HOl+s%}C+#q%C7#{$qIrQ&Pl2F`(%kZH& zy_H(d%ORb7{#P>63~#Uep~X7Q`mwik^uhkdAj?LPynpl$h$<^c`#$%9{p(QfZ}_?q znD<2d`x=8dl?89IU2_ZCMn}ADGz#jdftujvWaSW#Mvqn_ueJ>sJ41*@kM0jOp%$At{S720UA(cs{#Fs_FqqZslxC6fs zedthXikb>FV@#WHs2`=k>8u&n*E8n%h^n5haDBIWL;03po%qobf%~6Wp(;`ysK>YZ zqnqI9nUL=V2@*bz;cqMG{mke%;8LpX9}YPZ!D)V}#3R z;p@CKZTLAi50OT4c8fXI9F<25C%I+l37ipjGeklweY)`W2DkS-B~yAd4KRbkgRC3A#Y;4MN6~Nn=0_K_EpenB=xt8} znTS7rqg#R2*NM(uGHRIOU=28*bw299egvgx+}cb@^b-n-plkg?<8I~P$4@G*1ZV9& zfCnQ)Iw=G!srNH2lpydYeLV2Zn-@s)lEgjRYPc+jmkG-;(Cf8qJLYaB$jN}K#_z&y zYw3T>g){pv_Z*5geq!>OcAI1@pv-<7aEM_DqyQexIdxoD2!H@K`Aex0EX5l1jedZO zLfCxkN8Bfg>XVZQ3%KQCmrFPCNNN6hw?kpvowj7vvi2h=zbDB9#4Yn8jm&+Zp%5*2 zQE%tbz-WMfJ0}BhEwKok)_y)dm~CI&y-0y0vU_3gxnL=$G*QdV%E_|oTfuqsPN$_wsJ~gay&bekrk!~rfuD9tnCpj~o z0*zo}R$^9>i;lU8AOx8`XP|D)K@b(Ey!|5m5CXPZ$AKW}6C^lGC4*lB-2&wu^RtK#_uOE2(MwcjflhKr%? zJG)=Br0;%o`l{bC;6K62Wwj-kkHC+%>WU zFvdilwxn)BMi`&y-EfoQ#A{jVPUXNe29%^*Tc|;>`fAOafr>VEfw@)L`iJ|3kw*g9 zE(nnkW&99maE+FYff4J@>g_#708Y}qT?Gd(;8P!@`{J!Ad7^4snwyc6E$*4&ab26StWr$DToDzFn3E+3Z*(CJ)1wK@;cTMBM)R=i05=F^JgK zY5L30AE^Ae^}O}|pe~@%Dd2}SgfSk27yKZr-&Bau$t@XPv23!Nd@X#HQ0JMRNT$FVxH#P6*Bjz5+Bg86MZl<&8rYY2rz~zTA*83&*P-h!BG&xm7VQ zDND}jvl7cQy2QNY7>x`j`Lr3qiU9DI2*S54}uq=7czsnY`X3=nU4<{dE zv}DJeRI}b5;hRDJ?3q7Sx_3U;DgA2oeko}qpKNHA(&ah6lxQbad19xWC`C8`>(|db_Zi!kdm{qnPcvAj>Ls9AB?RTL@vAc@>~Do{j#JR5wSp3JcpvG z0qM6rq~zcf#M&L@nA$7vN;1+KS^%?PP1QY?jkVBS)tAl*#Z(}_s@#Y(o~86lR;dC+ zsBmF}9^`}Z%eMz&bVUj{u?#MGNOoREr~H#Gf(UFCG3!g-$1u7{6BYsJ-+nb3w*cAN zBZRRJ=799V=`x7xSpwAEMDaO08WcWpsbAJ;kWskV3@E}R`EV1C=T3ja4^#?Wi5#`! z(OPDG;IR7bg~{R|E-`BWAV5HYZ%OK~XU>K3W*B!F#PqT0CRS#++j+hV`w9BK*Ilqm z7@>h6DBbtS)W3SMgzYnReZ(3RFxk(%vhsO{2ZlTpZ~>YHXnFIq*FoYjmjy7q7O&Q3 z<4j$CPq6HXu^s3H({a6*rD|b=C#`RSAa2H|NXie_oRSyf!tD<$`cs8w}C(E38#U>M()x#1{2=Z6L^?BU*X??HoRszu(r8&ZbaWpBxh*4VE&P zm2>HYtmvJCFL)=7#NSI1Xyy#toRMeH@ZRKn>fR15gC)B^uTo+*@MyK!u4E0;weEW| z4976;*I|7lQ6885`YN15#&wiC=gCLX#ej*!a9IKEM%Rz1TJmlCJK(DZ_uzlPT$tg6 zTn;MW!ufeKoM3p_U1C5~S0D4hoK1~lx!5T9C}NfPsy9YZjrh=LlkhE)L9%487=U-} zln&$YHDZ$$kSLp@thYEM4A45_6j2XIU8~Kqe2WytU#=^BLhWy|_#7xXcXX+)cCl~x z{FxA&aYdBBx8NP@NyIaMJXbTx9|GgbYWdc(ltRp3>onOLZ5C0Gfm z$M`ksF@{#^D~?X}c{{z3A!?=MJ_`*KOqK0NY12yA@v1VCUp2x3$#kwrRr-%)?-I?^ zf0Idn%g^EbOESsyo-bd_*bTlB%^hb#TIGAR7V^Npcj7R&@`1BfE10han5{BMmJ0nU zngMY&Y(91o%=Sr!PM21`M6kcJf=^|;LwL}iL-=+ybm0@E9(XOGaAPb42t){m)5ol< z$YIoX`2jOZ*|&%bBchOhEUJKX8=yIisi;NT=cu|S7vNG_PBm>cK{Z!+yN^(r^ec@y4WpOJxjqGYkt^KL_l&yOQ7m&^F9<%D9#2G)?Fx4-06m*8M({;@$V%{y zxO~&Us%BI_kb*2DyIB}Z0gRxrB@}k)ffFP;pcaNMPRKj^J%>TSepzXFzJ}4$J5;2B z@T|QEkW{A~y6!P}M#(Wh-1ycfj(1b>Lh^nbtg8*8W0=RYYw8uv?{8>YjGAgH8mR(1qQE*>&C^s%N%(Yy&ZxR{UU_3y`$W z*Mfg(iX3QW!Z}{j0w?+#&qFN!R$8Y#&4B-3**^l z(EZIXq(+1DYFNl#uNqB+9J*pzUh~!I0*0LsQ>0}=)FE|N$5^(zxfwx2#81VAECL?3(S+;nmAU7qr68dHz@0l1e z>iE4@2A1s{+dm)N_w>N$Y(OBRQ?eKU$Fth!uxD5O>hHVimj2L#u#C=R<-hIbAN%~U zgabrk?OKq_Rl)3=lK533c*XBW9VwY@SFdD4RGbR(Z_+w)voaW!tn~Yl=L!(vLgF%c zPWDU-@EK$)*@ZQ!2Sl|`idMPtl^%vdy0|jC+ULs8Z*d^vLVtkOZhKn^?Wj>6?{48Y zu;pF!D>-@SZ}X84LY8`a)5ws1%>f)l;5YB7o=GGsgt;6+Yjz<2Nfrv$(Lziu8_=Xes z13{Ch6{L)#0|m00`dJ9Xo1cEUjIRu(jJWauveHv+f8Fo%4opZgIX>xArNVwe#*a)! zxjTZFq1$Ssih@)|_%D)bZ48vgJAxpM_n1ntr-*re+rHXC0Hg3LYY5p~_n|iFN%WjTwVX&iY@(gvB1=ctht$Iaa_c?3t7C#eY{x_2ysr|6!f~)o1%&i z!ORV4>_&tL1OJU&+DY2{kqUc7JC&}@*jDevm0G-jCIRPyr6O?J2Bo(|LCab}z9q0+ z;RT-j!nYK=n?}RIMa-i>9&KJI7fMwPkjA%tmyRD} ze;Z&#Z4TpPPXgHF@OiFR4s|7nEr8WeV|9fg`$3Jh_J)7ffg+C~VT9ea+*Uo7g9GVb z6C_iof{rrdp_e5%$2ofG7M9xV3xzLP&S|dnYNLjnquCY0i%`tSs+~tw^LM7=XBr?P z2riv6x_cq_A!n(Y$PK$mL9lRC6C@WxuV{9Dz3p#Ri@|1I0(yln6C3_^l1pzxdAL!fv06-@F2SNRc z_l|1l3o%|EEX=-$eU-S-(vsZJ+3N|o$7CdO{B)N`+NvCmnWXZv&8#P6uVSyRC8G$J z*u_X$ojNh&?2sNgj74lbZtJmUol0STq<@T5fD`UFl%jBpn?=JH6G)8uKE$JP$7}b7 z%&)9kbH!H}0iJk^Exgnq5|DT`_npij}`|Ga+?Cqnr0I?CY}J+EOG z%*));x;R>Nq=W`@^V@3h)tRT3dT#$1+VFbf>0_f=#p4=8wac92rQwC^_C)Wubq zbcE+Em>`BeYZz?uZm+VB>vanE_w_3U4f)7KpSjyjn*Pg*l*v5= zslELeNHR=oi+6Rh=SGN(lDIuxJ5{=OHA(Nai#pgt(!nqm!22LK;{9`pV(_UD{{RWd zT2{4(cjeVw#gwodTdpbsD|b`_XKN-O~E;;&N07=BgrB}f&Kejtjp42k*PsrzCv}G%7Au~@yQAm8$S|syLIVX4g z<}K9rV0Y?hDU*G{76R+OFSE_DROx@DQ z;^{H&&2BLxI@B|NVLb&7IXipQ0EJl-$Pr^W9n|!S5^xg8GyGU1rlmEN5$vZqmgy6n zJmdAXmX_$Q;Jd9EGFR-{_?a#WW>|N*kt>7Lh!d-8fPN>3e7& z5N6dS-?Px3qzCBx%fQ%#G8d!m;|FA>!;spqCCP_;%nx!s)$-XstBq}*1V5>gKoooF zq-T`M7&~VzV#v%IvXX3EUodP(#=vzM1`zseMFY9+c>XUw8IPqOl%Rr_z|E1;vY$>1 zWaH@+%13Brod;E*CykLbh9-HGaZ#yaMPs|Kd|!Po*R>?oIVZ?taP3|8n|6vnp5`$L zL@0{{Q;4S+vr)hnZ0Pd{4#>SUCL@$ZhHIJ}-F{T2zPU%^Hv}+iF0y3dd~Dn7bDl$v z35(kpi9EX%o@2`6FhY*cuiRe}mGagHexh*pM5nq^LT2^Ep8}xAQL6ZlcP9eaY%sPA0o2QHBY3? z*Y&u~G3+1}`ljAI#s}65RsUJzI#pd@B@_-Ih1=MPKr?DhgjY856RoIEy={XFTuDYg z-xAW+V9-J?fRl8eei=|?2BTOg&nTrc&Lez&>gPJo{=;V(Q@hs8QNLg7%aVewQz~fVa4$f5^-^>uqHJM(1{FFx??3d z+=DqmpP^Mjkx5rn=AYOMq2#t|qmcQeqj&7A zzS^ml5>J)z-!g@@F&?Msko+rJUSKL!T4A)u;wggw<+lM{2|-ThIMP*Z`t>1aTvE-@F%|Il*AU&h%@N{Cy|ktX$s#u z$I*VE{6GMXizMl-_7Q|YOh8}=XUz}D8rlI%(Cb1CX+*OFL|4(Q-Uy{cOY_yerAe=g zF!ni1wd%Mq4qXz>$*BrT=z!3X~ckmB7feoMS_m0P9H09%plXM3B@9o z^p5%Xrb$-LXqRgu(O7nud%Uz@>1Ij(_HmbbrPglt83!2geaF ztFV9{#MJt!si9GhRiZ>_!t41wFc$CG9|QlQ!=T-mIhG*SOT@VN63X9xGXY4~T+wW* z?WwUG?$BDXBFMOWhiYh!4@PL7bI4^bnddbRFQA!{hX5LOV!3EJqj9O2ZEEY;3Z*cW za?2|CsuQIo9+*$50H^>)@Y+@F)!;JCox2svujz#^h&pUdux^kE-r~>g!pN_`2Epw>S|V zlfNv}BjrT-tw<(ZvMX;LCB{h#q~YFB#<}~}UA9=mYuCVPk<&O zJ12O%gYk@L|5;lyT1f%j!M`)eNo>lY`(2k5R8!6^VY7N|gi-WD-%a2JA>otz>*-cbWra4R8%|1!GT( zXMZto5bzD|!Le?ZwsT!MhBl$UI6f|AxqLCP@uW zbMsJhx@#B0x(HfLbo%W{8Yu>yLAz$(Xd*?=u#){^yMfogEeyd-?uT5pyyKcaw(=pC zHrb|gOBmVK=PbL~I)oZ*JyQ67Gk*qMV+gP&&j=3~TBEyGSc;}FjlkNt3)G%TU1)(O zD`qh-ky0G4)9>~yR(YtnAkEH?i+86C% zcV9+Kuow_K6Dq{^MDl+_0HM&8W?KR1u;ui889ImJQys=k3S)dn-jaK}<|n>+h}{~y zQ*rGpL$GD4k;^f*ZvcAlSW5na!Hn}&ht59g!7$U~W(+(uzkfR+7?!>Bv5D}_m)d2y zG+T~sP~sKO^n6Mv(LcR@pt*@O;colpCUNfZcm#R7_K^hAq;tm>X2^jQ#t+$2r_bDv zIH7#Ff{X!{NBfk=5IH=(&)WW5;4e}2E9wipbK0B4Cc_{XcjA~gZN}qbwFP-7TV6jk zI??-$UQ1-n5aR4J{u$2Ow(_~~^Jm5Q_gPei6flVz&)4)YHIko}+xojj7wHc_+{`_t z)#9@<5Qx=*Kenj(!xzyyY8vXl94R$wgHM#+TG$?VDNXryxfi9Zp;kI3>s_Fv3C=mO zES0>38`YD4pW`PP`?=W}^RHOx(3kxp4++I2D_+)cG8EHz&qvz3pG29F^g@aj&16{aZZK#;^zap74Pv-Jm3aMK%@8ra|>9PH{8Y8=r>^{S4J(p z1#|!;bawiognHXKT}gWpjF#y&SyuinnWMw`@B&)77#FEi0k(k$Ku~+@vy9KEgTfI# zjEfjwZF;@FJ=?5vC7Q3P&?G@S?FX}wFQ;1A;q{i$kRSX}j(p<`-%N)h+JSD>$^qd) zJ5T9t|A{MD7(z8cXP(QnO7LcieWhR4JFa{C*u9=>&*cL3U^xv4-IBN4ZvB#j^jzqn zBuU#=7*n5v*He)E76p_i$#YABYHva6;N}d3Zr|Cp95!&c64VlVDXcugEkU54;!8S$ z`8FSHLS~l7(AHApb6N0Q@&X>ctgYHm)LxKW)|TApH&yo}4*vy4oMOXmrr9rPN+pO| zhe8)$Tgr0u2exeOHYMAfP8JB$kHD3)$FMpVzq|{Mtnq2T8~nts->IqxAU=tP%>_5e z+BOGNAbX(AloZlr{E7mdkj%3kL3L*#1Bq#oz7YPn^z&7@wN!<6=o%UpQ-*k`u{I7c zp^Yz`MWPcj(Hm7SkY~YJ3xu@i`A>e6U~GHAt`q)G$!R}6!k2Q;skKFlmP>M+nV3p~ z5mxi{fC!M^%q)*$AV-7a&DP!22F@&&@r{%y`qN?<(>rY~c`wnmSdP}G1gV%D@S87N z68q}8fZC;G@THCQYj#~cs#JQK@8g@!H`5AVrDI-=#kXoAVvfjE*c*V8VUndKJs^J% z#;u8tDvFh7GV@$;P*?SZV*{wo7E|xu%e@;?P=@;Z;zQKb8GLPO+aAM2>4^ll9G#ZiJ^^ysBo`?#aY zsZf-0;2@S=lRZ1$Z?3I3}!fl#nK7& zwqXzHA)z5}9W6h_c4JTAZ9BG5+T_?Gs$V^<1w%ql+adf7i!4OG5|X@$oB$O->c8k7 z@lT=vuh(6faKB{yXs0FUhNQ1qo6^-%PVh)4@6tmixF;cqzNH3;C@Z530~QQ8 zt+-suSPf=&J4XBroXr2#6Q1(gZRVUz=tv+3FHK-AYF5lP6hX&|IVgx+tcTs96&bF* zeCLVs(9X1AK$jO0lvo1LXVN^JZj1b9-B-6|Lql^YndL;vQNTwv$F(d^^sE@Q5Y?)m z94K4U8^IfL%wdQ+;QG}W+{pUSw~^k;%c+3m8U*tBin5pe|HJ51lO{8zUv3o#f=55l;~F{ z9b_~I(W$q#z8sNGmfV?^lW)qe4mtvCun-pU9t!4J`=LeoswFX56vMn}K+aD5ekOL^ zhBmeD2mwRTJQmq>AV-1psoRDYX(D)4IC@nRCmS9ZVSI(?Nk?+PQgw?0saY>`s;g9$ zYd6!kiRT(blDqLn%ft?kMEC2?j=YYcpnEb~u49=jP=&WORz3OFvdbwZcn_isQ}pIs zc^TF4!9^^wfV4pu4oEY3c7MVhQ4h!IAck(MY~%NSv@XFuF~uwSJkdV5$$UrQWu8@Q zag7DAFO=DIxrmQY;4h`Aj%H))f`E23#-r~*Yhcv9hp=r%!sERjEgdGKv_s_-Rnc{I zU9`Kbh`r|ky$?35_v)>Y@rF`uSbMBAtinp29at*llmCR1e=XGCpeTl%;dEm;E-nwW*o;L$x{HM+U zVN{Q25kJJ)(K8q=LL+o3@R*?HSZ#bTdQc_Qew$x4MJxZFs6&*K*|2cp(L;T(|3M3U!<(t^|k)5)akFwW5(P5IuT@k=Ix-7~6AsW@g<$$+}tIJZ?> zeMJs<5iBs>IxcxNaA{cC9J~q1+GP*+8zd^Abck(dak&gLThOUo{QJ_6Dtc4BA18mDG*xtpycP(?I9% z=!2CXLlm^;f)9Sa&QeJ8WXv4I+8*wrl>N&wJwNxovK}$VN%F~l#X>)$9Cad3+zgZ) zUCv?hn$wr8l)=(kHi0#X{ix$5I)id;6o{bP{mg$aA6+0QsrLtU%N2}ND@){R7hEp9 zwcUzF;T2QA`^cEj$-V)y17$3Ox0xDD4ezG0*h@bK6w6QSL7Y(IG^GEeP#k++BB(aS z<^7IKc+m-XUDroVsd30wN~SH9VkQbSS^CHgz9gfzBtBRdXKyZta2`_F$i?U%qcD!z zgqE2OH(sK5G&JtjO(Q<{h>XL2EQ)f%o6~kPLt#c_O1?~QSB#ML_emJQO|BgwJ*V0; zfwY*KKm&lR9@Mmxn}JZ$>3O^EFX8^a^J5kmeIHnZ-^6x|WdSM~9aoC1Ll);s1lWsV zjE*$!dXR)h?q8l_Ep5SCRUEXe@Hc?3E_{oMTPVRgw~F*f$3~Td zW^7EIRQhXRvYSmk;kw15vaHJ2OOyI=zE!sAi10mN@4GUWIn_eh5?AAup zbi>>&UT`DK(9rVfL_I1sF&{4l20CYkpI%|>2wg!cR!s(dSWv$2(ZiFTOyIcpLk`&R zI2uF`%=8ntH}+*Rks)-*!ejSjA>lzWtOuKNMA&V%U$}W)p zWD%}mID3~Pzuc$LkjzyRoU%6ZAn~vBGzT|uoVYj##^=p>GfQD~8F$vgvdwmE0Yu*K z_>|6cGN?+-8jH1Pm4XDX=5aDyf?uv*{CB-{`?XK6^W#Y(`Iq2XEu=iDV(Bat^E zLn>zPo-o9`Vmg;?{l_+X!6i9OvIIEh4Os&1agSb?_}2QUbjbMh@akI*$NYU1uz*0< z3KN*+6C;4;Oo_h;n#@HlRq)q2Dn2h+x`-)x=$i{X3O-4sD}G|#I!p}|#cFC;iegeR zh;@2l?iT?X;QfBCybsQNA1D4p8Twhw?tTa*SAi}`(3v89wDgjMTHb@d0(na$Fz}D! z)xT#_V!GsbPKq!N5_uSx2hB*Z5Vp7Hd^0&Im0E!8(`fe?y2D_}4M-x+NLZ*@6RMj2 zYrYS@y%Em&R}ugG{v2GhBAV-+lb6>9hLJzOt{6=*Oq=pWn+^|NU?O?C>Ao zUujX-Kfl|qO}@XnJ_N=58SD4gG>=`C{QUk~`g{AA;747w2?+b2-_Z%3{!3bRMf>x+ zDduGSxBT}}U7TM(zmb1S|9?L}wj%zF?G(&o*iLCTHfLMmJQn-kuYbVj=laJ-%X9z7 zf12q$b6SP`tE7l81^%mqPhbmnY%X(lXSDg(vhzTaCJ4StTFyZW!;vs&Hw(_q>Iz`-(UXi-&Xqu|12Fi~XVU*3_dl;;oZ__J?tjGl z_x1ee)&1>12E6&*mUvi;aq0j5*FN5s`uZ>MKSA%`Kc4^V8|+V%zhr;^tM4^O{SEmO5c-cJP5(uGFaO)&z54uP!hfIVJ^k+!|4(V!m+rs(AOD#Bzy5o+ z{txIMkAGYC|47O|Q~%p?i2M`sKjo07{t5f<*~9)*60v_j(Bxm#cgVjTu>XB2#r|JS zDfT~7TKwbje@`j=|5`%-QIv14p#Ml5^l#7q8w-;9&ks32mI3HU;i>K`I;|B&aBg$VmsdI@!#+3-zKNu7JG5|&D4AR1El}0 zTJqxWf6d}8{%`-75S)hc|C7XPPGJ93`>bJ~kRp^L^FDOPt9Y+`&x$`!BK%=~f3C;d zepi1^J|Qawq4u7k;Ggl}DMIz4$nSZ{@EvdYHZ~X+ohN7O_~G86!9wn6M>k2PJrMV3 z(p?_R&u7{88&>PO)~<{l*zd|Z-v8SAfG~HZc{bzueAtf6_%c@Wsc)&_R;Ja?6MG&# zeloLwXpuzc;R1cZ_ano?c_*zUJf8&`JbWhOf&kC7ZSUVc9)0$lJHlnsjn0Y}Neg zuBDUFwL?(<3yr{!iyDpWi4S1jZ!A5oGavqmeRu!Jr2APig17L2;`Fdh_voEQs6L(9 z>=EIktq1zDna)YEsYmt`w}2=j_?ACRC#x#mdHl)IOvX)LL#t0Ohxj8Sh_<7MGv}sx zwRxXc@!?>a2uy1iA|+}t`R>ulx$6pf*FeDTo*^7lOJ#vKb5AaT$5Pt23)dd<-Nd31 z3wS&BYP6$>H|ivPblMqP%HG@#)_dgR9Jrz39DnmzB1_a)+!!3B7Xp6cTW@?4-0^13 zU{ibMOiK8nYPxH+@9bd$jupm|w_0HA0t}yjEO@k!7a1}lJ{ZdSbSSoEFcbYZ_A}p` zKSEdW@D|n{88-gyif5t<6$z-7^(1zLOyu~v&u};VFY_sN@1~7R( zEqMZS3&-U&r{_6tVcCttCH>q!=0V0ZqKMy0u(3>4G1T={6Ylv6dZ&petd~p+ydPRFsVrw27 z24GgUxuXKE`#C)!vOLv$dvs=%;EG`J?aEaVvkP*tiQA|j4!qFA@tHZ9jo^o(Wt`iY zCW#v7ec)1=!ZR%(H6Min)^>Ha3MI=s>n)pi$Gu69E-E$IrQK=dn_05?x347&FbDV- z+M)zTa$m1+Z)N;fxuy`%yBhmP%j?HDPELh+%y$-ZWc)6 zXy)b!AcyDv)avzA+5+s8@Rg2-mM8;RM(n-EQT<%%+#Nk&6Cb^;KMC>q@R~zIPKoyb zFXtu*;;;Z$Q4=R(&6Emz;*Ies^Bqwa5^f>XE6$p+ir#qmh^ z`r4CZ407i_m^Cvy$1Dhh%7Y}mZ#Zp%vJ`DeF*S*^krCyS;WJAV1_FEMPuHAfUi^9K zMjgIJJ`Z0)39t=mY=F4ZfYRkb*fb9RCj1r^nX$(-vE(eL_*t&BennoX zb423#3D4OEh5IY+dYVMW`UGjnjR*4^Handfsh$pla1%nsKee$PV)+#N^N)GRKl3O` zEh4IM{+UDY)@8K~r8d|TOhr35s@B%0W~=~O$Hh@PZ|UV1c0G;k*c|;+7q{@M=v-dP z!={ULz6M)!p`Qlq>W-gi^;=boKJ%qFr`%(K0YcXWtstI@Zusng`u;kHJEL<#09Pg# zjaKu=-P?Ut<4~0cHU*v&0N|HB4Lc3rf?&s6~GoyYo(UG z+HqVR1V5&68b*<-TMFtEQO}-@M08HdIg zU$_ffWHNWKi-kRW3Yn?iR^@$B9WgfcCvxpTNr1P( z$5F!unK80;#36x80su|EI18i5mN-J?eyM-e$e<@kX3HiI4GU3pkI~?bZUzSYDh1Xo z(oo|ywsbUYGMRJ{z5jMR7n1I&^Qj6yVmLW^>d`0$@PK(Z(>Hv|7CJD}c(vP?)Ld|w zH1fMtK;dksExqak_^r#;$rQj-ApSUqyuUR{?)p$1egGOY$10TL7 zE&)Hob3W+hmXG=EaJs`i@GK5+g~DU*M?x}H?jfY`SZnKksYd68hrO!76t@}fZ`unF zQZV)htu&JyW%oEIKHKexNR?O}OoM2U5PPI(8KY}NQu2Xk6Z!TD+;2780FAX9SN(2l zq#4TAFk^gqV(sNDh$JjDHm-x^Kt^?%Mobo&;)I+C(>C!Q*ED3_hj7qar zJ#eX`Bqfe}cP|Z5HDpe`c8ZE(&^#e#*Vk-E8(#%b=6Ns*p*j=F#>c#78}Uh9fPppe zUZRj&F2ZnB*A2C{Ve2kX5=PK6h3N-DiQv2ublLSV98fs_4mNa13{B!o-QT=zar3iMJFr&L5Oe#|E9%Zq%HzH=dXFuXX31)Dt+ zs$7Xqp{9h>{bG1rdy0%ApdLP_foBKtC$ApT@6R}E6KWS*EkWDFu6LDMBXA+1#^vH1 zviXW#5n$yCa59P1KDZr%w)r|tBtEK_U@h&3NW$@WC!8(nQ<%d_p-usQ|7Zd(=Qa_3 zxGTzG0^0x<0Vb4kX>_Cx?6sRav*C}sR}Iu10MY2rCB0lrZK9EQmxn{(YQ2VFOFpN*?Cz6MjCOc z_(Fez0)M><+vcBvp9MJUi9Ga@HOQK9dDnXPGpvFj!4BLS8CUsY7FL)bVGbmfyv*WK z=SN``dVYQ;&ZGt(z{2poBV%%+7)q~&AmA2o_J_(Qz{{Qt29`kFUs+L~7_}^R9e3|t zXop%fAc;Q|IF=?MZ#BD6u*Q950~j}drLd>h%>s0oGc~qgHS~{MYk>OJBV1AyX4>6^ zO;evdW(*+1oeF)sjOFi5JS#kItE0ZZz~s|h2yX}rEs!O9zDR=!He^GtvmZQ`#S)kk zo()Ftq(FXKL~Yg;a>VuAu-i3l(6+#Z=HbA#H*7_{pR0iafCOrr@Q(oHE!d1Dm%=sU z7D2_e?hXqVx=0#j0Z(aoT3QUabzMK&Eu~wEFEHOjuXx)V>rsmoWQO_;Cc6$tVn-ac z{h7z9SVR3dI81!t*Jl_VTDVx;ur~CP`;IHAzCXrRgF3~(z4$a!xA)Gy(%GOe0frf? z0GgsH#d<925hb#l*<;ay>wo4p%4Rq`w_RrYdi`INJ{L#wpU>%V?CF>roPS)_Y;1!9 zE2}8hU*C4uPv98(!VJyRt24%Mzl=?Ie(F#NKhK1nkrq%|LuR2sf>w__M!I=$_7*s8 z7Cpv+;EZ#{6Z%hln&nGG!giolX%}X+$LL{2^hk~JurV&ZiQBhDA(=0GN>>_H4oDyQ z%?JtGSJ8>X2$%3m>j$jWFY`Yjxw2TEB~&gRKR0|;#fz&{)x4{eK44)|@AO2aXV<-a z(UAZ0Syn@RZtCg=aD({hN5%>yp-Ffsx|JxB4Pm`)d3fAw3gDY;+JioHYDx2ndY)q& zsrB4)UGGtG63YM+X17qP#}w0_@}((&0`rvG(PK&i^ks1XQtbdo{W3p_oDV=PalhcF zHsMCdAIc_24flgL5G5c>^y;GPqz~$<@}o?uA1`^dUhzv}yQF}aD>nz@;%}B1z-9VG zfPld;I#3diCaZx1G!*b1j3s4W??$bM|vqbY=> z*_L!W=a?V8yk&Iudcc~|>?aY!x$Tf`5aIABrU?%E;>BB|sk>+m0J($-r8MM{>(K(^ zpW_Ua3qes8V1O@x@@5XaXL+%nAxR(hdF@zE@8tB$z+J3jG_~9=KRkk(&V}qyY zcQ!;xF1=ULT%1fmhR`79*PWDU*B%B0gRjpqlhioobdgGeXL`VknjWF{7}vIu4CVSQ zsRCgoaffLTDb<`(w!~Qn40!p*ga-2YrpGU17!E-*Xcd;13*hxS%(z1|TPd%WwFUUN1-=047Y`>cgxR}m3>@J)!(?5GR+ z^!G#tYckY1mVj}u+0F+v?KxuxNaq;R3ky0u1-L zTO9GORy2-s7fzrL+N{R5hnl#c!*4?m66o*6tvB$dW(aFR@k?pnB_zwQ2tJ~?dTtpA%2HvRwC7ohrIK;>H%TEc zZfwS?>b{~XFziRz468o-}KfDczwEVi!{g%Ao&q;7=daL9w^4t5u8q3_wZXM!+zZP z;!Q-jcT`PUm!o7UC<1W1P%J`khpVmgSx&FIIn;*weX7vfluxWY< zWCHXDXkz@EKp?a2fvbV?*fO7oU9-;$_R2CtN|&PpiYk{L5QV%2MHe`1{0{(>)mJsm z+M;md_m*~R1XH$<8wZl~zF#Td6qOkpS2Ac?s?|qwxFKg()@!aFiy~S<%}xAy^-reK zR}k3kZisW;P(2xMy(jOh>1~1S*57$NjXbZJ4sa|2r33!OV&8(e7JaRtX#w!7QHtRE z;aF;xpGIOFQ@UOJG+gXMW@vKlQ(h#{^8iy;ly8xM{i}y@>(G?%L>`?Pq%H|gsF}S6 z@qVh)gUe&4L43U^X0YD6|4F3qmEd27dq)37s9S@LqyToWp-8YFdXN=KvI%B4l9}e2 z*5WwJIWNky$f7$hQq%jT#>j+eXun)x6hE56J_@nZ6HAWF&7J^*8m{0(TS!%5@O%#Z z#j>3HZmUp_VFctXIPW``GhxsTr-jCyJ6-I$_DtMa8Tl! zAEJL*5Cd3&0$Mc0!W9h6czL0_$P2?a#O`Jg8bcz4yPeY{Vy1=w4%#OBi<2RTqQ{@T z)_a1!mlbYaX(7DqWXeS@CfC)lS)4W+P%t{u0>0NO{i_v0mI>=Mj7{T8D;R`qt52j)72j$D`%;F19;q;190lHtSjYJw#&_p+sVm!K>86Iq?RI zbRz6-!Q&*bEJYhgBgxJ`TOmQ0L3gVwF7*S95VF~mwx_w+jXp8Hc+`mQ#8JNPnGTDy zS;1V=L&Bkfr|IvCg-IVT8of)kdq%zocqbEdbTBF0eJ^+4tiBn;Ib4O)XZYOotXH#z zN@x!yrlz*>&&JV;WO5@ZbqUj2A!ZD<91PjDg@+Oe^EA=QC5Ka91*ZfFR(CCiHDQR0 z*50NVUC;?MnUz7M1Q25|=4WJqx1dr?B_S7vU%gZsIYmuJ?}o(<(1rkl{5L>xYUp+| zdHu<7=v{(JVkxEcPfgdKm!Ibz2}{0~4XW>&%deOz!#c_wFuSMS4BC9=*v30*ITH%>tEmrY?~$nz-j5F< zg)0DBbRri?Q2f=tpX-^JtgMQH49%Vj!pBsjg{#R54PHXR zD-^-S0UPLxU|R|wZOc6z-=ial!f(lg1X2$}A?3zmm~ese3<<&#!%_~H>iBz=e%=C_ zl%B=_C(d11qba0%%`q)%JR{Mv8+(>pxQsQ#rsUyRELnP=ZpB^m&;84jcuwvmzJ~xl zVDe?lj;zNDvmDW6;QM0CFWb>X*|!j;ZM!(kvxS>{79!Z_)_IZ-O_RI_nTKl*JCeTny9TYSy@Ar3 zNKA?#=fhzNgMWxTA&Qn+eS7^ZqO9#1qM8pcA8BD2q=Pm{f}Vv6KHE%L{6T-sG+5fB z06riYNI8xA$<=#Z?vQkRW!o$kE-1V$eI_8NBKebL-ymk%pc=j+uTja2f)1;hQ8myw zP?#8@s!tz$zR1$+DE>@|*p>;5?;jJ(z` zhQvF^06q1>OeI1+puL=@o{+r%GGv+!C~HSVC(3alg9X2NboaYl2rD|ypZb0xg%9tU z{y_6FXd7j0U|;9WPG6S-k{Fz1L*xgti=xQ4I>GJtq5y!LN_oBF*^cA4=TY$**$l+X zWW|v)C_vy%zlj~xderDq*xW)sm<_YrqY0&$0h{0@&<{8dC3ey_4&=9@8@}>Ye|@zS z?`@H5RJrBT#|F}`L&%D>aZv!g!uYYam~O@iY`nPj4Znu zr52Urm<1*z4>AxytRUqFK|QeLYbE`0QTCd!ZIAtOQ(^ggzzsOAb%{@lA|G>CHnB^b zRvBL0(Km_O4hvjDT9v&j9w!_>4!Z!kWWl%v&`0VPe`197QBiL!jiPN|6&TkWIS>+o z1A~-Yxp9DpsN2UPBNWFt%aomYpie1?bYw{~dgVvH{uXs9>nA$USvU&}@Kc0>y6O`} zL09zZz#9ASL*vl8=C8>$ZrMuxlP2eZdK7oH^|y9tNRrYmmHmCv?CZt;4ljy5Q^;j} z{fPy9Tri@ftk;I;POlAv{dZm2XFmpk!AS@~l^-mHBCcap17gqo%6ooUWew~=8XkKm zqZlKpxIjEVW|4iJIFgH?9j*fg?&`alo0!w|q0GxFaJdHhKM=w9n&`&!CoC0-_-v0H zE>#=6^U0tj!#Rx5Yl6KI>vwmOj3Bi$fl9=lTO7nsE8>GzcW&v*Yyq zW5vU$(kvUXOIU+wqq0~tbqQt z3tGh6lmaSYC`De;ZJaO<3D=(x#5Q8f@nZtP^(2Z{Tu&%hN&=0#)`{d5_({{i{vmsl zBUp`1>?vB!$zTlhYE14-xCav)T}_IH78PY8FY4XDr>%X8K&A+Q;n*qo5F~3sM2A}m zpI!mbxSx{GJum%-PYv=D9*2l&q!qccM(N+pp(L*a&e0uhhZf-6*(Zlj3_iG-%>agu zf?(ox4 z10X0Brth=Ctlyl*=-^JiM-ugYosp2-=InQt%v1?d!cPdfP}{TIxNmt{uVg#|-K5-! zo~P$6n7YAo8c^L`(>DWc$_Di>@?HP4p~V??Lq@V_hDk?}7-oHg$*JVvCVgE8R15^D z+AqQ7e0R}>wMyt3zZLzqKF*JnYNj4PBNi{%p33d(gKIIxK}*<_0-9Ksx)%q1hHrU@R!&+}x! zT@kVv_vy4~0zE3>Xy%n0QkC>&){EiFQ$t~1y(VD|gur3ZpIUL#m*?2~*BW<3#YX4# ze3@4*e90fz46IjYMH%}ppiq#uvpiQ#3w1T{gv_ zlSX0Aid1FoU^CKLm#a#{P36*7XNUDX-Q=F9izDJMzmjSY53;$9qF}4`+P^J zH7rO*B+d!FK5D1qy=`}C3FhJBAxC-U%oO>+;b?jc_YvEb&`oS_XH1ZpX?SASy#7N| zNo2LMyzP7i)fAOASpk*wYMX@6j1i|nMAA_;QT6j zl4tBOMa}4)2YKqK5NL@abd9P`RdDwaCbwbvU@)wv$F0!FfCt%Hn~-tYw8ugz=}ZnU z$Vx<+FY6abEMk*~6kc#Q{iHJT`d^>^WHYobF>`459xn5$Sx)3ty#^!N^5?q~T+&pF zf+fCZ!lqzB@frXX2!A35Sn*qv#Y0i@35t81kazGS(a<990LPHkTnw28(Hn!=)FY@D zfv-J7IZblS7|)AgmBa(}0IS);0UwmC9(%XKk1y@8*w`*OG2}2{4qnL*Co9UmC=dBZ zWsW|R2#I(%s^98oSEGqiH{>z+$wZ-EJQ4=Y8`LB2V}h$hMA!`tf0WVD>Y5Oh7y~-g zzrIZ2N!_I3J@;c>EJGli24~N=8*)LcFABD%0lJ6g76ksW%3}9@A24a~Qh^tYDou25 z22}V#s48#L>8{VqI~{JuapjgeMrj?w%4<%;JMlf-kCvhg?x!);cC*u|*pQq#P*#4JEcL>bwJonQEr!9z5@VAl z2{khMnq;J0rE`DjbL$N_hnSWaeP1G%E}MA9im&eWK_ki5&Rrm6+sSz8-jcLBBKeqj zr;^n+0(RbE9gxR?33POk^ji$ZSp#*Ep;B)cjocm@`BV>mX0+-5I5EKV&e!#q(4+cB zTArMav0ip60c~3JKuBImRhmR@EPSgPlq11gsm++0_HP$F0huSK=c;z;jmdBBE*+2#x(rK?W zdD-pQBUK)N8BJjs(Qz{XyiZT+lNwS8W+Z|%7=+yX7CL}g2bV7Tkj1>xa765$S8wAE z;1=c~&-cnT%#Tq~TbmneH`HVTMa3jbWdELqg8E0Mn4f)Kv)<~M`~wpGNo<&dnSeFs zK%|qD-hjK6b4>F2^BV%le6H&i3S%wl7e)!Amu;dy+H-WAoP_ARrYjD8|urR@_ zq+^nst!Y)2;J0qnTl{e*LQ!xJgMl|LPEX&DmXeukBrMks#=h+tybwZ~_A=VQupzU_ zZL2kzQoWab9?fRX^+?QShnn=#C3K77#j?Q9mKQe);4FkTD@~$-1075I$OnptqnszC zz2^h=n`WXD=d=({5G;UjdGpaNI55-U9K7nGlsD(b1#o1wVypR%pd_Fz@xjw&3nZ`Pg5J|~t zLiaIT#XnTv=GzHeO?xR+#M?#N8JY_dS|>GP|TOS4`e;4X7B8-Ptq1N#z#wtqd|WLN;(Q zz7>?c6hk)eRI7JWf>dXdQ(>Nh7(}1nE2c;OrJFw1mtz;T5&!A;we;*K!PQprhZGZh zWKCNstWD<}B0-M~D;OIyyKP*Q&eRsU6!0(Ai#S3~dEUMIXszVs4BI zv{1l#^4Jtd(l|64!=-d^baT8;*hWq=k6Y_#4h?F#KKF_hZ(-dLE_GXCt^70DU8XLL zBSW})-b_^HNo9OGcd*`854%|uHA@jK5Fe!dE%}siH7-y_qwa3*6X8etxZY2HYe;9y zeF^Dy>1F_7B^uzQuY{dU0HJOu$QkdEc*MzwI@GGX?Oc z#cq!%7|jfAvB3nt%XFc5DXJE{g5}c)pRj1hhqZ)m5!et$MKJKet2uWKP_1^?P8kGx zcIOB&E-aE-#YxfrJ%bFb{i@M5Facron?O8JaEIM(z`^G54y;9me{W{2^%zc>6R+sLNqW zyiOxAZhE|l7;vK8)x;hH`5Sa_ zKO(gChvGV)V0!>kKiVaJg+@GVe8Nl-vBC6==cEj@48bxx4ftmdANJ#;7N6{Uc^jx| zlvtyF2tF)CQ|f_wB;`pDMm%4JImahaQflfsMm-XP917U< zlk1p^zv9HPl++lk?7I~DH<$7vr#jRqKFcpWX%I||1_$Co16auTz*zI!OUIDVj=?uZ z=sp>a4VOms6EK&r_8HP10wJw6Z;el$Yj{8q0i8_{PGb=d1J`j89z;- z_;OfnDbB=fRq||}lCm}oL65i^Jvb&^6sr7BmMsTL^8bV=_ukd zcRQo|78B=qFAumcc}JG}){XDB%MY@bjR2_JVW!>eh@^qu2MH+91DzwRDf>cqC;%tK zx{K0Mlgt22?gai-u#;4MnVgoLt0q!m>RR{LIFC3qrZBCVDMfD z&UPWr!rIcEbJe&6(vU=KWClm6WbTY|oN6DS}1I+EzXUs`Ln_ zCh-W-YiL|z06bim)$QvNh#G5Mahr=}dIZVFPm$lQWm>W6+%}4XTGFLlbWe2b6L>LL z0O?^GE0D)8)aS5@QEY6vN5AyXQfSn!E9_!`AKlhb9q@C0|==Z*KADV(?hq zk-VaNb$%gZA5BfLC8f|I)X&IPkkyL)8MP<=G!ZgEhS&WqxRz9jO`iI{)P-mjJ$N;?4b})wzvTFLl2F&BMm#{MN5HU*7R&4vhIdmCY+wN7RePb>&+Nw z<>z)L{be;OMeu~LigbRF1ucEG?7PyEz3$b(v#A-9c71S$Vjb{nuOn3_gmQSw;Tl|e z;dgbKyc=S`B!(F4JGfUxwy9cA(>ZJ;h5E=Vj>XKEIn_{mLOCUPd2$wTob;Ez zx3Aa)8&q2ne}6!8SC)#32WVV}U-wd-p}(?$v+(qeP^43eBmAiyoL41$yQ%raF3*8Q zAzLY(oLmv$fON?enK!6aSo(;V#__>@Q+n=9)UY$Q zyhh7`zGu6_yYG>^ zMksiD)f&G$9m7R@#6fERN}$ltU3Yy5&Or#2Av!OAxN7(thQ*%pgAV_hCbHf9?`!7! zBzgCy6NdB4e}@VV5`6Sp)yH1l+5I;8Nn6MMHSbnry#kTT13mC9VO~DeFbUDIS-5u= z?8&RsvI~5(i|zLUuyYUFd)rn}~1qZyXIC zO@6TF;j|vM-^z7*G`H@ZYqGiUk}p1k;{4hdISJzlI#J7@#U1^8-+Na|F|j8p?epPw z1;699n`|IjpM-nvFf{$xL%_TI=k*iBHuRoLwMj;Pmv7&(DG&i(+jM+@e&SM)Qjpbu zhTK+{5}T$vHO>b6-;NMEJ$KMqW~1Lyk*^5#$ar{E zM7X=prc-d}Osy&TJ7-5)Ws7B?-@$g=!>N-i>9c}qYR;vG??=4kYmG8IJiQ;dO*x@u z!#Is+&s`4mBVKWob`C`hmt@L4l}RQ*Dezczr<^JlxWMNf@8LOb-whC0ZHLY9tgFyj*~;1oAT|Z2eXl9k^!T(Wff08L|L=UC;q_ zk>JDyA6}R8cv}n0MXB&*LwJ15?Y09(wvZ*pGNsd3z*iHTbJ70r-zJ#H(LZX(IoTp4B-R*wL1-lL|?oqftcP8){ebMIBPTNGRt26z3%@TA z_&49G2>8d-$^h>Yt6);dYaT_@8t_vJ+p4w`r&+OOz~~T!*2(S0LH`|j2rPHsrs^lc zmsi%xi~hlO1Fq`$Y63oHw`k}m3kp|m@O{tRTkziAenk05y*3iw2Ct3ysc1XG6={uR z-A5!C;xmTPlE=^iTDU@WOUld(?Skm;nBNug9kAZpavQ4g7l^fZ2)T{1?a5&##Q}2q znz>92_&ak%l|L~>sJ|#gXqyY*i~$s-ei;Pn4$}QSZsMtX|Ng4{lM}N|H=K`4)ZE4q zfQY@2Zd81u{q9Y%;Nv~8z?e7)22Yhl*R#C5cQ1oPF(xVQY(k!XfdasqiaOSW=)I%?gtpzYF^i5U*&l@UQ1u@ zmlq{?ds8c7IZz+iJafTdHV?HiHMBTyMIhMuq#cq{2yYiysQ%i9Xa^rfhCKX1Xcy!} zNC&oYe%4DySD_6K1aKDuA_?zj93p10+uW-hH4Io=h!YDqopQZ)-l@E!{}uHqE-M}b zv6qsEyXYz+K9Nk-XnbQ>X|BR@*uxMrk88Ae8MAN>%z+?k8vI&-iY+I_9MIHs-u&|| z3URR+5|6~4)5jve(x9Le9UmWk)F~0)f6iBozXFbH=lbXCS!!x`(S1eDnw3R+;GW^N zF|d5jJduZQ@pb9V&{oo|&ArZOb{@5_JfZ84{0v3zM5?TYPp!8bnIpavB z@m4?t(+Rhcy)k(qL2V+KuOeDJYTeQpsYTTn`vtM1wG7aU(ex}Vxt&^{%a!)zPb z!_}~ICg283;2jcJ*A*B!ZGe6roUn-6ZHE8lEsiLOtx#lzUwFVjI~z{hBU_YK04r4& zn+)JBd|o$pzaET8Fc4fAly^oIx0_Mb^!eA+en5ZL3xz1>j~ui^n(bAK z4>PpNemIa(yNxZHGMhhkl-U;Eje^76J&u?YjhNgzLzM-{&~FhiwPvDW*+a(G5p<%S zZ7OVqt+=oZEyie$Wl}JvQZyP;4ytBE<^ZO1PA)tWE*z~5X~gJdj&d*CFZDS;KnW_4 zLVqXCf8Z-Q;fZ1&8+!?-#=}}7{L%r#PxHH0TmTixEsU=-4Jw`|nN1bDcxb=fTLosf zO9@#H*EcX`BlyX1O`D8kSsTETE6e0lx|~OD++BS?bqPG+1!hD_S{^XbSY87`(^5or zAF>54JJsKdK2vcB(`1Ay_ZiD#LytwZI_cid>3ua5;~|Z6OvE?;a!9dIIaTynBye2I z)gPzOjMB{Oj$skzxw%ivMzXZ>=zDEA?N%K7Ax+lAjf{+e=k!t(d1_|IFez3raN7pz zI`*TB&8{ELZOpr&%eNz2(rfBX-=jNjuc>swq0ryP6&BMu?! zyw@JEc~274Z22MWksc>fkJP`Q_dqc%g*y&*XP**`A$`6Y_hbuk-WlTI4a zkDKO`$2TFjNQ8DxJvO2U&%iOH%skW|hdI|3tlcq#sSo=1#eQHl_0uuJFrmyr^hVw+wI|b@QOJ{tFLJ`Zsz~R=wFz`;9k8?aYAk=kohAvOSa-Ok` zYQjacyD+VoAXa-#)!;u;WCsyB;B@Z~mOA>GliFu^Bc+TX;1m0|+iRt6V={nd7!isY zaX%e<&?-Km(|Z~%x#h?FHNJx+mU7_D5(d|?;0AWkq)0n-ih|)%rkK#+W}^hA?()qD zYTNdM2G9`;(fpdB%f-|!P;ujKs%v@30AYan)`alsZ&yw*iL+Fazb`gG2q1T~bT1Qg z^?ra);v-U0n_~b|E^LYgBfuQMC1jhQS9_f9h_@5U@J(jNt-l*Fp2h*&dZzAu$Y~W* zgICoxEF)9d8+lEv0Iy#?WOO1S8bI|0A_d7n?j0}U^ZdT+ptf#R@i_`XBUD?|i?%hC z&wYNfN;&|D2eD4oK~{Dk%0CaV)ssT3ahmQS6+^c1lc6Y!1M}$DLp$VW>Uf0Jz*Mok zxMC4AUWRrq?={0T>j??Y0$3ZKu{Fm&!Dev13*U1v4=Fv%Lm8x1%-Y#RK8yUb5zFhs z>3U{kU_E|`j4{sW`fgtEw%4-p9n$!JKZOpV+fUGoI!W5$TE2zbZyE@i9lo28N!~jz zK0Q$PISm~1Ji}qKH>hAUAkQfkWbs7SMguhB`dizjrkIl5HkUlTJ^04G1+v*T?@$aXcTMo#0m&g# zF~z>GZ$Fn+)NgufmK)%E$qJKm6OLkSn$I=A*eD*!Kj1?N;vC|U4$H^Sl^uaC5A&4s z=qG?R`9pq`d%seGaIy+r=QU>2%Dk@GvP%Tuf2V}bJP2uk-qmlLNBpd33hAHbI?xfN=DK1c!}cIX#c4)8039-OQS;mhI=e4hIro^3`aX;* z6{w}QPCSI|#Z2U%(OJsb?8`cjZ+BjuUY~)S!kv(eb4oC>$R0l~RBF-Q&qXU6jJSQ3 z!Dx2;Lw{dObOd2I$8iWFL9HDS=O6~@;K8eTAvI`1>47s6+a+}*kn5%)u`tu!B2(=M zBKS4S{QX>&Y>fNV&NJnAq=vwR`Gq0yMC;I#N7&<9gGvOg!x;z4NO<>nqsPCRxy$un zY_Bs|fv-?bLVc3}YZP4G#AYzgj|S6fajVtW6y5rRBabg&PzV`h*Vz;AWIu``36jF7 z#f54|ah_ttznBb5{-}B+M;~pkW<)3Yx?4sYtJvM?_OYWki9nMHZ!+TJfN zS|hx;-j}<+^9JOf=eL%#tp~v(0Bz1DS8gxq$WokT^UGR7^bHiDS%OJtCZah{_8>Rq z=E;igI=giWpTmv?0+hsX_uJ*83bu~36$!%zEBcKxbpAJWeRdu%de(Gd@$0O^wvd!T zFV%S3_J<=NkT%lw^6j3ILOHmk;LqKeAmbMLTSz$1qo{j})DDj>Pk9;ZO)6c_O3iFk z3LNk+xA6`*&k@IFN|cg;UeH-CxCtd&%9g>ww6mi&jToFE;cFXI`kM1OpD6c6Yz~6^XlrNF<#2#JKnYm!wl>ib95+RN4TM0E2$_8#3jTWti5EkIC`jTrQXo=V4m@8;D-g zC@B9j26(r!cgg^gNp(&`oxo3Kgn;zjnI>I6RORd0Z1Ga2$p4P+4YDG>Wp(Q z7Zx)aHbTC`5p+T@5f-@QN-`t!)uA_`z zW4^-l8Vcx9hTVqibjO^_z3r1h4cio&pR9icSYE zlkM=>UaTXz$6?h#g?E1bZq!IJI29Scb}@Sw`$$fuq6w`$kp0hOP_xFPb;1Xx#Xiye zzF*DtG4ia9p-IQ!nX=V*5}Qf1w3WM68zT+^r%kW-jIH&k8E=;1bIGodeKkJw`!C(& zSeUx8ai;K#IeFmjrhH6&8{{`j^ARFAEizDbK&XOD4%q`pZ$XDA31EvI00wB#rivVrZ3`7lc|4`S55+6d=++4++=l3$40hTxI;6XG6_?lBzuQFk zkY=k_aV|izc1o&uwF#_=>vDkxL~_Y{N8~{$tCN^@-Yh9I|Jqb zLtZ6R%_O6k&sTnN5`80aqCCrS0(=6AJgf0UbJF!eWzAvv=Tw_ad8af1-@ah*Ej~7r zBu-Na8EkvlFGexwLYr3)tLFH9Q0*DP!z|o4CuJqvkjpM=2AcvWDjqu0hE`_xzvX{{reksn(&#RKoQX7G4Pu*f^6+}P>o!h{x z0Wmf{#t6n3^g|wnTcV#!_e*e3!-+*$kV!THNJhh@gcOmlef9552d>9D6)E;$K!tV2 zYKv&!iVtCc{5P%=lkgI)H|I}ax|%X?KJLE0D~6q&W#W8FB=7zmS7+zq4A2U~v+@;O zYZWwRo=B*F#|#!4W4;>M0 zXfZR@@%B0iS~ZN4hWD`_RFeq*07F2$zq-@(eK;fK)U=T1us0ii-SD{61xo*xh;(Rz z4a~=~XfaMV!q~{o(r)DWoCn=0wv2=XYFmL0WG~WP?7ZnUUEKI9f|2jZUe;+v+CWvm zqE|I2Qe=cg|5^MK;l|*6J_`&#TG{kspWnp(trPE3lJAA_(M>FE+q|qR=~et9n<>Sp ztjnM&0!7hN1#&s4q(VqjEM$p)zuhnEl{`7Jyunk!`|^~pJwjXohAz~u_@cW5=kLs8 zV^Hu6dXIpira5*=J(iYx2J#a4mz2`=KuJH^ng7`V_+GPuGhV_4UTFWNB&7XFYEZ)6Nq+Y@MaA8m zsa?HLD^iRmB1{QWKtMZSK% z6uU2b|7MDAY(;AGqsi5Rt-fEWtZ|Wq3^@L)5 z0lwzgzEIT0VQ!B9ZtC}u^wlkqevcPd;KoMCzENxrVBO>N&k9ItN1reH2_?^*Bf{Ww z2Ti6-KL5Tp!Qh*kW30y0-LtjTTKHao5yrc6&G&RPmyFz1YwT&e0`L8KhhW*mAIHg?~lTik|jw6^735g%Y z4*R#e%HZpFmv^`X)TY3&2ecN#lpTFH)rp4rwzR+d=rW2xAkXnb%hZ&w!AYo-=Mb3z z?H*~M_u!5xoVAyWyo2b5v<1a(wj^Mq)A4=lrfWpAr!m=khHpcSzxG7sqQ>?XSv3qn z*rABYRBr*~W>qgDe;{uaxN5h}B+GZ8+gN{Hzpch>bTmPaWw9?TzDlG+vRFdFNf1#tLdbR2Z9SwPZSNiDOWWi&hE)H>17nCz_=WkpY>%TvJsi`o}6Uk<wl!n1=u zLq6Fj3|jW31`n+Wr;W;QA3=RHey72>XPT1XOW({Tw`}Uml${=wNt$<2#X9+q%>^iq zATrq}ms2A2gweNN2H~4WFMG_+gPWegCRfJrD$*xL+o|vSam#@TwiwSGgdW@9U+A}x zCV!peJA*CnAG|G3%9m5-K&Jqdwbd#%B6L2ed&ut<3nE9Kpv6e-&YB6UAkQ>P2{U!#MS(EM{r@tkJUkh0H)Q( zLL0t4UpjmM@su9=od@oy^K81LO*mW*tnQMefnQ;q8Dg2T zX!Eep)e%yHu*1*9=UL(Z)}xu3cjR|^9Wfq6y6b@=NMs|*)DgU)9);|nTTp^>)n-6a z1;{I|3?B~$0_m%=#TY7t{y;^>#f6{Dlh7ax^aWkafvFK)mry{OeC?e;Q;liUFnOUZyD1)IF#4njLlyqcy0AWgiVjB58?wm+(dL{nsgTqM~^c;6>@e!ho(Xs7;GCT#(zKUP!N8*CE7Ue2-_A}>c zqs*>-hUnLQz<>~Vq{cMe}B1NaGoP-qZ7* zaC%?(m|&jDh!I+9cZl>5%-{6-h@~CS>GW}m=KJWn7;uE%j9``?dSvG2YNY|>cxPt( zoJAI4by@bk*9jsaY`gvResH6GNNB4Yx)?=&8mYSi>tKZD{r35=2{`?iI?cLqC84R1MwFDfn3W zWsb|UZ^l2HEz}5iA2^wNClGiyZCB}c)RqJ>c@-UdD!_37%S6W?qxFd0PyCoZ!k+zl zReb-rBm)!ZBj>G;jnkIMZC-9nbPyY@y%dulHQ~;87U)n%Xf^M?MH@We+Acm2nZCHv zg;eH$cgYR{lYjmz}GoWa?g zOAgjKs)7?0Mx}=hP0V!G6iGL1lsdbEe9>XC;P6#*5tSuLi$%3Y2wR1tGi@Ic>aJhE z|DJB>s3ZDCqP}RCH2p4oDvQlo?mj(SXsh_O)}ql#LFEOYaV{jqDxsUS4EE3QE7CNP z@wc%L)a#W<1-hA_WiF6f9&(=sA$7bzC{`L37Mw7eP zS^xw9MZC&K`FCP&os@<)0f6m0pd2^3VX!!RtaiExQ=+6U7lEKjAooR*=ov~mWL zwbd~^xT1ZAOklTwn%$^SZ5s3uua8!ZXSC79gCZjOOI5)LTs-U$lWRAsHIS@GumsP0u8vrcqQeJ*&rf52I>P&B&?u z_m}$$+UJgvQMY$S0)TTPsDD{?KEZc3tdP4mxxGWuP-NO?=%;7+TLIww^o#+Fky@=U zb7>Lu_aj}6c?!4AUbGyxv}-4*OE2U^bed)`$+Ug$XA!!=ePC^GE`z%a9ntUo&XI=w zbZ$m{Z+>52_kL%6tp)~*G=Y$y#}^{!9I$QLVJHftc?8S)eKXl9I9=ZY&j`=j{EfJg z+y-9jC1WKSzEl`m(&Stk&AM(@z7!VWCqlyls({d>$1A7oo)u4SEm`r_fomzIcs4;$ z9Y)$^u`X<{wLM2sY&72^Y9Ve_M!ejB0o0SZ{28rFBJ;`BgxJc;H)x!0&J6C+hgpJg zpP51Q!I;>OUF7co-X^0$y7q-mqm=@Bj*4e{TVsGUc&5%&FG@#;@FVzY7YJc+rtdI7 z#dy0Q6DM_#SY&K^o0?OU(SDnZj``2Cow(6Rw#FBZ+ECfw@)Ep>RoYTLfSN8(pwy23aN{OqSL{*jpAuJLWSnd=98kA&~7Ll@~-Zs^YrO*>w>ED(f zzTHMZ5ci?q&>oM9$_eA$t~q9ml5Rc~%=H)YXa#LKn4!fDxq`^muNWmz^Mpm=Q_KTo zHyJUoCjND?w?krYjtq?juIg+i>H9+~J@LjADJwqm;{q<+T|(Z*?NS1sdYOIS4P35r zpHIDtgYpU%G^`%^<1i3TBtmIb`Ql(J;G8tus7*u?M7&0TMj+j0znA_ai!m$uX(3EuX7QqhpptNXIfchLkdek_MX+u4i+1m>I2%)p!w zs=%NyqJC5}f=>Ye?XBKj|{eUzTGKLA}+V< z-a(A#JBUTYn7wYrc3jH+1m79-7H0f9?@g9+w|g<&rScnyY)*}}HdK8~kzX?ff63#W zpFrjkRAiMDQ1ayH;2O9d{JnT#S_6nmfT$RxD0G;V#Nl%bg*LV7oAFNHo+yMbu}qKB zt-DwH?#E*w_F2V5T(D_ydQF1hNwgI<;g6JHn0z`SR{gf!_>iVi_J@irC++CN*rd*0 zjzPG+g9^owm|azWJ6lju$ic}$OlllMD8OuYNlV+x0)1v=pd}{@ytwN$jKtHY^m`g& z9ku+h#`fB;tYtioTQcS9gS_C`ofx@GD8@`mra@C+Y7QwFM`>m_`yztN7t&@ww^}un z^<6^S1eTxLr9MTDuZWRJ!+mKSAnr6iiI=u`o|OX7=SI};OC^LFbvyuiM0AGzJGnE) z>h9)&IOUYvcUIPKl?%%2n@;=JMeUgM!}IgqJIE)CsFps)&kc`?;=wF{FeAPn+hsLj z9bQNM4#caE!>-_+_oe9 zhl_Cx(2&VnVd3!R=wVeyKDi0*-9fUVu)&+nxkRjpC3%S?v*XI+hxXI29DKI+CQYr>LT4U_# zE1lp*&hpbmt5LP*kHeoHR(e{JW{b$&Vgq*U$bl*M=7-sqcqU;*F*J705Y+VjzW#@LA9aUZ60Qql-&6q6J>cmTZOfyYT73RL9y_UzJX_J z8pzE@+98=O(uaa+XZlRVXfdt6>h6@+{&&-MSolBnokyMB%X^phB4d}65NXjplgatR zT4eXTl`5?sSK4sCX$>kXRmUi^vJk4f1PzDD}G9p!xSx;~C;3CC}uf@(wna+b&!FV$SHez;fs9VV;h_ zRu0#n1WfMA@Z%S&&eRy5plzI9OuU^S(VA$7<^wtjv5Ks+Tc%5BKlGL%YG>2gNO|A+ zh#Lx^&jw{|QJeeZ2RXD-PSCrHe*Own?TEqpjbmFPvR0zPW?fURF*m|Wt%`4Ao|`8% z8mmQSd^uCj`3xAx3>7jFQ>RrKG|f^lr6P6!Jg#U$aKZ>l-)u4!i5lsg;O}K7GojaF z8R*hp@S?n}BDAe;Lt8?wRo^yCN}}oXA$OQ>&w~0HXMY;F7iX5+~>DX5n zE@BdRAT4DnGjreQadGTcAFoY2X4YP{G(DPwBME_1_ovwLz?Nf9QO$bPsn~SwghwdprXL__iKE%Pa?ltM0w=cix5fbyE$>6eGsAnmZ`0 zB*ri#5<2@-HJtTevNDi+6=o7`gH2_81lwg;>X!iVEk_DTcb>C-d%OCUFE$COdBxpsh1f+;}4czE_DvTZaAg~$0oEz+En+s7(N}1R1r_9;DEkfn^?OcST6Amqh#C_cB z*Ypi9QB=OQuBV>HQ7?}h!S}t}PphRqb-1c%cfiC=76B8gSC&K=qHYytK@sO4^vier{225gv$N_l%VLF! zaq*(mPD1k%>Zqo*R}q#~pI&Z~+5QaqjnPE5`ZVWG@EER+9w%kKF=m_X-1vcIbmnU| zB1Ig^gsS zGtDJV+eBQ-E@B@X1s;Mbl`|N-)(yaQ4s}b%?s=&N%!_;+v7YLZRRJW9?ZYwfU{Mz| z4Sd}-2hAhL6w>2kbG}~F_aV_xwo-U*68&xG=AEc@3!0C=eL3>v0-TH>=F87bQB4kx zh$4a_$dhNs^P-6o8dM8%KHOBC8UI`vMoLJdvIOh(_U`P^atUkzyA{zPc0jQC*hgn? zjrUJ;yR>|g7T=r%(x#|n(Z5GaE%`no1fSS;p%&$|U<%b%GF{xXs$YoCsJ$@cETaOp zFt3se^UZ&xBOe#bg1bAD;Eao36J}^wX0g`9Mj$mzh)2(n)XC`bH;{TB>M2$;>=D|O z#5d@_gC;b{8P2;C8W(C`-maWTMyL^)<;eY%7l8OGKbGKyeD(w8Lo(g)xFwfDd)Hdf7{xM{PLG6H1WU84^Y;p&X zHkH4QIDI{Hewur4(4EjcsH&{>vqWK<9h#qz^xwk|xcGy(c_G;J~ zhY*ZO`6V+LQaUCNzy-zp2t`iCwxIkHc|X!kLrs`H)im2I&(?f8145nIeIw%V#|Q+U zV|${Ea|ML}J{x5!Esgz#x|k81j$T8>UicmniX6h;65ZVjt&pM{cw$+r;BFD=@h=FW z$FlPoik?5+^b{%B5Te;^tYt#wooL?*XG%0js@B}`gR>#L%zPwsGTksu3`eQRGz&NZ zv@>XSV~**ac7F7=ugA}&{pAYnRwmu*VnIf(}*&9%=?5aLi#rJ_r+{ zM*{g^Y$^@$mQs(R1dU376b^V@%Fvk!6(?EIKNv=XQi8eLZoa$|TZ1nk zXG8mj&31F#hS4y5(?qDTmA6M0tqn}7y8a&J@>6l)>G*t9+00n_FFm5;fl-K&OxZaw zO7sxI7fGLI--j&v!i{TM{ttwp_~2YdB%(n9?%$Zfy6%W>wzbwv7`5Z?hwm*dFvm71 zGTevyINg)fo_V!64Uc-^ZWZ0>s8OFiTzOnMwD+6fi$b#k6;kycvJ9vCS@>Lgv(&%cRIwG@t2|@l zJ%iH<>E6f^kMldMdl`qn-wMm^O%Y!o<6p*8d77qw5ID`VrD+?q4i65RFi_XJIH7b= zHgV$t>FX8!XR;vihK(;NDg`t`alsg4r#y=$bo#2Esax1yh!A^8*j$mEoGq6*jESqB z74EMv(P@y@G}e%U+Bf<6gpbDc(v1q=dSG${ZIBlKju$*S5As=9oGp9Wz2coe;S0p0 z+URb4rgX0{O(1{w@xUE^K;f%ZUy2E-=@!&ae$+n#`T9C$-_!zim~qTm{}aEjV$786 zHCqo}>EPV+b<;zSMm!XJoMl~Fv3pP1yxZebuneHQVCID+IcEji{lc`#KHm7a&U7%u z^SHQwNs<5U1a7$qTrWN!QlCkCC-6eL{vNQ>%WQ<_UX@B+O5?+JaSH|)LBP>g#ZfF& zi(D7~_T2Y01C^#%?$2Tim4d^!!Qj(tL}fq&lGPIXYSLxVDD@-^yc=EC1nCiJW zg`}0liADL}6ES}oG_H0xdcH%y>>A-Fi{)*Iy0i=34wc_C+Wqz8&m{j&tkQqH|JQ)V zL}PBG9;k)_q-5UhqWnT^alo{#+>Y|#j$iHc-%Sm$dFvO=FY;HWgh%u$S2&&m+;RUg zi+Kk_6a=B!9I`K%(?VOabTF*?dWo=9$&}4@knzUIHM}8fUbOLMICW)UcJ)E95!x23 zqwP_`m7yIqh#q!)w#Viu{sR9VNv|^|U^{e}NJXQV*N>#|dUK;%f+q(4=msCh&yy%0 zx!kGtlu>hmGZjgQ4c_Hj;foVi_bNkF$DLscM~l~XoO-!b+hl-hTo6PQWstz*Mi2ab zxp18~ul}SQH8|vS50GU~uGr9ff$;@)8^9Un6yKxcm2gx_3!wLmQI<4=f^-7x-UO$j zd*|=bk`aqJh4DKVOhZjIy@+@LX`31@)GtFVpCIbUb4PD`4TC8KofsiCLMK|G<)wJa zPBq2vK|9GvqG7zhuQnfe$X1YLs@g=;Y_ki97-YqNv=l~bntH9}0Ns(df;`V({u2xRfgOSIdowX0Cag$)pUd8_z}6 zLB54gfPn5iR5TSPoyJb71)tBS{O}!bdA359?8hgm@AT2MOw+%1&}bG|l)3|eqK|{* zC}A$vTyS7nhp~UR(OLaR`zlb{<}C2eMx=HBEY)R?B zoIr5}3Za`kuM~|}M2TJ27jpa{WRCORIDFy-@O#wxL?lwF#;1x=;LOjyU$kOl(#WtmW*ln z^CuuEAd}PjxQF%u6|f5<_kUpbqr2TYx`z!7RIs47Z>|R?9RfaB0#~#Loo*# z`dlD!$)bZ7dQOW093ton(32zMG_il1vVQfO7w^R7MHgkcGr!&sMr`|JB@8m0LASW{L+t7Jh36(i#OIu^e2G6Mh^krE zM48`dM0%0rrY%jh9V2993mHI8vX8V-wm71Oc*Xe})kQps7xEML1ItqcG+buKx|#@5 z-fOhnmaQM(e6K=8d}?8M*^nkhjxNyKl4pbLKkTAV|2R5}CC6bXihht6F~c%3Gvm(8 z%>Mdu&#o&~oy6ADyXUwf$!O&SW0oc$!e;ib=t;5p2~@NRj=aW5xgFUi@yLWVUjCEu z!%GnP*(RbE#t$0T0x1JPbb<0g?&6Q3KS=la7+zK(R70!=rKR{6*n^ZO4CD;A3su$= zzWf;qd1I( zSFY!jkED1gZo2_cSv4;iFo6OF0K~7(!@licfM zX&HOMnt`rt{a%D`oY%5QuFO$B>~!CfOb?{SI(fXrA>Ye*J(O_YLNLc&c0-K!t3zz6 zoc^}fM8rLpg4VoHdTjwkCA}GKvuh$OP{d&~FjFIW9U&&NU)X~ju@Eo|?4D)D)ZkJn zGekabqU|K2g#(YV_^PSbTsT6BZR_t-2yDi)OO`a``E~q6>FDS1g-zfS(i2nEQmY4- z>}Ni3yeLMZW}zLu4Ly%m_-2vk(7mD=5SfYDqAkEIrVt(D*Eyk`=d&m1X;1zn=*w1pf5}~*&f(}G zclQVy0N5STb6GTG$cv=yRI6NSFn(TUmsZrmnpPht#8Bxx9FHOT+<_0FKOY3qd%*1D zkEEo8MLp{lN?WfEJ;dHs9pS+(FW=Ur;!VGKq7;;X-*4cH{vgr;O$+|Xt6t`~&|UTH z;-7Dver`ot!rR9nCTX-2{J24nIs7~RSs)Jf4=Za1ef#0L3gJ5@fF=$tQDBUWm0%H@ zL*tpt85B9El%MHp5&Ed8zjKQ88*~9F-(r$kh~1!FEBO-Qd$r5kRIB!on>xX8M|xJ7 z6}v~Tc$ZiJ6qD?9bXsSUg!Nj;sC=WX{CEOthKx|hlmKb45)82^kw*TOmQQHW=;n>Pmh*H@-|sy(H2f1VY+tr z#E;zl zk3fI&+mP8@iRv6Vhbv``RE34i9C{)i-OmSpEzP6(Ae(k;r-8xEs%US3QZ(oOHkw>*&rX@OZfywE=7oFH@$ z-;uc!-wXnuA^V)A#Q6!=fADvXhbge@S>IN%;6p(A;htup3Dz^tI6K5l_N1MKWnspV z-w&HRp_F$#pUpHiN8&ioY0Y<~{b`8o=H&Q=V1&eJk=X9$Z>*$utfWzf*kqNM)+$Iv z4qD?l4~;xN&*0K8xa1V~5JcV@cu&)GkA>-|W4FeQ@pHqw`5l>;Z&BaZ?o}=EF#?lX zVFdq~{BRs7?(%G)6{6R*zzo16T}l)UeU7OHsZmqgs)jzQUiZAb#X><`T4#kOo5bQV z{+)kauZmr@()HcE-q0xBK3Hw>R5*&axD)^vGj~$$oXNT}sj)F|kXAgdP$RzO7*<+; zN#7g&N8ouz$dgc1An6L#j<4H>sDu8cupGpDI}ys0XH10Ez}1(^BgRaq6`{bt>*mg; za(019D}IpQgsLoerPh=}f={TQXkyMankggDM3Yax}rsPtCF^Y9yT0P_>{jm{O%Pa&1zjG zN}RHc++p)~roG!!3cFpXz*@FaN81pAeEnty^s7?rL!?G`k#lcKP0I)38||j>_pBmb z9|WRFWA49v37fbJl~U#McoXDZQF0KKlT}n4ft)`G`a2>*d_xNXMG_51# z;fc>tVF3B+6S^;pNAQ5_fXs-M_?t+=kYw!Hx;RGoPiD8}&p#A{_`wg7qe%VMQrW6dpYf z!1`I4wDC%ldPaP|Z6Ixdj_Rg(V+lr@){cxM9qn8cNYZz(2|6OMOVQ6Y66)Osh;?uO zmVsYmlUr}A>b0ppVkAFD{8mf1iQ{O-JeKXw?rP^xiYfRWJ*0n+2qca8T)v?C)KrR8 zsK)612u?;imFT3n9}6cur5aueD1wF_KZ(vLEmMyjfUuW#F^5^yc;?%S+T+sLG`W+b zN|X``v8Tmx0umgcFveGwMzJ({Oo4KfWnJQKyb-RAHNRqlvw}h9qjW17`>xRU*U(^d z5cG?5kUet!bya#Q^vPEQ=kCn4nEIjTi%7sHSbs6{Acs3X3yBZf4kD&k&iVvLR6$q2rDtZ!%hvnO zj#hV)U+#MZO0_&J@i_n5WcW^AqFa2}@Yv(U8RomBfjp zP?=_@(%rJ$V96H;1zNc8dpdOXlnw6-B4FnS$`^x@&ivD*(SgR{GZ+`f9uz=Y_HS!^ z<6>o*!r2a`y3C_SuRR3k4CP%&ppS&vQ1bd;XUK(2#7AD`9UEk+B0Anj75eO)deom{ zt`bhm@dJ|ytji}>vfd68`4H2GSf^RJ_J*qGY*zRfWM|lV-;u5+&y|eXv3v3sZuWK< zQu_8lwe7*GCdd#n&=w~}{@Y@noVhB#w^{kc1x#=ojx#=%qUwqvj4$x=CEkP~ty9rp zu!&^Nq=t$%lRwx*M@C|JctD0g0(rI2A=gsYRdf3Syx?DMmR)m2FCE zg0cSdAa++HK?cgOLt|D^>Fp>{5NweHP4qaYsnZ3#TGGVWY|j1GXd|1d0YrYCA;6=~ zA^77ZQ3OUN!hlWx8fas)AqTN(2f^!wh|+_im0=mj0GF<^xM)}rmyEC-V_>9DF13J; zDGA;ynM#O0kIRA$#qwHs`qb6c4rtVsBCLJ8+Rw6Vn9-99d)rwN9pI2^Jawx#7#|9S zAzO&p#Y(#f9UXHYZq)d)j!9yx{F{bywy~PW;^bG|C0Nrrg`@S}OqCv$nr`(y zR}%)7@QcVtwP%M9)es~(->n6YFB=1Sa45=oUx{$udQlIrGu@`M0|?3@g%6j`85s%0 z%n61dxC81T7>d(d$LT#o-KPWV9^(Ds8-C0Mz1|6l|1w3fsZjPfB$T}H?ePF20Q;E z_tqW9W@Cq{8a+Do87^CSC9ckyiPT#d3~~^LF!EPD)r`^h(e*vsga9VC6!5pGx(LE8 z)w(-gHX+OPpxC`oHzR)%+V&lny0(Oh6Vb%^omg4^m?-P4TBDzUa~@TD$hsW5{RSKE zlpehwPS^Y_g_9HUth=}l8$3aOD+T_Hyx)OaEqy}OeJy~8CZj(q0K=NHOTyb2i*o;- z*OYXhtm@MJstdO8SFk08>SD?-oWm3!V=47TbehiIE|YM4Ymdl}XyeV8 z;$*1L@|%njQ~cgUy}$wgJF5>bev_BK-2|OHGx}0?(WEKhd@;UIR6Wot5|}vzPH2G$ zoKfWoc;plpI`y&ZS{W_F-j2_9!HjK?M{OoFnVg1os$1PCO_Orh5(RzHcNziq+gIVAEa9jfEdU}RT02Sn= z)L7ERt4ba3&T+-;T{%yM)SI!OU|-deo--_bE5UG|LC^b6 zaD88@6C}7RH>Hb_LXOg|6Cvls`m%;b&bfDSG=Ng052r1H+_%5>VN#n0GgsL-D@$c{ z{)N6FA3B2U0i{GugiQRL7X3%^qAZ|>=&1s9@RFMG{#%^KZCwz+OFKtXHuv<7Dz>T zSo3A}&y7>V@zt}De(DTGf+%=MF-`(v{H39lnlpg_Llb}zG4w-eC<*p*``c=`5xUhj zHN-H`?#PvMUZ^I=B@ylcpM^dvYa-R8n@ibF>ktv%;%-ND0jW^1oBsPI;s?{0lI7y2 zyg(CCJG~0OpiO?5zvnfZ&Cj=cH%?YiU3<7Ce2-Gq1B`c>9?8k&4_1;)De+*^H+0BH zrt|EhZYZ$bN*FSxAv;vX^*R2BL#uEgbFfBq7Hj<`qQI3-SiYD&oo}BKll+^~MW+|Q zp_te42~H}jWV66F#Y(m3{ak%b-pMNLTjZ{}=06oyHL{v|6S*|ROa)ab(cABDl{x~- z5k!YLB8NzPAnw6WxRb}Iq0c$KW$Hw?qzV!`DSSv_xS*S-yq*-!rET#Rw5AUCO8&WY zbkF-NPAgwZq%AB83nDBQFqy-~V*HX1`LXQ!kBU;;T26}=6Giv9nbz9E}6w3or zSujn&qqSt>qJ@QVKbG4fatx{Y$D;GZHk;BH>@Ib0u}5#^%tQtv%5-Y5(CqF0itPmP zLJ5rUx3&};aVGtyQ4Y9^9Y;8${jE3h0;XO&Ub|WncmxG_W#a!@$d{~MHNK&e%a*cB zk<1~ueUe;6p8Mdv^zV=trg@q956k(U#L3Ey>#(|?!j;(T%pFBr1CGD&Mg(+ia2I2AeW#dK9v3@_1=Dw21o2(jtf5HR&m;|lB*3hb&xnF$$ z{J8e~n!n$unx`w$ynmW{SeER!lz!3A4-L6)x8v`r2$V@CGqhL{*K+ z@KG=~xy8I^NE|rGCnxy9;z$+QQ|NYJtRzr;QG0^zZABge{PpRF?q4O96rdCBTPu1h z?4KWFK+~QFL!QrooX>y1q*LJi{az3MwI)Mfo=q~ccG{Wcw4azEXp3JQIdv&V{&j66 zBj>WkC6%+7@9ITgpY@=KFt0JkAbq0Nn+X{a2tUj26o;G3YA+7VA@u6|goL)d&Q-uu za?%1mPEW^jzuT1C0lm8IlkNq<9qQUxYFv;>Z9cI=qbpn#02CmS(# z%*gp`ByR%Ps~;Jdaij*j9GbKM{FXUJm91nJ9CKoLp*D;SbeKvlEC|zH$uk^Y5IZZL zLQ?VgYVEY~UouaAMBa9$qeO)x(%S)S->2P`q*tt!ui!fMrG<=~b3}w^?X3Myk)KD- zBJ^#Sb4~@vH4XO}C*=IGX^?fBvBPS9vqK(x8I!m^}Fx*yZ(hkF?f`$;IK5YlC*S+ zOi>(GZdllhtzNBsa<9H6t1e-XEur`67tCU!Yfk7NWKN<`5>2Knye+L^Nj#s7jZD}FA z=NaMNnQD>`83fp`$0N0S)O?B^QF>ocZgFrM-P>qtX$wQ{(K~TFPdv~;>T}7b6?+%K z4EO!hkH2B2e-*PS#$ME3b7c`6$|)Is-Ss(M&dN26yW7S3ZUSPj$~+x!5cqbWeOO5c zBxrTX9ZE8U_-1-B3*3e+;|5fdFxgLp9LB7r+V{Geg0h38+csVebc+Lh8Sw}ed_P{; z^9t^)vBvn$#jq;pPo~XPqVhX}1)*+Cw^H4hn!YqjE33`(H-9~0(WKC{&>MyAPDB4t z(0nBYlOHAi);@$1Q*xzTX=>iS)Tbgni%tiU_sydi?;{LEt}dwb8!+s}V&Foce=0+r3w?&f^0b_bgg^k(+_#X%R{veI>6x@JR6yv5<=L=Hxo{Y zp_kLk%n%L}a1bzmXZO??w!Mm0;UQC4>tI&=;Os>ZL=A`=H@GqkrFDq5VE*Y^ zObJ=putJZ{onw;V*1$o)OtE7WLT-wrKUywRGcL^x%Ej(nvM~`)-*}wzrIV^r7}qhJ zY9Twz9Ng{`+ovShrJXNx2F!#P8bJd234^{tf@u$~zLVQSxfcQAF@X{tBf0K+p7imN zj5JAtoG3T8zNEk(bRHKv9X;2__g+Tr@5!w`lZf$a)(ATPh>0^$Nxz z7P@MoGHAqP{cS{1LtWNcY6=b_UfwqkaqfEg-d(QzNLXbudRl8|6KQV~p+fh-aP7!( z(N!@|r0Q+lLLcEN45`(5Qy*Q+j^FBiG#c_;+C}aO+y=Id&n(l-0gK6G{#xR^28pIP z{+16?(Lxbi7L&8=0jhw0>`YVr#Ozzf-|`z*IQY&mcSnGh15306BDT)N@o~iuOePjM*!SYOrO>;cB2R>6~M%Dv+*)v|YwILn8B1WO}ZfZ5xjVn4SAPx6`5b+O?a4*a0E z#~rUv#&<|e4Yl`2U{Fe1#M=Qst4XVGlVaJ8yaVeR_TL?1CtD(6=O8etW(dT37b-xM zee&JZFuIQuPo_)Opl*JWF9(n5%0z%*L{mRv((Fi|>Fd`@W?;wU#vw4kYLbkF-f7rV z6W8MLQ>lW0BtUv6jjl1e_4TnhZ>v~>-~07VAfb3k`b@hi#eg3-_3?E1(aqbevy7!% z?NC`m`IZWcnI^&*TOhRTU0OAZ%Jr6DjPBolCSQngu&EGX6;dA%Q@tm(L<}annKW@t z$|4cYUCf4uNyW6zK|crU_U|7n1E0y_IbRyYdU2D@ZCZ@g45C5IBe_eXi}Wet znu^ko(pt(bLOkDy^h4FP>bD`g!J}?{5VpF@9Yz8-(nwap@HSk<+O;_O22)FsuZmh%TutQUoi z321OzSK(o8)0-=f@gpUC|4ybpze%8H^ofec(YD{nYRKLk%j96^h!~yG+N-Q4$?qC0 zwcqmm?up8ZOCl!q=ncg~Y6r_pt{eJ21 z*LJO+$FA_lCWjNV^xXhn#n-<01SpI-&9CZevRDuarhdjB$)zm|E2PH0069R$zxjKC zjS?X>Ks_De#06{P-ztlz5@w>H4;-L)k^If?A^htDKEz5xv$^9Ev@s3VYFp+|snfXO z?OG-bf9G#{iSaw784j#M(3@XnOq$<<@e&yf<-^Yw*wZmNCs8sXg9&g? z6vUrM%#H0ro-j{E0ojOO<1t4%&H7b-Y(R`bjllw?BP|q=UqUG>+(A%Mej|70-79yt z1&fs30T$1MY#CRnyxo)pg<`}0U~@b#;P6c^$&WMtq-}VC z-X39_XXAv0(Cy@FLw4}pGt%7XT!`0VzG89eI#dd0_2S{bFN1Lx$oz6Cy^4rUvbyR8 zENX3AiBg-bp*^V{!K0IaqR{cjh zJ>KYesK?6<)-qL5NF{<(GzcnLOYrhs-Ppw1ae7FfAUN&-aRFaEbrNvGu4~J{>~G3E zcrP8wYGt21oo%i@q9vUPmU!iJ-S>9su?xn*9#}2{bTW-n-|Mt(Jxdm#`QR{K01mZ4 z_B%?|OYNc=;^ANhf-bp-(1>L&Ws5sir%RxFv%(4#Ib4?Gd6&X(wUqg>8+*1)x)&E5 zfHrv#tQ233F%ThxUR1kORCDE`8|+E~$V9?m+-;Gs36)@pRy64wTcworOBHz6B57aX zTE_!yQ?j8F!hyfZl<8PEv8sDrE6;2pOgq~H-a;oOTyuKAbGsjZkpwBr=c3Ys>D+U- zx+EIPKQ`Q{o+~Z`t6%}2U-X4o#dm_dj{;~SwjJLVzE-%6T)eqO-@PU34b#?C7`WH0Dn1!cbizBKcX%T z0|_JXn@{-S_Lemo!I4?8ZksYlxD_62@+2IHOig%7&>4nT6sd=Tjs8xJdeupkXXkH! z#e(@wJ6;$}oPFCS0y*`>A{F7%r|9&;zhm_UFWnXy1sRK^#OmjG!Bsjs0>W}t1JPew_)JO#BSKX(YN$TtIt z^Ub&)sQ+gB9ILvAJA_*Tiha$?AUW>*s+H|u1veQCTL}0?b82U}_$$O@^lK_|(*73R z26{H>{NNJpt!|vcK-_?qLy7lqa0f(o;#2`;08-1 zOid702kv$Y#_!Y`^4%a*AR2K_g&9$VwZ0hxBGCJ|I07KIRtY*_unAa z=nt6LxSr*=JNbOP`AEFq7}YS}pg5Ce3mUQ4f7v;h2l(-RZDFXJP&t9%nD#ZZ zoO{%!pKe538_ac_YX|KW!;J42HYNHBbG|AAlVNlMy^aX_>t$Q?_x$UP(z719<->Mj zKdK8E9XE|;(0qo69{}y?o5cFYZPIB9f^w|3-NYse;P5iK5eeNtI)o z41C+9_9#GvMa=3v-B3hP4s zgGe?U^jnW$Oor!_NUmQ|YtaLC6UrkL_M%dm0aZ*|I_?gV0t)^FV+WxWU7LO}1AcbD z*pGOJshV$bO%IdltO}Fhvl(qK1bg4HZ5Aw~Aqjbh)s)$r(@-#c8Kw8q<<#t5*pVNN zCgU69fObu4oWJOFY)lD)o?C)|@<^(E+#x`v(J^uxvab75XT(!V?lX^ljz24gj+;U> z7@B9-M^z{&_8%gX)Rk{@v&R;A*~4a%wdzfR7^0GTJi+*oF&h-h>pUK@en+gSq9ajF z{%lfRUq$WaVPPi|=n`SC>)IRg)X3f*p1}Ia>5ubcc=|#DMh(vxL@VkgJL`AM$sa2k zH{Mr&nPNPVbMNiF$HR53N$~3tNhq!tZGO5D753!_T8hBuGM;VFHWs*pjH&7IS-l}5 z;!wM$RnnDYWSmqk|MFPNj_FBpnwXb>Hd9BKm4x&aAV1`JEj27fvaY4zhSoaL-@g*# z!H;5;ch$&Wa(Tv=Oo%}e2I9bbEUwr*8P0Ie4+_sH8O7m{2MfRxq$U&Wl!XGv`r(w0 zAfZq8d$ZVp-F__u5&A0aTl}2oXzP~(|J%UsSDKcq$bEULXA~JNE=wWvt>|>KZeM=q z4_d;T({#VBF>d(0_68{d>aOPd`6SbD z*NoiPD&Tpxfa2ThI7m92N(={V-F9y(;P`i(19C}3RX@hKFj3Cn@U`rnU>vyVUgJhfQs++)G9oRXMOovkflL@wuT_3L9`D?3kS~ z7yhmp=@yIt2f=F@gJ zBQa`<*%{;Nd0nxDwWLQ&F0&H^pl0Yy@3E;eMBFqC{;GZ)>6O$&lF(Rtig^E+gppWL z2^7E=#uThE42xQ~u z%Q!-G3kwyzc$7D_gM+^fA0&CSi)Rn3+PHsHoAfCrXvkq73Y$_1b$ACendc&GkwzzQk;X-?8E+_$p3GemzIr`>DCWLc}XTsD?r6gPL#(}OgdKQZODrn?7lS=0^^G9 zMnukOtD6erpjpLus68uv3I^4LOqyqmwHm=h4= z0R<2*Fc79Qa_2W&+*1Ol!GnJwg7hCH_cyQFq%H2l%6N6(M!@ z6`zHKk+usPZi^#-R|jPC{MnqnVTo=~b6~$AgL*J}$;#jNd|ZYOd(=u(94|1@=aemQ zks{i`442B_h|wAhsuF$4boi0IM#@b(29N&5kU;9E;_W}0i$MGAJ&1xh>!4x!`f$F# z+`wCb#Dntx)j?({&F%h=A^fOn+;>uu8;IZ`MspfrwprYe#;EEwe%5{uzpQ zF<({4TBfvcjRW_U|8a68aYHnsDyw{MU9*bAo@d^Tx{LaCf6HRUK7KST;zXpgt6wA; zGr+xS`KS?1;+5@nWBJ)s7;_*HWd4p2w-N02mEf;8Gp}qjzd;V*xl{NvuZfr15sVeY z!bJiBm~dxnbSkXg#6|;~B{#^1vh(Ty)}31$r(OD2|cvM9r8|)*;B6LyHtD9BqJ< z5BI^3A;^u7QcPbEqBa`W>h!zao1vO_MawLN#5(o8&MpUZc)hZNoZuGhY}`NJmOgvL zYY1+MIG%2eH0lgl%ICUOu>W&4-+&`Ho!!|@=r`Si!^uEcf}}&GA6BX@Bri4H8T|OD zovUhMkfDOB6ei8KwV8lKoE=i>@AH)*zE`BRxY?XN@BE~zB5vsu#Dl}1v2XJq5q#F% zA;G5kJIU_O_*Ql^{MiLig>;TXz<3r8YeNk+F+a(ndF6q0AVC#x7G&zO5Yp?>MB3*j zB)5Cp7bl1$+J?sD;y#Z%0MqsJuya?i+UU_`*aJ)n1>JsILz0ct7E&VZ>-txG?w=3k zEbdRWi1qo*-LsYHeI7SJ8ZVdZi)n8#Tw=jEM_r&h>@eB_{4DJ;i%QbTGDkZ_8cK48 z;Q|ANHzex$6v{?8qfh7%?9v^R?)W`pRx*B{7gN-v$ zsUtdT;4zokl`C~Co>IH`VHzcGgJ*Bid4x$h-&NjCTYnG%6|vwjiN%Cf({#t&u~wlq zWnG$#ASR?jh9gZYs{ZskvsA;tVq(aC05Ho;Y75>l3E$cN9NF&`J@M1&Y;ux6>eH9A z{e_wd9V248nRqF0QcSV$d7yD_S2^(GUwYob@=Q`dleB)vToF>`=?wxhze`&5vf!^D z(1*!o?F8Ud zNsETp!eF>q;PE9d{DFy%)(3t#Oc@o2V>OsuSZMaG#J9}8oXVkRHO2WFw&I_5vKTL~2$Lkd^sQo8{V% z0U`?YN92Vx!-<<31<~TJzuv>eR0t0mbPI-jen=-%WygR7Fh&XHvZBk6{mYK2d>jh z34k5H>TX~^?y!)-KVpsAM7%?S^++F>*=-yB8nvsItHr#QBhqUnAaf6JvOC4?7+cFN z&St@u;!7Yptv8f7JXzG!jZ_R}z58FO)$N8@{bI1uK`pCgPUq?4lE6efO%~p}`BnlR zY>#X#5qFHx5S(BaLpW3*=n)pf6p7UKy3fiA%CaV(&)^MFRjk5x%y8zt43VVcM@Dl= z#OR}wOwgW;N6aEFodU(Cq-lt(OT=|&{xyC^_|$C~->-w3V57#Dqv`5Z(TU8Gb=0FL zn>H51EUwyEot<~9E#dARF71?Z7G2v1qRs1hJ)|j+(t~_@g(FDh7lip?e|48rGi@ac z!)nxLYV$zv)vXr1d+i>Y0$Z!)$mSK`HDG`(khb2-4`K|M2kQ7=o*C%tKnTou(d0QM z276uw#c%nyDVR;cSA^9Y5mdm!r6j(c=7c!1DZ zJzR9*ImQDn5_vXv%fi0jzX=2kuha2$3F|y<>3>H2p>ms(?NS1!H6}cVNc|#4%A}-! z(`p3Gdf`^!*ZXo{pBW1>4&g-^)A8k1!20hoG-odZZ-bOrK1rmFMLVuwON(I{#vGXs57<{XPgvXs1oqR2r3$XK0>wrf&ch{ z)W*I$QGOaRVPnB&^TTIm#y6WI{h>G_woC|;*R~R&We+zyQyZr=Xv*vUEn;fp+Tv4V zwO|?mKNNI6>V}bB7+qhsH5VS}+r2V3nZWn;Bc8)OypsC6bEVCo~bYKS1F)ECZ9n+FKCBe>_cshaLN6y)S9Ek`C?B>52C%Tqo?c_qQLcNd!}TO14Zu z^VABr@+2R34CF++eW))$CBGb?z@2~gmg4F9UTta^9!^S7fchdJc*+PyMmWXucIL4` z2_&EG(44VP4Hx2 z?E~6kD*C5i*ic7bH7gdv!=B6C{+c>Kj$7# zC!Ail794y6(QgZh(zgQ)>tGz?9W+~UsLWiiLO!OG;CJIUdlQc`1iH3uzXzL#%I)cUGS%shzVLKnXRi^@HO@crSqzKI?bFS z-U|-QG^!nTOV3B@!_$&C_r(MSB6w>FF&!6rQwwIXl>01j*g(hOB&CY}J>gkccprzv zn?aI+6Xo^OMT?k=%!mHME$`&2<+}U*Wm)PoSg7F$Ltgfd0_FGzm!H<%u~d#fsR_4D zy)F{Vw#Fu&sXF z6Jkzo@82YZWxJMt#Fm>o9)-mTOJdjbpxWng>nGrl6NPC%V#cIl9*tWfhnwU^wzPR0 zIX>Tl_aGXs{k<(~sT2Vo(bmjQ)i0Sx{_=-n`YUOs(L-i(<5(1)o|1prpVI|rlF)~2 ztP=1C30H6#CW0QY*nC>w1&Yc<@eMki5K@_dpox>1D~yb6?bqF%;M&9e@dMWfjjb(T zX{IUvua{2fwE!8CCR#vOO1p5+BjILLs+T0Y+?@5rC&bsw_`%mqF2C7J4*>_7^s� z!D*d!ER|6@F2mffLPnphpfaGkc^iANL%&!dBcrJM`s38VX^m z@ru9G7;#d4sPuiOct$c4O9a7bqT_cub3I@m9TQ6o(5y4;_&4yM`c$6P;%L5lWrk}V~`H+VYk0lK^+(pjM5UaoDqedbXD zat3^HbKtFGCl_uO45nmhKN7CpIc|N9yLs6$4M`~69O^^|+clEBiPZ(-qrWld!j<($`prXjPb_>0`TBs) zvCXPl`mL)=Fk}scBP($3 z7E=C)vOC5sH3t5$NUbnL^|@p8_mE3z-9i#5+)?w;`|aGEccCW^e5rELZmYyohbPtg zi;mneV2m;Hcpv}Bv|zYG2f~`qNn(jnv^A&UhIoE3!d80jA9cJJi>=K=jowg(&rALe zq+J3Cgdm27b>?CH|ebtA{x(HJ+S;D z!!yEL6dy8}F{hK?T(Z9jAZ^oH_G<6P_fhy@S%o%Xhkob|71EXuT}Tu$j&jY>x#H4u zG$Z+G4S0+1m}7hPu;G=7pq&C?da`zTpx(K|CCbp2%UJ>i3|2Eu7xjH+pD}HN@DD6% zs|5(g$YT8K*OM~2m#(3f=`%<%Ae1Qes51dao0g-@(CvG@#lD=8+|iPP2O+5@5%Als zGvd*M0qOuLywJh;ib-)tqYJ&ue1xzc-3M|g29*`Rr>v`8Q+HTHu1%g0?_t===J{a$ zO{jGw*5^HG?S4w1l`|`uDZ=SpioEr|Xf&7d?9yB3dZV5Ti*V9T8?ODC*`t7u$B0|?s%4Eof;hoaD`|ic{ zd!o6xl`EQZmG(!&he#Nq0EDp&{58Ps<^idf!c4FS<;^CLGjS%co91p*1xT)vBMnvc zD!rba+*Sk;y!7om++e?YYG~h=?p{-uhJnGjD#~G^xUV7_qWf5UZ;?wE{*AC!V|$(i zmsyw=mhY5#&;|`$=?MX^V$dLP;Wx;wYVj-~~%QrzmsO&f&0J z&hnf=sz-+-&w9EX+eY#Ihl1S;qL@E!B#bl5^iw%hCAO$V{;h!EPNKejvmxTMC4IUy zt8<*&j3Alrzx&MYJLp_@ImER;74rLeqiV(FKU|?#Mwm0wr$C~a6pH$uFZ$OG&Th6@ zHq~2yU2w-J@=7VDs%Tnuc@Kl1&h;#CO20%5ZL)a6C>-3dIAu8 z+`@=oy|m7Hag&F9qTW`t*D;&EepXiuBQdOOf4*K#pE1G2YUq*sDJyXWXTK)bLw&uHqOixLicnTeFUsB;yU?GZUw%}p|25KyzP57E3 z$~*Q8ueYWTxg*YI(!mvp)>+A+94==^vnvM`#ot}%W~PT<7-tC<`#NEwLnIT;J2`r3}-@n38aw2CQRadKpgHrNjj+uk29x`du}U1Q3Xr zIG-zV15`^>@^+H7X1Lxg3e4;ZEKRk+F0dJCzN5M5j zxT%3a%kB;Ho=P80c~e4}_#M7GV-~93oH&eJ#H|f{8d70*_vHHnmno-nhVLOhRl-^NdX+zfwUuMNw>Mn%~0UhmZ7t za;_JHpPz7efH$vDThcSTa3#PF**jX;9Fp(GDk3utz3fq=58B#D03y zC>q}|fj7v&i{@!A^e&DRfblI&J&bK2M0)(nat$c%dFb2pFnk(7QKm6r2+flu^(h5G zbfPa*=i8_NQ`TO-M~>W%FSAwQs`|7ohYL+_kKZb$I~$o9>2!!@P7k|*iQxg%`rITE zMFQuKF;Jg2!Cx4HA2U6iqKs1bjE(#!+Zx~?s#fPaT>g6J`O(E2V=9qlkZ;Y4xa-Dt z7C(L~W^JQ>bd_3cO^LshA|s1jza*7ys#9pF-kXhDSaJH zc<_=wcQrSYBwfB?_?@FKT2_rim*2M*ij04TM&NZ2T*PR2y$psVLU31P-80;^-ND@E z>eCO+UKBK;?ebE4aJeS3Om2jp(F?oV7L8%OBn6_?Zg2L+({sZ=q&k}fB!zj(LK=@a zG@DgLK(jZ+b<#y}c6@0a_sfW9IIcnTRL@{1lQ#G)@rYukStkg(#&WCm6{}N62xp@r z)_pP&#Sn}%r5tOXg~G9G@Wvvy;9`OYYcFU-{Mp$N^Kxt$i52IfRLHn+n3PNc*3;Rt z_>MWYsTmtGdHmj@?6m0827pP4aO=*T`)Xnsm;9XaP_Mi>Vf*!ZGp-*@5*tp#$f!2_ zhDh;H$EBg)$IT=^*Sx^%CE`qF6uhpcJV+n_kez4_Y*MDbbbE;>Me60S$N6{SZA2#8 z3RWkz#mRDZ_j>#xc+}D-N8z0NLxpuUOQu1Ai+{=@tACd`bnK1kMRI7p*M*=?k#X6E z^Ljq`HilV}(vt(=OwKYq?moIcX`sq#ZfUXe_6lrHB>BtLkLfSJM6}z{Mxjzd@WC~{ z7XD$S6c(X*nfB0WOYLjoXoq_%W&vu43ztrBZyM$n9jwZdgin*(Vm-U6%ULh{*`Geex!{K5 z7jz)^p(=hAO@_$>9EfW*U%d7J#)21&8>OwwWSQW zegXns$R=~RaJPK>AC;1bbZ2-)q%Vf>SA*IeIA+% zO9#S7u`^_z6L91^bzOKI}UShHIZctFV|bvTmQ%y>YiQ?X+C1o? zRK4NG&gq-xu=2x#olavx$Z~D7AyHrYZuNK@$y@1o_-^kglKf~jk~6P9AmEBkuh)$M z5XYeEU|!Q3ddP!j_Ie}<3k(Hv1--x~Bl1x6ywF?4X+e(=;lt;RxS@KKEa>p{-56oz zPljsOJ?&zdXUkl!O1?2c`}w+PopMC9Kj!@QcRN8;|1JK$Nq z$MQOm6Ap&_QkETXg!-KJcP(x%-h``|*tcLx>YbJ5{>fc8{hn!gkp=8NmP)cWqU|3ml)) za`v2mr4ksGvoBds+EI2H)0+$^{$jSr-$LG`y9(hUF_+{)-Y($l$m5tyYqA)Ew=CGO ztoox-_z}>&`TjpVAobtZ=NS$m1Hsh>PEfPUES-q!#;t>d>JbRBFZBzr3{`!8-|SET zSnObS_`tFTB#`h+80uwNk*zVppF$5s`bN5jjQkL~)B^H$7`L_8;bEvOCm-A!NtbVgW85w$d$%MOUFmNWeCUakOOMV=9`iVR(f+S{f#C8Pat&%cw z_oHod<31MsdC)Q>QbcCg5b9=RiUTz+9I+wg2G?1tx^v=rnzE=vXcWRRi(X+rdK*e_ zFZTmC&QH447DP?DpSU4FUIQbRZU*{fML_8rLL9r_PXgF{zGx!#^p@q?=k*McPh)Wj zp6H#RpMHXkkpG>a-^;=9Yqm39VsotxONp)`T}iDg#K})_a96WDY>o>d|2A6T22jn= zmKHvQ5FtYq^daQL6<>5&4pbT*>dqrOy&S{W8w!E2_)yXxiOn{W z$nQm}asY+~#nTd0Mv<)U0|px;8=%t~XKLHtq+<|tr*Lpk;pMF7_aM1C24{DHr1#r3 zFUlTqVo7SR2&woS{8GSvuz#MfEmgOMq8-VD;E}zV7>C0)>lgF*@;Hcl1Vv&{3guZU zN8K9@zc-#c>FaRME%6$XE$^TE2$!6-L4UoKrh<5A4} zDQP-CVDT;bC~utihSB%V2MDF8Zsd+O>1`OCyxA^;L2P-NR7w3TxLWl284EV_ zqk*t__4KFdf_Q#CWDezv_plp2SG}51EEyg-Q~*H-+)ut>4G`^yhJDv*)MT(I-vEff z1HhBT$e|zvmE|$VQuf~L%8k_ zrV&x!=YeaeLDZ>ZCC-;G`5}sXL(2w@-yzVQVjX^;S+zSbWfiNgEGEgQG5l| zMBEABfZ@Tu1q#Bt{5&r&uORpno8XJo6W9aEyTU&ZCCNAi9t^S{$PLoL5bI54o?1yPY_jE;{@7e0o;nSX4w#{BWQ1P9Y{QF61?OLUz~21|O)@4ZM}Okj3YNQL@P4z9U#uk##Bk z1G7_O6SszvAFhxJV<aJc z?;l|MD}KZ)@Ans>NL4|Vga~#$Qv%BJm1PgRYLTEGm_IB}=TyRSgJ{#B_x(%^UI5FF zey9fn^2Em<&|a1e(RVb<&TNheg|F@i$WP6VrljlOt-x6vDSqc+1QAN+7sy5s7^=zk zkSXVogA!U*DI1M-#!6TLiY`zp=gJ^Q4*)!ezqMQnO1n8R;*Ux`w*_NlOgv2gtH(EX z`OWOF{l_NRDYx3PfHd$~mbOxnQ{bBp;J%(k!Gaucf*@}{na9<)UeH%PbF&D2vz9;P zFS>0}4qJQ=G+-6Rbye9+P;b_hrE4jFyT#U&zy*CY4@8Q7f)|*3)W^Ow>?J^e3TPOj zD`Os{V7U+Wy5x!??S4S+Y5Ja7qU5ggw3ky<7S zHf*_BcfU_GrN-5HYo{%=HNEqhZCdXDd}@bB!ESMuTslUx@`Kg02-bxemMV_WQ(41< zB7pU4Sphb#^|MppI z;*H=ek$rck_)390xEg0aZAkzZK z80^J0{C&VO-7sbh<^hmAKU-PeM^O|Vl75#E2i(QrC8;#qoL_@m6$B=!{7CZ$E-Z_V zKn4^NU_MgdV~l0_(lA@bg=TYXW$pairxmHLq{reK=}4fFIpZS`nwqSX||GE{%**T^>qD$V4ju@rMnq99o>N(vUozQ(| zCdqd(X~0NBFXGj#Nf@({PTrImXgDRQ(89zW~*G(V&K}G_u2fxVTK>K?WN(so>}D%0+1UOi$VM(#y4Ls zMp>6=&!c{-V7qC&p#jA$mdbIFH$7naw;%!?^A_2$RQSW+-j-&m0ivw z4c#H_X@pxm=j?iqzq4lwI(T^iTaAm z!-CGu?8ij1qp0%t&H=9HYMV$St$-)Yd?e1N5*ekdJ5Zi=qqErBnUBNwb%3L~-SrA+~ zNMZ{Kc+V7l@kj?`+&)Aa$ST@W0K(L{FuNtn@lY!i7vZnN4YK(;|E^=&S>a5EWC58t zZY3nbrb!s0MH&veGb$p1w~K=!@nr8VkVHym&D( z!{$>4t&3~fk1y3&1^rjgIGnN2&jw}f7l9JmWf3ctFA!Iw{r%4zf($X_eCs90RN zlDt!jY{Hn>sOICAQNJO-_`D+17Ogmen_J|N)_gl~tO9HsLrh)tc-3%i6Z6a^yphfnCZ1WDL z=VzamC!T%8O(QEf`m5{-E}J*vnq9mu3{;6O;@>cEh>5%chG{1B1qvHVay{bk3)N4* zlRUt~%9f-16?>W=3tkC{{U(H{dBhm{)g->-@+)*FY8ph-em> zmlf__*!=s?pcw<{IUhy4Q|M%UX<2ghcb=T^_@c6*z;B-LG-tPd)(9#NZ1DU`wJ)&! zuz{ikVVe-_71g&1$f!IQoYt=k;7@RV>2@e02{X$rH$NgFgx_7X>y*oUbU+}D=Q&k% z41zG{j`4ohXSn;Q8Hogk%!g+9RFj_px5Id@&ytzN4`jTMXQsd6g3_d;VT26Di!zGs zqDvr6Nz@z)<{<&1M?~r~u?VztU_Ha^6GRb$s}6vw?cqB zrigXIQxO%+?m}?;vy2_EGJZ)t&t)6~1FFZ{e!FEb?4IyL%;0)I<5&;pwe-MjE>o3) z882#h*4Fdxjenuay*wQ09b-JCc#97x!9+2Abd|oyJ|}7Sls?D_z-W`hx(WyIqX2L; zQL&HnrCRxM!x!)(K3Msn)muM4&4U$2UY1?Y7^1cbKw%UJ zs2uFc%4?QXFtbE+0jdf91jE`c$=VF|9JUlaQS+=-+x=Lrc&1+PzRBA1B+U}_BG32; z(U%ahRlf*>E$Nd5;mQV8ymD5bBxQkH64#lwOpWcIMX=XtlfjAsfNZutASB%hnP1n; zk?qTt3}}N)-!l>O6^3;OaL4ZSEP#h!A!~78G*2V7cJ63xz)EwO;_?L;|JVtisX|Q1qg{Sl}I2+J? zZ@Y1m+3xf#g77>PHg}Ze%_LBMH4nA&R98;I3rbr!e4`&T?U1^5ty?xLyi?;1m=o;F z64zE?p8k-Z9j=IX?!QxrgZqbt-*h<+K&~R?I;7Am4V<6RyY}J5hv*plWjV(d<_{W59+hMlFvowrO$ z2{aHJ#K3V^oZf~n-AHth8Ni;(MUPv(J0dgL9vBbrDTX(Jf$-k_!G{(O_PLQC9|;1c z+S!N6a~vo*u8DJ6(t&eOaJ()J$OnS-F(Ve1zM?~unAVi`MyD+CjHI>yWYf^~01Ud$ zqrHGxuCjEI$@rWI506R7R$x^Q=irrCaReCvGf5reg#X(54`!{B!>fE`T+_Vujzk7V zDIyHC>^@ehkjzH_W_ftkL4(k8-f9a~uu?c|TKSU6=xzC3kcuXx zBWGTwm}FC<;9c4c!kb^z0?r|YU^BV)4HuIfXj@p|(x}DFSa)Xs=8>gCYOz@)l?}Rn zlA~P&r=h>=LwKS?qCT~(tyadp`fv65}5my76{-&Xe{hiOz+8ehoQJr7H zF2XM%PwOK8ZR7=#PX*`~*H0PR7pKk7)R2DBFgbM3-VFloPZMFkw3+>_Rcd$8G(KD> zKAe{1s?t2%awzgwrNTK7vkxyV0t(xg`OFARk7`C?4u^@FF5o&%akTnc@6|tH%A(y; zGJ>~`=N4h=LEHk_NkJh%eip5pic_;^L1z0ICbDa3y0_2mOiy*Nm0r(sS16#0rlfXw zGLMyMvj03t@JFrQy9v?SK_ZG{lv7TR!lmEU;#>n_m2eZey z#(bsby7|BR&e%7q6t7?92MRpecxzcq>9>mUZsiyk3y-sT8UDZ~f#8Jao4ZwFvDn>- zR2hZ##O-$|g<*RWf1F(QH+DESN!O;BX?SxT;t4_N8Q+<)h96`pKpuZ+h*wBrILi}B z!1dB^yWue(xovD|wf4>8eKaIRT`t+iPpfgshaG{!jf_UQZC8ahF$b4F!~;^T!s=&0 zGh5UcO8VR8_0>soA6y+eoUaZ& z(b3`Gx=1ZdG9OHKaYphE-Ea2LoUq11ZQ!=I&ZtFTF{ZqwNsx2)9T?le9IG5rhF&IC zY+g&_#L8kn`l~6kmN4Mkf*!-rE2$l~B#ERBmB;&*+}*Z@B@9pZxgL=RF{*iUS<-^v zuw^uzEzdqY&`2_m-hZMg6D_lMh7T?KoQzm{ny6L@x2soxqu=MRY(jr_Vxj38Fl z3?ExQK#ta^c2(Hya|lWGx0l}va<$t;aUbMn3lcSa@xK>BYc$75fMys`(I-%K61spB;c*y&A-3 zijL^|DpIYABQ{H8_*6P@z?*}^gy-^0W-Po5?e zgn&|yJSZCE5p*O|Qs1m%XM1=^0sa6pV@8+zX!7-(wL<$T%VKzr#*dz%Cd6miJ3k`H zc-SS169zTsd_{f6?sm9q?J%S=37-(SW9O7e2xS z*z*(v7BB5fM_XI`$#>z<&>xT|zVoW~Hb9e`MhKGSyMwLrQ6QIV&ueGKr+rK&p>y2QiN&JO1K@ZeGLTgt43DfT z3<)+ScQ^F(jh^u#^PMxZcZ3Zv?rRaEdLhrAB80H^IIO-d6$eN2Rr|~Q@(-_uD&$`p z(GL3Cn70;(rLX-x7nLZnX&FQCaP)k_a}+G|I=@pyzWBwX%hR5zia(x&PSOV)P>7{P zbYak+RfdL{#IwEy_|U**9z@EY-~Kv=9%EL?AwId@be80`8`?0SnUlw#DLTN$^ zJm`27MRjhp{J=sibMTh-?_O5#((}Ab99zQUx?0W}7JR!k%2ANo$AoMo#Q#QPuLhS$&jgt=^i4u-&Mz#cZx(Nx82}f| z9?URIg5qKps&M<@+z`JI&_{Oc!Y#KapNE zK(s^v{N5EO?@r3TWLj76>?;-vk$XD#cYeoklD`j$*R9r_pP%_9$ zpScyf0=W9(!vViq2{$%7wVGTd9tfvi%_4x#rP%o~s0Kbh zIGwUSQ~a{sJbjAqWZLGxvaW2`RV3NI->*2@{n9O}F0%otPD#vz&1lT@#yl7^&tHFY zpRR6o>)HY*VU$S*5wX^i4Jf6;?ArJ=Xj*Iq|FMqkj=8CMew^(jKJ@Tjqt!ipJx^=pK=E9|%P2mFr5`vd|*cO#-(2!zKA>duT0Mtq0Q;FJ5c`6(qd?+)4e3a<(a_Z|G z5LdYJS0hgFxawqg(h(%E)c%=txH$NJC}vKLumgnATG=Zvj#5U2Q9tlLhsS>pj@ zxE_)na1vIQd?q$>oj_Clsv#appi`SZ(e`YhT`8=hjnPS`9A9vo0Yaon$12a8w_71j zXT#vfYA7*Co>;N84G}^OM@=53Xy<&LdH?~fib78l_YaG{qwV*-*o6{1QW~OmMdN4t z2C<@I-(6vvZ!aT_`s8M?yJPCS%#CVr4a-2b5=W7{FCAX7XnszpaM9_TKhBz|zOfkM zj4tr}4@0~)`#o&M=Qi#!oJ`&atDgeYOH%G`Nl5N$*WGS%j2CKPQgZ!Vq7x9`7n=bd z5{Nu&7cs}pqGRm`YYNDP@Oe@$*!9Y^F}|7*lRnM=L#;$aJR|c?eDV+CiB@d8dyFQ1R;@skjJBgUELT}aDshPz)ar*P z*qPYXN6!}O@d3dlxgn!WP}4vf>G>`{EalEXPcycSKwdsGkKWKDW55VUmFL?r&OZmX=MyR!E z$p)8--&A>E;h+Uv;~ZPU%b~!)%G>qYZ>iLM1UDN_)@5P!ZgmW@S5SHCw@<^=i1oQ_ zET=mK_fx1U?&lNc`ix_|a@<}T@!)sJB2 zvIE4$$x0)K*a#)!bwZ$`R5IcX9&r$es&nSVnc`bSa=qz7qEjyUXcn@KmTFhBkPc1E zDUErFm}Oog13QQvZg#>Oj}9e3z-i^S6>1Jt7I12TMYkxlfu}tp3YH8?PqyBKJAm*J zUnL4U(3}_UF~NSv&XY|+Ze*&MIBx%TH-l)Q%in3WB~wOG80vItCKu3V_Ma!Qx_qkO zrNg8e&di$50ilGks*eb-Fy=Gg9t3;PwfiZ!j|i*C=Q8x?+$lYi7JkhUf)!BhL$Gui z7wD&^Pa}}f3)>XmH>w(0wy|BGxC0omm2%`CB@IZWi%*2_YndY~pPe^3$};M66P;i*R7=c2P7t$4 zFU`t(CfCjB@Lowx%+O<7Yb#ZPj1s5%fwE9tekWZb^2rU&tYgVfDmyL?fIw3~u5cr1 zc`V;PhA(X^CV^dOqIDg?e&mqW&WZdOg$#Cj6C3jhu0AR}0by&h8}3KGPQ`LFMI__9kE1 zqN|jJKRd;&$h(TI4U~Bl8I0tejFhcd8xYW4Q6xna%&UldN2_knmiSEgE6K!RYET`M zPlmAuNP7io4R0!*tx94s4(%sGS~8C?n$jCF1XUBC(**=6_5iUTGX#PmrsjDD!@ll= zx`NucAem-qI<`dc{q>9tcIk3MOE^EbT6;cJXndr50(KB@T&ZE^&+ZD)}z)}}4Lu6Wy}x*2dQn66=M>)0w|FY;Irb~xNB z8iZslAIUrcP9uwe+6miYeCCfjz^Y*Le2n^jo~D-v!SshqY4~A>Pid@SzYNqc$W0XTmuVh8m4iNH8wmKxWsW zL2T^D8dgh6@gswC5(RUQt3scZp_IlJv8au7OnS3s7$asY=wdv*x=Ch`*Iff)IN&po z&|;C`U^?3avR(zz(Pgxx0uR^lM7^aJWp0xa75Sa%#s{UHx#~dds+77fSFJzp_gQDT z7r?TDz!Z?;I1J+t)QsF?;4!owO8oAEtd`p0=1oG{a44HuIVR1KLR3}>0F(hTC&!6A z2p-2%VZ;f|3(p9w$y|;dK}4FdeRyU_IGFvBvxuIvr~bw68IRj~bRlo3XwD}J7gfSQ z_!Gt6>C9v~I){$|VpKGF!!y23dIF?r7P-WIsnD#-h^w15Z^wvE91`Q!0Az6_&CSX! zhl~Z%dz3lzXP@fDLcWAC7RaPwd~TR#B3@$MqalxP8)J4Bh1_su>UK(LTOHI~aeigbm90>r zxIv0{UBUHs)^dm8<3fNq{=kRge_z2HqO&9z-bDjWaP$*Iae<-Wph^Q@wVTNeaKhn0 z9=MNlwlW8u$z*(8uD_+)rAZH5-(VLFvg(G;@X_^fUfH@r913G(#d=il0OrQ6$kU>W zk(IjaSnS<;nKS%duwhJlB=_}gbPeu7esJf8rjsAYfk@bf0FhT_w ziQrAi3R<&@sVkm_gX4m)6!4~7-}9*99WslwG+`!_=`qUMm#CbaaF?Kqn?W=#4Xxj= zf}uE~a>8b6$fg?14J%=4fn1l{YWh(rKzThUm}uBg%S%D`IjTpSP0l=vkKP9ppMF`E@owR!ixQiH~6l)dliA9B~G~FVr8Qfal=l-sfjjM|bEk z2g1lnIS`{v<9{e19;`E5HcfvkRd)X*{=`NNAws@3qldJH%I zwR`TTzUP2qAGA&1gr(jY7bJvpxHm79=9k0KWp-5`>(vGpWwBI)g@{hTsk`2c+Va~? zMqv__@7ebKJGdYEjZJRDh>?qVR>R8dR^{JHL>=MG{zP+=&vziYBGf%d1n#%DG?zKa z>!Ce^CJpQMxozw5Em{jGIhr@D6LE?IWW^ie!&xOD?Vcr%Y3`-@a7f;-X z1}6BQox4j0hq!{H#agHprutQ4w6Frd|(O?_Ht6_MDR2&V2a3YI0`8VpS=;aYUhqoDx0Xg^eL zJ%mkkCIlyJqo`F3HwmIXQs0YINYEAvV`c*?jADs9(rk(YZN4Vju)v~JEu3!;;JI9X zypv0Mvw|WzurP)zu3)jZa2riI2o_oqrrB-c_O+pppfO$L6Lyw<=xxJZgfC&6LO>?^ zhLvMbk#?oTO?!qr@GK=3I1d=%W5Lmh-+hD8l2MdVF6NGCD%L8wQJ8VeE@6(|lkF

V-FhWYO% zLw`4a?eHJXUprjC#`ss)p!v_S${*jR-@iNm`L#~%-~aZ{0sry!qo~{V=U3Nv`PYwr zh|_xcKGv@v^D_1C{O8x-ieImP8Gdi;E>Gj(=U1{W%YRv$zV3d0ed;Bj{%!xY)z;wS z=NI;G>;E6;_r1=(j|~`>DemT?pFW_kc$wC#WX=LM)*%U@If>&*OG=B@nmfBp|pO9u%3 zM{Knx+W-KEBmn?WO9KQH00;;O0MC7WO8@`>000000000002TlM0C#9_Y-K`kWO+ej zbai2LZ*p@kb9QI6x@oh6NR}n|SHhydbQu}RzSU%88;bw|V&A{9gV^`w*AFjpsjQwF z8ymA~J(CG)V1&@V8AJWu%7 zU!FPo<@aB!bshg51drqR^MU?(m`f0WAP9U0|9h8zKij%*{;Q5KP1E2XpZ@ySzm&fe zb=&^_Yd`e)ufHtoJT&?5zb0**Hvf40+uv9FO#ajNw|Q%yF8QAKLzexs(=%S4#^dk5 zF4Gpz`F}e99qI>=$&l#yG9l>yP>Vv7Ucj-EaTw@Zh`7 zalaJ9-2MJ*7q4@D{!jQ%(DV1l>%Tpd{mk-9_WQ4&=lw70gW^A$2h3ko=pPOA%l%*9 z-JYlGF#nbp#dGlYg@Awk3t0a3FIiqJfBnnPy%;}})XywGZ_t08^*7{Czac*pLjP=O z`WN*%{rBcMd;c-uKgM|u|2FV{f@z!E|M@@u82#V=f!6m%lgIe;=gS|4~S>|A4gkk3jZGi^pBu?u!8;x z9Q60s|Hgo%{&hwKf7U_#qM{h}A1#djqWasy$Y> z4oDHpfq5R9?N%?he2$9nd67_#`Ds~sMWN`Y0~fGwKlnUHDEQMKJS3=|75Ovy60Ks?XRhqkuO(Z&A&YzUwVBQ@w+1Ppqhe%3+LZI;muadsSl=h&khBY z;xe=%R+l0ux{PZz?v%sxo`apK2gRK0&X)_nYz5H(3P=Kjj^3~MoI8E5-$({Lo%z#c zSn?S>!%brsn^&Qk^Wp~nrdD1jm^n@s2M4@$PMls0J#l3q$x#cu-$|7*+Hu$4-D^z_ z7`nyk&TMBSj41@cR++Wt%jvqz?67A@ia33hwHe6ccwvHQ6d#yhrF3qB9(KH7=ozpQmpAD0_6OiT?@Jc~tg6|8Z?02Jb<*58z2kVY)iWp-s z8NzPd*7h|mtdi$fcp2QhbdiM@nZhP0fg`@f{qRWQTdGTmy*cEq#}12?_W>U$jR%v5jtA(?B zGFWJB<{s{SrZ8F1-I=lE@v)oA;%#{7?d)Q=e4*xE_aHr)(tOd`D+g{i#h^ofsW^ND zMAa<$^;}MslH*ds!ekl)HOIsRjcyg@l>1S$CR0^W(naIr1Vcijkt7Pk{^9PYu$GA# z(-C!fs*ma1ID|j<+fD3Q24CZyWGu|c*u8xU7U^?)K-cv4@hJq3cQNWDI!DKM&ICq< zr`yV3%abBgoIbI@jIz?)D#cU?U7m)1C@|DR%6zrZR99%1M9kLwg;0W&79ZUvtWW zb9#)aC@Q#LSor+MAmT8UJUqOXvF^gx*pe-L ze_39WG4jd!JSMoqyV3U9dQ$~aK-waMHFG?Z@^SZNi&}@&7U#Z_nN@N!wz;F z0vMmZ06DJ#jT&OatD5O2fYM}H*$k)6og57tt7qn1m)+Fzg0{@7Q z_;~jA)0yh=mFzssF)7s&+HK3dd7HfKc@wbf-uULvdX zG16@Ue~eSHScTjZ>TO+M7)j)l<$7?by)%Ky?-SO%jP~J|n_#;xjyw=oP^_`&-ern> z$f(-4t2JTYCRnBL+kZ$!tfvAm#|46E?}Q!+dl zQH2WavB4OIl1Ja>8J95a67x}fw1|xZgA{cJ{@95cBAtpOSYNo;jkl#(M4j+#*(aclw+j5JG2A(7g$Wq2wlnJiMX%T-QwR$Zk zwHCgRv#>^eT^#-X3FjBiXwZSo2NQYr04Oyde0}|vq!%L$1mNQbVb1}ZL>C( zfFDnV1DF#YrSTSQFQ#9>_cmo>&%|P8VZ{^(YwJ#Z$-V>jVU%1dpS>d7XFlA8Op`@( zuhN`=MMcijDO5lJIaP%?0Jtv=c?<0CwpBkn2eU%Ym&c{1vqMbkRxo`!PrSi_J?G0^ zq_qsHS2Zb`pf@(b zM4xDLzOY+Tr^;{HxVAISduk~fIZufH#wL6Nyg%j@*}!9%9REyP(XOUYl;p8O9l6jU zjwFE&=O+SOCzUMvdHdIubA?n8mWJX}ao$n+3-*K|;B*q}L@FIL5kAR$#c!6Tt#Th12xB?%G{=QRCvL$}I zk7*Y+lgl5H`8w`xS9^~}ZTKTJ-&yyF$~OrukN&Cx*={5qzV{|ASR#av@p@5K#^@OD zWI6P;%Fp&v8N42QBDL19$dtJ5j_nLjaJHw!i%0Sti}8J2sq-jlEXFR3<0@}uQMv$;V%_Rr$ z@Ycw^I#(!E{VnB8&c%s}T(Ide-&VzAo5>P+aRmgR={dF?z8&hy+iVE7_XgizireLYoSbeEF$nh-`F%M28{oK!pz9RdEu zo;dKa*k)^ceB@Xj2X7sB#xBNdz!qOc89j!j)Vv;U9-g>mu&=&Hp}ne`Dy$cv;+R9R zz0?FMQdN&qN3w#%mIV>ZUSc&5zP zwxLxFW;GW5v>q^noC2>EJrhDbIfPW)!Z47Uqm>W?+AD=(esIJ!=6q*>ziF9#Qy2!S-|}i@^^p(i{yVuI-0;73?fw&l)=0v}{6)sPlg4 zdIQ`c4jv;!wOn$#Ro`Pi!bCv+RcG$r@>HvVjiViGeY`mkMNVLEY3Wk@uDyY+OiIgC zfToU3Y8N1CM#FT;hh~y1rY{R%{*Wn829_s+W{euGzq_ASa~Ec>wL{G@s5Nj-syvv4 z{qg88T6|sb8`4HKG0#VcCl`UE-69woB+d768=YT$!0LxfVr(9oBKg5<;1DjSAG}C^ zYyDVDl}zl8CM^Ymi^>oD&>BAm(ETbTiO0+KRLMg=gyS2Cv}NaUsOt?#v)e}I6B3ZQz7jR+Yi!^=Y&1=%@Bz)|{cYi$X!8}s$>)K39OK~;MTq+r=@X9gC1+D~H_-#t)E;*@(+7$I z3EC&#^v8Cs#tUEo-!dXnkyeVch{J1OO@2)0oAu2c zGE%mo$3wK8``~J!7u9~=xuozDR3E6XX;Gn%;Q~;q_-xiV@5ysNAufYiDQyG{$Wam_ zm&Je#Y)&@)R;-`4-?bNf+%Ao<32W$OZ)VvPsHI>rGiHzEj4+9mKSpv(*L;Tih7LKR zZQ#V0pUi!$y6^{x}c+(D%5+gAvN%kjRWx=}KsTtO|7et6Dj`7eY_I~jjx0hoRFQ}74 zB5w$&kjzFs7L(lJq;XuSN`^PyP;(eag)L#_ObBR3;Q?a3UBU-IR&%K6@xQ=OC{HT$ zowLE}jOSke1T`Arlkl~LQRqW=9$$;aY$Z?Gn0UPk6DdbJq8vq88zqC&wCu|xRJ?%5 z=Yd5L4Hv&S+M`$Sq!GL9;ZCA!3qKCjtVS~n4BatHX?YP5vC()o2R4b2Fm-(vxfH2w zOVtd2BNoE}48(j%zj^HTeXvO#f)Y}Pv-BP6dIsx|?^BRZA?n2jSI@@qh2 zTLh1f*gTZioGTQT7x3;_Kfl00XAkl4^_KI!cSI}-Ht4a%_Wn2kF(`X0(LL%!iF5n& zs>m|KJgN#xZ+fH)gHQ#J1vBEPJY%KIi&CM9jmyMGbC|f%QJW7HlLGpId3YgM8iW%^5j~x ztJ+=RJ=BB9<78`W2|Jd+gdQ4uAzc_B2A`NQ;uGeGd(EQ_smJMweu-Z$&k6%e=MlXw7pz!1um8zCN<=}CEtEcJ^0k$zV`(0RdI!G(-Cbw zshBhntPT&+(gvF_Xu!^{Y;yO#z)uLD=Tp%c5|e!ugg#kyyOOSej6DR`d3?anbvbR1 zYimuGBN-&&o63Qh>Bv9uMH*O86UTvXMLDyD+ zdEZmtC%d$U9-rl0$L^DG1XmU$w1@2qj`-5S7r|p!5(HyYxMw6Pc>7OzN7Ri8W~sB% zN=0a>@in8~e!TT9X$QG5{dgI)5h7Xm%Jz_QLRrCS*@2T;rN+4MMen|i-PoSw;)i)Y zJ%%L@+;oWEyZ7KTOYg}`dMRRY3?1Aj>>mx^wRKi6-kODO?N929xB3r#$$HoK0u;~|HlN0cItR;*QAw$ojS}Mu> zezvW2J~k|F2(H3}GnZx8wR@x^BXufdZQoS`VrYM_>dB%obV_0HtEcl6#3(85=E+qp^LFC?Ryx2Fho&aiPAK+75q(R0`(&XFa6zvmDOB=aUpHN6-`E&X!N3KKj5S#J z*pdq&a0uG6GU_ML)6s&lwv({qrzg7EF%0lJX3?&5_y-I@A7p)~b#lIot7az{Y&xE9 ze%>@i9zSkF(BApTsb(?6PYq!b<%y<7bNuZh`M?yYxc+7_#XbVc)P?1=SBL#{dHyhd z8z{}kBsH0wdnPG_%t_|mBDUQ6meK&UX7t`>x!PMs4T(z*CUH}rWa=l~fzt$00a{*b zKpPOp{@_O!gQEvkQ+Ds=lmocg$|OkG zbE*N|?N;HwZ)b^UX6^&vkL{KF*H&ch6Aw&|Y3{+2w=bKw>b<}1u63KgnGy2RlRkI6 zkl-_YnJ0c!X$`%b*EYt1xgJ6xHrA73(6am1$W&cWq)kB0cWk$_wnO!7G#9|SNcd0IV|xCDv5ZkpS^j?LlC}664Mk?S(H=(dSXjNlNa09)}ud+ zKFN}lBEpW#A~M>D?9ppBRT*z@Q8b4*)melT8gZEBI5t9UI$=gT&92+-H1kOK1dq-o zuOpaN{d1ZcJU7;9SQk82n7}0ULYpc&wr^gVUXvt3`#8SH==mT@MQn8Y6jLLhYxAke zk`KY*9^}<~&KeaqzfX6MWbYoQfJv@7f7nYti@A>%ce;p)p)d3R zUk_|78az3k6OHA*fmddD(4G~%Jr(1#-QatFC+`TJrb;*59<-t9@xFE&O|4Q%hHYyP z(c%j18yph&nq(W&AyS4Nu7i*r=lA`1t@{RbV&bZ@LDzU$@e#d53~wJj}Zo0UF@tN=7rhL;w>Z}PL?#+*!D`JcSt~I7a)sQk18fLnE3UO5?4Wr7l$VuDi z0l7bSj@CY$ut0Jie|Nbj)ml!{qaq$2`1Eyqgm)Wk`?hepzt47_tTB1??s`g6U}6NlV-Z3idSbnDMlFix(&@0yAMge? zQ@BC^2SE704>4m7T`bBQ(;ueGWpTzr4;mjQeK0b$-nF-lZ)s4RG}B3DB#_e8BgUE= z;9KMPiLCT-LMi#}CLk~GWDTy3Q;G2m?uUqAcwtE)el!ubR;~7kVVr^wcI_I_cq(IX zhy(=n?V|-oiIn+xKTJ6@i%)K6q_|kqeJ>n2k=w<>+-;DSsc~Tc+6i zQ}+u%fhJ*;wK+=}ApY=jY9QLC*Lp{;HoaGGwU9-Cr1S%=xsEqtMJb(Kjs_Rs2BtO% z*esLqAq5R*Z##HARAx2RmfDOB($!vjBP9`{;bX;TnmuI!n7d>O$QsYN%tIZUaAdgZ z)S%G|j+tT(fK3c4*+8CIUb07jub@K!K}9<7fnq$MhG z!$uK3gpmf@dt>wAZL3w{pIEv4No(~_W9#iO9n6UvE?eYd#IxSK?=v~#F_p2HsN5JV z5Ojpj=Z9H%SK==NCa|&cPkWy&0$n^}L?C3#AChz{hPc%|X;;?*HPgE(5Ivm69ZLfh zJK78z4pH_R(=D?F*vuln#Q#f>ZJe=fa=)-D4Phxs;ETBeX)B#$z+x(8gr} z4kFC18mr_>if7#S&4xZ(eqLB+BQM^hc%rY$IjHIC%$Igo+fM0IVqO896))dAWPsZv z+)RNLaK75Rk}h^(?OI9mB^;riLES2@9{Cd%#@mGr7u@>kLDu{3pm0);j*WMILrUns=nWyWvLV}V zsS%I$noZeM_~RD*nLGL7QAz3z=UXzmWcBIW=&c8W@d3Lb=oq75`n8Anl`}Sd8*wf` znpqtYlE4Lq-xbw0`f4@WTVc`n8mq%=W$ZMQj>_L?OJDAxtBMZwKZ;{U^J9_sO)`Q4 zW6AxG@2&(>BYTpAzS)cG1{?I`@^Hug9a}r&%6O}gGK3}f!`X$B`l?p7yly9Vv}5bo zyC2)&lJ5qEYMS|rgEgL1woW022Iz8-OHrCRNc}|AD#6y#0k#S@S41;@O_QChJEn?_ z>3eMBe8~+w`h>k==kSj=ll_RH=CJ~#kV5wcL1XeM_eGHdobaT%PvuCoxQ4AjTT-2_ z>#`MpxPq7zVr1EeBQFMk?DEU0pgR;u)zX0dQskT;1#H7WskN7ZTtD1Qo7Qdy)QwX;38E(=PD;Jl>#6LIh*~+ZeFSeEad)qdj`?i zuUjyhKqx-nb5EzIWrSxhP z_K4aLV~m~Cdu)B`(3lcdITm~?jg4IO`=lS$;n2=2+LOOrH#K9X{ww6$t!GZK;zB@WC9!V3k;4&m5vV4La5(ulWJp>GFq0w*7 zF6oFJLoM z9|mnol6P9XpE9ol=!)AbRT@cZFu)vrEw6nD)3xrX@h}o3)?5dHx%i6mJso+Ad}0JE zj$BQuUiuob@gonC&2J8Pli&Hran5k`ly?w4hH=K#ZZ?{TP`_9fMWIY_R(hL7{g_oD zZ$KNDBrOJw?X?~&;n|Nkq>b|4_Ag*rm`lbi$HTs^oDD(|nk|KTQnOT;6RecwJ!~U< zKH~VQY2G}!=!9!H6k=1SSQ6@$1Zigy4t$XA%qvwhy0>^cc+DR9E7a)6)hzzAFZ_f+ z$x-cwza8c1Ke|nEK<%E7XE(C?pI71hGQ7pwOEh)fn3@0Y6^NO|G+Aa zsT3QmOD~vx<#EyRzL`m|N1k1#1g?um-@7z>emw($T-LW+NqR3$$hp=l;&Z-DjZNHp zi_)>|5t_=?0G?OeQ`$54Ajmq&5|2NfN{wX3ukHS%&Ud=|g52wiozoTLF>?nO*3*lR4GQGL{4*OX~us=`+{Px(Yk|z57 zq?t6aFl2oFjCh}TUl~2v3;kW6Qbdtj86i@ozm2x>Dw72+dN>PA^>-<|(V!l)OnIb< zfq}7PwbF-{pw52k0V#$n37FQbyVN^9&ExY>(knN>sE;Khg2 zfLq<`(J?}eaX9|bzqrQtX-8PSys`F5`c}q%xGbCT?Zsz|ju7UJa{YG|fsZnNP>J|B z`r$@TMZ>{Z8GVL)jFAyQXEd8^Z$Xy6F5mTqes#o8)-yOrmqxL11re;9lXGX0=@}|w zy)(h@B{saG$`<#-R*x>HtKfQ(ayWNO3RM_!0`J3955x~l-oVl#aWH-)WxR*`wZoIk zc2GyNA0Bz@A4OUyHVzr`-CDt|tj6U0$WiJG&E&^?6TM>dOPZzL8G@hM4%Eb$-iP3& zObS#=!-B`e>uhboWim;`4Q))U?F^^yOzLe88^C;OVJU=sXa|LYqn~p`UI;y?LXbk} zPco3hE)@A|Wn=DZxN@JLJt8^!V^89@WPXy&4Z>ttxOD}lQb$l#(gp`{AW0BJB&nX4sHm`BRRWah*UK(xJ- zST?|7Kuun~??vCI!Ypb?`UUfpLEyutpfULGjiPe2n{M>s^ryssm+<-4ZX?x*Q@Ljhn3A*8+ z+mQF#Knfz!ECuclftajRN zOENvZ$LRR>+9(_q%%ZJ`Ia0(lcZ#GC=(w5`2v6K1e)-yuEPUmi^M%vGHfvfEj|($Z z)CUTy=5PK|zTCx)MsL^gG_!XhLc#@3sJ6;z+im-giEsIL z%&o`k>rJ853h5J{A45F)e0D#HtSPC4JrvISSDGv&@Rt zZmFCps!^pvDvDf(#mA=z3;a>4t8Kw&jZ-nWAzewBDD;&BLRZid*|gCXFWC2pIm1$IE9{)6LbLk!*&qmWIjB+yp3@7U#JcPcYPNW&}BN z_J%iMU-TB^Ywf;ismz6-)TQ7fU?9eqqSS9&%|4cUd1*9umvfUzALqE#)|I@>iJ9sm zf@{+abJNW}Eo0RLwaUQEwE{{+K(Ae#hNTOpgqu^bN=pJzM)zpjJ z)Kc<7_i7?83uDlCA1`8JVy05S*c0KSb6y|n|!}#tg zxiEh~Z5XXmuIcqXRz*mVUU-*05$~kT?`|jxc(ktS_Z)ZGqzp!IQUjy&fCnU>rLvx3 z1-CmM#&n|s|9!*L__lZe|Yb{55N#<&CQ4+kz&0yYqK2ytK;S9iO?-yB*0m}rC zw|6~=t{I+T3c-FUEsL9UP5Hu|($}+{WN?jqsg_Vz2!&z;dC%Kig92|C+D%r+G&E}Q zjQM_TEWu{%FnF8I0*Qtp#@)k~Ew zx6~ieUxcWOhZ3fF9?eWk5yL1(;;2WKbMD%hg7HY%FZxOz4*JRFCwNo?MoZ(1GQmXS zS(FrU=sAKvR4E5Q(HYYT|eChnh$LLRJfsdsz z$?pvLT&58Qg2d1RAAw78T6_-uj=sseuE7s0h6NKi3;*33!WIo2j(s-e^^(oY{xhql zLUv6)UQ33-i%?tVGf5sl0h<-#WTjq-7fC!s(e=w$LZL^ny zpW$}{vObiw6~N4p-O-~93)@M+i)0%V@+GMHGJFF1Xu;SQBSuU$6K+R)kAK~OxPNQ+ zSANq_QaZ{S6K;YfI6XC5R;v59ATxZ(@L(P@%z8%*bB2Y9RZGn`VZvqx10V1n_ZJTU zF;ml^DGjFA!r3zlKpQa?(tYMQ9qV|Oc=Pj12=Cv3=PWwJ33`I*u`tLF7dRa#kqRa(VsXk_)4rlz zvlT%s%X2&^*^#Z|Q@a|=-OT8WFjbtKiQ+z2EhjR)GsL9O9CG z{%KU%$XOnY)eb!lZQXpqM5mm8OzrIe9MMg5MggY{Aye8R0-Qd{qf3OwZ&l|W-M_A<=3?CCj`q5 z2L#EdQ=mnSdZ&h1W$OmHEDD|tOJTrZAuAmaNum`1Ui7FZ&~16^YJ525H^*@SVS{6F zt~_f}a<(;d#m{oz&6E`lV}@A%CQc^a173U-^!p1Owo0(rFtn33TigDWe)Rw|=}XN0 zxlHC2j_PNzaTtoNOtm3P??Oh(Axj&VAk3vr&8q!|qvbQDECffX`-rfvT=ON4ZW7LS zklj$BU_Qj^(L~|V(C2=15Lgp8l^hamR3bc^AsXE4;!+B1WPtJsk;J9(9{P}>fLDhh zsFO+hHq5vC*uC6f6HL9rG~1!jNB7tdBg#&c%=!ju5FJV+^(y6-1`lz=iI_#V962(n z2RfGed|k?}dzYoL#X>;Cn)|#CA(wwV7;*sQw_F{*$b%p_0~s#&`Aq zJc+e}O06H?t3r=#4>duQi6bEpWiMTyQYu}suL%+bmKU8A{&|1b7=8SvNj#~ z8T~D^#`#=CT?-I@c=g!V`Q8xjPO0qmIQo)vD4d3ZB{NF9(8=U`d?P?xS(G^{JOL3?b%RzfP|@S zMlE8=VAWVjm=cYVd14YPnUpLry`L29Up$V#pP0w41MopFQoKE1&+E-w_oHX8(V%6KoIK?iW4@{}=gQahtS;er zS&BIOa;U_@?LY?^5U&j!HJjcT zUiz9P1rzlw5#Ty&aw0xJdzy!61%^<%D*-P7lgL-N=9Mw)D_RM!$3w_=k27ofv8Bx2 z-gKh8TgJAJ?6SlBop_%fe44T`0^exUBD5o@8po?Wsj=Zr{=nR?pzWIi=ueOX&6%oS zOfQneJO7a5HMtlNvm+0r0MU(litw+Ip}2vjrU- zF(D0%7B!7Vxebf-Cf^fqY@DJB`YdOQh6eAxm-OeO`3Fs!4o{6JNf8{D!I9!)?q1NI zVI`qpAV(A5Aj{FN0c1MDBFkWio|S6tu$v_2G-9y<2a`#UBuP#q>Gm#W3WkKaSQy2J zj0Mqu<%CiQuUeUk2s7H3rSbITOv6Ek5RlvBSK=`s3^2J+jXMqy0P>-*=Acb8dfsv0 zyyTS)B1ZOOs|zzGL8oaGbUw+COMo9-MoZoY87#~zxmI32`2JqL?2f?Z$;EPeNB%4+ z`BfF)0es2%D$FH($aVy!)>lG+c~JCZEO6PNvzix%4CgD54>g-!6^zckwR!{Bp|Nsz ztzW6&Zj-hS;(4;Ky`HJrsEFsqi`~iBDFBdrTjZM&SQqNiA{bSJ#33I~b9c?~4cAJF zBdk;93rtW+WVW-BTEdj{_w&0#JrxCo1q}ehK8%O1meZ}f68hHf%|tU0-)^;s7fWXW z;$P886*+m${{FKg1i=*CJQPpSr$erA>Fw(Y0$0g=1Xqtgy$B_zLQvd!AMT2JUV;L; zg94}wW%N|#$H7V~t@6`sBed?4R9XW7uu;5fB$R%?{pd=0=A`)zE^&;LS}|oJCRt!- zHQQoTeT8-=!=!V;SW4!|)&MMCCnY$FpfSdk4EM6x={jKsEvTe}FAsDcJwLvbN%NBo^5 z5+ri9h-YVzss5_wz`ss9lXHY8_r4`jMVV4YG7{I|!NA30{k520FiEC~ikucUeQrtS z2goMD6gEw6?vsC~k6BvVn_tAoLCH1`hG&&|Adqe{`lU#}`6}W; z8y*0UzllG~M|lL`g$T&4DL6{X$5Ie)hs#OQVize=n=+PEk7W0bGB&N-4<_Jq^nkf# zS5oM|LhcF`+H5f$AY(9#2YiLM<+6RM$1Oe?5xkbK@~atlktJr&8GP`k)PEk}$AiMC zTVD$B-Q9?*kXcCVe6x}?m9x7@_mCHQ`Dy^s(Q*#G+M1HiC(h?7Hcv; zESPGv2F~enyRJejWaZlhz8O`S=j;M-xSDsD$GLJz=~_I?7@C1_Qhd1rK4`=>sZo)9 zY_m)Nz)qq^SYqm%XR&sQ8DJ16EWJ+KID9R%;Qjoy zbk?fVVlLjF&A2NJzG|il7eCsIx4hMDpkrd+#zL{id;50&JnMIP9oqCQ5|ga~^pJ$V z(I&bMrcd(Eti9JyVt|*MGu*cn)?a`W;p$)=XtLN)tH>TNYIeSSEUCA)pZ<)3Mwp@p zxNXuUq#L5ISHri>n5TI>n2I;dmLs&0f3BS34!@#yeTy-NpeDDI-QAF?BPWh*1fD!X0$}z}bO&m2oh64nzZy*=iO(z-!lKe)+xBmcw zj9#0CoYY3c=hE_iNG*W{NlJu3-ZF3fVq47Fz=PrhU4JaO&c^w?W#=Lh4m_SzIuQ}w zQrskIoPUe2YFO1A9$Ep|ZQ{pZRI5{9taEN*{Lj=P{##mb8qnaef;?az;1bF+9huE0 z=B~lEUO|@)Zvs$QSj7xV-#FlJOn^l^K@TZoJ`AtZosGvXXaBm@hNixh?T&FX1wSpc z`p_V^p&&I{((jSV1rrMJ;DH^?;4dO;Pag#9S%UskGwDY7H^)T{K765$KPet9qDMB>v`*(pnzrh>o;?F^oQ_?hr0)PM z;=bcCreS7oZt3``!aBR{pRQpjrc_!fU|O0AkGwEewDtEFIWV;tteMDxT|Urq2|yDc zGuel|SF|4}eG3XhE7{Y{JV^v!zM##U^Q$n28+lzxi_Y@+etrPNhCCH_NQb_vEMSMv z#Y@IYU|{LnNVLkiWUXblPO4bmiU;jsCac zn|(W~|EZo|2D`e$Lw4_qi9^z9+McfxaT>Z1=enSy%1W`(E}!HXNEV}3@|LvN;+Iof zz|IDig%J6)X5K_!0#h(`p_&yoP*aR2!SEf9o!WDEq^<--5!MNYU|sj>qYY8I@ErkV zr5SDW@sMw?oOV6XV5r-w_SMP-k(1*q7D6A?%|pl?;`%;vK;5d?X7OX&woxrf%AdCE z+Tzs>wgMc7G4hN&>;yicV{sxHB9 zLG$f?pt<#|>7@J8gnZRua?S3J_iC{DhVwy7LhGol%!Y`Dc4L8Il|}EISs^<{1k1q` zV{WU9C48y)d@w%!(CG3M>5b*!UX&lpYOo&oOkl2(Ux43Cif(||0if^KS42O4)*aFt zoJ30s+-&JMW|91+$3t9?d5_HGIhf{PnD!aU0h%vF^{JZ>n%EdbA9!kRD6oLg%vvzJye|yWmAf0IhL9SSY zYW@MxW5f900H&|R%C_1NI)_wma`UszdfotJp#!; zsxW<^_kUL7V@!G_n8c>MO)(r;q(8N`r1*D z6@Uu;`gx&*_9%z6=v+e&jG<$$th2w*44f|`^nMb%U1-1^ZcD&wgS8-8wy?_9;zCYh zpcS~Tn!K8EW}DFq4^4-m*NRePxws2QXL_F|VkYpfmY_rwNWc)$mRa0$Pd)UKob|Az zMavdHHX!UqN(PaoMo*i=^AfgqH;gsVp?({+1J} z%{wy`*VD@}zVgV&Y|SOYT{oqpK1YtkXG>RveBLf0WfF^hc5XM~hu%-k`;lfJZ z1(s8fgW%9+nKb)cO6&V%BGxvZCGhv6I z0oF&gm%KB2(?5geV-L&wi;fxilc0~Qv76$kyl0KX4)Bk^uQXNjaXdCTm;APrXYM!X z>F6OOZ-!Qk>U27{UTU>YT9wLs_H6DsDoF-N13- zlwc3Y_Pt}DL#asxCC04%eqY3WPHssk;1U6gaCbZm4Yziw{P zfGT>Y<(8Pzk7q1})dRkZE`8-*LgYS?`FCWMgQ@zR-P0^!_L4-HqqQ>flhb}j6Hrj9 zWqV*btsYaJ)$Z;lt~tuE#9aiIRni_LqaM?tff)@-j!u?s1UBderX6|f6c>%RZPo>* zrW`RrB{Dhz$6#+CZ@EOTGRa)XE@DCZFSTm8gv*4S0amcU0R5RX(v7>s9H< z^1o;crmT^40LC`*nRcVei*{9cLO!DyFV%;KTuGZ+Q{HtYJ2_=F+FmE+v6EAqGFX<~ zKHE=`B$x`y0CP!>W2YSdJmcV=&_`rB3FYY|KlBC1`I7OUiRLlxV76@nkUETcTmd;3 zK$QnRF?qmG9cqoHQebBVN(nes9CP3JRtL_O(>K}(dgk_^ZV!>7U)h(!;VCH+fvqpo zs9ZIomXp@?#{@*hSkPzNzis&Ykn?qnSK^7;v;fNnZ+Xn5hll>~A0mAc>wRH8`xVsl zi@N6)VuHByTVkEjPXHaUYEbhz-LPyZAr83`ei%@GB)^CvFO(*jtEl&*lyN$ z3bP%GDU-IaPHbSEi5<3Z!uZ?C%y6ZX3&CUY9j$96#1DcJnK8c0yi-90n-ek~O6J?K zHl#RHTfLZH&;T)j2XpeZ;`5pKtsXPm82>y{)8o3=Z|xJU!S0lT#E~+$!_<+v;%yb! zIss{L^FkCscbhtVb4LRr6d}jIbtuMIUNQaI_hAEVMvUR1N1=?46Uacgykl+w`S>_3GDRF+Eai8^j%Ae+$sC`pq*qg1C-K%rRd$q z-J)^bW5I;yL+J^X~#w zE8yMVJoPi~ch6aC8a{nuY8*kxfArq}W3`v3?5u8vHXXGS?Q!3Pe|c#&(rim5j1q}f zGZ+$Y7w*fDRUgjqP{2?sw6; z4pA#EN*Le|JYC7uS4#ocYYvhzz&S`SGYfC-9f zV{>uqCdT;vrQ)Ps0xtNK=w;gf4D%DHf0U&>_^-p^WT(jC`K1&E!M zzU}vNT*j|_Ier;$-xEOt2Jz4JcML-3niCrWtO`Lbw%=lH0r%sM`=Ez|zO0A{Ued2HVTEtLTJy?OK|@S2paZnl?!gbYr3&~aHMDL&=%Qa7ErBcSW%mPmk$DJ5{$kEbw~D-`)I3MJ#8gIGT~* z(zA6Yfbw%aw<-GwAvLWl7;1ycjks1q?1)eiF@@emaS;kMT88QJU%&8ubZi2-H^9lh z2W!dR7$|l?5OabWXuEXk03N@B)|DY^Z=_!E`%z*7Ag1rEMz6QSCPg2Xod2O(O&8^Qql82c|rbJtGy##oed&sPm*# zbEM3{t$0N_%^NWI7&LJSqruZNA|fwh+YfB+1g+zKGw^+6>vQMtfBTK(@*DV8k7#dD zd?d#UHw1Ck5f-zQ#ho?3ef7!*J)?R1@8P}(qRUoYkF(?6-1Gpn zLqa@|gv^$a{KG*qzod2iL)Q=%y@QOsby~Wm?1ncvA9^k6R96vERb6focPr{;k|TX% z`|J=rIi?@7HD!M10)>~XZMi^%-3(^6L#y@dT=$WWeGX$}8~QYef)By5k)ijaxCx|x zvO%Z9T&5x$c?AW|9Y`(B5$-IXr4^mvr-JZ!JQ#Ptx<^G6Rmet+dSWkE0nX&N=fbOu zLlzY|7RA{e3(Au65io3#f6^&`<}a3tu=&AN05-a)7k;4ima&1N#nK}N7JE#7Lb#MC z*|&``&i)30-n`o1KU1cl`c)UhU!Ph7(klPlK*`nO-$@HaC{l14oRpaQ1C;>7)h zj?k1=?Mj+B>3)Y}gA1Pf{L`kTdH%GEF0$B4fM@8RsAuIQk3NY_`$&wS&XZC}JF0Vn zg^Dk6px3c|(;Qg6H$8`nDz*2s(d`N$|*w@uqD!TOIuVvMbWI>Aj2?bVgv2Q54xS z(=t|UM0qhHBV!djn8xYyaq#i2CQa;w2>Yqo^H(5Pn*{hU`k0z&2kho9K1d76DB@?(1n^NAR!Q0Z$rq|k^bR%5@7ng+rf|01P)(UVlxgfcD- z%_B<85!5?B$m}9iQRz)0^>#HV^S!txn>DrackBcWg*JYZarq++d1+Et$q7Qi!LDU< zb7qZ?4^nQ0f8%)om#UTcB9)UE`TJTEB3UZ3k}29$(gk_;(YOU&PIa_Hs zfc#+MYB=|zln9>Qek9Czj2(AGV#W31Se8LS9C>rJz~@&9ux#~dmn{c*>4CL2Ux$5H z?MiFbSps%KKgRVN28p$gAO8UJqG&JG6)>#_7*>Kjyu{_maU{6+APe%)562VC{Cq=Q zH#!@LyA*DV{9f5?@gl|%!Ufu+U;JxdZg0h5TY4O0#2O1FqjDvIN%m;U_@5C+{NE=i zTlPug7=PlhQlgrzPywtLe#Wt5$TAadcP)a;sxZ!>E^v1oY1@zu*tKAdq{35QyzuK$ zuE^OzXz_YNp2OSD%21X|Ur-IIBO(hKY4j$&im*aRnu;wOlnCwKHRoZpx3H*eoy1X& zTlepoenoe;kCe1ja85{z^9LNfJZOT&r%Xzxs5-?waPgWw41W_VRoai>5+xWU3l{9| zHm!WOtnLsT5U@|u^+nckH*vbjv)+%NCBp_H#rGPH-po169%b>2Rmxg?duLkKv1|RQv^!6Qsmfl%%Xjn~r zP;6=GCd`;QhtPW!6o8`uKL|Y@!RHK%lu+jQDPmCmxlw7PYz#>V#@^2nrGB~ zKfvg&;a3LF1C^Ix1zmiNIaglL1*R+VOfk6YwWUTW>tXJyKF? zec8mXHYzP4kXvl9nP@H^@cG7Qd|{pp_C12^MM9`tHi>A0D$jq#OuDNmU^Q5`)Qd@oW`6u zlnHuH<3wOoh(b{0`+ncCf{I`7Lx56;Zct9#;0~xt_K;uR+I%N9j>SGXgF0R&Pe&f} z51?^N)P$_G?u#Oc+2A;~^a!ndARN-?0G`^0F@-A}&w|ylGzzWAd1~feo>_JuY2Jy4#l9tq?lQ9RE#vbQh@m#leskdW_8Ke9ba6+}CG|dd zphQ5IIDMnSybN}%wlyWHZ9!h(xzTZ`S;l~Z@7@e(R1$!39EvG4%39z`VVRdF5Aj)q z1-(r!xM>x&*JWffm`d9Oh@S(^-zoe$;`AwVbicx5ZV>?Xkvy)2*?Zi&i6!Ik1}WoCyr4@8FXaB9Wkn(c!6zijO`F*Q8rnM8<7SWO`dRr2s7@_1=#mc4U4~$3g#^_VR;T|*uWs5;M z*fZ0&#MJb5S|T6u)oj4Q*6%Z(38m^vFR{1lq*_<9v&A9(#3_RtV!y`oi;)l2`!34k zRx<3yuc(~y7%TZQ={JN%G4vh$0OfgMMW4P;d~5fiG{q;X2{#E&IU^AOvKm08W)ST$ zB9}LIPba7~Db#jtd49*)A#05vH>CPY-5UFh>?wb&f&=8h*Tz%PkM9WYif zM{OB&()y`76b%ogO%#f0y|hYd4IM3mrEvB3jkCuC0v9AU z8)0J*wf5nd`JGbY@3uC27PQt z5zhS3t>aZe$31{85LScK)Oyu?!ip~w#Uh1x@xkCs!0?1exm3KDT#lhq@_6xd1)#%3mg%!Nc?fgAB?5P zVx`*9016!vQ}IFbmxijFo%ND|>^`G#u7*@_qvyzfl1BS7y z->EkajPEfg2LP^+%+-%#z8iSQ$ME;8stD+2g`3gaqj(}AmTYZP-e<_^XvNdpHW-3P zX_ip_1j}$NTLV@YIh7_&FYJSa{J{)MqDVYJOe-iuEIJUy1zD8s3QJGCPK$wWI2EKe zeOw<}WNwHb1UGm&E>mBF`yJ-C1>BAyY{R7R+;{(!w1n)kXTgs_c7_C#FV4@DRG^?+NV9hstPau%JpoJt~iTuT7w5mmBUE=79{< zE&wrn4=WbQwyz;Td)Ul2l8Qz;0rMMK<4}ez!rv5| z9jJCVJ7<^|fT{WOtB8jd`+I&DdzG;B7+b@X(2Jl<^Cs^&b|RlT!T=2<5swEhGa1Th z$@kz>Kw<6N8=VVZOeqG|-?F10KD6TlaR|ttG>|E` zs~Hd0^p03n*?)l{N;LL4VodN!w)zZ{K@XRywlURc-H2tmo$*0Fc3dlUtLzcf?#& zql$4Bfx{#h|d8Yzv+Fm-=izMxB|75_Kl(^v2F?#lCHC5EK&Y@!>1hw zDM$Jg@|&yY$l;MdJHO-gO?(F=)uOK>1qYtiMV#8we#>lLVj^!k zLMK+7n!p4IjmUuDq&&;#2Idt_+6>?C0d=J5x!2{JO{jgjY$H-h0;k_Gkj#R#Hu#P> z_xv#8m$=N%TD*H;Tj9047}!7hkl54@UsN2BzRFC1N$CBS`J}Un(4LYc`sQ>5puV!2 z*iYdSPqWTMCOq*bc}>$p=D)*Un+!EWE%Vd{8M@hjknDveBLKVy>f!b1-hKo8@V3vA z+93KW1UcNzzSv!SO4$} zH`cs{_%Z6Le5HE2ou`%5aM}QJBeHkYnj9Mfu#CyJ$ewLFgb%`o?0q{QfQ@|N4~6 z0jyc_>uR9AX+5Qt!v=pUjK(hw1NDkaXMZY$(Ga z_$#G?P8Qh!NpIr2s0}Kg_UweKxol(>vr!p1@89zVvV!R zgsvb`2CQR|W#YT`*=uR8*M)47qcZ`(@1dB^`z0CUX5=HU+Q!bHI#C^LPR`&e_+ZIU z>hB)(iv?D?f>i^z41cCl=}bkTe$;{7`fay(`FZT3!i_~I&1`sDoO^571V;)aoJ-(} z*#!ySY&s*N-^q}2mQKn8j3S_jr778F@(<1d@L(`x&b zv+3pc*Ee(TFba+|FJSLVN_g38aOm;u({+_J*|R~C<9$9Whk>4d=V#Qzn$zfd2Z5#F zd4wL`AYr?XefNc&56olBIpXX7W$-ln+mx^eL7j$K^R)33+WFlBnoHD}jH!ojaa5xk zvS^%FgZqm$I6a*qvfdlgnpKztIL%|ZL(w7dIqlyeMxDEq(W+eG&?Mfw^q&pZ39q|l zZ!Dg@eO|)pfx;L}h67MtPr-dd8#6BKatNB+Be&375V_jh)nBwH0XdJ+?~34GlyHi+*=lcoSHy3WgH~G z(PVx6C4FZp*smZ9+NuMTYZxO!%(Yo%RtTd}u_{(%Ns^3^=!*ojy=0u-mgt7gir?WU zIN#eu0J+s^I5lS_;%OJd5DC^O6(VI)WQ`}JYfgH1eJ1FmRbOHnuu@G9Dg&iAK<7x( zyz`91lU#|ZezttC!yV(J%%gLtG*VMHQz8=wCYULyH$E|OFakil2HfjoDk3(S$AQ_q zW^fLw5G6TSzAkyB-nU5JxdU#@FU^$nk}$FN(Itz*-ubhYsB9s1PR3go;(YgqewtJ{LU=5XMU$ zmz209n-g!kNXp__3!FKmMQQ|8&89LmZvDNZg}4SZVoz)pdLf48@FMCMK)ae*Hab|e z1EB!&_sy)btbLf+FP?Z4qU#o6FrMhQaex@b?Ue@JNIkAc;j&6V|N3))K5OGVkm!Oa z`c;GxZ~>${6NN$T7|PYIpY3 z4O7Nkantw}Y$vvm2x75Adji~l^DjFJF?|AKfwqsF;EaPD^yOvRZXVxNYD~?Pqzw&2 zS0lkSw;pZ59qk5dzBFtLMe$cR(Eu?2{8y91iSwrxzOxD1DfNsYtAeP)i4oHto8{W(s| z1}~bxojBlpkcM#@F+zG(mS0C~4y)~(n$kZ*^|rSUUwS_IulFnpfd-=f_9~d1$>2EN zc5g(yLyY%H>tu%?;q+UPBRUtP`YfNvN9*Qrr%Vf9Rt9#2#$rPUcczFb<;0yqmCSac z5^yKw?;&!zvL_{UqO%14?cKPb`Z#P5VDKjRCKcP+tSI`H^STr!mmeL>xo`jAQv}4e zaT^y*j(-L%?4tm1!rDBBz~x!v^KefnYw-mFw4emQ2c>-b0T@dpf zQ8Z?7$yOkIV}7LnzB%u+lvPt`xEl`x>CwdVfQSL)Xe++L=kg)YF9sI4SX2_tqL^mD zTBP>KGDT3nvOsE`(rPbA zgo8ZX!?24aZMUQt`az2GwwRBTN~^JUU|iw3PS$F(pgft9_(v}_3`P|Ef|22PHXn&& zrPww~aRe{A7=|esp%ZM+sVeezDxqP-`M0(UNX>IF5;^q1W~t_Hat^POryiAqoy2tmf!7M>o|A5mgXy{HOKHn z2CCqOFfpm>nn%he%f1?X1@|jI;y&qLy}-J`F4Twfn72pCD*D&ezw?;xJ0Gt7@UD{X z?^J6}ANkr$Gg4&dBO{JTl@S0W^AN)(jz*0YZoXepNHGF*${1s+6376xqd`VXQaaSD z;SV?S086LW^kfIHchj0O;DeLT-!QzK$lR&Y-*B8ZR7 z@Ez?~a@FD1=ASw067zTvwqVWgEyiZ{W&=^oXuf_s{32%r2e zsY)Bm`Nh@z9=;ZkehOv+5jlK=3x|sYSvO2!>8WrZp{lZ?(-B`hZYM7(lh{eVJVsJI zY6-;4zHVqJGvWiVrRUn)IS#T__{go1&Wy#^ROe$Djt^Bn(dL1Sz@E3liSKuVZV?Ku ztehCz-)>y1zpitz(?u)Mh8~REZwN8Dr!G zfr|~G1^eh2ayUd|!X&Zi0S@v+hoTfs9Gr2}rnHHpu@~ynExp+GUFEIR=~VB;= zOGqd*JA#bS`5puLtTIXC(=w_rlJ!Y7$HXN|)8D-yqtu{GIjtDT8;b8^8dqRg3dyci zJ?ep_qVlA-c+{96L!}xhAf)dO6ip(t1R5}U5d0!UvZS7VM9_A`n|Yw}{MAU+&5JrE z_KRQZ$TL9#ZTC9J)A$$OvyM${SQb9`y2^Ndc+qqFEY~r-ss_130?_=yA4)%L1|r#+ zcUP`K@jYy3*ZKTnDCUpRM7U~kpv)ptj@~vm*Y)Ltow6;SNiKNzp|Onsf`kPDuR{=M z%whmo@I_wCS4f!4bhCa3LN7qcdd$gOQbNSczBSxbHdub}1ARrF&|^BHs64SWMnom@ zgX6E+h;cr{B?xl z7PH{3HCqtrN3g3V@obk#zFqX%XW%C6bnf#!M%3 zjF=WR`?#dEEG81EPe~TLaV_6ROXqiho{X~&Q)xYh&1$m+B-8AMUNW?W-^iW8{314u zAhTesX+}}R6$4+4)VYl+YGb5arv`4hpOY1F4r7=^Yb2-WJ)c#kYodWi z8I*9Bjz-A5pXyZKx^V9x9-r2s!0(B_V=Y0Pq0pm9JCwg%%gFnt3YY=npdQO7a)^PZ zQDZxa2q>&fhVI~?b+k2D+FF(*5$V=lUzHGwB}WB7t#m{aG7#BQ2~iCY#{7C=I2uU@ zhl2eT#=m-IOWyw5^3+|+cizj(ZlNag!0D+%s=nsY2mIv{2<1PM_-)SCSXPqr)v-Zu zQjr~usr#JO$#||X!VZhKboQ(vVh;MW@jPazo@G_~g6eL4A?|Y(Qx$WHI-U=Eg0Y?6>lQLDWK}*4ZTSZh7b0prl@^h zfQj6f+LB|BeuqCm1ssd=@Ej0%A5v$&odf8OU>46AM+9wr$IA5)Ef4LjLOVEHpeIaU z+`-K72Oc(67^DXtNrDs8M}fg@3ZzD~zTn%f`L7KECAR<8k>zfeJ#-$}WQEFQk$w3w zr8dc$)kp4i5(?vec>ubPxev(G=_*m;HKM1@J@8yA7amxUHB^aYsk}leJ?nZ)McnMD zk>BoKvp)TMRG!O~K;Pu9%+N1r;uZOYLo)Ntw0^}YH4`*JFvYf{Fx~Qd{{3A$%S~Ci z0}F}Rt0k&6h6n^jF|b$Bvy??S)3whjR19M+3#kWyRz+h!F&Ou%1KQDdwe4WId3ZW+ zvZ&>F`zhevL=e8cZc_3|j3D5PR)s9Kh&?Agv0vf(z-0r5%mSc7S!^Lqm|am@c$OcH(UpuK z;Yj&@l2uvld+b@i2IOuVBH~IE z>a8^BpWC)cbOJC?BH+C5)3{-C%BV7I*Fe*$BXFPWNCNjbYH#4EYIHrS1_O$nL*F>p z(6{6X>8WF6zFQOS5$3+Y<(2KIoo=mG#H5Ce311&!%~z)gET`A+lkt3Nevxw@PGM2o|kJH_NN3{Wx^74raXitvO#xY92b2gR9Hm zJ)ykq*$pFO^mtxM$3slz^Gx2^&*4>K>Cu$%vRv^!&8jGedRfHHba$g_2M??tz(G^> zl^3OLBb{lG-9%wB#Ej4pkJ$>46DziCi8MM|pEk>i1KeH?pK*<+e&S1is_1J6DG2ig zZjn{^kocm)#Y`x@CSyX%;w= z=+Vw*yIUGaub%P4K5SPrtUOO&o@MUt%X*H-#tO^l&n!Hq^dMtI0SJ<3GiW8p@p|me zo8N?!O~3R!PL5?~<+qua`TqUyR6LOx1wc>o{+65};ba0sng?0rD0kF+KrIY4UCP4m8}YdQc(`R&1VE zR)=RdOzqLsM-iTnV6VXLG+^-!;|(N#i{9LvvwDVe`%GvcQpKklofRnN@xOGrHLqUIZ%t?w8qDq0~V`UfrEwRtcOvLBan_oKBNsOBpOy11rjCsnt`ITDv2m9t<=jzY>hU-OO$>_AEL}ayZKN z?Jwmd&%FCkk*Vx2h8@HasS*a^TlvnoVMF_F;qaj`tYQD{zv9Ol+C4R;G#)HH-X=5^ zAoK=Fl-&Nt^8{`u zHRWZy=(tOxJ{%Y+k08~hWo`PgBw#q1R4}W=+1>Kh2pjXW#H^;|B^C&VSF<-k8rJ9q ziR$SmX6l)RZqCh>jGP=Yc5{l_UfUgJ!c6kBlMgu}lt7rNS!~MRvrO<`K$HN3qSqUY zc1tDdC&0!2$4Vn-gUeRe$l%3WF|M2dlFcB8tJEwQXDhJSYG6nd<#vHFj4J8v*p|GW zkrnRu)5fv^OJIww7%Z)et*G)?30_{CyMlAYgzd0vvF5lCb%Tx^2cSrSI$}uzjZVSz zg9|ebcn2YxaEKb*X<}pFG%%_^klntqKQM#pOH;<+9M6+2B`%2U4=>VVf{7Cla9Yfl z<~)3g{98WEm{G9c5JajDE4J;yy}6hRYX%XbXw(;Dz@RW&OD{dt076e#rMZZ^5!jFm z^rESq_0H}0^-t={XxEzkmUsBc*1!$_t>*;d1B!}B1VF2j0m;8TVtEY$fBnyAlN(-E z!3UL}J8zv_^{rL+Dt>0i*xAQpfVe!4R8oSAr(kw|uYlB#mD42NM;oD=sln~~LiHsr z!pAOK&$yBz?;v#(K2E7b-{$oOQe8e}y5G?OHK8#&>X#L+>zWp03Hii7DrEz2AjkpT zM%wbQ)Ig{Tu+9huajh4hB{@iG>{r6b`}MFFtt*396-o#z-Fh{KB4pP!)SFYD@E1{! zxV9HdJ*j&QQV^#EJU>8q57L217R#%`G28981}LQpcFwtQzzm&DT>~~ZQS}hvbY1tS zW!k#gZcczWDd2`6@h)L(>XvRt5$Kki`H?qj{;k);y{Wh&ksaPn95RuncU(Nq(MMdg36M6aTA#nnAWQZw9#95%23GRkg6J={t9SH(-wG+HUR;q?ok@E@`<7y zO|Cge&(<8#JcW%^P>Y^Wm4J$vUxe_w8gX@XtU9DbxfBvt{EqEPz2VgRe4(~1I$Qi* z>sDOe=Xs&{yvxpJt_wqgrhl-%McOPxG(XAUuaV5nX_a~J$RsQ(Tgf|DYYcQ?iL^ql zEz->UmOyOrv@k{|z))NGzYo4V$1*Z|EOW&CvH`U{c+G9sHx^u9f4AA9uFSPmn9erwGeqj?oW^ z^GF7aoUqw++^hReViLLKX-aQPO4}b~mT~*#<>9Gz3`^54rC-TpJHhMyKZcl3WMW6} zbqV!qvgLk7U!6o`>AelQAhq>y^wN0VUNmiF{P54Mi3}FkTfG_a8=dL8 ziLdDsYFQqZ4}6BqOosuFTB7r&;vZyPApqKRu_h&i<_3cT5Lf9K288wmEpl5w1K_{R^h+kqII z3`(S!y_RW%h~|jwojWpSjH&eq&^&xsHoJj z_Zf@)+mR(_DV-U0rF~*f z_O%_~a56rM$@5A8pJR5g_XCyJ+PsgQK z)1%_TN!a2&=~}GX^V(BCJh(^$dwZ2XTKe2BF*C}K_H%yT&Ygaw8YB5goX{=#Zd;GX z*IV@S?{QK=ya8&?Qme!Tq==&LzaFfM#oENG~VVT7W5 zMr}W{y`am}FFkr3dlO3RK(TV4N8z-F(uuamaXx}~t0VCGa009VI|P=ZeGp4(_2l){ zbFU-qc%wPZz0IPrHz3<+vDRDm))0j`6|~ybr$++8^qR%8C1U%s3);-}01AUlgc-a5 z$~z{fAuee2#+$YmkS~-qApf%!{Seu_0C*v3u;mLm4AkVV61}yr3Hts6{uXj-|;#s8ds8l+GfPQpbho> zwO>v)?R!fSXeS|ALDh%P2w_pp_aqfhWvDMf(3c8phE3niJ_Gy1!`PS{*=;seY(2TMP!djPu83 zXiyY;Koe|^#uFaR;5c$BMuI=DO%Tby4N@ISRPB%&Bi{UM`UQidWW+pc_a!4C8g1+R zNg>nRvXzHoj11TQNJ!FIv^n!AicZ$wQ#Xk?_oMW%Q*07*i$FyWDMB)Y6?l*UDkWI! zh0C`4PaZDR$amdkXG?%yMf#I%XluGp{2kpLFbXl|j-$B&6~mChKWGC;#05t}ZlOZ! z#8Tb-+0m5E^Z;5YVxqu1R5YPrVXE45^emRsY8^StuK|pDiQ+F+l-NNR}AGf zV_sNV{jpd2wMb-yH@cR7pOCZ~JfUdDnD@ZmO)n{gafF{ir?&*w5WlES~iAlrrI ztvQ@vJ`qfTLQm7t^F8g1hEM$|Rzo+DJ6(d$#UHyfFv@}j1PyRxl^0(ik?T(GpKadU zwfvf<4~slq<^+z_5YH*{f)3<8GFzJ=nxB@3y|zaw542(B7>Sd0CuG{+tqb$IF>)r$ z3|8f3>56Kkp@?_jRG{#tfExC61>|pTsmX85(V8F%;G~VQ|CK)aX0%pZenVA}xqsgs zU6u4PkeH#+Bt^P)FeMqer#8bvR~eE8gOPE4>)|CVo;O%c&G8sD)wEA-R-L7YykeC6 zK-O8vpq5*n3le!aV&)UmMwP_m^9)**)C`zChIOi*x}RzMA~zC>%1say^MDlHl+FVb z-d%#!?pEJrTr2PP55dO(%5QW+@xi3lD**;wg6|)0G7T?@Uv8=Zz;`Hs+#kNe+2QyI zE2@0R6eMa-+F7La18P>!y)wTe!=Ur~6Kw4Oka)|2r!u^fIbsOi2JS_Wp`&*j>NLB3 ztD5JHSP9B)V+gS4lLO{8f}q-Ov$_8G%J=SO7qI8Dz*@=k@9D0^inH5=G`a3&Zzl^& zRnWFKND^(U$52$fhMNGqzyxe59%bSbpy|k9UUR&GK@DA1IOAnyiwpB-;99SI7JL?U zwCLxwvgLzP1eFtAc zM2YSbFjX4A&)Lr`Wb&cSPa%qBuX4aK`bgQfeQ4EiZwzE-d2I92T|f8bQB_56?XjQq zb}SGc{%o)35WGCE66t{I3nM}^N4qaFwT)u#3e6Bza>d!{S)9e=%j1{PV9hYx_6FD0vjO#qYR=+k1-Ud;5lxU6@3- z&EyW@5fX2yzSBFIxPDuaLbaTrDh7HX_Yo*y(#xJW9ev5ljtc!-9SFHlSS3pD96~b~ zrNOtKr(=-8HW+LbCl;1H7Hh-pvpzC803nu1+%je=5J%J157zn&ip8dA@_}gzaiAF& zRFWQ-&5xM%~s3<434t`LL#063usMJ~cX-9>gY%c#=S zy0ziOefnn%kAH5~$xVdVa$=enHsxWsD!AOrc`i;0P)lttVf>ii=a=liW~ODxhpKW| zSQKH_Ga5!ZWDbYh=jiVpc8rc9R9?C6>eg#I1WT5dxR2*!0#5KB}csBu*|_vwo6G7a4(YKz+8el+`A$J)COs#sD>{> z-qB7ECwsQ0K{ZBX*5nZMNv{w-&mfd2tU=)u;?HAb&@#-RaQoY#mNAwLM#@UpYSECg zF{{f@`GiZewm9U`wOX8F@j4g+7>PmQp1Nb z#ucUKIay)_!!}jS1n$P&kr(_22=*r$pSp2Z^e2hMuA(Ri@#y$yy~RO}VuizzJ&N{N^<8vH0lQ6{pols#^<;VH9%QBnQyQ>X@7v$DR zcCWYtftJ(rPnR- z9+s(5zm?Q@3a%B4rRLmW84fnLatGTHNaH{eV)`&fSmXGkcfc;*kuQPC^KMwT3|ol1 zsni_S-)#r9`4vJ)T0KnlkD?FV-=YlPRkKerKJw3l$gTkLrTA&34=zvyDHf$v8Or=z zLvlD97P#?jm}qyHiL;_y`LSF&|M>uQUV)pWn@jraIwC(yC|zNL;MyGP72LZH#YL#5 zMC)TqhLLP9nNPjxXlGPXS{S38zgTbsr{?lI&2dD3kQ2auu?C0b94ijkSO3PiJ0US#{ zcnp(TGmr3kI}4PhB5?K@Cr1Y=4mM~?$ntHar7U%-D0p}7@cU9Q|5&6u@n+MCz6D?g z5sDqg0Is^Cqd#%W3lJB)wo}H0+!N-ttz+QcWGekS`}TXABur78^`crAE8`VT(WVU<-cZGf{GD_f4^uT98ytNRAh(wQ*v{JqXqX$f0_ClBq?;9ShT@UFdb#AQ zm4zk*yban<;B8xY6*b^~Sq|EN)nTCGm9l-tM-#XuqS42GMh)>Tt*K7__Ob%>H}9Fd zYDB!YBz}N8eP7NP!3%!QRsn<6kPrNm-iWIAkXO)d7NT2Q|p z5@6Yi9I9JAuB`ki37s_9ox}4=S!}KTLqMH+xMOtK1oVlW77maQ5wL!iwbGj(dCcru2$Z_M z90?D-_Oev5QAeuet&HAZxs#oBmoEJ|0=#t&kB>*3EF&x4g%?$eSi24%>TwdkHud(z zmlo=N*wOp^dX_w8Zue2L*H8Usxuf--d!q5QYsWvb9EuOTJgr~FlK)yqFWKby{g^sv zr!x%${I!~Bzc?nrtc70+{fz;iSm!wBCbLPF2np2(y93-0J7sTehg7!2SCPqoYf*-H z#+y`L{iq~f=~Ju#A}TPl0h^19Jo=eSEA*hueO0X9DxaG2bplQ9?IMWyJY3u2;`hzN zZgLR-^V$O>iUewJyA&|gR+da}S!@6ztqUZ>3oj!I>~4M~cA|c%nP_pX|4va97XDNC zZN4m-J68+Y%NNJ*Cv|1&abw6L>21kl+h|8~P8|MP#ZRUVzw1MNB$2GXG7bQeL$8Rc z88Ucg%SF~WhwuB5Z--@;B z$9^H7yW@gK{jkCQW;yYp;c9>lt7rmieAvt-P+|tYtOX*x(zno&5ny8To{Z{_Dv%Ib zP5}SCU}OmAc`Yl6ZSpj`B3wLk5net``DRlFWBLkREdYN$|JOXDA{AFr5rj$l*Q&sh zw2XsM*$;Odm?%nW5ai74#zLy%*$P+GlFYZhJ!YP18@`Y`k_4kFYKTZa=aaw)%pc{` ze>NhcTf;P+soJqK=pfHyG`PkN?|1Bz-sA>^^A@ru<~n^T$W-By>d)YwE}PX0yu!d_ z>7WrCnYk4}iE03_o_dP9LU*~_4X}a|SRDbis@r@`qLayrZ5YDbV8!i4#jwA~xJH&R zLntBiZyGfCWJ4-y(sc{;91bVpfsB?s*ALGBeP_(~77M5_`w?#ELucsGKls&lS*X$g z-9V{l?z=gM+wT$WEDI+O9~ElC{SHvuHnuvd$V5)W^@2gMI|(a^(JkYU0SHgtWMM^O zcrjoTRVc-}I8I*At8?5l8!+u+U&R>TBBy?d}B5QsX;*hvdou)jq!A zRbIq7MwSGh!lhN(K;(9$iCRv1`~W$j#w3qY{ap^e5afy_lDwtqXy_|o5`Cgm-ANP8SDv~%f;=+hR;v?MEw%y{RZ+>vXD(-JK1uaNQA zlv+i3kdy;NhwA#nJKq{rH+#K`=JG&sugQR)BY=v%NE?HOYb?xf5dBbCF`oFkSygx% z2v}a~5`DKk65QML}Ne+|mnZ)cq-fr@o&&1?8@DBVOpC~D~N@%S{1a?^5@8`~R=kfIDO zIAEy=i4&1uhnSzhDO{Nkdq)R1XqGFijc^31S40eq{eY~6^0z*gDds)64Rx?egzQ)i z*6)VAf9bSbG5njV>hri4@=_OeV>r8Utigr_dyRFcBu>HFdO^nVQ&GzE&b0^04T)k@EdT+dsGM<-(NLLEbTS2y$0Mx!P;;BjIAMG6*Cs-Vb|Pc! zHjDmdUuQ$Fv!|;oHC~P11!y2YH%l|mp{Dfo&7$@ide)AH2%*_HR^>`e1~8=Ne)EGhLmbplva}GLaO5==fz+)#h2_Z zk)hascRZ$RdPZw2jQ3y- zOYb-iTUQ3WEPw$v*Ov#|fG{cU75)f^3LhmK1K&sKX)uRRssMM7I=Cyqy_BleBAB{= zg3e8>^T_-XGTp4dnbb?VzbC-X6N$ArzxCys1@m-VE>j##q?C|mBE8m+OIU65qXI7u zkPo;Efa-0Y;-+d*?kFZ2RY<5WpKW7GJuzI|B+myd_N#7ay}9NQrYEcsT;mx_N7DGi z7nwsM$ktuuqs11xW=r&(c^SeqBDGh?w)6D^?%`+Qb)iq~@z8&liPlSkum)WC6$m@> z@sy>-Sc@7*OPbo-{xS4Yr`}@f_jmTGPO`AD?Q0e`pkSMSCVZ-bni1MqF;H z#^LG$!Sw>5>5tsYnxYfgtqY$R5jBp)+j)_`$>;W~1jbK`#?!;?L!hS%uvUO_5daY= zx9jq*76)?aLqb0guop$}UK@7bT=CVS^s|;4Bo=e{QHTfm^=W*N`Qsv70{ zm5Hjx1aE%NHc{JUm?rbDWC9e+KK}J)FbbxX;5o^#I*AaRF4|`>xu_6_D9BX3o$U1H z?)ckqB^4Lon7wjZ-KAPBR*uXlzv2GSyu-)>*W*p~`P*sJ)t+_nIy)-#(jkvf{d}&w zLV^GW-?rpn9Eg^)iV@g**V|TaMN(0sf130q+@= zi;)Rg9asW_ym*e}r2;kw(1$`u7V7|@sMYyyPzSjp#r7rVd!u9dH5b5=D=9k~AYG%c zVbk-(+1E8t>{H}9`Fo&nlL0s3Mi5%qcKl@mu zbbx6!L;h0Xw;Z0$aohCNh{njBuyYFQG>PCIAGXDD3G0f^vyk!<&SS7I83c0pG0jrr zfEVGMy)7z+wyd`R$@T=G^}-0}jgHQfV$VHF=ts343IyQ4g<@HWU#UnhrqQ@SmG9X)}+%oO)Nyz<}>K@4I4$6@^5G==>+*`KM83kK%yXLF z5NR{!*S?vGISH9M(Mn4PJnnIL#U+|?98GkuJ*2*hH3koGE92|&Bgr9ErUTU>7%IvI znM=3J2^g1#lP#}aoi33Q@-S9LgZvF_p#GWK^Fw;(_<<|xlCr_hYN@qm=5h? z+nN{Lu^@!Pgtgk>(%1(xS$fp{lB2JuQ53tj*u}QH;B8=irZSmZA7;ml$Qzy7fBn-% z74YTg9x!%oAsnJDUpiNNhAtI7#!ie7U>XE2Oq0DdRV*eNbUAZW5pl%%-&f&@C6vvpdjZD6u3h1Ilm0(`DdF zs?rkP_TO3AVI}A z#sH)vmx(b~*t>(?lj2fV#yWca=U{PA(*YjHcY7zy!-_KkxOT~^sj}U+dZ-$irk>RZ zz`ut}=CfITNJP{-`dZ4d#fbX~v@&irC-}>wgwehBErO5Z=UbQs9Aefuwmvm#DZT>` z3IpKhEkEGH`eVW=3RD}7u(m5AaZZ2HXn`O-{rTn!WI8}|OHx#VCejWO7o%<8Wo69a zcjW`?j+HPgU+~9PHebD$2HHGh;z+Pr8pr`_GZX@YXm zER+uL*eHrwC|nE%-P(qPe^?q#Zxa%N?TST~_Egm9^mkqb#!$1z$P@ZRW5P6?ftqNC zFVzDmj*_=p9UF>TnNjq6-ZPn2P4h9Jw0V-E#o3|F*^`e3bo(uB&POFdLKrDSUKU~(TCHS_;A6fn|N6maXyD2Ebl+xv zriO>qh{QvVJF=Dl1Ly?S)q912U3?4*H4s}XR5n*Uk6syH#x=B_?+;wRBeadb$dJk_ z1&{D+X%;z;d%Hh!rs{Xm5%c{PS-?dXKhC`g#&{f-Bm@Z>aBt~@@74h9@VNhg%l`Uf z8>CK`nvZ?kxC`epZ58x~4DyL`BC*<;A2rM#sH7nN{ooJ6Ssd~L0zdsx-B_FKH zS~IPvPcvCQa8AeaBEc+aq~)r`h*I72c_F%PCh?+)m>@#GZqK=Nl1EU$14&cUa+7{B#`3pZo&Hw)AzAW_$uIqciMzF7Bq09d#_BZb%2yjE-T zhK?w#dEHpS6ee}+M$S)Zq@teURSr-K?>G)R+Wg26W7#4N5x>Kwp)h662q-;d^?Ifg zTCMjbC29(+tIxnpa4d;2JNpC%1QqTqXkf{_@WR3l1$- z5{)EmZ&U0c-cDp|ilzSdEf5Bury;(^TB3uJP^DMmX3@`)nHLb@+(eT-vXMW=BG9z~QOD zGWwZLl^0rld?K<&zkm4Y2Nl_a3_Pxn#T%_+B5w}e(Z{mvatFnrq8Kp#Wu?np(Bu2@ zp8FA}*9Pq3I2PR@bALsqDG@$vl4ekUpX#x|JJlfco{0}ZZ)5lab2s{hGh$0K)VB*PDIsQcv zx9YNUKM2u;?M;`6d6G{)o^wWh5x$C1m(=b-_^70-oq6iBPOop(xYtQ8vD>PCvLAA< z(cfE_&*ICr0^vqkTVheFUIM_s?o$L(Um|V#C?!sdq8n4HQ3|SVocy(M@m@91miU&a zf$45!kf&dX3WVJM=hPq9YuG zwR^pc8=KGh@aJb>hGH)VIxfw2>}yUS6bdm(hbj7EVKKiXos)S?(B+cFcb4+; zjA9IdY8$V9Y(gKTrsoZ8KTg~X(B#+te)n8)1SAs1D9vZdK1;zs^`x%9B;8@@d&4`4 z=@^cXq{XM9~i-5FQlbz4v5zZ-xK*Wj5Gg&Yl@s zbk(bSg#>TBMzeSnf0vp=-d9GUCs5k5=k|ozOT&ze07dVc)cZ(qe1SEb@@-q#w>mKG z7BEp-z}F33=2wokJ;4MBzwB<>OX;Ac;J4A6v5IvA zo`PX!r~}Iff`L^!!8aWTBu5vj&2%?3R=hNLPF(Z@#OFMgkGs(Xtm1tUB;kn(SczHO z*N{)eSK@ZJyTD?OcrWm$ z$xm{t;^mYghwkLCJ%4%sko1=L3GwV~QqkvF^Pz~=-mT`=E=*wi{q=v46HGXjYpCTq zK$sP}lv(*?$DV}xzrgN&<(pzorc~rI6z}G;m&a7R{B{^5kdB<8>>M5=GAp84DzcQKBKy#XhL-j z>8G9^E`q=%s^I{yViV(4HIG|oVC;_HxZPoqxZz6^U$(b(cQX}ggdGwutGcrXgXRNz z4{ojKfZG$G0rVv7PZ-i~*A0j=i`}yDzU$jL*zXu=Fn%x)9=LU z&(*G8_6s>h=p(I@flRHr-shK4@%bTc4jIyb*|*?gnNr1C^NrS`3$4oGg^_ z=qd41i+}!#LYCS6R?%Y3i_noP9TSpWqT|ia_C1zM(>B2chA{Q^X` zFtl>WJVJyQ@uBsX^6K**zHhabROOO&iR zBZOS0*G5yDmrso^HMU_Y+e1k}YZrNjUskppWPmUQV!KEt#tZ;bc_nKW!c z6BH#!6L7Byz5HS>(8l3hf~8*CRml6sMSJTF-9vS-do?=688>1|{o`X?e0`w#^50~K&Q@=o&GSqh)3qv_sj6HdXtezUa=jvV=~~muq$78{nxll1=uxo@16ZC zT=~kvE4Vc13a=0UBK~p|=14nIDDyspS3hg&-!%p=JW&O!W;Zx4)VVTd9>uAbZnqf@ ze@_bKmc0GddN1}O*{Z_`+jA;7M3qLlC6Z0x1sykDaofl&R2t6sK;hVovfa$1N9XS( zpZ9|LyEk553wYsx-$1M{_@dA#sSSBh2%ojKRHe4QAmNEI1jZC8B03SpxmSv^zpbZX z64CAKD`^nRGz#6_&YoP`J&Ns4QFPjt?C${F;AqNeD}L5k8x85r>lia;r-lRTtL5XADK=%VW#liMUhQ(_G}qoo^niNdX4#nU*;` z;QS#LC9u1gq%bY_-L`2YnC2{LMGQ`9di9pQ<+CVHy@O0OcY%Si%R9e~%Y0ZSfmlCsTCX*?~V`8n)U}%hM#Hu zePZafRuQLp^6lfM7#;-Ln}~9u*wYsD{)AL6rmao--z) zX)Pa)O}!aXZygZ!*ImHw(GT)#Y_QUqD?gnm>F&gIsj`BD0T8jxwFDr932Ip-RrtDN zP12Q~1@t4g1}w`DJvr!i%%IViq!@o7gi=jg4M0=kHA0oBIFFx<%MqtYl;F|JJNI`( z0Pl)--#l6sMZghZRRw);5w5%XWG}-fIWz96~M-?@d6OB5DeWw;Z z9$YJ1E;c!**fWK``}WyyaAw#$`jw)nCh8||-jla46jAoSdIL`=$3&CzNdWoUG;Wz? z4bp~E%{GbJH3jqYICfc+V8|-r)yy~Z1@_DYBk_vl!8^A^#sbRO9hj0Ig0Lo@Sf z_v>x>R!tB8yTKH~Cq4&oz)L>qaO|r`UOhM4pCxSlUje@%<}n@%`eAV|MsJ3SoQ)$S zU*re{y<>87kqA6U`VcHgyj17363T%vP0m=5osenE2P8%qVmIJb6Hjxrwtp^k3N=hE zqM)YbI#BM{(L@57mk}+xmN744s~gd?&Ft^uE>KFi*BG`>;H9Fs(|)DD_s#UgsG*o9z%}_hGKb6m1Ln zVcPO`WSmq)pEOZuDbt^XY_PbdY)9AJP~X$bAQ-BKZd|G3kn??WxsdyjNIMOR$<1c* zY?w(G!r893#|Tio#+{4uBEs5qk;)LRdu33HMFmem3ilJ_VHV1Il+#SjG zv_O&=@G+kY>h&nt{c{FsK;3FOyusHR-3$~_JLW%4Yli~~`RiPScD$!i{KhZz-)t**wZj4upvq$;jw)ng9m; z^6$0Adq6&D(UZ$<7QgO(T2(ABd$S$vHeP}_M@sOvM8YUM&4~8 z@4^1BP3To>}Q=vLJsj-cZT$Q*yLTBFCg?mW{5jb0w$!AP$ zy8tIb{~GeRHAC4YfXrf~aZne4qcVEffa10ECCK!^z{0}S*B6kom>e^?o7hU%l}=;~ ztPL6rUza^q#9#m%$%Z-6xJMo|XFycqLv3wx9Y^XzB z`W#Xx!p3VjTPB%Dg&CJOGsJ7Hn~MxYK-H%37Q>I*LZ*=^wvn{Au^sBvjn3PB(-ZcP9_FW@_AmH467lwMgnC>?i`f32Mw5J zVpWR|&^3&ypF~-FFx@4vowi4269K99=4OdO*2XnO&@5 z%iY&MM!*lA?f!dSu#n?d*pNqcHxDr4y#-XX*Vr&ws9Z*an$C#5JK7E~+{o9;-jnV|w31TQXL0+x;}!m~zteOv@AECQ zpO0i;Nyh8h$_P4fPzU{)C$p8M=mAZXCvoPtWO_D)oKfmc2a+;2nPADI=&PyDm2{2TdQO?++BP)jmDZ7}RP;ya4 z@RgRza-JMQCDOpLdz#o*x|_Fs`k^_62G&*dW26GgWCz$$0e-J?EwWUwEcnI1{-hoR zz#;HEF6=uI4})Z?o>+_^wIWEXc2gOVcIQf&HtP;^kM*fdg=F8Z%oFw#7W)dAvZ?RN z*u(Jc?q!9t444(`&s2!7j%BCs?rCfqqFfVwr?qxK-4BeMab?AC*l*!#?;xZr1 z-?fOCWXEIMgV`LZ-`g`CB7%h{I6641bI^PIIBRSselsX>IPmLZS_$p26nCqaykglQaN6AE{K(8O`cBtO zKc!jf!ZnHC&7d`E5-ombWp~di=uvs|{d%S)=Y{TxbYb)+EJ>k`mWJddCZ4%D0veIr`HR1LXDu=lqid4uu>%AV7QH2H&&_>!f6OhHQ^sLitVAEYifM?J@)O7$h6DRDDmq?8-D8Y|8Y zL&Ki^@ZG<1Q_o(4MflrH8&I#!L7){qF!m)PSJ#pp5$#}U(AqMd`ZN}`((N%}uMd}2 zno_}VE~=9z8w?udTaS}E($8nF>}AZF!M<&OXiL7Cl)m~A8LR~#?Nl9aQ8k*OZ)Bk{ z5{J5v&b4{XQnP}I6HE4hf6Mo}<8`4-AFQgaD0{H1ov|X`vbDF$ZmoN^k-W}k$6M&V zcj{*?b_eK9)z7p3bf$O@?e5H#)phr~)py>=y?n9|rS*q;Wv{;&RSbL-A12sUS0nz( z=*lq6K{8eB?+Z|eIYxPCjuL}Y{p;N?Z{Z_qTa4$SL%Gc4(=R?SGE2$Pbj#Z~4EP&) z1XAJC5K1mE`tnNhATrk${5f+szB`J4F)*1+h;4YS4t@f%lH$1Tg{?h;{ClKKjRqw_ zx?%wBOnkE^#0neN#j4qc&)CQeWKd)C*2S50Za=K5GO$ead)A)7{8)g0)>cf8Gl4%d zbmi9N*n$YTiyoI7a(~T=z4cd5v;W|a;e0O+lEvtaZ^8Kj(SV!DkBisMH*{eSb!`7!l$@~;V{$b+k?SdRgD^#i_qw$dPkS|p%Clwfd+C9{KC!Z+t=N2`sT z7e#r$gxp}dcgKi>J@4k=rOSLnTb>7+&;qOjQxphVnrAUZ#2b<%YM^{JaVxm}wsV#} zFYqd!R7yvin>If0KAFT<{9c_=72*`t<%idZ?{?15Os8}AED&>{Nq2s8UkXuPuf4zN zylgH#cV!y^mb`eVCRv%K7Nnc{*AUI7wPe}@G}_}=!fXk(PSyzx%nHFoDWz1qx?_4g z;9a8nBRoh)RUQoNh2+QYckLDGcfS}Q)D*yMWi9`#~ff1 z;G3t5p*h+&GRnX^sWHd=6gh0$YwOiCteg&pvh6T=ClfPLN@rh)=f(-A8T zwkce6ZX;{yV<9lGj97Ef%^rO5!K2+SQvxXMOhuVTp>tPD6C|9UGaK%ZXAFNG>TjY$6AQz;z3a9CU8o zeI2j+5`%>`%Q<^PL{2N8k(`t}ko&#D-_YNqXU5J4G4k-~`?h16!%i+J;u*<|2;Uv* z3#!P4Q4){l!~(~kpG#-v@fkw5zMKvgbd3@RqMo@CQBN2({>K$fPn&gbN8xnvz z99fb|UI+uG;3e1C>F#H`-|g16NY^ZWf3q#tZ&H2w-(Wj}hLjt3S?2u<)>)VfV_%Ex zU{+0j&vIhYiJI@~Mj-FR-uWT8$6!}1;qJ-5w^0H6I!O{BGF`6QcX^^b(L8p=m-+?t zA9n`%Zdhja8>;Jz+ZP3uUeP4x+uq9T!OkQhA?A}eyR6@{^!*cp!?x;5aL}P*RObMl ziD{b%pUq+A`pDljkXO;Jz^E-Cc=Arfi@;dYt5^(N54k@k*A4o2{rwutV@L)vUs&0* zjM#{mD`2`os*eAdXUQQ?Ik^=th}@FYUxbS)*w#-P)A~f@_>SOYxg0+sPaO7SV6HJG6f_~XO2lPus(s!{H&Q`Hu-iG-(Hc(ap6y`piyk-3@ zS<3d|pTH+4b`yK8hRso(Eve4wZ}oKIIk|qVxV!hr-p3i8Zr}9K-hCSPB2Ng>DgK^&sXkE@cPLULZ5UI%H++h$ z{&rHIgG=n)UpI1t!x^|{yt{4rsH5Gu$w@_Y%aUvR^j~;NO1DdQ*18l8Km7BHyak3| zE!UhI>k{-(1BWEQdGBFbwHyQOSzA~Pru0I}pic8*8=rgdH=hMok8!|v?peenq7DSR zg9OYBg#YHVruE&yX4^9VYLgt_(fN)DweA|82jRpB_CyzcWu+R z-_EY^4*-J5Rnzi;Xpf-Q8bu(2$A>kRX0;{~)(>$o7DbL~p&T&s8d zs8fdMR>6`&+kU>Sb+ms+f{AC8wSKaaMBac??AM1)Yuv&Uw~4dJ*#5#h&yKV)XCA9O z?N~iSr-I9a65=B;kpP|m$Mm`^V>qP}=lMVyZt+7w{#?9Pv$GzE*c7cRha*!(WpR34 z``qf!7kUcgam2sR%ojLiR5W^O6=n%s;^=a-hK_(K^OydLNT*rz-OHSIHJ!NG^iH{V zu<+4(W95o9;=7E(8@d{Dj7flk-D-QO%%seBJB%QCzI!MohYVD>e{exC$imSxh^ci0a0yH8s57%RQF5Y_G z>$Y)H2i)sTZO-7x$_-w`?!urJ>?6zAM#1vTsHJUVe1YJW^fM(@Kqo%h!iUNSfu11AbBahkq-I44kii7y; zA3%2$2k{R^ly#~|8ZOq-`Bh~)&>P`Aqj46Jgl+zAxZI1tK;7*=2$eg$Ap;o62#>5- z;(pb*70R-FrvZL0ik}-xTqQlz$+U^-4V$yLZvwG9W(Hg1=9cl=jM=OrXipbwug*Os z35DN(s*@$h9l5tgLm_lm=B&yTmb@TZJtBg`!S?h`Oft3xhE!B9MrC;5wA=&fM`^#b zvQv)I-3bF5wCR#wKe-YNxCKlTB8uuX;Y@mU%|59~J>2sXevmmN_j4;ayM?@j{^qDl zG<4&lc=d|82Tv8n)%X$cw~~rVN9en8(yn#S1TAk_g#88>#&e%0c^w6$|7JNdVXJ(`4LFu7@HTu z8SVVA0u>(J&u|oRzN0T|O0bPpU;eIs0@zQw6#D#ky$|(C5argB;l>(CspRX^ao^0V zi>)MvqUx{aJ#Lq~W`zZNjdrsZW<7Dz)V8?y6q;00XQD(WUkO3&NgE`w&=7qxg)^9& z$Zi`r%Z4ZR4(NNx{f69whX{JH+t1072cc2W=bO&Z`Xg9&>$E?Q*kGf+iT&DanMwEg zBi7ZIJ*(~VmzqIcn)5vRuc|8Bg@|9pU9-sp&bzQgfjC2j|>e<-+JUi^zHgYle5i2 zwY7+u$4kdXrbe(%bx1O&(QSzbx7nxIpCcR}QLn?o^~#tz?5i*n8Ht`Ss^*~ZswSqn zOCl`&D_I8Y^w%$XIqEyF7E#C7&Df9asgSn&ru;pWFo~*M9?BEe3~+t7xy)7{$ACdWOdUE*(+@E z-pV)bNM}}V_k!h%X1&vz3rmR_`C*AKX(X#EWli^J6*l_OeQe~y#N_>ksAqA!y<*xA0vB4&}r0qG-L#>ez*l-@u zz2Bh3mrgg5@OJ~1tk0eJE7JgPJRf*h7wa0U17NGYkmhixH{CTZ3efmdhjJj(U6nFM znybDh5cc8E;nr*WwO?B`GT5NE8BsMLbE6-S|HgJ$YK;88o%f70lJK2J{uuN4I!5uq zN8vKXd87Py&`@1a_%coo(&*T}ASbT}#+@l;q%D30b_bp!OdVbc*M~F~Td%t?d?dr= zOSMPq=GVj;sLMVhgox45Z(UBR_mkpltrRDae-nRU=UQWe+Nrx`4`CcX3$^u-D}>pB zNy1U$lKwzMTES+Pua==k(f{i{WaNE!kuC({1asZY7E|i>@Di3Y2p zA=s@Ukf{eA>$Aw(Pr+ab;}WR{`*$8!&2B<2XZugcE4_O8G}e7IN|o|NLINLCu8fp< zMZbe&)EoL@FpPM`pONyoO>>tVWwtY%ud5Hu&5<2GFy<0#_ineHBRa85nUr=k9INLPLk93{G`D;ePR*# zz2`X1!r&5hcj4B_L`<($=>qGw_&Tk8;;hLMdzusQo2vn5>LI}bG5#}aoW&*&Zv95= z&iw#l#gro4gB~1WFm~8Nim}GNuV(0PwVngL_Clzj6-Sp&BZJtk328CanshB!t+Hld1z7f@I7nQFg z!?=7gyLZb0hZ>43KuY7XAXqOLYIyiY#Yz3v5b)MeJzfy{NCW=ezE+H@A}@wW_0!v`MYQg#4*olSI@T8CQapT0!py|TqzVO;%8;Be!kG>pRR z1Ht^68%sx0S_9*>!wtTn;Yxfk%B-KB?E;=h5cw_0Y5=s#)ow(cl74%Y=psC^* ze)7QkS~pCi+i__o8-_|ID5)O z9R4*bvSNI&3+Ue}CTxE0iZ#{En5m!$U4h*fzj|i9CQpYw^Tu2T)NY>+D~!M7-`#7b z`D2+GE zft&|>t9?D6$SN=G@6!#>!UIeDGU}UQz242nF*+i^CoIV!|uVwxM8 zOi|QJ&^>4QHs+8X-UQzL5Z&NN4#f5gSOW#9Vm>^N4NA}w;&eZ)Y{v#WlqPI1?m@tk zWZ^1xR!eVSC@5b`c{fJ}$qk*nv=~J>f0nEJ?%${3YWqk$8GZmDo;-5_7wO3qLG)ly z?M*pir!S>5Eyj4&Rx`LAa@^)nB1Y=NLZ@!g0I~aA)_BVepM)j)5G|| zwS-M(w;%?nkyZ?`-+<2u@LiwBW4?-Ji*FX~;&jiNhGn^kfoIRhBeNpokrlUm{D%Ebl3N9EpbpHNj`-@%!;> zt~BvL8hup0L@a<$~U@-N^y+`(Ui__HyL}ahy(+f{L&o)wBcRGaPR2 z&LK@?S@a2Sm~*8`XXA;>DoCvY7T(!7y>x=r5mply>l?@e(t4d^h2Zl|PYRg^A5KkfaSV?&CrmJ7UmY+>cIku{9o`mkMy+qL zyRrOjBoVpbdC{RaXzKRIqvnt?9{lB^;(=yt%Yh8n{*_hNuM)ioYx$ zwfv%i{30&%3uySE0}4G~56wbl_xsVaeWm9d8Vbw+I)NJx9f8bVkz09&_B$#h%C|dp zCQ^=_#pB0aHc;PXVxPb65*UXb>&UR@=cFuj^ycFAJ1lY6`S{N2>w!#&Nrl6(U$%K$ zm2-5oPv|dRHp`|byE{cF9xW1jlX3dP<_sb-_12E% z%FESPL(8`#j*Ha)UK4icyRh3t(S=j|4gm$ZNo{m*q^VZpO}86pH=K0Y!`j`Cb+r59 zjG7+}*{lEJ$jhTjR&T9HtgPd>@9r+$F1cEy`U*+?y=tYWdP9B)=)z(nI+T{}&E**M zBI2be&?l+`4E5y`rxcYZ35^YLb>6Xm7n)fIRa;d;+;|ckU6np(5doJfy}|`{=`!R; z=InoP1PEK{H$XPj(`I3{E5qJtztj0=itkSr_R*u~ky{LTHPlU@>CAjYPizqk=qn!c(e0?x+O z%9M&#>5oC_co-xxGZg{+xj32z^p0up*nYtS&x&p<({@=~{8xmZDN#q3i#shd8ck$S z^ml@zhzW;Yvqt;YucZk#uBRn!#I#rn!B3E@m4J(+N2xK5D=|4oa8h zx5TiPsOGA~eII{d-l7qw#CeDi!dNjcU3Zk>KT ztbYB3Iy-4e*W_2^E!djiM9~(hF3i%A6T65hn4L#VA1@f7P z<0YGgf8jZuDh~b$hfIxlk&N*0D%@T<21dW`3nubz`BH#Z)~4#Vfl)*5AP1iU# z1c{r9&x%ni)pg(4`(-RnO)}{vOYM~p^~^w(3qh7+Nu|nhx4nC<&xp~AXNR$K8_nR0 z!4*ZncJSqns!5c)=*iNyj`?mlnl3XL9hO%$FUE%e{~Yqpi%DsSzn$?buQjemj zb;Er#qKm+9;GxYY;n20gnuOK}kI|)jT{fENpAP7MHxCEcTU(v>b~;1I0Hsr(YxmiJ zzyW>>W&Fwsz@T5qzX(9@r||>ZMRB{Q))vp1{kY7yuG=RKX^slV< z+Id!6(?rkrRV>Xu=@zv%IZ3rjA{tCEIh~Pn&RqTGpHM0(}(^M1AAZm0%58zoL z5%S?vOPFTs%1?KGxgv=VFR8K@g4lQxKeKMlaRVwtMR%x5&|jYVc8+^1N5viAfUk{~ z>)<~(xXfF1fR0_>H(1PFFE=XjGtDT~&N$kqjgYTRwawmWy8P5vFNzrh(=~<4ieUVr*awBN&5KbS1>uUL@koQL z!YFr0be?rZR-c7P!wWlVzCQew%UnAD*kaDg(yG(GS z)vU6o{V6Lc*=1DkG!hP(JsEw%WV5w30LzfB0lY4RwPiG)3!%C#@g9@OTwRPR<8@0+ zomyrslcHT^UZpp5C0Opc%lm3vSD!$A*^;tP9m8VR*8A6S)L{Q-ooY#~h9<2B^7}$p z?jNHaabciD5VJcxGo-RcD7UOZZ1YvLJ(a!5^6-zeW>vu}A;p-;RR20^eXzvU(}{~@ zh;Xya9O~ZMhiLJ~SX=yr@qmRR=MlAD4?>S4T7}g8Moye%!APa*MG5QEYB*=)GnPES#;0 z@8l*uW=?O|&-gr4n?*14NwmSzB7qdV9!f9FvkBimv(wkPeelr%+wyb0S{4YzZ;%!D zv^yO2r4)y9(h`(U0{pTS0K7(oO?yM_j@{R(4Fv0iR(;Gg7$DT@53g9-{WIcnhQ{84WIi_OswQYX!jr7qbjEl!`ewi zt#jm3Ij=fc;yt^2?a%y_@$Pvup9$DZ_$ZOn5|Qe74hf^-%>Pgm7q-INVx3t~7-G^*${s;9ao zQBaIkN+k86Xcc*@F*XAac>-UMY;!P|g5$^^9x6gzQ<*V}l3KZy_PqPa5t2#SCPH{7 zzq1tphUNg8BaU!%T;LLHwBF-}o~TQ{%k4G;7(f459ZEJ-P?41pM5oA8f>&9CYI)v=y0Jr>iW^qr=SV?wKRSh;^u|0!CDfl4{ z<2h+>w0?7@#c~aO`d4(B87%%>hZ>;ck=t}w&}fP5FBHho`fUTx}d-voHr zD`ApB5)0;FHKh&2vjSp?Jb#9|qY@kxD3(p+2JoJK)(aezYrv(A68|P)Y1`?x9`n;@ z{-qHU&nXbw)-A0qOJLSZ+2C zwYB8HED_6DB?$PO#4j({Nd{euzM~Q|-l&z1D%&9t7N<0TDwaRcG5`zb9 zMw?8o2w}TAcS!;P`_5*19?Iv?>(-`ymIV6Uen> zhKWOW!QQxq=EzRt+QEJso{6O$^()OdCKlmpK7YL9XP9M_ zYfqdd&uL0h2Khvk1w1-!YM0=`+gcK&DbTYYUKMzb3KPc@jabl3x6)A^Pj(Q(#7YXD^n9W3} z_hvMI+6PB}39PN6ou}S&xLu{T&zR1Re!dzt(mMAd-@%Y$rw zd*T&}w_(sf<1$XTJnzWS_NcU9!5q8j?XtqqVfpWoKW7%6<8E(YR`|B+Q@sQOD+^~} zpOsqe(DfdVvj63Wm)nt{l3rugXD<4+zfy32oXTdgkY3H7{w>lnsCkrAJK~TY56!V= zcnuolxCh(;HWTq54m7y`(jhEpDDzV=RHy;jOTBP%{b~E?B;+S;#Y%zCh9Wc1?otap z2(x%@sL;Lul$5TMZlRY5O)Uq4Q>6;?2u3SLkGfX(R{;Fh+^bZoY}{QPRbk?(iBl)C zdyuwCd2-eHC2x1)iL@iV3HvkU>s!9W7_C>7wp`MykvX(}jU47Sw}r(1ImYem3<&S) z7RD(CtJM5lojCK1y-zUAd6cc6O3IBAju1F$XOs2}%bueY08(xH@ zZl1?!$Rc0NUA6Cqec1<^O`09K`|E<8Z3#r@;R5c36!z!5`dEJrnas)Hi&d0Ye4X$f zh+0(?#B5r?dhz&TiTSZ*y|CI~vVR}tkZabyC#ARfaC_t5W_-zx)*)*sBK+QkR~N2D zKsJug{WnX#8kjMl`x*@}EgvxRPqQM!Vp`X1Yxf#P`e=FUW2o1&Z5^Zw$fi7`TXrGf zgNgJc$2#%wdA< zKb3$@Y-DopcgumHrzza-Kk=iLos&gHEh#N3S@%^TEJs#qlOvhxd# z#f_IvzMU1bx8N>8VQ^fUMdZM|SYFHs%ws}{ZVMLS!7!CUYn(fB2JL_#KNY90T*|lR z@{cZIDcofJg`28841|uL(v#bcPUp}lVHZVE;fL=zQPyEHbelv(qOKGFRe)tmK) zIxMx&+y~K}4R~cuY4jBdJrDyAan30yO)JX07QRCvm^PYdXPaoFm(Rr0f0pXVd!wRX z5%l_ybhN$YL|g;Uyi|?p7=4{!>kF3fxGYhIpWEjFG&Q{p({d)aqOf9~uzqBx> zQ}Oj{)_=nm9gUGw?7}l69%d!kpt=u+kK$bs-b=T*=BucG0W-{;%xBTRoz}9bg%9oi ztTb(8!L9CxqmPLWZhF*7!6%GVN%4ewV6&in@R)#aErz=Oh4gUcJMX5s*Xp!)iRhE3 z<2533pBgtXP=vHU$0NcimE!ho%==oAQrL^F`b9~KTbVR8f_=*_?eE>`B z0Ryn5)g8O=_sR~+Ux_y1aFqzNB~;juPp&Nvp4yOul5Glolmo8==+ZfvwFGrF+g0Uo$HXK0o0 z{7S3)izNv?H_6<;la;Gg(-x&&3zB;&H2ino|* z3m3Qq7-7%0>v{SK+1LM> zZzpsN7B)He2g~`CSoHMIeSiff9iNP)R27v~ZE|i{!dX^zFXZuZkJDtBzdz%v>(;|r zHG?jxSD&Z)3p_Q~TP`B>k%n0-rkV`q$K6+Y9AOzd-`MuSVeWR6z=0-l3|kE!Z?X8! zA%CrriJ5$w6h7jt!wt8zikmgOv_R_8-u}iLh%aLTl;h0G5a?%l#$i;eulyBxbO98} zk-625E3yadmB#FouT^x}p0S15LR`h%DwUeAMo(k(Dmo9~HUossA*sa=TnfF* z2JSAEHD*&LCmiBBVpsMiWkg2il0h*1HlCB3(a`|Y2ij)6G`UG z<1d2x!qpHaQx>u0=ygZ7jFLwAJB*U{rsaw1?qFCwnFW13-$!p_?`RJ6M~l?7xO6t* zAxj4=x$zjl)Yd(;2j-ao$Q#ZHSBPpIoqNMAHmWnv1&=-lH}eT$K3WOrdc*XZ7BkC+he6Q1WoZrkU%+et{Wjay7rb3!vccdA^*2xNn8+|Nu=3?0HJJ!(V z4R7#p@w+BxF=mbK8?Z^&4V0J;7T|R2gTyoc=cL3$({DIlTSF3@5*1C(i=0FNLk#b$ zdO^TwK$-xM=A7zjf;CRs6dsmQ8MP_hUXj1#_36mtu2^(B>;Jh{gu6oMlk9v3GnqI99Y=r&Z-xq=3Jl~l~I z5026#*|^9khft6$!obt(jgXe=H7n!sCI(a?xE*W^vT35lt+g8AUK2cHZ7ODEw$rdq z&+$8^bZY=uW$y4;EjGPRpl5`i;cgeAJ+vFAoCl#iT;vcgWQMrQ`3Z89C3!XZG-D^Xs+M+Q%AfDiTWJH`7nqp|k@Hohd6t zsL5q`Jyf{{M8vdE$PJ}eV3a%x@1@s@NI3#jG_q@{ho8M6v=Q~E#bG#Ntsgi!JY(i* zo;8jxu0TwRnGDrMm-x5#d8 zA3_nE#BW^ZK=Y6w2BS4CZ?o2!2kPDw0VX-SM;OX`WmL2*&St#Vya&Cm3FOCiK=e21 zn1vk6u|;SyO_UY4t^mN0cV=kfsYQ?{V1&*=bz~MrKsrcRah;)*uQH&BmT|?1T}DEE1%CLWMPx%lH7;LXFn=f&wnqh z=kJq9nKXWnj%lJ#4=e6+?4g~&OF##3CaAP)tD$r&@??0!PH!#?Gr*L`s7h|g`e#OZ zN((R8w`$?y_Ce}5$n3!Mc0}+YxIu@F#RACjBDuUG7BL1Jtg%z~ZU~?!24TaS%VEKW zXGQ8sJv}d*{pjSOn~P(c1B}eA{LUykY)fz)ljxuTNI2x(0Kv*5Rdo7u*l5VEr1!m5 z8d$%qsV4m`qv(>I(<#Jnq6;UC9@m8I(|}Fo*o=j2igTilN(o-9{*f7tkxe4O)<9@V zE*6xpVqDA8qBm`GABg)h!DQ>>Hu!L5d{r;JNuDt-HXW6(>yzdn>vM1<1Yps{m8Zq- zx2svXH2U#L=C<3OmU_^DgxNLBW&b3~`j+!#yN?U1l zScG23hbfvA(}zcA40<$}4r=XWO-MIyG8SPS=#!Z#_gD!7dKMRDz_H6jhw}wW7tmqt zxSvlCE_n$Xlp!g)$!_f>ze5ibP_h0b7Kjl(Ieg9!AwnYA29jAclLCVTrK>0sLhxt) zv8ZZhN;4*3-!_%XlM%cxmpr0KM$T=&%!uW}JXltY{0V6Nw( z=sA<{V-!+g6rjoO3dx2=BC@`+;f?}89kL&!LF%awl7FM;yfZ2qc8(hr2Hmu03;KEcWnC>#Kz}ICXBCY&s7b))& z$XUmFd&iD+E-~_Jj5bbYX2Z5n1ct<2I*t}`()pd7 z1fm7OqA=VRc)Xgts}cUu$)ELzGf+4dRnq|u=uDl4=Lm;#qmb`CBf_dEC*vs5JI^TqF=WXMKhWWv(fJ}=Dk^A>8j zV-C#L5rL}#5gTjAYH-hq@dRzk4aoV!Q5;cby;A~s?8Bfb9co9^>J3q^u!Sqv`Wf(% z2tW1ONR%1Z4gE!Z0{$fJzN#2u@_dNNKIQeC{Tq%A3n)s;hf#$5X6dN7x?I0@`?sWG2jpM zLGf1usSU5&QA5cB##j$eHlN&_p0+?v|Bz^2MQxM*|%_stmBcKWdIe!$jOFO2>G3 z;#ORY)0?U&mzQ#o88zR+H5y0S7Ilf3u*-`FXPSQWf3E1KX8*s-vh`DOwhLrTbN-yn zK`pNpD4lbsXhbX8*JFe#@Qpz<&n|!DDa}hL84$#*a-hY7g#5b6$zHG{h;ys`0L+2U z2sM$fjBk7=zCN;z$Cj=OiVWwBLtsDnxFH@*6owu_8x>OtAU*$!9yyT?W1ca5Zht9* z@o*QRw;sBvWni;MHN${`xA~D00C!9Za6WY| zV$2>k&<9`zxPR@CKbGh@jDcnTgj;*a7^gq1#*jk=#+S4vw=m?*o9U>*)WgsTfq*rB zH^AF38%S(5y!+FU*SU5KB75|nguTEOXOoR+B<(p|kdt7&i+xX9O{<_=YM?##VI%^n|7`EDsU!T0kus zDW^9X%9;(I%~%D3Hw)yNmW~!Gx=;0FhB=RA9tI&Pkx|KzNE8Cz_iWR)~~c^723%e)s3{*V0w>! zqrZO-Zm1jWW(c%(0VEQAJpPj}It2;;qpi#JI@p0UW1H1LgHIi}h=6 z&GP7ShaLJ=yg|_{rg?!`;)f_8ZgE|Q{7>m+qW37d;nujZ(9(ls%8LLot?8`RP8vPq zY@|M~l0nFjX28p|NS3N(0NEi>o3QWpVM5@wj=*ix2DDEQP<1wab53gok16j>k}Jp< z9PLHk{lTyx?fFdPSop_df`<)oyHrzRL@^l`BRmaXIf~F>?$o;GBnJ*Z3E=)%^0@Rl zNxgS0TIr@fj-B?QVuB3V(622XkhBlb$I?-7xz)LTS}|)*BX!GE(TEvBmK5~WQ9M7z z^~5(Gi~+6aTxOfRLvH3?9%xfBeAYa< zMS(ME8|3ROUzWnBeBnKa_^e-QUG_|qo^j|GgAR__U076jnivPmA9@i3J0&!Jvn=FQ z-=k3)UnliTHGp|$P_8q=oWv9A)mwCDMo=?<2WPWzAvbH0 zVyRb0fr`%1J}@~}!h(mY!WrBOhngh(cT>b4uwD7_u!c&UJ1c+7h^pspvHj^~H7-_=waEwaQ!g#wo8)pOzij-S>;gT-RQv z1stxA5q*}?$#j;V;K8gAyY2YA49?FOqsw_Td?=znviOceMKd|nGgct`ulW=-1bvCv zJmHtAkkJG98ky^RbdoxPTdy%TPlvzRJ05+I8-7uv5f=&ff3DV5fJ$YZs=r@^cs_Po zpBNLg1%7SzGV_FvIl4#cbxDiEeIRSdf`t&D9+Boft#$QHdKf6LhZucAn(Yza4AEA^ zYqcMdz}bQybc16LDc$n+k5f8!i{~rGI@jk0>osQu(g|tnP-SO!KY&f=1-sXpL#^zQ zmL(|$b{!y%Onei0rX=S{@0evR;v1l7&kH(N62JXb;`^>IeXVL(7xn*TjV z#&b9Wl9F3M8U+#R8-+p=9%ThUnEPydgP1ciE`%>(o_!0^0EUePc%sL?F4s7vbNY4p zJ2Ju{pD@Zw5%tYuZ&hqG(=l6MukS0OdHd2cP98sD$bZ6Dh77A?X0XhP$Hjs$L8+)J z08_t~>5|Qw+0c_1G8i*FxRTu=A>MEKgZ=M)cawf!Xn<+*{L1-B_tKh2KlQuQnNG?D z@eWkGipygp9!A(7#)mqkLO_%5I>zORVzdY<0F4W}_UWRzU2hAotB~M2cMo}KDM8L- zk*iFr8_h|_S?9Wj=P&}Eq;gdQU3ilhO&as=C-6yp2s!f4jEO#YR+7N)dZ`N5+2F`K zY}y243~nRq5GveANL;I>0#pz#IC5}%Ljm9yyzLKoYs zSB}`bOEP>u||}3;AmsHx`h&6 z)6Nu1;u0aupv!XbE~@TkM*W#=Y2k+j!dbR-#q3F8g#VJ(uPF68?kH=C29vilyJiQL z41p3~Yh9YRBm)5!QeC;fy(vLU2z-O09>|Js;lzP4pF0mlS+w)xJ(?xw9pdptw?>%{ z?dS8KWsLqVW8i)5IlK8|S%)KuG3IbfCZ~g4k#uH%eb$joz&cnIwo~@wo0iq7wX?OI ztQJaBWPC5`hy14<2Qk|I#3$<(j8Tj*C* zg7gi_U*YxgR!<3G%2cfk0lumu+FN?YFL@`H+V9~ma;pQvfE(Bp6Tv`{ssX?$;sVOnR7J%Tp$eax=q}RR|0jg`F&m7kIyBaaWj0OegIEg5xsXGD_o~ zIk<8L7!>ly{hWV3S zxmc$YYI9+ogh6)j^Y1VG zADe%F;rTm{|K9bx`JZ`}|M-*i&p$i=*I)b6{m=jLpBetIzy49wUH7lQhH=RM`o}oM zX}$d^>tFv^w`FYefBp48ioYNKo$$}D9`ZDv{`FU~Z`=Qs+Klz^ufO_w%a{M1{`b4C zeqa9e7xKST|Nr^?^Q^N!WqT90B_7sdT>5uk@wU|0|AhYydjH^m`%}yJ|9}0T&Gdfq zwhHxM&oucD75cAd=xvO@YxmD(@7{{!M?Q>M_SZj-Jbe-SpLtQd8~;`H|LU2)|JS4Z zkN@ZY15ir`2(Cgw_Cwb+&dao*vm9{n-pU#Q=Nxd5H*n55zJ77Dv#P6S zdu3%sdg4mB!4c+0)XveP8iD(-|JT)be>w7Ht;gZ-e}(=9{Oe!xAsw@NDF6Of&*lF{ z{Pq9(w|`xa@-JtdZPnlZ`X&Aa!9lq1|N56Iughxt$1RA2zJG2Vb$-(0_4mJme*ymj zf#3HV`s-ibIfnJ`f33D{`fs1ld7l4r!v8WZ<>w26;O8CupI!dj)zw4$zv>8)B>DNr zPyhOF|62Z~sJrg(e;vjl|Lb4YZ5iAA?|)6YIBoy^?ce^n+IR9legC%X-PWkvP zH!qlfQNe$2z`s2I>)joBx{b@<@}hVz{<)CPzy0f{{I`G2@?!nBfBmx;^UoypJIkLp z@PD55Z{Pp=x9^_`!T)GU@-OOp`=8Bw_xZrbxFIM1x00;i_^?zeP690Kd7<-TFodLnV|D%Q8Bf*;yTXy*~nmAWCmZ}RV+YC$~ZOJ6h_kwrc@Fa`MttO zWi|t3hQsi8IN%s3zxL1BgUb4m;avVc?NrNtt*CHdab;OXbe??*_yUkVB1pr`v-NTB z;(^icvz|CkToXY&xZCtGhLIY7SsqXSfPfSor&s=mx**Z6S zK3m&n$?g8ZuQ#)n%h+X>Mr}Msjf%BXc2~OSw@tj#kqLJ0l^0JF;Jh_!1CS}FezdC0 zN;y-X7?>A&vA=)&)*u4d|1#kD`7AEN^q zSs+!dUCJ&SzYxPM8zoqd<|=@_RRhIZnQ|NLPX;AC!b8PHxhC+(rsdPOs{oGH`#B1w z+EhOzJwDk1xEd@Rw$wZe5TLqEF9h7-bwKI+0XL!usLAA9m0kcY*ZM7HM zpgiyF8>*fv4NIBB)?vH8x3*1r1z}S1NxRq-@t)4!F4;>hO>SX=uL&SLV^BOt?_DD%na zs1PcFB!c}OuX1KB73~EhQ*+F9&G3*~td&#rV063T6J;1g-~ADe+pv&dCxB_dILX#V zc&)b2IuA7uRsjFTN=0)O)yw@YpTalCzM%TXYlJJ9tAo8LvSO-KR0{}(voB)IBb;XM ztz=2u(MIKvsHFmjafDy$k@>&@envT#ncs}bR8*d5q~*0GgyxzxyyW<@Zkpx~v4}Si zD_2qjyP@Fr83I}PzBn`IpZw%Fdh8mOYSQ;wtQj~*%e4r$%WZyp4j_`|fRmT%S%(!B zXs?gS3UsRG>eGb->iV-ZensK)3nekDW(a)aOD;!s0PfBwx5fg7%RS^%yo zgr@^TVgirn6^R#)b4yp?nw9`4bXg)AEAlGLNjjX21>Z4B&<4*R zS^!xkPc3T+Uy?z9&(HJs?n6PVSZ}l6GZ1)>L9L1v+sx}1@O}_;vb|p^P|2O}()+vK zFQV@R6OZ*FJWPB)*Y^t|Ko@UtM&{9fe{K0STb!M00+%oXPfpt$m9FxSUk}z-h!YN0 zYxdO)FsO`McDl&OKrk)SwO>yFbmF=~Gv^|CTY8ma(8PsjWsSot-@^~L^e1JApJ>2* zg?;)uhImM-F-sRUx{qMAq2|}2OX|Awx-aF!8-(0Ui>;vOIVurTs)5Hj*BB`UQAr5k zLy)ZuXk^%E^gFg5{odPdlG&bUrhHs+wY0+O>lBQ{5IV5TCUG+5gX!05lcbK~3*7Gu z?yBEj3x=^`NAG)Fdbe`GQ7&6oR4f5bC%|^JuC|=oR|KMArADxy`*d=BWE3}#A5@wH z47IbH$5fA+dw~ZGG6dxv)UIt1KR3!pl?t@99mGXcDKPb?`YkK$xLCYfmpX$xEes;; z@1oum_w1V!=K18nANzjv-LT||&}f18-~(vfv0t@r?!d8w59w9V2Z%?8gh1;I@+xn4 zxkHfa7fzlGik{O5gCrXV#$ z&YJRbU;~Xazzh^EvYTm#qYGro0sde^+BeAO>Uw#O zWvQ>WA>|x%zne=jw33YFzGcH0Z!O|)+$-HVBrSU~Q9!T1(>buuO)|d_cKHD+jtr3} zgw#`;kQUGr9}TJ_%(IaeHUp;M(-hU?@{4_=;hK-mk0r0ps6QKUwO4Zp&ZTv~OCY&{ zcW4b&G|^ygyo+F9Gc_&NsHxh``YNztd}4FPrVD=zAc;v9RH3<13b`gM_ZdlS zXv0i3)6GE>xFzyTz3#hv6CpHU-yR;&wLm5XVC||7ml6H)cG)J@a*w!OMI({ou@#z>=NK&5$ZFuftLZJjuO$8>WW)$JWZWaX>9e7;20$e*1`k2f&mvNUOf(k zg7<=1tiJIe(^OO%w)y62*E}I6c8=Y@Wv#O@psev*ZPzPH_GT3sW9Zhwb*~=h+*v%ViR+tTSz1)2oJyN<5!WM?w<-mKB7q7G{QJqndP6A zMX+Cx1L@r6u|AQc5MEy?&G0*$QZ3ZG*d@#7&ZL@nkY{ilVIHZH#9AI*L$8M(D(2RW zbDOr;g-3;mY0DOQC?4I|m6O9icwjuDI_fJ}W@a6QL!vMdeZQ0jCvt3>uo0#kW}D)Q zi;DNdrxNcL8*G|un;}*v1Jk2I$h~VRhznLlQ3$vFnhqChykf6|$niwRl6wY`==!fc zAb!>w4FjbgZ;Tf4*}1AtLf4=LhGt-$8{AA@K3!y?sn(KmAgkvM*N*JD4{`1~VJQIv z)PvR`AYknhr<2(T-;XMh7njQ?Pu)Z$ZiW?STn4unv*+M{Nd+7uh!8jzc$ z@Tr!-q+i+Ep@31fhPthjJmO7b6@)ctTTK`=b#`h2%o`>(`bm-%=6RPzr!eT#tLLkA zoG2GaPtuxfl=o;rogmEszQZOPnY`p^A({&&uPjuC83C6A6!cfyG7t7}teJyCemq=L z<|Yqi(V~HX1Slj=1Ee^*EPC#UtGMh!ndEq=*CI&6unZg>9{h)B=jl7fFk7u|YL?)B zTD5hwRXC=5nt>z|dA=lmw2$raSuc*!j)u{}y}Dm)yz)?Nps`pY@~g^+o`n|S^cjB# zurK-(moQOyheRxj7*#~z3VCs)(p$+~nc;PKh-t{>EZ_s*(F5ki{Bl&Y$OsCX3eJ$8 zPFx{$KC{2-ZZ#fFNA+Ixk+k48`xGD$ace5mv4orsL`)&9#-_Mn;mQwPe;eLVJIA*q zy^RaWdYN@Al07t{hdLZ0JGbGZa#6Ph1-UuQ1n7au9+EHl){?tkx(sZ6F30!01O&|^ zCKlsYt zT+@?n;=7;~%nK137}`+;ffk;)Ihwh!9zJu;L$BPb2(A@I?ORM*MBY zTIGG1%SEZq`)k)I7*01|cuP4N(`noj>OmIx^obB84N7G(z*t5_kz_JAa?#0|6dPo6 z;zkdO9q2TOY%pB#Glvlm<0(I1-B&CaLdbjyRc=+koEVM-5#zA2Or8A&=e|1xdLMZH zh)h;&;j5pet#b=yb$=385|_*oGFLQ{_iMK6v%~l~sT!3tIe(IvwWxtxT3ntF5w1l; zC#u?(jU8O(<}d||@QB~KkyEmu><7T4L(HX&>Nw*lYy45Br(7zQ3r5Zol^e(dcM`f| zaRsff-*Wqw4Uhi<*+M1Y=ashP2Qri}{bc3WUK+58;_?QZ_tM~2SA#$pFbh_(@+TC~ z$7t!{PyI214-~Tb5%g3RrFGHq?)`O)>$Su;0_Zp^h|r}3IIv#AgOYC#a-w1LS5JA$ z8nu;e>X=}lu`rmYd%n4F*3qRUxzy@)s{Ft@VA-W(e-0-ai!BzHG9v!~Tm-kz!f_9G zeLIB6krXx^IGZUrEEWAtjMU9*=Qc=?>R=%`7nyFPTacBa*8Kv#1tI>aQo;5*?-1qn zflsFH4WvN)k6tNR45|-t?ukrKj+GfM}ep%jQ&9R6ddw3XIh%~6QtpkTd-rDfh z5s^%S@Mu(WsvIvrHKUl8r9%8Jdbuw%{bmOW2Px$b^wTrpBC-&iE*-&%bv8{pro&0S zT!esFZ{X(@z{koElbe)ip@!-#5r11S(fIB$IJ{CW{g#2%Y|NI4D}2a*N~E?ePz-+Z zT{R(U*;BrG-fi}CgTp-qPEL?W3D2xbizs8BoB1LX0OKLN-sf^PksLN$+V)k9DK> zlg9yk6;cEaKfT8Gll%ROSq>2U;p+(Ts%P_Kla{nBrTap&zy*d9e_QGH`3#7~VZ?ss zi;nIg((xIp`lg>vNcsy&5bibdZ0ZKaJME*`R~Nca<&Gm}_!hoBqcfENMXxG%H#| z-%*f$z>+QoHQ6O}w{%MtaSV^cBp~3{SHOP(D?-~>2h}+*C;SyM*Q*_3Un3qVg06ta zr?ZDmF^x;X3lO5r769mj-!o1qGsa{aUvNu0qSEQ%UIh#_)K&-5bjXGp5XER3A}9M6 zSD-z?UmXg40WXAk>p4$j(rcki@zofYy4V;x+dAtlcBPRmm9EK*-heEMInJXStoLug z(5}hl0};p;=;9C1AGOB$2e1z4CDU!gvNC}B{T93Utv0WI6`Q98M}ks2j`ZSV_ z06mw#`fH0TJIrBxwux%6=iQ%DGqWvzSftRQr&m4WnuVlVokcA261VT|ybQjYULl)R z`?39#aWLkioqlv*mCXi7EWhCo+@vX8?k>^JE{VUA{O{`zX|nLEsbb3tLqY$-XY*=q zfheo#54Y6>_mI2jPsFrJutt5_Bi!ZitB^=?KA=c6@zx<&^zIuyhQsJ%Y5jx0KKF8)JEYTZnWN;cbYx-Q5&|MTwj# zP-2z(?Ymz!W)2csFUKS!^xi*U&2Js3K^2(ng8Q%PNzDxTdGcUSOgphetA zYqrX59oSl#ieceVW1sV^(QgyI8gTEy4u#^Ww+2hEA$J}V2T79~ipA$sqKpL)-l%4_ zjW0Dg3_5-Q7IQxUU>JSr7E0cDrMEW?bRG~-OCFS1w;HvyQTw)@zrt! zDwRc=ej$G;w}QDqD&FUGH)FeaPc;dx)%)}7c(L!e=Rdv3_+AFo(bI_aIx zs%XS}sRx(~ZWc@_%p&vVw7DU-5mn)XlGg_vh`k@e?>JLNHGTw94YYQ1oDP^=eE*!y)DLi(m#) zi(+996Gcv6EXcomb_*hMom+w-_M))oI#b&d6o^uW)T^gyW-_z6Q%pJiI8M-6(~LgW zEQ)H#T6x>LI~x`*Flag3r7r=kE&yBCuWb@V8Rbtt#sS}e4q$CRQf~+lKg=jci}#$) z$FFW%Y>YI`hwKNb&2!!@=M5^7r8uy&MyoV(tVh4GBpBrRo`&6w99-9dD8arEltJ>R zwuCfQ{Rm7wo!|4;t0l^npBt}(`n|JT1ts(vc3Hf!nSLG~%BV(tpxeH0epCb;#ui(E zUe`w2tHB=Wma&^?woMdv*?U6ly)CWyiS_10XXL^3#4g8KjTtAqxLPnxvD+x{8&HYb zVEudt{Ga>SSDV4(1&lj-Y;$@Z!c7+wcqjDiwx z;Qm_82P}t;PV~3V{RY(ctnF5zk)!N=|CX&g45gC;k zF3k`xRkN{x?$r9h02uIceFKw8jc5w^uBh$@41m;L4aeENdCOFB%QaU*);d zfW|r`G}S!~$Hi&YKr5ZGuroNdK@F&F{yo=(FzE##xISr68$hI8IN=6`&=sDCOPZ0WEGSkHV$AImJJs<`T;ZDJT1DiAG`Q1d}fKJD=(>)gqtgI=8o6 zEys;S={%-HuVt;Hh(bSkgc@@oA?j;bb#%^b1_48lWE=8AtfsfC$4}yqxEh3ay5vL< z&Y#+S9g}BhX0axo{waeH<)yFWoWHfop49(zjNHTEm!YNu5YZxd%lnfw<&-8rHlm_z zcl`0D6gzL6*61o?SY9#U<~Qj7WHgX(P^*5x*cx9Wb8 zNc0OV*E1X(_LC@1|rR_N(X==Cf==oYND9AdWh;=&jb)~a^;iZq2B8VY%Jp=-CP-1y)VVqAm!o;yRyamWzgAenU60i}SQ^ zH5Gvz^qne)MUz2-&?nE=s>ywuJb3n@Ee^)X^-)XGLU@15_cg|TLZH4?$Mhg~y*_EQ zebsO%^gLbx>T{!zxJ&oflH>LXu|vr(c(@xhyq0ZN7<~62;3(xA9?Ae3m2zu|o!#HF+x}6fv82dRcT5cRguzv^%!}X!y zWbxH}Q%MjA1`~(-Mt~3lVSPylx92pt53D`7`}LZ2WO;tWm^_RXHc-aj1dawOWY2?3 zW*LJLgj#a1sJv8h1Wm5NQoFhw$33lWpvkE3K5ZZ*$1>#n zy5lVs!A)!zc^~({R*-~jsULK1R@q;JW}yu|Q@?8%VNHzwiGCIkIEc~b_OuBjsd9J= zyQ}sYwwYCLnYe$SMPR4Rhya^qq3b70K5jJC0?Mj^>!bmX-v z#Am(z|1TSm@*ENWxQPk||9vFfnm-W;$dr@dLk z{ylZ_5tm-3q_Z%>j_70$MiQNmVqv$psv$5G%QRA_hVQn!-TeWa#KM~e@T4TZMr`Mw z9mf>-{?JAl%MnJROXS#G;m&l)Kna*!L{M?D_lFwJ6;e{fJRSLIeu8kVmDt|-&n8uK zzKz3_+A}M{?PcX1`8J{I;j}5BWLT$pF0^JhfA?xLr@}#{2U!5aF(k~9KftUx9r=Au zIF-ZDZBof&Av1^Qu!=$C_tThDzfkD241%*iIH zdP|*P4ADe|wl3p>Il1;Y%Yy1g8-y?dtuT6*4+}-cUAha{O*0oR`}P^u-@8EiuftKD zhHdoybsxgD*RhkAcr)W48n9F1WjuQLes5<}-?DF2I>sQfimKR}fUX9!8;DRDwMJ*0q6oCW3#n~bIn zy2r0|V~0cczSk;=35><>%zF=Hd3R)dxnKvKV)6FW*%%eFUjMu|>?(cq&l3*yk4mi(ph2@L_W!)e^u=R)KN&a^me2rr}se0<5IhXtJ~L) z2=+uUJ1^1v_h&+ay5F-eSoF;+8_w1^z$X>%e9fy5*Rw0B zy0I0EcGV%-i+Oq0tIWJ;m7*=b<}2}t20n1jO#3~+0FED|!n`GZw_!+puBr`sY7wQn zP0VMWhMg&=R%W765VuuX%l2{fq(o2Cl_l(C__^y5W41O(sGJESIe~G%NJJqorG|Wi zG2a(z?$56`d-JW*Be{=Fr*5(hLX?r~Ho zmLj}-km^7-Fr%=N$;ok()j{ZW_v>)nkovrHe-Z9$?J^hD@>@{JNVzuq&E)rvr;Yq>0p4+TBtiEf$|6PGU@u#*k|d79C!=4=!qWr` zbdj!h!9L`dHlM^RgHr#f(Wb{XTYf%h2{W7j@`*h*0jL(9mQW%zec< zEMn?sJ9YS@v=K>x6hL1w9pflEQ=mRwW;uen{^z;VR%folz71^p)aF7%2^=+Fg$bMl zBgmStCJnPSG-BP505+OuIv5^t=J!Zy(_pN88vKQj8|1L;wlFZ7|9qqQrAVE2ia4@C zXt=9Q1pJ2HKhL9C`t@a94k3`(w$HcD>MxPjW``w?(~AndYF?F3$;YW#o5nD$O+$aK zFr0_7(-eXv%=8DiSki~`CPmS&?+Lvz+~%uAO7PM=HgI>IJZ#G=M@SAIskArs>@Yos z8I`-fBOY1ZuMNhM%Y9C)(3UM}kp(L*k*gw!QZ*N$U9ch(M%)jHZGio3{zx*;_sO%b zJy;*k(};E1mYFSU$P^;6VoX^QUca-z_M0n$!x<;h`d%=XUL1PJnXU4nHECC~aP>xg zL>G?9V%z;3moNm2mi@^4bA9Nad{!|npJ$i8r6aDp_#BnRuEP#+FMsTvv1M>xja#=K z0=-krptY_s-}YgBZe75zM8^H$=cvW5}=w6Ca=W z0fPU7WgKS8#csH+(Q00+=O{&Phddn{vZ~(yc2HdWT1=`)+u7?{CyDS$4tp(uc_HsB zbjPb1eP^xXG|N|G5R1gEP6DFbw;-sUJ+3W-qPA-$u4fg(YG|Nd&||faxYD*&wO2nVtwzcTZK~2@VI0&MkjixKWnqjrIv0vbuQwQ zYc?y-Uv@EjF?3bipSV$7wMbQtc@XOXeDiw|heb=2&7X;Ydx1C##PH~Sy_!~KPP1OF z->ZKrNU`!FENiPTAg*igMYL4*s(5m%XeV-R>D+&ig{I_(+6U3)?N^2*67%`x_#3Bm zQGG}tyGnMNAI1SbM@5)+c0|#yqs|gC3=+g74Y&?JTChT<=3j$YcD#W-?=9^MX-}`a zxkFF%OD%1|AJ0gpn5cECJ=9Ml?9m3@VG|7rte8P&RwOHZZ!f0Eu-w71f+@yfg`vUr z0WriLwvDZF84(HdE1wzPylLe61}r8ZzFuhmSyqw92M6bi6xE-Ubys9OG1K}GMc|y6 zFin!o(1y|?k7RS8R>wa$1eX$%QNkm#;YS~4?0a|uhlvPc1_g?q1gIryLsIcFY1}&=b|dl zRImyv%PohCSD}!>WXd?`D->Td6kd)E0rzRYLCcY<3Vum{!|c>~ei9Z&&y>%a$vJ1` zpbDggrv;|gP2bWmc9*I=Q6On(aF6#7qRtvo^E{kg0kkWfp%gW2+&U&_TNy z+)N_6IkT(R&bnya_IIMrl70?djP~6))a{;lzo$RV*E1ZS+8c}EtMfN*!op?zhRI-y z<{MyLn-lC9Vrfb&S|wDKhSX7oRp4MtEepcK2B{_=+WRQW6XU+hY9+<4jfk`aKSI`B zjP^Wkx=S}`JQfmQ)tb)A2ImKo%>sFjGftPqD7bi&gOTj#OG#J7v8+P&QPXkhTbX<{ ztKTBHN$kIZuRFC(Ci@4_@{y=l8tvS9LZFXGx3OZC1*gAm4p5i6iF6-&vdaA#YY!-L%p2Ho*=UxVA39(Bz@jKi z{PTRgG}{gb==KZ5>Sn)Cy%HC!{cC-##F#E3Q|?KjSXpEwE4L>;F(d@GZ!CE}?c|JM z)~5-5{SftMKH)tOL^4XJ_SUDWuYZ}Kcl3+N{VEF*@cCAK-Qg?IOFefXM{~;0i1-8z z{Dx6^ZTQQ(Ol)P?)+3$PT7S+ds}di1eKz{5(XBcc2(=qB4i$(^k+OSej8jaQvsYk` z#)+}f;q)T!$OYWVppMx2%G=*umhtIVUt5XjP0rIIJY)#Y&dB#_r=v%7gMQdK?BOvG zfv~O5vdU}(^Sil>7#DkWHahO+R!l+lC2MZ9*-srdUYdayKClc?qB{b7{jxv_P-X%F zC?}@=+i@8H13>)0tN0lY_g&%NSMB;iSp#tm6*Bk2k7>kBopG7#Rg_?e(Jj#a z=WBma5r-4o?$kg$9Ur3CIEd;8Vd*?q2(5=x=$1*16Ir2RY=ZD59QHR(60FG^2|{_k z48y|Ia)f2uv{a$aBeNG-@MlGwYc6$*kg1irG@dX{uHPOn^u2)9bFVk4Bo9KuTBiKd zQy2+RI4O_M_JDf$;nykN=hvo^>_#B6Z#KO}pOB<^?ue&IV+lEA;cSr$uK(wmj4ufU zQWThV!|eLg}<$H0r4eJ#QdsD&lS5$m-R^;?lA<_kTWJ;DA>Kh~=5Ba=WTY+>)3 z>D#Lxp-Hb@dTBJz`>pn#`z;&GKqV16a@BGhE>MOde~^A%`f82yr(^XBOUB6zA&DhS zw`#nTQy*8xljowG91_z&&sm-Xj|<;((c`s12y_zJH4x`NDU)@P=F^yZJcbERDSq(` z#=pKd6wbZvTQ?qy!$LBbyqR^7yUDX=dUv|;qlRu%K?#NbW6fFomeM-g{53HO9t#sI z;)srK0|oOB@)LBuNh7_q`uzP0&~C6HJOoLE;uezW4^_4*8dq6vbES|C5OlSs;FHDRwo z|A+xUPX}ppUE-pf8=01{WAf{frtwf{TJstC{w=i;2E{h7IgRW1@Yz&Jdu(1%C6R+( zIeu2FNrF5vm^r#~>}+Wp^!daA(>!kg_5LC?se5&w&rBGGv9>rWm(?C@w(VeWZEzqH zq{#f%8|pW}`h$D`dU^A$j_TGstDW5EpqvLCN5bjJXL^xI2>acwvk~Sd*3->@U(ym4 zP-kOQ#JcqyRsM<^i12Y@Zzo+UeTs>-n<)B)_Uj=0)xGQuvzvl@VY-myo}c}6m#s~{ zzs=pWuWlWT6)+Cu{w!zBB)0yIWD3E1$id?n72^iil1!jrt`)lr;vl$BW{0tkNg zMmP){`N+KvyH00-(C=dVOHA)c1FaPllgj>)7 z96#mivV-+#z{Me+sd;C?uKk)XbPAfuJo6fDOhHFqBHxPRfu-U$9$4)CoqVW1Q@0fN zVrGNQ6lU*;B3Ph2QE*78h}i}9!=uw~zIt_O2%N?xEN3Fs-{p%jqt_(Wo*ZMMIs_0q zoW!rdHPPJNBlPf*3KZyzx9-5TH+f;^5m-Udp+5=_;&!mq+*0dkOpQqBO3_rC9<2~!#?1fEO`(cG7%S$ zo^4ASJS%csV3u{UFd86`V(-cNu0VOxDq8@-CIyghRHCS?#IFWleDww!1ZanJ27QV_s z+W95BX_D~6I!fUjx_`r+L2$-Bm+JsVb13ia{ChCM0C)Q76A7~A&D4b$H2QPc#9cL0pv~#iw^lGc4fRH zH36uXUerPu#qw1|EB>LIa(Y|O=zy3^lsrl5dLYvh*haw)0pa9*xOtHcv}CN##>DCS zQKu*$LaIZ}pL!t)U|jjkb0pL*eb1ppqG=9nAjWVh2+=;I%(v$X+Qvc8j(G`VGiqxn zi^HMxO?+t|G}UPFc_oBQ6>|n)QkaCppJ$VA%x}x>V+!HP?;IN-vnW(HT1A*T1|S~G zsgQs#W7RZ`gjNLZFLj6_SR`T()c=-J?~N@Iat;j2vMhWn4dQO!Db#T-4aW9&@s*Xs6*)W6oSaX~?= z?I{hfGYLmW0X3m-nCZJ`v;Il2OPjJSeuJI(6fg6%i43OOURz!G78sxw`y1a85;Hn) zXn!M7Ik`lHB?6`C!Qh64tbn~ES<_jI$yP-Qz=$aZNbN+i-rzg9 z1Kl63uJ3aE;J2=IDz)Y+nk-mH)`V2;d3VN|kEVfLpQy%*ezv+hnwVS|i)7hn^^1KJ z8=mHY@@oF3$I$-se~?F*$>#7V=v!9}Yp~0~+A*RKRSw>o_EK&$158=R<8tC{QeZ-d z$lzpmD|8dGM$BVQU&%{A%aXt2KOS3Oi8__Pn@^V^s(r0}IZTVQQf2BNZgljyoX)YW zM= z5U~~RrN2+{Pi_3mK{PlOAgFWfu*h>4uCvAu}7`Ew#hE?VTr@jPu%iJnC3O9 z&Uqs(9EY3`!m;h4e@5XfZ-e^^9qS#&8W}5!aFNpfzezf4Em@TSihd9QZeio@G?Jl> zyMO&-?h7WFHLDw_s&n>ckYFbO7~Q<}GW2Hyw0~nfegz}`bVI5%<>#~>Y!#7HLqWMw z#K2+NlcrVf5vvxe%x6FTTw&m*!DcQl%HBnO69D}b zuML(5qd55(2J!dH5L3G8I_4+t$%<|6q`N)ji}b>;l_1<;5J}p3Z-0{dewfGSZUIfd zPLIUbOS`w#G$Kf_9Oa}{JOZVFhq6Y!&BFfzf^TvzkrNj5twxyaroZdG`ux*WOhnZ7 zH3=BaFSQ+u3-9K}u_aAGS8vJ?09(bCn{8Dr&D&BqccGi66mds`>hH1KkZi`i*5;hu z)LeLyDGtetrh?!aJA-vs!~$dC;m8^*x=K~q3sK|fw1L+$z%=8a&%^g`$*yJ4TP0da z5f`mrH+^SP`{tg!ZVH#GqE{QUt+Y?C>vc?|$QA2P+q&=Z1{|o?jb=mRu463P$6P+<1FA+W-smSVwePVW%XDYB zb`rtfyj+-$vT8hb6_P%9>KHDBk3qSWxYcFSWJw0h4k?#Xbv zHzBxGDle#!OE?@Ya{VqH@7A9t9OACt8)N(o<+svL1Zab6oJ_}1D$(I|A(meVN;u0Y zJOGGBiMSPPkRv=*=)b`ltgE-o74RG#L|&(P0HStuv*smsmbfX`AI6y6S`p6qVao6L zvs`gt9Q(KB%up+8;I!Qjt=a&v-YAhH{#L`DH!nW<^OM7he;SsW1aGkA=K)9zX8;i` zOv|%eAhUJ0)j{;Pw~lqUEMs7^jeVQD(^FCCxnWRLr2K}NBEKujBvDsj5K&jkNDNz} zShQ3rxD*Mj6Vp-pM26@E|6dtI>onq8cG2f>LJ_&FRg<-#({-*SACL{^XC-sC;{q;c z@=rQdcHy4%!i_4?STLo9!0`Mi$;pl6T0LA&k%wYu?Jj@levq=4nv3w=^;h%TcofE7 zb+*@Vxy-dP2N~(anslZeQZ4YBJ}5sF_Dp>**AdD@;9Hw2Sc;K_1a|M6b<2OMBI`zi zFAR;2516xs=scjG^!ru?#V|=nt{ab4d~URB1dSzzNf%V;_1)lT3<2$gYhp9Yl76Qh zw&d1@7^g)T=@U4d$6SdV`O~YS-&baf6_6u^?S$rY*LXH-py4#BoPV}@$wKe{ECQ-f`=s>!`&YDy)VRYV7b|7+tz~SsRg`X<^ zzNaE``PXtAPy4%;X|1lRRt-e_nU*ezcn`hhsSbRNJZR$;RYNzwHgrb7+PmFpA_MO$ z6O?V~D!3e{2xbKf>s$S>Y9CG;lH1HUJyx$jjyw>(CP2VA+Y63>yr<#u9VVeNbhfB^ zqnhcO#PMbXrdY46VYAeUb)hdawejhr4gvXZ`st5c!4Q@X4V{QxAWq8mUHU7D7>>`2 znqaB7q$U68VH)@?x35)g>?|E$zWcUlv-i3!V2*ru-`ff8e#+bMIN-tOfvK`8#b#|< zV}5Ym4RQqG8-g}ONME5$1pVv&!BKRx2~5q4Mh?Zh(hnNQ-8ndtBl-ZUOMBKtd=o?3P-@9HhU? zvy+qMoO*8le3Tz%{@xCAQk(}og7!&{053q$zgj_&jXyXF&2{j)%w_J)yB*5jHImt( zEDz)nl{$kD+5=m!MBvFa8a*j$rx)KgX1ZYDU$}4c!jyJ& zCocTg2$jL-Yk5CZ)*PK1BPICMu2IDLD;taonaB1RN4P+9W#G1*%uZx3^tE#+CvRwK&)B8=mF zw%mx6J4r6A_TCAP@G|g2=zw#GmH}jKg1z;_8K^VBTux=>7e7*NJUn6S-qp9;Se?bp z_)c&~to_op0WOeTrMmK=Q43#&TuhUYRe})1HCn1nwD2q*7*Fi0&Y{S77tEAewedj` zW_ggCt#J&{o&!?F6TkB#H3f`?*F27uP2MScBK@aF01luG_0xSMuKQ zxm4;ANn6w=W#D{Lj=#i-z>|yHcWy2-jKZ@_!MTJ(x;A95<8HH|k@O?*ZZV6;VS=A) zpOzZ6#z!=S1h^V7>~^8KuZ2Y|Az#W8Ed+Qfo-|*(n>3x9YM#kL?|hZyMyI7A1NRG4 zsj*f*9!?z9;rfSzD8N97lxQbm8@N^n(-bZ2G|=MMf|g9P2;PtXTP64bX*S%_f=jyNjT6>c<@H`keJ3X|*)^L_S?e3KWA5IDG%Ch#w_g6tJ27+$b!XDA<$0A8$I+V4!C zZX4~kX`(Pc(QSbcE7ngp%_-(C~h)~cmdMm^qeNkS86^fg8ZEuRR0ybn=9Vd#%SEQH;a0lquFC13|Qmu6EQ&FXMmdzc(*;h4C zb4OdtA*i3sqkeQ^f2YSk)OIU{%}=R;OpytmSbm>GPJ4%!U?)LKyU6(vlby)7w}JLz zDi#=B+_9!RB^W#U$V2Eks@bv08zePbS;ZxEc{F5>C2O8sTx5<7I zBYN^JHZYd_O0&L>o*9o zgg-?SE6>AC!^IAX+l(!i;yRQyvWM{!iRmBETe`@#!oAt#P`4(j=UOLnRUC2zct0JqbLp;%ivSe26{N%=?LA~9;sr%MQ}DmER|4S|*0NgEer39Y zILccX69$~lXIRP<4W4_@nWipM7I-7$VLd;8gNZ-^n;SAQ(1nwC{VrB=fB18~!v`3z z*}g%Cj}uiFMtyd{LQHE!iDJ?@wJ`VvhyK$GPSDCX2#;4+=muc7beyy|2&8fSN?KjQF_BUeFn0h`xR6A?5nvk?fB=>XD2_q5tL&O$ z243|l`(>=SgfiKR*O<>Lyf{6Q7bJXT!`oPsRkw;AP4~fSax2x~V;Db#FAc43>$pWB`VDNaoTbk=d{zcPU68f_qjcJOG5i=4c|B?Z3Gi-N% ztB72xkYpO)pgyVb#I+TseRJ*T5g*%=${z892}9tDsJ@pbWCl2q+G-oR9{d zRyj(d8d(3xV4MT^ZqYBDo!eBP6rB6WI3sjVR)yU$wT7!UcGpy(X2a$3gzETlA~zH2 z@zO8|9(vqmrh2R3Mt%FdheZjOSZNtC9KGxZq3fb2q1=`$D{*)4axmUU!_*NpCvSi? zGUJtno{4a#jzVqC)BL+8ILG)hN^r+(-&ilJuPf_7GacbBfx*wt^V<$jbk}6ww+0V; zShnX|12oo~pP`@zM*Ox(Rsoe4v^5ZcD?dnDS4>V=Em&i(W;_92P0_hjAcO%P*axib zB;m9n$X`pD=_3;v)K3F*RkyU34iv4&O#K{XUedAXC$|TMgJk7k2N9DfJoYDT@!3nh zSHISdvf4lVj>CMy68~o5F~^69x7&2ls$@>$={muYj&`zjp(t`}Si7LNlU#m*ypIY+ zz)9djLb!bHY?ATgyvQ>*N+8<n>i^*LKI%)Q_XU%sUYnCiMRpi!c ze?cUL7@h;jujJ3#2WEzyWUpXf8}fDyGzheT_Z*>X8+UXy_YRWXTkMn~KCWHzK z`ym*U5XnVeu0dae?*0xmC*2(C@07F3&J-LRGs-FRCQ%Q3s%V14B(HC)_l3Rh7@qVM zgss_EDVx4RQ4Bpna+SUzQv$po%yt)x@@Sj4UP_oWRY+D*nSMJ`M@^$V+j2N+8R;rW z6znzfBkU2n8J&<`yHjG+cJyzJUDI%3}vDjm=( ztx+F9u%vkB%7X{Lk@*o3BV(X?rH)d14DDBhNSpMhFyiy z6{QFw$H8>wJI1S5M<2Q0;l!EmFlM^~1-AaooA2=n2O+T6+lzcyh41@gehleGe{r5G zXV-VO)82wcLN7REZ@esc1T#mEOhpZ~oG{b^8`i zl@KI!b$D=c7<*BYxVv}hZ9$u@H>qe%dw5Zm;CGyq4uo9ZL6gUFBF&;()ml(DSMs2m zCnlfNi9Wr6fFbsRz9Nn8!f(ju<;X1xAVb=#iMCXqZ?2qPnq`7;9F{ctKHpLF3$@Eb zQ(>wDeZ6FJCyCtKWx6lKm-oXKU5u>S_IB3Y5|r24!L^Q7V7X0qEySGYw5h_9E1_fj zyAEkBJlYQG&7@xH#cF2~{ROqJ$_G3)mDG%Tha_2Tg-iQSZet(M#(xhRbbx4ZBiPOA zw-G5_h+mK@Ox8t6{uczCddy+?YwUOItv3zO*E~%Z6P!>c3;?xUB7+>jyTFpwBb^l8 z3l*_0@3?Ei>|aA?vB*G4u{q9Sj3KDLFh^l;&Kn3322R zC{jm8%RS{o867bu$mlPc3BqP+PuW35mg#wq+E@;pTe>!8V{Da+EAD_krz zdg3^b&r`MxZKL(^nMP#vpx}5dYAG@$Q>i#o)RQX}_q&Y3*+j4z5rcBOe7d~jpMV1j z8cSw=xr&0nUdBVl2Z=0Hho%Ye6I%OfZQ8@>y9OBU|w-#z*%g-fdnVvRf|U9# z>8hsz&IGJoImz9&`s3?<;Nf*X$>g0(>vh`R`QBIDo1@?vOfC|59ZK36=_KF)rqTzR>-r5u<@;3Q#$;BzM6Za_DJE4*#&y`B zL|~12&wu`&IhSk+0RNg=E!xKN?H-`J7Ai{CWA4XF+%5pVpK!qLr~+_nZyg}GnVif? z5Iy>9w&G8DL+*$?OeGJJu`=32Vce^ygo9mRGc@=D?CKi$DhhtetK6#Gn4qd}AvLvO z)8oB+S1Fx*cSXzu8E61P!43sReX{FrNW~roq|`B-lrPhEbP(@r55ta7UqE=terFfH*^n zC?eK&kP1?M5zv>=0vW|hp9E$!_|C52J=c_+NjBH0J}UIyE^kNo;<@UdmH z{XiD7!+@%n^XlX^vfrZ(f4}1hHXVH{R&9E;jEj)eT!&m3Wx?K|uVA(#*QJIYap1w{ zqkh&pRJodpdI87j_@NU5x?Q~$&S`tPZ_gUnscrdEGC243R;4c*EYZ9c!qop6hHD5lGQKF0Q2wp$-9n<*=eu+Z@3XMm$-M8j^9ho1NF?84i#Q_8D z&<1>gW#R-l>Px*>9Bq&Df?{?w9y85&Zj4_tiuz?4w||>2`6)wh9|~XQ6ZnakfEwm} z?VMAwguBTkDGI15tk3M$|w>%aivqDzk9G$mcexGu#BN$ zA_B#9Uz#2B$0Dz6(Dae+9mdchtp=eOC_elwCv@z@8rmORGVeZR@PryRy_sI6Iy4;5 zel*WPNz+V?ygld>Zdsw7v5cFHBa65iHuQXudNmIAbTQj9BjVTG19{xcd*uSS6&U+7 zH0JqAkwjMfV5uYY`9Q<0=v9PiHc?L~33^#D3I-y##*tXk%uvBNTM8A(@iK*b^S0ZN zxCmY;_?sa}2MvLX?T4M)l$nycSmTF63ACP*^?Auc6$7Z)y7Pdr?fCg{01aT#z$H5m zQUGz#Fip&FUxeNQ-ztgXPPcR{#_;J(2-HcyvPXy3;0TdSk@RQUWsMDry-oAWnxOll zPs#3Rj%!KaRj%g zTpO4A_L?=u=p8+l9sbs$V0l><#C`nSLV9B$6|rb6er}rifKo}l8K6E)z}77< zATCQt!(2ZEQ%RkC#d0n5#`%1bl<=rUv^e!7O``zOOkgLU5x=4Yi1UQnpa< z`=1Xhsn;EWzAt#o2K>LB?IPU|1ER!kI~FSARIq3F?ECx2vG@E-F#3X-;eZoGU)|iE zfxX<2=Fs8hW@>;49?MYiIDtM44Fwnh45t(uuLfg~;dLL$9$mRz3n0@_gmb6%W|D0_ z3%i;a8n8glq_!y24LtTu(AqV3x&RC%+r~hY`=YR)N`rIzZCbkQBzrD+tW<&m@7X1E z?z(8DXC1`|EXO4gCs%yQaxr^a`R*OqBrOVlMOcYmXY|fOaW)Li6#B4?Huk zq+pSPsEiNF@{^9C##^4w{=g4W6uqvGAts74{C(M;?t~;QzVe-|>2@I{(gEfqabzo< z+K8we`?bz0J*c@2fP+S*PB7}kbgLjpp&i4?38-b{n}`*}0bVJ=>lc0-*8h7>s8Kx( zZ)<3(q#|xZ@FK)Bj&&!dC@xHdBuHYJN3Y67X)OjFZGYKE((O@y2n^EguEG+`y{hbuE$@vg`{GE z^WK-*5?h7{5>UU@cXRx=Q|DW+G{>q}<)uCkVzGyhdL;|0J)i%0x9^ps00FvYraBt_ z?xj@Od9pi*&QHdW{YrKr^wUNND(5K)D02d3L|XWma-)yB@!w+V?}Fn4>*8djqfOyV za=O9L6t)YG>Ql-vi#eu@D6CaSl}p4=OjdKR0T|nt zK2hKqIPNJs_x% zaUyuvc_pcxFO7fa zv`R3H@TLM1)+6q7S1z5q%vM{%J>>1bJLQ#UG$febOHxnXURZHm7Wkqc^=X8)bLodk zE=5*Wh)+Dkr?^0W)H5J@L{iiZHE3LA(P~LRa53K(GJGVe@l#kji(z?>{fZp>|Ix7l3ShIxO6lk+ep+ zg#?c)pg~eMj{^WXdP5{FzN^m<2!}@JNs@x#Q1`Xj+eJ91)=vro1aJ3bl%GYEJ23OQ zzPE?pcV2nr7bj^jtRpw5)03*thc|5syx!&B!MTpk8Nj~2x&=nBB{rPd|Dige6M?c}d0CNeJnKy2d!W5qtNvm?E(I?7id7k7? z|H@Qek|x9m<{mOLR19;K_zW}LXJ(M+bNwFc3i*QH@;b5doW3Yq-%3SqX0HJA5c7a? z$)vS`^9H}jZ=2ew?!8zzT<8|y7Jakc{(9QBjysS*vPKe*uu-e#cm&cjvs+!JIGGwm z#psE=Do!v1{5Urn+!xdx-M@QoUT-h$9W8$gBG<5R((dJk%`*B|J4v%Lltspjp8b5A zz^Qs}G0_G`9XD9a?&Id==4>4vz>mebWcaEV_}KC6cGplfre)h7&o{Qg(K!!nlLDLO zU#D5=(*HfT=Y+DZV3vpt>#hr6}p8YCtFBhz+H!qej-+hU>0Ar$FvbjZ+) zv7;mm^eq>v4Ag!fBnW#|)*A=Oz51aVtg2I{nsD zY*|y`{G@O;!^jhr<@?R+`i;mh(sR+ymfp~r#fGIv?m04Xld@=jk=Cc#+IeiyiF0$A zJ^hy*2ZH6oK_)co3Kq(x_TiZsp^%%j^itT})&n!7!}rQS`% zHMHw=o&|e|X0*yg`lyl?7ztnUYW``gsnKLT4+GrLp4)bYy-4|pwqdG+e~`?@!Aat! zG8@lzd%)ot*#=@miJ;_{cIxQ)>e80w0`zDn;9Y1e<>;|@mXOdN39vYpx2UweZlg2t z!LAJ=K2R7j0h}bHiP}+>Z>m;X00lws*RDbt%OB}qpJ~uBJC+hawK*iL6G3&6ZK!U$8C#y&v@)Cpm zs+a4A*j*H-AhyZ+0qlZKIVf0@FXo%MVGC7`hgqF?lukCN=#aocRUUOOw2Vl9I>I zM!HZzh>EZ+7xctrpicvW^Ox=-4wU-sH$C-J_3aSW)Cm17TQVDgIk5xHbrW5|vEC4q z3MqWFrD>MLSik3Qrjs!&I{P9gwA3$v{^6q%b;M_A#zF}}iYowGXQH7w96*$nFL$L1 z1Yr0~@v1y^OFyzyicW0F-bI1@Zef5S(OZUIJ507G^?>{-V3wMfMu9<*U6FYa!uY&U z^dJaJpXR8Osg`%~{S^n$-_Qfc_PY@ATbOJ21*I6Z#jvGenMlTrb5V5A-fD^8(WR~K zMe@|TpU_vmrUj(n7&z+l9)7*O$59_7Bl+I;a5+=$*qwLYNGLd5eP_+o%3iu$J1_&8q^;vdom{v_ryR1=#W$kB^?I9F7lS3B&orovLC{S zcS}Q-har$-i>N#Y-u;)DjxG8J45Za_WB-eMg*C}b-wdUrWV;7yVA^>rGdEoc@b=Z= z39CByAtw`}{{234a;oGxG8`fEb&wjtu^{#;zDh&0uPV{IGa4O&*;rV$*$h>) z-=PZ#GR*9~{w&4Owv6JHe2rT4AVN{~?!qE`>t&{3k_K}Yp~}J2Ov2tCO$l&W8XL&YtkPMHW>0 z{1D?851!NWP^-g$Xc&olgNd#tjh$TtWrDsid}|ZW^}$_Ko4X1K0WJij;tLJZ_giC4 zHiCOSRgThrp#0bc1#PYEj*Zvme8V3qpuswR*_on@mwI8QZ@T>GE1?{pTiMAgedA9k zPLkU+yb#n2GsV%*-rF-i2F2iZw)$erNot3X@#%>E4ix>e9|fVx+oV5i%r}_yVQ-L{ zZFEX3Yk{BEaijW)XefCD$D*klEd@bH^Cf%*|K?#Uytx-#EUVFJw5gReXm6g-&E-w6 zhCXx_!=jtL_2uI1#E!}Gib>2cf!`oJQb8_?SkIcC#I$%_TCrG#2myA8vz zIoO>2y0%qTuWkhE$;uA@p^}Oi#1_7w4RTBJ#WoZh@8$R{M8*9AYd~p7xt?GsqF~kf zte3d09d)aRuU1@AqmlZVx7U{djg4^)k4`?g4fmghIXx}^fQGSkil10WF*Mii{Jd|; zt-Rnr(@D#A==`p2x{XI@o2lX|N4N+N=c}8MdZ!LK-7q2?fzW>A3Dbd-c7!~C1jGrr z(}q+#PBe=;`b0)!|I6aoze$|qVCjfjQtAK|rE~0}yqE@o5CzNTV0M6Y*PFpUcnCaq z#e1cXB6rnFxcGP94UO(e-C??QS?t&d}mFQi-~#h_6{bgY0hEk8E1zgftYC^p}+d zhR`n2lil-)or)pEcg;%OgjnJ6i?h@N96q33JTtEm> zhw9w&k+A@nYjz7hZ@xJQI5kTZ_2tNOxFz9xBM%?{q2038i@@wKxanRnQXr0HK1$c! zoraH|`AN-&a6!*>Gma$T`xpRPU~KBo0gSd_Q53UCWjF0|P{{xbnLQOSa7Q!xQ{Cjx zVn1uE&8o6)x>AXl6vh1(Srx+eN@I8zO#I*Jy=f@ZoU1Wt+q&3vzJlDZ<+_lSu zFEB=%&|7P2`<7k9EojoLrfRJNL3b-x*X0%~PB@vcGl2&&Yx}(A*@nnjUlUp0+?_Wg z-mg!1;Olu^A;oYw*n zqLq1|QF}+$%yBij{IrX(jBmJKm2nHEB*TW*KSkhVHkztYA>4@TYW*){KutSR zH=Jb0-x5qcu{Ov*iKym|GVt7woj88tQoTZn(F05|8T;jKu}=(EuZZAMj$8_Z)H0wA zKiX%UIX73QzSAvl4LUC9i2Qs$zYpK>_Sb%-LCt3iw9p}t98}Cmu=Fd}ZuhSCLAb9EQ9v03b+^r`%|idQ7Nih33bwIYe@`HOok-6kGaR1JpaPQ1jvO z3#?IBgt28$zW&(6s4Q?sgs=pNAuT@8r18a)ei4B@QKI)~97-+G89S$I`?p9HFrn*Jv0R6LtWM3S@_#>2U0ijS2P(2!Vb?B)b~+j%jmy&B#OH7Yx14;+go>qeY$le zw5g(X=PV(9*Ye4M9fR&76&LM%|HiZR%j>h z_m;Ok3Tl!RK&JTmBwsENU!81xz4M89j(}-(YF(O^>~b^@Cc*>f)I<5j+O_z|0+7#$=41SP92X(pT?63jZzU zt?9oME4_GQ=|eQR=OHP1AI0}ZAy{Q#=6@`m$8xMl5Jf+T1>P+i4~_S*!#3XguOIYc zR*H~XiZYou?-5mraEZG84w)gkp~YMgWOs4*2|^l&OR6t=y^Z~N{hjCO=j{VJ#GAxD zErM~JKD&G5>8_HZm1b9(`hBR5BKHY$;>-g>xTJyZ;|Sp2$)wy%gfrg3yc|2~9IQ%X^f)=a~U@a>uJ|QOb4&5!R54Kir~|z{{z@!>asq zh=>ZGNY+8I@tq-y36!^r+6Yn@g_cdps_})TL}~XHlRVhfxlJLN3}yR%?I-$sIOZBk zlPrT((&(K1>-7gm6h97)icxpWH9TK<<7&oVDvW2x)MBz8^yu&IW_o!$5ACJa%g#>m z(=>;PQXE@Y7+IOpo6$LYR8;eQk!>3Hv6&+Uu5+>es$-AozEegd&X`GsX19fo1Wdt= zWr={vOgD|3OT9cQR*S>E^EU@YT=->MFe!QGSdf3SQNd!es96qKSBwP zzjX+S@(3e|by@RAsLJR~^b}QSv+%7Q`95NP;JymMFC5;0B2okbmu|aA;8lLqDo8`| z5Su6*9n4Kp?y2?1Yu02tON79hF_DVtnG+UPUZ$4x*yzs(8G`%o3ECEIgo1Fu3?pai z<7UWERy^g*S8c6Gvx7yfqj4mD2dRkAB}TYnbs^OjM$eU85QJXFa`U?t-dxN%L4?u8 z!}EhDhkH5nEmvk0(*@x-4<@*cIc4@|?i*uZ1Mzrk<6_Cy(Pk|=dBn(RmwG-QebWLM zqOe%<7>(>~%p8@L#@|w=-|PqaA{W139KpfFbU!$<6vJC}KF)MDaRHQ_7(crXe@Xnw zJ|+#$zxvT5ha7s(r0K_zxWjf zcYw$@dAf8?Yflpiy4fm_IX}SRYppdmf&Kc-_t)C>R_QQn(TM*(QR@=3q^`dRIlx36r0doRcOZ^M3oJPh>3dVf(1iHF9% ztlkARB1emza_^V5hChAlU*%C`XVc846q0bc#L=acrI0~>LK`Ddp@=9{ixTYnT zC=M7%VLCkH3D#0&`H8J;Qb^44<K}iXYYw|1*;Hgcm@~WkornOxdh#q4QVSr`GqqO@|*@x|MTV5V8h#gz+ zL7#TOA|J4Gt{>z?UrYrDMh@P^En}fv1YnkZhv`mQwtnOY2W!HtmW)J)KV3k=m>-qkv00lt$zq5B-Nr&O!Ou$;3eGH|J&H>)X zUz;09)M)FGZu=SIUwQwyw!@~m@px(isR!bCg-fI1=lxd9i1^%QTLg2q|NS{;wKEli zX(=^&k6Iq3#BXp9O=mp6d)knx%Nw!aClG1LF76H6?en_`1)l`5V-%{|_hD)3e;1p8;eB*YoN0x)9wM zHKslxxc=R+9l(Lf(ZhE|d`H{j?Ym0;Ar{Lb#7F%x-7P7-CAlS!_npSlJQYT=r7~(g z@#L~JMAxub&wqYoyT8)*QHBlJDy9&vJai99z#cT+;70o!Px*0)1hU5KFa$OFyg1yz zF-D;&8({RGEJN}4a+U=v5OqEzaYedb-L^Z7Ru$4Z->)9yBhm&`QR|#AF|pupR=3HN zS)1J=&@CWnn4+wICSmIZRuX?M!t-Iv&DC8N{`%f%x=@B_nUKtVR!JFaO7~XFkUInn zTi(Ji>T^Q5A|jT*KroGRHa-?mA^ENbL_=79eUPH0OJA0=BlW$K#ISR@w6u2S}AYRaKR7@Py>_ex-D&v($gN-?wgAL6p{E%!tcD^I?R1&#JK+N_wihxxam%!Aw!ekT&x z&R;l6B%_b*p4*dSw#>qM@>l0gk|v+0FzjP@etQ#N*8Zy;5Bfbl^;#*`hXZb`+%5R< zpBts9aa1Fs>CP5n_=QUaB_r@y+07F9q8uo_Y94``S8)4L{m9kY%cSR$Gkr#p?h&ac zA_T9B&=*x081-nEWV4$o{P$IBN?EM$IH?u+`uiK3c;S|OfiXh6!h=Ai*M^yFS~T+o<%dTATZeA)vhaEOmO+CQ+xI)=Dc#j%80= zl59o%C4oz|t`gD~IibzWxk_3-m5~w)muWAQcMXN*u$&@m`}Mz)bAd-1V@?CKF4L<- zC5z)S4_tTcMzo7x({CumC)>Xhyyh&~2A-wBYr1@hU@LV(ok8}-G@tll?J^{cL~9Oz zA-b(*^|)nX>?we*%!gAhdRlwSfVd0NV3vxf=+Hz*;AY~qC1kcoVJv+97;0I?xg_pKfDH*AHN%9^!rcH*xC`oJ0D zDBsKX2e)pJnrV`9$gXaXquSm8cb>l(^;*WaOE%-QROB;^KX)RwD@RRSR67_#!drsn zguq@`o97C!TBKpzP+eP8sR+>eD@vim^)y}$YM#EJjp3Vc6-FBB6vNSLh4X4XemwO~(W}y&BKb*b8huMBdRO}UOickzY`Psbi(-XOCZUTWu%`_%42`X6z zZa$!*4MuQ(?Oo&b&X`Av)e3g0;%Y{es{yRM4wTkxs)Q(W%wF%qI3#jMI{0)|b1ZBZ zpj}~}RGxCvOT>F!=wgl+L}|di%6^_6qo^UPrPsXKDZ($K%ST-UeC+&?%7{xq{U}L8 zY_ZfDcVzL+^PCJ9wDm239J$e(NYw7a{QSU0h0K;pAupHhRC5Kpmy$s7&mHt-S7MV_ zpr&xiW^n>cSsKRds7}Y_MOPzPY6dbY=^W)2b!Yz>8;ftCRht%-o~f7rc9KkoG1LPb z%F_cRB?RYd(*7Og!s|1WY(Xtv1z1+x)^k?p6ts2G+qgU8TG-T20S_bR4QefZRVHbV zm;qmYfj{%Bis54d?T``6l{k{S%fmr!LgWo@QNg;vOAn;L#?`8RV6Zxa27$?=feD~~ z`7EhHg2=rQSehjr7jB5_65c^3U{QR&gsU>wek-3{LS#kMq1T(xvxSLnV*x2Ie@3eq zJ~427PyRzhe_g-er7Ml!W-rOfvGgA4z#sI-AG0AU2nfQr1lCx|zJlXOf^-3?!~fuf zx+9weG`MP_?S@N@x5uHnr8_VP#IHG2>R@peNjWS5+B)z>E;Eo@GMdUL)g&F|<+oPT zuhVlP@mB{8p-JO~Fl)O7V8M+-p*qNuN;f06IZ^pzGIOS|1N%1P6e{#?aVwW>MZE+b zC^NQKv%l3k0Iyqko?2P#;W=3!9n$hbZKngkJ);J8yH8-RdDFD42L*V7XcuhxZBF-K zMeFO!H4nSe%yfOVeio!LYm+Fa|&p;lMxq%u*b6iu~?5Z%C!-247+35a$ zVT2ink5GvNE)k_Uam{JWa=n;l^~cV1y0g8|0BUue8)NC1_$5&atIF#o8{su<0$t2* zMU6)qB&H_U$_2iACqNND6A*VY!xnllG`%4t=Wh$Zg;gM*c<-0zZTJUKa)4~fXy>1L%mYikgYIxwVI*Y=L zN<6`@Nscl#WDlQ6In&ar>o2-jRbd^$k{6#2aXGq%s~qan85wC zipII4*_^Xrq%c~w>tUD{zDMfs1E!Bl%;qo?fgkgzAe-jqcJ*{0&5YbOWQV^_^k54A zoo>8IJIGK;s&0RG%e_crJ?JLl0J~pjBBe+vrL(Z%AWNL6ati@3^btqCiZ?O)@bW9NUNTiLj_lV4k!Kgc(qO-=|A`@D(^$U)qkGN*AcL#S>w`31 zObm(|j`D3MzX_b5DHHIpp>XNW!i!uHnr zF!R-N^f+-AKl5~=@FH%|0?0lKH<-m#gZ_>tIT zX5X1nA5Oeyk?W@%m-doa)I7PeDQtA&&+1v0NwQ;VwB?=en|plC{Po<1fI}4Z;w>yv zfT8lym^s2nygHgikE~J)7kgN_AS;I3WGralkJyKo&T{7}?GQ#}eTvQi zC~cfIxUhX%MPH%_|DNMX%`q)V(~Oy?Ri2dJ8Gig=JxC$K;TkQvcaq#y+W`sPUYXfhs(z^FRNIkKUrvs z>_R_7UOk$imkrkwrJd*Yj+%2C(e?eklw!WqlDuM)U`7XPPz)?leGTZ#nB#mv>aD0U zEKgD=8lg&(03`h6@9<;*&bnmW!&ojl&Zg)Zq3|_dpz4~>Y14;|{qq_88z)kj$mRpz z#fswv{PGN`Ye5J7#qMRo??3}F`&ut+fxd2!udRrRj>3pq+j@y|LBDe9sY}~I4on;& zQ)s4h1F{>m-M6(&%hVNr6BL$|lrZC+wF|$g%76$XhFgy>hxCg+iG{w{ZezQI%BMz- z5UFn`PJS}WUuz~C;C97-X`0TH&t0@Y{&JaaP3fA|j{gTgyh<-V|gE(h8~L=-pjpswL|;(~_-q=nOFma~)nU zku4=KSj|=gKu=JVdMwaa%+KTau|qR=w_y#UD=3eV`<}wg3j4X2nBA4t2LCj` zYqd!EOi}-0g{cCk>7Mm4X_goc8W#XUYbm*6kO?dz#wVV3QC^hmPN+0inSSxEuG|(L za85{pmiFd7rEdqaDS@P3;tQ$lB;<1tty3<7|eI4*EQ`wPO@o>n<^*s}T{9=XHqkv{a$dh>y7IQ%P17TA3iyN?- zvR8M031|s_z1ej<6-6NeS(+Ccp!S#m>wq|#08c=$zhjenEG?tS?QPbvf<3@}^9%PZ z9xJKQTo{C~(gZVeBMtMi0p4U+O>rqY`Rfz5e+KQ0D-ti!NIPx=FKcBw}i-Oa*k8-dl$&i1kShM0amo+O0=^4HvU~|X*L80xL@o3#js_0K3_b_590VQ zpJpRT-@#}>PWlCiN($vTkwDB2%zyLqOFp^q#n&h~CF4XCt za$T)oDlmO92Htu>>%%^aeNnj(feU6%Kj8QQ^W5)Ofl|e`Q$UR%WVQ(O0}rnc%ZGp| z*#hWD8mSpRGSg^3Vboft!IIZ zcz_PH&qU)R=E2s4lHlih1<a?+(X))GjG?h%pGx6-#b( zYEP2grJu6J+7(fM(M@Z=o)pkf2rqj2;Z~bJBgJO`r*NZ&gK?=8KVe2z9M!IQCrf0A;=kF4ksF#=`yf)a`|_FBt+Tu3%wB3d?-c z4}AAsV(#9KWcio{jkBWx;XKM<^PO~{O6J$Y!7&F^udP5luXQz%vI&KE(H3xFgqTv@ zrTn4|l{g#(32USXCt@%{iVrS#fI!qN(T3(__AxYU-vVp@&@TX3K|VP_MZ?|gefeFh zZjp@s8j?=dnC=iO@9HmhuMXqiu}c$kR~#qklz`oT9yNK~6feRQh6}RN-Ze-9@pdV& ziGZLwrVPj_iThAAt4BZI^M6J}NxN}~I&)=^ZGig%y&-N}2O!Lh6b6sC>5{sr+uZ`Q}N%%}`EMZAlZklOSE_4>Xb4LqW{oS{t6=R6G zC*&Csh1%RHbVBWOc4Bw9uJEA1ItHfQ4!{ulHr7M zOQ{zIg}dudcsN1G&G+zWhW3>(%Sn*nfIZm(luLt2e8pO?rnkNzH%lumHeeRt3z(2S zFsnoW-PKjPSX?D6KQ*|7 zU{AtuKD3-XESNahDuVDj&sprUq}*v|{6B7gx= z0C@*1S}}FcdUe+I5q#c;=E8C5m)x9pf9J@w%{3zNkOVn((Cmyvp1RP)sBYsiMrX+D zncwX0ejs)nuE4^_(ye<{B$^%4L?58lI+Ca&;nQb-ORjs2N10^J?^X!!k}J?_ty!2n zG-k#!NJTv3_JtF5eTmly1&7GTO6VYR64iuI9Z~oI#z2r)d+bFv+~9PoDLq9Eh(2v= z-r{2Ug|%dwwmNg9G#B~ni^yg^^<*PGtE}RWf9|RM(fO2cr4fSO2UJe-Lwc+{VootX%uZNdY#Xg7CT(m5zRQznJ$t8D8|pxjgixWY~@{^2%?IuwX4rEbKuU!~N%6MS=X|JozdXv?tW2hr4c^eT}gu)|AOe zUidU>jg;)fwx_Sr)4+0`iC^KW>hZ9@!a`HdHyTCHKV4LhtNfh&nI`NcvR^|}-&{>4 z$a~?L?xQ`I0-`K6?Wer4hpEOoAFRLi_0N z3>ps+g|;ZxOhAeyDe5a*V;xYd^Fsm`V(Gty zIc=qbQj3$mZtyw~PkCeiH;J{&*~m`EHD(swp$mFm0~=MhWt9OENBi}?9VVvvDH#g2 zEcA|mQhlY#=)2UdE>v5d?@fyBWMSG<2(eQ~mT$euKh$ujs~MO{hymz6c!Hm&q+Gm8 z-vg(bpaQRAG(VzOTMds2wYq~1K=5A8FK*61MDN?+CFS2=Ox9oKH z3v%JFU5s@!`{keb_TciD<6K#N7`A$YY$1X&u&5b5<;{65X`cMlTOo_@U5zUcoaXpq z*+ra_bxBytuto)S03&=+m}hG%7cd@z-F}02n$%nJ=w4hW1DBA*!&Re$VWlhbO{+d;DTr^r!p-^YK5@er z{p}xcw1!m@T2Y##JeWq_z!v!|h8Bmxq%{0xQjcxaTuTQiPp*bxeh{Uom$|yGn^w)j z-Z656K0nVV$dA#Tw4P-)K^-A1E@YlLm@NIo1*5Hj4Wo8y&a5W?PEq&q(*?iAcG(+# zT2d;_7&?>RUX2)hGW^7I;F@d3NZm1u-%HoEZoTh?L7yZl*?U)u%GcYRT|lI@kuZ|j zh32FHf^tyPl&sCg-At-cJFi>ThQ8GAqF+=M(LzO`tpo1K&=oL{IEuJx&h9dCem5I|1m64PM!FV8TG5+?2XCQ$yPXB}Y zfD#ujrE@yk)wfaGe=lvm$Z=Nt+x%WtEpZ&4XYtn=Ar^xsgZ)Y~e^``#)~PQS8_pK< z)#Mf|Fn)+Fe;wM@L>LyWZ?0$~%BgIa^+%HWz}`be`|UEQG*fyqPvT=gcEh!PEA1&W zX}H>4hMB0jj>7^Sy;^yrle+{PjX8T~vPEB)wv!hurOim~{acxQr}cqSlU@ss@mjyx zPumq`LUq?{G3pneJ!nHryxZ*!gg4B_?~?4<`lW%T5LZpg&u_eo1G)D|?Z0@g&#}@r zo!QVV9NDeR?;+LK{J0?2xzb8|{~RO+Jye}}N&IVmP4Zc4uyB0rA@4mR{>inndh%}q z9E=05WV_#cr`H>Qe6>p*`>)S#)=9gD{DTwW?^yk?Q9xqy4mwd17>La)bFgC^aHfk` zdXp;fNd(fRs*@*wW-kTzJ$3R5+`91k&Csv1AK;gGy^ML!i$8F;j*n0rN9!uwvfdg!IM<+7GWxiBgmzHGBXBRcr9fD%NNUa$rMedBa-R1~ zd*%9#Ohy@ao~$<#ch8rJ!=X(%nGXCszIg6udM}qxseM%a&_TZp?F|`E&a|K3Y^=Br z$Tj9&w;p@C+qVn94obD0nAp;|}!`EBoV z3)>QE;tXmyuwD;i}?nVrXF5(zJH;VULqesh>k<4KHkz>K#Fy`;ogQ064D zM#-yZW`3MDO=|hQUpEw^ZX2q=635xk#^VmE_pS+RM5Rb#M*8;ExMsfd>WU8;guO)V4H_YjfQuSZ%{5lBIq8!s@Ii-nMv9 zn)**cL|v4rJ{8ppvsdEsbTYq;wPMcVEl?X#!ffDd0*D6jS`4P5anFp1WC=uW1O_2bugZks5# z>Ep)KTdmvaVdsi0-_~4~P(0SXx?ZTE0cP%EA3TPXZac7OZa9z{(CYQut=*{~IQjtw zP}$(C*Q(haWp9XW7IMqJ3~ctGW2apdG%B>pu){XBhpJ_vjAR*{Zq)|oZ_IBnMa`^s z7mK~SCM!T#SLL~aYqA10H6!E8eBZsZe`o4QHlBVtd+n7`Q^1l+?B#6jZQriT_Og%e z-}dj!_P^Ij6Ca$U3updAt-e#)Ah~>wtQPMOt6~qh?>#xgEY2T~Bq-*`kQ`~U-Z>1HrTF#HPC;#f{F|O^7_nE%RtHzlG z!d%J8u)@BlyxZmpn1etLrolnJ2SN0?mr%`6Y(eo!vSG|e>C;%r@n(DfrB|7o`K9fM zu@+W5|I$v1=*fk~7ooS^$1CnHgnF+rrq0*gRcuU1o}~ns3$dl5$#d#o#H{*rA%7C) zOB{@PKV9B@(9+1Wlp1~%R|v>YCv1uvBk|~27jnPx7iS?pwqnJrt@I@9h+q_o9vjF_ zs&mhZ2N2okEF$fZZT%$2r|rWDwKOg=n0K4lWNDuo3lAwYBxWZR)T>oNmR(`Lz~;H1 zrW?`%!*5iUt9t<nue4`3P=3XaY+AXEcxh^SM(KY=%bMv@{X(Fw-oSQVfG%kg z4gUfsKQlokFZAY{@w0V&<7gZ^X`sxX{lH%Q;`)^AaL7+8S=T_5npbud_gOgXX=5ge;Y z92reNt1Yx$K`THH;h$XyMiheH-;W<+vW7CeF?6Aoe8(ZKISUM28)Y; zH7%9TA0l&wv^y#R2(f+e!Rwgi@r>h}EG&dDt%o7&0lNp2m#hgp99PTK*9d&JmBGFK z1_oek-N6Sgz6)sr__5-zue007oLPRj?RSRp{M}pyyW}@M11)T*_=c}S^vp#f2A)WC zw~bd$MCFIf-fX=TJl9*G@F?Vnz3SCdDhC_ZI~%;(I!={~25|r@kB$NUh7~Ln-;Dyn zvIB?g>;7F0hyRW>qT=PbHS%)Kh~C5{NB+ZEl1N9dlY=Zt@o2HCf2w8oh58d>d=Ok* za&HEsf>8tf^mKc}vM$Y+WVGzk?ZwAO`7}}G+OgQ?ye45|G1WyXw}!Q9AJ#wmUTU?# zkF`k=r>Hin1N`3I1RY2OXNQqdZes8N_gp&=w^6FVx7WZm-K!x36tM>EvCfw9x_u0l3f9*(3lh zXGQUpe@NU1#x$~#uY51@jU#mLV31$J*1QIF{AsAq9yby!N?V@h)f_|gxOsdsrO8P+ z=_nusGZk$41d7&BWEFAvH?Rv4q3zxvJR+^VG@g|g&duO;9O4joupfL}#l z?!UFBu38rfGMSVc(mvw|jA)1D1@N$;!7ZiPH}{xDC7JvXb^W-AovDS(eM33)9mDr- z;SsWgn-tu$fL?AjwS|EV z*9E9#?fEa}SX2-jCJ>OzbNG)<+|M>;hfIk!XBG30kaOc1X!5}XisX9BetHCAHQ?`A zM+*D~M|G&2Plw4{+OqdK*NAGganQ8$;;0VzG);DpI>~0bviKRhuQ%9+D(r@!xZ~jJ z`o*5;Lw{ahvOx2%N(O`f2Dk;4ihujaI>`N7>a0yv{MRhiU)}Lb5C(zLUK+B2BDi<= z^F9uVPI7(fjM~W#XycXFTZgJ;aae4erUzBOy4>Hfv9B6r`a5 zhjp5jp|H_HOMejcqoj~l>N_r)pX3*|g`}+g-(5+S2}uHRS4{<gu048``Zx-pJp-bczZw(;1aeD-806OnVrDOv@5Bh#b=~U}!=+66GmMLP4#i zFS2$MxNyJOFUd649$`|jsvHQpokNLq%k`m2_2P#@WCRe{qz7)^h zn1Mb>?dHrH|FzBQ=^HSvLRzPj{JGyLu+P5PG2Iw?uJsDrzm@wZc?Fo}@$|tjZ7vWO zb;@=vw&4!BUwu_TvF|f&o;XTn{P#ELfB$BbH0|MkE&grJ`ZwAL#UI-4`v~+EnZF)q z)}m2;w0)U_CFd0tL=$UFG|F=}#-OWTLtHhNbo&-gX267$thGzbOlx#gQr*-1QCPX( zG=pqD+=Q9d7WBqRQ}poE1c#3u(U)&_Vt~dsrA?_{Tf+z%oVM5c$$hAFTse0NwO_=P zW9n$t_Nc&rCx$wp{6VVV*auQwmWEE(<|Ibp>xh^zRsgJu)41lhv!&jZhIw3UdU21b zd>55l%dEJLp*EJ7>J4M+z;dQLi!e`xcXadRnsuJ-L#Z4^O+VT3yyEs&1Q@3~yytxU zV>Bj@nV*lvJ20?bX>}kUia;N(9lE5X9sCPX3oQToCSQk9E}|H8Eu$!?9Y=>g?Ut8F z=fuyk93x~GFo~wh+lbu7V1-%Ausk*Ni|J3I-4>Ch5P!opOlu#R#Twu7=u%@9xf#&gEtGX3P~vk%D_MNhd3Y7 z)bv~h|JvFX`|ee00DXBUGA)-hsNI_DSXIh2nP9j;mn{yAA@RRr~eO>?cwMl>2e!v3D8y zoHM&rXxB*DGL}Ffh0E{ZxPXiN&|7AEbN2hl4-im4L%B<|6UK=eLB+F8)@ zhbh$H2ZgoP+J*rD8g)akqJ16x!c5U9nCze?uIw$G@8J6yyI<(-pd*JSa6Relj#UM~ zmRcCp8z^KAjfg>!+IH?O0kU(6TNKUc)jQoHRw)Q1k+32~bSi`l3T)FSjdL>&lGkm= zg1Qd%cjm1e!&0&eUl(ed5UZG*?e0-NuQmrW14t;d3ToscpscVX+i$rTU!YN%^3&kH z`vDa_xbWhbTyPbl4m_r#AJu@wzh~h)Ns-1&Jf-jJRd%-Isa2-qMy^Tp zZ{55FvA~&oD6xejH3Z16fG!>py~FGH8gSWhSvLK31kUa(TaVYU2zB`rvC7-a38&f= z8p2MS%Ki6u<|w?tOS2*gZJos4mAYIJQ--{i+1c;xMjF=%+-5m{as6Q7Yhw>@?;!9@hA<-kr`#i$HJUgN&m5`Jc6iQhO2!rT&Hgnkoh z$^{t}e0k1uiyr>o+IH)pNIA@snIOoylkFQ)hG`BN{K&oE-nsGW)|835?m*r{>+`QC zKCH5hq+7#fc?&Hv3}PZ>M$rv+l7l)x(YJmul5vBS>W6{X%0hws*{esR{kfA!Isrvz zSbracmRzOH=TEWz49hkL{*tsa)_Ap_l8f(S5hGv`TgP5fkWG))BZ4dh9J9iR{Ju%+ z!`3xE0$&fn*`LAt76QV=L6zeRKq)vB0OT z%lQel*FbE4mbS<@3f|_upMK=yKMjgq*+-Lf$D|phr@s^bX|qOB#ay3(%wB)uIh-BA z$I&U_o0?oWGl0;MjW$VjW0-;<`TZKlLvauNZgiHR9G&K(hxygApgZ&YmT7M)Ts;AJ z_E;M_W4$iuI&WZ#D$iJ$JopFOm5}OmT76z$E3dA`eg@|Zh755F7f!6b6ANE1UpqV> z4WMUZsF%Os36)6?@s#ja*OLYW zV5Tns&d~QZsQwQeVe1MTuer#IF`^|B-YSOVTP)5Pl#QxGiyM9J-Mm?(RJO zW&Rs6%LxLi&dL0;DXMzTy)cg_{be(}bb9Kx;)IdxX6U$*cjzW`BOIHeGBxkiB>1jG z!{16a_;Rr}T-R{-fjv3*9dmmF$n1fi`R~12^2%#<89Pfgg6D08UORiWRxDbD=IR_D z!Q5()*_}Oi=sSP3TpJaL_g1T`^^T@UPt7h)ime2J75!`MW#88_`(?2pEMx8v({u?1 zIXtu&luHUA#vpVC9#87D0Ox@|;BYZHJC438LoD_^DZn>kcJKaWKJ07W2Z_+>QF!(w7lbTmX)Bp`h59qB#X z$)uE+4L%-pLr(<>lRZ`x=;LimbMOaX=HEMh%?NJ!MTYhZd6 zyZd;Xy3Oix_2z=^e!xPp>N<)XOnIvM&2+~f_7J0hv4-(#+nE}qCiTI($S|I z&EncF0>3@sgj_PW794L&uJsX&kE|w`4Y`!H8X}hqX=j@!PvJE{enmEX;=#(j3R_sU zA?e=2HZ`_qENZ)N_1pUUGu_>HNn_1AbF=OZI%KbVZbry+DPR-v#5fj|9b|9KZw=M1 z1_ExJU&E;oAt8W~mY*%1Wk&a|(L{iJcimHyxIMHERg0Y4_7;DgaZQylC?T$3Sn*uc z_#GazgQ;|xz_XjS4M^TRsS)mv@_JY`m|B=+#m<;R>yLCMK#8?FYU>R z_IQtfM>g6I==p9kQvlv+LxO$@(z_;^AvsKImpVHYM;QhZV2WH&Q{26oWpX zn=LdG!9qCCP$Z~mOvg|I#;-$tQ=Y(FS_#Wj$%L5pLhx}NGx(J*&ffCmIpV8#rjC&OXEmz!yiW#nBOM$QY-wS?|-4J78w&!;9 z;82ID)bOq6a6{n5B?#RGa_i^(MAyAaE-Q;@Yf-+d6`ZmiwGv+L8`+ildy6?pYp2Yq zv*(?xZLf2_b@5G}P=TSEOMtmtM}tu$#8?yuyY&uxe>t6Jup2Elr>0aIbM3mfR0N)_@Lf>A0EdiKOan9sTp z#$qBanJ*$b31QM6x{2ozNdS55K7)69ie1DKPAmdg>Pe6;(oy?h4)OWhA1HRsmKxMA zG_e9TlLUaSTKO3W7^O$I?Hz+GAyPk7DqoL5GDN_g+NQM?CJ(EDjj3m=#6gI!JX-0c z={z9(g|Ag^faL1Y5l{IrNNMfmwdGyvoL$Ft96o%cAQI+4pO9ym@ zZr^?2t9Ksv9GP)V$SWv{;jc>-D(`o1%BeniXqrw$WlrE5>4_?Ik9ev6JIjD04XyX? ziFb={3kg$NrN;y-63DL{OlTyp4D>gms5)gQdAOo24?0OEYt?MlIIyuPk%sc7J6@=pJ?x#VsvLFsA);dw~31N=ol+N|TYe+-Xg zWHB{WfQ@HiMNr;?vp5-*KS=J!#QS!Xg<97rZV}+0DgxegEr{}6Hdy2>_J)sxK8?RF z;neiHq5~HEY(;N~^7Q8SnPa)sBmtS_M=; zvM!jU(TX*ulz$ncal}6!41tq&NdA~*!qJ&c@zuG=`6*;a=i^fkd(FV+M?dKp8x%|g zruzl{a4|u~x<6Rr)4Ac5f}Er#@YEbL}J21xI5Re{)gAAv~1S zVjZ2~g&Eb0>`Iy9L0T>mE>yvb<>%g{f+WyMi(qd2P(rJC|Iv&CLPFbsJO@ zBa)cvCSrwt2&U^+epdwOA-SdBTIrLIu^9=C=fwsn3bF57VRM_K7f>Xg*P$4k`|AIj zMB`59jCH|UY3yIt88&nLT$-;iUwwI_e{3Kmh+!uk?$!tea&;-6^<&U?Qbo#*tn&|O z{?5+|GVZ?VMVl0im4GZjK70&pT!iV6t>2cwSRepVTsdbZmP9{|Uu*cGu#qCwZxzr4 ztrO*WM`-c}ce}F9J91BuzoQcH>L7jgNsr8*`ZqSxXen;7&kpwjk2}e&XZd2lrB@Gm z(FdP$>(d=U(lbIU|3Z2PgFJu8eogFaqF4d*(9R4fD&Go+VatB~Yh z3K}@LrWD0O<6@H-(#Jm{8q4y(%_kd*1Sz00i#$C-xqv>ZM&{oaROJ=*9owP5_iq*} zA-GK|NOX31J(DxX$T-49x^2n-RmWarUu*MLv(bP@I>hh5x^UTsgf+IsZ+x_E3696= zVC2%t0pe|9dZQ_>@rWJIhFy?p8k7%!g~S`lLWI0-rT6tDmKByNL!<}4Bl5xosE6_Z zR|X_Ym4j*UN_Zt>i^%8Q^pQZFbuS&1UBo6oj z__sD_dYD^#%aAN z?i5jN6DoRc5CcEA`s7t4+z@IMI@L527=z+uU1f7#uk&cO02$#b@{951%X(*m1q@N2 zx4zEKMxwZ%H4;MdWr8r69Hy}_%*;D2lf?qKo{RkF#pR?E!b?`F&dj!Sxy}-eV$^Fggf zOd-`LzUH1;lU4=*sW*VNl;w1tjJBDKs%1_`9?bGSIxHB_At$m7nTx+Y(~PRy)k{Kj zdC*$ET)Zez%&Jbe;=m`zgRvi`j5inzmo*qy3XWJ(To_5mn3VnNbz&y zT|OcNhmHPe=G-FA)-n})ee*f7>VM-%YdR5nbZNzt@UqsH2HFc#_&N^U&wAx|>@X`2Q*m798qNKQO z=H6AOXb$rr{1Ov9wvg>)t z+P?A0Q2Rie{ofj1b>0v3w!B8dV*h*!&0SFq@2j&^sh<#94WlYp-iD@Ui{c3w%y084 zzoxtkZ&f2{;&Q7B#$8R4RJHS%J zn{eS)8+2s+QUy#JmG1PU@|hF0P0vHCI=@)gBGQtzBVOz2aJ>QCAPg^y?wPk<(j}9=yrK!m+=ob7KkUXN0U+lZBF=X$+*GXN&0WU$+55iu>M=0 zff4$z>Uke{HH#o->LCK`#7EKY>d(NE0?>~n0}NqdDl}`sxB%~vorohOMyZiFMeEP# z>GiG}M4mzy`#1Z{=w((^_0{l>zl@VeHvHkIp+)ux!FYXHBrN4_vP7&M3QJ%3K#uPz z&d2JY92e{6dN@Oj5wors$hPj;4bUZflLoQJOlru}In8>mqWp4@(8Cu9xmAhh<%vJ0 z6eB=e8S+?y#8~XuxN!jy+cxYSHv&1OHiGA~A^siMGJ!H?IhbV~(~_JwN!e*?UTyvx za3k^H9oz!+!~N|^hCF-O5k$)~R;~?sVp2(kDCja@UiTq3;7lv5NOsgwuKCB4ocgq1 zT!yu+y3-BAZz<%*|*>_0%fI8Y-FH>&1tO0&`*UK#2*5ogKdsk1X z91)(;8cTbd&b>J^CAkohen(y61>39;gBANBf4ybF;8fLMtJiMGP&i zx@}mHOSdX%#ctpBko3g-Mj8fo9P{Z>PeIwkC^S80 z^K!>&!WBEWulUM1i3-cYu+oOeJDdxnFk;y%_mH)V#KbCU>)1OkoRzLZnZW@b7Wqr# zm%tQbrWg6si3MTm?cO)2Mce{PU(EECFt?evoxktXT8N8MiyoHB@)p@moMfb$xq+kt z-%tQ1vLQ7=?>X?0V>-(+82Nd~6eZV26vBW{rDq%e-u(k^Uti_W?rhY$S##SC#lpDS}d$;8#|S-+x;a+ z7zjE@zd|o`bF$`w@H=F##kV&F?4w%WJMQUQ4;1VYQ;+Kk^HgUo(Wm;ew!s=&b{$Lz zF>>%bpwYd|@|`?NRLz+$D`ZnC$I7$CJzMKpH-f>@)%4EksFDm5N?;!@C0-Y^fo@Ju zchWu>Co)c~l)9^U&ezcP_Bz9lJEgO^aWk+CDOLSUy_OzZu8i1tmhj3DxqQRH8uV)C zcV|ch{=M_bbhkzHOETzGDrEsaO-8s{z6nsBvPoMv z_{sg%0f}!#J@g=*v3_SGOhJec-HvXfm~gtHu%#e=tlr`2wV2D6dt-4+2R(nKLu&hn zX{eN6igX7yfUq1GyQWJ#3#ITAoN1xVZs!{NmQ*f6T^y%feUHKr7YfBEHdV=(U zX%&r1jwLGqe0f7*sd`HXCaE5i%G*9kT46~ob}jnJ^4U2X5TE^wa-FfZX5#lgzu~QV zm8bkv53#0>?J~}1l7YCuBRSKUXrv93WX&&PCdiN<9;g&@9E!GHb*CuThZk5k1N4jw zrv45h?)MOS&It+}44r;rC5gp%?E4Ik-qOXpv1@B7=tW2~U@Du+573|#LPonjVPj_j z!|dBz&Cs)Al>8kGJ`rQ=KWc&CTi2%{Xan~qXE`jD6q%}P@-6-wFO{mG8@*m?n|L6X zqQE^qy#Nmv%2GOT4<5Oa4z2Xm6lW=Z5|!4k_0rjo#6FGtOnxL>BTPh04)=HDXLLg-Yka$W^?mMH-%;ie`i86L>UTX(~`&XFCjxZWS3M<_Sz1)XbAh8 zk9tJQo9ZIN_+)y4)tu>oS16tcd10OGgXO<4QzikGeUX_UiIXXFr-kuyph@>Pft^ZO zPcsaXIq)HVf0DmButJZfPcHwK8hel`xVsApCpxGKgz{xi{7rb|1GQt1UhkTyhjTZM zkpQ2V8r$-Sa+%0fu3ZUwK64?qR_^^%^t<{WDzxvdk^lrR5n@W^$v-Yq?gaqrd|r;` zYIYX5ZPJ1rjM+I4AC!PuX#=8hOE=m9y4JoLX8(Z^ruifo#Qlu#7FdyRLs3Y%m*#^ev>{lym=fl`Y znO%VrE()-jM~Pnh);Rmt+LBGB&56)2c?Spcw(ozc9n@ogw@p^=sppFO6o7PHo4pofN9hA@DwVLtXo=~x_Dj9*>K%AL9RzsC*%piT(>K@79 zgO{ME%$3O2I}M|QT-<&Io)Xt2T=;Qf_Lo5)qs+Seyyc_hJy_ zZ;(#^JADNovbcO7Pdvi5v@;HBJ0%*7YKoYcVw$# z_uxs4<^jM?xt=_3zqurIN3kiW96GDn)9N$ZQ)uA*Vov~k?;ik~K|i52=Pi^In-f#1 z6tLE+B3f>?Gx@>2h&TlTe~u65S`4Dv+9sSss3AmBwy_s(O-x`HBHUzwUo$JBJ14-3 z!5gg!2^0gux#A}0#`Mrtj`Wl~^{hDeJ--)%ACLh>j@D921*s&z*R@yj;}?#d#$}M2 zIa`leU3gB8RZk@~l6v8iGYKgztWq;DO93Bo`RJ`>(W==)UiKDNBEDSGMAiqn{x(+ZZO(Asn$*0_v8MG+ zw@%-2j3SGImJEFp6DUt_X`gXGtJQt*J#3_G4t(QM5~;|=X%SV1_LoyaxV6;&Cyt(e zCzD>qrH}VMqog|nnicYCKxR`cW@ zi#o<&Mo2aMd3JLU{bnA!;2ohBBW~{&RAN0Fynnb*=mrD{#VEyxQi5p~4468ytHkfy z+oT4j=)FvJv<|`LASyJ$^f%8NXJ!Kg#)Wta3q=g_ z5uAXPC26^0Z5d%oN>mea%XQr9fcK9NO=w01yb)(c?NqxX(OQmGM#*O1%4U_kJ_zL~J}w@+z+aq`+!YXFC#)xqM*BxuL)zAE5=}9? zJ^Ay^5bT!uUTX{;#IrwdEW_4M1HEH!ER?}>Xv*MTpm*DdJq*-R+_Mcm>5_LkcAoQQ z3wLb_?0w6=6czaAYiI5MoGsXE<78xMj?=SQUs(2D*Xhs9|HcPHz>Q6H$Sqg@8KOhaoT7u0Q?S68(^M1!Vk%Vfl>IscQv1={&tA2g{3>dUwm|Xa z2a%qbv;I4f$8io2rmn`0!^et}TR!jYq=fs`O&Kw%{%S5^YMNI?#3^@frERE@qc-@f zcEQURe*hG9_;grZPo9CEG3^M?H;SojuN6kqt_*c~Mz zh00_sKS|4!9{N;tO%ltacZrez?dY!(Cvn*t;7#ZXJ?T(za)SQ>9-R^;b_#%CP%uB*p}81C z?0e8Y39cA4pD_=W#WZD82qCI5}*{)*1JF2=u)pBP~`nH1~*`GFxmtNwI!EY?Dl>6OuUjSSo?cNo6u>tS_+@D zTo!5Pm-ePSJ!HGF#IDfk2JP@u82+XTk$Pp?E?}Xb&aKjY%XwH%(C$XER3EwRXZ19K zcI+QDqTo)XW?t>RP|p$hnOa6k7yv|yIX;!KMT&GMSgoUUet;feOU`-A{uMIJIs3kL ztDN*=hnhD1V2RwfF_C%UNH?h=U{7Do(>2-<4F0yS)X~PU(hXU_j&qUn*9~-W{jq#Q zP=B6{)Yu3}Mp7Qq<^J!L3q&Wi+${M?@_vsaTD zRlzAUJOv8X>r$M6KuVsqSg2cD?8xP?&m&WBkweRAKt>0Doc8bR0V|LT%F}RFKz8n> z3jA)-WI8aOFE;GR{pjYaWGaHx_~6FRP1A?D!3~-sr z20aM7K<4J3Aju2&mrGQiMAsDvbO49`r<~4O5~x!`hc^m8xx4~Upq$Oli4nT72<(#G1L!p{4 z&S38VX^;xu?I$5vJAOCvK)jfI%C2*Rx9-#hPdqs#h1uNWOmceQ&4y?y68TIFSVyRb z{K0j^#I69DO+4e!nvna-NQTz`uN6)BV(C#fy`cW$3mf?OsJqJJhU2%LBO?crcjv$7 zc66k^mA|X7%s%U& zw11WEd9lVy)t;KPja1PJwLiS6nc=|$R&DBfdoiE-ec&3Q`qC;=1_b4Tjk_{{F64K3 z0)Rc}+3ZlA#Q(zs55XCy=cBy+v9q2`tMLAp-DoWP{iR2AxLg~Ax!XV+a}m7jz&qIh zw_IB%j|#xU$RxS9+um+-Z98+2PAL0gHkXxH{f>8bj|K1FhIs2Vrew;5#8;uAJ7XIM z@eFB9jAT6bwW%A(aVSNT&#z>1AO3pd_Zwp9i)OnbueFZHwIiS!%C*}wgsB70EeU| zi01vmS#&g5|EfuT*nGZX``2p&h!ydGp@(+DREh=LRpU80s?Sp&j6Pxyb_QX$K>g5d zLj&GpcMS_=4hS_zIaa_F$gl*FFMXAr;fhR3tNJpUoozv(@Nwq2Q2y`(O|_1zQ|aDG$plqI z@nZOB;+GoM?~L69c+X>L7n0DIO%CC0Z)TX*r)XIs^n7Zi2wIO31nM%~pU<9aHO3)F zca8kRkcQlAQW+q4%Gkz8fwJ7bLBc+ zk{Tp!JE96dX4@jp8F9$!E#7_mZQmZIr27|NJjg>j5TFiFV-jbE3O8O&;x~$c0*GN z3>Mo!EZ@eMaKP7Q-^7!D&Qa?pplED~UtLRJ33)RJ;+MJGIWCwt(QvNw4xQGy^>0uZ z)DbM?EZ)isFQki*M`?A5qt<0Z6kvsM^15O>Z>NZ$*a_ zUKxi9eE+o}RhJgSTuS%P#sKUs_QnCZj1S9YCdyMEb_NYMoIWk6+` zEGEKS@ZWxe%3LYy7F#eb1g{E=8b3D}IIHRZ zcsoOl@q2b%FmUluS{`j$Y|DAu;v*cu%Lx8(4UDJ71{^fjy`udew1 z<=&k6N&whQYqmmpk&RCz4=?4Ocsp?fMs2eWCBV(V*|dC#ZkB4+R=!mMsMahhwG!;( zXEi{qFe|Y-44$)h0ABO zHL%emV3G{ZWhHBL8b5>OL|_bRx9mfb)v*h!5A7b7dIHF9UV&3{!~Ll)nn~x1T1zWV ze4w?Ij~l)MaB-T<{!#`OxyE#*UdRaL5rJ;I#Zre`3A(H(I;YANQjjFMFYX{N9Huv{ zj#1zf$HRQ{5s$OWLX46&G8RH!Iq8(=t zuCBn|tleM3V~k`Umt5o`+5pnFRUjo?w}XBcZ`L#^<}8v*VoBFFVn5U)blEo*;(ox`yzSeK<(}}LiWgj?;f5K#xTHn50xro09X!5imIkpKb~g78Tz>=fSCf$aK}|qw zGnG&?d}4im{3R(qdBFPEM^q7fLi6WODgi7_6}4{x2S^ntp*1$Cg+r?*QfSf-e)ruC z%^i;wX(#)V{|K58v1wkF%$G+2Z75)7x=?IiJ0-b}L{(hjx9c*{`WA`+7L zk{K#C;HVPqW$jnlCnleTCmVUA!%-*vVC**#H`B zlvacrJ;%#%^gMJGZ`O=QbTy*5J^Pr|_$*g$W2d5~f5g8Jd!Nj)rldP^CENrLo$y~1 z7`pQ1$b52=NG$fjK_NT#Yx?}3sl$344~&?ogz$*Hc%{r%23%V?fmZ}01S!d(cmT(M zYA1Q&9dCD$)_b?Wif&WBZE7ZHToYV;dv*T?dU*T zq$^+DRTAwm!uMAl>Gsu+zr1Pc>&iz-8n%SrKYQb9z!z31HkI&jtCWWre0~RB-Dd_f zlC}Z|6l?mM2)R=wrMw8fYn4LhQ(j8SGy!U(#A;aYme3RU>RZ5Z2yJK16VJ%yScS(d zbMjM@pzO1jLXwhc*O^smIEc}o>>m=G(2N+YhXhBcs2b{N{u7=T41%qV;vBK7Ufjfx zOO@L% zubv+&orJRer9!)Ewk{0`bCzdh>&fWORj`?mKP4S}Z)K`dJjV+YCpfk~7{bMRYQRa7~76$l=JOqe~GT zbeKwhRWz~z(Ex6^1ZNrgWiEg;Klex*29=lqa6#RLeS9T4m^RNG!ztL&FHeDRSSOWA zInQ`#0>6gT;^MHoNQz<9;xvjsY#o|C~6!fBcr26S&t6KAUZk|~V2)aDTFwvEO zg|CQt8N`JPTIWRc1aM>R&=j$s)I)jiPyH7C7I*#RMm@j1Da|vA8vpDlDyLoBT>&$% zq2i)o&!MhB%xtoE$$m!N$7`1er9R6t)NY{_8tR+liw!w3Mh0eACy@Pk3b;At8Qbo| z?JCWxbwLt1B8B~S9UwJ^VV|?{nMvsC_SNQ5bvC8rPs}esNhmFQ?_<6_-0eM@ z?+k`V?@c)?ZyKMm9bSTC+8NS{_4eXT8Xk7ihu$xf%rc@(D$}Bo1%5u@Cvh6zytntO zJ+O%FHG9jUIz%YIGVD~6y;EczQ4R`y0K+i?`&fXf2=A%wDL3SzNN zk1CA+TSL2E*@AFObF}o%t&#`%>A+mX-5Gpzd8l-;j1@*KNg~PZyC8*pG!|kV6a{vk zlb&D#N}|E$;sp#y>Uak0&Er)g6OB+?r{1<>4W=s?vT0WxU0q+FFi(5Ufj?=N$Q!%5 z9P+Z_Zc0!IKSY-LoYI!Iv)r>@*};Q4VS%sA^yjW_GB+8w7WgO$e>3V9#}-f{jzO4A z1?s8CcCItTq0Ky`o@w0mUInZw8<%euMS=?uEH4zMFYrVe)H%$DU<$aO5JMJIvB2Nb z8RU?`mLfAvmsVnlH3S(pQ$}<`UAHM!JlLI^eKf6k&3Eq|Nmdf&*d86Tjls5jIfpYL zxJ9f~#sUcCT3W`@2Emz{=*m?x(?Tye4l8Ulo0}}MZhx9(sG=i#=g@EW;xXPY4zfb? z9h=x9XF+3#z*3Jk$QSmCqrN+S(;L>|WB?TyfCO$a5Dwh8r&7SnVLK&Ll|XJw z(q-;JqS{Sc(sZch^v_LhrU3{kQuKP2d&=nZGsAGNG#fUR{?)ZLl9y@j86y zU*g6#^#|7*nSo?5e=##aW;V7W`$}Li$)U1g!!HPhBHe#tLpsSZN$+xVky(|gURZ~` z+v&4qi13Al4i&(Hs5THqnK*2=vQCp0RrG=SQ5gnz^~0? zCR_b3j~~3M`F=quHq2n3$Hv0`2`K`V$2v*xxY5q~dcY1TDnf$n*KJmf#m};6l;`5J z0#TezF_;F@F9xkq&GPdrjZmAf9+B(`!<0hFs7c*f*0_R+Bi@#Oid01TnuL*Gv@eIu zp>O5iDMvG}Uu|>Q&nLh`G)0%p-$VdU2GO3Ma7^#N%H?xxRHARxDY=!$#PRzE|Hoqc zF-Z^hrW(wB^dr1$5NlD{Mc#GSEdN2@fDr}0_;rk!z=U1A6r~eIEPJpDS=-14Dr+OU zd%TI1IYvSft8Yg+C?vWn+6%mVrs;*A#)1`svGOH;^AP$`r9l5fo>_JA#@~n26=UUV zx)$ani4dED8K*vyBziKw`~@*>Q^AF-#K?w{c<}>itj$P%Dbg{}ZIai| zTMe@e1Pw!ii3K9_#5L(< zOIO2%$I#+Qlt}*N1P1=7fkuRgN-J&|lAXhP-WD6GYX=hyuQXgMTlI~8dv%@(I-`$6 zc<-1NQoL+RX4Ietu??qauwX4Lt7IEWn(Kj#;GN`>bo{l6cnENX1+C}JtNS{3u|OvZ z$tv#Yk>e$a8zRB(o@Nl+@1{#df;f&B(+A&=b69gAKyc$jRTpow*P>m+Ez%u9lXSk@ zpkh3Zq;W)wjI4gZi9J0GY`I^u#>aH2ZolB;U`M(KiNCZiBIm;M{F>DHpw#fEQiop= z9c99GU9lVM@U*`3yVy}LY_r>673UUQLz?++hN*u**Yqpd+=pEct%iVq`n_dNQv=z< z<0HfEm_#Htm8^Vlu~zr_X-5SHuo$$=*lKNGf z6PNRkD>#yteGXA&0zm-skyD>TYQK7t>4B#&5m5*?7N&MI6ISPi=QRshY=Mn?>GfTT3ckNI$LPWfez3J zH9VZnDgrq6#}w7?J0-YB$}Px44En=7)+4f}s7ZNV_28}i%HefpgL>uBuy+?}^s2@= zFtwrwWL?c;DyKguq2QAI7p>kVO8F2c$!bus-KFcejhT?7p(&-jzOORF^0sd!X$Wqc zjv$BcJ%d+sG~=9nVn{Up{qzUIhC|JTa{ES+D#=QhYO)&S7|fDWKDCa`i35 zL@2vZJ)C(|Qfqz9#?lcGClO!F7I^R7SVGEsK%P%;1s!d2pvfREk;sAaqW^h<07Jk9 z=ZORIJD8$$nsC+sCr zTkT)O-4hU^XS?u{mA1QYH<^cn%&j3R2&PYQaNK<=-Y00uon(I?W@BIz+qO*x;cQ7Z zz{!Gqhb|bz9V1Y3Fwhai0ez%COuCPL<1K&t7Qll@fcPya!wU{RVme$TGf?(10tWa7`$I9Q<;hvkmSO_) zUPXA-1&yxZ9 z^-XG~^(ii>_95Zu*TZoI%q9sLp&>-*UB6K8-p9X_$T)t#D<-M6Wh@!1F=0#$?Z;f( zI__a-+j0r*qh--;m%pSEEx_dWlUNIUL8gjSsfb(f%7CTVL=6{0V>mZ$6=&;l=fs#+ zAE1x#WBBav5N$^#N93j+8s;AtmR0OwZ2d`^HVI&IQpXg_UjzoV9=XZu)cHfW47o*J zB-i5u|KDT3A%uyXIsPZH>kSxCV4mrG|Bs~T4|0T6xrJBa@vWb%D%yo&NuoDTCttd% zSIETCO;SbH>%TUCg^$5@9FN_ToMm>qqqq}_OA8hAJQ~i-NPnNXuCBxm@39JEDU|{X zq^|&#i>;Z2QM}Rwv#l}zM+|v@qu1TXq)bgwkt}4)2~4a4F#~l~c=zfYJ(Ps$pIJ~R z!HJcgNv;X(yG6y-4-qn}v*@lYO!1yaZ4%yp;7Fco=Msser4#X+h4TTVo1#*aqoapY zcYUP)0Ec;VY9Q^HwCW5yg`LVb-dR4_Edp4VR+YtBtqI>><@@g}d|*%M(I;}~(^`0A zq_%gVJ>t%%@Idku+tX7zYXc0Pfxs!au+14z;-V-R1;w_|RhFBbrw>j$S1buva`^V= zk?l}0^2sb10#`B%$0-K%Bi!>QZPqg(Q%8TGJo$|a7=hapD)@dX5T0VJTdoco-b+KJfQCZz2qef14b>PwC@t)x!-T2UvB{99+wzv zccN)zK-T9Q$wQ{N+MEI&AmLKvGMF#>@PA z3`u)l52_%D?7##Td-{yizrpty5&}G1&josg6nnT^(J`khZ9HU5-6&p7-U}jG zEHD!sO5ZGEBoKv*cpJh|v@aFJNp^@abiSFliqu>I{{^Qh&Ho(NZ?_nfSqMSs zY`Ah3<*BJfvq_px*eXFPtlX)q-DIZTC0!MjWunZET&`QRIi2!Lk<1&k zA$_^<-bsq*z%~U5;J^3bn!WWkM5v^MSwln*+T4DuC)n^zeK!1J6GAY&I^Y2saPt=W zrx!W-(@)Br$K5Y8I=^}&$UtdD;BItg7{JZn`iT_~8M%bNsJUTNb0`w5hqDP09hD?i z;Vks+H;P%W&fV-1JSfVuMeyIuyI{?EeJB0|1IkyTR^QkWQ$#xwV z@sWs9Zw)Jh-KXd zj{=(She8Eg%aL0nPnA%_WNbEor+`T(9})~7Bg1kSDUN8PIkFqgj%1-})WMrE8uDS6 z?>41S@1@w1DTl){ycw_S5pt>@=iFa7fl-6Uv*3JBUFmQI3YC^B%FhPs^~$$C9wnOE z4E{<-k$197PlUP*rY%ICJ_0$p&33oVPe2);3MHd&9q~?To{eQB z81Ao@w{yQ{eG=Zx1-X8-{E^sRC`2GK&TiL@Mo^im3<@~&f-xU-tG5t$F2h4DNmiG( zmkvUCwhbmo8X5y$4;eKybfk15|HdzAx%uthRHw=de_jKzL5%Eu)R;`HEw1Iu4CBO^ z0V}5VGKJuQ+VCobrIis=8n+|^R991pVd)yisjO!Yj7a<-zP4zI5(44mIhJ{DfvweM?obIrI@s&uWn6xnV26PJAKfw(0pJvFajTAATmt%}pNuO? zB@gD8mrrw#X4-I|Nk1x~S+ZL#YM(`2J8b4zB*?`uGvQsyBAfVRj?&pcdjF?QkG~B4 z=btRSxQ`sK>GWGR|N4&)$SGIJB}(+%AYx?{oK-3LosA>)r_#3sjy{kIzTv|& z0>0@!QV3t*mTFTam^jD0k3MvS-x4&p#?yq;gYWdzK2F2@mI|udK%ddEVxlE`9@-oD z3M`}gBsfKUEh5mcBvl%J22e7i&uj&Wi&!fxvc95e zM5Mr&O=@IeZ+iFbkIRwrK&So8p|j=Z3%q#8mV}o%B!mXOaIJ!aGQ$`&V2l z7-6~%QqGKkKpKGdXxDf(+ah5w985(;N4fMgzrMX!_yU|Nd=MmS%z?48Qb*Z5Is-~n z){1@dYnx93@dv|M8;K?~0TJnkFT7aYANuHhFkO}#`^+RcQRHwc!t3Ni*r^GUUL58F z@#A|-Q)Ua&ZGYFIHJIQBJQRu0T~}Z(lN4pVfj=av zY2YarF{Fa8wa|m_PY(~MXCD<_UTjSdE%9p@*Hn;J$YNnTgpjO0@L=peO-ebE`|B$Q z%GgE5y{XBZF6M`|1<|QK^4PE1@Rb^gNn!rT#eZ^U5%h&q;TUG5@FI= z^XS$aeF9Ja`?4Ut%bXExYN%!m_FmEmdrJQ>P)-|mhzL_}E)mdI5Eq6pI<^ga?rgWJ z6C+z#Z^YM$P+ac>1yqhBg3+{$ip+ESLx^O|Anoy@Rp&G28@d z8bgu9RxKe00x8G@(nR(&N9Ydkz<7T=V?JfNJprtt4+sgR%nkR1yJCSiiPm0}I}G>U zO$5>u)$+1V^#c30UPE*VX4xS6S`{gnT-gc5Swqbbm+0jgv|uJ~#dtDVPf=b<)!lJ3 zAsYhO`ADbpJj=zxp5*CkvgeIl1bHJS6!J}i&N(z?R|HEB%pOR~!;d+^N*nUg_!q%%#iu^)_Ov8(Aid>@) z@wqkN7I&d|BT!A@Th0m& zN^^0IHjpw^gzBPSOiew+Wz=SueXYqfFl~+e$CicTT5cOq!!ddL-`!>3(MO%92SYIz z8-K}n#JQKO$_uL_s*UeJ9)~)&{Ef(b?IOw1kSQ_-K?~JQ>2_PArOBRjVYTE#>GEy2R!CZh6fyo9^f13@coZ&@NxJOMqASmfL7VTRL&O9#7{MeZ zuOU4qoMpf_Hmig&Ym=SRO6M;SAagbF!CS(B)p;9VTJcN%;F5*%1M7^V8L3)T? z$66%YX$q?t=g%CQ!!yF&tb3uJ!_bN+;yO96Bk+#i6zi<6&J#qd2eQnZ%z0tG*Ys-1 zUf@r;nBhuIw(LSBq2s$T=t5YOHd%I2#>_!LJmZ3Cpu%#IdUd6&=`D^05s6+?nzT*e z_3O3!_fhBi3yHyDC!l>}s+-QCF++Oypf@OSr=tr9zRG3;4XiO&5V<*!Lg*2ysc~8h zRvSbGA_l%lkGC!340Bcd8rv7UrzlQeA;N6xBY>ZEJuQ74QHFIrDP$?!IBEq?SS?m4 z=bS6q9d1|x7wH-ww1KS}+((3tPY6%trKw@#g9S<8%}xD~@7g|Wp(V*oU#Vj|osw^> z*G^h|c%G!hznMekwyhry`?YzJ7QSW9uBdI@!~-vro-DwG8^%FAHChER3>qTAy30(; zl>P^!B3ExH3UPne-0vHHDWHIc3xOM>( z3i5p>#@5{?P^aH5`{bXbw<%C-y+pw_dZ;(7j_(!K%VdV<$p7l|rw)32H0N4Akl{<- z%dgG1Y|H%?asyv!UuA3Yy*IkdowZ4_KN9%4@#qz`nlNS}W-7#30PSjsSu6Mgd^^|R zh$0>Bg&;0Ya>M<>_O&%`pc1~>8N4E+w`Ojf8OYHXp!hj$FQrB&SNjrO_7uro(=N2g zTx{&>)#FnxN{~gpWZwZc{F9cyO@BJC!d3Wpicn-9Sm4Mp7*@ zyhyGCNa^_ai7jOrHZZ}(2S$l!@$~mTvg4KO)KA@XQI&S1a{U<6^eJaL^{tYx+%DP+ zHmip1jTZJB{=i#vg%ELjbeqQ7)8$)+!TViDaEh*vAnYHp;Ty2u4~})o&J*QbIEBUV z5UH<2HJqZAhEjpP9a5OivcTsl>_r6%q>_HRd{CZnLd^G%`*^ie`Y;vnpq9C2Cc(-h zD%dQoqCDD2j{TbQohCX*+NmtMflDCqad;y(DX~ncb6O}h%Qfw;`g~a#*6ZmfKP=6b zVXhI5&qBYR^6M+IB9JjQ|+j$!1r4PLgVW#Z45HngJgc?Z7?;HaxVkq1!XC zSc0*vmVFsTEdDuvl;R+ZS!uMlrXKVXWL8c5;wfm`qVEwi_a!*Q1>qUFf`oSzmRrM> zP<433Kn7KBWzMUkN&uyS@%_pszZ6d$M0fICkNmTIZej#0`QH*RCA*jZ^>~_ z5YeGf>zRcfvzM7Z26Rnp?l9^|A#HDLT&Xg?Y(#tqk2PE2AW6ff&F-v>{ny4vp}OnX>i*wM%#+uA zh2y~Q4{zY&{-2+-XH##ukNk<>(cg#WchTaCU;UDa{KGr^AIXPTgx5QspR0Mr2f?eV zpEu_3ch~#=0DIZjyWf|5^q=v1!GC2}KOgLWL?5o=on@LVz8?T7w#$v zZqG&U<4kL^i|wp`_%|qz_bWbMLm>Y5Eq~{^=jj>dy`EnDt5EoNQ$*47%V8&fYLy?J z`o#q6>1&P9H?j8U(NZ~0@xW02cWvS;!0+|)?)T{zNJ$nFDjM`*LzZw(_ z4G0Pf3TV#XUl!pY2|2VF5+nBt?Fj%X70);Y3?S(!XzYbZtUvrVs3Bl;KtzU zVY#Ai=$Orf6u4L3u$`^}V<%qaqd%F{?j959_j^ot@1N$@jRWXezCwdcl$Anb zhnKJ&yJ}T<82Ss^)xlneZ}~0RsmLr0rYtBC9FLr0)s0r)y1VUdu=naf*rBqLrwH{x z^or!tj@jeSg(-E!^>WQHn}nmT7lqc|WRB&oGYOe?SW2aVSbPCDqhe=@--?bj>DNB;EY$0u*M_qO1IUz3v$u!Tk-8U3-{zmT`R*kVBG^D=h55 zE@B}ic2bR;%LAL-xkg=fP_uo7XAlfoO#6=?At{vdDs&zVd;d$%ip@!#Uwaa2JhBMi z{Z58nJ*=_-9!rTcp6{tH-?`$v7Mgg-RMj!oii`##-{3F_F8_Mz5}9mcqx*3Y5NhAC zdFoj$^4n3dUEco3D@n4SCyhzaqY32PIVkaRYsioh-w;8uzu{0_$b=kMM* z@YyZx%G|2sKs^ZVe>8+Z6>hx7;)FeQC8Xr)y)fX0cy%9_Qk*0jiOk@a*3vDO}1>z8f%#A|I9Ln|$kCIGI~!1*os6g-d5yl2w= z=r*N~gIrtL*ddw5`PgTsR-q?!e!q_|E8&|j|Jx(v|5dNerc0C#6bR@H@qbef|9`3{ z?`URj$0%#yG+E_nq+qx##=gT!BfDz=G%Yf6pK9EOh}hfh)*m);M3^-Tgl|^`ng5 zD{cMXn~44|SBz6Ui1II6_0G8DGlY)6U-2sf$-mFvPd%-Q>2`A;#PYuz7ubxlMGx(U z>DIBQ*Md9sk(ba?Utdz6pDEJ1e*+1M^M!u}?)vMDv5HG{>i5n*P5FPjx&(ilhf(+3 z<37jlmj=%Ky8OuO&vre4suF@T~nPdi|@;FsqrKT+@-+nXZnJg{x< z3G=4&SMqbaKalV-J~3~qAMraMq;=-z_lvMU{?{>Zu;RCkiX>3v zM-|OD>I?Pd70BclMe;fyUhL;O=_?-gx}ULW{r6zPvjB>K>O`iOYb)?SFxiY z5Ss8=@@X$4ce#I7MkG)qfP!o?u#M?)`fdBSSiImjkh$dN=C?cRH?#eh*KK60>j!gS zLEV<)_vz>EZu8PQ;1m5lFarOF(dg>;8}CO>De(UQ|33i0`ZG-ZoJG||MfOh|ej@+t zFXNmo*}P}WGCuKjqO}_S*w-I}|8#pGntXQiJEZ=5IcNEAzoyX|{rm4Df@5F&Uvac# z1oo%OXHDmTUQ#hI&%8Jb$#mcyAyF=DL?kPQ?tTWEsv6&l)l)uqETD(6CP zjSz&QXa#w$-mE$)3O^b)DT$K#(mnY*mUDt22temv3gpOXl1p^w+f+yKQjeq+Qa}j3 ztKHyDSDukQ=$eY*1qrbB9xe4fTLy?J6z=!u@(l=7h+|JK;3{1Xg$R4t@%w>e7-<#M z?CTSRF0hREW@r)WHil=4*Tgo#Hw<4GH;>nwF&UkE2D3OLGMM)lLT|3Hb3tS#WsARt zj$pP+kSJ%0%$t1zgsH(s+@(U0P}R@Zh=gl_gV8 zF8PUr7L)h@`V3h}#<2|%_3FVO+6ajeaUsvt^$vWPsOn3?&ER{)-_Qj_8*Ow?smrB# z;-A0y4a9M2_8q%WUM!S@!E2xaQ}?IUB2}^S*7I98cgGI85LJxB@kHUzbp@0JK&wb` z**3(}Aoy{zAaL}>2h11x!Y1=A7#gFoEN#C+6t4Lgwa?=Xi7ZIED_@38|hmv z3Sbapk|OiZRGp0dW;*~_VH>29aC>*z2R&<3q4o~=``In5d55W}ETvczg8;^e6F?zR==mgzywX`-G1NCW+iQVnC1sC|#Ta9% zGBy#{*IfpL!u-=xtc#S>n=YHDM`T zB*J-^`LlT*ysxUn%rfrfg5fF3R5pLm&xkmj6OW=@2dE4)&L=qHPaLH3IlZ1lh?~dd zAH)%sS$9dwNq=Gnw^OyAyyXy}59mk6R9qDkg)rH%j=rUm1Zg8H?PF0~na`Y$L`0=( z!^Vs`!jd=j@shTWneP3yB62v zeMzV=MUqeEIIR>wns_p)2FstMXROcSx5uBUcG91GfHG}(&F zr%g@TG^7-k1q&{}scfe&_tKDec;)O@u{gahc9n*{@u6mKZdJnh36C|h@f??Tj}_`= zTkv;D-}QxKa1%S2qwTGcaK(#Lc?YG1E%GUm90vEzOcNlC9b_`R{E}@%32-{_C|n++ zj-;>$kQkeZ19F>7YTMiyBNWnwii5eHeA1V%XM)<|l&%KG70789W~x@jF~?F7Y8;`q zWwT*XbU?xKFEt_@d${u~jDUUI=XRE|>QlKW~q{2K5}69JZZ)*&zjU^Ai=!HK(3ud%Lc@R*y~uiiw|ZUTC* z?NyBic0sd29ir4JZC_lwh)8D7yE`CdLuM z?>EwwIFNtd!A?$93Dc?RJ;Z+lwu5&VFoe&MqhgU2Jjn`*)v%12xLGNqxCyP_fFaVi z8hn>po@c`!86ry%T^Us}Vjx-z=n~PXWSO_UK1Uy>07}{Ree=@npalaj-*HWxix>e? z$smnc$@hK#oD)~L50mgw@y0Wvi9`Wt-lu_qb1zK)tyMSzC$T!0KUFvFrWk?ss#S1 zzv2GfQYC1M+@cr~1ePNT$$jOFB~WV)6c3F;O&%o88ar|-80_KGfM{aN=D<6c1lbJP z*RE*d7*u*@W*pE~qs4a9;fZA6_KmHc+{_5g#Q3+*p4xu7u5m0fAyG;GzKQC`T;bUt9(9|K8zop3j+JsybO0>8tpL(|%&U(2?W zZPxOZk}dY^qFOry4KXLyyAQI19*o4--Lm$=p;KrH`hD)C8-;H^Oj9|jGu8(&xEM29 zb@0)Q3nnbQ+~Z^8{ID3i$US9mJ!lE}j%3=5A7n8A00xV>xpBB-k2eLti75sorWq1| z&=?kk*CX~~5gWYzD_|my_WFw^>q<0k7!=E#-i96R=g$iS=Sdo{rHs?A>QfM8stmLk zT-FTwA^*PO$<0l3A>kN1&vl#Auyf%(St9WIre>)zsvUW9H>94pw{5QhDk&1kk=+7_ zg#y_p1$}wL3-8B1wxZ{d*Q2FZ9ZSyOHf1BfH?2l-od2XiR(!yXKL^?yll-j*If$bG z$bcb2%46|S4<(ly_TEyKL}7t>@Id)lkArC*^2B%9^%$TBDm_x*A?2v%uY&>wF{VS| z%^8Si!XyfopCmJ%RdkoW$i7#Kd%7zh&qM0cs4{4gBt){beC1@0I-gp|5;`yEeD9ej zIML__H-KuNgKh~{hLNkR7b>cA0Dr$@DlWiYFr@cMW%eT)nj75;x&vIh5G-0cj3kfE zm2LYhW5fjm^0V3VZ8grxUshDN-K_GGO?YsGK?$wL-vLtX6r^hDjg)M-C6w|ed)DQs zB*y^C6Q?|#zo==4=}8GCHaYJ0b2b7DATmK?^d(c*bGq2>k$1*! zD?k@G9KX^R5cXGY&`p;VLdz;vr8-|%FAM0~ZB|K3C$D3DDBJwn~ryh+F<3nSM1qk^@m?C_iz1V~I$#xXw(LrKHy+3nQ*Y1mB zYF9+A&-yYGGmzY56lT*6HIDBIarU!Qa+8-{N?-Ll$X{e$;{%18LaTr-K$DQd-}m4F z8b8I3ywF=u)N@iDdH8`<3*qu4Zn zY}BKL5TmID#lE*3zqzRAK9yX)2$9P=Xs~6Aj+AlGB@1qf)ru3mul;7u7tG{1myQ;9 zy16ELXVxx>Xw)6Dy`+p4MAICPn>k5xO+t_4qzGl3KWb%B7Ei9AG_YuXIAFSe5!tM> zb5DF*d%#sT;~Sei3oB7NKD*rd*!xE+;Ed8KnTmPxHu=wa1?kp}fV?%B6dQCclO(^+ zl=(8UspS~udNn&OWh`suVMznaiH?b-eqELpnYlyt*Fe0p5j|WVkugf`xFZRM`ZfgKVU(jaYFcq#wR8%RQZzin>eNlqJVgDLa8trbWJ+1i~t$2aHlUNU-9 zP6BgeEowEW_~^`|f9uOnaC%&E`cY9lq;6n!`R=ug#*V>s#Dd?HV{dc&h>L9X0V35n zOqcVPn#;Ib)d-=rdl0#^w2WEP*a!2By-$*dw+IO*X`IU!v)qRQtJ5GwCCh})*182v z5q4;rgBvyus$nsVHSF+s+hDpBH;m!SXL{qofYo=h^zadN`$&Ce4U#?fyY17ZjU+sA zL5hQtNMZhtAba6?09atN{-N|jPK#kc^SWB5MN%if%#b)Da}FfvlhTbokiT+q9#OSm zyQ#i_D8lpB@z{GXAC3BL@7u)z2zMV7LImI(X$}bwLY~q{CnXssrm{D7*|9xfp5nRb zz!Y5(FNZN95tzDemS2H_5bUPoKrC8SSN!B)c%4kGj-E76D_r6Dd4Rmedw|Cz45~4t zCw%42H02ic&c;lVBe6_VQMA0ngBB+#iorH;w>fX7^G^OyBsZQ7=i0gO)k>7vN@}NF zRQbvlFLBTQq60q97j#{|QNAW9<+l(^9G2z1Zxyf!^yuejf=njJ8hsyRt-B8|t3lAA zdn%J#T|S7J92P(~%?&Jt_h_PI`{IxcuzYt=9q`bFV%1U6mB-yqB&=5HZ3)!kW|-F1 z2jh_E_5n65AuJQS(L9NhmC$|W^8m4X17HpsLxy5SqMj!K>;a?Ghn0=Doq3>F6uSaP zMJ=l)vacd1#1Fryf_D@`zdpb|r}kI3DCIHKx0C_cx3$bmSIBx|dt(LL&gzyp08yV; zfV`zoaQY^+VMXqmV+Z2hbBU*N*W6b`)A#(NGuN+axDGik`gKn9cl$7@o7q}eykigs zwnsNv8PLs7ntBNx+9UYrgb-wd8YiXW+0EI)n~8nW4`D6vKCo+|;}(3&)0d)aD+S^9 zigTKwkstqY{E&LxrGXKkBcrd)XYE$LW8Pqt^L+TQC#w)|bMa)azC zXJ^E$M_K!rB=i6+K+?aSKO5*r;=SCwcXx_|B>762aiKt^t#U@&k`SW1EWcSdvc z>t|pb5GTetbp=VLjz0oOSSUO^z#aT1l8SIjv5T9>&$l6D^0}+aVn0JtEvMV0@49u5`l`e}s{*sK>Q)l)2$-`=` zTZ8G{{YmMl<|PvwfHNy^bIEpX=DxS-lZU zC^?+RnrF))KCQIoyzw3@Lf;u-q&v98Hey2}BXq>+U{VC()`vIpJYR#l!1nrm+N zdi>FR9`7wMW`y`0${Zk~CTrOz<_Xdf$O*`G1x9ztGm(bF!jCD`Bo4?^o~H+DWtLxQ z9`0qkS%)aMzwf+^`#h>x)9jOvIXm!z&>BlWbxax$<|YbdV7wZgxRFxfOpqc2@ZtyV z$L}XYL4WwLhoN3Px});}Kji4ud%g!Hl|DA5$;e3-C7q^7M+K;5+0dP=%=bB-y_6a| zpZOG7w&I37gpO)i{>sklAOV)y&ImVSGnT)u*3_{@4zC^orVp}3pQiL}w$NDrn0<3K zDRpli&|dJx&B2-2)Pjbz{(kW*c&G6b0uRM8@Numk3c^Z1_>FZZF|+O9w#L}fStdK6 zCNe}o(noC8P$mE=y%!yiJ-IwD-*+p?KYD8AJ*HUXjR_oyA#a%?q(n|~c*_8kcqBMp zwRDao2Dl?l_POJ!r**BbFWzLrjM`&W-8-7S>=kLF*vIF^ahgu;*U4tZf9ywlfzkso zb@zeEQv(gG7zY|2V2M46 zNuGxnwm!lAQuXe^QSk>_DmJTH&GC13O0?y^L~gi50zkxk23y5Dx;_+145ZLv9E_950K{Vt%$4e@{Pef1ciJ~lvm)~}+p-e(+T>TQjM zD>q&ugo45*c^3>f$or0bs~Esds9`Vv8sKfrMh4#mO~K7Q%4-qh(^tY-!l1qYZ|>x2 z;7^4{0R2OdkP0LGfifBa4w#2q*7w}Ov|I+OBXlG@&&`4;@FC?Ml1~dA8k%P*JdX2e zN_A@Fqq<2)t$YNkvW)MoZL+r@D#6hTiwMO+s6DYWKAY1i@`hU*9QLCl*LZ-taT z;}v!HK|j47%!JHrQE)^RB9a&ZD^LL`%PzvQr(T+g!jAT}DB{RjpT`4@tnKK-Wlu^y#5jynJ8lUC${-QL0k%Xm5N6k&E#5?zsIEsc z*o#^A$=6rL{dfRg1|L2bX*+%IJ*|*}yYt*gfi1|lme_ZV_N`A&{$6|SMnsK_R2`*4BT);>4HsUK;uXFaff>+k5bE9yx_n-)QTr7;8#JUqcrm!7IVyutRHJwx~Zjn4c)23Ot zo;g52T1y7;tEJxdhNPfMst2idp& zaRmA@>U|wr861-h>DvN>^+B)4pmV&~HrxsV{EBfB?KSA_WS;RJ3~=F0mhU}l&8(** z@TPz-g;*YG?BG2EgxUnyVCGvIms47oAPM(U4kE7{g05PQKVYp8K<;z{mnCr(%iel8 z_oz=!(O~xEKB^RK0NW~1JEJ=dXLhBqgwH(@QK3VBbmNV1jwZYVmhNE*DNW8vUZ+Eq^= z`NJ827|v=X0kGqh0F*&z4xx!53Et3-5n>KKOe{Y+_Q)*yL++ZQtXy6ad6XXNq(aD8 zhsKOQb0gm4fx5iOg@Ym=4}!matXOd-RmivgxS$W2v?m#v_^_Kx?E`!joD?f? zqU3_6mh9x4S{ou1YCr}-myhc~#L`zD;3v=DxAERFl+R)LGzc;<`Xr^uj6UGWRvUPE zdEh(Ani~;xX&B`=4gJRpx*9&P+*1xT=a{G0XiIYhg(_cm;MjtVzuHD$+})!SnvP}l zaYNLHa*`b^kc_70{M*IREJ}Nd=!x9ddk=~|N7f{nLIlni(i|M!BhKz~#XjhV&|8vh zMX-JW03D{jV87uB5ZTD-*OlHaiQccR`?4dHQJfddlA@6(U7#Ee(;h9p z#t9`Jk?l5?iba{E*xUV@8|wsn^q5TIY!w{dON+ZCA9~M3g`)%`+8T>vUv&!?45B0x zRS*i-T9);sqp@^Um2-x?zNkwr^mqYAo}(1~6ry~rbcL09P;?Zf!lPc#?Z|gjA4tOs zobG8$srYz2l}O6?;1eGPI6gtO#Dip6vsi(3dERkB&v`>o z_j!_!arJWpONBkCt~0fWV|^GhXJvq4R+6l9d;mNB{B8tqgAazvZW{$2GWV(a68R(OE zFZdw%D7_IqKwyS%ZyD;xE1mbfQgbQTEm+sz@ll8B-KDP@E)uVo1Q;O7*V|7+6km=M zri@#zw=AO*lhwC{JP_D;VZNj8o306y`RafwrpB*Aw1BQNk8*Bssbh~>i1Y&~p?L9%=; zM;xj!Ub8ut1oI<$EIbofTCBAsrh&6{&LmvMI!0&S*x+D$Mad4)zsmz){C zUmb3g1R`2=2hAauGNqs$UaoSar*Ylg+i&H&pIZ=I<7RIcph`q!9ro#i5f`&aO6MoB z19w8Bdj){=koUVm=41T^l2mG0oCO>t08CB^1~&#laL14Evus#5m6Eb6 zc;q?C<=&mc`fb~=;h)ns&&t)-VmRrflKH^(@SmDSWd;Ff@S1((P- zs`Emi%CSaYw?qb8;lV1Hj5TEVW^oGiGpL&>b(=G^E`pO}(ZYnx7KdR}!;SA&n0MnZ zS&Sz^Kd^=HR@(EI;!2>=CxkC2ZW(t)mq7D>HlEdiGOztKY-m-`*{c5 z)Ch0n)=dm=BH+NNx3Nzc%kEFGk@lJ6&Nm z4cQL#IxXn$cGV@eiKJGE@dKq97@Zvmo|#Og!41#8u#luY&wyLW{{Fi^{)jyjq4C2#yL0jSxa&rid`nu1&zuZl z0?Tu=dhfzoxt5X3@2%lO#c7k~I~4RWhWF^~17S}d>lg52_P&G-yvY(XMI!Iw8@Rz4 zD@8CnTy*OjjVH@lqLNeqBy4~e3>=Hk+5u{!OKlL`G$=pIrv!qpfT$s7_e$`Gvf%?r zKbmQMkPg~k^;e#3n{!V@0OJ*b(o@{QqG`+7R30WCibza(nrZ;OJ^Vylv-6yhNX8R-b$Qv$xIUWApy8w*~zI+Donlrpzj0 zR(jWXyV2L%d}H)wt)spm466OOyl*U%O8lAbgV0-LU5F-`?g_A$~Px^n&szCRj58+17q#SUbpo zv}H~H%pc(1{rF1_w$al;``|h(S;z;z0mlj^vG0vmFjBM!1-%6S21u~L(cFf!ynOU- zzo)x)n}CbqFx5SZta;ZGx2@14daHwK_QhTrGcDGm)=hhBF?y)9$Du}%?wfjhjYJck zD-Dv9HGgKAdkF|eC5WsORIqF5a%#whVCs8j3Ts44O3!gGNilm^{n-= zDW_lKfHp#KB+Cr587&2XB-IK?)oy0EeoNxDlx?qJj`~6dfejsJ>bvt=Na55&vv^fi z@F?ucJJb71#LLk&+(%vefDd6iz&w=F;LP|AQRQL%`^@FdExV3l+lkB=NokEu?RrF0aLuAI8W8`r?8mC8$Nq0EL z$_tOKn4M`HJKc=Zt2EOKew`lG7)yxQ8SwngeIrFrOg`XqorqLBh)R2q`i{`4#qZBK zPLvRE&WusZBzyH>s@5XTD7oqC4N%1e#Xy!HaG9G}iCfliX3y$KpurK_qSNcyp6k># z#y{r1FeJX$9cRE7tTxKt1gax={K-w;hBtHXgjA?E@oDk%_IlKCI35%AD0wtmaES7G zT5hy7<48c>k&?T|%p}=)YZ>>^Rr`9)$D|Ix4!dA=Qu7JFFKm^x6Y;-wGi9Gu5Eb?;*5O#1;Bg65i7^bvFz(x7eRk-!GlPoe z9N6#~WVgklt?x$LzJ2w$nhcv7@=W|j&3d~A#!sH?qIzl6`ry5nIC*cZNbpp*G`*nY zb3z%)8TWxdgMT$0o9WeGY)+4y#tRNtwN%qs18`= z2TERWbqGa~*^^x@!jUrm?cz+=E5ZBPjVSdVfq!;ORj>v8{wy!2UIPpO0TPW1)~QF?%|`mjR71Kk%0Y3CeAjT)Yz0xhU*{1Jeij527@_fsBUd9}DPo*F0b0Ame~ zQ`{%o+t=O(@EzxC?Um7^WQ{NuWloK!SRAQGz8CBC`A0W!kk&1a#jo`7IhKcHqpVQ! zethd}SEbSb5o`TsK#a5g$A6*Xqk8wTI-uUlVt#y3^O60hrn|%4kA) zBk|{RJyv#w7c(Q)yxCh`*>2ZuX&qrGgv2gMsfV8aw4#qIB$T=zJRyvIG|drYY<&$v z#~;xSh5c`^wdK$6^w!+3GzJ3!>h0{NX87l~>ZsSX8KQxB)F<1OT)k*Q@BnO6R;!=T z3^c>A#%IY_U;=*pSlgyzN$N@{f|a{#{P#rFH;Pn^mIO^ho5q)POPde~ERix=?jJw@ z!F8h3T@n3Oe2Gg)E}KI%N3#Qwnp9?N4o=?(OG$8(a18BQnUL+ulhf#@O^v}B>%}og z_yeL9A=6(lo`RakKoUghi*m$A`pD&bqx)wCDY0Nv45i(&B$R;VkYQf^^xeR+STica zThQqE$C;0i4kBWc!4#K)=mS#w^v*cdRnP4GU2c8Fd|&Oik;w`W_cY}EyraHS0XG8F zRKCP?zv?~P+uB(#fcC}O%9hyOx$Xjlq1gMoIp3&uVXt9M+msSiXjcG5@Fqt(m{Etm$UEF}|D?AyaPC2Ve?>A~x90WLUb;7j!@F-@IHWu85g4x# zNTiVmnj3%j#;rOsJU!WI2h&0IP_?CDZoaM*r7Ynt@Jx9{bOL0bt1`2zw>&sWKg@Z; z+6C-fhKt}{aqa?$h0RGday&J>WaPfzivhzFNo17hDja3rGOXueygNq5F<~fuRPRo9 zjn39?k!}%6Cnw`ud_#0JW{DoD%pI$08Wp0%~OH)ieFanSF88XwlsE}1{0u0b= z0Xf=A@#cJv{(k&`1DqY=Ne7XepTx+(_@>A_HX0v8S@2T;QcyyBTgg$b2PT=V71_*} z2%eAmVfp(Vx{tpkVcr!n=**UBxhmNbqDNOKFx&cJ0`p{Z5^Hx6wjBw@m!%ZCGeM!Y zF>d8&Jkc@XP!Q+6F^3cZPyCNJDO}b3s2|#nK-rqUU6>C&6>_I^;@4BA2k%xaZoa9x znbXi(a<%6Us4&^oK@EL;!|5BB$a*;Grrw&=ctx49<7wULbZi zax>pp2;5ETo`7QPci{KWBW^f$`98r)+_7ERUYt3=e{rqx1K6QvYHF(7?b`B-$HdCG zHi+4t<$G6%s)FfJLHX*c^zspmC2~BSaJI^OxDP&`Vl>k5Th>Y5xOAYy7qK?m#OyT9 z2xKr~K>VhA3#Qk1P?=v~4TgOuk*`e2sG@Mkok#g#5K93#_E)~j*0gi*lhA}Vfv3~x zN>HB`Keh*B&TYcF_=PrC@?L5hDh3JtWdhInFua&oq1E0;pyn=Vpa4|rCUjPF$ zem0|zemY)$05JGaVHhDI3I_=AcW%<`;}Rq3E;oj^j?dJ|ah|sAT4IKKdYy&5{n+7T zD~ToE9Q}&TJjU}wJ`pJlrz)ySoNeghx20HHnW1CiIQl&pPGAP6T2Qc}|v zC!$ySEYgsw-{FglMXJ|AU-DgA0;3V#CVA`cCGiC4KCr&MCV5gF!PhTGpNdk#pW(-9 zJ=v4dJ)gvb^TRy&ln@#FVPSo*cd0xab7zMH9~pxS45W!HhEFy=mvE98(Vj$UYxQZW zvmX7fks$)3N)NJBo}hAGssac*F7LjP&yi?@2SQ+xTbGc3ZYf>y)a~-cXEQ^aEnGjG zG(%OZ=&K)za*vF%1EsOUi`t`iXa)6pfe~Tm3+GYr)&Y|Fpk)>1MEj_T@m;ETIDL$0^t zy06Einf7#z8i~NR42E8QSfA~C@bCC~qf%*RX~QQ2RCDI%?S5)CfN`%r0tkb8b*KyP zoz|#X8A^ib+jnP0zSD48h3jw3j}T-=5Wf|}@r55**yE5y_Q$m+U#x1s?DerDhOAf4 zk(gK=^S~p3a5Ku4(BVGcmD-{NjfZSWzQ*_w;732wH4i^J2Fg=Xf`rc4${w?L@+L*; z@uk`OWy<*2xyoGlj-~{inyWfA#mjjcHCf# z(=jkt_dVWyEm~a^`Oi^S^ihYP#EN9Y(?$iT7$sWfNDH)#E}mYd`I;x*^{$|uy0R$h z8T#AZ$^smz`l=;5zqE|s!bTZsgqB+51$H6Jj3!`ztN4O%E7LR29n!b;q*pdSGR|rn zz~!5YE%UCt^T%5i87d}$)^n993YPTY1;aR*qrl@ZXuQP>ZY|+$<^D9r#b*8NoTv!e z208OdN!vxAai~CEAFGLm65PG*)DATVaGa2L!g`I996-bRCEsP1vL|=>cr?AuO4_T? z&s-S1^2X{h&Sf9Y%Xy!z=PXD=c?!;|e+h>8knmnr;7f-lujLlC)?cd%a@@x)kn92z~ZaBZBVhl-TOSkY{TS z;Omiar@Av>Hp`C>X<3AByCG%AP*dfshpx>(%w7#@Kl0q`q3tIlG_AQskBWjv)dG0{ z!mz~0$NZ2SI0+d@=(uPp&bkX@uBvgp5GA&4_yq2c9Esr16-Xp@GfSKKNPbYBPmf|^ z#x3A|oryoqNrP5XOcU-16XUekg2ubxgwW8RRlEFOFeWlD6(fxvy76tw)I$1qk%QX6W& zAFQNv7OK}p2PEmItUnkd7tuM~phNrLSG?1WZ6(J|xbF}6=4Uklk#p!li0s{7$=|23 zeymp_-fdzXKS`BBNEPzfuE7=5 z?ongDNe9?pM@C=43)fc>#9KQbfFhr&5I0)z+%eRXL&@yFwB^;EXZ3y-V8?kpS6k(u z=!j0D>86Y84zGIh+oQwZVCw*BiueEb9dNq_r~K0R~HT#^aw~A|~8-z>kcX z18x^2!4bW^3wqR{xL)BkgsBhVrpmTNQl<3h_C1UUWB4f!KT!b;Gzh(p)e>qQ2&IVA zFe!#V;M|&4|JoiM&qICtsAV^c8LY>a^=t!V=#(#R;DnXJ5HSK}9AU$$ptZ=|0Y2k* z-y~N1FjV_>C!GuwtXWU^IUvmg-h8p%El!o>HGsf~yc6!dH?PLe3o^&wG3O7T;SRJL zpdx4U-K~n3y)Da;iXW)(rp;v`DH{vWe>C!R!?7wMv@3=Bj#5J{!)7g(Ad&d#F@7N2} z7cL6Y_Ri{DE89fuLL#{M21Z~>!u{#;JJD(HQ@<6X90W*H`rO7IJWuCUJhtR>EdBNv zZ|~bYF`V&-CS)aqJYPp%9lX6!nASgEVgAv%Wl~+R)jq|*Em)$d%G#5s-O-$Za9apE!clP4)gO#yhYuxrbZn~ z%S6dzPyf@vlyEFd3sFC7xXh90fLbUs{mpBs4SA=4_?|SR>hSW^P%9g#ZjyO%Oi}b^CMu1pp&lVeMZ-os%^#{%A2ZRr{uy@O5+&6t_EyTTlK9f}!;nF*XgGIA6h-$Eu zELrpru3$rCaei@mqrcB`Q}cI2>m+Z71JnUrbE0-|k?3^o_}a^_%7yhd_3rS&asMq} z0Z%o>rIxRWnEKmId?IZK?>4Mi4`CDt*}m7=H%4d0CRXhlF}DSmPY2c!}XBZAN|K zAgTGTL-Y`=jc?rStdVAIlw=SD&p1{UV}vRf%#+A4INxTO&k_6VU9<^ha{*hGh=GNd5q$$^?|H)|l4)X1TtLMiQY+5F247OB zVJfXU@{s1DfD+#xgPfx`4-Uh56-LOKcYU*M6)PiNU&}}uJ~ikLx+wLezRe6&b^Rnn zRcqaY)iXKMfSf>ILA$5%JA-z3&&F(@P4r+1Pj={|Df+^3Xkr>+w#U>UEB10vSH-QI zipi+2UAQ1Cf_L#96*#I>t2zc%Wi)9Pjs<3^pC6z+yM`Jwt-}j@#1`UcAM8+8f%T77{ z@-8s7{jf_1dah;KL`hyZ`AUrK9sQJ(Ue?PSB%v>LJB+x?1|_S$3Y%gH%pDOP2CBq= zvgvFS)V48D9rLDs9vVH~*v;M{kaqdoth>ROI6}^PXDPmz+&X!1H9pMUT(l5mU!JX)aC3$e^HOE$0wM z8G&H4fQ3&ZbyW-zHg+ZbaY3#am}>v&w)1l`l*s|{rT`sqvG!4AHnsq0i-N-+rN3PN zja2Wuvp}Y_Dhm*+LF39f&hZ@tCa{bw^?$%!(W(<*Of4vCs5@8VV7S{Id596!L?{^6;x4gGVER zO&B?xyR`k_!(nk;M*Q%vdG$+Jgc||Zeon*nW&YAdMZDk9;clHJeL5%?VbG7)7>p;R za`!mvlU<<9;EVF$OP{5gD{eoS?aqO1x4Q#P^atRdN(;Kb`(ky7U1xN#7sN6hnFDZR zv)&1ONZ4VUA*sD3z-@+T41OH+3@v}GFTV4jj%kyrmC5Y1v74wCLxpb%?9qo}l(C*Y z(q^TKu!y~1I0=N_Sus|(yZdPWs>DJZxBDOmwwBpPPB>?Xy>T=4^%&w7B^_O?X&FVY z?{FXTvqWczwl1BD7x63Fx{Gd98h>+OYXuy#-TjW&>z#CuOcUK)(Y{?skTld9@KbhL z0X$iSKe$6EvnV{kJTBY${EjQuzN{+|#YSf8yEm@GSsr%13I&4^(HDpAt?2uU1?Qd< zdKyowQ2c$@kCxi(fb*R#8W+n-a5lY-;x z8HRuC$8x|eUsC)AelI;e&;{UQnC(5*9AMHo!K%ufuIv3ZFb?Y zLQC!kyH^z4khOy;Tl_ms%@6C7rpsR{g?SM%v$L^W+!9S&E*bJ*tz8L-NhjX=9poCq zppsZdLJAu@gpgVjGwSPGAxW)-4Q^XZ0fRhoK@1US)QlF`)-pSMcJwwP&mP-bgo3V` zhDkpVxS5wM($_2=(oJZ7b^fwatYUlfl0=Y1IXV|_GItDaXb4%O{bzX%>;}Gy6lDBc zljBr>!~X3wyb^Jcg^DT|Fk({@u z0O5M2tcIrhk^GM(-ogbTC;zd)$r{o4wh4|Tv^%r6#!?%9Z;!S8;i_qDi0taFfF-mc zIR@(|K=@7XUpkfmBJ`?*Eo0%)9Ot;Ds<8SOMXXH zP0gImfy60M9`?oEL58y@S&e(vHNRr2nc^74N?V7|INK^T)|x{i75rXv3M2Zxl=MbP z#!v+!9@;xT)-SVLrGzwx7aQPfEP`Sbrj>-D>@Hx*hX!k=MZJiJB!Y!OCd5~)_8Y@|$C84*w1W*HTa$ zZQ4;8=^E|O%~R4ULlZu6i~Xa1TzF-IdgGB-qfR;aBt|@9Md8#{rBdcW00sh=F(oXR zXC`nyN$56A&Q2WqXAZY`$VZogv!!gHwGjn5$LLM)o|{&j;>S?r=Q}#)k6Tr- z%#R+ZJ*0O1*Bd}kBhf%?mwZ*T!dDf151-yid|89`VZCc%=k}sj^q~3J!!|_m0DQo? z%eWbz*Lfm9#*K6Pi#yAa?2|j)GHR?8w1;4=N-hrY3uDlOEbIFX%B{xnw``)XVA?Mr zS~F`BQ>lTdWGS>Q?v~mg*kKj&4Qc|2-Ck2Sq>C7WVNQt>WqJ|eiS7n{XqdE2*vk*A z*D{w@s}-Bm#=a%@^dMyIJG_N!_+B+njqZxY?cyTD5?O5w z<&Ou)bh>+fxn{1yK3R_~+hQJ5gJB~a)(A&>6H9d}G4$i=Qn-l+&TP&Q>e14b2gGY@ zxV4Q0<1LisujQ4?Ah!kX*&Dx2gJUS3xqktTxx-(g5E&t{~i<%ce%+6wZNtT){)H=ye! zO}v|bJzzomj<=x6fOlyJ6#z#QZd?RlI)I}PfW{Ovf(>lm5~vhwHqCBR3A9l3)%o$b zD)<}G@{D_Gr_6*(h+5sxt$k&_v`7EmO$oMyslv@QXc&aQS zL%dQCRAB{;`U>8b;5#55naZ6K*RsPy`-*_8DA|Mg>s1(WyuY^Zo$**cX_h0lA^3mK zda{u@m9)%1UFP-K7QtnJ4R2OjWpP2vN50%Az`$t40Y%nn-e5PNG;z`BBKIA1?d^Rx z18}DoiA7GtH8B6cyuVO$*Qwdg#)8=K&&jajt72*Q>OT+~qtLIjb0cEq%Y~!!)SH*; z$7CpcsS_<{p|#pG?^$_K){ZvfZDk;a;V|##RUg91g8buirjrP^bsw>%f_asG%K@0s z*_lhHFLo~mSX7{G?8jv0i4r-bcct88yqyI>_5M+4FQB5e|7jRX)viWT(ZL>_KD(rFM?MmU&eH>$`B=U6fElyc(mt-@smc z@DL6v5?^*HZODG(OA5P*Inv0d2H1Xb@K$Ddao2{lV5F6=>l>ckhMC*ZVewyXxf+_J zgoct1+q@`ErCu&tq0f&^=uG?de}`O!dI}UROBI2^dm~S$K8USWAB`VoGasJ9kH!16 z54?ynZ}o}oYMC8;(+%x|@+X`RHpA5XEw3dNI0b@9_+km2N{RQ!7uO0w$*Cq*?H!QJ z0%BPM{$7J}SDekQ0)npaC~a+VWv)m{nW+-Rry8;}@y_lk8tb2+NV3gW#D2>0$Umji&G>YqL=CEhiSkYYMsZ%@3#m*Mz-q8(XrQVpjPSJ9^dkLc*h zw9HsGA?AtibH-b5XBX8^P%$S0>`QQ>KDHhbKo!53Paz>^5BLE+5|#&ULdh1gWcvNf z$)THY!hOd6Edh(azCA?aQQLcx=e5@y6(7$kXA{FIFa9JP2~?aLd`px$C;)SJPrrdj zd8L-xtPXH)$P5MHYKgK3iNHLS63RbZcnEr7(XgDrKY6EJC4e`}Rk7usQ$JC7Y_E9u z9rY)&RJW#z3F#j+Jbr9erfPfmrFIxA^i02sNjkA{7h?2fElc6&_9!(^!eL`p`+IiP z_U+ZQ$`8mQpV$*=;QNgNHIR(0k9gHw94y?OBO*3H^rAqBoPu*8%C$heB--=Pq?k}Zas(mz0t&N`-=;tAe_00uz$zq#1v z3JB=zxQEAr4$R#8HanC3nV5CisQK!ZRSXyV(SOdgP)>BsMkY>ipqy!?`9DMPA31os z7}ndPxxf2tpW&ej3N32J?fb_8HG+82>mKQHazKa!$mzr(9LPmA6FoO%|2{h{(y3wMcm+L@?g+qZ!6qjOsK>%qSu4YNU~{tBb_cND@XxLGd5 z5QIW8u+A}P3VmHC5FjUBgIUH?qC~x&wCoO41?z9Drg6PWv%H=I@5T-`#P}!Z-L&U7 z)oj*@lOtV;nW=A13Ci_gv|E0+4zrPG4VU86K!&wK{oEpC!M|hOHF@x(u z?(|Z{xO4J0*x`foePq8H_*>&babr++!l(1&>32E!Ph<@{OWb~(VL;X+;h&=6=N}AzNCrIQ`1h%;&0`gMJ zIJqVqz)~yauprglO>ud>Fb4TYbg;|_!zE>&j78Q?b3d}wc%}{3UDO9AZeD&-Lz-vU z5|kKX=#P5;%d8d=t*Vqo3$gPIh&YXE`Kv`tFb!3P4hQa7bUc$M`|2D_oeY<(O zf!ERJm@u1AQ4V2(jW40mD7AguDIb@2>{7pElTYbqr2>Bt3Sc&y6X-b2MdTb2rhCv9 zX}?Mr>Z%EuaF}`{C8Tcq3N9$)P@+cd^SI#Uyy>A)Vq&so_2@RPc5G+p>y)^HgO_A0;zW3?qto}tCIF^s`Z<6URa-j|fSkMx`!=Sy);0$T@P4*0} z6NQmivOSBSLKbCw405IB@+;?Z3rk8=v~i#GDd|~MTY`cby|`0V-ZS{FDjAm8tV6_c z?A%`Dh6};;ed`;b0HAv5pkJUPFCB{wD2L^pqM~&eV1vw>D9j_FQdP|qmd1$dU6mWb z&3gL~KerBQg0zJ^0{Jb=?6c{fH1+4LUuhbJSi>YBC5UPcOyKI85k;0!3E`QzX5W`7 zH@eU3qPDz-kmu6`FwK+gLSg=P|J1i$v_^IYeE4=c&8|J(ATOG>7dy<;t`rA1sh~>- zYwBGCL{ejyqEem?CoWoI|MwPkn=?9_I_;Tnd};;4^m$zNvAxc_Z%MeiVjdOANIMYD zCi1P`uFxuFX@r@B*G$m1wZ#!wq9X+d7nw3NO4x+rU?@&tC#C^9sksF<>j@I(bxxHl zAn`EchY2l->)k_%Hi(r=D$77PMLYmnHI7A06wCozv=>J5vnorG&xqkX-Y!ecY6u4C z=$@ZD^)SR;?!M64EB}Af2fMU(gQq0>+)YMdqBHl1wX>`UBL-y-be+L8yVIlB(PlJ zW${P8bwRga?Ys7u=n{)HqW+uvs@FPhg&<+Ru#RIgEWo^~m2uNH>3P)?w$jVAzV;0S zQDaj1o;-EKF9tcmjDSg>-QWC4KxJSQrt(GOqN)SRX}cDbQ0-_nZrk+e6m9tdA*x_s z{((_&DD6-~-(blIzn0|N;PR-(J1VjwN5O^{Sq!{CM5(aQDUkkn;hiQO_GJPilXIF) z4(I3M;+$@`v60hHyI+bpkE~NDlC8n4($b(aH*b-aoi@O64J+C2FL#?(!$sI%{2_D?oIum0$A2F$AJ>PM3%37Iw zxK;kvoBg89lDYxe-vhC~oTF5ymvq{B{Kj0_Vh*uZPZuEEZ4CWK$2w7+v__yXP2dKH zrNmv2Og%*O)oHZuH54VMmNP8202puslo_lq+%AQ_fDX%*lU|N~kXg$PQKzfd#6G!@ zKCSup32$qqoo`J}-GhqxxkS>h%;S9fF!bsyI&J%f74pR&X?F=~QZ`<$U&(yrN631V zUdhe^0^JjnjG9a)K|2BRG@+9eods1tx|0L?2p6Zqc&lv>E;(+-Xf&h)X0c4VNo;IK zwYpBu)m#6bS(ZuAE{Zh`UXaA+8@@7c3ySjtB-b0m!UpqeJaabv&Y6DGuEXHLv|#Tt zsMvujkz;ceoQMrqYmceLxf@LxYo{I@-M8}!_IEhGYf4Z-1*=i>j_#y)tb-6U@Dz|? zo>`-|wP~Pq&1hIdLI%`%=PN_MleGr(T1U`9UyoklSfzT>Etm@}mF6hmlK$Iyy*myz zt$tS(PkRTNeXTw91~t#L6kO|Tg#cf{fmcNMXI}G^#k)1SXaN32Js9uU)(jz;0w5T` z_)aTuo2}oj@$7{7_)ZO9902i88nWl|_fSDD>gq?t(||!ge6iLJTeu+v*-kXCd68np z176jh#ZYkHUmcxlUlVc8vGA+I5qTK|%h!V}`E;7;?;irzAZDJ;Ty+Jfu zgg66{GtbL6@~Ag3>-!e{&{%>BUcE#{;YqyP;lWjh6~IN zu{8pHgmI&P&h1Bmk0UIG!-KMH5N|?hr5g1v%RX{X69wv@>th-k_ub7R`j&g_U8o8z zcjsgDjIlb#DO^p&$4p~zUM(bT1!y>zwfo!uicyx76-f$C+2xabw5FIohDFaCyy(VIqud(nP&kx9?|OZOAFPS*@LAME3a$4kH6 z>kVuYDhK^q9P+@46i)7-IjF_J?bgS7>mKsjaZRRs=D2GG^i9T!d0C}tYOK0lXXwe# z$$b6g{r6Pr-f8ij?7qDDJ#co%jh9}Szf;2WLpnQevJmWxQll41owL$kYwKwhN^&LI z{+`rtG~|HetecJX9cn_2^P?~9B#&H+e>%69dR7jzD~@W~dujpptFD_^{}B=ozs$=t zV4Wli0f|0Nk3iOV2ieR+xss3HFN<+})6=~iE+d3+SRu9478o?Xx%gLso8O1ldm{be zahaq|$Z#ry0Kev{fQs;sO2XXU>+Iz2Pb-jHf5F;j6sp0vXCRFBOW#a2{yo^u>34j5 z2y9ZEuPkGh42{;b_c2X-d8Aq>LttnoVK=f1aSqJuyDH4b2mBZCXf}e~JDOS?&>h*p zL0bHjI&CdhKc1~qZ1_0Zuh^>|E``Kt@hGpjX+0JKN~W^A@=?_1b3w86OYBwNzk|bD zqvtD$bV5C6q~bzHz}K)YU%loOC?iN_t~WGQl|^{zARPv&AC=9N#T9--6xrcEr88Ie}{@7oF zWN|$Q%2{7PWJ#2oXh(Pcb2zQRd4k#8-4G}mm@`LE~BhLB8aU^ZqAoF$lyHu z`xTiqK5M7`0315(Me9dO3%j-QMUk28C|J^3{8QsvP87g|0sp@*Ck|G6k>}BW7M~!R za447FsJ-v2wIh&NqqHmrE|uOpL5=m2_L#HXz~>yK=o3E6(w&bD_a1nCoTE9p1wBm* zO;R?wvnof7juaQv&97pHxVs>4e5YTBd{qX`RJ?Ll79$|#k?ics7l!L(8v6g z2Qm4K0_X#Ox{ev#n^8V#^{Y%9i+<8>10DvfQh+D2;tqD2CY5?-U@uH);^g$2!J2$) z&aH0gvkLrxQxXJxU!7t1i0!^BZdLnqafDr4gT4`?zbNt;C2>xtz})a{&p-%M;$ z^ht*)GrQ|ub1GuzOhD;{{AgeG=;k!lALR7De7MA`C*1tDrt7d1%MQG#uPXT96 z`p%l79@A@jZCY+ud=MM$-s7AeFHtCW7U+|SMf|UK)br@TsP#9D$|-fc0q;ZUw~kzL zpY9VU4!K@?Igv-0J%;naN~?xV+~gRz*pVd2!XyOSUqz}eu*T6JSr(>!G6fEyc3f6q z%|2E_Bll^G=Iwr$a)fukM)AvUh(aeG*J4KaUr@GJ~w(V zqmw42O^MT6A;4s)RY0wOKcTVvc>(E8!_6z~Z;X+9rh+SV1z89Re5^KLZ@;%br?Mxo z*M;_BF6QksGC2JFcR45*PJ7#}Nap3L=af`G;fjhd*AqsN6gs|^od-WXJ$`9f%72%G zC2LW>Krd00)QZ@!08Bu$zt(w^Z1w5-T0)HHIPADsl=OwVIg(2VW6Tj(``nPE1u~ya ze`uUR$1il8!FG=*S-q?-*2>prrnELAZuH&ptw0AWQg>yaV3N@>WzycR5Av(1G09V zp+p6h4`WZPRH$^$W4P6XA63k9yMOMF_W++LP7SR1h1xye8c8@ze@V4)hbAYS-;Z#H zGDV#n0rq*SF|80i+gKfgjma?XR$xZFU85zVmdh6aYYb#_AK$#eB5*Uh$~K8%jIPh2 zoDe;;k^W9(=Sg%oo=xcU5>?0AXzVbac$t#{Ln?k?AmGzZQ0PEVnWkRI^FnaPVlScx zU;i*tjDtZtI4s=!csd1Wk|EJ47W!U1VFT6;#iuQh{@6~0KdX_u|MjD;@FY*RTcpbY zm$Q?xW%DK*SyH`fcU-acX4~vLVItm*qvWy!Mvl0m&~*rqRz1fJRS3Vr$f?K&aD_aH z9iLgwzJp!Py)nG@IcTwF^%+DXBIHZGDkUmgSk25jE-}{WBcxMOTKQnYmo=bN zH=NRDY4gEHAw5t_3txEQLPF1%z9uAl zd9pWeEMIJhbk(em_%!FW&c)I2it3A#d2js&`dU4dZeJCOO*9muRO6}Cx>3I_rn))P zqV6uaM_Wsxuj8OH^=wR$w;9tF0c%uTtyZ04HR>M6u=TJyWZrZ__VRi0N2qT2uxx1? z-?u1yp6_xsBR7y1KP=&0bVMMOkmRC6wEPeR83Jt}VzYhA` z^+DKm(16VLvHgZ80baTT7&Rr?hfTDIi3WDj)NX!$J$mSF!OHtGea|9Uwln+g8FRtH z*Uz2%^CJglGnosNXX|i4J9{e2*tGz0#M05Yy-9{bRj42&-kmpj78Hr`*x=tTtuX99 zgQC?QlNZyg7}$_AWd0j9bosIKQ-5&SZRo2BbL5PV+^J@MU#sW!h8trKUzQ1WW+Rgv|}B>(C?fj6U?a{s9jDfqTEU`|%+} zZEJIpX3Co?loz_&jS&!rB{_M3T1d}=iQSu2HjmW2@Ft~xQRBoWqyF7Dzb=CQuhOjkfZeW&H6w(sgudvxla@vt&}^0}D93bOVF8v-K_$W^nVl!2Oh-VlmWlal$R zX%IxwlzI%j$78qh4fDOgA27-eUnPu%UNcqYvY)!eL6c|}->(}nMvCSx?~N2^IxgAJ zOOT!(1bITb0`2EUNEv`2LY3tx15^quE!{Vf`%{zK-)*6wd_KI!s^q5)C&!$_W^=Ai zSKtw!O@mbX$s)S0S76+nOrI26fHt$kPJgn($Rc^!8OeUqh^C{#FoG&v))vy9aRA2; z0PqM+627L9Lv@XMQFY+8P;*iwwM&S|@b_o~sx8e&(dfwKf!c$s=xhudF4d2#D?L)o zTBNo>)z2Gw5}Pp{FqSZsg+e$zc~PX#DZZT{UrD^h?DC^58X7MBA_Y+oipXU`3^%5p zgD;&B=jv6dh{U{0rcLz4U#9|63NZatzE0}tJHNC1=FFZ0j+OAxn*KXgz$03&JUHzKDAv17Z(8(^A};zbFbwy#C1qlsMy#b-wn$EL|}_@K&7 zG}iB8P!KgPps9T^9^e7d(y*Pnyf>sLFx5w0X@^n2G{=*$I;Kf>rg-OlT>{gZBj%Ma z?j&Xm*h5*rV-?jH5EOk2U|0Hqzix(o0=zEXDf63`&Uhx$&3wCP>^zr2;D&*ypTKV# zJvV>QylgREPJaLlzmdE2NR1YL#M52}`_2uQs;7h@fKaUN%{1FcF3@Rp6)A0JG!>0a zQt(#gbt5|ZF%lP9qgrrpV&X?p-{_F(BxKCy9j*kPj#?F1blGEHtBw3n{6Y>DdMq*U zH1U{Fb~iDgh^qnik*EUf%S>UtClWLkUT|FzGHB zxbZ`|3T2EE8aNQVNq>6o-}DX}s5o+a$|H1C3a~Ey`)HY>`GCSH#+@Yc2uZex@TIo_ z`CCt zGjThLeu+*b7NmYJ?nm%bC%;?|!29u%AZO0jAsK9HMtv>dU?9 z-uNZ2fut)huLeog+3}Vae&o=(D$kyVFZv$ z;O)@yGqV9n^7qDK|AXA`Jb%IpU1#+N;2Q;VDdUv)L}jy6_58LTx_CCHg5WI7Z60j= z4&~xm*T(wXyb{x*e@!+ngypw}YyOJjWeo8l$5*Q1FK=-w`BW^uzz<1>pGdSau_SR^ zQlUhV$MoCW3HP+3D_|UDky<5l$D2cT$C8O^x!yAJ~ z`5=hPSLWnvV7u+t;C*hZYcK9{Smj3_%16glSEy4Hrp01@Q%@<1Q1GE^Xb;fMrP<;O zzPNAD)3oe)WV9$_6@`J$8C%zYO@}Qdq#?r5`q_Z}=|?4`j|EljBF?})NtZUOUMg)A zCC}#KjLvWNWC!nAUt0ZuJa~z+4!uQB2fLNO;7FYO&bk?}q@+V1%ma^l`?Tb6wcOwRn&yp&e8+%AID%(FSYQ1o9kEuN_h%Fpspq*)TD zW2M$^?ca`S_Ooeu%k1~Z0m&m1M{E_A50gVkMa?Q|g4CXjWjp2O z9Be%xj#u2&A_H6v+)Flon|$TMbVMX=&eJ`iF}eEFu@ib8{wALlPTZWXK16$&L^9FP|2{MDQkB?&ZTGPsdNY|*8FY>G zqA`5&GdazjVuN7Z@u{f>S$-)3sMaDJnTUf{na ze8JcD@!o1p17{OS)rI+Z05}zpwS$BpE?TD!mtad>$1HWCY>KweA+-AJ%Gp~WRt=98PEK$Qz%3d>I) zeQ_R$9{-2Tw~gy&uq-`dSPO-hZg&2Cq_$=9-`P2V6$yjrU)UB$>l?)(nGFOaY~K~I z8n5@Q@amV}SPoGFbH+L67r_R2b&Q_RzAn;R2sN6M#I%S(a(_#$zg`I2Rm;6>=rXq z0x2KOn#uV*+*2@uzedLQ{!oJxqr8FH37@feu|G2B}1I@VA0BFIjKC(o&#m?F%a+}d5D3#xZarCcaYFXhmz1~sP zMAaH}g@))YUj$v;!^J)x(xYseE>iKqCg=OA1cV;SzQ!S;2E8#S)A|iwCNx!Ce>^Wy zR*58#!PuNSf!fJWK073SKA-Z#cl^(@LTtmAt%;{aY+V6*&JW9p$J+;}e3?ZT%T8Ow z#pGm<)G9FMSy*&wN)OHlc3HX3mC#eUcO&5q(P$4*@AH?!+1tT@jex|#M?S_c^@HO{ zfLc^-2)*EbwvV4&lNA)T^B3_)tS3PQygSbl{is z=Fk|V<0Kh_kn5e`p7m{9Rl&sah8WUr^5cG4C#}wadd>==qBniSZ}2N5ithx(BO##a zFyS&z8wTqe2S%3pQKa{AI1sU6iVvJHwoXiYx8zkngMK%$r*!-i38)i)PBia@a^fO_ zYxa5q;VV*1aoV_IM`voh0jqL>H~&7kkRw`32Ys_)qBO#eQu1U(@<2$aV^YoLS9cKlPr?x zfrN`s1}xMjq+i;>&0;miEl)}f7FCt8FyBHk_0{%oq_Y`5ed&x)ss;WDsPeI`PO}}% zsC>#68jZGcgYqlr7ix#NnmBz~n$hP|Zf&&BC$QjrdKFt40>J1eP|gqii;pk(m@=oG z$sSi)-k^9J3g#)5XH*z$Lh?2x$mGF7`7m}3Y%%QP?&lp@*tEFaXp^N`1wSMy&ceNc zpCOvEN$I+@5YL&F}HXKFcix#HS?zcv<=v~U1joh@z(SF z4uE7|ROY!-gA$;Ki23u;i)D21omn6_3xW>@G6L0{jUYPdl(vY13H9&o;BP7BSNqm@ z^7Y>YCX!goQW%$;?>n1TbX(VQdWop}DgTjl-r9~TQ4swg0=x?a2=Bef@ZNjA{&DAJ z6U@>@-RD&8LT$F3>e2(EWZW$;Tps2&!JTZ}KBhFJ#GF)xHM z;JT*Wk?{L)OdqYWju{(^%6ixwqjTu~xH!LKYJSc0w%D4SZ{Wel=B-zG2Yld)v0nsR z@Geqxz6fCo)qtv?vlV>$^!D7AaV?vnLa&^E%xURnQ$xiUn5g+je76xG4^*sAs(B`6 z`HS?AshxSjL?&MpZitnt_#yfQ^M%Lmb#=E8fQ#QSF}?jgH{n@|)B)5bYfPxMSOxSA zPW+P$Ry_HpplcbX$YxTXuk(V$bq8q%e_?o>S007(NX)~x*%y8}P+dAog5>q&_rc|U zb>&%l@frOX!Z*F2Gnyr}{5z8Zxl9H2CFGIwIJ6d=mGN0Xr6Jnp3C}?)+u^-?J(z5@ z=O|mCH&V{l-LPxTJ%Ql|RuT=5f`%RCLujLa>omJp@cMRLsz`?s_N7zXei~D+lnQzYh@!(AyhS0l%!$qL6i;eK$3b1ZH~$rfqv`AtB7lyUaOE8gZc`DdW=OKwZ!{gaX(y#}h7=5J!Xn)>vo^o!PUBktzS^9gk1(w&i7f=}-39Z}McN#htr zU8m?T+rg*%Vk8obvyXv0a+`7WaiWuYNJs-yuzpf5O!&K6iVZI&kGD1c@S-TT0YaVFuQ#S3D``?Se)! z3Jr*?Euu9;br&LienFix_=4l&r=WaFN8J_WrH>a-DIo1wBm$ zrdm(eFn_Jd4r2N2SQ|$qRBcjyt!(f z!{S|vh~i*$jzc6j{tW)z(86IXG4DRLkbs}X1JbKN_oMBiL(|2*X;9F73*(3P9LyB8 zxtpZSgOqhp4>(No&oYl3ZvQToE-G|ZOdDM*Gq-{y>fr~x)X#Sx3Zr$qCsBI(LvgjY zm^~(@BfbI5Z%@kgP6%c4?C#ZAH@$i#b1ql-jjh3CwN_S*tyg=>`hm25{Wx}pV=Wtx z8g^>m11;)&pwV|#2PU#wI8-|FDQVxl#6=V2MHmsDQ`oxwaag92lA^8RpT)-5Be`QN z7y1>R4S>dB78F0rNDHKrzlGop-%$&PHsz;8M83lgs4w^afY!5BF**R8vyj|ZhuAqc z9ec{Z{qV&>Kc+CcN3epUGIB|+YS7ZO+C9*_Oq0=B1IeLv+uqOl+V2!R;W&n;)Zta~ z#ZW>}nr`8IhJkrOxJHt7nD*ppGtI#_CIhg?#<)}niC1x1%DC5JeGpCM1NsUN zoVt%bK&TxluSdiBopUuoZfoD$x(4OxW9j?w^hT6HoocS^{p=4!xf-8HXLMpDelsZV z17qGDcO-7wYZP*z=00vHXYuCnJdH!*JM}O$!eh-`*2B;g3MH!(*x&N*gt+TaMk8uD zg`xM;2do_%VZHTVT5ymlKVMIViI0bq{gBz0ha(Dcd>$JoR@0_tNG)s@a1BVjKVK7K z;|iVfcI=ojwm}&JmEYFV8iDv>Z~p)-b9^#n!}SIPD5QEUF&%fr&u)34*??dpmsc*G z;6!it;6;TpZE_~J9>blz zJ;i(wAXl7>6qu6~l<3>?6Up(*r}YiKg&!L-I^7Zdmwpl3Y+W24937#wOi3#s z(-G*MGcPUvegZi^rZ))lqH-GI(EwfAZ~u#$@HXG`zWtG3SY64P{~%395*rMIa&STi9;uH zRVFXo?vS0g=a7Aufqk=+{6!(7akntwaqAw-A*>sAFhC`6-_H-i8}2Wk1=->aF^q$c zHJ+BYl)mNUrC~#kdv*Dji(M%h#l7ASB=u9=u;8UvKSXV(^+bP^AwN^hIAPH`Y@p2P zaPT-NQL3PpL|)Z()#5bQNa4F)q-$<>T<6;?V?CKpV}O%3;apmu`z(W`hrD|qL27}U z5SPfXIQZ4m1fcORY+y9!W6vQtgk)#>GT2j>Ma<#0T;r&i>BR*nx_myES3E*6e#LA2 zvb)`_Pzy$#)T;#11B%xp@r*krv_55%o=nC@y>u(8DfblktsvS;|F3gNH}g)-lD8s8 zR&ESWOQ+I z;{Drz=7IZ1XO^$VFGGIq%Gi`FXw>Ry^mlhfsGt#;7?yl*s&<3@3KkD|;KzDDLVs9m zZ_|hXU_Y4!C+fxm9&g*F(@VPe<2V}tM@+TJgi<@7pvxpder``D{JNW( zJJ)99uVJhDGW4O{mni<0;r{m4fo)Md-(WPVC7$cWaVFbH5#t%!CrBe;Z{-w$=php+ zT-7gmarhsK?mnrK^w#p}qBONziQdoTJ38>%o`;=fhIfjg*a}g1#U;BPX!NWvSk;BG zXb2#iBKgz3ORvMcIigQmV*5-X%z%laI2mf47Y+Ow3Jq69SSj@B>DhhmVkYM#7s z%O_@M5|I$yc}gXaY-!{j+#w+VLg2AW*T3dWbaTq?ZmhZA77<+`-rsQi^GClkvU+sE za10HR#Ux373prb?trlh};07-?X4-gOKBgh))5@EQ3nd4Qd7p(=NFx30zd6|Wxnz#_ zC*{AeC^W)m?dD~c;NdUdKyOd7Q#1_Jp(lYO_?w)~O7nW!H|@?$jV|OnPz}nx-cR~Q znSQ&OXhoR>o~%Nsd&$%&%p74O(_Wk}`T(yvF)Z|HzIT!^l#jDjh|iqmPb4PSTxLzy zqTsj{>eY-o6ze;u@3{8jvhJz5I-%$CB3H}iA^{Wl{&{J72x(Cq=Ez((bp)U_FEkP? zu5o4ZG=3J093)X2qm=frpSBjc36U`u4TCL`J12wH3xKb^wh;+M`bjE)LVgaJAYzVz zAv`oUMeWi2P}&x72Om|*d5}8|76LtQA6QDJp1@rZ-8xUtVQNG z5|xtRp%cp?#v-Cj$fQN8<*3mY<$tWm^VSGVhVo+Irb2K@ANAM+u%#Ht8lj6@>}rnT zk9M}17qD*?)HNKs3L+o|oGl959jVp;8S)t7$+DwrzX*x2CUjOiaOX z+GZ@?|q2vKs| zOeeMO^3Dpt>7O+3P_=BdJAQs3YI(B{n_)NWZx6QXx|#vw+|XcVmTu-JFrBZZ| zTwniWOps7Kb>?6?h}XKzqf_KU;sJB z-^N~|eaA5O69&-l2zWD10VZ2y*YW~K-e#b5pDusWR1=z}{y6i>U>?~D$J*Uk@Kx_F z&eJNn+pBJcJDcTZwNqV4)OAko%|^#m{A##gh9Q#Mn(9G>DSzY%;JM6@#(spOOGvw+ z!Qu44ASFXP|BOwb(l*D zSq^grdG`9wOwc^2)9*;AQ_AfsuL;)rSJD9(?ZAP(+j~-U`DN)6pPHe}KR+}Zb+e|K z9OeeN);M!m!hP=xOUH!ERmm$N9oNLg)>FJRg*YQ(KiRjOT^KlHuG;Kh}fm z;D~HGvb((?d7|mFX`PXosenrlJ>=&d>|w#C*P?!6erb97jwc+3vtt9qSZB;mHQo*6 zwEAoIM#_!G`%$i~V4z%4_cY_*E~L15tMW7tU<8G^fQhFrWu!NO7G-}tuD9+XgBhQ& zM4skIN*u-H@ZWoDW>ukAf|6j~oezY4IrdZSgZ|+Xe)Oe(z3KhZF4dbJ6K9!M_=$RoZVC zxdnz$@xYWKr+vlMnV{~W_;J`Vwa0{PxL8pB<{;}I{25flQ1AOgqFQwoKyl=h(Gk`N zqcnN0-Sp7i^YjrCMDd%%Pse3BCI+m!u7rav!kNTI+vh*mujSr{i?mrTPwA6bH8#qw zRDY!QYklPp&reAf=!=jhcNt7tq=S2E;>N@ zz$=P`P{ECBCK$=687fa(MVJcE^LwSlI-=H&sWeA_9?mG?>{;Yv}$6jM6Q#E)2}o80PM zZiB+9Yb%r$rFKO5>y`7s+KaKU409quijH-MH|25dUp$X2w+1P+>CS}EG_=HeAjo^# zlRw#XPu=d%U)3uys^sIaW~Dx>=!aePaM#-o_<1jc%%`_?Q!y6&o?Z2~{TAza@1n$2 zjlI-d0VG4aC00(_+%rDOr_H&R1E#zX{fo?|AMFRmjfb3I?LX@H*#x)d)M`UBa*oFA zWDAhs-|`uv)N+gIa}~%v1xza+Y8o};8wtbG+_UlmskUyXD_!8@!tr>k z7q}y?_ucsm9<-thSr!~p9odFUY5JjO7#x2$lo|Zd^%*J6)$GwJTF7RdgJa-YD?E)M z4<*G%!@@5L9~+hf$wKZ^?w8D6{_U6Lqog7krT?B=Wi+Vi+w-3lAm^?mDk{(x^Q`6T z%{loMe&?M-oJYpCb;ap$BF-9x6n>{BGp9_DRFchV1JQ#q+* zz()CUKO?SS+Tp@4LiUI?si^Sj#Wy{WAA#l%E!o9@8+;J`Mo5?$B z6!9M+6*@AU%8z6?(1xY9EcFSd4f_eHxL`kH|HBboZwMVb6K~U%V98->hiP>!P5qR_ z2DdyY+R)0LoeRU@>6eL02eKXzrUc9*^XzjA9?Hw#xjN=!cvY_zg0_h+N^TLG;J=ao z4H(w=RqS>n;$R7GAfjRmBuDl&u4kZ!LhN(~dn54hCBRki{(DG*ZecQLktzO3P>Fzq zxjopm(OV?w`yN`V-}Xjfqvu~8ac-DS-ZG&pI^9w zl2nde&|n_;{_44G&?WQK2{9X@BT7Yhn9q;-l?~2RZ-oP92B4cAovsK8YI2{h86tGx zh7wYh)Lqh{?AyuNQt>uh`5|WqToHkUIx714OfksCL_EI3AAN0)O@^}F<7kO3elswOO>}haT=fgN4$W zBs6#S06zo@R%n7P`GA!I=iDDPJ4;Rk{T8#BwPYGuMA>IDT_W~qovpV>Na4i)x!2a? zZVQLi=;P?l4Y(@e*z|!wx`viSqQJtmoUDdU_{4-aRij1C!j>Q4q6XIklkQUBzP`=n zZ|oGQ+61}N_GGcMJZ_|_O=;ojTfqlpuS6m8sj*P?I<-0Nfk9NeY?V-ntP}u3W4g&v zLKhG4NKBLd17sO@-w&5j5jkLLB`^q=DqaHp=(5Q3$SW9jql!T}nN$*yv;I7_PNDUA%JLQ{aaazKUkH6K4WkQ@VePA;vNOUI4$5^~)^vBu0ELfMhQE`u9VMCi1+`e|O>%__iuXXD9Q24o`BTr>fgLON!%rFjB zbZ++yJv;+;!S&fwQ0AAEws8$Yv1IK5?`pqGobR-^sK4LAwG+V6Op zlq`sieal*o0L4>Wi)=9EyHUdcs59l0;s}RevJ2_Q44}36d=NqBj^QGs)}JF@kdc)j z+6mqSYLIGfq?c;Zv;kh?O`s#(J4joo;H9S=lMeWg>hn7Doz^`XYQAQ?9!eqJx8w~n zcxgB%X1WVew`En$^JYrQa~rzjKDc2zVwGvZXK{|o#+*!+mT<8+OV?q!_cv{| z2mNH&sKLZJ`?#gJ3=81N^A_zpSx?U{&l1H}?P18hSYNwT&~COdhE;Q!f(%x#>602{ zLM}!wi=|(~S1rPhpPr=1O<+Qy@)@|&+R54^SOzsJO<~2$)s_et1tpS(Z!Mvx;2$ls zt7|06=DB}+nSRJs%--BI^rz`?zysoUgaH#1f)v@|znZ$O%bP~zV;e(oeev%8i9z=P zQ2aU2(`zhn8c_Aow-R85#i=J;yxH_w9na@mbF(l+C8lU z?puGChiYTXoL`kkY~>zJ(wYpZhw;c#Q`wD%*(q5_sWbD}MW@)Ggy32MB8j(JZefD4 z2@xGZz1%SL14qF)462UY=K6#z?HjcJB(RRG!~L@91qM86lDZP(H4oQ)H!sP)Q{31f z_DRoL=I@aH!<8VpVI1(6Y9tITIhQqCdIb7iDgF)ZQPsoM%_VUK?{=T&YKIoEp z-k*i7(43fVKXwD&o+zOmwE%Sscal`bTl_)S>yMKAngtmJe_S{O_8Y8*L{#mc;YAN5 zkw5}X&oKrW&-4>;00uz$zrRa~=bf%5=dc>IY;v6Fu9-`9#phsqir4Td@9sNt9D#W; z3 z@#fsN{*=Qti$GTLa^uH5`dl<|o!GcWR4v{EeS>RyUM#ASwG%}qrto(#V4lv$HSM4m z#%~}mN{zxrZ>}Rk9BNLI8gQ;(Y(v?%^SOT6txs5t_2=%2TRmg0;QmUsV3&9VG!fHo})FG`P!{3~Y?Njtq z1bFIsXvg52(PMmHh4$qeO^XgCn;rUyw{uVZxQLXqNt-F@mWOE&x@v0ACDZ*APwaXl zp_+=GpdUUxPANRXayRbI#2_Z$qL>zPNoN+Ho$+t;;bIMDA%yg3wU| zfMf1qhMAA3tusg9Ds)br8zrnb;)U~vS|Ch3g4r~?sQ=1xokQ(diytjtLW-h?=GKHR7tXI^c3tdL{g0>~fkg;in@b4orUtG8`#g zPt=nk_)~(lBePSVryF(gov8zthJ*K8?Di`GXu`Z=*EdE@6IfB&+o*qh9ZAX1t}+>t zLy!0HxNB4zIkXV$DbIVL$yRA~`ddAf$t{$nytprB`$6`E)tZqnH*=R2q9I~6K0eI-%z@7KdabPnL2(;>umX!?s{-5F*9^rIp|h4cv^RST_*3?MKyq1q#J zMRP~xLin^+q1#JiwnM!RX&U0)IuTJJ2$I?R2A7+TM#kgcsWQx#UtSP;X9?-O8P`u4 zZ}!3c9ZYj8x{PY^p{B>p^$%!jy6$!DMHZ0m+ktROY zV^gp{KLVOj*+G+XSZtilh^38VcTNdmHFSvOKh+C*(~WkM-%yf3T)%|l?1^~Ztmw)X zV%tQsipzl9wPB1^@Ww*QNeSrrCZJC3$KN9KA9k6VIBa_cFj|>2X5>|%N(bS$$l5@B zJU@C4+e|$Nu*w9PBLtG4mwraOcx7eJa~qA^+;ciq`%!eH1+U)M!i=lc=q+l~ZP> zci8!h=x@V>nCV2zP^PYcas3U44`pj8^bNd@=&#}H0-j7v4b~I_S0NwBWZ7kt=5+HR zX;pHL$&?AhDals0&-;GCwi-6}Qk~SMBR{Hl8A0g0~QeJ6ii(y^)y+cbc+_XNyeR_uqzUO3>cR>q%Yt>Kh)r0D^-CSgp0*E&x~T92 zSZIqt?&vb*V&0^HZT#m|=rVRd;`?z|)8Od@0YS@mkF*JLVIxfGye_z4ykoT5YxSD} zXPe7ROG!Ctq87U=cQ+Nt)Vv{cs4$#1opMz1aift6KoN$J=ut3*!UTr0z zeNwXO$-s$z{L{*Pz=qG+_j$d!rg?9)JdyY0t&21XL}I*3QR)G|E(z$zY<%l9)KtOD zewlnzt@=_B$Y+D&RF7=Ud(xYJ%@i13)$|v~Jq)ZyI61&}7i}`EZ=OhEfUc{oZ0v?kVSX(iw~{P-xnLvY`E~Me=Y&Yp;z9zgy?rVq01~jbD^*jEuX1q`V#UASAj6$o68<4x--&ppEh&Ps+8Q>$|iMk zsX%>H;qVYHp2s0nCr=6jIqZCHRI8Wg&s`R1LN#?8md04j-SqE%Tgvf6CxY|ekoZk# z6Hgo?$;ABx>3)gpFAEsc(PGUI5OfRD32g!w0+YLY|H!RFB&Ng@Q3^!E@D8MsUL(tv zK}35gb@t|ih;Z!kbbjTqguvG3LKkby^f3utknuHT6-^RGkL~G(4@wxw==Z_!=P^UF zv}GTAOCeis;2k|Wbq`>NTfnr|p+m@TR1OQQS4SKcbr)ea8I*s|-4i52wg&3d*`>zT zPu{9%HGkLo9TKtb(Aj~WVXV0-RQ33k58kI{;EU%2i%+TW#nhLp9?H9TtDe)w#8aCT z6_6?dy2hBld%{QxmY;1#i;A#P$lNTPmVbal;WVCrM}H!0QGr;FIua__43$|=UNw#! zLy3DR{Whj^GskcXwcR&Ii}9;6uw%jIri*dG94vz?&e`vxzTNg`<=x)*i_iB1Ci;m} z?yu<0dK&O!Tv~y){ zw8;|>bZ_AXYd^aIpK;&Rw@uQ}5gQF{HTm&{*S$inv%m~mbmjUMWlSH{9`!ER+yk=# zJZ46}YoeES%`eh;FE0^JjR!l^?5#H8mbL?y_$GU-M-x+J-1C${MAp0w>5^FN!RXh_ z0fTE+q_g69xw7Dk1A^EFRyZ364fS-{SJ4Q;e6tCXe-yETL`L)?Ik8oyYW$4tIAXtXNPMJ#lN#SZ#VV_41V5$ zZ{EfRJlAwnhjyY|yfI_jr(gkhjA)N%jy|cGj)-Rg^H-jx)O+$2bbJQDo-X(ZZ7l5j zw6l9EA59w_Qx)>$%w!)I_&W(+O~Zb|>z{O{^7aGbLSEpH#9eX6C2B;u>~ zRbQBFilsk8kr?sE=;BZ}lP!-Xy`zHI9gHJ1KYLGZX++%V$<;I~s}q-)nFonU-Q(+9 zgFvaMe(?%u7cftE_}aG}I+INJyPMNc#@$=v^e}XF`WA-EUSg?-CeQp9e2Ft9`4#7T zz^EQroZ)6sSP$!WKvse$A}Y;YV{=vlt5J}9j=;&qdRuroHmJ(=pU_{AP&ZzZql*a| zbg`~RiiT+}oZ~lO00Mh)(C+A9WJ4fY7%}t$JKYfcsmp_ zi+h8P%SB*hSFV%t^3L_&yWkIf%7!(i(9Z2JLF)Pm=O48KQ+i$yGdQzE5T@_*xco6- zT_ti|8&_TXKr{|hj+v$)KWIFmR+IH+mmnv5gE;D@Gdb_?=cC{i+wo0t~CR>g;rfHl-VAbd^pwO_}W7_ z2{_5uLE;xKk!9gP_>C$~AQ)WR9uoYG8{=;;IP1#&u6>DUcIlbyH6I;}ii#e|3~70W zF2TE^AJ!$`5$S$d?|y4_dWbRYNe7$zJgObhcsy_#2`0${4HKQg6b+guw`p@l%-V?J z@)#d%%GONvZ|6j=X+P z#MGn^w1n0s$0&Y$zhCQ&@8CI{$uGJ^^IiI?qxQ{s`VZfb$xcK2GStrdVfcrdOxiQK z0SwKh0`-X8vnlA$?8sE*E0lSZb&yh=H z>W7K~p~-8YL!yG)lv=iiG`nByYP=(OB|x)bO73)4VG5#+l(HWAn#a>|1AM}>wGYN% zePEVyN)HjwhaUDOJ07b_C*3bhFR!>zNIeqk2)b-z+KH7qEBDIoOycFu1Vd z`iRJ6(@^vQ6eM8j=PIeFTF1GF-EqOjNg+QhVghA&g;ybNEri~_%4wqHLNwWBa)l8M z>aa7i#I#_SR(vRzJ@20ewT=4QTr^)ldF-C|Hvuk)VRs8TC$!7=OCk0+qHu4aX6x({ zpt+HCJ0mkBKom6ZQ8A)NPZiBg$31;(Mk<_gU?jrmre(zk-yW61c|y9fc0yU+DV`*f zFu~ZJF6vnW^*7A}(lePj`RB*;)$Jrc!j?e|&Mwu$2UJ~s4?ESBoDw^eYQKl56?MyM&uq#de%Dz^y(zapZ)VnF=EWILEcM9}ry@S; zai;Hygi&At;wo(^sH{@DNFbc>-=-V&mxMiVcJI_F=bcI=JMNBRE2BWAQ_!Wy9ylb= zh;hzFAyJRdxFLmE?vZ!{Cx5wGf?yyyOz7;D)I3QEBZe1QDvar{=Pu#2%2y_g38Ai222F=6A;hKu{c_K*x%$=l@{MX zvvS-u7?2tZQ-`G=_C9(xL@qXL>ZSl;;5a`%yu)O9Gv8A^CWJ{LK%jT&C&+Gv{!+81 z8)s4spR0h-$(K4$hLaz)w~GG|{?@X*LI~x>`54M9^x*9rv*ay=G(=EUG46yzdRP-} ziX?9|t;v0FBl9f);p%v+N0;;wzok&mVA=?7>ZoVSEo?JPFOQ=7l9(xf3dCbiU;0Xc zC5&vVv@S}Xl+vX7HqjL?1H zZ%^x!-E7$m0WK20DVn-Zija&2(R;_h)arGtx-S7fy_w1^&9ZaHS~Ul?as_+y!Z^`4 zbrJ@M^hP1eaR&jNoMS*C`0eQZ4o$OTO**vK4$o<#!N>8cObA%!#BrRD|%nExyU>eoHi1@}e z0ZK8o&E45$^c=8}=Kow{gvp^!iH=NlxIouVr6=g4E6XrIAT>~v>IS+e&j?BPU6ki)i<)=CE8a7pw~SNE}Gd8>w7r8iD{W$2958$0|7ED(iGTaDyj9uwI2?i85R5B z$Gm$}9gw|je%*Wd0D=%~pDzlz)Ub8+bW;3ANR$eIMvoQTrpGVy(PmyUS=7a2V$<8< z7e`A{8~sD{BGVvBNL|w)Xl|$*TNaC%{#LhD%H;&wVkcy@Q(gNYStle)_32gzBz3bb zHJvdr9_uCmgz=Xz%DzlD&rDNcSw9aiA2Z6xm{Bq_;LKtd2ZK^N{2d-0YiQl1lyr(A zpSND9Z%9?7P&MlU!jBYMNw`M^=sgO10K^Lw8xkzjz9i7IcFh)g#rIOsne!2`)Ot>D zFJjirum2GPoIhbdIM|AbZ^>Wwc;GlL=TQT$Df@U1_X*J$6uNO$)j{G-g& zS{s6Uf0m>NhWSsP9Mi1oSlNC=%|ngv1?#s*MJ4W7o@mY#G(H8GcPz;?H@Ge{Y7k#{ zkAF8w(27@_-3^Do&zqnA?jaCSV*{pW_ck8Go7gwd~Q)fC7{h5&ERFzG*Vr%LyRf7Y2Xq|8a0%2)>viy!m*hCYuh!{McR6_6;FOM9=o<|Rj9Ptu9+ z^WWTzMN(c6;7@wF)KUNuvO;)p6g1)mv&?Qh-zVq7#8ZbttRNaE%^@B3@flf3sTn+} zYCOY#xI^{D4NYZG{e<4?t(!@n91_R%<*mF{z150i73g#E^gaMP8u75|*rA55Xn#>= zZPBqzisoaR$!)QOKYHF0ziv18^v5Ft=->N>JuTVO)?r>PXZ!|*r631H1?xo&Qxkk8 zzKnlJP!*zWd;%cu-ymUCUnRviF)zu|H9@fmupS0rw~no;h z-Qneo*{};96)~n4UO2}o4R4dyw48K=s$kEwux!qtsI3gp5yRQx${VI<(t}GTEqjN# zEWAqb((6^9N%*AX;8bIS{#eA-Mxa)y-`ZEmvd+G$w0TcB51DYrujA1Y)U4@(6QZ&Z z{clio*|$h^7|rXtV&uqc*V22{EZ2K`;1$B7qXrgRSq`~Ra`_2nTOiy011`kEvbzUE zqgwz68C?e#c1fSdINeFg4JzNO*eVEpC4?g7$NK4($!P^0X-l{U~20x8mxUgRk zKA|ccXa~@D81g8Oadhn`=?$2nt`gPG*b|#R#kVK}8xq7!I-TyDK8PZJIvCgzP zlL4^2Oeo1z26cLxghI2&jkM9@EznNRm;mbUZ zqL1*TF08UcX%CALw4`jFYCNN{;LuYrh{om3N);2vFwQYFB1_#p(OXdv83BCXx+S|o zA2*i>mNXR*I-nu0Vf^oefXtl(1(ej zYp3+-K^!@n&sAGk$h-=egMd=S_alsCC>X4_Cu*P}U1nTCp!Yjpq>OgqVU7!0d?Z@8 z-Bb1}ox%t~Ul{q_%kC$%+$!`ZwaoK3^O|w%Fr+!`mT?ar%lWvH?lIGdSPxbY251fP zI_En%hdi&m-bz1%8&WxEN+07FdV^BUZb=xpNaNEwmh#0Z*`oKnF|#i$SUon(Ie=5K zn8tI)Q3v|^d2G|A3~!7|0ZjUL9w#&iaRmVqsvGyrF&PjlQx-$K)}Wo)?t93QKJc<= zTwJeoy0h7Ya2ilaZ8B_MHGYAN(fu@j#5mVl%2@Qboeha)Zjy6PYxu&iw0^teTSEV} zj0|^1uARIr&99mxfx*PS-XZG6q`?TEmj~K^4F0Q`#))NU|KijWWe=W7K)HzaNnI?yVCd)y2sf#@d3I-Y23Y7)W0_3qWskfLd8L4>bWm>ZOLxOBPA+Q zRchTxP1ddpEzoy~GllDnHuKrEC`L@aAD1pO}4p%4+;mW<2cXU{GM#j_dwesIX2qrG?&Jo!s;V(K|3ZnP9$?F6Gvt zG$)yoPK`!BbOJbkuN~^?u=MC2@TmSL&fSXTiiRqwm~)Df8*rL+GQErr{Oc>N$;U-y$L3M}&_e zh*H;seY4|H-|2q?N8sIG2EAV=(K6LlAUVwQ*Jt?T!&b(K6Ae|D^w6zFNKR#?6A zZuA8HzGaPXzI>jcY(C_1LQ1MY%6?xqwWHXag3s`ibnvOTVA%(0JW~`yU5}(<=^-gA z7YS<^VQgGG3rN}BR*mGl%aHp8+0M{R<@ibcX_ct3abXLUHO`Ztul6{H@8rbnfG_ zr|5O@Wv6=+F}D+KoX?x3&B43yQ_4WKZFL+dJLLy6!pPCijUCe;6n~SlPJ_reSXn9M zp1RxH!7scuap3YMVD)ATm}0^#zLyoku3aLjXcl8ij4S^}SY_Ap;4vsaK3|PB4Zl+Q z43J*U{7x8gJ^T3gPo!ejJ%bH&6=Vt>jiZO3JjvyGADGyfpdVHHg&8EB&b$eI=)^R- z|NWn3!~&~5(Yl)i)$z@udWn^67HnR1X}WZ-A>7ZU<8PFr5Wod}Z2rL+bWTD^Hv-8J zQa}BWLIm~2M=$K9glhA{)l)m%%;BgxtOD~61Z^kotcZLXte_6F!kvV3w$vsWMI26!3-x|K;<~U1b1&#bbytIewGndqgqZrf9y}((8%FZ7llXv%+Zz;gNht<#wa?i z_`Wh|qrgz*YOf#6h2Tma4~eG#@)yT(;+bnFLP&y0U+M+IUhIm}N%sNdt0$N zg(Ld;+xf&+-{;LC)c@YO6F+i#GkWK|PbFPcv3jJNW4dzeSL>$i1qs$hKcMi7rC?x< zo?MT9i1ef9AwUp8cO70+)G{YD0O9WiCi2ULhlJ+-OKv6Gl4~DMW`Yk8)Z3BO3G{q; z54;bCs zaYQ=0gDI>?3ST(^FQzU%?8_*|2$ONh-DO=--<%edC3c4h_qy_w*7_4=hVum0bx_=J z2(NBcXBnM6x1RZc&=v@BHp9rw%OSkreH6c#g#?%y88bD|lSW8(o+T$@LYsT{UdetB zJ)nyLgYqHyA`yv=Br}QGl?78+fH@nQe~(8I-0j7(srJufZY^9@5vXqt`&2lN=$Evc zI0-gcWq5?Ynl5P`T3rjV@r6ik+7K^Rq=sfsHUq3Zd7XXJy)9K16pCz~0~x`OxP5UJ z@b4p+>n_Pvq4ol22kMj^pyoWne-&x_IOWINTzoHp`nr*ohc0?cO40R%G5k4-U3>Tx zkqO`AzLmt=V9cwu;OomETEN%Y0Eyt)MI?!&t+hj%Ev=s%9k1AE(?bDOq<84Ex&6Oi zR!Sn8^b{YT&gTaVWglot?PIpFH=h-4aAq80RQa0K{7a!hiO)HkPp{(D%zPc(mlMSp zVN)*WXG_>Drhnw1jo;NAY@R&jSvxfv%wUOPVIi{mn%$~CpG2aD@6#Qodq}-H2NrT_ z(OszBE!mWzBwES?)gQb)Q{Bb zJkNfQ5@sU}d6>o@yE12l`33LrCNfR1j1Qd`-XkZAP0mpCHS3eQ_WAS6L$ZpCa{%{AD@v7TTyXEd?PGL@$$HD=kE{~?$d7^S;rqds-RY=PAQtG z_WGd)F3{}@VvzBdouGQ5_6^(Xbm$v)sC}4prff&9e+l8C1j*jfn5*Cxw5p}U3ht9i z2iFJ9NY-ODz*)%Ca-L-R#gRnpKNv$>k=N!{ykD!`q#sRUIS(_3E3a8k!92pHiGFZD zcIsUBL{IZOV)327fICbyRi;?e{>l%!mPq(Clfi#j2DE?ijHUItZo73Q%ScSm?#2)7 zV}{%o$@uYHSrNT-FyHAUi7^$Grm?%x2N-tE;Cn}h7{)wRGlN-0KiVdS9q$4ndV$?b z3#!72>~obMq?6A!Ib3sM{nwn(lc%T1b`>v z6S6)s24DnBg1ues`k5W4h1p=uC}NRAQkKi&xec$2;<61XGtN9PAd~3E1HII0*^!KXwv;jtT@Mt z#@l?lWD5Plp_xgtcpG!0xoM4}*HHBYcUFs^MUy3Heuu-tA7~Zl0gE+8tx>>w->kVZ zZ9MTO9tz*vrL%c{Z>#yAwGBZSl)4k(;9`=j<&X}$Im>NoJ z_chwwmeZ&OyvgQH?WI%gn%1|nabuxm*jlPC>+#k{H1f(T=4p$7I1iKgJOCi!jF!VO zLdGOllFu1;7m5M+3kJ`jVv(Zn&ML+N)}A&Q^Nh%jpT4hl5X466^P9kDJN9Qxs|$>6IVxVsliAhttH4rxM%yiIGF(zc? z6h+(@`;@>AkqpfQrhLClWA^lJ3E@5$Li7!0zxvFq(P2fLt$Y0MH2Rm_(*%_mV#izD z*BV$8bb=w|A&Qe`RJv8^k%oiME+s0kFn3&q(7#_x<<}siSrRY5K^}q*3_^9FDzYC& zKDBpv?g1th%vl<!d%BN+K238*%sy?w6k!B0$9OJS3m<1btM6(?NBcNqJV{kZsjo|T~$ zJTvJWi_F-E`~WUC_}Q+i=!quThx%Q0@RW;TcY1s)11c~p46oMbw^FS~B2VD53yp+- z;^TUM_gLaNR3Rr7#?R6e+;`3@D}-K)+wAA>kV&9?o#4+`4508#X55^EWoGjue8%Zl zF1PWpoRZzHaq&ootKn&{Z3+bU%n2RKo4AXBlSTtM!hBO) zAi8j$!-6uWg|nv6u?6)UD2bT5=ujYGP6+xol>HrzvY*75i==W3?_r%|RKjASUgB?K zJ9}tdbNb-=QlEq6`;V)4-;;E08CIG8_p7QB8>Y#4-c%CeM3jdXw)Br{eI)J&81bo)%>U$>% zAD|y@0|m%S>-A1U{23hWw8|O!d24uVLVJTzbJNMqZ#y>)9257-0|BRF*txtuFP?ii zITn7q%xdT^exSO*F%6?j+VKFk-J@}pzs*s6*r-yfF3ktb9tX*d1edBOo_j~OkYp;9?P%mBhbjgkok(%-x9b)EX!K~Eq$h`E~PB%86s~G z0O@3Sb8s#xW}>eL2Kdh&@>pq!?Vh?uJL5euyr+Z-3 zPc9f=Qt|m-S)Vnv**i zL5;yr4()1f@pAA%VRttd%Y0Egfnyj0MTw?zQ-1Dsbd0Z*bmBLDps$LqtW4f$9BS)Q zGGAHxRu9%xGmS%%0i&%mQ$5%X;uY>(sg|>*~sUj0oj0hKFufbUhp=Bg;6|vyVOTNQ3j5iK-&! z^AY^jNkP2GHIb*QP#_5`&MealI`DvR1k9`N<=H;R5Bo`#Fph=6JFZtN-ai+85VZ8! zBL$1?x$freK+Dq|y|?=-7~MD|rEe#u+v|CI=i*L_9v_X?j|XUh%H6Aw4F|JM9b-A1 zlkl|=TLjfzbU;~YCRZ5k;`Kl<$tbd;3rZ{E09<)chypT4Fbf*Yd*xQAU4Zl5xl%>w zWB2@;eS0SClrb#xnei0G3IP31Ye7VdWI40d*pz~5UyO*$>}>C%IyBpFo_==Hz1(k;FJq* ziNsbDhIgizm4dZFj&p>Q5F*|b9u&T3_-jn*4LyN+ai|ysQnzlT{$Vl3Iu1l@9`gBG z0p@4>orq+M0^mj?c~eFvqwe7x9T}izo)`4H=^n0H@Z;JN4$2!gNq71Wv1E&PcRHZC zb!8}>mPn78i{N0lPxGX&;j~WRs)9e|zgRIc^T9;P+d+FWhON5_C(0FErx`&|({xCR zU0DPoZ>A2QT@>7kv-_sgJ%8{+{s9a19S}}oa84XZ;5K<)C_HS&Ttz*_x8-x+R0^ACQ-}bVZ zNDC-eh2Y*#_TV{OBCBb^dMx#K8n%h8NOD|wRrY$ubEPO%pRpwRx6*k~gcThS{+3Ui zin-vwT$Ih0F`(b}%}HKo&=Rc9!U0MeEJgc~_!!zV z!NjxvQk>N%VG+h$8#>2ZC6?u*Vha!swR@$0V1h-WQ%wUAyB zhC~#1AN7q}N)Y6*FU08H4{N5M`Chtjvp0LTT;Lit!}ZGm#dQ&0!<} zI&-7|?vTW9enCLw-@~9mIM_>PZBg{eBNW516KWJHz%s^7=ubdkfaTJaU#SWHElEyDI+KV z(JQH8;8`nb0QJ01qTtrYNHR%wJ(vS|C-Ib-t*#it53@7{PqQANLMs@>{n;G^G5p^} zkjYA1ahsVWc+tn)QOM95AO};?x{bAPFiJSX1F;knXy!Uqv9azBVnMPH2-iaIb>W z99DmC77i@D_d!=LMxRq!AD!L(oLbsu4M;wSJ(3&THrlK(83 zhn^J}=+F0t_8(9dRwfSCyc6V0DU9Jls2RP5W)|g`95VH|`@rWYbyfJWf7BxU*(Gg_ z+tVv!0GE(qzHZr9hLvkEJcQfwQmd@qu~UkWRK?0WH7jk;sIoy@HMJptQE@c2bnR_Ir}*H zL|foP>V#qonRh~!oM;v4W9ob92oMxdd_4p#eBP3ttq#*Gt{q^UPyzpAOAVvYj! zU}V~qY;2N}fpGA}puOM$w9QZUkCe)STNVKTYc6`LheerOxx2@~TM}c_P_cLf`EU?F z1*+S8JI7JZc@wfBZMDej&;Zb>;d04dbsulck2WDzP!!CqS#^-pNHD4&!z4VnSY!7% zZdF2IF#5q6jnL$SzA8#i49A{UNw9C}oE`&M6=@Kx&6uZ*MsW*0<7mp?(6VyrhrOO` z7R7Fpcxh=n?H=gQvMz)#J1QN+p9Wk|qyyvF0bq&apw*|P+Z>t?VF0$f*TLq4+piYI zqPyazXdZ;s3PuHxDN zC7il}ZIpCGStHMjvZ4BUp4}Ux{+;F}C&b|KUQPP)z|%4XK&kkCSazJR1nYy>Zob+* z)bIQ$EaiN~{zduD(&_wEUVA&9rUSHWyO57^0aFhrA^14MiY4XSw?7P^R{IFcbhW<3V_;MP4jEsj4~y~@ zo+4OYkIXMbJH1_8$lTq{tT59~J7fEPzjsHN>D1_hZx@LKKv%)WH{(lTnowRO#Y%uN z<%_wk5BT4k+GjTRplc@d@;W5E@TeKoe1Oru*PeW5I|i@1&rMO@2AtUR*8(tIeF{*F zPI9`yD}KNx--b1<*OV0zL4qg&w8S;ULz?34kAg8W%Y+bBq~LIXKD%%h>P3hR)Mxy+ z8Bj3wNG#pLNf_e~G(}?Zh3D%j$U0eH6gYkv0FGy4Sn~}x^J9JA0WaUyEM znBySU7`UkoF44#=tbKU$kz}}QKivCoe2klne781%&bOP=@X)QeXTi9=rD zH|=DMK<0Lv8>!8V-lLyZHUUR{dFwn)!YG<;vx={6Q)LOQq1&`qz$P!;858jgQ1c9Y z2)?T>h)HcgpmB*bztP0;UYfbZ;eAe{N)rXG>RDfF+D|YChF<=v;9_ODrxyJ?Zr zBH(hizy46<>;VGab9^D(JE;ua*&vEVg6gCN0XXnD0vh|h*$5nIh>Br-2!{K&fBW2V z-yGp;DgDmGb#ajGKEoKS60OO#&6g)*ec}x-!qtUGzdXC7qu+TZqTpPCUlS+kYR*90 zBgrqsNXrgr^jR<(=OPsfo8RPpc|mzIMI4iX(Qal3O;Wc}E&bWv`NIaD8qiY$DvYN_ z45oIs`R!FnEZoDMKK)s=IPigr+^uc(Ga!&5L74@)((F?v=NIvFKZ+Av3YxHA*Jpz! zqm0S`!)C<%R;PcSt+8O`e($13ukDGKUjNa)%0GldFv&0H0+O8p8<9S z5C?XgWOCnX=?)1_ptRolb>GfGXAmTtpj{rcWr8;ts&Al~J1dfwir0zli~cBlKY7^H z$KO%g+obaOXX3goYiafGnK>W&P@mEAlX=yqks7~x6|%xOC-={pwZ!K$ISLztVg03^ zIcQJ0F2F`S^LOyDMrKf^Ab|(0A5OdCLX@=ABS-GvTmvzo{;=j-E^d;^qS`I!3heo# zz?E19uO?y^+T=;>^-NVT0!a@HMiH(==)<_I9=ysnkO8G)qSB>E(6Ms}(bGm_G@y^!bqh!GPcc&d}I}XPh*bA<}7uOQi9H z21d*sNtu)+{%wof?OYDYPQTnoTds-DGMRT}a$?4J{`vd15+rSn&54~sStPYvIDi-R z1`Z(sOcNi2BelwCcF{c`K6JRJaeA!@=z;}>{)2o<`ke+PiV(I(TW~qdd@U$36WqC} zm{Ib4d`eppX_GCSxKA>4H7QCw=^Uzz0-cIGoizbjVWG&TvT`)aWUkmG5E1U;LS73Y zX;A{WRsC*Z(xuhUo>FU%FiP=u!Y5&)1rI)E`lHzBptJzh3OvQ$S&f8S#>Mww&_Gc+ zG7#lH8c$PLmBS?a{W}C4#mMC^{gU&VHE*lZqtWW*P`HooYJS}gNc;2g*aT7{>!i0v zd>jy3iaFYegUkat*ElI2#6?ZdeP`nuN!H?h7qrm^`@^KY3h$3b|XA?;ow%C_Ht)K~5OcEBCH|@nz9>>D#|SWsuzPn?syP zh0G_BX=uEhTRf^WXrXR%!f(TgJHvA91@;F@{eaFUK#G@NX4v;T!1&+U0;tdL&wP)@ z(QB3Y*?13Id-noPj#^UJxCC~4}d0Sb>Zh%xq7=O2jLINd^kR9QjcarCi-jr8Vx@;J`<1?4xg zWIX5M?8bh>TJY8@F)oaqzP060LIG=pzf2aUtKlSYj*cWX{BW+*2BuKDB++DR7{DeF zmgi|tK&0C=I{MW_!2@@P=fI!in!`fJNN?bfsl5Zcd~}OzsHZNH43s_`iuP|BJ}|m- zDml5KjAmKt?j%E}rH;*N38&<>`#^dQq?VySJg5ke>+6&dE%xlrGWb!k{Mo0jH1k>S zI`ze5MGS77BH}|1-^Ha`Z=$pkfHtBa@7$+8O=HtxFb+R-F2j%6f8hN%@4&Ld%7!}e zqu>L?zQ9U+svdrBoPWD-(7CF}SkOw*>T6<5W<~>l_^B>MDkyi0HrSw5!3_mx9lb8I1T;fdw?>18QfdF} zgLIawK!E9Jk(5`0IGHb_p8frfNjwvW#hs6H`KN%ZM<`fBGpW6$E15ve92sBuGMbef zPQtUX)&5&34a7W`JObPPU@59QtO6|U)ajXY&tB9bN#<%ljMQx)=(6$D_gI{`WgWhJ z)fkje3ZFhyK^id$;>gV2*TIHE=|{sgYym%TofdO~`VBdyU|zXJzTUmvRAp5u{!jCD z2GGgQL=NyLJyLfK<_RA_er*6qmz66E;jlSchd(w$VlSEiX-nVix`FSSg4^k_#}Z!p zbIOM)8kXF{qNLf1^%Jp{dp6I^k0$mmuB0gVsa$?+*p95{+3fi0XD&KN@?24m*buQBn~sWmFt!S1e3YeonAKkHG2OQ z5GqqK{?Luv@kd|1O7cOVI-fOw$6-kJCX598RDL}XP-a(n9dKm9bM6n+?_JCXUr5xl z!G{S{z(Eq738s;Pr3Ra}w=KIR*TX{z6R!nSLiPX$KR%5{($d4g*JKR|g9CO_K0Uy= z6(C-aalTG5o4}*CTKtO)7KF$D0t+qygyhyk^Yny92rAat$GHjgj?=y z(MZkm!rhc+HI&SJy|mqW&>iKpArNaMqR%s;S{J;_4i&8EV z+~|YLn;U0xgbmd9a#NGsR5rYK+F6<@8`^o9BZ;o_Z=kS!fdqznIoB!GPqkgSO?Dy0 zw*8ljo4Ri6yk5H!XfZ?-x3aJ&PRJIoJaiV&ze0*y02e^$zx4U}=J~Kb6d2<>O7&)v zo|wJZ^>=!Gv24#f4b2(#0m5Z8;r?oraf>?CHBqNkrHyOQyhJh9sTBV?m$}Z%OT1!Ot(CgCJ-~oL(*=714m69w1G(;*VDx1GX9h<%S&F}B zrndr$1~b~2IolSA?q%XAJa7{$w=~sCY*iJP+mD3HZ<9N*p*Mvt1eeJxy&$$; zIxg0>CLTPy17FySBnnOML1Mq@UisY&+@!&87UQnSrVi5)qI3td zKv!_#4vxa8-$nRLr<}HGsdSE^V_FRgb#UJks2I4->yWP-Udcp{*l>NAzl))QV6|<+ zq309u+2jfIa+8N_+VNA>bHtQfiO?o6(c{ z=(S(v50c1rw)sKe>!FRq`+N|7X2M1k%2M^o-nJ{*t+H>)ZHIKO4Jd#ENZq|(F(9V_RyF*`h5f{3W%^84jQli?uzZBGe?t2R)(i9fg677 zzT67DUCVuff?=47;XB^;zwGYmabmFyl1bA+V?Y(`037AMgG_WFlW$rv9d__wmh-Rr z{`j@UZp(-8*^{2+*FHvHA!tX!$y!%e%N)QN@g>~J*|P9%N2RGN2rhgM^rJnK&VbJ^C<#K_cg5P znx#8u^5&#g+t>szOB|;6X+6#nOplNL%Z}t`jvhPEH%jjl2@!19%130aaOX(Sjn3!A zJ_~Kvumn4{?o(d4X;dO=%HYAtE8Sl2BNQNwRUEikM%`%`8pk=_SYu4wq%DK!oE%Jo zgy1s{uVibvfk^dmN?Z!7`c_3j#kTzR<;pJ$`6UGy#Hq-!4l7raizIh4;@m(YD>A-c z>_6Bmo_`QarZpySZ^ZrRtPN1LhWXwFQm;*K#p;lc1*}g?@+rj!%{OxAdGRb)W6jSg zWM8B?84|)5;mSUG>L)vVi?Emyq4k>rX#+#=Aeo^Z{aM6=mx^I@X}Oh=q?~8$w+WUQ z<&bky+$D=K6RBP7g=;@rNqbWlcz8%Buv8Z_>XfYOlZ_peykCSW^2Sndcd_b6r?(Ka z(?O`lqF8=suPo;Fa3BWT7eJ|N44P8Spqv+ZuNE?SSoZfLrOYU4;{DSd zT8kcZeq~Mhe|v$;>n2lu_krQ=Wnf%{s_(H9M&=9G16?-&QU|tda${endHacKE!0K9AiWoCb;K2>Z9;g)4$PtO8@m=R_H z!kT7HnAcl(R3HLK7DBFLSkbJBR%~aGsplq{_o^3n)0$elou| zhE3k#H!HE;gSnRe(Xh=DY{lj`yWFh=ADwCVyU+n{7BD0E!>0t zq~){z!rV6ViM$h#PI>QpeBKrU%LYj2xCfR@7`P3%xYRH2qc!EB+A#JU?qn$NA#vsF znPN^{jUUKsR^+0H_YJff_nzUq;~`oul1Sj$NtB=!L4N(*lt@tNCaoJG3gsp9Q* zzyf~IgkdNRN2|c>zs)8>23p;cdK&0cl3mBO#r8nyH~AV==rCcb3~lUceqWsQHzLjW zLvwoGg&NfrRQal+3$aLl9(=lXP*7Y54>cpPX$JWGDrEQi7ERZzKH~QGTRFh8HB}Mq6$dG+sNbJMU30PSL!9F*oLqpl^_e?H}9;z`GA#4ZPM> z%B*<79hf-bnH+$$P+wF|&klt~I`YrjHGwUSEi8Z@i`h^NX)+p!pZT=+(8y0U1Q9-n zQJDDD*&DcwKmxcJVt^#2s{rl=R}ec%(tiGP?TLjB_)9LiJl6% zQ(_$+Jk1<9eME~5LuTX>upm#`BFBQC-&=mxoTf(@r3O1~i-X9Sd=HUba$NcYt|b_>I8 z8Pw+UtI~kRO`qACLep62CnB0L?OW`l#>ZY5--pw%uO|>Gf@{>Kkk?i_>D3C|1$c34 zdaA}ZwyS`Uw|H)QY6lqJw~9Lkr!QROJ2};f3vyC`q)?|{pZl8K`EjqZ}?scl4RrD6hNFOD3J}&FZ)?G@qyt z|2An&S9}-gfjBT8!8mLuVc?`v4aJkak6ZvSo7gJyMWb4{FRp)Oy;rZZ+`i>`-=AXZ zt(z)wc9WBI_Lj&wW6~WtgH47{-#l;CDOGnb%QkB+FT&(M#~4400N#e6n&_=gIr|8zMV5WxdpVaQB)Hzzu^ zstoVUOv#ty)#{&h6M{6w6LE>eq69Zfnq2aCm0zkOIItP-YwUQL7(cDU_auPqpt0 zAiyZy8;9RVE>u=iQ)bx956Ol3tlXU!Rw7LX@I8fX7TX`fte=<(sRv2NeCFqSiCSCe z^hWu^jo;d7ANkssVU@o2gxU-SWTu9ypB&$qrLdar16DVx;Ygndg%4s{?{hA#E5<}? zp(tos1|=+N4GDW6;1pC`0)o|{EOHV@dm=wB9r&6YBw0=W;*h|)EZ&DdXH;M47qJsz z&^Zx$ogL_);b3?64f>S#dCW!!%`pY%OO<3u__BJPQ$Qv`-Lyd1%O$P5?Gt5wWqQ|n z6o$EN^$_+Nos5=?P5SzMpQh4r^3L`;0^YB6*`}cN=MuT_QuL+QT}d!?SZoNCxye)h zYYi`9nK@JY8gNa@|PWz!R%K!0!}J!ydb z(%5KSvLx@YoxLK9iu9Wd;YB8+6`Uv$7QwJls6^8OV_73?X7> zt`Om{P7&Iwan3!TIxXkh>ypwjPFohQrU}!u3!RB9wEXWFkhUHauib5|TuXEw$+|S5a*spw&tjk4z z%?#b<$Bs4@azVdpf~L>bA(5k?AaCb=FgfHy0@Y!Gc&+z*&7o+A$S8bf$6cZ|&-)oo z1tD<;Nb{vm$~qcj)>6}HEm4BXm`&IZZA~DD&`{{Fn+K(jBH`d0i)5uJmzW+*VB&(_ zG+!Ld2$P>6w3BbIu*}(SvbLn90?0cJ#w&uC4`-gv%ImuYrw;J<4lob}ah1QQJnxwc z6@&@TyDv+d1i*?!yA`#KPDv}!baMXQj~-$21!>ntWe`NGWF5BYOP?tt;1`mOFXwqv zmWmvpM@uQNJX%#U`5J&he7LW~0mYG;4cuob#ifmq2MAhruxXxD><61tzbHx3b`KHA z*gin@Bhbh{5e%B2!Jw!&XjAA;ve~toBmNAtA5gmun&*H!t@OqzzN3i~+`uD2<)J8F zD(w_XmBW{N;i5|DJMyrqLh_vCvvmQkPk_Ppq*~-hO%(Ro7 zL;@0U+p5Av3nZ>@a3WWs6tL^M!jl!`E6TNR^K8l7iuI;4A!Z)h@0~uhns-Qzczvo!CK0iYTFJEd#TQ9e2Mxl?jIZ)mX)=J|xL>=pSGI>=)p!TGmK zdp0W>5>Ust;jS^69-yB0z$}+EA7IaEm2}~_hi#ZQ$_t9`eeb&tZTDh&K;%E218}27=~Ybf_K9V$1xLHnkQgXV1z_^azOauo@&mT}Z=a$9H!s~IZ-z8N zepOi9t8X4Z)y(-zC~|wki~~8Wg2^x2yKs5nmHwk)IwA{8PA7ttyBotGWyyp1Hbq-1 zAw273k^;mR`bxiZ4<#ILzCS+c4gly}PTZ#@Cquj;ER7CtNB9@NEz(xAedgoPRibI| zeu^c$u4{~6m^NbayN<_tU<~ZPq{+8917FxK5ysC|U7fSQL&?I^$iq_ZR;zJ3T1dILd6R{;)$<$yeM zVRL}TGYLkeA9*?NRDG8bL-5EW;Juj?nT`j-;i`$P1hVMtt$NPo0vnH!g^DjBL%|fP zpuEhR586c%UUlx3=dB?L0re%H&l+Ntb}Ud3CE)!#XOPV)cOn=@aQW8DEv;Z_>`CxgQe*k*E;Fo?lhH41*~chF^vDM<%>NfcckH(mSa=wZw1#+>y1 zQCp=0vC!8xAvvsybTSICMY~uoU-o<6tVV5EcI)4R`+UHnrmVVAY;*#^k;jesx|8f+$U7)J!I-&eQ39~RHMe4#_`QvWO=Cc(9$$@$VM)s%iMmF z{_Z9;S9B6=9MjPZZy8LaFjk2a^tq5e*`aFAfZidH9`hkzFg(>2_=52G*#>!9^|R(r ziG=j^r)1q9O6+_yhF#)fyBv5a6 zi$2P(0=yVLjbj&m>8JjX@Waf+8;~V&aU(H!63G$pG7PSOknw=aRGO+aLYoPE$w!9Fm|E9Fs^8^i&Z?p8>yD z7pq>QAH`Qx5X8wde$=6`k<{adh$yU|KOk?koW}Te@aOrs3AF6LCC$dF|ISTE9aixb zvog&eOQP>C*3HrO4c4fH^O9Zct!0+62dgwup3;BP9S4KgM)koQ`vr_gR4WW%jmHK> zT83829&i)jsPAY~lLvrMvvhXeN257Co7AI;;e=cCm=f=EPb<&s3xw2~p;BG{<_&=!8E8c4xfP)$oo&?W-g=MVPCA(yF7~ zGy2U*P{@BDt7Xi&r?nacozXj>7{EEldP?$)_h5MQx43K_kaVWX9*08bb;PK6HkS`*{ z7s!F32u6;DXa9i+fca%nUzb3BT zj|wgMCSQRici*AY#3c%YI{Ix27~2PV_<|iiQ7#4ae)#1VU^uvSrt^u0!)-*k=_#DH zn8DzMYOnW>^z(4|lL*mCR>R4&70?-CvfxXtwm1nj^OAC!CPAP}ZixLX5s6{_QUC$M zln004$d{Y5ykhXUO`H9A7*9H?bfOA2eIjCc$1;#!A^1|7o@>rW7ojecKSfLb`EFiC zEee+xy!vwtD>fk5Bg?ol1xQIw8ygl;$G6YoxX#0Zwj{0UQ=t#1_cVpnK|i*h9Z`UN z&WV~82>MZKIv46B7eZU?f}lHPpu^5v6i0GVZbbbvsQc-`%1 z;EXrX0Ka0-s^5&dG!^&2n;v4!kI;U71bIg~v*7%wXg}@vlu+vzisMRtY4?JVDfhUW9lQ9I$_dbY z4dc744ry@TC%_{0Ghd6OLOcjq^A*E4h65+{p?H*r1Bqub=I`@JwwtKVmtE4{!%|4E z8@}4}e7BS1qM?kFy@w2IYTw5-(*5?7hDD>nEymZ~JQpqFV`T^5f zRgD<4^b@LfVh$fWw8i~lkoXP7&)IKj7@Q`!0Ob`PcD#Z-$FHs%TQS0DyAeG`)4d%- zt19{~1Jj9s5`}2^43ClQkhp4B+m_Lg^0)(s3xtb~x= zW7`1RSs&M92>SNLhWeVIYYB7YKu}4CVo`^ z*v2C6;hFXWl^&1Zm4fwvR`u!c!I#Zh0B@>+pX)?ou$-Q{nt8=B* z`l1itVXZFiczlat^q`wz`u!@Gj^7lhb>*iMbt0~3#0}ACgJ_^UU#jYX zKHo>RiRBN*A!>v#W>tCi7Di;7e?Gleo`5`Ur@id9UH}H(lzUvrraF(*&f7_Ivz6IO_>#LMUz{XeP8>3a^{RFn5%%N zT_vFAzD@*BK@;6&*8*d48f{$JKUg3UcuwJ?NZO&Le%fJ!L9D*kiyxAL6!))Em7E%@ zIjTRjT%U-CW^u(dkD2!0g!^-SR*96N43AEL1f(`x;I%m|`{8KyAOaQpfKUAazxxZR@zDYkYeWyFUR-y^hwu4y{XXAW?_bq%rHrJZ` zucP$zpoZ&Nn_4N6A!BD%EVqJOCsrb{1n+7e#ee&f)#3$Kb!Gr|9Dc{(SH7~azo@(F zl5A3AU9^b8mbRbTEJ2(7Ega++A{9j|t5^XTh3Czbs76*jAYJa7`P`lLzy-l>byl(U zCe3u2;E;_D_8w4A(^1kErcMLs^~cN<@)hhe-9nn-=@Dc|5BZHhdheK#>2$G+zJl-D zzd?uIVMESrUHc#p*@MgjH1L}a$7aqt65P)6uGdQabDE;(R*RgbS!1uZ8kUdOaP?yd z#*eojlO#p*0+(LzgGO67Kn_@+R$^8zQjq1c_9s=SMvT!P@mTgDYpt0C@&2q)sUKPR z=ls1PQ-Z7qq6Ri@bEWt{^?aV4l(8*O$Xh#FHBLPzGpim)lZMh`cn~#SUfDOJi|#Wr z^>t^{{)w?3r}u@^3RhQaLb7m2BsUxeM}HK4WsjdHHc}Aw4o5G|u-#Qp(ArQ;_iS>F z3mVUKK&1C+4VH%<`8Mx8aBBEbtF1_#`1!t&B;Max1a904D}epAzl{k_D1gN=kuxaR z1Jl)OCjfsZ$U}}}YAZ;8rUqB9WZ3w7>-db_5P=<|jsj^(wP!-DrmuvZUI16BBUX$~ z7Vi02a}kxV|vB+h58WOOl$V^kok4&!u-WkXrXU_-dtlpEkod z_77+5PV2y`9baHgY+uo5@rXJ?L_un+EK2mLO$y-~x0Di{8WpOxop1n#v>_nGQo5&6 zzz%x$naBqY0}SzP(n+MKj6az4I9eK*_&W7K<$u4U)eUQvt^?r>hUp(( zWC!2;`Vi|Cz@Sp}EJCs=foq@Ua|BQs9jQTDNjpV@mLN@vWQR3TPSV-!Hl58PM_lV<)@M+(aiL0geJh!ji2=nAW<8Gi)-g@h!Ng%GRE`?9KeSlmOA| z!2M|cR4qi!0N^*?Z7bgdI#_rF@=J4{)I%ByWTTR%`IEcyqNmh?rmM3*!7`Y|`833qOO1%WHwJ>E75IO&tElOe13VIOnLCEPfUtlz{8br)EL@mU8} zp9#lRC$T^zMLVf3E6!J8jv(p38Fx$EKz>UKI%L7A}ri7k-Q)i){c*ee_uGQ(qZpumxJ*nnodIs*Q&%U}s%@-qQ)6j!ab zDxFQtFVFDhY9*$8BH@=3fajUPG!?gbq&g;V$CA?W@QLh~&_3VLcH0f#K>DZO-blm% z3)75-H|*Ht7)K|b`tG%^e9*YLq$~(-e?F1gd+2#35p7@StHWv0|F{$Gyl(dOWh{ds zpv%B&IuLJTosd5!-L-cIg$(t1+R>4S-sprcvyl%&LZv=6M?t5%CI%E8p@k*4VEnEf zk*(uxqN!y)u^#bBP)Msb0A$AgNR>M23+NNfpirT--`GixuOK zBW&dT2ImF)Aa{nDjV9Q3q6rx?3kPyjVH>0&Zed1}S)mSN^2c%$Rd1<-*Jy2lot_1) ziHJV2JHQCu-0a4{f|Tut((mhM6q=aD@s)J2J^VnW=TAfa)g%!__z?PHG&sSN8&3+^ zDP8cB@82O+l~|NLe8Pp2FGs`aaB9E=t&+fTQJVdfKNqI+W4Sw!q?L&Yeh^W}0Y+;0 zsdmrg< zssuAC{39)YI$(uu=avE*m>y?2s(ulFj;{jI^g%p0)5mwUqyk3df^(W4^Ka2T3>c$i6R^?+w?gH+d@Bf z^+N0NNcQBSOh$rvOVE`$BVQ@y9!_@Qa<5lr{b)cA8q8+<%-8f!(=$%ffmW##PHO#e z)UYCdZcrqfXb{2FF)d%y!s%7Fxg0yN9vzRrF zZWAz(t?*0B9f$`UFn-rHO@~}wEzo=M_QgeWW-^dWTc8AhSOxX{-VWLnB9$3al$Q))-FNJx_rj4me*%*iy4LL6rFUQV6#FSsSta_NjF3@hthm46=vJ2*@5Jy_0Bv?FI zN7o29<)HxAlYVu0S>`Zkyi;Rtl&Xr2*Kv%EjwwH$V+#@Mi@?8~T)CS&7ZKix*La+Q zu&d|9NXT?c{EvxbH+u$eaMV>G>?RVh4`9G=2Hgb;SX^P|2^M|!tChptDp=#|TpN=lF!hDKaq4DDKi)11lE`YRFe=m>( z0$zE(M_^hlfQAYn0}lfv4}j<}=li~U<)+hF)us50~on|@x zvN33zqs>br)ZSwmHWghmya*c~;tC$2&}c6~k;+s0 za9aE6hZbwZN{z43CL+Q%+wejHgK-~*c(R>N2J^J{13|^QhOCE3Quu*?t_{f)5U8h# zl_L$S&U$-*8VB~v(~^&Fg=P$<&kd%nTD-(s#slz-`@^iy+AbN43iZ;Looz~Ogb%XX zEVjhL3hh5S!0GFpmIh|vS3OC!;2?(_9g(0$8+g`B{`2bS%{LGh;-412#C~y!I>m9z zWpCkAZ)Gtuw7t2Ehr0FaPh$axDyPn6hv3(2?K;1@F*x>=44FdVj2P0;3dOI~u}M7O ztLE=MNBH2=KLsLiq-~ZaBDcoV(a|@s*V-*bWMoJOqLz0i z1bO$Cl*kIJPV=?{G`1jmHnl$m2%6M5jIehF^p~a*TpJ}{_pYRT(?2(3Vkd(6^(-vg z%NTTP!| zQJE-C5D~U{lP9Y5wklJQ2I!E2{v_{>ed*SP3rL?~^nvxT{lZo8DPei1my^=93W{JK z2z<_?Hd)_7pX)K7^GQGZjQOWF1;6FWK;;Wc2gnZwksznBDir&`^l|r5LXF=Q7^UfB zz>6X>y1s+kD)OobdioFyVEgkeIxu88IheaCcZDp*+uEA|%-5~V7pYKw+gpMouK+&N zcwk1^OT{Kv$|Y~U%U_O8?aomA2KejDlFBw4ot3Cuor^X9!b4oHvTrHL`055(E3vKL zCRo%ffVu@~E@w2*qZ`*{+Xe|W|1JSjLjwDAUue~XgbImujlN{q#8sOYG(mM~#oNDT zo$w=Woar6>In+(acg48w%Eo*N4dEFz5eaaBmuCi1N}7`RsP5Fk?PjAv(E!#|J_3K| z#46ih5V_EmlnW{)Ln#HKY8R9#DVub^VetE#DH579s5n8q8l@l?C{i;^1QEb5&j{q# z?+v@T&G@6sz{Ua<_}MW_1k95&3(1c$f0@JJx#$+9H6H!cI=UL1$6Sq zHClIcVkHe;LvkM14ceVjMs*kGR%VWC(hqRGHMWtb&MMkX*G_JH)%x)ZWaw}%g1Wkm z-P-F2yMOlLXKok=uXe+h`bV*LvgWJ__YQ*LOypXfFKT=_b>sd@-@u0b$Wbd$}8EvR|D*O6N9Zw7)`B8vOHp(@55UfQo z!i}}CMGKyBn8$vIC;7#?_t7fDTa+Fk(Sr1Q5Xq(MWx}f?)4cUW`woSQ9y(f85-$}~ zc3~dZra{ToG9?;~heXV~Csu*z1f*Zbk+xPk!zIrPSM%xjHxg;)nPNyya3}c2hpnk< z(b&iwam2mL%4iKSruyj;b(Jl8r%}`!gaTW^w}Q~WloQJw8&Arv zz3ET8p(b25X01$|h~nDp;sm%Up1a}W{()h>6Z`Oa#Ex>$=Q&RIG;$eO_$9sG;Ev2w z*jM{H|hO*{qf8z`~W=Y&MzvdTzBX!KSf37#n64$k$K1LIlGxSklqJX z_CYzCR~$3Q8M5CsSjADW8I&u}baF0s?Vt_wBjfpM`CZy8+QCOmLhzfTrg#(((`%iO zfeecg_zq})>ogVV1z=9Yd-Mj`7{1gMiyt&#Z$H6;3Z?SPPm3WkSA3}TYa~>68>2Vo zR0kQOi#K+W5V=ZzZ>#*0f#>*XYV-}QgPJ))j00G&4%rwZFeeALjKeb=8%xcJl6)jE z3VS-(H9DN$6MD?ig(S#js>_!qPdnJIIY8|wjlIusBqq{YHt&E z0$H7tdNGO$gR*PmZt^sj&a=l4&`+hF_?`M>f1`1A4) z9fqj?&-CA~|Iq*b%>Oz4_h+8Jm-An@eS16Mf4Bbsm-ElFE&i<;{2$Q! zfdAvqR=&^w@qc#J``}~Iv{ns1xcF5mb_|Ih@-i;}ba+-_cuYVk6zRk-& z%c^=O{@3RJuRZklb3N*R|6l(PP)i30KM}IVR__1+O+NtuP)h>@6aWYa2msH0eMy4%pT7ZnkR{^hOlD=-%kP_x$yjU$vQ@xwE*qz^nu*Nh+C<85t4h97+H3e_ws~ zmm^=+dK~`#SNNZyzy2j3(lM)t^6!8Bx#Hibzy9CCn6oU2r zU;k3&by;oy!=Eg8g z_tU@q+iYLsfBODy*}Jz(e&oZLW&hFX9WPJg>F2K{>j{pI;zukOgxZCw7A7sY$v9B+rz=_k@_$HzZ3dDLic~J9?8CK|BKqu*IT~)$Mt`l zb@ki){jbRXx98#iMdkW`-ip5=F#b<}gQ-9JQTK6~|3@u;z5mz0OiRAz%aJqd^!nJ2 zw|e~dh5h^Jf4aS8`t{Y@{;8|~wOaDx?|;qWE&i|n7!sU@^8ZTWH7Brtsy)`QPv|3+ zBlA9V=T`~8@;xf7_f3X4CVX37gE!#wrvn$TiXVL6BNY78A3SBKUOwu3Trxr@Se}gy z#zkjj+1kkf__%JE!(rg%O_qvMrln{@ETFKWAbcHW9`$?~KWxpg9xJen=yEozb-4Ze z3ASS?PNn!F>kFy_S7n%WnLa(biWMqY>`k=dKMyWevh4;OMe;nENn+lQV<)F&$$@&c z@nhRq=6p9-V0hlOEf}jj1Y;zre@zlS!i3QXFp92=tQNB@!JP1qmjo+|12t%acv?cJ z)&Q2RXO^7>6cV^`<>WL!cmd2BMIft>jhU;2l%>X7$`J}u@s$KZzAYtg<+d-%nyI4f zq*rO`))FX__{;eGPd!FP*fPfMobQLdlPQiqRO#V5NlhHUg}oNBV~auz|7rep+(3Lg zGa~LsBC=a8p&4KRx43Ztb7b&Io{wfLAr(_uaix>5OF-s}yPKeVGR<=%n6E6*&Ut^)I%rt^(wf+&vjncJV83c&HVm?axc zP4OMk_&E#TX{Kev%@s40<}sBPGFd z^D#h|`TUPLdMt;$ch$AGy1NeABoW^Fp!ll>n?!cq4WcAd7)@?CW_DuaL ze|(r)!aAwAjH}1@6y#&h2|a)=#cUJTbkLArnUWka9Ac%A;tucN>mSeiM*~ z*ivJvp<3$HrUiK&b3!#wEWn~cw3u(*pJBgWUga|jtHqCdXSeTmH1=}DUbI7vxnI0{M zM%`Q@>8zzcH7{f&&=xTxf$uK3!k#NK9g`$yzd$@)Ig<~tpu=TVYGVBLOzf36O0c7a z`z=HXFi(Gok2Su*_KqiqrZv(iGkpwZ8a<}qFsnb+b~~l0N%`>G^C$WO#G+3=+_2x; zy_pQg5Me2Wm> zf6Y=Hb33($6BVLU!&Q~f_>b)~r-?$E<~UIhG-X7UPh(~fm=YbR4J-d$G1)jz!C`5I zwmzY3G5Cm;BzQFY+bbVYF3m1rbfjRC1kgwxk4W2}e`+l^JZQ{3Z5B2` zAaCI3X+tsjLp)G7WC0^x6l+fe;&N6Md4E#MN@z%~%LG0Lz{>8j!DLH9&>5cm&fvPy zUJie62C7P8|tXhcDK1-wW!;n?Y@mhV{a~Ji`l{u& zrX7Ml25W=A4y(S=R>iB@^DX6T0OiFm!EP$nzEGL zA)&=>DK$JjzhJGf;Ppc4{gnSw^j)2AoW&=FEVR*<9ATd17ZjvvIaj9JX|bnCuTFzO zbb{NN)HhMATwMmgoUyaUn436f5#wH-(Rg3-W2uM?sjUui3;!4a3}R1{GC^866fO;A z6v&J~8o@|?-{55v6cpqrEZ8UpAtXh^Qnr(xmo`kECcNO_fhrI)B*AA|I8~gbi<$A` z{Js3ziIHx5*m&wv-Y1|Vpa`NJ20x7T!Ij8_e)$Sy^j#dI=rR*O6HQyLcaV?GSRK>9 z!0C%hqxvi+-geL~eLKA2a1pev%97gNRs}LR#ZTY!Q+PzCsR&ShZYn%Ui>}4n1sllq z1q6%K73Fbpx(-@H9U^i^ox%=_d7hcuD$ZgbvsKC91KBAhS{imD3%W59{{iV{`F+Gr zM(7ZHQ1)i;vdBZ)JU`NK*W#3=G6Z*g&({JvU=}2|p(Sa|V^I7~<7|(6>sk!MWT&uM zAz>kX6ubJAWP;|{M-;KREC7q%28$nSnQSjN!IVMOF<%t0S>-&`*i+%9R^|(c%x6&wywW&$*J5#I5?F`redYEnt zAZA?gB+!xuP`06Z}5 zJ9>8#iI39Hx+u>NAppOXKI z+PFL_Ne~PFpm(q})Q7~WZNXCz^KE|A9|(2SA-VCbBU`%kWlveqEO*U4GIVBgcrPuwyTQR zNFRga$#ns4{mXJDtkbAB;)KPBWPP7%%_~3@ZC(=Dpdr7SN*$2>pEmK)-#wk}?l62N;WvnUPw90VFd#G$$w3Z6iH%|Dl%VuQ-bujRK zyD#31sgp*LK?XQKw{oG+u4@ZoY-KDodEIjEuY4KUJ(E7}>hNs6vlsdQJ zluj~f1w+lz#<#pic>?2HTvFeWmJ$oyH~(S^NF(X1d~eL8(_g_)Q9ku4nIIl^rENfh z=J~j0xbP}Sgr6Vq<4d2^4Pqh=JfKM>DWIWp5I5^mj#z#D0AA{$$SeYonk`Ci9780< z>KdJCzprC`+{ieI@>zs86HD9JsC%__8j00xQ`-@6l@nya>(lnN_yjSR+j5~#%)t@_ zMwWq2b1yTgN^%9*4oGaxf+IA)E?nwL?DUxyaBDWvsN5^_JZf}ei*%w{=tCg%MfLzI zaEVva24URs`|*hz8_%nI++HT?yx{Kxfi?3m);eUh1U5#v_zvR7?@7}M$R_=PTh~`R zFMh@~n8F=mq8IhIj$6~dYrL0YVNzvdTxF9eeh~>a83cbf}emp0F0I z{q8xO^ET=Tm9^^T$h=>;%c=G>-bA9x3-hM~1zEdUV|8{sFrk$1QLM5d&@Xm^JdkW+@VK^~we zJAKg|05C*k6lu_W_=8dUk8n6^_I~wpIw}AL?MnjzM{_up1B9@25MAjFNMG|J zN+RP`G>*W4HHVt6JO)U=8SftadJ;TPQnJk7r@_;wo)qFbb`{j}dzHu!3p%Kyzeqy( zv&CEc34>%;=)_>lz>$SSDz{&@GLWl@>LOX*!^1i%dE4tR!}7=lk^q!0+*F~Bhz80 zbQ)zi`{^Li1-a(C*+y2Ef;)+GwH&ZI{`%r*e!c6r-)tB?kPQ;T1UR@P$^pHjuy((0 zsk0)UJBsZNQED|7^?pbbAdtk><0==MMuH!Hg@TY6MJOd{IBj3%#v#2TzQ&}SLWX#n z5EdQ^cD;4i*=`dX@uO}YQamb z5q50ph~Xil+@kq}X6$?dkVk{BB;-%SaZ61IjzDBN5&jX_2|);?nYp;pAOGuGaZI01 zO~yVprXP)r^TRaVp7zF?YFO12PENmrYLu)@-}*#<0c6^8YZqAw@~^`+nW{~WE07)g z7!+p*=2QiL%Bq{5>Z)k^%C-QBVz~^a$TGK=6i5#LJ;8U=kPFj(0@mZDs#7#vHKn<# zdOZwZcT7HBD8kTF$*}zEX?-`mH1YVN;z@9>J`qE45(PpB?iN^r@cv#{9cD`k#00dp z!Us$NF3!tT&h`}5jU83b&iKr+iC?yiPUL&lFc&C8am_lo*!34}{0)mmMe=4N4Ay}5{0 zfD6#rqoKpg$BhOFYHRCbOp8&KGiWN9MJynBbuPjK2~fZMECqxW%N5&W3R@!jy+S5#wTGSP&jW8QgFbp(7sFf;U>x<9{W zc!!{ky;I~v$+ZJh+c~FTG9-3yVgc2wTl7rkUX3TniuZ7^mFNj*Ncb=27AFyOGUb_8 z4Fq0SzfvbuuP0vKmJx1zuXztuF+1t-($E6?6Pyxl^Id_*5WAtFHpeEbwQ9Q))ps;Z zsjOmo3DMwq>7%JC<_n1DmiTG6yJkUt%w+193kWK$sD6(&f^?=DM?J6J%FI9dh$=la z+qyh7tmuqU<&ZsAQaa_;pSwCjU1e;L|2Yj2*!yg2kqye@GU$SrtExocN}g;vL29&3 zTc>sb*?V6>_?rP|@k2PPqA5XUTGthOih022(Vh?v@~jnNaZ)%^yNi?X~B2jil@J^?&!C)n2?k6gJQ-vq;4-pF@6M!%_Nex zlY}}Yw2X6`fqO2+xZC9W_DhWOUAOqb8XPHkdjDUyVRZ0kNDY|}RxeW%}_kxmM!E@ax^vj-(>e4pqX75bGTVk&qqsi;bpAz|u+I&V2ypqUl_ zvGxGj?cD(yJj^+mMi<@=HXLS#xu)5K#*Br$?vi=L+d2i$CU5xCw zp4JieicTf&QAEzXf5USB4v7FLzjbzK?zH&o{BG}-sZoLGyDBOKX$O6sQ39VP%HEw` zJr-(3I8w@V&g!?`&q($N@d>Di;A;m{!Qyv!XF2`t`}YijoDy%W$z0rIUygp)=n^UH z2BTk(u{Ninfc{m&I%qa1WU4$a24K^4Aa~75z(-GEBTCRQ^$UY z=6i~l77#UbvY%Q7-HrV0K+=gu=G!0g1L4*;NuDd63@kVmv(L`O3{c(izT9)7o;kJ} zmht{-o=OtVX2x0)bc%7>rO5r}{V@6l!a(wa!LsxuybjRDUmt16&AN_T8%<1MdW!&%NGFo0i6quv`T zEEqjpcE0=>+bo%R6!}xQg@6gvWvWh)%usvSY`^7;yIT@2JzZs`RRY13rK!ju^U6@O zBA1-GDGLeCtUUe7%6z|Vy^b6V9mu{Z3=2wDWkBvXWZpzY$XxWl)D? z>T*I74fSI}znkWk$1l3^No56?Yb;o6Fw&RhTnG`P1`2~B?E1AFq;0C_w~oe@D)!$) zJQg$Zon6t>awg%ac7NaHxxUIwNwt?V2m`Ceeck#PyG+`e-g>@T$!B3YX;&Y2_AA`Ci)}y&t=FUtg${u8mk8q?T+x zG($ZjUS_RR9lL(nmwkEoXL|(|fd3ryHaM^}tYlz_95y5ayF|zmPhQ*J8d7|ZAvY~> z3d`O+qupFO8>XR$4j={)HNUT<--yldCEc0|wU1i=)N8hZJGca_FsuC)S@M{DE_B4QZ;D>zQ)$JenAm4+BM>71ia0>iliYeQT*jj~1={Ravl16N% z(#Cm%f!`+MTnzYDm~R`{oMpM?D@Aj~tpFm!d#-KOYHpHwC)<#i#Shj`dj&osGt?s7 zp%6C|Vr1!GZo^SkOwU-d&~RK{qe;ufQYNW>;zN``9IeEBoIKDbXk85~Ig{(LL~_wN z^$`u7Anvi; zTvkJBpv-wV_}kaksiDDqShFLcfO5sra+O~dnLF$^c+Qe52?RX>>&|!pr5ZB)(Xw9o zjA8=RJi0q(VZVE)ea9<2BDIC);!o+sIg6pihtqbUQsj_By^vG6m(d)IU=rhF89qf3 zJlXvo@*sOK2Dz2k8)!65bTE7n-18%?zBiv6ejiC>)kV2}e@)~Xf?#bJ7j=U1PIm6% zU@j@k7P*Z1-lVpq@&GS*jC$UXjuL(*jt8BC{Kj}Tv~pCVmYQz8=#osP47PWjiOSjc z*+Bqmy3{xN#!SqonPkxn8GDZ{(tg+#u!Wja-M^sIYUsk;Q+!PWxrklzE~3&k82adc z@B`l=TmHG^cg;jlZk9hdk=5jf(N^+!uSDb#low1?1d+;iX6#c4ao6C3zEr)$h40p3 z=qhdZC;JuBI3)Muu~$^h|LcD|`mp-C9V=o6R^n_#v;K6d(pA0sK&4W$Bho9?we?L# zUrr~UWjI-;1(XLO5s=%D(TRRv7P>O9x3Hu1qQVzP-iho@MoN(;q`X`!^zEp|4QFP0GabgTpPKr?V@V)R(FWaf<>g&D$ts16!q?-~50;>ufQXQ$eFz!HaURqpKV6@)?f& zf>oGR&u43%leHiYW0N+D@Pv2<{ngZ?TUw6`%|<$}Nq16<6ycGdb88I*a|6DqK#YgQ z_`ItI_7Onpxcm{w7{BT8I4ZJL&?(8kijH7N{@x8S4iXE3@e^(E5K?e%YM_Kyta zGqeBx`5L00&z`fI1_+2nC~0f9bF&nZY20JRW7%foeSXc8nTyuE(&grzGqWA1kQs>V z=nP&Wecw$<^jNez2|4`U0nysc!%s=$bm-b>((?-D;0hZ^$aiDF3+V{F8yKw5c=qdt zI(86gg)l;cGTd&m*(>8*XQmhlB0G>M#rmsZt3uXglL8-uCah&*MWb-PYD**h(?r?y zGpZ7)+DsO9*;OMX`IXD()z!Lw)y6uwea3CeO?_1OYtLMp_nmn#Fe^f4S^K&xR9{0iQxw`h{z&c9H;!Ns?3v0R8VevKFSA}Pj<&pp$2@l z94O~;f5s-avwF{oz;F=+iR&I3E%}pYB#CM$CZOhg<-iPXX3C|*`PoQ93lxgtViK$y z>TI;Y*>JN=6<#WU6nepnf3!LG>K8vZJu1-eS?ebcp%kXx4<_N;r{9IA zp~e6~K)$~te$Q^ic}bVrcK^06xmj&BaU#K?6=p1;FCD|A&`8dNK7kr)y-t_)#x1Zt!DuGJ@D9fVBMJdpzS(ZgQ`!Nd2~sS z0MiYHL#R@h$x}=Z*2g?yQ*V~X{! zPwTDUev6wc{R3IQB>Kn!s-V#8JoY7mMbXbDLxOkLMARHA!Fqj3=Y!FCy5;6!bZo}9q~J3u97ETp+6B|+v?kOMELc3u+}44qNA!MA30bIHig;{uMr z06#_lmfzCCXoDT>r~4|(&sKOxG^_r@R;}gG?o0)V0?!r@#=pJjs?gpsJRsHJ!*41H z&5aWiFsq`f#x&l>m%F`jPAa$4=a|jrgq}XlCESrZI`7#Z*xsoPn#M=0?{vP42Z|kj zf$#KOfZ{i#kF2SMsAlwfw&as&V;)|{cx=b|Ftt|(DsZdFFBp+QSl!qP`{IhjOu5L? zE`7vDf5Jr*tlj`Bb|3Pm`7O5$U*h#41tQiDij=$sXr|niywO*>ag?z`_CGS!FuEbM zHLV7%5&f7Qoya)FU6s(re!$H<7P-7!lefPOC;@W@CtJ9#5)1s&cj;#oXx^g|YPY>l9cntC3 zI}va>IVoQaKG2-ze30rORo-5rs@2-bDAq28#1KiY+rKr`$)`?1#e|uu-&$DIqID1jO!55w;Wex+w8CC_1xaDW*cC4|R~X#$!exPU z;|NK7G5)2j0Av60;@o^x*H+$0Um3kv4j{hKpqcHh2K}!( zzhhkJO{{ZTqMD*)f5}1n9cIAoeZLIuZH=s)wtk5mo#fZ%W7IASigMwp|x}W z!U-;-Fii;`mk!NYpCL4r<>N6VJl;9)cfW+8#K2)|cFC}@=%KN0IkmFMM^HRl^xH44 zozo+s9gXfuJ3&%w^U$|7_pseb@xfUVz{8BuSb6nl9aUyHgL9htbq83f+*H~^>?lCZ z3ZZZtXoEE;LZMML6_4~Ky( z)Giw$X(dL3D%PU#7(G1ELa8}+j`v(5WpR%G~?*G*4w((6(@?xO~8-!eR<6}lysw{Ymg6J7jzea687GHqIgn?kW2{U zxe^U___?5`*!N|kT!&WFW@zucsXjhVA=JO7SGupmAT>#pb=EO3D2a)qXp(uNK@=ho z^eR-UG$Bu-5RX)kxLQU14I@`n;-^raAM5*Tf5RW+vGXlL?pFf-Vn=&a`tY%D^Gq0m zN{yJc-D5c}QV#nbkI_zDE^y6}X7Uqx2iJgSP?3>rvOmlb8yFUf1J)#Zw{p+0a_b@0qc~Ge%0`A;)#P`S2Mh z-n_ODaYH{+6gxRd+GvGTiY1M|)z+t10qPr~B@~*4%$kCPm{<_%de@D1ia}N` zjh&V-)fXKw1$j8VJtOt*iqKz1szMCViy@qlNFk(ny?flID2~x4ZIA-e2{k_q8HNuy z&O{Y_o89c4XuXR#<4P%_R9hLhFd$Uai8J=sCb*NkI#DU{3u3Kqqer@v8o9eu{%r>C z`cQy`mr;*fInyPB5lJgA^hxM{_Bnh6dA!L4$;@24ZNk35y5`eg!Iei5@v(%dUhvk< z<>k{3v*mW84N4G7R9^ZR{>tU2Y*6l%DUvGVotq7X%HWtxAo%E<@c`v2dV+PbAMq;v zoM-`6^6NRg>w1fJfo}^(_H&!VQ|=dLbZy)N-6kEK^+M}KFLHG2T1YSi13Q@;{D}Bt zQ(eBM0oQIAm*CP*-F(juI%W8>fM3BgV&geIJiLf*x7XyI>cW+DiTFY&0cQ+qpd~Rb z8dZGWDDUPAaWY1$mD;ZUEqF=-P}xZGCZZ1LQRTmP%q;UpL$f8ir;UiUX=FXubu@X4I>{56mRWdF(rw|A zEFZY=(Gc4i4Zm}n*Gj#-<~t)fp~6W6E4DzYYMZqD6kEP1z+n_h-s`JDmbh zSpsaL(GtVFAS|YImyc&rQP3S8+NBc>alrAE1hzYZ@tU+M_I$fOj% zGzzkoOA!Dw<%$<0jCOR=J7knS>CUSfsWdqNAC6wtbAE@>-d%yYErAZfZl#pXitzhldIx%#Jwh){rv$ za4JLscRq?E+`kRL({>}q0f$Wu*DCIXauQwx^;`z%jD_f>>02DHSrWRSsU^UiAS*$C zLU3cW7$?1AF2KP?*(0T-xs|{3)lc=0U<*SQ2N7gtBFhe5x(SeD5aXDQoGEMvh8T|4EP4a-INhix{&k@MI z5RQC<5N(zerxTi(xSxJb(M$h~Y#hG3Ji3Q7lW#;&+Wt9d-C zk5Lt@aSI%~;OKIG?PRj_THD}hnK+~X{Y=9MxF6f3s|ym0{)E+I@u2YV`xztALIHG+ z{k`Z~Y4cS0dr@9=I{e}@f=irdFkS?SW9biud3pH;j~nXgWr9N{2cJG=POq1p+iubM zEpjPX#*>76Wd(Iz5n}oa7_ZI^><_qywyeZR{Q0g!xB*$U^~Y!Jw@j?K;sXIu+GV7? zIh2DF^u|>TF#Hr5g{G3?3}at98gjq*X0=kZwY6Yn05Bqgx09qtB({E6aot$0Ma_(H zMIDtjPv1^XQMwBMeA#lRWdxuyTw7r%1vmhX;k6#|J6PXs`}u2~;N;bWrPXA#0t9y= z60T%#!E?FB<==NXGuUii5J~5y+6B)92hFzfl5!Izp5n7mO0^?jC>STcC;EW!$LnkHPbErBFW z4+01ypCXL<_9s*F1j1Tcc^-X5Rsz>G;mZgN9J|4Lw)c>DGxCl~PgXu)8sh0(P`Drc zJjSc)k^VGJP2ezzaU2nzFRyp`b4*g@1xl{iBM($UsfKxw95`4FdrW!EdCO*$P7X}J z3h91AWkp^NUgO#bF3A>zBw{n^f^ghdM8%k^m*VMT4E?>q*h;grUkuI>%*nOnuyKU* zVq6v6+YpW_>m7%E=YeqyN{cGJp$4^K2D2YPxkN57B(a$=*U@IG)cbM@K=`2`;FzYT zHQ>Oo1=w0CL@wR~e%62pZ1Zy3v6qPf|Ct>~;fqbLy#Z~Bsj(yCkVj8tSi^vU568Yk z9IG&7-Eq+!AhmY5Fw?N5Hlyl0tE${`*Y{rpK`R&bFjJv~T80HJIhmus8@UoW#v7FK1 z)Bg`i=ds+Z76jo3VnI$za?XgfBMXspc>0U~TjiC@7J`}S?oS*Yn!Ns80geh;Zf=R| zp3vZ*o#SV~7oj3cDBy)8X15`%%}0xTI1D6eVm_taO=b0J@Qv_|3LBD^*M0@QQTgxt(E|OwlRSJDhUOmd!x2#!Hn}=xbw4Y_*~?g4 zreN?z-?&J$1@mh&8dr3zZ}dC=nlF>j0@w9$0g~fN_Re;XOG}%@_GB zy)a4@wSSRd#TO8fVZwidHJn146TL8bEzo zcPB9TF*cQbm3I177W@Wrk$On=eHXqy%>BBNIQ&qBgYG&ik}~6w+QB`>NE4}r|Or&I6JbkT5y(fyn#SgFetBUuW6tC&^2)hg~N3g z$H8u5OR<}Jg=$SLZ}p7td0ADTsQ@l>CilkFdh?MqZ;~J^)nmePsW+#^zT$}F*eIK( zg_!_gc{V=KnKftS0YdcGhZEzqP@5NHIxtT;2inEXJP-ar)IrKJNpI&9($a6&i%s64 zK_WwWi#tIxaNv3NR?9Lb&+tM+JKxGc94G`l_XU;{LG;=N0K#f(@_Y@2QuuAn+VITUBE9%F z)X$bTh%iRDzY_TkT;M}pHJ2@5{dk12+M4g3`VjTnS#QvA@s(7^)rb@5Lm0+r`#~3c z0wt;hs<);Hfqkl%G+B@8I_o{=*oDUmR9blUQG7jorqgBU+T%8~5t>ak9@y30Q{saI z+UkjS*uB%?(Px7|=>CAvZ~q`(NhDY)weeFz{Z{Kw^5t?s65$_BR`Pl^aGW~*4-P7{ zgGEMQSiG<|iul5C^_ShF)TPg=k*^Nf(2C+5bDd-!{FT9o|RX0*o>X|on+_2G) zWPPZ_o5$sfJb|!Wy7b2Bbx>V4qU09gz-NBQRKLY05mc?g_}`1OzGUkA+U{3~uNrf( zZ&cLW{R3g57HtMDpj~3OdLez)C=KkS1L?R{T&w3nrd~X04lm$SbGO*j0H2{`lV+5< z#A2nVJO#C{6XkBnHxuJ6JDm!WYhk*0g`u?p{Cf@~yR;OgFJ*dR^P}+CoWKJ5%!Uzu zbcaFF$rgbX?&Qg9%im|7C7&1TG6Lbjr&X+)eBhU1H|o>rK~9O=-FuqP<~(t@B0wpw zHwaH$tN%4w8nioU^NH8fsUap7oy00Zh_?`KAp-9mi^+xC>ObNS7o%s-qXJ7B;cJmp?-crV+6TMy&~%8LRO-@bAizBZ!I zwg~&_m*_pZGCe}}5~Lr_F=&wp9A+J_#OCu&kc%3vqC(bm(~_wzqp32@w6gn^?bbyd zmdRL}pN-&3uAvhY_uh2^gsutlxN_4)ZTfP6a)Bm`)OGgmk8vPU&@d5`$W?2J#fX@kete3zwhr=SSh&c1T*@Jx2MWkP`B}m#Fu})YpVT#Mv=+ zneg9_00Y?=IOULdGr{yJGlSg=Vm)Vw0qwvhWJxuifUY0qz2`_Q81D@GOeZ`ShtiGq z$Dz86Vj-0xt!v3}2giKt)Fz4Tsa%GWD0yk(Ho`jz;bsFf?em!iZQoxnPf=gZSDC`f z_)?-f{c&v7j<-1PBlvw2!PPs-=w)+P=imWW!m|wp2&W950mwOvggQu#!p&Kt4@S!c zNJG=SP@B}7f(N)#mTmQXSV2@=xW@n&sjQhUZXE-5cUq_^`zbj@G>8$=Ne;2E2w-D?OTzTO0&eu z_hyD^{+k4;T*7u#s+hvjun=i{RLzHM1c5=d3ZqTthsN&HOb$J8F(Mj5jxHz}`Fsm6 zq24sJx6z-5vG<^Ez%enE_u};^X%+9>P1G?Ef-`Z0IX#4<(>krJsw}nXq_t1_9o)6` z9*aDN8e)~qck#3}oFxf29#9W>Zm%tYQWz6N$o>c#`q*z!H-la%exsRl7J0U7l%hJp zLY$f)p5In&jb`I8rl*8M1K7op0yfS|5T;3d_Jo-&B6&qcs9A_@Tn*yMMXY?v8@RSb z$V#jUYYXW0WMT>)iMnyW=A3U#tq?Oat1V%uEpI^=R~rI6^A4p6tr~i|{8i)5XNj-x z)a80}h{teg#mO!x^gmj^mfkYG=N+&`_lk(IVU#I0kOw?p9J-szM{fV9?ek?dgV#_s zOw3*u(k4NGM!o&drQ!aiqi)Htw~t0Hp1(NDdLzA)R$T-6s~Yn*n#CDiPZym}u67@- z9qR4?hy0Ta*!IKR3s2A2f8zW(zDCAfVbUB*)XJ0V2V#U@5>!b~Qd4PX(k!acqp0$@ zauNwRgoLwIsO^}*#=LZ7L6-t0KIZz9L5&}BsMMq{-9)~5i=tsTS$YLyofg(d+py?+ zw7c!J885cjGPb_1qFXFDbS8&!VL@vtQTjH+xm*M^<@>wu_eAf&Y{etF^-9}VywPrx zLVXZ>P-+Ou3Zul*ay|{0%oSBI_?;Z{6nct(SOhsot}zEFsF#rZvJsC{)w-);7e3pcj>>}3A-8t|6$w{o)ZbkLiDj$eLhk!7OX zWI$>pBsWv>v(3sWFl_N!-Wc=!rYh~a>MDOg?;zCDcd>WwnC+l^TpY+mBTMar^a#aR z61=z6qCv`c>*%R3dm={nGJ&!tfWUiAZ}ucFDF5c0~$;dGt&x@F%fPn`JuxlfSET3SpFwNO*xz<|=uycTid;Z$QR z#+0$JI`~|CPwRPVscDf0J0>z0V57!DYn0Y}(-xOYR%s>LWdRX-9?%$o-uBB5RQ+5F)Ic zyOm>wo_H!h6EK#Qw`mM@(L6)yMCTLaGTZ4{VC5y0It2ZS>k|IZ7Ucp<0JwAG2tm0? zbE%l_q2c?y#Zq^4WRy-CK~<$Jmm)&)TA?VI{gkeqQ!OJglr`hP`*+{qE2S(3KFB?= zh;N^Hi?3n=LPkw{neZE@SCAygH&MVv$HH^ir>Z9bS+09bMB>8^>=E<Ty^jSYtN$itcAY z5C*eJp0ZJIW_E|}Yagf-kU$bXFUHeGY_+`?x?=Z0s<=#n|JK>`6x$Tt88231GFfGL zGDH6;w$GJ&i(C9uuEVL$voHaGQ1^&`J<&EJ+k~4I&#WIl-n^hQi*i^+uE1M4!Q0jRl=Q)h>yF)b5v-KeAen!L8hRx z(6d07{`nkyulS-MubNsKS7%0m;Gj6%a1^o%I zfB9-M`Or?~I;nwLDDeDZv=H{+LG2XOP&`!uk>OH|WfRP<&m}nLTwc3rU0sIw=|{Zu zOoHYo?Ukk7Wv>qZB#Sxim;s{r&ZAtCR80(;i0Wdhl}1Id@49)Ql1cYy5 zv^-)oCUh>o1`zoEfn_qk%53$tFi^@me9AbFVX~nplK*b|$^%e-Ex`fEOe)LO^BaR{ z&bo@lc*=~Nz|3uU>wna0!x@HNLszY{hsaJ1?`Sv#BYezUD5l*2FAH3-$nwCH7FC1L z%v0;zPTZ-cWGta7H3j6@aKnj2DVinNo2^EhAUpdml?Pvr#W;k%ez9tbS%J7aC5k#- zj*5qeHr^WMmF&@-bfrfyU9OgA6y3-|dfw=GS$UxpQIJ}hd)14ofBE|I7~(e`VUm7F z2_!9*t5*udXMTDs1zv|Ly1CO1FyHj1t1o-t@4|MjuYyH0@6l-t+t!c#eH`rfx98J+ z9is5;8g6uD?-P75n{L#pcZW`V7Kr_XP5zI!5r>+;d|2L=^VYAIoxO!mHCt-^);8sKxA{bhvL#c>}*nppuSLSsiNSgBWeE^Bs9|)=#PUVnUm&MiL2bbOC-HHDj1B=(K&<)oZ#hLgEZ~CL;J# z3sNwDjlmlQtm@u9W_Lw(%X1)(2y30nq*+`?no zCYJO|ynj;o1~efb(^f!+udAt0=Q%&;YbVoUS3lV^JJc|zFk(96R4+SKpzqMeI3nGj zDtjII4nqf=vG{!137yZ~x83dUYyAhxCkK22GUm%QLW0U|mz2hs&{HC)Eq%Q`Vdx&7 zc!yohc8?3p0ztS&ECP$jDh#bL@N-^t6${7;pp`3y* z&zPf`L2%0DtqDopzP(JcuD>nGRFxTS{184@>w4a@-?TaKQq-FlUj%&SmjrMJW9^<_ zCLTlgMT#-=wQ3ygF@F(3E`&Y1GS`bWiuL0}NI&aQ)xVj)6P7$Hj7abnqy0Q3-&|Z4 z9Ko)it)vTVJTnKWeo?`=6A+O06rHoymDSzVwf$vu7zMZQQ-)6}&K`$Fn6<@WllkPP z99o+Zq>j;DMA6@ahr8}hC0+q+U;0Ejl&N-Aodi_R5Ge$z_15C1mbLgbKOJLR7&~BU z4}Oyf-z%w6uCM0E%F{%^Py#Mm-3Mx-EEJ{J34~MqK2s<}Ph%Ig`o@STgrx_iDd1xdvN3JH8B$w&^V}T*-(2*&R<_(l};>3 z&h#7PHSN5V>!F9rh{v(DE-Nz)kCPE|GH}xB{w4`6KYTo{_|j^jeR`H(^ei=7e>f#a z<9R|^cwB_|ng7HG6)htW{+(;kCHt$t((y{rl=EM9@AIHr&&= z>HwW;P1OVAZ#j>E6qD)mI%zge2DqOekhWh<79P1gO@BN0RsB^~KFyf7vGTRj^G_0o zA>$?6-|N8t*52pL{*f5d6oVnqmO2(>jyhcG7ku!p))SUcdNI29-(@^c7YkX-HsQMT zPI3_rS`tal4f3{`Gc#lg2yO@^7(}I!NO7|EFA{)YHoRXS-m920EU5~^QF5Lv@zfRzTkr!)vw$Q5a zBAm9<{U(_;1h{!aLNcA|rXv;E?oOp5VU_(Y;Xf-zhfv6wh4w}Z4{pD%h0@vU|ZF!4&+FKL~4VfMR1${;Aq-sYZ;? zbf`q+$-I4Izxy14Hc)9Heh_kwieRHbt1**)0PqKgnNFcUGf+7bB1oaD`1qABkq7{;+c)9SV-)= zV`ddd(L&z#(Ti3v{apg5ebo-q`?jVG>;2>Aix_t6(?h!hvVe4*(CtpSIC^5dpvoK4 z-{)3X_)uQhCn;W*HqRllK@uw@_QPo#`^XX}(FcyPm(gn7U^!D*!6nXN9aBuYKu>%4 znbuSf$?w%&Cj2sJH%H-dMws&e{k?JzRQ$vVJ7TE>%MNdVCv?)NQV+zZthzo!kAa-; zH}-1`=ACLJrhGA+PKdU?YV$d_@R0dt&q)rLrftAkI!<(bQ&OQHpUWViiug{)Z&S08 zn+|7LmD7uXKB)1nW1eSV`r~g;)y$KY&}W>uVz#vMs!ha5i$Q!!5}2r2fu5k~17xI! zO5?%soJzq3;1euBMr$(HuRZKr={i{T*j{Cafv!%G+zCUCeP+RMvKOcm%IRl~&$u1U z9qQD&?oxg)in_`m!lZ4yBJ8%;*Rx@1q!0dU-Somc9AdmxfkKoF;Tohrl*;LZ?Pp$Gx|gU^<(scAmD@vJ z;=tfNrz*@g%Ov1v*MM9daF$t(6$4|z|JiQwEC zKXQFX+K{3f^HoD+{42uxVbO!O@*lupau>)?RFAsS=0$^cwqF7)#-HJ9!%w;{GLe<-a8ir#b>ew3^T?X z$6w>cd1Txf6ljs)IXT--xko62h;p-wtQ`UCdt8PsBOO!`fI2B zigLFjYaOOy8c3CEj&wd4Cl8Y`3n%Lp+pUP(&3}8IazKwQdbH)620k2LCJgrQYNk~H zj?rahPl>EaX}Swi!$OXLhGShBQ~6fZf>ABik7DKz8D@Y&?RV@`O_6P1j}yl~9WtNlBL+`p^)am{*T3fc<-%W#~&dnpEj)rcdK*=E-ItQe}N@|yxJkSFB zJ?<=!hYd2DDtE*j7AuXOU<6Q3pNznzdEE1ycA+H-19)EkOA5}{=6PKtrcF!M`;@=U zHd`j|gH5NiNdrj?^=cAN7VgnJ@(ODO*l^lL0_fb*WYHDAP`jf;ksi-LZs>mgJOaIA z1{tc@qn~{aCO>ha>|(B{fZpt^&c!Fca*pHedI<>Q8_vOLZ5{G!wB3vlb#7 zw-~JH^1%dtq5ih5dPxpamSh3f*{<$M6dI2(J(897u%cTMF^F8D^13 z1<Etf z^&4{50?$q8+wBWRIY;C z7`6*h7RvB>NMraw*Jia?<(Ep6fZC_Kj77QR)zaB&ROI3eiBmzMd&1T2zEZ!iNZf7; z#bNHCWPd3YLWgB_%3`=5XZ5<(FeYy?rj`#v_zteb=#5LsV ziEu=##GuaSc%`m!qz#0^;ad8%y`5G}0GV<=Im6Ggv6ybA981_n3^xsNp|WpG=Z)jK z6jF4@()numsJz@2$D7N=M3+)L{c@O9a+MO`A&f6B2|rlXUacy0h0OWP)UK5EsS;9x z7jzV_is zqxX9lK38}iImA31|5k3i37O~dHP|pHzes`*RcyeKo@c2yz42~SCLDh8#FkCrI=+2>+;;u*;oD6fca{sbR}D^j z|2vc;r@82|r^07}(@5t*0=#t%KjKaYeAha;54jj&Pvf{C`lY`d14Z+`6+KIijT;&1 z^w)!f1}r>_RXFH?ubn+*#vmOGI}4+sa=C-{1*g%GVQYYY)8#lxRaKQQLjYUkZ8Fs!>$r3I~O-eWb`Y$%@V+4a_Dn zU6@`C5gtU-FG)KmL0FC31p^`czHK9X;$aLB=k@(>qFQ1dx+S$$JDU?;7^=hX8Z3;n znDnIKVY>|A<+aR*Tb2qtbk_7c{V8Esg9>ETOUsM^y?#Bz>Ix^EGOab{mLIz@#1@7t zfsHQVk72)WY<9Z3xlT~~>n(GnY2%B`z^y`FP)pDHeS{5?I>+7#+b_ApuUw~seN6BLj6NCzGl&QLe!+# zm8CZV{F*T3wjURGUwE!G0}Pp`$vS9h%VZPj#cYgKLu8JPSQsaYwA{kz72xXkPB1kL zCGzXfFGg#%mfh)^GCPP$E8rJ-NN?ZO>2C@RtXFiPxJOr=y7A7HShw~V;kG|)@1g1S z>1PK>1O?d`d^c%WzbUn$C-AvIn_QrIaH((y9_4k?Uzw&hXlil?;FeWw{z?A`53UnDiURqZ@9aN>`O#!QUJ*4z7$WCkl=i1`iEm)5%kdmIw0 ziuN?O&Wm5vQHl;5ZB7#&ZwOl4e#5ZQ58aPW)~gNR>0B6g|1p{6JJb4NLe!{1Zb#r; zA}^k}N!S=vReiOkDw2?Ms%ZCHFw1|8Z@mEMGA0{?Y%ktzX5yxRTc*MBDLoi>vWj^) z_W2Y{7fvy}#f$!cPNq+YPxf~0yrB9tqj$#O@5D=6AvN&~&V-A+q+ReW6q!GJhi%#Q z+ixUp=yw?{0&fO4Qc*w`K%vE;+KURDyJL=STkCJ_i^BpNw7}o6Jhcdgz*njVsBBLwC=VooEEc%P_@Q&UkV|2xse@ z{o$lPr@h!$?ytuyd@ga+@wlcFgO3b*#ktUgu(Z7+g+eYhI^LV@-@41H*@`dOM?1*h z1>YAng?+wNe|_TM+?MiniK_f0bqn3md|X{(=r=S5-)UI12AGX}t7s>i)6XE9@i$vF z+4W;n~vU8Im# z{3G8x9F0hq-xX(@$=ck5%zkBRG|#K9B(8j8mWL_A+Cn-=j$8a1VRB?cihv1?ANCi1 zGGB9kEO)H9NnPotCsIMF6MAhg<4tqGy$tHxtrl@HXphiF@egiH^mEZmT>0X*^k}}2 z=92huNf6`?uT~chOM7?`9!Q5+Dh^oq7%YoojOip%yMAp&)wk+CY1`h2us>ucZXLx2 zul7&*qxhREo8U3PBTHlJyn2Vn{dCmmroT;^6spTDahLpgCv@ln;zw!gpDyyq>g=3o z5^$rDzNuen)nfiyVsc$5i=!l_v^6Zo=JM~iwe?+=ODnl6bItPg>?cWqZ#oXR>Bt_E zs1A>Xh7Q@$!qLqm&kn7i9@X4W-OO%KRB4IMH9#47>x&>HG{kss^K*-sB(<6~rf6i|E>o)!A|`rsXur%JY#tWbL%dNc0`RViku2KcWX&NOO-uR7wrb&W{BVr0IlX|U6Pnf)>)jJb6hP_J@$ECijBdYxB z&2Um7K}ZwkoYbQLkVsK;R-9H}U0Y0{U5#^X`a%jj+E5+a)8yDx!Pq)e|0uRTDXzcq zA3SzvtqKDXCn-c?oX_`ebW|0VBLllU5I6irwhr-+`+e*MSG`(tr<%uI<(*|J!-#>$ zMU#DwhACb?c8#(fV@ujjbB!3%I9^lqG+b3==?fmv?i*m523KLHoWmMNhwYQ;Qcj3U zo49*s`sJnjf!#dp<88%qL+iYyl7F2>M16Rl2*>l3WE{65CjCJU;z{$BZ)OP}Is?*B z-A5YLH=3zmF1J76PmGhV%d`vF2#0;Mt$ZTDno7{glVaOK{^blu!8K` zQ8-pXZft=IE)DlqYzu9_Qw#Zaw4PAVx#Wu-#b6C{6)}oocZ&M^&}TMmUkry$i|Ix^ zr>No!65lJsH`L>_-)OOx4}1x#lf$`>Y@q+4%ku_ft&v0gi3C^^hLwCVsQCcmdbH}T zKT8v&Qkob<7PmSj>+*~%&O1w*Xth3WL@#w~wq4gx>4K%Ytz7W~lE3FTOox8o+p!o8 zUemvj1MP60_5cynuSh1Jj=r5$qG;ijv%xQ)t&mbIhRNAh6qzlqx#E1CrbR6s^Veby zh{c9uIA}w-&AaO4bW=s~Z?ANLnxLwfH*G1|Hq;R@COmN&m!!JZQ|-QBVn2YgxQ4v^ z^uek8dX)C@|K~fD91x*bNYt>dpaOx6ko;?IjM8XAdT@M{m3TeunKwIf&x~ib1FQMq zW_N{JYhRJX41=LrZ}TI+1J7aN$x*ljO58rlRds1+yHL8OlD7U^kHzlT0cT$mn6=M4 zmwcF@Rz7jKrvXBw1qjE~_$JDSZmSIS3!OSzHSEa@&+h|v!O_G`D)7@vCpdMewo6D4 z?*SpCmx$q?U$wh;DRiw&gZCqD8L>dJI)1wN^IOD8u}#3q4w4a;-gYY&A9%~0EYFh{Ek(PazTA}$AJ)em(1 zd^?Mh%OGANIIqc<>Ha6$>t=Hdum_AVL!2~L>iOt9n<`c!M)Lm)R; z$wjBURt?vACme~<$8vtMh=Fr0Cl91X4a*`=lWAfedMpiwBP8xyiUSb0@Wzfr{V-wP zkp-1E((wfi?&KOQQHO3MM2l~WzH~3Q#k$BS%JwIn7x365(>_rB7&erh`neFFJ@T(e0X4!KxDFSO_+n4aI2>=aNdqck#ThMx z-ejN$PyA(n0SgH%0q?K!My$rd*RWn6(n^@DUMz$%w3JrY>=)?KUA|a5viE(Q!QP_; zjQwr z=$JD6#MIR2-}h(mNiIkek)c09<);aImi&t*_}=d^BqHFCs*R)w1$#Qaq@jEnWvx%yMf<~BtaSG0Qgse%oK&!4>UH_OUETYMMQplciTzkb_-~(xFe^WjbBMd zl!Vkoqg}UY3)LGPbCU3vM|LS@|4}?|Vsb)TK_LH`be-vEm=u2I>@}ziEXWcSL=K+r zZrrB)tyAa1X_b-(#>s^^<465`w_((DuJA%{^j+IGzqZ3HDP|3p+9x5lVc{xtAjnO{nfnc!RIE95_z1oHiDc#!p^1t&_$vED@9sLneDQ6b)c-BjS>H5K zFblJ{WC5RoBJ$YaZNR6k-osw#GsCc|okW>4jq|rW)a-{>G00CET^NBt*#}bx#NhiR zqaLvAKiG~y4q}9S^ph$%UI)nJppoa!wYDqAu7;81epLx+IZhrr%_R4GZk0OTvL%wE znc34zpCA2{{i7SxN=cpj+qi6=rTO!I1RhF_E_aJ_4HhLiZ>E|K3IuK>+)t+LRD2 zh9AU2>4o_roq*)N(IK`fKRg}azzPs@2awX=eZqfIG(ana>KDsyG6 zH>b(0tN!iruW?>0_}AV}EcU4thgBh59!U0_NaBj6#B;0ZHinh}ef7;Y>?jpRw~9dg z^V+6%dPo3!+et0GebZAx=$%BA-QDt^A1dk>hxo`szK0P%2KAMR&=%0(7B6ArlfMm; zPUe2mG*dH<+F|4fU54TvP3D6q=<@2N!n8cv&MOXiv3lY6LLd2qsL*{*6B{N|Ks9CF zL;|3XcA)oUPmOS&K@q;fBl%7%dAp3Bw%hwIIS2Sv$u}V@#!HEYp^Tfr7|J7=h8p88 z&t%y-h6xuq*E|_ zx%y1Y6RsiZ4+4%?wY>x%R8(?42d!8iv@O3J8Cgqaq(TnKOH1XZ1?I;ukx_fDKkqpG zLg|Ohh&P}Vkln(=$Ol+B^XXQbt{3#gUAS#GmCTdi=M!E-35h}vpJu#2Plo*T^CjoY zS%r%;R;iC|QmxO|R7$xIVcsE{HXmjRuMpffzgb96r~}ZG_EL|nPsk7n(@TcAzUS>l zRa^pJvdXu|)<1J(tN#6o11{HGDVxmF07XE$zqM=sVmdgiDzE=?%n;g@#A*uV@(a~Y zhn982%Z3d+_ikAVq*q6pW|%FBSsuHVpSlJsOgU`v0fGw*$0wsoFYDVY; zC-BX)o!VvLBS3FQYEuw1KRg1tJs~y5hvZdM07Pd>!MS0UORJ(!3gi)Zq>K&oe-EP2 z-Y^~_djOetY$ic{JZQVsafasPym*m)gx|;tp=K;6uo7D*H#o|NV4(29h&v&WbT0?L>d;bUCo*0R}}aO?4v zZbpRd_(w{n8O4`mcyS3EqnTUIjlf}num`CXuhb9UG-pD959puf&ekU9EdSfBAW}Oo zj`G@lvE|>hgxaD}j=(6knW1i$x>JO*lZk}F0YdQ1>FnwrOWTYbA}k)Xjxy#i(E-6KaC#>X}2JM52*XTNva`mc4$90_wzBqust>* z^EUr7Y&5Wue1FOZ!oKq_{TZJG6%%Qh%Hm_sK0Tt=W8w2Yi^A4^Ly>Ll3|!Hwj05GJ z#shrY$Y2NEvYb2+?x}ZO(OItcVxe0Z#nPCSIzHX={c)~XU=B`GIJUlO#|Ujz(O6k6 zMc%gyxSFc1w}d&`*M`lTv$Uo#S^&Wg!dvz2NC$&oss`0 z!^}3for_6yF^#2n%`&tJ4F{L~BOIj^uwsaBLJ$Cz#fs`L2lLCwM11w1{BoifLu89Q z7y_LA%h-+~kG{+xRWF+r>|C!6mkajtA4g}gB`FX@(GOyQ+p=(n!eNI~xZBqcJ*zoA zEd`m8FYZNoWLoXaTkJ4OZQamX&j-JOLvMEJYacsK#Fqz=Ee+Ntn_9dq0=;sbI&0X5 z7*hFZaYHgccC(zw1xIRM7fqio1U z#Jx;L=fNsE@jyndX;g1^UqTVcf6~dk;r{+=-PEiIJ&5y9HdIP&!(Y)`wa@+>uNN}K zw1rA32P4L40`Gn}@5FLwhKXCXU$-;w8(as{;zfWlKv1fZEhOzvfiJu?C3VVswo=?E~bpiD1c1)X2r8R#~AGiU6@ugFS+z=tln3?#|vWopI zjKk)J##A7wUS?2f5RxqtiZ_#KJFjBsWnAk#KNi!K?&^E~Uac_?7N`@ag4!QZ*}p}H zX16c;5p(uTPo`V!w#b15snSOzaU9!E^YD=Fm}I`b_ZgF56?gS%Y~{xJ{iew@jRet+ zze$~vPE?-Gi}IYxQlojzR!x2n^}d5+$zx>X+B$pbhPkrtrhp3x$YL86G~M{T1Jj%x zsIc?UfX{AQ7yP#Ph4}!7=|IfLUF=(qRm;$9Zop~>a^do(G4(Amgq-y%jH zvzO}Ov5NTEqtA?(Im(%zA4aQrth<8>?z<#DqWb;m5!gpSeRGHI37|zsnbw}gLg`Un1E-A(e&>Gxpm(hCRMu7)Lxbw5w{1R8pCS5c#6>IF6PKd~@Q};tm4q8cS_T~dd9n&+eYxk<-`sN$%&cFWR z@bK2|xaBSsZ3K8YBfz^ow99-QD5b(sk)?%IksFb_H4hOd)|iD7_Qg>-bI=6~@HA#j z8cclKTM$zp1XRH(%NnaTsD3?x6FLMUj|k)&0Vr9=FKID3)G%2c3o<(}C_B9}$MW!K z79*)dKBg<2zP-@!lx3fW#ozrOBNWg8pQw4{xz%Y{(}0-Oci-WHr$ZN!n>TzC@C zNeZw6%Yzvn>hO1XWZz!(THgg{vCMpmYbm-9R5b5O?-#H-JlZ!crH3r<)Z>fs0ahC8`PdQ@-qqKfg#waB-IXH_xU z_yXJK&-QGQHlZ2nadA4Kv8kZQP9We5Gj=3V~+TM8a7klm0qWQWct#_QN&6KHqPsq`QCGnLL*`3$zWn5JLzOH~lN zXu7!H@XPX`>dJ%N#C`WCzJc^3~LK_ML;EEvyW_{ z{80C;v?(>Xelu|^p7O-Iye^kQEG=8T6Ai22SIuF-r!^l!tOqaya`zLyyF+N0C|&** zt&)>+t7ubq{>1NuOR4|t00#yXBBu`*)QG;^u)|&jEj%iV5!b5I%9>emdFZaW1DVk)MMF7X+iBc9+j5d|aXy zQ1KOP2~Q&upi`P8{8q#)`Ooy6ceMJ62IB?)YdGtPw=O#K^kM3G5* zMKA}*Wa;o+G+8UbiKEue@o^2#ZNeZZ#pL!JI>)Sxui(juwp*DWn_mKs_rr)WR=BWM zx=og(s-NO9;d+?F9p|R$_Xv~^k^9!WbwNOv*WpwDB0{pS+1ppOn!8(KVBhR^kB)LQ z&P`(#%?2gg(pMB`3!o4;f?m8MrY(zCS&3OcX;dp+Scu9hP!`~yzid_VU=#=woSQ=6hHFoRd$aR}l zkUamjGi}?l53nRP75$IgI9=hwwSO!QKgQ#FLBER`-COvW_u;;?oj`l3rh7XIZ3 zMo$s0&-N=8Emr>C?&}s~5{g*4C5-gKV!go0uf#Pz3<6%T)tb3Jqddi!+Ly|-9hG~d z{DU=<$s+3L!nOsX36d9T!*L<5SbY^6lScRSlW*#4WzK|S19o&52}XKJ;ZwT5H1X5h zC3{hk*ybJjLV<~ZKGAC8wL6nCyUu`w<-uey|%6gt5Cf zY-|z!1WVskP1OFIV{!2ve)lU+P)(~RRE~N(WutDl@3JnQlis`!+XypEQB0C$JMLnL zX9za>{F*W2Er3(nX8Z=k%efqeuH>9cYX1!v0?Iks)K&9k2y(Azu4r(s*htn~8{8rC@0{Ep zew%JLPea*5;Up!%51gf}YkOD0Bnoo(#=3eHwO7PX#Dr>4$(ISg6qu$ALF+nO!`w0_ z(j)3Nw@NmH{IYCuMK;RkV<|}go2b7ZB%N=KDbW@<90>%6CRz8w*-2s-&yrvSU~VhK zcQ{pG`}uz1-=7|LG+s7ZZpbqyc1&Dtqh)N^ucqODs0_{MdbsJOS zWrexQk?i~uI}UXG%;j6NyHg$Qz!+!JJH3yAGJjZA6Z>< zUrM~SFSmYm@iG|dwck-3?KAlUVY#FK8LmnW}-}z4Dy{E-#-NpTb-V5 zXtuYqmzd;(5=mRtW0qNTkK?Fj8zQ9ydRmZer}5@dAZja(Ch228pw=w1t(+>;HuU%z zOxq|kZIp}tc~nS_NTYL`0%_H2D1LIJtap*(684C+!JS3nb4fhYWjV=0g+c^dx}#c5 zE|tC;UVD(nfA-L!Hiw!A1s)z0RD6rv+ksAW6Ox*7Z$6vYmAiiTi}YoZ*L}fIbB7@u zehZZQCIt0Ia_^W{oQOvipfcoWt~Kv`)-K@Ldkw`1G7M|c78~Do8M)=w-?Liu_F;*O zyk371jv!a=-&?_vx`K5trf;0%5O;DyW*Iz7R`L z*FGJtA4NxlBF+V;GU`vSN;5L29a%p=`XX|Mdw2dwCq=DG^WtpP6D~%Z1=Pe6i zSyaVJp;nsnepJb&8ZS(0U7iQL4XSqxbLAs_^+QxdB*@L|~lTJ3* z>snEmG`c_W2t0#D`Y`wfm`=bOE#`?(hsE2T$R!|gA3wJ}X<~&8n=d^GOc-QNfxOOP zby|b|_*&dj7=-VLuTvl@HTb#XQhPX@>>&=D6FBW;Uv=+=n~Qtuye7stQGy59js|m&>sdkC|c8 zVz?swZxJ!D-G4fDB?}n#bna7JfSm^ZJOs7xQ zmvfk8?}|-0)Y30Q=s=)v%IC)~GpNYjX?yW7#ro=Wn34U5(Y3^9STz0uPF%_Iuh))G zY{gVdw_yKiP3I7~Tru#E6?Ajf!^z6B2Bo#JaSVF_PZffuqi-zVq715**hbNF+xQ!9 zzpjSXtfxu(SA43b2XNHT8sgdaK?hZp*MhmY0rL2M`p0E3szk;U;c2o*XlgvaBY{Kf zvU88wienUwt?gE!w}rj^8(-JdNEp^OWaGvm`gT+SNO8C3M=lc*DVw~IeCzg&@l5*^ zG4i7tH|A8+MtNQu2)Z|l!T!6evR~q=8($`bv?jtf!<`{PvezjW_u7jvI}$Mc3_uMp zb#Uc>RPl1y6(If4F@j?~23MlcL60bR@MR67a5yQ?x&MT(ro6%}v>5m`wW73JAY~XTaJk@PIST|HTg68EE%h44SMOu>}P55 zsrhbJY(azPM?FgA#_%2NBc_2*eHW2sIfPCdNXmNHLV#kQ< zWrdW;SI$7pUYfs)M9bfccJEXS)3)lCw|r62@y-R!D~x(;%*Gr-+Ik0GJ&pCJ`E|@f zq>8T7JMECv^4nDJK7nhMvvey7pgCjl5tE6vJha)2R}`DLt70^dl}E{GBw%JUJ2~-U zK+6o4 z1pG&t2EE^bJ3oba6_i2v2)A}SBrO8N_gh*>cYqDwNzzq!5*W;1NWg41gZQI4G%T?% zvO*mPjJ{h|hJdG`v?GP%-M#;C28*XYCqw9tnI3&#&)DSB6 zCGv9dH$kN6zx|;3rlwf6DQv4gVa|JHeqO&7=NJ=9Lx+0`+E?1Sa@TL6pGNr{4D=aH zfj|^DPldP@Yla3`gx~G&9mR~7l;KONbgi=yZR%3jR+Gq3g_aZN-$4rYA0w{v|*828v#eOUljHz^F>c)!ulH_zb;X z0s^asmQQFytgU?=-UWR5#~?yG5vnT zvTm3>w?kzNZ!z=?af@6-T&u*GPh1378cSH^@CAED(*+)n-VICKGH_+0=@eExQu&e< z)l%e(FCijn*Qg%hCg=3q_p$_JY?#KN)BR<+3sl>i-|h@kLwbcE){3R_>8wz-X*{&% zA)G7zKx?W0S*WKx!eX@3UO1ZChyY8Q{zYQDC9Ow)ir7wmPxKqas9H-?9lhmu?NQg` z9HHUu%rJY&Y#Y>A9%&LbWTLVu2(Nebhqz#2_N-s@YddJR&dJL0iOm{riPWaI;v1B2tVH9hr+{c+9_(mHh$6&EoNSZW+CJZ5cYqUXy?Zick3AQqL_6k` zN@W|`fd~}2qFjcShywCZ^i{ILg6k~rlvcl3M+i3xt7J57!~xdy+MBDJh%)Sj`o69g z#KxY-1?qnTE8*#W=g}gDE|{gg1E4%jRCIDFVl-{u6e6mz&ANMj3IeHBnkCo;R-pJ( z3q*_$am+8F?#0kjV*v28w9id>EBN}6XhMDn)F&%PCMQ{W;dg33172pp+?77`FN4Rv zS6KR8`9vGSH=ro=)o0Hckq|06Fz24B!0PJm7M)I8Os|{ z`Jo7C)lonQ_TBS*86MQW3rmV2=neTXfs!*bS7M+(NPQuf+357*^YYTX>7<&Bn~{Y5 zkmI}vrGP=)UM)znQ%=#yiv2;cQXyaHGIZ-eO$WMA4dfyQ1?G7kNaYbM=Y-|YULP40XRR5jO^ z9vf&ObX|lGeyd^T;G6veJ2Wz?AxXVjqM`W^L_aUBA)gV;vd%f83wX%nwiX^6R<(8zG#W)df<*2xz^Q@cWw1~bJpDr3Z$=CJ z?wjcQNF#utp0?=M%);#^L~Vccxc?n|&8J!Omxqq;WJS0wL&xSZV0R25kOrAblj^dl z2=5*}RjJZEXI4wEC*a~ee?+(O@VDRUheM>5Q(!M`YCnK&qsUuB5hrF=eQxfy7h!}k zy`c>m13c4;hI%r@)3(Be+FSC(Pr#v{6G2i-UnW>>KUM#V-VS}CjmL7Ci0{8Cl`x}t_>wVdeh$cjP=O;#ix~QnomA z&K%ESYT}892KTZuTDK{`1XU`zBQN}3Fv6R^LEg^^npiuWG5vqjvvLV5>u+{1RuITR)JsvnY<7;i22=!x2Qqnxn8*FkP8VaK;M|x*t zuSC>Twk<*%!*GO{M3=pKW%9+dedB$J51)Ov02^lRjr%zqh}4}l{B7N!Ba`CLQ%^I1 zLX~CyB+glmLDy%5sk1NXH#MpgDnoj2pPO(Wr7c&D*lg$klc4#Ak~Dv>h#;oFyRzL7 zEHYU#Yp1|1!hZW!C8EqzBQQYI;xG@Rzz3S*K#O`^9kw^i`rB)P%{_^?saZ(^n!V1O zB%l@=hE1^THt_RCp}T3=cU(yJ_k)ek^BCtYU(DN4AN9tItXy?dIB?tSHgiFvq9OPF z-c?nn&#-$y65UzW#9mkLBWAlzcwHXl&Jgj7Zlffb)iv-^0*wH3kEg3NNSF24c0z&n z?%l1A6}7p)l_6NCET^U=-Zn-A@9%XmP`7u&t$Ev1wBaG#55DzFmvyh3W$66r#yz>+8{s@0 zx0Jan;~{_1cZ6kH8>X5P0~_&a?%UoWWGWi63D9P(2n4TiuJsdH6;2kMTePxnKnnq0 zzxsW&;$znnnWLZLHpW-&wE^6fewz=XX0UgC(V!B8mW~eB2eYOSU!$q^R-5*q{`@7C zPHaq3qVUtTDJ2n4oJwl}Aj$^Oa~{eLE$(~4ZU7q0__GWmNQ`%^g5E}CqGIPI%)j`1 z+a&wrWiSmxy}$DcWo9p5N=tlV1-^HqX#sNDbV_Ui`r-C~jG4a71yPzp;_v4j&0%aH z=#gpff}2V1LZ+ckhA(d*l+VaH~J41jr3Ij`WmGm<+g8d}Y$b1b#(i=xq#vW8;l@1m0_~=Tm^|8lt0I2y1s67K5&)Dkj;A zPfnGyA);ew0IxzUd+Bzv{Zxl)?iP^JS~uVPu|N>~?orZoC$#g)Kp}2wJiqDf&bN+; z8AX3O7S{71tTimfi7CFkn%-SPl$gD12yag=syX~`$(}H1h_yk^3siEXI zXFrdLA$iyrH2Xyh{{!vi`gW+2^?xDM9-txRsgisN**3*r`+aAz&Mjc-xZo$`x)myt zl}-fz%tiV3AOc%sBP47sAK=@CY)ejH+sHCi6U`8Y`zF`JeSRI=wT@u@fBaMmaE1xt z(iKSGSTu^{mAp)q;2_;q<3_<)2UE+b_>Fv2;MiY2I<)L4dXmYu&o=T>zT0lYT*2 zbBHL(Ov>-D=PH;O-wF3M7d5%|{>%y4(Z=Rp;e93-FAh)ND$&HaCaBv@WI(pLEeJ)j z&k`6RYPA3aDJ>3P<~qpBz14Z7pkErqNoHVZBiYJtV)#67X_G4y%f7R3uN%W5vE31$ zD(XAOz42RErPV%xDJAg*)z!m7bEoM=c< zWTF*Xqc`AzH0OBUWqgL53&-Cso1_;-A(RzbS_gW@?m z;OfL>;fEe8l~3voAkC1kjaeNQLBvlP61gUx#nM$T-vOM!L3dHCTa}Rb0)KH?!+8$Y zf5L>2ftiS5LBlTI{`UPxZ{ffeP%2-C)R*qE2IN-U*%G#}$&1Mot9ImjsjWP>L9jXX z{<2eO?L)z$J0kP%3Z-HQp~ZY6ONr`tfqYa^yv^GTbbzpLG+(cDnR+pVW2=xk!xV?} zr{%O#F1JX|KK)CC4Ca43D}`Es{kLc55Gcz&AS{<<&0-qarOY$6TFM)l-U)g8(`$IhG+}E@vrnQa~Mf zyzt-_^*4h@UHO_KZ)_XrpAY-_IG)Y;YFR|q4_glB7xt)9Ya2(Z**6%%7{wL0hRS$X z{Ewr-%7@|y43giW*fJUcHH9rf!}%Y0$;mEz%fn`PXfvYJEUmf}b0Ky>TyExv-z z{MuT6-gMa{Lmc+qr*(k3cx&h5R!pCtfxBNcOC$BZ;7ma+D-`nRR(sw_8Bq?38`%wd z&-*zp<{%g^$`NBQq7~P0kwaX~kzph;5Pw~-UhQoTPaN#+?U^i!gm%||FzD7XCl|-< zwqk}f-jUXAK-`OL)J&R}@KUQ^h9{Epk-<%kYiNP6M>sRA;=B|~?zBC7tbH&~__RPT z!gulk4LbijHWg)g#EBi(_tAEW1v=Ecc3ml6nOcl4s3sfFa!&W0Y;X1~Y&ENq5m6Ow znou?vS=tss^gWGM9HpunJSY+S9Pu9`RW?V!%$%%8l^+rWw>mx-3JkC#*eH3FV$>Ebug$5!4&=n;#3 zC_N2Vn{hfarCLn*gvw;@jJhfFc3 zyFk_T7Lq-0Db6une zm40dp8}Ip^0DuErIWSe&x!kp`ZGc@PrAX9Mi-$S3{jaMfD~|%FF_-&Z3TNT&F#YWR z=lm?b5!a;bXIB-oFjSFQj?HpAs841M(Ys)6mw1&g(()2Ga#>cws5z_NAMwJsTyJ5A zzK1r~cU*$^H9_z@nDj_Hedj&&B9(n*HGvO0aC|r>SfMFGV`i7;a%8}2ojL@%zpN!% zVtCW-ITjRFq6rva$m_L8Fj^}fA)&pqLK<11?8HSd#1=%bR zycf@$bK{Hk5D|(W@I+zb{ZR|_zS9D-W3YPXPBtE7Ty8DmP2H4 zj|TNncp0Szp0o>O$Fb?{UTPXo>r|V#6SnLo{vCg#@XHbaYG!I8^dFh1P$dzN82S}c z+k3|f8_W5HLc;ojp;ZB&fFweFpclMWkzT(O;k42Pk1*f_h|bW4BSjMT2zJkiO_SM8D!b zpB-91{nytxIRd@Ca>(a)fBMGQZRdC??=wf}jR3@1kqym);p!5+>)XPTvzRNC_IGT- z7VgBg@X%YnevS;Y_1%hkDmb=%?8F$Q5?nsNvdMV@TwA3kJa%TG>fhjn#@=tbtJoP- zl^UEWLMymkA)tPKE{s?&^9nSCiia2zruL>)s}gxg;!_E}-?EPqM6Z{89r2=2HB`{+ ztUg3u7ABbmhgDSWf+plJltAvb$e8Jq4lVkwI77m7XaVA*A=uM^cC?G8d1^x|PtXNm z0;!SZAJO~X67%kvh{5i+3;@D`rS{k#oA zdv8=gfN0{Mpcj-NI@+i5x}za5A^v zX0rv0yhusqC*}P1PFD$?BTotevXBVD(R+W#K;t^)3GsKnk_OjU?Ja}GGd*Vcs(d;b z5JC8LUBM9Ao^SR=Kk3Bp{h8|-Iff~yzYI7Q^B`fzsL^J%B}Pl`x>7p=UsgC3I6z4a zK#=9BasFoCa3S@qU*70UQTaQEHp3sZ1X&fQoh^Z>>mA(X-BMUi;4@M^zCn?XU7z-xae)vyAqiiH{5^yOU>&}wpG+{?LrZtS ztNjN1ntJvPFWF}5)XneT;T^uI4`*-G(MLfe06z-n@0?OH@5v_$bgc-A{?|i~M>Uxp z#fCSdbG3sa4s+6(9_WU6eHkU=pzJ&J!8?+fT6A$3Om{h^ge>T(u@sOL!a3d5y2{cv~mp=L!evfzq9aQQ>M|fqSrJ}C8&@MEpWkts{-?Z1!ca!7KCqziw(S-@$(-+V< zh&qb`2HWus0r_=@eO8V#XR5B;;ZM6{`rhymL~LaG@;)}IW8yB@%Ey)z(cd5K>twZ3 zT4wy3wM=q(XZRatZl3H+*L92f0!l{qXuas)U|O^V$A-6dSz`SnErq|XMv&>5-U8t` zhitl-0y?Yycg=gAU;Dcp1Sge3l}|=)cUcaiV})=zyL{Vy6ZwRZBKIO=Z1DQJ)Tyx| zp%1%#5NBot#Ug%Lp$*M$Y$z(MHWpf2)xECH3|&x4pSG{t``%rMP~Gdc{5ThnVJmf* z zPe1V{9Pr57Q`a%cq`#-hS7HW()FoP!Yu(>KXm+|}8-`eYxV=&G>kmWiW(OlMvsolr;~)EfG8DS{w$(naY&;5NdZb z;`$@Bz%EA9F~WqgZiHAw*oPm<{Ah-^=fO!I1_{y3#u}&vES)P&JoY%(%{kgb$oB7A z$R5uh$>n$rcnb7FA_DM!IgZe1*d9j#K{os1ksH=d$s)eSuBdop)a__@J$RhJ09+n# z_3bUn-ojr=383V6VxzKyEe$zQs28O*)3Nn{nhs*2ZB9FZKfsHbdrP7uvtMa#y%x8y zNQ+zt5+(dM>r~X&KFa+0fs`AqP8Vd0jXTq)=Go&%yGu32%NM->mVxG0+&fc`@F{Ks z3BY+Z5tnU)*-CczyhO6LhiAG1pNY33U_j6t%`{$O0i4ce z6@8i>w*a^aWa##7XMgPz?AC9MWXq(*jacbQ;AfX-9_ktfhh$9MTa*J<@!rahexN2hH z?^LsJVBgKgxZ{U~q&fG5!z1)*p4endQCcOM`BI56hxlS?YKI2kN#alo8TXdaV zu@;Gxo+oP|xx!Uuk7H5JM-BkoVPtRO1Fs9)fpXyKE!Ux-@NVwwldrus~G#gIaRW z{^1vYmH6iN<0$`uKY9k}e#A39xvJ?}&-@ggMUwId;sNjWJM_35d&!Y`P)HgtWY%LO z(Q&oenNduWNNO|CX{sTWHAhKL-9l=Os+3h-%bMnc1UTqaOwb0>OW8kZ>%q8?WRKCgADd%C0C&O2uLTKQs9?7z#arZVMRetmI@Zcu>d0+h161{ zVm}yl;EWL<@9sj+^h3Co=13V@=hU!1LqbKU(t~EJKLC_Cr>a!Ql~|!QszXXgbRDWW z5TosUY@S1K&2rjUvD+jUBK=)px>-VW zsO-mg=BE_V#F+^%dK66l&l)|F|HwV2mD7*mkBGZMNWdgG@Z8ipUt>XGEW+>6EdFI6urQFg00XuE6yf7}E z=lDV31pK>Q5oL6D^W4%*4Ro$7L&Y_gX$Bkm>{JL4lQ~lil2|)J05MC(?eo*ylZ&SItl02~kDUpWg5Dke|kiL2`G+?^}}T{jR|ULr1e@whL8X78?EuO`d;scP08qH2ehT`<31zr#vp ztbK-W2PzMeU*Yz+Q6sz*K@RA%$SI&W{Ldi;e_Jy3Nl}ae^3D= z9`g3ABOp)eQiqR|kKdMB7jz@fP;U%lMm@!JwhP)1`e=VRKyli{gx=P*3j*%V4)enU z%{;M*s|e!?62on`!He>0gK&A0Ja;tH@aP6Xb@NpyXR@(k^q)gWXzX|23etX!MCiH3 zF7UZsv)UzOD2ZVgtCi0ZD5Q=r-^mVtaKW1kj3245FRG=Hr->%@hdgN&jtA*2-9$e? zD8Db2VO^nvp8}ydTET#~TUel$*lgb1-(5_5Y?yOnN`!XV|;d zDlODLP}9~wFYj7yN6l_UgyjKSo_y@}?Pyi{x+8sqx-_?xRd&$2iwJt+#7K_;>$bbV z5~?TH1c#pP$Tb!Hp!!P%@csslqZv}>l*u`{PRtN&SU%rImUo&z7K28smagK0_@==u1xC&B)>jKDve5L z8z)40M1&>6EC|L?U>kyP*m%b1f&9**HBQnOrIoy7K~1eLxgsuwNw&>27JGZcx2G9X z{9@)RP-S+}3#=-+;x}*nrR;@~x0nk*yyXV2!Oo-!A0|G&qG`3vLx#ZT_qU^8falabOyj?H*fy;NydXbGMG<#oYpmfPM zW@uPG^+JDa=&&TsBzfvB8!fP&L6ivVOZ#fxVX(99?#2YhNSW2oSl<@CLbm(rTB54J zJCsE#_-5GmM%Ktl;j~&=<)-nwrjv>xAvJF2;Z1~imybgV{ksl6R2e75Vv5y|1`G)z zgn35gyTZ|YRg{K`UVSu)AGlmIdZJinNcB~&8?5bV$MCa(2FZ$?nsX?6iToWuy&o8a z$%KtZh<~Mb8PT4RCnWfU8zz^!6}Ow%u=^n=Xv&D7WtcqHKGGQ=E>`c5 z(J-UdS~*3e%x^8nE&LEnkY{3T#j5@_3s8xeT1~RsJG5|>NKRorH{1mpbtD+N;5d}D znjYS;MdV;PYb;-M4I}o_jmwC1nfA+#!5C{2k>xXJg4e2MV**=!&s=yAeJvcV>G(IL zHyNB!6J)u9*s^JlQT41c*$l*bjRg`U*n)h4vH+a~r*Hn#Q*8M1H5E4Ub7NA?nXj@g z=sO3q`h z7yu0ff-Hpacg>5q;A|hhkOWh)Y@@q4U(bbj^>>_}1`N`usH2L?`hE|Zz4L6+J%ic{ zPxN;wJCLwik7jX!hC$5cj1K~x;J_b8^(O(h>32356VTzHpLvaWg9LC^D2tYDfeey< z*Pcz%wBvmy(z}@;L;St@`Y7{vkARXCPvLpJo82=vEZc}$otP2K_D!=;|9}YrJ-oem zYxs|)^H_3J*`nwNF~GZ_@WLZJGraenufJ5kH|U6}>Ig}sPVTc7CiAki%1fv_NVe95 zgKvt&8#ZW?$S1pL;d@g_(>g5671i?QoFZ%rh01|f-*$ZCD0NC#D!IPSF&(byZq{IZ zKYz=rsu#NFp5UWq&=O5PssVWp&+y9p7Qv|b7&!LD#shZ0T(2ihL~C_fiCr(m5jqW( zF9rg%~#3@yJ8 zmKK3pH5W$~DH2x3eKy?3lWeQzf7Lyo-wq?=GvjIN`E3~Y5s}dYwgS#idoVacN)}a6 z>6ekr8@mm0c)|2*g8W(1jE#PMuHFl_?!;(&LU3?L6(J`v;A&cYDW7g5Kd+YOt{M*V@} zSJ+j?eGc3KJIg@Bc@fE@JxuV+x{-GR22Llt9m4nR4AL$Z$uTw(Z0G6YrvR~r>`@Gn zA53q!n9e$F`lI5=TfsK5(S^M}km0Ln{`$4cGRE)*9^C9iP^et@F*yuMtw+m|8pOgLhT~$A@eAKYuFE9 zZ$XPH&^0>lwwA90A&AF$wa6$l2+D^f_?)l|&}rNPZ_Y<0pi{H9N4&D%Ht@G5H0d3& zV}G7HW97Y#`5vsUidpm8LtCUZ$6}vBdONKRe%3|tiqr-8h9u8$7|pE)gi;m*0>0pB znI)o2!5+Tw1pnzituM4&AIo>VfeY$$LqN)$sFnA7U#hmr1JGaE*V29mw+rk0StEx4 zHbJ?R2>Izu6V${;=E$~q`#ccG`1WLQOqdX%!k_Hrn|pq_$;2xaKOzh<2UPW+ohFvC z8sxiJD%Smdwi$)=8eJh`kw>|296Q!83rYy*w{TR7H<5h_bsFQK{92Rw*E?A*G-5eQ(?3jwgif>R@sA7)sR8!{g8##4Q7 zzCDR!mmAY8ClJ6{Y#s=`KAZ!8(8$3^BxiF0I#AF~UNyz;sqKxGI-k7U^Ft7^e(D>h zJY%&OS_DQUn5V#ZxIWq!iQ&w-K{C>`f#v7J7{YCDGn=zsLxX_|?VtFdVZ^sb->6lA zoV+f5rC^Ms;ss2-IPP4;N&xc8;_uPlEL&Bmbwuh;RY3G#J$qv%eufA~?!TP&a3GP} z!Bq2x1OS&dnZ24+LJ4m45o8-mS- z3V`zvrh!2BRW1o_KD9yj;Y$Ee)9poJE4WJS0`y8j$qY4RHKhm#|5VZs%SOA*!M#Lq zR|8ECectX4^H7W-_)iA42!$#`%<)dfG6DhB8_N`u`-XHZb3?&Zt&u;ORd6zdh%e@E zk`4AvM-66nd@-QqvNk=LVK^VY{M(>ldiidzxQ^nfXnpQp;$Wf()Fs}c$bG&~chEkMb? zXY(213MWPjzf(;w_-D$cA6l;rK1V8kZ;6+K$8rA@!APRF>7s{K5;=Kj!oaq#EKKBq zqJfnW&D%AJG?}YK{bYy`-sJD^1}ij}9+DpZ#&bGzJCyb?SXtVS=GPu)sN=BoHp9p_VP=5QY<5|Po2Ug-R zCm_H+FAv@&m6Io^Pzrk7;ct;JGvTDizzm$lufgu}LWt!Bp>0Doy@jQ5(9ljm%7QsB zWW5CSy(Z^twOh|R+Vz|3DLf}F29A+A&3QX4!BBzXIO-ow9X6e47URlTt+Q_v*#j4DhjJLntDV zUT4$rnI_wrPlv%V%#^M(nIFya;Kc+v#;lX-NO5>E#YlEMs*P~PKd$P{H&zWAoQdZf zb>0IySAH#3a!wbpnA(`qJI1oKx#rtY0Oa+!qA zmpJ%>z1ZH=kF0m>8vB9USgH-|udi@HRIKpd!Yv9{noue~6kcOQru-Usa68uZvwbxd z%QdCWsU?Wa$-Q()4BqqhDoH;nyNX1mmm%V#JLPvU=zb|dEu=PbaKj{h;g{;qfgS}C zC@1369_!$ih+AR*+HzByBn1Pu-rNRdIwrff$Sftc1o2z9 ziRapzdcF1fN>qrD>UH zZFOx_ex7G(0eF6+3mR@IKH=SK&qyNKI|8dUw97^*PuB$5xgI1YuHuM7*VC8ghovVOh9su|9*kfOh&RI4o{4wlwuOG;= zKA-Q0k$=44I*5gHdzoxdY3!sOE=AwbG?Rz`0T}DAo5<1piLdGSHjplU5Z$f=G=_uA z)?p&n2j$3bkjK~thi8S;QY`H3-RsG;wl*a$%R-4 zS>!>Azsns?NWY!>Ew3f*%-r=N+xezF0rDTZATJC9@w}7kR98^;n{^%R7zDwLD>xh7 zn^p5UuFfWi`%_F<>36qwXHYY`E4LB)?``VK^mosUH*a{58x!c!s^X$`h0bRcP?P0LcFkCoj7Xe5NiQ9Wm47vP^E``@7f-^ z&qGKA;zOPn8vlr8@a*20ZVSu(a?lM(=xM8v!2-bN;rMuI(M{hREBZZ%O>{`)JU0|k z<+=`O9CAkBWLWiYCO0~#NXC~s=lpLsVNKwF;$^&U=u!8Ke{5Dv=#YZN`}eXGsDLUV zx7W^Qx%G4Z?uE@co=gsU`DG83f1O|==E4r>k;4#FDr+*?hG;8IW3LCctY4>H9gUzs zrNs@bczxHAx)4$fCk6UCY?_T(JF~|1_2u`I{bHamF?;Ydgk`!k{_U;qe53yP;dwZ@ zrp~qtgUVmjjr008kPd9xTzoZj4I7|)93Ka)&Px__jQ?^p3_~O1aF?B*=RAwtU7M8g zG1JzAAEZ%lH(I3yHShF8zb){BxN9Z~=que*QtDB0uYT_)lD4p}-SFm-v57f|f6jRe zIFJr`BOoU9d09tMFQl)A7LI;ebe_|<5fmC;VjXrVQ*^?7@zWkZ!k?IGx5{oLNE|j0 zArUxrfSzt`%k`${j)IUycem)>oRi3k0R1LRaC9ae$n@~_6=mnn>Ok)Rnd z++5jO$@>QOiEU1i`~H^#C%gyY74f4@3(zBd((bKhE1yiFT=wJHmG(Aq%l1j>Yt=HSl}0vGT-Jeergr%NsT(@kn%kY76v4Jo4~R%4 z#if0XLwW}Sc+~svPb^MhaJFzjvQw%6BM|#@P(%Xw8itZub0ahG7%=vf5 zuqp32>ZI&4Qd+u@A37-*+I5I4?R4oe2j#$Ig@Oier|~YS%zT3rWW*{H(pa*6};gTo7OeRxWeQAH(Wm4~Q^ zTENIi1s(hj`z{Vzm>Gr3Evg?~fov{}kM1BD?B7}?4jshdAt<>a>-U?(Yno}%s(uJa z5KmzulT}DE_nHXpzCk_uP5wBdaVdv`lfyMQ($>C2tqXaqq`b5oyl6w5ioe^j=7sS^n*fSpQ9CA1@ISS zoJaNZod&Gy9g90UvecETyVv*NSwpA5_p7`m(JsR*wyxgcBzCS1e@Id?wt0zWi zy*>ZxV(Z%PRYjc!-YN;De{0VE#x=%>OCx-NoQH=N!L+eI!A+3@yH z1FhU|5~X;%-zmZ4R3VB!-6ObF~Ihc(|-hRw$AG>BbvOjwj2G$GN4Ac#MkOdX#`55;v6gEh3`f_ zHbJNMCQ=ik?3^?Gtj@Py#6HTxoB4XcaIBJ`U{=9E%cLZJdAouu> zpLMql1%K|A(Cfv24b~lHO+Ewf0RurTKX7z3m7U> zaeJuj0Ajd$|M%rAI^jw_0%I{gLmnr3AZ`$f4m$ytfTMB$*4C=0WYsP+M&Qf_Uu2JxgnneR!VkFbrY z7V6F_(b-M246=d1=1A*{wU2Z}Rl0UynELWl=jjPl%&l{Wf5Q@2gXVbx7X4{IUx?yI zH$vfR!B8DIji}uogqM0N(LekqmPf2tIh54%7|ytiB&5dCdT58Ro)6zf98Q8%WY8p_FiS=R5pOZbqcMA2i-H)VC+~{4p;h zv0YXT1U+%QMUA2kP?J|}v@ofP2T?xrUnEWq&Ylo37&;n5R{z?xWSJ!PLsfbHREHU{ zovE-|!9{<2CzCEi0_4~xeG`99KUJRB<{j2X-Lfe+QR5dBYXz&xR5UShBssWOd-HyP zOwVp|aGz%cAxEcV2NXUieF4YexyDQQINy10Z1dI3-r24CO0O2TJ$p<1ZC`71u`$&` zM4c>S=V(8Q&jduD_ufKigKWgvQSig5s2HlIxyq|Gl!ZD+YS1vI#OawxUat``pI&51vE$koO6#xU8VwhNVwliK5 z%piy{&IzU7D&&L_@v7}4w*Q@T>t7P9vwB@}oPmty$A+OUm=-PQg>|@icwF7vNJwet zZ9AqzD_H0xHKy~n2-xRw(*4T*8zsRo3s+WAv>Naqr8IG-;5_GyAN)Oxp$AVGpF(%* zId{A8D8$G#SFRD?Mw zYQn)9;4|vPWY?<_-}U zjW~3)?@ySRElGL^PUj?TWc#Fu1$={=_5S|kB~R#{TGzi&qN&O4VD6zG&X1H|;uF%% zEvaU({bwPmxp3r#zgUitf#Uf>Vd!&a%q}!6{B0uKdo&c(*@~~lEsz7Gmz2>fbeg=wqM8_id#ps7IS#F6{|LzH~RyH~;ALWuSTOKvj znVh`gk!T(uNScOVJsg~d2yKw18GZm-9XiZfx)|i#ok(Qn?pQ0twUk?h=|W2Fg`UR7 z_i|{w0T&VJ33}TJ1|Ox}L{^R$F7a1{fn9qC)p^qZx252V%gvf!$DO$5@2D;}QHC$| z&8?+Sww{=^9F>X9UPvbvi6|O&T$2EZxU#;Rc~il}siYI{>>vrS%#Knr@|#I#jKK0Cdwe0qc40J9PTJ_BdMzlF>|A+TxtLn8&V zt7%um`P{`__CZ2=p+)F8){@>C?6x)M>u4gnj&D|w8{@u~|H%~m;|YJy{M>~M$`arf zCLSqtk9o-#e^8ls{HIno(ApQ5Z)nJxR;nVlkX3R~Cp>A-pFx>sXd32b!^XGR&PdA> zi}+jZKo`Pw1uxFIH_6uC(G7Z^dsQEKju z&hQsd9Sw_kn?KA;`vy+uh`oi~NaqSrlqywq9x8wlrzcQa1m$9Uzqy9LpQ5Mq_KC|J zZy4yvgI^u_$6%$y^=nyz*-{N=D&Uw%h#L)xjH0(tmO$R9Ll^o-%lK=BaqBo3L4HeM zuVu|yVxlt7EH!AA_lTlj%i|i>l5$8yoYeK-*Sn8yJ&Z3Wdo9g0H?i7z zf8h%$H%E2gJPQRY`DK@no`Ukjh}b^=+|SIA*6P;+9`TBsCOO|(@l^%%_gS#+T%!-& zFu_ugkW!~O`54Zr21kQNcC?VIYE_kIET;coFx4fa)M+KAZl_j(5_e#$vIJgOnjd3P>5AoqlJ>+Hj8MjJF+ zD-tq-pn}=Hb(BcVPSeSus&4ZRvJ?dE1PR}pGE<0*RJ&CZVs7^o=%w7LR-A7qmkX9(_^YPYX^$t?2-ugYKsm zybAl|2bXANhNNU(9*0PsaTvljNI#wLh_pFD z{{2=djLD74L%!ugZqLgs*{~)Gqs{X1GY=prxb2NyQ83FhoKI4X4taLYj78+%v+=EP zQ4#(tx?{{r&Ztbx__@SNfM!ZHt~dbtF4Bh-w9A&a%9To)1tY%sePw4WY3D`{K*7H) z`k|dtYaQd`K>`n8MjjI8fz}-^cc}V>(U5553W?-0T~6wWgK}TX0z`-WGtL$*_OPV`fqQt z;Op4GmznV;A|)Sz&;E2AOXSo<4kgv-EyEZj(+H(60)&-h4(g4jJR?0lmlP_)hlrl0 z_;gbDcsvw@;popcru|8uT~+Hmy66ecJWmc$_aMlb>_-(iawIp!ZB}s8uo!FqzF*r5 zFJ3E}>Ml?hOhmX+6jb-Zb)vNiM4yQ0IhhZDE(Vt%0Izs`TQ7ZPl=CRK+|RMP>P!J( zP#>#&`o*xcL0f?3R2EV>> zA*i%3TnBjkrfX>WZGeMKdm+2HI}j|tDb{Zopyo;}ysd<#mxiS)y@gvsEZV8C1h=Fx zAAO*=MtamQwzNrnwUlM#+*2lx+er&>ogc#J9y#VnO6)mxobS;be;*GG$^Jsc;_SH{ zKVG#CxCPV|?)&Mi0h3gMd;;=i!*m=#0u-ba6rKmtByB%TVmcw>P1wJan){Pv6=GpK zQ&?{)1*vNzAT^tJ5&syNJg??iJ{X9ys!{6aM=Dt43eXo(!!Ovu{voW;>|G%CV#8KZ zX5!~h7J5DtQ7%qy_^pOu+ z)lX9djdseANw>450l?C?Xvr{N8S_Tq=YGjnHUSNyvao~zcd@;VmJw^mEYIvopA{u>`Ls}8x#{+)rK;JjU;jgEO0R` z1jHuq&<{J4e9}{dfgJ!=DiirC`Q!Kx7l(0IHNGW%)X{C_o3p=x>2AX{@i74C z7?jM>$VQg_^9KgUX9v4(Bt|Qf3V#c~JZE>{Gz}bGc`Tn}m=P7}d5ub2vDl4Q%nc^5 z=zL}139i;16LGYBThW`B9bl7n>|ahq-y-Qd^p&OKXPDV5;f&;M#7DPp<8w2h^KgrX z)9#0M`4vx%!clyjk_Dfy!(n5AIs%66NCNYM0)fb|15sx;)sYFMS5!X}v+n%ZR|zh7 zb8I&VUon%!9W2&i@~C9A3NIBb4#C2O&l=AuoW5TBB=GfK8jh;q{#p;3Az+s6UunB=@#+wi2M-f&8@ZAiy{ z9dd(yhC~w6q0Zx`V^57I*&h}szx@C}cw?puUjchQpsjyyAZz^PPN?&Zd+MFb_!=Yu zHJ3}61t!Cm=n3wxkJZnisaA)XlaqvGWS^iWLoY>3lU&bPky6t=aObOd*^k;P)wY+q ze68O1YLQ#kE;It5>`kOu%v@~3qR9O-R|YwODI+v+QzYPx0)Ma`Ua9+JYcdCn`9Xo! z`HH^;C_c>tk;c(+M!jWiAAt=3^Rk#a)u(G4j#8mjhkJ$~9e2@s>+TLoqkrD|&PYr_ z-8PZvnx#Ps=k0s+w&9G>*Ac6_l5myM2T<0sw9g&1_a$@J*|B;eC*s zYQV!_wEoxKg%g9IdM4W5O-~ApCdpD5W@uRM)AQQ`CRmahkj3&R>B(xldZU_#?z7ih zx_>XjJS@8<(*sgL!}@!!akTm%Q^G4I7p&OdX1Ty1<>W>aWpe;-_xO8;n+-}QNheb; z%%8`n=1yA9Xdv*Mg0GCkVtv81Ol6G<1$h=Dw`5 zJ&?Nuq3*~~634mv=7;l$dUcFt(W}X`rYYhpQx$$}&+X_}z6rhaASIVZi8{`3qM5Hr z`ow*gJ!2J+0LzXA@3g2lt@8-WBu8ls46&@rlrSqmM?ZAiGRhPFP_C649toU6)E`i0 zHT(zAlGWKzek^y4x`{yNbarXd-k1`nG)iX%*7<=T3Z~aDBo{tHOf`MqBlkTo?b18RrQZ;?DJf@Y$3j19?+13 z-kT8ARbTm~5;U@#8V4g%QGAz0QfHq8(o1j1;5@4hFtg^SbcW2v;NfPlEg6)3>HN8s zk)1CcM+ZO2_htvd{==2hNBktCRe12nf$2tln!meg-mWRKz}prW^+%O&kWiZJJ;hUQ zB0)>v&j5$f-$hG|e7F-na;Qk#Jx_7+f&8e=3u%-|6&s&$tbu`RRZLdMwt2v5$twl4 zBe4-hw>f*ma6f0g1!gunUDNqP1H>isbdq9qDWaw*b$e}44o z_TFX?Crq>LPR=4Qg7S{3K~$>*Wz*FhktS-p6ugmO_yd^LA_K~4)4Kq6S#(+fg1V8w zpwVeOwRuEOd$m~-3mx(RkV=^Ri@|U(=$bLljMLrI+0YhX{-y5v1pLLt&>Cs^(x)=3HH-Z%y&`fd#} zAhr8-lQyN~rD;WZZ|H_ozaZ)x-|R`Ct;4OC_;p!)&>);gC3zmF0KoTC@6f)M&%a=|buYT7T*?m|x&ISOfgk$XO=p(}!tBhn=?T@_ZZymjEyOSQccv^* z?SOFe7cjq}vM%PTtife0OY}h^1hgm14sqaFWZ>*pu zC;seUUiXFcMqAQw?Gr6_w9$8O;UUXIjBSn2qHk|JFeOAkdvrplXSCVT^`tQ0OKp$9vnj?X6y1JWt zwJ@b~@P;%W#z!Z9KvVirFjbs1iEsZU4Cq6MJ(-rDjQF!!X!~Wh_leAECa4|qpN<#pz5AzO1VxqzIedwM5!M3~cscZufXgx*P>a*JpH7Tb? zTfKd1ydw{kfD<2!C<@VxLpcO7v-(*lD8JJ#L@Kk-*!ov7G?-rIstTvZ;?Y;AaRf)t zHTZm0VL8AHQLUNS%QqiJ$nuEnXF|k2<~eFjL0VHV_oKP(fnr%1f^thpngl`$SQfj) zDEx!%$mNSF%e{fbp*Sv6+DB!7X9IzD_?n+BsouZ@V5GSbo&0_clhqk&qS^`uFEW4V zp32*!q{kmM`T}f$oX$R(V)@@lcGy_)D|P3cfL`DtfuUYQ4rv+$R}-0ZlVwpS3>VNj~R6(s;CLTCW93W@=%7B3F&Sb-UM29ZGqXxn11t1a)x&5XB!c zl4-;8#m~@SzFZ*7JYb(#Ej<7Dbui(QhKq?6y6-tr3qD9xJ4m#JCDDiqHw}j&#TRsT zoYvE=r{{z5weZsgR01II+ZMNol8K{;+Qv9+RPX_vGWSoN??bY%00wq;Vm65O9#v9D zs*_+d!G}m-l=JwS#B#v+`7)W$08~pT_odME4b6IB4i-iLQ49C@a9L&(u2UEioN!w? zCJlQfCA<5%3?NII8>|u$bh5GV3&3<7h&OI54ew0H_6y5qgo>l@9yxiS1xoVb5snGN zGN#O4(nXsYfK~lI%tc%J$w5&Os7%H(xNz}GP06&Q{No2uV>_|eV`*u{Ul?h}=2&la z0q9%Y+^;`|1}@gW9lh);_M4IPB$>zo54t@nkRBr4(E5Bn<%jQh%d?JShfmbi zj00VQr7EyQ-QcR;jqT4fNt1Nm>Gp6`N)A^n482JWUx^Mr=dAQ>k)%IKMTRTqfW-gV zBK)Zdn`GWFviDQZQ*3XITo9>gicwMbn8G>KUt=K;ijbGLA@F&;0s6LMiAL|#z;iKU zsBI!x9xK!|tbo%Uk&VW3@ZR*^24MP|n(4FW5@t4VMMmBRcZ(3tu&3%#j>K{G!$m-f z51&i;hW!9jM376Tv>((udiik4@5~L9Typ!drY1MHCDPz^!Uo`%d-|ao$`Xq^J~!-w!;~|~tBV)ztA$ZRA>217bmnfHIVp*Pes;4hxK8hLfh<@vS=TTq z?@C|yYJ1a7{fqP{ysme6F8{$Eh07Yfk{tJ8__@;Q&j5J zJ=Sm8hIUa5`YD^vq`s~j__gEZZC~4x!@`E%1{;2^3!s15Jn+&0lKvtJha5ataq0JE z?7}Gy)svN?m^lq!2Iy0y`%fR~LP*F11FJ&{Lh^9E$9JFU^Fvb(B()Mj41~(4g57@= zo8@WJbZMAPDQYFN5Ru}taGPBui3UZjmFvm;L$ZM$J-S07OOTm4AO(i0c#)@tBn=t}JowAxcU8M{+( z5lDRdnQiG&$UJLG2`hj9Wf_4;R@UPXy29Ny>cO6n+EIt|YWs9m^3SpdGCK$$t(OAi ze)V2dxCQ2cqN7cFb8j5FYN8U+DqIJv2;BR+yBz*0pS*X4LxK;%-UU*c{j}#u{>^*x zrg{l|n<2M+T3%#Dh)~yzobhH#_=5}YlR(X=tFP{)^OKCBT(QR+ons1yjv~i#<4Pnu z(r=V7lB}h+z;k^5JY&KG-r2y5fruq(uJBgzlf z7HMQc$d3$(fia8pg5G2c2U|4EkFvJRt$nVfEIBXmXf9z2xjD#vo&haphv!*eoGdn~ zf~DWh#6=lKra5dBzbCm7a8$XI1L}PTPBU4b(n)j$Zrelqlf1VIDa&VbfQ`wL6a&vW za++ualLaLo2bIdlQo2_P%R+}feh7zsa(KrWmH;1sFTi`~_5pH~B`~0p!Fj>+ z&SqXtt*pvj;22&Lttm6!tbm6-?pethppy*D=!PZsfxPiphOqd}2JcT7KCZMB1G6;! z7{%BVMfh6-n$B!42?r_USuWIEfSgplD`sL;VLJe`IE(#iUcPM`kt;lQok5s**+=B( zZ#C^86f*AVEZ?7jJtjUUPwVyy9pJ7ew~K@OaPL`Bzq`<0MAGo(s5ZAL1UEGY z#o(BsEfo#-ZS^n7gZxvSgEFmH9;6S_T>c_o{GrWe-Q8Z;Ulo*X z6qVx7Fbh8d9@0XHHFKJs{gP$FP;Q|k!5>q&>&bjhonw-t0x{HEnZtEx1L+202Tok@ za2H2bWd1Ay`rCN3j!g8pF5QQF{$qxhq-c}74=~hy8mqO@2{cGxQ!V-Ro=28SI+F=H zYJJi9e5l-ox)F<|4^3a*?S=qE{Ae^gKJbtv$nT=v7Ab;FTwn3|(hoSU`XW7BTD(1$ z;sOoVuIR%QdGD*MLC$*K^hnte2~xeKbk~IAubQA<=SU#%&mfWMy7yw`9x1V+Q9k53 z2DlgkjFrgxd7FL4eBic9^8RHgIw!I)Tz^8h8!PknAVrosRHhPa6TTH}JD8453ap>c zbtWLR9?R!SXRZ6&XZuy>-0UZ_(KR7cL4vf*u{0^nsF_$EzuIqqngt>IU;d(RIGPh* zm&dk_J-WWmo2lqAXjsTS?ADz-ics|D@x0ZT7qe#i0MR?weoaCq6YK?g4gxAy6$R|!<$D1B&~0%bZTDLvI=Ajr_2-{`SK-|S25()z zH~=bI2q2ejg-Wp6N!4Jna>Ku^pj#-;*IxKYbIS$-cDLv}0RWKloOx`xSjwan5=`>R z%NED%{heIhdD&7x%ug`eP%tb(z6uEqC-x4nX8^72)|`mS>M0h)P!~P>kV`!1pKt$y zs7SCl-ocFnjI_XgL1!^nccqaR5hA$6~@cMb>?DQ&9-|gIggROjli`-xNPoA;A z-n@Y~5C?~+q3B#qxxe-GYr-N)I>XW~zsGdtx%g{*D<%3QpDI5}mf^*F^!ZDW&e`~n zrn6X*TZw|`2WcUurJw~ZX4r|i z6C7fR;qtZkEd?ci=!x;iEW1ax53c;ZoAayg#0xwg0}KSihm&nk#n;r6-#!oE2Sia1 z1NX@T*9Yb+wHH(QgGyJ>mOiQBf64FZBRI@{Ltq1rUKmNd9d)L7E5}w>6pg30s2=g zRaB1Dsl_-zB~}8F>j?V+G>b@C5@S;R;I;a)q+!m~y|xs>1Wc=Q;9_5V2PrfFP~-qT zDkx4=?UwPo&BND0`MD}^QCYoAfbUb(u|!3O#zV7%dIm89`c3~4Ln<%DEuJEfIzNZC_^JQNg`v#lA?UsowB{c+K$-!#IdUs9Gw&% zLz##Vpv-jq5_xE*Ee}uRRVm&W%WxQ0yHmq50SBC8jIE zAB%&w`4s^(}j%3tFYIeeN+lSt;QFVI!~| zSAoMjuJA?IaH9hus^>|mje@==NX9<9*qns?oeQmsQIsX+bmYld(_*sbWrZ6Wz@wlC zF)xTixs9>YEyBKNb<*XN252)5#F!(@0z-olr_D}Q1LQ}@4}4;F&CvUau?K8`y&J$N z>`~27!$-AiBhfPuM%UsE(L7S9pcb_f6rUk-w%nFHXjYPve)an@(16+AJ~@0nEu4@_ zR|4vEFJ3%vxG;(Sw|}v>l($PA8`8!s;_o)yOXG@eW(YM*8NK>7Kk1KeUO*Q+@$^k! zUuol~mIeL#c)1Z{#P2>`EHb_hMW6k2<1YHW?DG?-T$28-IsfN5mlGy~vw#zZ-UHYP}4 z7!)kDG=sOj_A(^z6AirJBvJkwRC;MWkFsMvM-!jWPw7MwWV+CXgZ-fA9VR{lo~bv? zZ{k49T0W~%+hTu0eA$3?me-_MLzzY^ajMg8nd^N63T{tUshe4;y0cGd;gsPl=|-YTBs>a8MJUdILLOUs=`aKY zTu2!4N0B|{C9Ne)I3ZC8gb*aY@rYaK7q6DwQM@RI-HKGTx{b27eN_l4gB()BA zDnPt5X_wv>$e9VS4E$$$;O>bL{miI6P(WbRuSOZjnMpy$%8lsD<}%w@xw$aYIUKc; z66ybJFI&R{`z#*L-F7O`ht|l9=H-jh=?)ORU9pi-lws+sunPz}BTmkvheCjJ{H9l9 z%_tX8*8gdr{)KBVDM$U=J2D{UT>O zx#=9Ri$;wQKh$?O$A0AYG^R}VB&wJ?41CC}$EE&W+`a$-K>oj%V%2dCFQxvM|g{`@Z6gC&WTeD!2}37KweAaRLWf1uNtOoC;3i?^{M8nhR>5~@L_E#( ziPb!kbf{}Bk~A0no_3p2NSdgM^)+VeCB_4hnX4}(l^uYmGlNe!3NYQ(7T5BIKgPX4 z@L^vr`-&MecLJ*mFi-mD{eaxL6AJr#tyH(qo_Z};uz|zOs19)q6xY3V`VLaM%2Jdmdchkmn)jQ-!%7CBFpA!EvswTm!#Lj z_B}DhBe>^jIpG6&vk4T4p@(n0wX|Yh*EWK&gztnD7|T(BpML0}K}4M6YT-_LF|w9!GB_)x#u@*|TWH??cgIQp1-UeLIgnHy3BN!U;E z!h4uW`g#l$W<4NQ?*Hj~bk@kG!Z_H=XZ!iyGeAC_QE}~n9=?_m`)Zlj&~=KMNMSh5MQ-0RItCgt^`uyTWw-oNLy7D zUcn}L(K>S~b&TGoAC=7&)&PifbY9KPbC_@dmuLG~?%&Q5#7>6a4?174c5B4mXOZtd zd>{|uc5oB|AoxWNQ)xN`a8y)s{E%Z0k7qEj^tT+}fpw~5#>8|*hHd#_I{K;3I53+R z;j2g*$S+pBqO;yng2XD73{hkh0E(4+G)PHhr@1j5ewdG~VHSw+V((Z=#&+(J0MUJE zqgfFUS?We7r;4hfe&;l5P}#oMTLt$UG3UP>Tx@4im-Tk{fWGrtlCT%D9%hrl{Z8X~ zjOF0d>E9-JV*N4Z&?zl11<@sgpU86Ku}4bon12WX3nVcVxxeapKpc>sq7e1BS6@iK z*)rTTZ4fz@bPGn@(^|ITsiWq!G(U3!^G$L$<>Eca0*f#F*J#t81pN8+|bbj^P%z8U9~7;3TB!*9es1KuP4@rDxD{~)McmM3JnoE zGXO)VbNY$NM!~Fn0P4T}V2wZ^CaPJ0lI2lNn0XrIu$+~suhz2V^h*N$t}FCg9X)e1 zy!={-uo#!C?yX<7o%8Hx9-5r;qfhi(y%2D=pr~#|9xdHNE@kFkY_a{E>!^|PhKR}s zlle_m)6)64NloroQ1Z!zsZWZ~HTqL@0HIKg1B^#P&@CN+?%M#{%5zp18C5p3+)mxE zdW>6#jyGP zTU+YunkEtCH%J3eOj>6ATf-j)Bc&$)1qg{?%$Y;6@37GB?M{7!VTatN80sQ+?w(XE zZ!aTlIyo;sPLB2=y%^fyB53ZcInt6TZ8sb!71k5z9y}GD_^{FmkmY)U^Cdo7U zmYUdp49@Ej&abMTwgPZ>f;DR4i9Pk5+^H!MT$*J)D#z|W=i3k1jugyW#5~E@M~X_@ zHRTH5yH~z$=J(02*i+sy3ooYh*_V^wIsgXOy5S{rOo}e#kA%VUo5U?sJ_&e zb>m|~I70RIX95*#rDEodQQ@@@vG2gc8ORuAo}U4w%E=P85N0IdWKr~EpCC^J^yq-H zIU(cji1u|AK+0~Oiq!1+?BA>L!iRey+k>}A`yvLJ!1(WhjIR(Q*6AUNInf@ZZs=yv&*Qix?(Y5eW9M+kcQu? z)Z{7O1>fu!q7;My4fkYv`e`CC!G}+G0Sin!qNf=Jult!bE9wZ38F(%1q-hSz$CEhH@#Xe%oDHrRUu09p3ep(4S=zxk|u~c zsXKfYqmJQxBshE|j89RZ1z+#vL;=KUjoOI#WWZjn z#qn!&D9)e~B_`!CAf!k$J4u1^%n>`o#&INZA4=;6?4~24H@S~lWVLgO*g&}Dgw(|iK(!kvz2+H#doH2LlLmk}CeceN;tx@)Z-Xh?{3}OABzx-aax`bH z=Z(TDq+WUF8mFoU0e^vkqrToEQ^m8W#SG(l--6EUaqHdOFflCv_niS_g@y7tvz(Co zO{}yZB`dRtcAEhXezOXOU*Ld18-Qp=i_6E$(N07YX<4fvLTE@D7#c`ajN^oK1!>I`gk@cv`8z;RtO#{ztH zlH$E}SZ?IEj0v5UR0C42QSQNL_>*LpR!%n&Heo6TkK}Yf=WQX6i_QFg+Zy`DDW-#Ps8G6U?jJRI$wg|m_IAON%eeMqNbI5O@FHLouh27VN96B${R%6F zBxXp}kJ+rYPd*{b`E%zQhxs0e*ZSVvB8C330C&MsNJTC?&wcg9Ivd$vs=k0%^K!Kn zAyzK)i6WeaugAp3tn^tle3VpW?^~uw%_ElD&e;4L^$2Nhjx`DevMAr&o~Xb}c6Uh* zU%W~Og*z;9Ts)cTPgXfkD&g7_I7Ky{uk*D_UCt$(B5oiC4`?ZX=lQZYHS{Tk$s3DA zJYVLOp#nE(6IAt!)?dOqe84@((V!pI^OScaXl>-GtyW z@=sQ@e%6`2a}11dTjwNa2>x8)OcNEt?@TYDT3S^NiBbt0@V?!nq{+{v({NTLA5Z9+ z!gZ69hg?meKX4CmeqV5vuMT1*g}gS=W_WUUWwt=6j)cI+5~sSgkPl>11WgnZ4rC=C zR{PAA#LTxTiK+z?^`g>b9&_KJo2(*=hJuTwx3AM|i^d0pD})@-sTxeffWF5@8bO`J`aAOmY}o5R_UipM9v6wdk415#^6S)#wds^Bw`{IZZ!L4;pFHb?dh!B23h z0wbp10$gTGsv0*S=%4%NaEa+t|Mn7xlE8hf@>tmHQv_S~YqjIfN5!{R>~5rW_-)JJ zd%{EG)|dthe9$yD@Q@Joj4S;*zS+^(s(|oKD{Oq-mF9l|xO)RUm3qFWs$%P@BEqrW zR#CRfw!f6c-d`!LwJnj6H%Ro)m!IBwl23hM&+yKDD>Op^sC6XXb0`hc>KpiBB@5@5 zTXoD@@_d)vF2h4 zNa@K8R9*9m;qS7f5U9UIGV0>)$;3=#ot4SgNPHmzd4e4SU%0`DbpAv=h?=)Do^-kd z@C8?WfXH59C;G<$%xSp&?6s=Ytcw0Y3*)t4mR@FOLOlB|auKdD6MxO>9ZO*B5Q7aE zx+T4+!m7AhESUkdjmB;Jb#88f^r1{$g*3AtpnY);56Z7nsF;zuUr`+mC%0?*WB~}( zbfCm*8ad-ifXqAWS#5AxP}2_Yx`@n`?iJ5mr(BRtYUZGU&Jt98K`aa>PT512)*N~( zGlUV7ls|*Y9arQ_;_jYm^M&Uz(BT( zGGt603xiYxIBn&xUepVomw{4?yQ<)}grwxncI)rVp8y)e-m`ghzbPb0JG#!-NL}X_ zbnJ;CqVa00DQ$5oiuvQ@rbzYDOk-Pbcuglr0LdG#R*8mF6`(>zSrJ-KR#?xHc02S+ zHmdtAcm%*?xgiyG9RXbK%^w+yt;-wdGV6LG?7rC&x%zkJg4*rH9cwfkRZ+oJdF$)X z6IvRTAIAMr`B!d4N(QUKXpVf3B@zRli| zU_VhI{5oF@ub~i@i$hMEll$&EJmLV4YT+qSK+ZO(8lI?EsywczR`KyNa8dZnX(fSA zUb@G)-K2&3t$;pIS!}QG&8SRfk90FX>#6pV*H{2~!;S3^S*OwacO6S9@`ZARUg z7V;~+LRm$GPA*G`go0mqYDMqQ^{bH}F1-)3F?}^*Kqs}Osk~88B9tNdbiH*rE&dZ7 z==sz(r3yKjo~QoP0)oTFriE6WWixLUNrhWiDK*GP@_z9E1X-FmcbQGX?sQM)ijU{-7%+V@^%LS@t#%~->253^^ zP3k1wxXxl*TZ3Ce;rEe#g(3C^x0;Ytmr;XQTYUTucuVlTlH5w@3|FDD=7Qzn7{UfF zN-M7B-x5+8*4#NiZBo7QT!sEx=5uqy4e;HE4PA?tIhsynPW=fm13KQ{nv;>F*&T`r ztXtXzgYLzxWxIy#F`H#Gw2G2n^3~U_sc(byXu=uIFaaHuq{)+2z{w$ z7zSf#fUBBCUYA)4A!THRnTx59UDg@6GXfTf>QW^L?l-)gS#%!4aPjNi;G8KNdc5IQ zV@KJ*YXI4VGgZnxEO^LrDNYxdOrdg?qP4M;!3sCzXN2B-&@NYoYQ={<-~^A*W3pB* z(f~PoGi&mwK>5{&reV`wy_e5cKig%0y<9-(of6@RZr4Px!Tf#$Z=r3X$tpoCt*kjLJu$d+bEjMN+iD= z3V{792)ooB9YL&@W4}Q#S{Hu>dW69L_KY4?rwLnNSPF40k9|=QmiI57jKdeY19HIe z5v89sP28n2piOO#pjqq^_?TeUG$8-Zr_Fm41DpdXuGcJp5KhLUl0Q!%@$3OJ|0K} z(92jDjpED>%|Lc$9{^hCFbl075w;^uAt87;Oxh@nfE`*t>;nLu!et0wS4r3o*%60fm)5EzxNIZ68jGEN{qDohFoRhU#4RHJ|@qU6^-*3 znWB%I>O@UHE;8E`c@7jJq$tS-Pbh%g&Mi0h$SP-}l5BzpA}Z?jK1NC{Fg3(2>*e!Q zA4rB&y{nDi*J#>Zw*dQ%bH?V_6-F5WbsXCIDRatV=^BGJaKNWJltD82tI5X~K6~Ko z)67bt|B)#*UV-rWj!W;hX1o&q^F4=upHnsby%-C^puTzLr|(AcK6L{*#UN_V$yx`Y09+B;I%ug%M>nj_--tEnn|dIL2Cx&!13Iv1$t z3n%u+d9ihXwd-xBOMWaSkH&`|icwdGa)Uc>pd9LTyYJ642E`D2A%~f{OcR3e`O9L+ zjjrUJf$#69FIB+qN080Z#)-viCmN}oNVoue%gQ%)O+EpfO9#cqVT?CmqnTcyE3>Cvk%QmC6_0x& zw*~oC=t#JZLqYE(vB72QLbuL^rtrc*(3TlZ-$aCvH-CmU9OF)=ZbqX*3ZqmNGRVe4 z7b5pt?$<5>+)8a*e*LpE@$E-P#0_W1Ub(I; zgdkZ_ni#fADH`EJG`3;&N&?X{ggesT{t8hPn>UW9dd7o^?%oC$uq!~1(JK?0x$*VM zLfb;X)bYfpD$sX~%^_Mf^F>-=3x#%B`igdHNDsJhczW=b@GZ@c-nl~nwTJhU#6rqy>qp*s+C3j z`*4Yoy9n8?AOP2KzCXsL>V9ydQH1OWU9Yq+XAl6vy!|Y@Di0 zwwT!fx=eogiIUw`$ND&MA*Utj_BN5K<8NpVUyN`ODSyDfdyQskZlnn1JI9lbsc ztjUm7r+hxS$|-?8=Kww>J&cb19?wpve*LKUO|AF?d>+PE%B+EMe;Ks${rMD8B&1tr z3@l(G)@c6L>8r(5DzJ2+hTyMxx&Y zXH==lO$l3zqylWrI(qYXHheh(cq)@KKzQswg}Tks_!YBE}5KwCa3cyz`!H z1#!xJzPX>ete5Gape6dZ(m_CO273D0C1^KD5r*&V!1vGKvlD@kAS+k%9Vx7wC69j4 zlA9c(+g^!IKg$bdSE->_)*JABG016N2|MOiD2&fmnG z*4sx-qj`|59hVNg?1HYdV!pQ{I+r%Gu7(IO3h2EkD{2f=NpjZKrCGkyunj9Zy2qqt zxfeJ@78W!YNaH%ZmiQVBeKfQ&_do}I);{8AqdA}?`@#w%V()aA~KF)QSI=7vY0+}BB|={`QUCJ@Y|FbV;}tJ zEtyv!{*nV#pP30d%eTtP)b#9&k!UtuH6hXK)!6bk;Kr-}dJ1D2_kIhnU0;K|v;dzk zi9Npn2sa}9`O42H>EiZVeZ9%=9{lOm$R$JQc@?|?2gBx01{toV9={-ZQHNAID;BkY zE8UsL%#tht`bCn$ay&ok4bAX=bKFNDT0-R7md5sr&J-|7^w);U)bQQtg9K zg;(WTTl$H?HoQ1|X=I(<&^i#2Ldb_xxNmMhj)lca=?o+`K)r3;8(n{?lH! zwxfl%J&ok@D1U-i-in(LG)KM8x6OlW(8o3DvxNwRr3+*7gNe6uj(R2W> zPNor?6TgV(Hy3@%iOqb>kX=IL9UgzC)EC@oV_XG%?;8A75FVo0v3xbF;Yc@tC({9S zukp&z3rgN7yC#?iBlcv7*QEoMb7_Nb9s@62ZALs8k2ff%yJ~ClKAQNa2@9M;oaak# zy*sDcz+JI2JM(WBgg1x`fj{|;TmZ=fOL^fO1@sADhy=?OBertbyYt=H}mTi2A zntf>cuUObO%r8y8!*Peh=->J&3)aUKxSTu4wE|k%(T*ce>JP2f{rm|k0T_NVUP{ho z?H6e3)2U{H9#f8%4?amhh7=LBVsCY^fqWV1^p*w~86Y|yEDt;6Z_HBZnjON1EW*nu zW~0BsMz?&b^C6-XKY43$Ksy{mIn3OvS1GS#GmR z57aTGpqRO4kC7SiS^pP)#O=DWbbSgNuhz_*$M6CU!+pMcK?LQNl$AD66?O!NtJEhk zgkRcAFO>KarNT80xjd;v26~fVcm?v4pKZU+Nr`gOS4gnPH~8j}DQ$fCh1Ofar8l8| zpNZ_-h)-DUd|)`BlnJwjY_f`rEk6dg7Gfc(LqACqqn+^4#T7kt}m#g;r}!oG=1YmjE(ifW1N9wj_8l zP45um)4h7Kz@*lZ$}b$i=47fVYIvR_?uY!E1IYe(VBc^8TT`rXmv(vX$Zx2_tw75J z3vzrAse`<2?37q3HmKG0I^uAe9F1PtFh5~jPp3kkX?h*NB1eYrY$f^EBS0fbyZP9^ z*^g!=O9Q2JF;Dy@AEUBJPFf11ogWAjw)TT4{Aga2$S@1~daOSvj*QQMRZM*HeT$Wl zceo%z$FFwYaLwqV2ue&Tv69wU)jojuX*B!EX)c;3Qwm|l2>GAx4dStx1qOI|3oHv} zkWYl1xc5SL2Mh*uBW7{y=~ZlB-!D0b%>7l18Q&}U>@XgMG@07IRlO&7JokhQqGS03 z)NA`F8R!c%Mbaq)v53bq{uD?=$=O2K?w0G^_C<$gI#r4-GTI9crOfe;?XthJM5_+$7e3) zW@9vn&)TuNq4^9q`aRUsJ!d_AwF{weUntp|5B-tDJ}JLwW1EF%d^D0gesQ)Zh}DV^ zDpySaZKdGJlUGDH968FPmAm~gnI&2=H_MszKe2qWhM-cvcSbw$+o5de$$ z>t{=F$YCjDJO`S&G2H9Y5&cDEHfaV*+VG>uWB5`)8IP%-Mi6;ha-T$V4|B4qaB)jC zPGUG@D?)FOp>@Jzu(15Md=|?aebE0qD^>cGaQH!t8DF|hy%ah|qqBG|11qJoTc3J! zo#m(my&sRlB9$8< zUF|y_V|>o`AGX`eOu3Kt{pyP~Kh8O?3v?eQfD=*9O?P7|s2*zDW^)%VAa5#vobUDy z`!|NlA)-IRWMD5=_vA4>SydM+_@Eh;@imY`FR6=AiiWj4z!c<*>Ny>fp^_-yTF_Tx`wnb8}#K5v2hCo?-cBSF+!B z9;(zXxA-FZ^Jb|zJ$%{z5YC~m==wLKk9l} z^fJlcl`eaX^hnv=_Thp`eoi7qTH4>R65RLo=RLmO_KLGNjt<|{LH!)2%xE1J40gjS z&v6(}gJ3*`E8Jh0h$EF;OV`EI!2xTB#Sza-Pz((=AoRNu25UZkJrVl1dw0a=T@6P1 z$~@-^voewQJLoJ$vhb#O z9ALp@Ve@JSenO32ixH-%mHK<@JEndX40Yx^B?w8c)X}q@Y)>MVEon9B{ck|FANd$k zqPEn>d`1_eS-r?67DGEaV7pT zqWtom(=@Annn{>5L__;Qkx1B#luNyWe1KzDm53mfS%e)LNvhL3nz2nuU#nRCdVBHN zP``v~Y-DSdCc|S>c_SiPSIP5sR3ko2N3FImI8{>DXtr@JYR)crkbDPrY<%i%nmDJj`G5+ypQU}hB)-?Q2nbr!% zy1t!EYtSB^P+m?&%k^{dC=?wR`D1|U8}CG)GTiTzGTUxAn-Pi{*uZB#mB@HwnzGY{ zc?@bq;^%8KZ~`3OOQJe$O3b&f*%NuXYyM6258kJ&=062e&>fsk+93E|7WJ+tHWQbHzdBT@ih5WUlZ`LI+k5bE$&Oc1M`OTJc8z~TS z#I-90%7=WTjN}I#Y4&sB>Hp6CFC&J!%TR$6fFRSyn@=Lv{iN@?4j^%&kc{!xfv8Px z%a}en=j$|A4@!b}Dx0P_o0dydAeTG5V-htBWa^(0CJ&NBrQ^9)DJ(l#X-a;7CsHR~ z*yx??W^fKqw3-T!N;k48%iA!W%g4vw5kJBTH}&55yUH)K(79PI2F1Inul5q7I=>wPD5l)qR-nR4G+JzhgUqWluDa$IHm{`tv}xaz$eHQ?WMV9L`xW*B2>sXRXH6(?I@ zB7D3*L?~;O8Gcl#dw@D{I_CI$3*&`>PVAwje2pLvh&%{lKco~}VTNL4^xfbTXyp8& zq8M^SrNQ5o(?L3|D^qh-vHx%wpk=uV6xnKLb2saO+kI5$4S}*m5m!UIvmCAksewiQ zO?gOxYRyifxcj)EB`(#u*%!_FqIvhaSPxab4xnTJb3o0>j zhz}I%pt3P0SyWyPjWY3N%#f3+so1-K3@!Rm$GyoQ&~hGfbOi}w?{FrH-$CqekXdv- zM~h&rU3C?O@$3%hqY*v#LG%q)i7Mw3)v+&(g-=zn*&m3LlV$~Sl5HuyyO;3hwN#{C zK4wd9A(mx{b2HjL>C$Ab)nruLyIOR?;{&dSy&xnPznq#8RoPD#2(W5>9=l_zL}-U~ zc0KE}{s=XwY2j6*r7@d>dl>YcD3eVH(zpnWH;?*Funf_?n7F#*R(>I|_X?uxK7*>% zeouaY@ijhHh7m+0Bp)i)E&k97Gr4E*V4-JzYru3K9M;O>^W9ZqLP^4Db6kzszgoNA zjIsn{1n{i4oZgd;GTx9CBM`~(>KJsK;tb*I@~D*%Z?sy7=Ft_pd#sC^jz92m8WhNW zC5@RaDm38~i9s^~*)*6$*^l(&jo{vtSPod*r5#b=l=@hHf^Bsm>(LYpC9)f^4>TugRby7m!xCoFE70GWCWgQvmN zpfaZ-$CjZmIpG>=`-TT|%sIw>FN*u=p!r66kCCf{A9_+}`IKg-=4oXhXOB49Z2o9N z+)n7n8&lZ0gE5143zCEK?+0>Gn>d~iA>jF^Q+|8^=aBsrgfbhIO6NNh7Qn?6wh2J& zT&^6=(zi*&SW|_b?0shrSY*QUKC~mH5kS~DS(U3>(!4Gaarq$Xb)aFCmTm`tir-Gj z8Ud-VB=vqRo<;OOll&64IhJ9_29-JlmoWOyn^X9Y2;MLu4{d=(Jb4rmt*&S(XV_U#T&P~i0vEX*GI1PnhZZ}uJ5J!9WS;{Xx>5HO1qHVl8R-l`Gq+m)Zqik zonCiFkxbWrF>QJ`!tb98i-S;s$a!lDqqO3`yGH8tH-%*a9icJ7n2}v1v|PZ*5>?Da zT9HxoTmKl&d}n|na~Fn58813i&0pmVSCyhljuuz`+BCQlbk8dC?c*Y5Hhu~wl?CAM z5KNN}cPS-}l^jzK3vB55Z%?~8`6kL)$A?Z2<@Z^JkdT=##vtV%^H8uZ{s+hH?kXuz|s2k8{^#FX7mLTY!doYKF=(9zaXFlaj*}|wz&{G za;jt(cOJz8FHPt%pg}w_{^euMsX#Pr^<91oEL!Jogh6_tN^+dH+~kUNYCqHi>gXF# zYZ3QsXN5#wQ`r)xT+J24$9^j!`mE^^VI^X8Z=bvbL^@boCDxUFAe|qttfs8V_Z)MsH@rRJq9f%I2r3{DxF_D{LUuGS!XG6r`3!OcxOF@b-QZws z807qRim^#-wK(3?t7WtR~k7S6(BlhFqr=x6w-^v zU+L1VBshG6NzQpJEC~23@_M%iLre=P;k6qyq55(fo->gMD+Q+NByJNs2=HZ}u+sAQ zyK;yE6R{9t^6w22r-^d-5FTUce2$gD*I5jFqu)lw&)rL2!%}Jt4|i3bQ5STi=z7XD z77|Sig9KGD6O6tmo-z#!V0L04{A~oKB?bwVWHON&BPJM?tv|{~b*OkUr3~D29FYyl zSg6UmAB*CdF`tiho;ckq2KER}Du;O>2{E8gJ9h^uh5NNqpG^~(bcoAuJnd;R$aB<} zHCdT>X>j7&XMU{he5mck(RDeIn4*#c4fJ1K0cKO5Aezjf%a)#R!9l!KH@~FO*fWmexjYMtn|hi;{(hW^ z*W`l+0B>t2PjJarDo0#U(L^ILBacIzb#MQjLU?jq<))7(9dgbY>DIdkF^+*Hb~?U8 zhUM{T^1|I8C0&mD7LNB(zF&ZgouJn%8G5YD%Q@&7CZmQ0IRd^(FKIOH(1{wnDIQ<+ z3SHFx`nW)w0wy! z6!wtU;>e!*qJ|l)K7ZHyy6w^C;#IR_-?7X%=DPfdXWEM!7-C29;9FT44Xm1P=8&`) z0z8V+^AbLLCW8{e4?l>-%Jc&ATtjFo8?5dW`eYmbwiTv4jg7f*3^U`yd2;SK&Mupl z)|UR}JOt=o=-;<^?83JeT-{$EslMJjl}ZTFaU$=j{L;ELEWcrG8#P}+xBj64e^366 zCsDAE-BF5`{0)WSD32_`(wqLY6{We%R}-2#(-VaWSfX2q1_8|(Vp-7~|6b&q_7^lYP87Yx_ZIFJLK~ke`=gHK%@7nv~_(@E`hU6}Hy4=Fv_o<>rLh0FX zLBoWUs3lP2Hu8j^K1ed}pODu#Mt8)1EcpxaBrG<8STUm_*?<(nA-Y%4{wlj<{fKc5 zN{9WcBcv>lKxpP{F}Frr^ykxvOhHC5*B(HYi$U^t@wP4nB4tMXv`P;y72?G;o&Xn0 z0(M(SNq8bmbYr$s1(D&K(x}%$ewH?n`1Ox(f3c)!G32=<>dDV*_)OUrT zB7mOMyZ-jprsRIGGGJ%awouE@rtY7Ty_0>o$e}PHQjn&bjJEcICc`x%8MLD52YwB7 zBboQ-%doQj5xlG6ttMwHo9#lLcIsK#s1j0JfKLga1juiGRi{GiHLn?ALj+R$6fv?H z7eKiY7Kqe`a5rhk_!PY$=2q&BJkVUHQ4ofbcc%9@&+drQUJlJE$dBl>rJ{17Qss=h zh6awqR$INbRUJW4-v}To8D!$>3!o9G6;s-VPf0nHF3Y zIOBvgG}h6<@Da2a4Ab{rQz#YN>P?D>aQ26cTg}>8X|#w{qN7U{&!2oe-jV{)W#Kwh zi~yUZL-g;>Uc15AOR_&shOK!B(=`f^eJ9>vbDX;fdb~ZEvVND&)kE-7Sm`^0yuurPt zk~~+)c?J6sUc-LF8m^dmk~J6v0@oA5oy1v9T~_={96TY#oQfW5*pqRt4(AgIPx0Df zCC$*4H7-_$mZzIo5%VTaBN4Q<#A0@wwp_Z^4SS-TdJD(%_hKE6TCVUiq_64Rdr|P_ zJ_suDX6v8dd%n@(>yBEexTnUe#hj=eC(4>SrY3Dvy=^& z=eL3oCIjT}J`^mVanspe%7={+#7Tgh*FVdYZ*pQ{cnA>{n0TMuQNQx&hOZ2u{hk+h zif8lM9cIgw-&04^*6hAwL$nSEQIR0H{>-u}!0~~BekHss%jzRGZLzs!v86;p^Vk8hi@-8`|hx`0$Vy#EV z26_yT_|9*YRo^_j`4AY?gs-i+E=~}xaSRZUh-RQCTM^Lya8hx5N6C*m;HT5V&T-M* z$URasJ`DhHIEa7LGu^XN?{R6lqv$!0aHKp4|R1x!*g03k%b1?B<(3evF(6B|!3hvb#xjdwJu%F@1K9~bTzDMl|G`}WvN%n?8C zqSR$!@#o5?3hh2h&SvP7WepPF+XRE7#>n`-lYU^SfdR>+rxtZ-b#$})SAbP~uAj)5 z?cPtagB{MJeHY7C`sgRHQ{Y$semXIH%PGg-f>vY0ZXuj`mWG$8hsDd`MVMN969Ci} z#Ial1|0q0(ysLn_+^6B4bJSKK(sP1t;t&y(^%pWk`Te+=z6Z#VJCedvS@G31vl0kZ zQ2`LlWI!4Y*Kx>pL(8&X3xcmxzFhqVT8D=ojwGDF)C|a*+2EM|{BZq&5b0{AIgVbq z8%-Ta$Az0}n)6m;u7sZ?6AsH2UQ-D)zb!G<6}QFyKKW%x}+vWbAo8;9A?h3Q-6Z3#X*8IvgX~b>}qs;#J0R&1^XmWa{`0jIgiPm?{uRHSMD5l~< z$*rf;ewCTk023bs9x+w~LeE@JrI7a0`8pVloo0o62DYNY%{p%MQvk)19*<(vc|t>K!jo2rl`IV z)3+cCEbXqs2?r%jg{$>LQp)nhmc0|%N0;Vvv1w2Zu$c6$-8}?+XNw}iV)lVdcCrry z0h0HG)gzD=1nvXaUH-00D;l|Mupem@!v-8T?ta#xRkt2ZRy2c#Ml43|7{|jG$`^!N zW^d^x6++Ib!1ih1VjogMcEY7TF%~l(<1AEkG->_Ijnu+)=JV)Zdt?gp1nA@lDRllR z-49BWJdC-01oGO;mk-QJ5kxR$!UaxNH8iydIQYDwqgOo4_v zvnS*2J0q(E5B#p*TLJJo&!7Csd`vVL;NACBe+Ccl42~C-8uMPEHmn7o+K(lzsgZ$r z!-Jy+Jsy!p(LNCt#0|%Y0awo1ZH!TVh)dlif0h7B({R1jc84w$kc0|lSOpd{{mqRE z_whcK%r#%u7c$F^Eh}?{pF;j7qKeGcNBNkZa=+zg@~bN2m-@+7;5jaj7jL}-q&CK6V0{rpB8IxqV|Y=wWt0u4^}ue&u|&TuM6U8)q%Wi>kD zP4%`zRy$0UZt{33A!g!(u8Rik@WpnQdk0eo2pm!IZ#=k%_`&Q0e=X8a@;M|9lyEfIf zoK_|FV-+sxHV4ECR_u4iMV>LW!=WyUnpq=#$^x%Jd?Q=RfEMH-JTd>MllRL2oHc5qbZZQ_5ykiz zx6g%pkqh)MJ4OHxS)uhH#($lnST=w}z1jiXy;aYG#MH(7B|WE|)cbLc=15RGmudGs zu6rmu{2O$G6^~0fS6#U>SNciY`cTF1fb!F=-q^Qm#|yAX2HDITFxhZz^)yulsEYCh zo)#pzK~}{9IQ7DI-L?-dpV}A$m;>Xwgowk&ECr|?eA__ae8fLv(s9ItG}eLuU+-W1 zADvKWd-yu@76-=<39(~X@kiF$k))7@LjM3kvPI!Q#9VkZ^FqHrJVr|^gUg?%>EA$3 za&n;!)tH)2T|djO9wx1dO16pt9z=NPxhfPW!VehccV1hMua|=ZX!rZu+rb+5i%In9 z_7f+9(XRv^DR<8>uss5Zw>P|-vBj1*|A<1ZXu*mRf7g3*lUjJc{ZtxGKPS`6p}@(< zJME^gtK~p#^=;R(hv4n)--KsuYrW(1CmUgs3`$2E6yZ6TQ{z)`R2P=r1k;;#$WPek zrNF|qsF%;mz)YoOnr7!1w$IG%F#|qC2Av7VH%!K})2l)zCdEIPHCD3gQ=;m1Nj{{h z&SBfA07&YP+>jF#N3G+!ayv&Ni^)FM0=hb9+9T^Vv7)_5DmI&vc6D?1IG5 z=ZR*DW%s(KB$;l#!a{}gW63~r5u1-_rm;@`;QjR_#0AaFSzV#GK1^=L&@V8c$`Mqon1av=IxR`MbVer9V|I3nD_B*f?ql^(Gk zpx=?kYEH(X>r-7?csRbn+DjX>b;|jLoYRS<(q!3~Wkfoejwnv&rx#9B_6=wJv&pfy z)34vMT9^oh_{#Td)yMTKF#;;d7DKW+sa9P#Pe<2`MO>oS8+7 z2aYO>fHO(gWoHf19tjaVWeKaE_hTd16TKTAegMhDycrWv^B)BKpA{^whDSvqb*#awmWpe#zJEpTOAFZC3zy zFh8J1r}vmNP%I>ghxMPq=F=61AriNVTq11tsx!GoWZMmqn_U96%CU>CNx2N_9!9{e z(aH7BS`-4z!D?|u8a-@TtO=5Ky>pFDo{~LZVZWSNnoFPdrQ8fJv!`dGjG93Z&l?GM zwX`rW-fny`-8!0hG8Z%QFkjZ~8&>3a&^yk2FnW%+)(B)Rc=MKUny`IOr+54MUU*dq zoAHg1qDp6pnc(3W1w)*`P*waM(?~0c!$A09Y<0`N2Wm66UJ{^t=y$>26XX|gm|XWW zi&WQTUpW@4P=LW{_X=i(Nx+hlRmKN*uXw=J^@l9D;oig4BOhCU&gfV(eM;w`XX&1J2K3)-{Y|b+^kNu=RB) zRv_ccl=fodR36=N_O=VU*>o(Ri!Z}iEjY-;roWlZ^E?p=P0=?2xl4$mDBHHU+$~95 z9>Ge^Fa{INawlwgH+Vsw`|3ug&=BDl%9Y~LSO#<%5k{kMq8KVud1o7Tdq4K+ghUCu zZ*01h^+B5k`2}c!cs=766=LkPls8x5Ii+~{gCa0ZL`(}W_H#sA=I9#(aGp|s4Ii)? zc}Rk5LutTrZqpFY@HzTQtC!qX-da&`lZHzA@~j6~$0*Kp?rN@TIKf% z)a<+mzqM{oPWcX2kr9ngFv_b<(B9&S{0v~Ell!e6I9Lg> z^m9#BFxZzbs`;Q+%lm(qjqIZ$j3hol`qydxxiDm2{}fS`-C znkBRpt+?;3UgF&_=WC|>(DH|GyejKk)-TSXrNJZAw8ZfF4F?xXxf~kGA;Pj2GJJeN z4zs*Z_Y2=>mL@nMOyasE)HD31tJzESPVEl~9?Wy_kgAP&$nulH$H%sN$O=aI@+#Ix z62hE4PtZyVc2jyAO1vo-0esZAl6pm#3I~>)og!@T_8{#1abJ*?LE~6wBef)PYZr+w zTEqYZBrgq?T>QExA&`9wSZ{cl^zFc(%O69UK&V50qcZ85l~fN{N=ErchCsu4ZLy3b zD1TgqB%IZk&a_-UjRkDKnkAVEHu9o5zKzsGKPYSiMBr2WRLEtLs5c~D!~XXI`V#;! zJ>Tc&aHyCVBkXGskE-OwMZ@njR|XL&_KJE>%dI~pf`QEGDX4tyxg8{2WvOqSYZ zmz~=VBgY2)(I@j08$(7RjCo7FZJ@ZY@z037oH$}1yrVY$Jt+_MEklRyu^s^JV!Zlr z@!WHx0j)m^ptcbS>NHoy>3z0mjE%la+Sz;c@KavPJ|nFQJJ8&Ov}Ed07s}i-pz`nf z2_fE%N-jVv`@r*(185u_to(Qi^h7#JDFF)y)E#8W*T-iL<8+eCDIoKkluU4p+xLU}#ffe<`RIE>BlwntqxdU`Ilz6i zWq(<7;Pk~e1H^3>K zelK2+O1^^13v8ZT$kN40vGn(vEvb}&#qBJ z2yJCOeD?Va5m4aZ#LwvIJ5A3sFff13=VJfT71cCg@OI2UPkD z{tTxMpG}*#-UBvBr82C}QgSDxOn_plrhm*5G|4LcZ0&GYZ>Kz@gYU!oYm9G(Nl_8f zfqm}Ff-b_f$P|9*KMyr1(zy8pXPs*Q4KeF zQXfii1hr3*Zr;YffP2509n}=R+~T2k##DIUsFcH*9#czQ0ZryeZ+j>xHqSlOF_)j) ziOazY0Ma=Z1(IDUJkA@~q@y%wQ!qxHaYvYaPHbkU3&_%`UKlwox!;X*eht>1+I#iI z^Kg-eL8fXwMR8JtG{NUy=&KCDz*^!M95uijPSxWH2}PX{Ngbeh{m7&55fSWWGHEK2 zWH0#`U}aIfn1d{#ZV&~VHQu{TZ1r%BVkx#$n2#YPNzNdlzY%L--aeYJ_b#K7k51}N z@@5>S>Zg|XjL0`sM5eV~^_QvVY;ISSYYPsIg+*hsPzM$_ z8=(~?FdT+mSr5hFPX@YjvVa*SZ}dkTMp=U>3+U&}Gi=wFUvg~aw{HWVi0Hi^7{h%F zU`AM}Azsps^FSW@9>H4e+X%Db;yOJBuJInid*qyLT-`wHK9lAUG6vLR=7+~MtZ~gub4Fml7XO4Bw@DXrGbDrXSD~&?< z5gl;Qwo_RSKP*HMJ->le)BwMDg8eLysXDV>lw8-rAF8v_*T=jNns0=m$QHlz|1AQl*j( zL?HlvcoehNR1GIy!iIrF-}?nPyD?#80O_^oq)W3B*=YWMB_pAk4RK?8oPZ8-gf) zyCYoUt$NH%;(1uU(k%0%G!5efhVr9G^8EHTJELT_V{#ez+_RP-d7Oi*as3ulN!sN? zN}xVE?@Yq&+rPvU)FegGAf7#pWKFuT7_*g_<{gb8V+#?le?IMZAIHa@{RLL@GoiX1 zCrS*bHzC0U_NlbpRDEDte2p!?_)U-q^qcH!^i+DM4tK&%Le{T)`0!9^Tflf{UWhs1 zh#fwqC*kR8d-mf1>AaXQm2F~qI!|twjX>Kvb+*GP$xCk0p*6n0YI_YsTtC>10jWY= zN6PItCWq%iwM6|v-*j`!3)p?=_B63Vfn^!VAH=!3bu|YR>mct7;Fgudc77$Wy&<06 z0*2T?hJQQXz#Gd+-`_3`_l*1T*d+5Lc3kUT_Y@@ZjlwUgihoel{7CV8#C& z=wsrls}8FPnIU$bF*5@w}NUAOPqqX%C9;(#415^nY23U z=1|#Lsrn0rn|Oem{SW{TE&!-~or2Zpga{NJCz1;(Km&{A-*4-`ISz!CAT5mmZ)qmj zH|yeJS#J}zUhw^3!0x%Rrt^P0(IcnngA7P9B^Epso6;YBd{_1UR(8Pwml)ljrZej& z1#YBm65yeK%+_GifDn$L>WuXkGyrtF&`>Z7y`UnN{Nm8g@4ou$v@EoDPmBTC{sCPx zY@Mgomj#I!m4CuZ!Zle$g`6hkhqq6 zdG~tsh5x%_pPbA#!eqW=mK{)ksnGv0)IRFmEu^y9S(nQYZJF-ft;h3vTl7N+?vO8> z;^-c*=Nhc4{3Gm>d931Ufh4LHa!rPq-Azc=RTl8Y4hKdZXZFhPsN5yo8Q%=e(Nh

d1+y%*-NN#>@@FdAzdD%vFs+CfALP4LY`X2o2G5@vE$Uy|4@i5) zWr6~YWiEbTNXokDtYsp#wsLIkO=?*1XS)fqJdo;pF%VBIpnOhNJ~s=FBh$s`y8?ap z#+as1utu(n&}S=aFIE(=iV8i5{c}|b-3WB@2^~1NzGuYo_4chZy3bn(A$$+~@+GFe zy0J4&V^(>LDLRX3>5EEE^BpeZ!H$mN%an2~d_|yJ4aQ{YD<78sD!`1ZcPo^I6(8uuvCx~WboGL%eo(pnqUTj zIzI=&yg1rqY%uwV?n1)0GKoU${*9Z^7{Y}f0t|%KNJ(w0^{?9bPzvSWA?8^1i8Mlm z`M+xi1u=p$VK_cBx9U({KA#|1024r*o^@65C7wD=HxC%@`#?#SBR`dv+7FJp_{Ht6 zHIC_mFu*~!n7kFGFb`c({0X*k(B{&*l032wfzJ33%@YbmsUszzHi3|U_>GOUIXm+y zOv$ci5(&i(_LtTD#Ya0~%U2DY{FWa)kgJRtroE!+=asw!IhAW9oREQ%qIwF%t-0;7 zE?6PI8n~8dppTzR;;V_{!Ala-yW)PHuZoZk09Qb$zwpgj{*G)xf)-eT*NmP@tSIR6 ziguIqQzFZ`2$x%$dzx280X1D-wz%A9YVOmvp@cacFT1^&{x0jaL(iODd0W&-LI2W~GP*wn=stqvf)xWAx72%<35n7kHH3GajeGZ<6EGi@k(P;Q5 zL<0r*<^A1UL?zD({oJJzH|0`DJWTgQzo6BECQO>#&BS5Kt}|4Nf1d7s^y>Vi^dUU! zq(*_6UJiK9&~3T#p)CQL+}i%@2EnC&ee92e#a`Hnn5JNUxgcrZYIkb4BFJanGTJKpL*+mAHifOu(#D%V3Pk?VP)-DywPY>6Tx-?9G0SZWnDl(&0il988TXHUTO8Id$?YpWdG#s+el=wdv>pmou=`!MM@r?1?8%NEItbW*CZBn{P z3-+*tMzFLJhTkX-s$AHe{uD?9y5(@PcPv(Moj!tZZ_o)8`GFJ;Gw4%=K)%Y%omL`! z7-&9rF6JC)wmSNs3-59lbiH=3jqv)g63|dv6qRF-@NX)?e#wBUR^rQO=n`n>B|NH< zTU*p*;Mu5C5cSVSvXi&_^|WY1$2zTZu+GL47oQy=zkU8PcA=%h3-ta0c*r1qL55)} z=F@#F-%`!^dX4c(6C?FL;1>g(Km@4wzo)|UTOD0OpngLXldE>N7y$&ZQ)LUF_!~NU z7P&mCRav^ouw5icPXErSnHv-b+MJ?2GV93UJgJ}dt0QMgLU`B!`^nW01l4-2#wF&T z27V9-(*D@aAQ&Dz$M*E*bR8b|@dm69$aL~eynFMW;$U%7OaO-uCMHJ{L#%bmjod>E2CmN-P$=@fgi+Uq- z4A5MEnsMYc;fT3e$&}1IBYns{dpn~GPnzsS{$acOx_K9@VLM%hHd2+l-HMb`=7!&r z^fq&F3#d^ar<9EN+RQ(g%_Y29E}8zL6v}dT9WAwdleyGjAVwTqO?37VS?#q57S?e0 zx+p$xV${G01E+BE-2A{>c zdbAqC!+b?e`G$7xrT|?PNA3Md3-z$Sp`YOpop9U2b-FzC?(khVYtB{$14^(C~*>jBM^UR?g|>W8gT*l&tVv~Usd z2Uw9krNWHfwFu}#s%mIgCeNDLMD0s;%WX=3@Mc(cvWNpdxy9_KFabKGdt@MHvyX_Q z!4WgH&fHy-DkCe|BUA@tga(#U(MfcjeB8HBaOW@ASIyDdQ*UKg^vN>Ayt0Jo4JKDmTV(p z->3hg7r(`3r4>*<%#t(#?8`=9`Y(+8tmx0O@ii9a4I&+08zR@e>}H+YPPyw!{4Twvi932}M%tng=0=Tsr#SUbTOkDmj5`M9n z8%+g{cPZ-Si2kTVOhwtke-%tN3g{FJQ*wu=xv!HBdu&7q2?}CY-+%D~r_S=^y&8DS zxJ*4?Y=W#^=MdwY7`ij|YYVroU(JcO{A>TXFb?eHcP~ z>q8p|3GqOAm|(!IuJWB?FRGORQ{`$y(3P0#MC`(K{raeIfxpa`lR5N%{8>`Xune=O z-Q@YZ5W{ohsdU511DT(I5Y&MKqvv)cpi;+@vo1(D@zdj^4@Rz5`JGODdHgD-wl_IU zbXnhf zmB3H~!cVOvE>}!Kocj;WA<`aIs`~-YDtQOfV9@$2SKV#MwTFK&A~zVKI{2o)%a*u= zz;M2X9%=zaJVpgIKT^|HS#p_B+!c^)hg`QHA_xyWP+&L>@1*LQKm*3)>=hVk5n-5E zH^9S0Xr3!vpv;qhM^gq0g^lA=v4#l(9@FB)(RU<#B^S$U{--J-@(RRKlx3^jG{{iYlc5UW|Y5`y4Wa1HY0bJawxzhq7nmMKAHCij8yo zm4_=6Z6q*4!<}>fqB{S*%NO6=hU_MmrnTU0_rF>Afo-}+0KBO0XlwnnulWqRzw-J<}0 zZ3p4bY60iHdn|3aXybUWuM52Tc*01!(HRyvALhZ|nhyt%JRrj^m)_odO0Tt~O32(2NMWi0pQ8qK!fG#j?Jy7TF5niNW^kW@R-1GIi_9MD3k7PR3)PF)1_V85-4PZdlnW%>}WOW zkH8U!9GnCoq-2iTP-glpA&J8^+;UX1oW+dD4!$9h?;U zn;kE4G+a@inKa6#$>7ffBGz#m(gV|MSx(g}(*3&b+oUQ~=p4#uQqC$N?$y8%;C$(8 zMLQnW^IR;g>9a@gtPEK!{*J}glyT#ZE748OI zg0GVyB=;a8^LH{iL!~}T7&4o^6}wF}Yq8EnHj8t+<5KxV@Xzq=4vId0Q3ubw)-ODy z_yYLH0;f0r!vop%(H%t$<((ojSVA^6DTMs(zmb|2%GT$K{7Mjh7j&P^?d+U)IfYPm z$X>Ad*xNamm=CW&3gsIXBBW0j+=NVs1jf9;Udlt3srj(ePrKj0S3-AdM+CHJ@4Bak zQ}-`?UEh|Z43Jh_{&o$%^PTa|A|;jZWV6gTjI~jKXA?491aGCIwszXy$7T-9)+Ve| z$lQ0aCO<8Nt8a>&{CMYmSAu-x4iw=_0HON{w*UAHZBipjOm3#ET=gVKNPtlOiKS!% z_$Lc+I{B}x_iA<(+7>h4`&XPgez6PRCZ{UjTSZ2QoZ*d}gUImfn|18#a(Ay)T9Vk> zVlo+XjPH|RA|wS8LBw4i0e+F?#vs(r>;Z*bgRk{%_m;t1ZGT(d9&U^LR-WfiCN=xd zuSv#{X2|EX6BloHU$Q>}rh{yk6!uhqW(6NJZyx>}V2gxIoyi!mav$Ph%#jyhrQT~h{)GK zrUsroXpaD|nGi+qzdUNVKz7uaP;q^)l@*2qAMb7Rn*e|}zc_EAzL4^~sd6;f4X)TQ z^m$=QHccT0n87@}N(@O2jio((RhYnN1$%}wcTz}uYRQE(v_J@4&nPF((`#(w`|M(l zTx*sd1pG)Zwf_j`O=CZ4mCUJ6PU`^QnB5-gH*dX*OKPkHZa^E$Di!6Y(2WiumUiZR zb%cKH^VSZtPHul7)wyfaR8x-A30uBBc|dx{A0QiUq51v44y2tG3i?dh8wkF#8odbweu>^e?`bH`-Y9d)b&VNzbd<1p-^4 zIQG9Aaw#NzQTZ6fF+SRRGJiM|;-vEtxMD=wk7sYm;5x!}`^$I5!mQ`Ww3!;*?cCL6 zg8Buh6(Y*a{(5Btu-l1`q#FKRw4v`a6Y7=N86sUJ=Y(3YnliMv#P4=|$$XW6Vq=aaYx+7%9` z$z^-sXC=SDbf2~hrNhtpv^kp~QuKRe61G_nAA{RmG|cA%M4rBV&iU}BNX0kxhrjb6 zygH{6K%@Fcn`Y|h4XEUO499$NQ;W`Ug}YVuBk{QB`00$y{LR^dTBv%s8evjjx2$I} zH1|xBW^d`5>=(}abrWtWDL_9pF=**;H&TJ!jqP+>TgfT8_IvT8$*BRF$M#E25htsH zZuJDbkbAgs(^}B*%?3*`39sV9*3kIdE9AGM427f9Kp4^v3bjZ2x(;3ra6-I+IY*q^ zK0!Hu(xz13FqO}s(vN2g`%>et=cx!^X+9=AJ)aJbd7>u2{WIry{KuHOgpzU5>xR>X zz20f?y+Nvm6jU8#NdO_wv#Vy32C0^yj`O_A=-b6PUZYt%$A0l<(oxrq1IlO%Wysh% zotmx1$vme-X0)|C9ks}DQ#u_Y)LT={{dA~YP_Ad0v^}(53^|5JrUfMPO8$Ic;bnK3 zfNd!EoW*KkNWM$>i**8d#+$h8iujyK}$is#pxi_t*K!#`ms2(ccQ|(?*w1^;-t5GL-Bi+k{5& zEV2|ofam9~HZTFfE;*L%#cRtL25UVC_WV~_+0ys*Ftn5N=BwxD%2D zYC-z&MUl3PM=(K^v33Um!a6iLz7jG!`9h+HcDFNoOt$&q$(iFU#e)8UL%S*Kv8OreiOJlZd?13n3VM(-{7 zHW<&D5_ij2n=;l3ek{yiGhCRb{;ogQ^@H2od`U1$j{srK!Q~fi^V6~{Kk0(#?-rJ} zS5BF%=A`c7X9oAdJj<{GaJtDzjERg}6=h>);4o$3d+~x2 zPnOlHfh_4)*k`@@GFT;B!n@%tFOKj}cLaP`_^~hn}s3&@+$5TH9lIZ3ACC6Mr_A_z=7j?Xx(cW>}8X2Ox2$-1| zZG#y<;B!*(`)gjqA~v0i(PhXco{X)(nhReV=h_2D)^W9F*(#h@KyTNt*3Vp0OJV#? z0u?`t!4@SoaXL~8A0%yDxakJ7ojh)LvPP#*mOLtO1wP-&c(i+Y4z28z!>E-A?1G92 zxr&6#W-)M@#(Ed6xJnZNt28yWGDlG1)uUj5llB1y%>kqlSQ%y#E^idrSpgr`{j*JQ zyT*<;yfC?1;+^()%)4{6BX3cS{$_HO(+*^%aZ>j}_eK~3n?9h*v#t(dmGmCZPaqs5 zt$bktd>ZK2fL&U#WfX2fjr4Bukv2LFL{`KV7J7Z<^Fvo9i;QlxlZ~P{vBC+IIjUS- z5MMN_3|bh62rE$AujkBGKGFx?r9B=rLnl)gv(z5N6jLLG^sV524H@4~9?xWmqfN)!kl2M-}w}G_Ssg!uZ0l{XmO^N(!0<#_0Z?6ws%}&&`B3 zv%#@44^!HLSxS#ry;YE4Oaj)gO^|Vrf7HjFpJzm=gHwN}Y~~!RdE*!D(RV!jO(E1D z`A1s2Y=(jH9Us+2^e<7r&BxJ?PU)$-D#YtU)~cbRE+I0LtpNE4-588#ToPB+&%u;C5a*QAwpX%*cTt15d%9|GC=@+e zjbzQ;uroFcfYXazzzuYMAB7H1-j`jCYWs2}uJrK`*-^LggSPFn+$w~-i#9>tumv6wR(RodbNusUk)HhQAew&G2@ zi03*?rkeBgy&*L~CgNB{z92WDhYi?89`!rZ%uqnD;k>p-1!&j^lOD=G$o!o04hw4$ zcmEti=}mz5$+ox=w4(*|kuXlJAcTI3-#H&>$Olzbjp&*OV!X9rvvaGuX|Wj>b3TOk zC43Mk4~8;K7K{kHM5Z5IMtjfE&;0%e474Z&Wu~K02rLX4tOVq_eUvdH4U+oB3lgRo z0Yd%PzIA3No~-SysXi&cZna#p(d-}&_$+=2=Gxv{`wVP!W(>|yJWC^ye7EsO*7>Oq zE7;xXWAV%d5;Kz_`lg*DN)L>^YK1o9wYu{nnz9lIKNxauXVDw+Th`w}v%P zd<)GL@7o;opHo+>o=t0f3QF10d<<%FYtfU7+td>Y9V)!*}wN?dab@1&Q={A zxUI;yT#J!LRJ>GT;-lIt+TC=6dyf?nc3q2M}={uE^75^4IDPM49ICs$NwdkCrxZ5hj2dxe7I#RPY zGTaHO5q{1+w0fPRpNUpbb-X_TA>Pq$6Q40g2$u>OkVkRA9CUtCm=G$> zNd7TrP6T)x1CD?u6k44~6ZwRzaH6ti;Pd;Q`#7=FJ_Na!%4u->n6T9VhcSxX75YmA zDJ#7FkEMNpNyF!H(JODYj+-?O>PLB;5AhmM0`wbRe#Rc-l%o_^+iLQ}gj36R5ZHRQ zCVTcGw4+-C7IAtks`FWdVICgr9zEo zG*S#}F#+H<$5|hoYIUWCkiAOKe0yVey6p%+XR}hEy?O;ShGFr1mHW*84icpMH~B(z zbzOXUFDmQW>vm0xf0%(|eF9W7I~7$hz8JB-^rma))LrE;xnULwT*HI2l<#(3+(kDA zv;GcJV^|&%Z^|1_rt{Lg3?+j3QpXGx0S4T2(f-h@12#YyxE4CPeWKn19Diz#FJ7JR z2(}!V+ccBnBbrBp2nPuvjPsrAUuCeM#N(e&D%tt%ukO5~Vs-?n+NdGov!CD{r&f~O zV@nyd32}tFsmo>BN}*T;B}>-Jha-}{+oYHRI0iqFuG8+~Sg5*T`?Gyc3fuHpXEn(F z{=5+Z%KZmi!Ocy<8XS(W$O@6E#Y2oRSuew zX>G6{#%D8i3w_ClF(%r8H4NAf6mW?o^v*Jza%^sY(GE3_mo-kNp9aa^^n6ev$WTc4 zgu%N|JNv=N#3x%`U_|8RRN&@sLUVxRrCup*W4~QnmzvJ9e_w+``L{pE=`9s8gMRXp zalxG5KHpsC*VbIUn@`BMybj}dUjS1!~2FMWa^t` z6u6}o%jG<9DD%<^-I9e-tU+QQT0aB0fvf zm0u2Ghl%pbNe9JWmj0a&v;lR(qmU;__Tuih$LE1@2I%^txV5$6++&8P8PLgn#ltVf z>ynUqKvoL~fd;+5MJIhBgZBEc&++(FN03A5R?t3b=j^or&0S~^{mGg$mr z@@S1m@}~=w55g!;&|IEzLKG7`m_VD}_vIR+k!Rx4*CsrzAfVjp%MnY1Ze8+p1o5^oRToj=@SrtbS8}1H_x} zVmPDteZ|vBV}3^DtD2kTLLlg;F2#N1ab^=bg|Oc)cRynUngCY2w=7SGa5# zBY&vxkJqfF{A3{t2>epMO5Uzyq02gd{Iu)eXYs0h4L933i2zv=(cC&&IrA~4H;KEI zaWUG87*jb>Q&Xq69-&yumf{rKZL#VD0c@L2&32W69G&v@TF>ClQsaUW7=|4;$Fo^q zJHj)hYjxop6ypN%tWl6enR?77-u9IkwD3sR;c3oKDl1qlDH!nBga#%>Kq00P`wb`d z(*4~TFG(THj|a(Nj_&gn*u2KYjl~R;_kI~GELUX&vJu{zVagYj;R?P`cwdt1+e^b>F4I9VvKIEtR+>{E8uv z$z1%r;~x8veE)&OmsuSBbhtzcNQopCLd3>3m~WlDdVM;z8ZF>E+}4KFdi|ra?>t>C;7ul z_$SxJZ7bNf$e#u&i%*4}O92?8rRdpZRNS1lEfbgsH09ty zvL$4cVA}geW4sTTeAmKseyLXo%0$Mv>bau#sOr-XJ07g#F0rM`iHt3vQO$-kSm$aX z(BEV61sRAIZ*=(F%1!Y4hOK7PpyqUC!TpX*-SiVG47mdspDD+(C1A;=bc`mr$cmw% z{*8yX_x4+=i2&f%UlBEWQW9e$`aA+95*i8786@##BtB4|UZ8 z-O4eBB84k-?0xM!*=C5(l)VB%fQe-cBulr1;BNHp%km^}#kZ5J&<_t>1 z%?kmc{K3bZ)4+PeVR>T-S>-p6;yaClU3(PY+9urqzS(;ufS<#zHT^BRJG$ZcYd57U zRT$fc=R>CHiXRK2$gRvDsQs)zsRBZk$ZUjee!Pq~ zUCKMGya(_g$jRYU0%Xg`$QzvgSd$eI-PI3p%V51(TH*=@H%IQ$$X|$5v~>m^jBfwX zl!M{StEI&GrNGd#J6%bZy#_w^|a9xQr{j_RJ=8A$rfBbvkMA!q$oo zqtC7xVE4kgmVbEgtcfOb80R5g>u$CqGwd$rPD-q4u-Y}xnWOOz2aXTRM2yHSB?Zuw z&yipT51n>DuJE+v)o2GoXnOhFeHj?=AR$AU)i7Ve%wudnpa(5i(l~_U2LMQeuL06< zB*m%dnSX}Hcs}OY4=)P(6lZS{|KRvx6=$Y-M~eV%l-Ek*1Ay(!$LbH4PqMabiqoUI5JiB z++Ps(%#&QdW>yU?*6lJU>1GM&09uycE0UJ7c3NW7c9#z;=E7G}2d)}d=Nj$5lJ?gZ z)QyGfE%vENQ`vIdA_B#S3y!$I8v>~_3YNVYf%>HMbggz46|)oam{5fQq9V4DTGWkm zN{!Y@tKCQzC3mUcDU*jp>C7;`qzaEtf*S69G(fXFWBcXMzYhDdtD&&8A`-dztw&DI zDhxiKj{U8h^rI`yS^;+J(!+4BP1DC5Tg=&=WB$eZo_kbj+mse^$k*FM zF`5eOh!^+oGJ19X)#pfhy$}IdLMjXIW)nds&5eaPoh7=qs(%k#(u@Vk6goNR(m6h! zH8_B6O^jH04d>+Bb)+vMoaxSsu3wIN0gEOjANOF1r1VX1(EhOZ#i4uEhyx8Sm zEh@Jf&}jC4Jp^>tNP5LClRxQlY0my;7jZhVW{ghy{HR%8CUYTLIfL~}Y`d`{9KNm< zYrThe^eYa^CGDsKAd|!E<{1z*GL2p_u-k{1Pepgxgfb(aE!zIpBx=Hz@DnF$;v<6Cp+@DbT?E>fUW1v577;0Q^M(7!Z;46z(7AEH+0-^WrSQho5^zPXiAkI((l&Gdy0F4z6sw3_*>g1^Y$>nd${vsvf;iaW_*lO ztrC|=(%JXT{~hpZOcX~PyNu}@IkiF@9lZJ++h#4xCUDN(=fS5V_4>%@<8s8VQBZ>~ zu|gK5nemsy5~g}3Of7cMZ-UKJ-VlKLv{{`H$?EC1)mK8~b5Ow79fOyng!Q+j-%YgB zlnbG&3$}Ap{Dyme^Rb!2{wKVeK#QJT9DTZI96ODF9=rqNivklD?Bp@XMV)KG;!ws8 znCmNaZ+}EiahT5u(|4uRk$4;{e)4$!I^U%V=ukJwv+z&3Hk&rv@fAFXZ@z9Bec^UbZLk$f}=N`|}NewY5aie-Rt z{%pNA>qvP%dzxZJ1tmp4>{8SYWE5wbm*2sS_K*)P;zMl^-@$v;&dVh*ic0rQ#{~II zSG^(<_12!_BM#lyw5q?4gbLrY#>~>vr12-@VhL=?(m2gw>t<0qW0mZtcOT=r+@nw8 z;$&%;rGAK_GMv&H4O9c7KneoS$qj9=O*xATY41jH_b8RR>)wPQm08;@}+$< zN}c7Mh659Er|6EIq7?yO0MiMT{^BTM>*SLnPNh4h&Wf|!|RmQ35 z(T5Yu1T3|{6&tgE->zcMl{j!SjTg*`}^CvfMY9VMEa4lpuy+W%AeRi)nHVb^2wtRTsW3QB({m?Nt$v$Nnq|>u$ zh(cpr((5OS3>iL^D1FME$yKNzRGfh|lRnOrAS;C+Ar?bYM$XkUA>^rr)LL59y_8vZ zOo0bK+WJ-Z(Ml`m(!l(l@#t0zr11P>L=Z}Xgj+%LtBy3#F6 zG_DAMYc#3UW7Tdsfxp4*SUBsOTs zotA-N!FmVIsPRT>wR>*1E$EpI>?B=oAf;V_BlcruUn2#5&H2<3Gi$M^~ z5zcRjTFP|`s7)2gz_-RzCzwNeP6@=LS4{|lJ#{O7Z z4fgCD@Pu8N@9EXSo_7c1YYhI^JSnI-=NFie#~bK(LN5IH)!@N=@cd9 z1>71QLU=d9D@g?*BJxWY4@pUZX_l5w9hC;5 zkcgsGi@sfNhEfm>Qv@E&7^^HHVs^sggWMo{LvhHYD#?PGsd^&C5$!dZxK}O-vlDQo z_!c^)*WL=JKv7TWlUrm~YORbKfg;iEqHj9EIA_z-a_J=3J@YV0l5;bA7bj z+{id&GIZ!^Z=JM#v$DJ~G`!dyF*L*p*Bgb_L60k=0NT`LKDhDSDZ)%2Y9R;J0Yl>w z4`872v0|rB_tpm7(0EOeZMH>CnvGlTn}1E7b6W5j(%WRD94S{h@~B=KcOGC*GjAJw4yjwmX>U zQ;2@6->-Ix{BbE;7;erUG3Gm(9L_s^o@W1X8j-`1Gf4o$lAyJSG9^8_{+g{)F z(rvb#YxZeOWfQ>l_+Sqzdx#P+zp=AhQn7S(z+F5^=21b28-YJ3uWE)7X9@9L6}Wxx zpAokg>9)-)0LCAx->>+MArcC64nNt4;vO6><*9$2mNNLgS;`w*U6ldx(P8NFdZHp( z$-y!iOaw*DnHbGHA#|&`E1r~I3yjb(2^E&thI=9j`x52QZpGY*MW_E+DYzuJ=grUtf*v6bBWu!bU zZla^k#^_&eZr;$rvT^pMUcM9hibe}|aWfWsj^;|i1%+&N2f7awAZ~K$bHZ0lBCn!m zQ1@hHNTi#vHIkDM@cHmY4|;tb6VAcEIU1FKg(|p8pm7KSZpTR!uh1-<$yi=nSrMmr zVABOccK}-RW(Ht89p}+yF3EKI63$QDKGCdD^LC5<(Dg-xtuIOOumXDBCGuS`z^Z>08IhHd`L>wkc$+f%GZ&X zk4RIYDg%`5+-kQ)CQW0bHmoW8Rr^5m(w9J_=wu=WtgF9k7gP^gihGy&R}?a5y)*4r ze8$RSD6SM@h0DV$*#OrXPY0${l0VHtApmKts6xy6q!vC)&)47EZpg;hzFTXe{YqzFD1yb^nyQeI#S&B_Q zYR8T40I|3Lcj6gykPZ7))EiBo;}y~}g%J)!^tIp$>AyAQ#mk|jQMN0}LUT@9|XP&s*S2Gfaxu!U;9pL^g%wc*Qmw#l2+ zm*;MI7jp=SYN?O-`i#{|hRVXQs_3i83u-c?$EK@d=JZOv>5LAL#~M!U*|P~`L|}(K z7XixGNv4EyaCS#3fG$#T2B)@)N9-VGip+?R-NyFlnaVf_)C5 zM4Al*TJBLOzaO~R>QIf_Uf^1a1>pm1+PY_k^6CO=@w(RX6 zxbhQbz3P|H(x7w0g`b?rgDU{F7kE4BCtKd%(HzF|SKHJ2OJU=pbU(svXrc6&{w*js zJBQZNNWYQ@2oLpU?=`B|zctztvf)Va<$>w#l^Ov;6@rl&v* zw@+1S5}Nj}g$EIF>|jr;mD^n^G5$>}HUYik4we;91!dlR=)#Z3+QrQpkSZ)c7_m(R z!e}}}nwAXNwKyT{O2 zuz}&?630J(T7W^y4SOlLg@4TTiwu|)FFBOcv?5z)|C`k%59wdYg_7;V4cu~8ja!Q9HE@$u4EbxJ-1O>mLqzXZl@4?hA{*^hObU9&&SZN^phrTI`V7;~?=?nR9X&O^+z!b>X(|m&?Nn z=KbFsGxVIzkmivE`HK`YBNFl(;l$83p~k@mtC9E&h0Q)zPprIV_i>8JBj1{>(L&m% zfVgf>ZnFJa=MBfcf(Ok==GrbUSJ4kvU8r59s2_)q{NZ?*mlGwxSyB$qrENGr$Vq6E z(t34y&HqV4G7q-CuMzkG1x>rocnXRsdm6`pc&*=aC@t?<<2=fLLsqj^W&XZIGHaIc z%|MQ(*}5N;zj6I=Ocx|X5OsUb`*}C=NjwDphjcHf!_IaMvThuN;B%W0&ugBRRe2-G z=iD+lDkhSnWCrc2K$9mcOe+3T^{Q#Ew1p*cg*}!=o!rbzsp&~!0etkhsqr8UizbWU z()BtTwub{LKN@e?fBPti5@DtLxSI1VDX9ZiCpx|uN!)S;#{i{#do^$wCJ)Cr$ z{y3Twwzb=)H_ZB!?eUmus=xCjCHE6`StJ;FWe>C#lVk8=!VAlI+mDUNv$gl`!}23A zJ3JVHA*HPFSn>Rzs@ZW8&%4SC<4o=6_OEZZaiZf-g)$Gc5?18={uST6s7V3xO}{z1 z)3FoqY?VQ~jIPRbSxc~j12=q_z zKmG?;{m1{vi*o&s|B?00Y$jX%k0$^3fBrpz(SQEO|Cs-lybH8{L;i34zyJODhYCZ~ z|L5_){{BP#*K7XI$NzfG^RM;%=i9#z|L6LufBY@_x4#wq`#<-k|F8e$f3Ebu{qrAX z)A#@W&v6=yfBs{dldRd^_QL=C$GR<3SN!`w{|of5pZ{F&Z+$ZsSu+3oKhu5N{$ESm zsTu$MpF^`1%l}^fuV;Pp-o2ghznA|1*Yj^@lmE5tU9c_5xR%p0yziB4OLP5K_`gH% zFZ|#Cw(`CGxBs)N-hcV)81g^w-rGM^=s)kEw?qE5h5xqf{kt*6EA&&I|MMS5k!{oR zZ^cXE+4jFS|9|bFf8Exj`j7wX{{c`-2M8#0oBfSp0RSe}0RT`-0|XQR2nYxO&wYJM z0000000000000008vp|N8si)}#96Z1S!C{Z|zFD@`F--~akc zT{Km_{ij<;Q=II0{r)TT3-k*N!#~eoe|h>C*57}vw{7}Y5IoQGuP6G~aj8HAf*|l| z{NJnm>(w>G=fA25(=-kK@$RpG|6BD-*>v6SzYgP2{QAqfE#s&7{nxZhvd^C{fBW~* zKAr#6{cYL1r%G`Y!|+xL(D{v6LgkM6gBRCw^+mSkAVap`~mwNJLCx&9~o7wGx<`t$l1?LqL*;s;O-`m=z3x&Q0g9YwZ{%Wp+lJ{SK!5b*DR1FOIPEicOT?|=K5 zi}lk<^Yrrb0{!P+e?$KA8}f7r(f=r)=P%lG|IhNdfB(_spDjI?|JL+>0%~8n|M@@u zX#ZdS#Or@Re?0zu;Qs;3U#b5#6p_Cm{|QAHBL9N@8-Un9;fVdCfXJU&lK*jm{r4e@ z{U1ga`wwKxKOX-(vhe>gT>ou%K5#+*1RwNg@!z;RsekSjC9uCBKkG)q|0rRE`bGPB z;~y8#JO966r2ggq`#}F=>;CWT04+e$zme|S_Fr&E-)zP5kNbbT>YAtc{a57wi9GyY zFxUV4Qv8Mz&sKrypY>?^q$>Ww#Si+w{xU7aS}aGwtkZ+>JK37?&x!rn`cJiorXQ@H z@`qRdwO)$y_h0j5OaAqbCc$Z_{;xDyiwDleXU+EssZupE&%1d zn8mv2^Ex)s7&o;#GES}LK&$y{hSqu_YQ7&FatqNh5OF&+)^w?UU#c~+%4v&T{dtYo zG|M+T-*c!_hx2j>bDKpukW2+0TEzj!Xu$1;9jB#nNzXFtO$Abkx*V@p|L093{aQ^UKkoU z%elP-ni-thk%gxzr?)$StlG-(6a<@&x_-3uH42@rG^?#vGst1Catie8t>HLBFBJ^2mo(uEzi6!Je!vSzuef3BTGU*R@ZXcER0V{LLb+wR!7iDJHL zxlS2dUKSCJZuu7HPF1XEWIlJEe$p39J)amd0fCAiJhqoC+Wtqzu4kv8;SqoEC_xi( z6iJ(KMi|yoL*d69H&^yBCzm;LL4tJ!VvS7~h4VUxb2ZQ^%QzVIkIU@9xy+Fz=P!6P za(MSLwq!K)t!y%vGj3}0J_iaT^P)6#2$MCQa`f|#H`IC1zL!C(+jx8isdH(tQwsX@ zBXd6E(oWyhLo?b;!6vU7qB4o--g@4CeOlQz@Exb8p$X=?#WkbpU&W%*q#HlUCJ6{OI15Na07R%=9c@!Q-GPB%WyCKKMZ}fCI z7-tXe9RQTHGkO1|H{|P-ITd}9@qE@jP@U0V=~&vR{23(8pQjE3GbrBrt!+^-NLPle zY7OR}OlDDO>DQ^wDnsXSwBke7!OiaAh2Fi*kgKawn_oowak?qi0&%)lAA5=Gm1cp}->h^%dtdW%m2``fMwsH#gG_&A&e{ajhn^xC7)!Ru1(#SP8;1pRmb zdB#x>jVzc#6K^Hmb6}3n0?{euIt%vjtsfD(Toz8_P$q>ooE?~pjtK?)h`}Cu{t50* zveI5?eReCe6ft+kcKR?&*QeUaQQqb%`GuqRvL75^?GX8)N(XA}2*f|o1 zEOdaS<_}oRGsp;dquqVSh#w~rGlc;L<(!4%3+wE{`L2BlTvhjs`vo6r#RHUq9m@jT z%-zGq;XXbGM7@+1tzku5+WJs@m3#+vyPin3|SYvBJ&rI-VNl)!57w z9CNsG0Hj^}L81jiM7yc8U76bv*2;vvKEMm}Lc6mC%JY)+%3SoNL02dZlf8qW>@?gY(aJX%QorI5_Io9P`HqdHwK!58cxF3D(0oA1^+}!G z5~D}xD0uwvJ81-Bmj)q!12;bxre>ObI$$pqci$ArqBRtg2H;->z6FWvPPJX{cwmfL zmY-y9*chHJGGlRQJgeV65HLUd(X7X?%-9sCz2~8IMg!^F2cNC!gL+02-wLiFovGN} z!b3jQaug%p;Bpnj_2S=_rS+ypfAMNEtR>br&lUPGyuNQ`?I4cwzaAF3zjmLp_bT z(-$g~Y2%p-14?!%!y6Mx?aOxWVo#9!`64!y(M#H9sAGDz&AwGA zhOJwLzXLvL@{@aU&wQB#1JIX{wrJKQz*kz%5|S2n+JPFz_)yd#WL%LR?#ZPUNM@Kn z)T8_Q`)!x_H_6n(pylr1CXGOvM{SMo$Rp(1Hb9nvqQ(xz6_MMm-dJK1BC;wTZy=GFnHmXP(goox zk}`epl^##^Wpm2gxx9LGk5W7iBvr3u>4F7y<--*q4sjZQPjv9%CjmsQ* zA;rDa$=QgnM`6U=AD{H^tLi@>P=2!LIx6vU8_h} z?%ZLkGfFg37gym^FAywzA2b(IMA<2+3@eQ2cNn7`=i@1`pu-uU4B~$=`Y8I$4A{Gg z&8}Lf?fizz_(;@Iey#CZu_#h`hOzjv4o)5x<{SDVB2El|}m0%i8^AT_}(jdh76!kSK6DnMN@cl%eS0Fh{UULJxU~F9cuSeJR;SSIy_7I6n+rQ$R`81>|MyB z>&o*UO`CTL~+9ZyQ&t!>WH5yi_Q+(WqK(VZY=^tI$|Y|7(rQP^qfC<`^?KH*5c z7Y(FwIG{j{)-n3q@nw>1-((47_qyNI{^KvbtW?CA|E5R+G*W3k$yi6v1}q$8>nyG_ zf#R**9L%2!uD&>wYM>QWhK)&E7l64rl$)6auHqw)AOvoiPm9VX_8udnuERAMGs9m& zXLte~D!HKJQ{2Gv#Fr zmPP7j@7kHyZA=2J0VU*|nI346AxoJ02b3^jHkUK?wKLZen%=)N`)Gn{y{>!}B%A*5+CQa{wN z6WR#9AlBrUYB@ZckQ3;XPAK3)s?Jy7yC7(zY*(@&0s?zVkRLWQ(^OU)Qqw@D&JC2o zxNLfV4~VSK-u*h_Oz+20E6I1QTg1#f!-uyAmv`1v6?)!u9Gcg$6a|~o-&4&$Iu|~P z;(8VWb}}x-DIEj8^_h@s@a2FMD0s}j7Szs3)fANkMOw9ziMlr2-K_e<6+|ROEL@iF zfOu9Vwit^cwjaI*DWQvkt&IX?(J5eyT=XG_&)W-_vbB!&a=%5QQ~CS4740AU27dg^NrmX5gV*Bnp2d2g5Mq!&yy&!SoYQ&to;D2OX;-qPz4at^aH( z@$MLwwy|om1Qq#Ka<$Y3ewb12J;we?pMU_y+@oavsPb^6yA+2DI z%m~@gE$U@?WkfAtE-LXuYFd2-m!&e69v*#`(l>tcWa?~$j_#WAoP7|3LyeJ85QtZ5 zRU>6@+3Q&pj&3j z3kR}mnw3-ObkR*+;pk{Oa>u0pX7z^=^m$A`RRE5${TLwVBl3@Ek~`oRga`sF3WFTb zelh5~i$crd#KCLrVTa7pJ1giT*;m!=0Lcy3WK(;8sE$lB^8yDJ|CGp>&PF{?$cH1zKk!IBTT{6T&X9nNlQnZB5#Yj> zERg6R03g~R)zyjQ%Ae3VCO1g<{yv4q5l8F612B-OOh_$tn5zCwZ$3Qj{>Fxx7BGHt z8z(??GqUyUux}#YCbZnU?yw{Y2Y78u+JlEckpdYTcfa5rb{@+S@{e3xPp&Td&miB= ziAo-);wv}T5}78L)g%I4g6KSuen-~KC$1ctqv=bl=mA35jO8qLX(!^Bg}&i~LDPMI zd2vXT44uCgt127lA(|4WXlYBR~40nK$zzD9%5z^h6>(s6y(kJk_P{6&x|*rxu8 z!SCo)-{dRAZ#_aoqYePwtXNF@fQpFFxlYI?`$)XmQOGlo71<4*B4pC`m&{+R+KT*b zNe=QIUZ4FTl&tgvwGs)3ar{8=+HzP6 z2-*D}y$zPudQ#4{!!mO`<6%SsqWp|970mQto(!2g@Ga~B@kZ+sOMra$*!cz<-Camy zse<(bK7$^|#y8dP0*cP*lcx`XY8*pPgZ+FIa?w1+0k;^xDwu+kj^cJ-P-hV6fW%)G ze+4!Oe5ssy$uAk>=pcIX@Z?TUl&8m z(j#{h4xwFO2NR^To|{Lhjzjo(0FG&ZD3SKl6RrZsbZHousb#cd;Ow|sc+|NuCm@Fw z*|*>^^a-X}H3Qn-d3W!7n?4P_8X;FjNxW~3zY5&8&nE~P2fiz?<-bZZ^uK%n=68jN zYytvl@NKF<(~K8!mD?d3YW>azZLM7XrEfZ}gp*t^4Y@qYWxBRudc{1m>|dGkYh`54 zJF&?VKr%AQNSloTeI|47$#AJQj5kvf$$Cz=RzdE&TRQYeT=xpkI-rK=A<0PzV4;bJ zT(guBW1yP(_RbuB6F6xl*TSVbgbwRG`dr2$#z4cnfxksqFHt$QOUCZ_6yhle1M*0J zfM|_ZjilxrpY@V4RBT7QkGDNO%79(nedG9{eEB^cbHKbp0vr;bP$VM%X!BVa$+aQx z`J?Hw)Z>Q+BezGSGSSQwUoAO*RTmz4a<$(?;IadypCf zKH`S3J~NnFQL-*?1k-UITCAZj4lLT?4zmgBHiCA2uq@It+@0`^lH>;A=bML^ za|r4Z4a+CDcmgrP4s$rtmwDehU-)Zyj}gUPtWL zY8t;P7isL}RJU;5`gqd8-ykU)WqKywWpau!YsS8X2GYCosy zwuNCzP=!|$n-Bpi;ncS>aoZ7!)vTKGywxukCA}vq3wz`1Mu%J{f#YC$3DAA}w!%>^dy`LoAqGrV4fI&#>o|xhbe~nK!Xr zien9~Zxt-krE4IVIa1KV7<rS|Qs@Hui4$Yk!~a(dF%V_Ncb zHY=|a9eCCJW4?}h7pzxuvW2R3X&B0HBr_0L9WQTH+A7_)*$3!1*S*q}J5r{BbK{Ni zc}Fj@H)pyE!@(ySqhLaJ75rk1nAQ$hr3CE0SRH%>jXYf*1~^BZ7VKIh8IuzqBELUcfKwy-fD5&ei0^W!ZdgCrdDfc z`Kp5*o^$ehC>a=I$fYb{IGc3wea|qJc^}a=wuGkzkwh184{gXbGVz9(eA$4V2c7J| z22P!NUl2b;FP5Bib~jbm>HCY}U4g82BkQK-4HMFX_9}|2Umv!!#0C|<(=rPZx};t^ zVmyZf3yz~$BuEX64Q4@739|{w;#V9~$1_jaT$q9bhq<4G?lvUQoNmU&+qU#`kims+ z^FYwc@I$X&w9DCE^R?gi$u2$lq!MU^pA23)x%pTzg3rbGB^#K8?DkY*DeJSZdf6Ii z6)%}`x!zdXy_eS~CQ@&Tz+NS`UsynLOF6LBM3Pgy>MlsyH|E01<20vj4rxy}F`V|d zQN^`uCfHL7HxaN1du&4Jx*&OAuHT%eo=p^`C)m_-Z;S*@-FLH$8)l;CSr2%*cl_Y2~xOnHy7&CE0G~S;miND^Nmv zT84P^cc^jS{|-(y@sE1g2#hSz^c-dKE$CB6fC(S&L@|zL#tzipW48I~q#S0ZC*MMa zqC!MJ(wxo#C&W{|^jWfidjG4SHtLCilo%BTJw{HAZmojZ{>ESE!_o zPlCn@YmTL|5sy&dx;cH1g!wdl)995;v(-q8MFfk^sORLYvYM@k(_MSA=hC|6_T?)bwK9bsdj1F7`_SsnqqGbm3|hkfXpN| zmrdm2-s>?v-1uJ2Z0f{aU(t^NL#*K@&Y1+$%$kSL`bqdkkT72mC{W)F@pk#`755h* zIMq5qQ^D*C>L7_wscX3r-t1=5lYIt#%PFsik@-lcnBup`#8Sz(dh;zoDc{~m2!!#h zn%zPgBiwXRvwc6CB>ABJvtI+(&g`{5sH+P*oHN2jv`-ik2d&P-dhtKMENW(xoAon2Y2$QP4~$(uOb?vyiLO_rX!|cl_s% zCa@|@2_c5>p#PHReMi#P(}!)y^xz3}bG?ZtC%|mq8u{qV02n@rBMi5c+e*HnH{C{Q zjzjOoAtKQ7Lrv_KwI6~fgF{wcN97VVZL7E6C)Wp0Mgztwg2$zWSZ97UzD&Fs>umbS%#9#q!lVw9 zEx@A^jzMvO!L#8P$67h+uFyeNHiy67v1FN&w?UImpXmwU*3Nuc5@qTSk|&lU;zidt&Jgl{z5lVQscs6baVsNl^>dawFIJbKgs$_BW4J|{ypm6@-gfx2m zq#=^gYk0i5wC{G=WJeNFM0&%ZVWy;>D<5u%bbR**p}D=!EkhgAdV54suM7chbWKQb zU88mILDSjZGCStP+_rLoBc4hOFZL*+O(!<0Z{-1eOip}|P}D!CLaltUvL{GF$$&!xB$NX#^EdUC1(xCAC+99@v^hr!q(%zmba%blTz|h7%twPQ2M5O+LE1EEQb#+ zjYGgx;pZ*)vmUzVbSDoRrzd_#o~dMON~I||b=<21cperNV=Th8K7N^Ws&X|`vNp3=nW?i>6zjW%h;zi`zDc%DE5W+~S65sn zE!JAb$cxPmHg+jKYcA}$>3ALW!DyzWZ)hfdzD2?w)4iK2L-m-r9o|Dhi2Ww63a6Fn z+KS~%V-1U_DcsJtjGUomg}(9lAHEKv?;MSuSyIqP$Q2DYf{eu1u!H;JoOY+?&iE<< zZPq4_h!W&rVV+X(CF}^|p*nX1qUx*kGr$+%Vx#b3QS_rqUm~5`OPz3&C0Gq>Q&lXD zfocewBnI5gq?x!;{ENzfyg4%CUPFTf!qQ5;GNG|e2yYxFvvc=47 z-AqB*WWFz>;zIUe*o@IwfdVG<3FZ#Zqu>Fu3xG=7E`L zg*=o0N)G0euzFk!@U~wxPmk$R6T8dJAI3D8@l?5UO0@=)K-g`_Pfdl|oV@p4+=6|3 zO5V?lxs15di}|h@5#NTv8kRi5L4Y>{V}kpwK62F*Syvh#!)BtXldK&Hd%HI?#Xf}Hpb0ceS0<v|q_l|-C zQpVj(=IdlDV)$)@%$rGx(5I)NZNac*C07tjn0-#Oc+WhC$G0cd_O@7tDhP^XQ+Hv0 z_~Z9lq6C{NNoCEvGzhK4Jp{~}uAnoPQ=}Pq@Y$zQ?2PGVt5%@fkwzn9Q#wkQAq=ro zpYD66yzPj=&;zMc{H>w39>Xbe?3%;8wq;?o4Q`Vb&*V+{qACo>9nH1LMjoTdzC;wM zR)rhhIN9GKtjst@c3zoVk1VBuQhE50e5O`iHSx67B>bFaHF{ES)jBd)XZ&3)^o3N{ z5S|@Lqk=Z9_(DVh0WJKARv1eX+51Y>SNx1oO@TD;Mn;$EBfZE^1zLx0bKZ4v@|lg= zx;)Za?r$STagLE%N=KEU6`doh!;>q#dO8<3AVN^nO%pTM>dV4i{Sc&3krTw{Jhf}C zU|g10rZH?KN$TJmbQ8Awo#BNWRmKgqH!E@bPH`R`P7eip;>~)gf8FEN15}n4&6Divd%M2S zhWH|GB=hI>?33j}r89$9G~dC|&X&0>Afk58elsLq0?U=qMQtD{zjRRtWy~-r?63MB zzOQ}X9WuU*4*eeFD|7S%pXUT_L=X;1|NVsb$pS`zdr}3s%#MrQ7M!*YIM;wW2pm9A zr2Lr*tu8`Rr8T(gQY8c;LI-<@i}<~g3SwS3xc(J>?iR8*7Hsv0C zRsTXuwvlNtTnKPAsyjcnulblEmSL#`$!CdFspVq{L?5kcBXQz;oj%^re9uCp%e+Aw z@K~2qI<;Ewryi0JKE&B4hc*<&AXN=>A6~Hz30;zh6Im!GR%Z`L4T=F{`J7@7QIM0o zU)f3!q8XRLRIjfyZR$wJn8Abt6{JDJ1B(^_izj9XSnPjg=}gJYDdZH5c2W;zx9eeb z+ACupZX|XHbJ9m*y{pH)^UPBfXs5P1nkcdP$QZ0D#WMCdw1YtTFmJBKJ1}V4KHoFl zL-xC~&hd#)7~ujN;wb{*^9rBU?d-y<4vs3D7{e9;?QN+F^JGxxIU^GRk8++)hw@fr zb0|Jot&X|Kl*Wu9Le9cru|bx-=w7s=)x-CU0g&Z|9eW7@ilTL<8C*C>6q+>=&v=hJ zQ4a$<-lIo;*1_ds-(e8K*QV=&@;QCOvB>&JmOP>#=W^h^Vp3ss`Y;T?dZ8Q!hnTrjpAyCaDFaly#xL(b?-bV&ZHrj(!+G8yHNZdFPv{a^YXE=YcyS&=34A5>vS9%DSg$ObO37Gpcto}nM@N#{n-v^^3_AoYRPS~R%Z@Ut z@+=TucA!~1GPgU3jBe=hD##7Y8-PrA!9cq~cyVY|qYTQ@kYYL4llcPiSe|o#N)@Y# z5fIq;GaDyQXJzfbN$(F7L=PJQOi=+Rs>r>#TbhwvG78qb)EmPkl)AQ{8oLbv z#zC3I_gYAIBt#c=@hVQg))IT7i=Lmfb2yJsDLafH#tj>3wN6hUim45dZ}mJZ7mXXM)F?0bt!NGKol#j^BhyDZ%<9HuJE3C zd!^P8W7+wlKWKc?Cd1G>xL*MSmKi(^9Aojcw=vfbe^?g8DuAk0w-ZKBD{vnw^KgyHY?kU^fLi$54mW?#<1Jf76@hew|HdNuHQ1o0%e#XGe)Bt^(#5jQ{IUOCDw5sT>-`LuyX zD{cZ02Ie7gIFF{uv3Ti1Za9A{6NxW%uyPs9s9{q8d?~t2jd>)COh;&Y8jD7UbqD*L z2jf*0%1k$KGQ(~G`kd^z#(U(5qP`~LI@q-M64Rhoa&t`2w3*cBs?YhVDD8_2Iwjln zWI|(5Km{33DFG|g$ztqL4piJjRw&mfzpmDD^+EEOe)=ecePApdD_@so`B02nvueem zHFrt=VJ%E)x{Gohn?HT*$NN;?Q7tw6c)$%IDuB)8z^wot)5_2q7k?*T+OtVf?4mt< z=FJUJVs`M~*xOpU`3Ybowv<&IQT{zt>IeMnhKNZ}l?rAh#0*p#WFeUEQgTPFEftHJ zP*P??U3PDTtXgaEN&dZs<{Drke#D&40_yx8GhzlsZ5fZL_dTy^NTMLEkz7Ya&c9CH zlZXAqL-oXV*CAVIwI9~KkjTmryn**8KKS0FCslgFnCw5thDQ4)lk6R>6tl^i0bQ zL}F{Bi~?Tiwp;T^8M-T0&Vb%0fDJd#fzBsi)!-O%Cx z`?L;Z2=<;*UGrm>RO>jmj<_xba4sY8MOr|)wX{=e}&667B5oYnC0JINU;cOM{Ay-*1s`ZA{*$? zhT`D*j>_CNohvZgYUeXSkC6#qbhSIhQZ8m^AHo4~@$^_$oSw%o^+w;Myv&yL(MOAL zUbs72xwGmSvYIt)zwk0*0URvc??=UqkKAS^WJYD)G6THik-!gHj|tj&mC|#o)4FQW zAItg%2o3{qD1uN{3k^Ioy9oWR?`kMEVO=Dm4U(W`yU#@3`36_zX1QV*?84&^Y+D-M zXJ+22o?w9SKAJgj`y;!uz;o(z@k1Hwivvo89pr$+jH-v*;20nti}pcw%yMwn5f6!` zAOsE>hhULIZgtD?+5MV&Mt;&8#)t(P-2Eppt_S|4#wN-lrY!MQW^I8CT-(aqFM_D2 zT~m4Fq@8s1_7l2?H}&M5w+!Tk4oCI?o(ebJdx^ky#O{yqR@$eA1OG9_-SuVsS?2SB zYXqd#k22Q;2e#qcu$Q4cCo)Ift4NEt%oG?fPAqB>Qt37j3?$b=aD@be(qs=ghIVyI z*WZ#W{Bs4%vi1QyrHcw6_QiThW(O5#XvC^kVI?XmC`-uvPNkQ!6~)D;?`2t}#RLIL zymplwLTJIAycp975GaE^Comn?WzK=m#Lig?UshY=87K+hRYlp2^V^$%;CGoQ-4J}E zF>;9!Lcgs&A*z`sL`GTg@S6Am(hlX^U^RvzRIQFr1#XKCF}Xamk~U9e@u@<&AwGys z%$^E7(h~IX#y*4>aHvtj?frODHY|q(#PfPfa95iKK25-~LgxMdrs*uUo@Le`dO-|u z8{!1FU^ATHZdd>FerKI=5<<&URXgc!q*YUrx!*sSh099Ye|(KqsWrEz3!x~aFtIzd zP>eiK8FG01&Q9au_L?sTy%4G5OQ1w&QN%$vH58v2bfDv^VfTS`1VuIBT1Z~fj?m+ZlZbTXtOOMU4+*bpmCn$)JA5ga_Bpys~0lrzWAFsWir`k#6% zO&-_5oYiJcwTZ|lEVrk;(g^F*dvbtEN@T22AHq@gK*3fVp7U@)E`mS{1C7$cHm#+F za*g*WSVIhF77oQd7SOs(T0jKekF)9zIn#6W0pw;tSN*`X3liLN5Zq*@90E*$Y8dLOU-o0KDtCub}(oAJIH8v%SQ3aJ!>xrGV~?3;7R%RB4?+}1W- zd5a+PU`#*E4*{%Xe$-s61eW?2CQ>GH2FD6pMuR-fsb<>-UENe`7AJpqErVqrA)Sbz zl?e+7paaCca{;DN(%lM?Z@uz^^Sq9PZVPLt$Yk^;g6}&kEs6I_&kB9X9A2U?(IC1+ z4NAcCBsv7k(REyg3Xnv=I~DU?--o$ch8jQkm|~-@7dAxpDwDG2^aA+|;FjHddfD%Xa_Ml2qD>TA zC%%Hi(j1gm&Stt|vf@`zoyi|^G1>5bZBU{y-tkURi4@8D$*$+w5H)!Q_j$2~v9Z1? zLJxscb@!{60Yc#eJh<(-2QYR8DvM_#GuuKGvVZ|r=jR&kXPQa{YpNutrKobXX+?G( zOK%`$jc7O8uM3-;TNevQ$8xLhaOMPa^YEeH7l*8X{QwZKfu;I^2n%tK3f5<4=4Jjj zb@ezLU3wa*zsu50nZ6_^8~lc$H*CSL@VhRTdu<)Yg-n5KYFqsbaa;w>nUD@w6Pp7~U$EDUdB2y4%A<+bvW6Qmw&}myqGu z@*-frC-JDB@OBP-1A;1BadK!3p@$ZscFlO_onazXCe@82W4{p0}5-ltg@g{@w`IWm-NKz1YzoOxtgu5YsqZe631k zB9R;R2bcZMxd1)G_q`pi{Bf}Hdgz53Z5S0GYu0)m3@r0XGZ$g0SNO;vf?N$`0yF%g zgEAX@sqQ&d&?Ujshp41DphlZLP1^b5D~?Qp#y6^=3KG@IA0JwEdQKVCfCHixK>a$< z&t`$<{v=9VP}=E~meed%dUh=-$|-&LAo{^Uew_0zqK4xkPM}^f0|+|b|Jy7Joavb$ z04Wa;O)JN2MDX86;+zCqlN`wNv!^}$2;}h!_f}L7b!=ot|DN>%$Q<8R0yH;<47u~~sO7H`FF z=DqEdxTW%x03ojgK*C7JPqftSfEo+Ke6`H^1Uo)eDK9JqR?|h41Oao@6e50l3gw+v zH;N13&^Aw;bMEc}remlt7HyJD4}0ibD;L_)fJdDD>vCNo+#ItUgj)#fT=sv(Y>JP$qwmp;qk0Usp;!y_1v zy2}36j01-RV8w3(u%IY>pa&MWD^*h@Y4~A$5{JbO#NmF(O7uekLMTi8n+-q6pMRS@ zL8i?n)#S)6U<%=fiTfVTETOEgt{#P~mk z`7!+0EPi6`jh{?7k^C*EQ6-+}&Dh=xmWZqYJEUYNCCJE}m~j)4_go~CkRFlGTH2;!_v;o(*^ zvXfXgk%cGLPjGQjL~KPoT!t8gbr9N=;H&M>6v*=L?O%H3Y4XOPY>6nR8^W6629Um^ z@_OevWJ+lt9C{8UyVdLrcz~Fivg`JoR%C9sah?T&$p<>o;t_lA|S+%#+wZde;QHwZTt2R?Qu3a`4n5Vf5K8Qz(MJbxWdw#u%~2V2R&TjbvNK(Mx6 z=u%?Q$b|NhfC;sw;ywro{vOSqOW}QVsq!Q4(=1n4Tc%s$&;=QT)J=rb@gewhTZvd4 zK5JM&FFC4`>2t4wO;Q0GZ~p`!n1cC_1YhqpKQ7)uTnz%_RW@&zJ=k{&_HoopV=W3~ z3@(_Y8$cnEJLtYAQRMXZ)6`^A4USrlcGp5fO?otJ1O$;*r!^=KQ$I8;Ody6+<@_qo zzVIWdFHJXv>tz_fj}JD|_jYw&4(t0PY=3h4!p`@^90dWLH@=f9CLjkI0l+Yxho#g- z)hw|%w;Ecdvu6gC;`3pX6drAUu=2WW9E=8X#!)4IAeA423=LXWwZo!E1RP;0{h zh&;fwi~`VW{bY>w5k<0~aDT@r08?P~D9GOl0F;zc`5cnO)y4tge_`+)@~u3P;_Xg? z)4e6D{jFU6ES-pq{E;P%%W_763}zjVB9P56e)pQ{fBrpLHQ!eQ>G=}fz6g4sm2yIS z{KHmxVJun-uj#$i0^QNXaSh=HX9lw&hEUM_Hf9E6Te;cel4}C>(F2wNZ8@@kZ4?N8 z3HBWJM(6R(W(k&Wg77ho8mExm?G8Frj&E-(^phx$B`h)SDEW=(Kr2ev0-zKz#K5IF zuh6Sz3V^(Z0V7(+%J;oq41sNCrK`-AwjN1UZPx1=x&xE3I0zz}nXEaA_yKM4%X_Vg zBh2lnIo}1;H$5INhvwC{oX)jxqxpxAEKR`7fF8|U#y&2)5$3+_-0GghL{w}Hhfw4` zRtAREzfx|mrtt_+3_rYN+20Z^owqk`TB{LrvV1B$CJ0nmPP-)rXdCXFeVi2t&) zNz*X+jimjtWudS$?QA(lG&cFRe;CT7lzMroNF1p`7e`gq#N6GA>J#0|v z`7a5-+R^V;njD_Hn`*U^Ca+@THih^(Q3|<2VnIz;X6zgA2sfMG3G(*)!-gcq6JE9rPcn0k%fB3>;RL)4 zvUC}l8f+PiqNZtt5+!B$fbLkM0-2uU)=T3;P?Q0s#rPZ5O%gB<@6CaESli{}KJcyl ztpPMN{48Pyyd*f+lJMqeX{WupxJa5$8J+{9xIM=oB4Y zuSC^ZxRWUw71U0DzqnYl2%qmpzN&l~IGXaBCH>`aYL#Gh>jQPk*2;Gc35~PELF#m> z+6i22zC({5{c+)EXP-*U5^nGeS+oE_K)%1~&ym47IcA|bWj}-U!C=!p?f||a9m)4o zFGKbwa@s+7daps+U@68%?o=?gTmU+klZ~7|6Js?aPgM&l7TZC^&PQdK~sX@7~rDu2s zKO#-`wl8o>8k`Y!`3vT+8NF&b=jL-xypf-@-Cw>>_|&A2zYRlriYjm%5U)pvmiBfR z506j!3E(jwjRFSkf;v)dcWPNrpHeE_AMka++i4roE@j0NVR><&!$~8QMn!0^yj}t6D%c=L7>n;D;7)5l};w8|-D zSJii*pzh~WI5ivkIg;_&iHX$gz~yM(DbcP~n%B3V>L50peLy)%lDHbGIAB8Czfs!E z#fmN?t`1d#LlZB)A;ZEYkduT25&kg=*)x@d%@8s#_4p{JlBi9C3_vP)QO?#?|lM;>PkEwenqFA zeqBx~HIE!J72hfBH0NpyRu{CGq*2YsXHdTmzj8e zb;lc7eUW zc~rctg*@;t_O&G*n1RlSBZtsnCe2<8@E2K#!muu>_bM7|eI)v}{OwynC_wQaV>z9ExT;!s?3!-kx z!02kI=ioY9-1Ug z!}D(pFEvzRkJw=5d!SS;*X`HkT*cQ>3Rm2cDpIwpdcUEuwuGg2E4=vu13VEu9YRRQN065k=fvR%Qug zuI!V|D|$Iu(hUzFta-oP`x3`=!?+O;*LsKB8H4SYL7%JFipfv4>Q?&IoBTW& z_{^nW(J!u}thG{jR_e&{Cr%zI9JiGCLejp+LZF2vpV5~DA45}L;h{0v^&_9~+?$UyN*UpF0;2aG7`DB>s(et9Lo^;#d-sC>LWz)D?eNsr^p{;Yz%C~rM-k!%0ORh zVX(q($kpMW*&-oF;lWwpky7-iUM76md>nN1 z5F?euGW-oli^QSD8K_8?kk3r?yxQ&9I{w~UT(lSf*H43Aq2HT$X0b?{A9~%SsmO=E zzF&O!9Pw=8t=!DMX091b4I^vqV-k6Jd$@67W!#faN?61yzi5rUTPt6}jQt(`V`vA| zTPu4eY)7SkZfUZ6uN#5%YNbrY!D9m&!Btl;lTQB2&uiS<4iFB2ff)4#On7=p$pC>S zDo(gf<_8CgbL$cTgfHcQV&&-#T!{eD32^BcN`vT@*IXzVhIPhVFoV=SnyONM*WXL= zb#qP4mJiUHTIE>{?{3oJVI6P{J(bU zfXON#Twh7rv`2&M$=}O*35Yj1he`OU!ZSht}Y@n}r2}PEhZEe}R z5M<56THo?>e}poXfx78dW4#7&tq|sWbK(4=Nd@>VJ`X74OcL4UR2@~URByoFa|&HE zyZyp)%#SV^8_6RxWiW;XI9ubCljQQuGnqWviONm}4<f+e-j|J=0dK0DwH|-tV8e3e@*Zr+n!Bh43yJ{-ZSaYq#j{1Iz*n^sw z5#mEVRpi#V-nHhk7h9J2;QeiyHhft^G*4Vb8T8FY)CrlbIkUMrzKj*J4w0dpquQ;|E>q;{2 z_LvFU!<7-vI1hVPdt*Xz6Pf0(6r1Afx{8^VP%ynZVlhIEwQxX?IWUl;ureIqY_Cjh zDc}&fs88QRrOIRcHdm|5^n;^gm?v>RjHHv(CK>T9i_Prs(L|j2*92N>6V0DIlsr}P34w5P5+Kab`&2N+>gfXlK z`?tr&X6oXVYyMM5Sdvcqp6PFdh`P5)*M2}Kz#NWLyaPc}3RqfntVpx2%ta_9WOH63 zkh%4kq9Q(oE!3umIoV3V{ac4y${%0W2!hb4J%42p(uNc!$h(cOdf78iI9igP%?_e^ z0!MAK>yxdHfykHHSC z%m(dnyewzU9@lp*y6wUuQ|yOdsoy%o&UYCV>Rtg74FID$FuI>!r@J?P=Bi4YpNgDj z^p_NZgAm({9UWkro{E3ZqNUg|;dZiI`m;xOB%AMtprt0s(_34X;rj~L@_9$bf%}Oh z#?_s6+~3z5E)0hs>CcDR6RDMhS$>jZo8EM;ECHK+IQU#n))3W_LJNX3MJ&A$U~z?L^9>+O*ICxyY}#x5o7n=_1A-E~ zj!A7!+?H8D1u5PGgilc(!5;1bIp$puaNJ4^YgB^EzF|0u)Y*kIhnriszs&Zw_8ZMa zjFml#Pbu50Z8p60Uv%9<7JgNTSqCF!^L?y0Ch5spuP#dKYY8_!t`_Huiiek7C$!)+ z_Y5f{2Qw9TjlQX1J@L&(*4Gk?-uc-!KXs;I8u<Gaaj$o@_0{lCL5%HS|*jonWWSKv^izXSv ze4et=V?tA0-pb`78d5&#Vdx-7C)rXTqCU}?vy-mIAP666Tr8G7wgJKdBwozIK}PPJ z=DM*Od#^0GM7*gGOh9><$~zv%=H zLfonM9H%_NHjVu=(~#inYr4-^Or}#~muMf^7*m3XQsdnC3V0eq67X6fDK~@OoZt@v z#U!}t-{JE31ntWXWN_jd=xLjwGUb@bw@}&r#)M8qs-?mXkJux#+;!kEYSt!v=H*5NL36u^( zrr58>n+lWKYI^P7Mvjd5@_u<5Qf67YlEj?o%s$Jz3Mh{v=DdSLxQY(|C) zlR%IF$=_x9yc4<$f!AkynO@&eqAW-=RGh})t517~;E^J{g{!I~#C}JGxckm|dyFg_ z&jWGa7ZI@jGD`=8?eDG>@Txk{j%^hTb}KXb=Mo(_B}u?9l$=o|@CLhVAJEBuXxu^@ z&1br-eOOC-`c0&1{j!7d*~VSFH^WixSn-pIzTVq5GhR!H@nf~cxC4z_xJ2)ROT`Q! zb3|)7ILVr$0Q-G4E9pxri@eiTa3~~OuFXmNV(C);@ylj#3myy1QTEB8sDF!Jqq37l zL}HDu(!*WNa(kg#cILx=dGd|{%6ym*F$%aJz{5-7EwHJEv2DPYQP{mwjDLpy%#2myfr9l+A1h z_WFt4$GBYYqs1{9I4Pr$Y6+~n^(j{5aP6;1x4o{jFMnA@fXhPT+mM?|OerwK`WX^w zx(Xl0=!9+LTCr- zW{YCGJJlyQXuOUasv|X7ntd>|4c9(yB;!+5btPEFQxgEM1f|_6X>j4->==7`@hKScF8)A43yqJ3t&ubP?<8t}U z2XS!&#(rsG0z+Zh&6L<@vRVp4M8hzzCEF}!;O`=U%As|VVN%wL^*x@@n#}CzKeGeQKw(yB^d#KgNQ#`)`(h4 zZd%K?!H6D^YI$hbhLz`jSi5c5oL^mbUoS~Bgh;1OINo?ZIZsFmW$PFlf|x@ad_4() zG{hUx$Z@^GCTDdARdD!vVJ_0add>0Xjp?pOxBl$(5!4n@n^!((4e~a zoIve?IAkD6`CY!QfP66E1yx(50%L2V=~23-*|i)VB6|X?_luRclHqF<>9p!^Uo1@? z7!$s2JA2Ed;~lB-GSpp%t*$p{d&3ENI`hD%CZUXWOJ{G%r*r+wv zDqz|RE`Grfe&DtPk6Gx?wwqXvedEZiSle~?$`){YUV{@tKD*IvD8z|(o>1OkIRZmt zK>amF4qa^iiyb?7=xH3SpJt<991Pr1Bfx%5x$i;+jWsCt2C5q8=nK3|U7~YS0GC>l zA-HgtpFW$+zD@5M9NXdCN?DfDP6LfC=wfz>&#b%qwA$ylcqFfh8;DibiP@y}Iu%en zvkcg%A`ium#9<*Q&4u7l6EpJ&Mk6CnlrXSzi6wRE?}bz&ynGEo==Nde?OFWNrDfEEg?0?CI7D39GkyU&=tVK%)t4Yp6%nL7*vQra-MdcCW9NTs-fktD#-~v6t>~ zNV6b?ji?H)?z{N~W$TBp+-NK?T)}|v6gXJ$NMED_^S69W`IPp80mv;`k;{UrnX64g zk?iIcN)O6&@cgKq3yAVNT`Ex66bo9a)2QsJ4LC}Owq>&^Kcm$(=qLV@mOW8-K15MU z2|@Brvnc^B&22MjZS%{n$Ak5Y%!{>*5`eDsJRR$6xzF+ZV(1BLLZn!E7#q4VFXOD#3 zAhBMXzzYqz@5CT0!oRo4TfIVwfz<*&jvXIUV^-t}ECo+CMWG@#U}*}*`5mbC!yKi( zMhJ=u4(**kJ9_YDjLPV*RMUP=hu_fjC_e*$iHON`LC7kzXxh%$hbqZ6y-pay4)smP zsmF>4+@0G=fK)v^_j>a56bCN)gO#=$`1yIGb770LwN)v$y5x#%gfRp<{r8`}Z&)+< z7{ISwSxbfyp)AV5d`;2D)n(k{-3#A-L+jbI9=Jf_oSAv%g8W;~{mKBuVaL`xohhu+ zu%!ft0ByjKCOXR9ob~yl2R1vSkMoOG%^^8*KN>(@<7Lsn<(ZR>0CTF(077jPCekiY z9FPue9c9&;>+K0*lau*`3SLNkS5773f?{6R*PCP1`RQCdi1{CwT4`#uL=;^UT586R z;Ya?AV!fVs@hDO7br&^*25}tM!JEPQmm3S976fUxWT#G z6Epg}ganq$O#{Uxm&afa5}dSd97t0o6lJh-jd!D%QDFwIvCAv*8hrthfs>6J4rVa!?*HgoPh&YH#j! ztj>|^lKB(4vU#xkW7lP(1c`+0L|yKL^|d#fbGe1RcZ-g5VQ1W%`Q*BkLfgid0bYyA z*KLLABD{VS;0B9?sjGTk^!DGLU%PW?-;MnJJ9ot0lM4b6#VPE1`{G5hKSY~BT9bgM zGJ7+VR&;&XQ2JBckOZ4rKS&ECvuio0JopX2zf}!cS@OS=or~x+<6vhF;$y+^KLDaNV0FAKO2@QT9;p*4^)pRs1t za3>&0M^FjWmrau3@?$5jjM)TFR4(yOVPa_Da65Ja0nxPUat$zs@)+4)OVhmGNcnX^ zV6O|gMbz+kQbsJx%Z-&6&=n@O#bF~Ux`Ko@J*|E>0v%kmsc_aV z3dv5MKDVMA+^yy5wpGUtiDDR;eP@qv4KWmY`iu8iRt^~x9*6Y3HdfM6TdUFFHL3Sc|iBKrumC81yh(WB=6a8~h{8Qi-SvB$hsu9x=|AenoK@P>k$1Za~squ1bJ^lO7y zt3@D4V7JaxZ?lHgY8$aU3F+m?WsfG5Chsu3Hk`(HL&^KO$^8OH7AUVVhcxqn{e>Tg z^X*v^it)*iRadz0IgOPPr)vWwQY!#-ejN9=lwx{5=E_X~v6Hy6b_XLM#oV$9qD-dM zc%rYCy-<_^_ci9sLVgkyP9kaft>4gjaC_(>=P%G-@~9 z341-9G_YunnJCj)nnF3i4CufxK=jt(g?+EZXh>-Ru^P58+J1EC2kD*@8uZ`sDhw?f zztDdnjt;sRC>mFlgv$=$J{^NAJ~#M>{(c&K;>%}Wx(y2O*qeqU+rBW!b-nLws0`Ga ztfcm+`HBIa%h#ibt%?BrhOZMMPOCkj9{>W3Y8|Z@WjD&_UOHrn;e!PVF&4h_(@9w- zDnmXRpD8-TjX?D?J2Bk@IrYvn8J35m6p~LvI1D0?ezJm=w)u%p1nvWEd>wD@bYo1+dG=y=^k|5z=NDMnf_?j~H_ased zwttmIS1UkwV%9n%+!}PCX&v^e82!`nOjT=$dTz6cHegohs$pe+-iKw zl1SYGU@qbFg_}>4ljVlShiH{#q@^$OWpHC{NU4$3QEDr_KZx%k{G6S1{bBzOQ;>Mg zW-xQ3Uwsk8sH0RNji;AZrs7fuZwn+Xf5$sSD3bx9TrwMNOtWDkdR>y1f&brrjrthN zbicE%O>P`;zB&tIY=TPQoadRU{bU9_?z@?Y;#nvv*)3j{Dr|pb?r;4CXtf+F0lzWZ zV8zF-wv2bZj1qS7OLAOsM-L!H$?-`b{(fG%WPPwQt#|U5m9ec6jrAdN+X##AP&F|7 ziG)II=J|Zv%VJDf`t4yImb`;}A3lKm#u*TnbULI|{70-!UY29Ae8)+s6ck3e#ybI}rn5(V8R-ufiKpR^sw$jt45vEEmW` zi-F)P5yk~i(izqbNL>4xdBGt& z%46cTrm3ri&wwplPf)0(FXYvScK5>f7nALSNM9I&NGAYZTtHX*Zm-{oCLlUEn*5M} z^BfmM((o}O_41ob4UnnJ53+--)QBPC?PEEZ{qL-Y-vh=wZRKx7scRLQ+Mf1T-|N>v zwl9+eB&2NNK^M4eX`#QpKze$25(v{tOYv?|5P-2+FVw?%4r#fg!aHyc`(`X|T7^iS zJdKa+x@1XE(AL-cmX#{l#!N-qhr_SWhY27&E3r%W$cnM6Gm*8Fw2Gr~LvQGh4_7hy zJNLzRg$Yo>Z6HmlI(`-6CBOs+#4+LiY7SU%QNv89CiPi78_#1%=P-Sh zGy2D7sqC!bMV;BhmjQbriN6jwZOJgK~ zHRK#juCTE*&8RfeQ?vDGz>TzgVo>+`@=&WIuN?`|bp)sIK?`J`N&ez08B$gL6jg*o zV}P#cg4+MK!jv0dSkPg8%)fJfkRP=5BB(}XaGLxBA@8&=cq?5=T>^%`=RdADyF3mn z+{x>$URQhq?gvU!99@>?nx5Co>EF{bond#LB)pyi$oWFl#v%0w!w+HTyhWa>EQa6vyWtJ zpDkucJOAG1kJiLz{K8wl=PeS5j4zR>3isPHinAyALP-^oCkNlWtIzT*}e;|Bil!R~?jLBO_VzIEmP)z$As<*s{l0;Mng z^DAy>?-GW<6djxI;fBTLyp|OYYm?i4XiWb~^l%F@{nhEHm`d?PqJKCjT*P>Wb5faX z@iwU)yga0ZJA%?P_}!^04M~tB*GZ$}-lB@gAOyvUL)Ly!>-3$L00VR7`&pq6RTBiV zY<{rqDQ*|~0;JVx*c9-PvZHAvynYP~x*^_~DYT#C9tL?DxYKKQf&2=gVVZa=!)a<$ zWMfU=ZvmNwe(n~4u5}!dpU2N)57R^^x4#n+fhh6c1R$=(op|Ra@)0Gx%}P6W_fQq( z5LyRD^Tf}`4^v9f2J#N94{*3y5TrCrV?X=}-k2cyvm2iIFTlJs&1IRx>%0$!SM$0=&b z(Ky8Jl21YE6j}9`Q3jpcJ%j}>VU~8Sgv?6*YY2pw(i(Tbta;}lTodFb?5FX7o$5`u z|JnY_1r@p%pg9N(2$hk4nPB{>lcY1hkQ+B^eI4npjsUT%55CaNNWnoiP~LHrb}I0$ z%$w7U@MGEZ4wYFi$)4gsBEa?=osEeRwosMu1QMV)UpBgaB%kr4n%P&D2bQ$710do( zB#AW0k4Je2{PDU?gQ=MPcTE&t9k_nMV?W0^WP&DCxxu^pEC+ogls1Yt2JdASud=@@ z$GGhM4SV?;b3rt;E99~A9&Oi~Em?sqq%RAvU!@+71}J6k%kLS_x?EZ#YUvZbRe2aA zRm-G*F~^bbRr0WpJXrvF%33@VMqQq5EL1ymcxTc-U zh^e3c`+nhU=j#P2`BoY$wW?i~8Q;svFHjqY7aLQb5||?#+g7$too*Pa5h3pyqAhLS z-dKstdi!0UIB$99QV5)_N|%}6VPxi%#u0+)9#AMXYjoBBaQSo-eXX)7DZ zgB>#qT99LOjEq4{FPlBFmc}42nW$F3_6rc+n1Mh$4BR7q<4woByjUykZ!7L^BK@u4 z-qi$b(e$}>Ymi#gjj=u0tK~dGNeB3s5+ymNLB9++w83d(M?A~LkVdsIE_LBoxEV=5 z!Is?*BpO)rn4>wj`$g6W7J>{@o%j5LqDDvMzw;(^3zQP>hZ1qH&sZaucI23=m6HXD zi1Hvfllx{f@?oKt9Gm!l^^$=hp5Pbh0nsY~X+CSHhl2m@424AkSpEeUHh_;nftW+3%V`Rg5OZ?gP2lhhj5-*3t1jpr$1T{}t|aWh=sA%U7u65fmozJk7{SF~rcY^^ zQ{eG#>VKDTTR?v-$m>Cja2j1><|N6bOo)c|pNWDZ9EY zjyZ{FO3HFpg33&$P^zN7_g3*VC_Osrv@f&n))z&J=$PEOledxR1 zC>N@DGW${;4-rRwe7N=v?lGX!iXcIEFu!sYhKbKS z&aiMtQ=p-sjhXCcgwr(ukrhOvqy_HddNu&77D;K{;>|@Lyxu9=z-);G_A0Kv=_#rJ z%RSLH!DF~rM|X6DCG%jJ6>(=tIzzIjuK^bD(pRyl_6r`5m(1>;@z<@1RaU8Dsf0GVY#%N)24k z6!i<*-Sp(LLQuzG7xINtQCp=z=0k#0t+Q(bO`4_8LH?w^9LwEw2 z296JrDrv0yHRaKfAIFUwHU}+ z9eZxCYwyV{jMzkbqA-1n7#6?PjXqJ451b4{dLKG0yZ%n+O51^P3gN$Ybg?2e`gnOg z!>3vpP%E^>KT?!|^p?Br1JVFTlK}lVBK%7{@9*3&u(clK;uGkDP!!CE_%P%;Yv`A)WG@VVsDKwFyu~OKoHcj}rTZ*J_o4*D~Ud7;@ei@#>V>_oP_b{ibzBzhxt| z`!itwigMC!c*Dg0#&X|3PQ}CImyvukFl^;sl^)0@DiOLukp~sm-)zwW4fyRZ;M7=&JdRu)Qzxt<%b(5$=Rgrwr?c* zzO3-o-;|m6wjM#wlmE7J;QE|?=-v_`{cRX?j9JC5Gs^@p!z4Rjl}S{`z=fgossWEz zLFVg&O;dbl;a6;p z!{M0|ws(|wp29TCQ}i2w;DP{x024s$zcaqs!SDN0_E)~+&M(d57p{+CgEc2C9Q9dE zf85o3lM#`62eV_xAv(~97s1ciKb$fzmMDI3r3^dr6}TjOjKyh_Nt8<=DLrS;di?2G zxn3i{pPIl**-i}WyDvgg2zw{o1R8lbrm*Pm?1n)E6c*GFsNg9cAhz0!e{vp{pod2s z6bz|wp-P-0M^wOk0M!#mRh8TU*1HK8`;RewFrcNhEa0 zvodFaVM?(qd3Vr;Mm0dZLQ!|!a$c|xQ2VWn4?PU8q@v|vB?`5tHZBt+-hPjgD>j?1 zrS5fG4~da(Nlr3rIS4l41S^EP5eRXlM#Z(uYz!$~KZuN%%25ov;jHCXTB-6;KJN2C z4cFjmL$G|~8UOf1N6PC+#v03%mqIjYUul3?fTLxqI3Z>Lz;*SUqOqoJnS99@ck zkKAcW^%`YCA;k9s;N=yZc*u*NyC`E_4Bq73#;ZYL7COObg3wKi6M#xnsX22v6=9G0 z8a7cQ0Inqx0jSAc3D>(A!6MOh=_a~z@ZZk#*qcDR!Eha{3R=j_SG6Xh(@`Bvc~jL4 z-9GF^?!xzY)C@|U$%YaqMKz63oln4#yIYL`scn2=L~xn#oO8mt+g41%{=OvLRoXDu zWP=F(ytJabol&kg?D88%PUgz33kUj@@&XgY|@lH5}z+Vm5GD6Z9fKy1^ zxG3Ko0J^yZAY7#I|PUDcEu{S zc*oTwiXqDJTwtg+F&8W6dvYmI#nRg2lp~WUdt+M{N~FQ;Ilj(Tj*po&dQGngmBiT_ z*F#)EJLJ)hNilh=5kIzk_N6HvuiO-L3sTk--cewvB>M0=^) zQ6P#zSdMJncSfCkv>kLVl`JBmc?+nE{3XOtznBBAo8&wU9_L{HJ*PIcFG^lap=TTN z)W?f({9op)4vn}wMxYZD9%#e?XzssG>(^qIq53Yu&wF+&q*Snqy4bIg5axtv9>W_1oJzaPf3Qr<1lhml?ARl8N1J`w= z^oblQ^j25-gZYf50I#^k``hf_yV4TzyIm*_;M72RyT%7krR(GVz!SvT$n0Qa%I;V( zLfv{QyvxNQ+2!l3}!_Lk92 zJH2@JF~qL%u?DLXj5uK=Ss*|ljlS0!0lcb>N4*!X?Y0EUlP+|M+-n;ans`pmA2{_i zUs`?v(kz=A`;=o2`o6ltR1!WC>-5R`+-<6jKx?qb#hQ)#gOV7j)?Wq7Zvot_&g@lj z(ZXiQ)p4VhO$6H=g7Xv0eo@lVL>D3iuFa{$mH zf7vx2_twx|HM#R0KXe(^;v{Zyt+bO?y0R=7$v0jo0JV3OyKl~u{V?n_*~-M4s6Zyw zdOv^yO)Q1$fw#{3)$0jyvUk!kVrdt36w<6fF~2PG8*Dgxw;$$nCjjjRsHU@1KCbHN zJQ2VWXG4R9ai$6Po9&4GS-Mb|ywfxSY_Ot!wI9Nq4mqiwt6(2HV7^G|XdW+!v-+8Z z@6o53LO{PBue+(0($do1uMQ?mqSP|l_kQ@ns^MdupHFpuW*!e)Z5=>!ZOC+b!T+1f z=7owYbqva-OCJA=vgLMZ&#n+}_IqoTn7K!54u2=$8cEPEZm}HQHN(u-D{UhAN=#$8 z^-u@+g&8}jiOj=GbLyTs7drOA^dtpW3P>+;acXz{AV-*ku^Oeuz%T51kKP$O%Va$F=;sX{2pMDBxI25Z&r?PwDE#H9 z!}5Im8~o<)##%leB#Br%^-qS*#dw>vK~s*crsPYp3<~!_z0976Ns{|TM*B^K{!9US zo*!zHu&AOj8{>LVye)Qs(HtPOZr~G6qkM{_negBj(Q#}Oc;cHCkjwPth3seW1{ z@iBpKtr%NJ{6Gakt#wH;cDw=a%`vT6!{q19?7~3=b8HDm`R1Zz{(U<&1%s7>!nVSD z;V1Sy?e)L1>QNF&m*?s{11m*njc|Hn9+dX3Dv`77>`-xh&NolWA&as*X$5R-N%{-2 zzvvs; z52yQnW9x6GE&BDW_A=`T1x5$q>pn62L0XWVLMQn=jbeLxwgyl&p8J6lyuvA<#!Fv! z&N>S-Mx7y)^YvQi2Q3sEH%AKlzP?4Q&nZX{MWoHLHIgxP;23pxysd2f2>0s3DQ)+J z=#DExz_Q8enOT8y{QT_}nY1q&Ov{7-{^-fPj zvwlDN=KkFubUsa|Q_>fnyBZ_g+n-;%_`7i;YHoJc5<}GU^7TI70*nZ%qS;zQ`(G4l zZ%JNy6i!3)rc?s9kz?vigv=%MjyaTgeFo^zcV3q^_JEM}sFEYDv$;&8q8j_NhdQ(C zg{uBCqwL}%NTDNF&AP<(zCppG>A4txXE)`&Ha$4ea+gH=@Q)r*JgM>jYZ;m4-YPvkP-M!ThrJ&+ z1C(!eRRj?Cc3Di&3k&AwvF`yiN=px#0D+fI#{7--XWS5d(3_-|o`!hs7ul9?%g`(C z{^E*`{`O7$qFlR?Og@(Z1Ls~;ys2MvceK%yz?f`KE-Kr&!LJ0%QdgCh`+<&V#B0_K zef&imTQ%i4{oxmf@WcLKIQ!jc?{1D6%kBM(Irtxz=w?^O9;DVF_w6dp6EoE|)vVs;W1veqY7%LxL%sNIHGQ}EE z376g|X1o%{Beo#9{SXXZ45p#W(fiaGic)xW6d-Wd$-Y1IWsxo@nB=DFk#d7*qWyc)E)wOT`>?(tUE z1pOIaOPlXDl9NhGqA1feQ287qj2FVHhTu+Y^SA%1eYSk9v2J%g{kx}7S6c{ExWu2) zmP=v4#EGy*P^Gpky4i-x^A>(c;rnH+sN;}5XZ+ErNK1Ri!~=vX&Kmz0Hkl{&q>T% z?&}VWn?44L2g9NJ zU+nrmDR8*=$hP?I&&^N1b{!oFsW-qdN$1=gm-vGw54X8|rXp7)oS$_0)qHigjlz5r z(G3fS@$Q^ofK17pi^Hi-k(gvxON(Aih%V>KCefD8+Y8Jpg^#F1RzPxqFtEB5B%h2o zNg-LDwg|%JIq?RW=lztG!{dHR5S;6ew+=tA*tPP!&^aYTdLOpf8`P#5f`e2Bi{qk? zazpI*WvjC!e~Y$BnzY;43BFCz34xLb$Zz_>dLBd)1~B!C-0Sv*6bet_)tp}Trs@0Q zPw?+~9(if&QLy3wPx-{DKa@6;h4>MKBI?D2Mn13@e(n=67cDx?Ry2uyx_c#@c~*bZ z`cx#i59;h9(K)WX_Q`H)(cQQl`1i-qM#_(xw#q^$r0$Pbu|IoVXFq!XPN>fhC$vWq zd8aOD0RNqV(N>@P*6`l(7iL#Y{8Ns6n(yIR(Q2F-Sj_>w&cc#{b|jS$-tlAxnzcez z6z0?II7WlukJzlz=z9(8INB+VOI5&rU()%@C;sjOMOA_$1 z7-WWG2SMhu2*qHnJ@9Q2p+|Oxa*CPt(VyzBiSTXY7w0_W=R2S60Oezo1gHz} zqHLWj@Es~d7<-$iHg;u7)>RhVA$N-Pnr+QY1BdJ7iwWUTGy7(FJ33HfKEFc>zjX|w zn%LH7dZbhmNd_w2DC>y!s6BtrXk<&y4#~d$))pJ z0YQ^lo`H`j*?2pM2Ag7hiO1mV9UJ9+om-~?Kym(&CYy-=Eb=HQa4QV=Q%?!%4*7 z@WIx{Oo4inic0Wrk9xLs5OW@afQN;UageRe#_479jdR^#3F!5hS-Jk+KU{M~xHct4 z32hi=)t0F4yJI8Qu};Ww8pnlG3GxGLiTX?1c=$EfW*9nkREjcj_5zHzq`t`|+p{ew z49#*iB@6=5KsM3*ppz=g@K^}O0=-S=&Tad34E_fnT0_{Y$%i4?Xe|g{U%XB!5m>ib z+NRRovmmglI{sw zRH)ZEzCH13J3LlbFG`yX!>ASg;ysp-bu${Ooa$@4`XBBsS({RLlIt0rWlOx;5iNNj zwe3B0iGZ*b)n`g|xp$)7gVgX9;UUqX`9sd3SYSh~5#>kAb^$EtSMWD106Rd$zt2Fx z{sN!@zWTjL620px_~6l99ULh=*~JhyoQM(P34fXSgo|RAnXyD$-iu59@ye6>bv4hB zY7C0#MyC}EgY@5`vX`Zdmcm^~M~xifoG31iw)hG?LRX5d@^?3RBiKR*BGj4XHGdv} z?OIvZ#ynGtjR(K@SL5GbbE(AmBA46bV}n^>A-Kf0dYT>&w#n2(kNEV+3D%- zl@`sG0xMoQMupoN7J03mJZ5;Z&OM|W-?PUpO?8RzG*v=dJ^K!ll&kd&mMg{2*0cvH7 z&he)SoC1ZF`YUnNr&G5#P<;^Y>Gu``P`DG)21N7wt^p8c=#+ebw*c`^^t$?&D)yyI zsS_!SDhDaN+?Ai_I5_kz`88bXq1d{veS6jC2z?3aFS_MUwWyhBhRglEoDgBvp)B_@ zH`M0%TL+u(Do~ubBZTBlVj?Y-ZR4ZFhloec)R+OqS^?YJUGm=cJ(2ml9(4+#Kb{t( z36)-O1>S@{B*VPh?m)XRx!|*oJ!71?RNCm|fyIBk{R@|b6Z)UfJh?o5ebm*C=X;Mf zJMEd2Mv*gjFMhUk89;AFwbECr&LOqGjL%z5+0Lrf$zG+5p*L|iy6A-H{+I~$O49*& zo)6>dZKo*X_iz2T2zQCV{WQE(dk=5KGMNwkzA)qxo!nQqHon%?j^`YSp=zu>pxvNh zB!DAkC)b41XEMK)DtJeE(1tZksEJ430X-pu6i4>)GLkY%kjxMa_nT1>K!(h2_Cpa* zPax>u^{x8EUnolm{`1Zgu~%7HZUra~@Y_=~P2duhA4KyO`J5X!DO)^~UQ6-j>b;xf zmzmBk1u@PdwkK&8$=ynZK@3TV)33*$FW0rd!2kZscD7fjqMuqt$t%iDg%wvu`h%!Q z%M_xevVfR2YyLFK%GsaTjqdhrAi`CH)t4LRhaY}Hh%ZeQ>sVohR_qYGqKwq(XM+6JQV!kHDw0uk6j)Gpg_32Lv_VkbanmPiaE7Xb%$PrrzJD(aKAA zA!b^tiI{I*rs$Ht1Y+W_bx=QX_*u;eG3fTUlE~E&hTFaLW4L>+|8~QiaGeN#>p~@o zL{r~u_OIgFq+j_t$7_+q>D!Z01TP{4Xg3(uYU1j?+D~J;h~i?7y|t+|W?HUW_?|!T zZePlR@uuli9ccUugBpD1mqDEDaH-NW5+O<5PjS5Q(4-3^81Usnm#jRMwM08%9cST7 zeC1nSUwdw#=5amphvcDG>x9lUAz?KN)s(wOTdlSGAXds&yP;rtYe}2DwR{-`s4vng zZW8xUxdmindC)4LJ7rnHLZeGwAnTIUHew{EWPCv!JC&XtI6v`BS9B9Kc#r4r&n}v7 zaD_QEd!2duRFT!AM}0V>rR63Ypm~S=bvtLTAuyLZ7$X*i9rtyW#}t>~rk~!r+VS!o zJ^Qrw>B=B*P&gfi_;jjJAZm`Mhsjtcr-eF^?Hd zS?u$-(@Y775}+R@c=9EneI-c8gNJ1Gh%=b36ylskX~DCa%Yo}SZ-B)LQ8etBJ5}3{ zyF{7WPd|SRGO;cVGNiv9`jroLsO4Tp#gDV#;SP@`m2unOhWkQCVd@kcppiJq7LR)_ zGzb^N{f4<#7wI{^!mgVZ$$gv-< z+hGDDx$3VqA~ek5V=OGQD=dQKXC8hA(G*-WrEi`rIx< zRzh_`ti=(IqC#c=2k${%5SqD4BDF+xL@qz=rTtvoCf_mf*Atv9j2$3nXK6fJ#!V@- z@r~(=gnX#4ha+BJTRn-1SdX7a_#Kc33PwPU2Buw~ZK`18h*XgqNx6&E-b1=(!v*cf zdx*}u5d}~&)FzSecpMJZ{KN~0u(ij)PzB@%lBuXLgjbh}yj*HZT4bjQSbrnCj{p&e z7Z*eLf|_sbk|4pktR{QSrV_sY>VUdReE!`=N<%ClG$Sb(qCcL~?oRYDKbV~YS|y=` zT?N;N`N)Tqm8ws3I9V>P1A6Uf8z7^I@^yOycPvk997`6t5WikkCNyv_xI_P1ui^*E z!$KPDCL+43nsRgyJ6LQPpHh)%q^L17OG(|C_|j5*v)c?E%b5Vh+3+Gb8X})Z#YEeN zld+ueztD`eJK77HtIa5j#_Zdi0@`fe3#jpcxKuqfZ|?EfAUjMG{KI9&%ec zUd<2AUpuW>rB965D zzI6n5=)}4_Y>q3zo#9fH=QyBg2mE@H#4+>r25ht_ko?igaB|}_TCMOaG(R_GFU?5i z^LM>g8RE4cml6l{d$&aa12p_X4e(M|7`J58n=yPn#g7}`4E-JsibQphq>)9BP5Qax zZ)DW1K^_rg9=yvF!js?z@J0a7p;miTU*iHVc&82u|bcTG=F+GXM(ax+pZqzt_-*}7BPpy{MRYO+VZts_K&Z*P(uz0yOwtO#H5 zH>&|T*_FtZl*ZY)f^HpUFVZ{+j*}EGVt3?vKIO4c`|<`fuB*h5&F7-&8jE$ibfMN7MQDMr#3t-}$ZIY7_CG%a z>0ska8Bl5&SV}7pq#t#TUVp0aQ0U^yC*jk zHwnIl`-PqLTL-5$iJrJyLE}~tE(+8mCMMF$#Q4nR=*%sCw?%Q00%>Ard4!y;!qn$O z=SQnG0yVYQZTU^spEb?hx8@?`-#Yr(_3IkxaKuE@oOoKGy%tkBJdv6?y1D)q2S;it zaJyGjt9tC~_DOtN!!>f3N%T2%lk8NIPgV`)?NsHwzVz5KnRM0Bp{lw8!a ze)eVgj!%$&1Zw=AfZ7A8{n^@@pa>v;yAj+1(4kW8a=ucr$SUy(U+psP?6VS=v>;*R z7AjccvG3ESqyIo$$Mji`+=oV)ATu^Yw?&06i(6>+BbU#BenUtENN4bJ3>X@Fe)R~N zem}iyM~ct$%EUS z1cKt(=XHNPSN58p{!V?0u@|KrHvhhpAub}m1eBGyT-ppmku{N{-$f_1GHFJrP4TnY zW>*!D9-Kc!%Ej%6(5K>R+z}`IpAfT%>RcbKh49vaS6ax7DU;#E(y=*hSGN67+oU3} zGSkRx@Hd_Hu=Tg9&=?yS?U35zXK?E+j6$r_+@r z*EK!a7G@?_wDu+*&7nG)$!{+D5k^-?$|zyI?Dck7tNPGZom}0)U9SePG3IVHP0jIS zykWFa0(QECSOBV9@KuDXsrkSI&Nk_nm5J&D$1p+x zRzo)@z$?ESYzVnGv1K#EtU6t)MgXmMu3YVPzLgL5H|8&tHdlaB>`dY~KxkcEZ}ykvu%2-rzT*E=^H zHG7{Ga9ff7-ZT{1Cb_1e1O$@;-yaiM8He_FPawPq*_8e~)AM>DYG(B5`^7uqWI*;a zhl`~fZy?wkSPue>&gFr;np(1BcunkqrwOOk|uYp>4`U)++F;0LDKIMQ! z0f4XHaq7ZV0A)|`Tb9hsau)ZKvoxO@ZuDz>GrKKsPwp|5x+L7s@$ad>|Lz|Jyo*xL zD?Z&x*qql}#S@FIpp1h6|x~ zhuek9iTjO-X^vQMeUvoNg0=sU$b!{kgCESoW{|!))fV{MBju8hZ_eIddaLimm5#%a z;9?paVc{fo3;-me0wWg$eM0Yot|#F{Tpx5>uYN0(tk|!#*M%qt()K!3L~B8#`sgBZ zr4dLKqSlhRlN`@$Yr(KWa4~pbY?S*mj z5Rt{{6DU5ZhQT;5yJs~?{0e;-){RgaijFWVb-skFjzR;uK7Mm9;#)R3g4GF<@MNY( z>qP*xP5xAWHD0F6jGmup5s2)0?4Tj}riGhI7;zV?o>30pk9Z|CTc-i2jt>#?qd+!D?}{+%u$x2aVL+*e`h!xDL!U0bTUj{FfurG*H*-us_A*LOrO3Un5Q&_DM?oTqA@ z9iJ0moIJHh+uM23OgaZ3>ox= z$Tl~+DJyhU%pThycu*0{sd!~1K5{t@;PqUTB$d7{4>FY4+&B1GM;}v|1C|wHNZX@q z1(@{d^1h-3nC>luWdN5?90{m|N>*rF7!X0paCBjTG2PF=tAn7|XGe9y*tR&bG2+T@ z>gZ~P$kn6ho*l~b7kG~i`r&v{y09;Bk<4cRuVPdxr0x^D3RGVADE@waR zPM-%*L-5F#D_V9~#1yR3DB(Nf(CTv*jIPR@Y@T9-zN1A2c%bW@` zFT*{mujOw|r)%c{~QTLtH z)H7lP*p3sZdagFA6f?}9i2RoIjcNVj_iIp!&tv1sSA04Vb?#ck5tv&yt0r4L<;ACR zw!yb9ZGt_yF!>QTki=Wtwdhy}^iVNX@Tl z=F(0-$@(yL&oK4A6rR-tS}5@zN8g$Or(2sKQ5GBl$ zH}mpPaIBKH?UG%%&)L2jwIg)$rBN=b+yl&g@Qge4yk5rA?`L_ko3GKRbA*Qx>uu@s zC3~Pi_~jSjP35vdk=5Im35ID(4`!vs(MG@#k@*dgr&uuT*e~q@)q~(c*~)WoF_nu3 z9P>8FK=L-}VzR`8&FGba+zIH=gwb5m0QvVFX8uY%S?#g>OoAnXD{uUo1=@f003)3Y zIw-67kgOM@jmn^FJKac~~Sv5eoQRij+wsxx%v&NYxN+j z66@-oy&XxGLTC-LaWfKPUPe0r&a_*{_bs`-iA5#4u=bnMIgT-uz0vBmx5$!K$z?!V z8Y4rZ9vh=4uqyKX$mlR#Hl^}90n|J_mcto)HN3)@jKluz^ESp<;NPNIBSSLLY)^G- zMHyABoBT4!Qbww-UsPO#iaP$1X;{7>U^2owxg>4t3|plr^-~;MmpKG(XXu@C>VVEq z5+FF)Hi7i>?zLvwug%Ug;F9Q9Qas}C%g{H6B`b3p)p2#W^N?~qkPn3f`nD}45)KfF z;EqVlw7K`EdyFj`OJqISSKvfYV$*pyOYX40Xr`$rIC+W;79k}-6jDY)&d$+zLh+jH zW^sVu9yFUCTUxa20>kshuFs3K5@Dkbxy|GOYoim~Mj`k+iywvMNpCnZ#!i|wcA>L5 z7cMo2>3fDNgxfRCdMnTi7&ta-h5rmz+PsPZ(bqIfZ0zM82C<=*_SJBM!p<2VRIOZF@ zcLz9++Mm7MZ%dBobg88`9r$n3X6sCAhj-!g-eVX>H zICu+=e#M6(G%6o)XMJlv^W8%`F?#DDRV+@+)j_>=?%&T1#7LZufaHVgf~K)17q+Yp zGOtHBoyH|4GOka4eZUUTOPqG?c?2#S;1?m>t0%WAzKD6P=Zz`Qo}ao>7PJtTKjGtP z7e>Q2eP}dLwgAD>V9kNA{pS?H&W$fHW%QLF{#USKk4Gh_NR}deJc6dkH8e99@ueDE zq*$C&8f`;i86GH>p#4B^SO|v=%kOZ1Z8lpOm4rRhqVV^lJQJEZ$uX%$994@`Zb8^d zHc-^OSByR}_R57U{9Pt^n#Z{T)xYw=Wi1DN;)#~?8A{}hEob#=6&OblgJ}yReVXIp{ z;YGff85(pCle3&v`DuOf>R{FlcDTUzFW{mRB@3I% zLOs3@#PK`UPJivqY+|&H=+{{kH&W(2|{rki||2AI4N z`KdF|KG2?4lA4&2a#rfE;;?5A+Db8@N=~N|b7lGkpJhTCucRpPkV}j}RZ*tn^VWPN zBI37?({U*&xO*QWg1sMnk{spx#qX=}UDkJ6YJhtJSZ80@i&1RCOcfToR%GIgoB}`f z0Y^OV{;leXHUuxxN*vyYjzVs(-FhP#z1q^L*pDEJDRxsDMty_+Ctbdu2?lk=Z-GII zh2Op(!%5*p)&if61gRUZD;~poVc|eI1ilDjQeO{`BV4|+=!eT&6uf-lUNVgE+GK@$ zhCPz~{kPV(Hf@*vhGz*C55CNlp?l7JDsRC(IbAP1a^&zHZ3hWC!tPY0BeKCuSZ_iN z`-=35|7^xhy~V=?WAy!Pv~(lw=U~2%wMij2J%W#lT(3BaYw6UDe5(Q=lpU)i=w_e4 zvn@bdp`rfgTg}9sEn;=;hwgAf^?TX7Fl^!2;tPoFFFv0x>FebCD^MT)rFJ)bdblOT z=NN#hd}k!1{8DI-WO(V1;53k|)^i@%sxSwC?-M#nEbsq<1nsqcoo>_bHzW!hgAW7pvNIPFtDJW3U_kH2jgR&Z{h~U8=)} zg0MW#k-A>E=zC{ASp5!8-~GZM?%RGKIK9>C8T3}CGhRV0{^A}Q{u$R@fRg7Xn0R_g zxdVxa((Br4xIT`{Eu!ECjl7~0ad z)JuNkNK<{NgH=5snRYzWI#dHBt3ZyT1KSBD;o%JNG>{!2_P(|Aad*$87S7dwSV>a) zG7y#K$eVtpHnaUR$q;j~k>EMd5GdF_=O&f2TywcW zCQFM`rYkAWfXGHL!v8#TGijLzw6&{eim1s242mQ$UuGzXB(ZGZY#FyTKi7wjKv^x0l;kQ;Ji@m0yLzTL02sFc(`m%5rv4g)`-2vx`ia9?zY zc^%S!>@gBg2N8;1FRzjkva4o+ZbD%K)DPuc)OWe8a4u^KYr@OqK(U>Oi|LLphTU<& z^>2^bC~+f);tiu6%f*OAHM=psj2|NMoK`R5@9^&=u!3ZR08}h9QQ?au(1+H7S;$?` zzVNFl9iLoF<7b+$)TO|0a|ac-sINMgkrtg*qyiOl%u``aMBcLI;jBe~#<5Ii$=^jE zudaM^HERv9oPK|2wvHg6;FT3*{Tbi_DL9?{9akg1e-*7@%*UG&X~NdO8=X}9%XVSK z)3rKZ9h{c3gUNBgQ<#*3bZfMq`Q2ShdFQ{>CexIS=i7!oinob>GcABv%IWP3M`eb9G~z zIqhAZ{3BW$L5>+3nn^B;r9=J@+O^dSfJJfUeoLkKWWY>j!{7Cr_yw(@ds%f78Wrkw zCUjpj?mKkP)c`kjn|(K?P*mH?V;E-91XbC%Y&i!Hf2|r!4kF&E zN4<3Kd|SU%o33cx@{m3uZqP&zs%7S<;93ddi#ZqLEnJyi50&BGP-h$0DnD1jQo0P{sdeE=)Z{?w31=8$geqV3 zBGO<6UMG>fG>Zdb=A4XpvB|>U84Q+iTO>(-X)_-E9j--GwBV9w8B*!3NsJes-^WAB zO`Nshw54`9-lM*sqQGR>VvV#P(aaP;xwGgDagy3mr7h-8rAFY{RU$Dwc&!vof3et$ z>-Mg`=LtiL^=Rp;i_0c@2FPYut>Za`q_&@vNURnLY#Q2xtJOB$lS4hYsf7houNAmE zo+<5<`RU&*Rl0&%Dqy7}$Xp4H4}**E6T$0Cfur|q#FT_0QQ09!KEQx*FLuj6G~atJ z{Nw8_wwPs687T4SfY`wVey{BWj`P=FSi;0LKhN>l*MzDRFoPbI=*5z({R+xF$L4nfPr$YA%DLzzP_aUURP4=hVvmD06l#QG z9u3A>jU^Xkd&45J?(gpw(jq^NmeA&K48?Mu6NM1qc4%ib0IF|f9mUx`w55?!T1U2A zv`rI!0XE2l2%1yHCPwiN(x*ACHaWKf0-Cn_+W>4xUn`=bU&dW;oez&SzVU~+pkw);_F~%m>jcJc_L%+-e4yCIf@-JiwmLx0#>Cj!hh>}+PCm+b^3?^ihe{bYWERrc zzqi#E(HLZtgY;+b{yX-l*SlcV`Wv@?UfsDJ76S6%nD#iNR4x9HIzv7#XoBJ<1-s7` z3Tu|Q1QxdXa`UEYp`LCfHJfBq>19qzfMw<$Hhz)!-5rrw5{Zs%?%VW51^(c7bmKcR zPo>ozAvRodH}v$VQdCwD$uc*XQ`XFSj3mB?dOmdvg$&-oIcqYkj;iQ`6WqbmB8v-r z+7EhQverX6R>tkEPzFR?E~CxZ+(+`guqNJiA4Eipa@WVNHR`~LBZ2g6Rh|^&nO{(V z*7%kydUTU%Trth(f(L&des|;3r#`DZ_f`hG4{E4BvG{k^9zy@F-(<*bF5}$@7wwNs zizpdetX?eJ>;P%>PI6Fw-w9r-RhaES-rj6@`>ehvFPW-FF-x$1+(F`i>w!51(kpkI?@0o0p@{0Lw zj*oTItzADqHmZ~d0@*UNAKD2oL}Q5^ z(`Q)rQ=O|~^!|xZkdWc*Xai@0%4R6jglFinu5-mlE_AzDa8r8h`mRqkoHv8%Er>sh zY?FDjgD{;Jct^24#h&Hy<8BtK}D zPg`Hit`GkXS#bn8s%wKV^jq6MhrspJGo{QMN#4pr!IxDiO4kq1T_QcioZ74xBLOxo zdapF9-W3{hc{;(pHJX+s?fAs9nJ~Z8zWRwyL}BAKkKLK>7^pW~QNA%UebiuarW9TS za@lE{7WbFoJbB`OPY=#8w0Dl_evqoF+Z~)n*#2@abU0R=kqr!B`7g%nJho3Sr`4>R z;C=7`>|p71aE+_8 z7&AQI&s+oDEM4(FX(h%2AWhVt>Jl^2DGyFm@Fei}nU6YU_PDmE^GKI?T)SDW4QP8= zA$-p4yb}4=0V-mscs9eYw?Hws!rvYah`$@mJw6Ll!NddDWc#+0`4MVrNGBKf(l`Ia zatT`MmEb?S%P;NXRRwIes_6pnKiYcmT`D$iAG$qYT^E|ROV+z81UbWLULkY+ot<+r znfnGCkrUaTx8_<5va{V_f-3|i=p(-4(DP0-s{4C3v0!LgVd=6h*dS3P-YXbUD;UfT zZb3w3HI4BrC#+iB$@xk5PATL)K{G=9^1w_JC$5?v-k6^S-^rY_99S)WKAsY2Zq^@; zJjqqp5m!||Dqc!dMp>F50st`{9Tgn=v#zOTcxA80yVi6I3aF%&5zjD690`Ml! z$b>-9To>2bT3-c&{dO{p-q%3oZ(FkF;UpBLtTmv%arz?tgCISM;e26X+*VawMMTFG zXaY$}(Q_LBC{5w+HF`w73as4>O#oDW-QF43wx4v>rs3a@-RAylDd*NHQb!{#T183(55g3PIlPR{S}zQk|2a7KJ#@b5vFpE@PuUz~{+oHNQPIW5#ft5jh*A)|W*;nzen1%KjItV$Kb}1$^?_|QS zB8~|5_P=sHy`G9sn5M|ZZc$DB$l#vkMZQT{+X76Mmz5Ec#^?;}&t)-II1>RsOmsXj z_W-G)e_AM73;d$G6O~&0a#*hJ?S|qj^h?hA<6L!Cv*GxxeB@F)YcOJ0_BcI6wq?P>f3V_LX8C+gnCxFNj1_$PoOKe0Jw! zk;4d)bpeuJ25+(e9zvgTh^x~_ZZ_%OwHxhrSD7fpkBMws(cniss1#=Dw^uukkD$*s zc9F1o%~%42^I<=Qj3*brj0qX&-D=+@0#|sy*x%G|*{vGpD=9NgZl}g~jibKTav)jB z^A8zu&wTM9ETPOB4J!4E5jA=TLYW4;tQ#?nywF=O=jN_&Vd6=_d|aMu?4@}7MVc#L z-Z=}8auha!IheoPALw7KVKhW)Y}~~W(8lKz=1d9^SYb=7;73A1hr#n2a?Ki*posh7 zW;dSA`?;)c>Hhy-KoB6z{Js3}jWa@Bo*D~vwQGMHKZ3HvH^8=*R>m7i=+v(M&9TM5 zoRM#;Mt=&bs*2Tyq?ZqH4EeJ7B`<(iFf*IVUp!_MS8u#&iX|_zi%r7yZyQa?+p%uK z{p~?g2FfJGo(b`}XH+>rRL5JdfCcCyIZ?AjyhtLmR2B5&RX^opDEjM5J6-7jN9&0k zr3?ClG3U+=EKg3=3BJi1xwB?%%Dp;GUOlLVQs#AmZxKtnaSg*%S2pxeduOt!uwI?< z>KTHi#rism&5)ovW#df8eSVF38c?{7IdQ~sk;App>#C_`t(bXFcl&Jbyp7USJXf`XC(F=ONFBGhNQbLQXEWGMYGaAXD*)GUlv{|` z4Sk@1+AUt=*{G|57XkvXY#HQ#u6WqT%P+wSApR7+$?EL!KoeUzJ{a8;-s?7B)+aiI z7_LE2u_)Xtr8AYkJiG!{P+@DgCLxxh23p2#a!L;ndB)}?h@Fq z@S`1o9vt$bq@*Yx@^9?>AjtQJZ@NlLKa=+BHai1-%X`r-8Jyi1X#GVOwA8Ocjy^WoKeIjD@!zvGI@9UE>)5}c{aLl;{UXp%I%=N;=w(%YVR zZ85z{V{fLkC&=Jk?hOS~AW}9X3J&)Bh$Xt69!7N4^>w_)&NNU9PGo_(*NxLn zeNd*3B42V+$TJvhy$1$x1V;TF ze0fOdCA?Gajpn%z_4eb8;WG|8G(LD1(aZy9l^}5!9y^q2m(DdO$>(s6Nzh zD}*6_e*5Nvaiiht_?)?=y`|-nIr%^@>AIBqoYr6la?ZgF$tGL2E$`fBgg;!D0Dt91 zAttzI;-7{oQx_<76u-+_(r#E#>rI=WRkS-8)`&B>j%;{Y(G+gL@JEv=vub{;7nM3L z+#Om5naYpyN6y_l$EfXhx zG^(8mM>Zi5)K?>L zuL1&ha5|TN*unFPUygX@QrXLR4w}ryA#sJdeitzO)@VM0B{3bHS@!dG;aXde#ZV;b zB@?Q{$TPsQ`jJs>U=B*L7x01DpR4jrRLRo|QYY*r39G|FaW??8$6=74))a3}^Q?WM zd6vqO1=RaxzOT%2xMs3Dr3x*NW?yza^DODLF^_P)T>5Dtgo=xZ0j*nzo+TWO%aO)Y zS;`4nQ&on9gZB?LJy_@OIR)-in_zRn^X`AKPDg0r__@3Fn;Qz3((HuX?vN{vfk<7* z-75>ru%-^_%(O_+6~6sdA1BQ+*Q1}ZDbg1c|G&m~U4)Q2<_Uo6QNgN?;;WFb8 zPwNATIqMiVv$PZ@Ruwt}j>Nxd=xM|l?Uv78PrAX&poc>A%2g8uQK==X`J7XO{)9tP zK~r|@n)26B-kqb=ay!vM8+Udk?E8^?_*U1k5onTvcYj)A&A?#@%2ABX_EQ6$;M4{NC;(p6~I- z@^e@_KQaM) z_SC-J!~5aQtF+y7uOQkSUs|>u%$}J-(pXV*WVS9_Z^)|GRUiV7H476&y9fDAS@j|6 zBCXoZC`t+=)joWE4q*01?QI}? zt&$Ox@Cil*A6~+}b;@C^1U(Kb#}Q4f3FjKon*Bag)yO;C#;;~fYWGAL`{QeKCnceo zn9YAe9S;G_qBmE#bwLO8r^^Sx%vTlBy${8{mUtd@dfpjRB@|%*zx-QP()kSsFj;0 zFIik9zv8+<3f|=ibyYO8hH`gQQxiY_oX>RA9fz9%=XH^ocPFWC0^JmeV_ZwzwSqzMd^N=nBi93l^k%K7|6+=uv%YaOg~vyp6=qVE0oUUx~_%PMel+ z=(68P=KZzrVTZx2Y<2c50YSJQ79iAVJFC=|eT|G^=u!J(*oSmviTQZDja_SD8m$i1 z!f$<1vVD~ZNL0GGj5!%)vVBY3#FGPfo4_wPhHxv&T%>LA*$8HbCP;UH&0pqRpm7c+ z$2dTf>(=*cXRs?J*s0b`_jzF<%KEG{k1od7g6b?g^%b8ol~Dbmt&qaNfhw(7J|HBO z7f6=*X=Q7(YKZ*Aq%!-y&UGN^nzmi*M~9kY!#W%HL-l-2uLF(2K27`Ack^$Pg>QfI zSJMhjcpS%WTzJ1MWnp?OV%-;l}myUM}BwNQ7E@SOM>P>&k{z-zu6DMXRt_y^V_QC!3?`YojU9MDwf% zjeJ!Wni(LMR3!2tA2cJWz|ln2!^&H*!)u#i(}!n756TEj<3hwq_Lbzcj``2JJa-%A z{D1~2!1Ndn4*)^=f<7`IFgV z_$dAN#Y31QhO^H7cpPC|G(al*Tj%R+k_(GN}I|W03;7Z1M{iJj1}Jd8=5B=rf}w%$I;mTklsgX*s42TeS)pXiA4*-f|qi zYwa|c-h?-3-}2ShCnU#-4^*j;XhUk$xvaH+>gKa09n|J^CP-e*=8gS2(Wh5>V*7k! zH@(>Xe9}2u%#T4G@%Hz9AbEdlfU-_|9H$q4fJ*Z7wcjA_gDtW2>RX&J93f$j>2Kv) zsz^tmP}?9dX)dhyDACar$o?B9#Xe09VV3anM=30^N2$U+uT3dK2=2$RqLZ);#Py{= zlq`Z&1>3~k+e@>)z!OwqiFcH41An$>w@|6Q34deer}Nqu+an8}#vq&h-R2t;7Z^cE z_$WR@V5HWT#~aN43g-`*AV+*X68se-!Zo^2^G09@u{Btd({k3NBU*rbP-XuESuhy=5{3t;hka!+l94au(Ye5YOc>C=+6 zybMSA`cBN@8cQjMm)^MC-Q6PD#aA^2R47j^%+{{ba(&ouhsMAPWl0^ z^9+ldQ-6EY$rjyaR5DmQe%D#{MTA~iL&Weu0Mrp1% ziJA3|BapLvF{@U{B^&dQO2b{UJxhL&&}+3+`6+t14^+RX1=}ldWT^aus%B$Qh@_%W zX*{g{N&_Yy6}d*yv6>qM<=H`(>aHF2-~1}#b@<$6-;?Hi`#2rS z$p<%499QDhS^W^&aLw!-x*)TYD&2C{3pLwxLJ+CpM;eE@|7ia(r_K};LhY$&@TXN( zxxH99R2z$rYb7dLIM5)^?a3Ny*PZzGwgqDGu%c9WJe6E`uO=77X}ml;@W3?~WP=P0 zno6CqL%n5CRFJG59_rqIi%W268g$VrDGj5_SNU=WyuC1h&>N(hcW}qqC8NNcEB2fI z7Q{Euj3Z%33PByQp1HzVfkyeRVXtb88h9anr_filmkLl5%8m8ih;r5NqOfzJPpb=kB3~H z2F?e2jb;biwBH;88ME1Sd!T$HIg*-N9gt%qa{H)z$sv+c1)bC zJW{gX>kxnEZoYE*r7?Wy6&tgNjRWY{S*r;nCf08MK6~0U(}(7t+Kwg+*r_kR$b~s~ z+StTC+C}$}EVrN#oXp}1OS)L*sFTa$9w$Tl-tk#vrcNIQjgkq>DP;-L(5y0gcXD|9 zn=i(9;>ORLbSY{=!a2AO;QeqdI;YodAuRt1|0MZbL)zsgOZy^y9Ex&kqIK%x5@NM@r*=&Zw#Un;H@^PP$Z+>&3n0C1pM%J0Pc0}O9tB`+d5c^)|^em9vqjz|I+buq@0&}#6 zS?f9@8B0}9#>n*7CBB?4UX`NGRnCuH`g{k~oP4liokyxW0)xv|k3BB-<*0caoCpy{ zvZN@PLl5_PfQM2{<*4Z8_|h$KU9uAi@2uT>?YF1iPsFkWr9$&AFXExjlI!YW8<5 zj=F3C577XUasH02n{_>@(0~I|lJ2QHK`!zEv z_`%Ok^3t)SUAk#&iQyE_>Y02q$6IrEiy3HGUT-rN?e#D9)XUP_$J|i>!(k1eZXRms zOa^I`36h<5sh!q>j?`@feP$^>PL|4U1}8U>exCD)Iao49rYatv=SuG{AH+Mtadyn@ z=J*ws3tP8BQqR>|gD?C3Juc zQ-plNMPWBL`PacJMEr7&06%t}?@zz2I6j%R`=*L~w?prflkXLg@*9xQF8xB5{ON8E zVfLlRlI*hK705HPui$AKe_Nb?0!HX@P}!oPbGvcRvYF@(#hs7$CAL;uii&;!1nrUJ z{j`J=M)MkH$*Bvw50VN)w`fmXHE%^uIUWLembVE`!o}#&xPP!_&| zXmZ%ZvYAH#9w1o#n~-Kd>FgXV`-!2`GrF&(&r;OSL{qc-m!W) zI-$Lr=q&)#VI<*f8k)V2BbiVz`+IfVC$j+KDFBo5Hks zh|m@|Z3vZgm!k_4AsqC28Tn}V5i4HBE!CI!mieGi`6R|S#i=H$ahK5rv*-R2Yvoi3Q894)6GG-_l z@!RTn+l(Bv06Rd$zgnJ4Z{sQ?dFtN9^V7nKOm!_&i870&$0^vK&7@*;IB!QT5%SG^ z=Y2^yDjY@M47{?Ut)i&mGH1yrmjG)s7mIkEH@kt6O#zX^{Eh40>b?V!5JG7h!vk?S z-k=07ZY|N1!3E#RB{8DPno_WTz6Ao`e9rMqvfVF>MsDk>pQpRagA~IpzY;l222OEn zZmJ4})-K`I@Sg*@-~K);i7v~IYF%&S=RECBthBKpK_G2Pc7Lb{zvU9mF;{cf>7^*t z#5Z;)-${)qiz~8J&=026{su|NL-6!>$TQD+_Uk9=Iw@ZI`6TVpd2-AR-}%<$wboy2 zR6@}g;?(YXg=eFh*R@*a)%x@ITS>y-(IWH>Bxp}E81>+B`NZ(_URR%Egj*dUpbk*x z4Pv1FEl|=scIPaaytekEX;a7DG5mMnVtO6|*T(j`B%37s7%Es+Q%@{{@Z1$Zq$0pn zIiAFZ;KuZGY(D@VE!WI2)%2{68rwwsLKTN^?VCD{J~=6nV{VfaF7pchI~z6Pbw(F; zZMrqG^mSNAD0KikEa#0b*gw>M#H2Y5OF104W-KA-Q0?|D0L)<-pV z0WaQ39}(u?Immt|<^sJekh{;TzCllZHm5-jq#z3HjNmb;L#TK}Q~UXOFs!nF{aSf* z?nb)Gi1u_Vru2lGWFdR>i#&1hO?UuR6Xm~v0W4Yj?6 z(a-j8^Ai83o)CV;E&<3YDw*g9qQK&Ohpo-}Ja>Kfq{1bB>ifq+LD#KKfU{3l+2&(% z=P{&0!P)gHI>DWso^rECj+bLD{vC?7sL&Q7*M6Zjt=9yyjJ-0tZle(z0whB>rT3Js zTTUvKb)|Ec4gt00QkvbJ@NMJ{(94NYv5UAlEbV*3;MU)@p%^xM z$0IuErYR*sFSc=%ln$WMyjp%Vd^OgMgH&FBlZ3m5diUK&+}9-+>qAFgvG_*Wwx#=v zUWE0m43%D$-qR?0ywc?7MhK3}2Y8uF&5)HVr^Ec-(3_O!(fagrk^&{Il6kColJ1eB z;yfu}pSd!JUjFstX0jQ7s?UB~Dj29$C6%ir2qs@G_3=03AEv9C{c(`)f zmKKEvk`bs0KTc_I8HY*W1S9$w;k1aWKMD$x_-kIv!xG!sHHh^X1~c!$&z!g78@Yxt zi4L3#5IEn^B5q|lMWN}gORzjYspJxZffJ-}#LDPnlgb%T*&M`!rJwr_1ra_p`*RQT z;3k;L>GOC8AKF-PJ*Hp+SN7BZGz+mCvB)*OzBfvN=~Vdg{m2z%n?uBh zMf9b^Fp$OXCMU#gezLNH+!Ss8;y4CmPwX;6z`9}j;*_xjpxW&I_6}qA7*_-=1ZyST6Q(O|r*Bk)o?m zQlz(TDX(R-ix|hk{8VW19r^A1`>kH-O@(;;q@-b93zZ-3;APZAq6Nzp$uHR_-DwK1 z<6#y$j96EwF3jB;rjOC?nrFmGTHUn$gZ8q=0@5RbvGa_(g}V42xo?kCc$G-w5`c66 z5&X{~17BWPruA3JCDrj;+n3ykEnpR)8_9VKYWaZ@eYZ!qt?|`~jF$0BP+i2V1NUM>E-nBn5%s0L+^H@ZGH(f)vJ6A+7P~tkimb`) z%hHn1rAhK=BwP(_A<4P=(PhEJQHOQct_I<(nC0rYenJ)`Ueiq}anR z-8wgMhP~qRR4(L_+ih|E>AR7(lZz+#tfb}a5d zt{QZ1F3nER8_I!kspqv3kpAvHFu!cP+0ThWV4Xo-zQSVT?b&4AKq+P-r6rn7AZtQr5vHy&Q@UykIVW-TvhpyUK+S%SW3^BDh2l|y{@3f?4 zb?omj+jA zf(+pnOZ;aMQiA0s-kVIETy(zf@`#T|UW|C^yYqjW*iBbZ?@IsvL|A|L;F-of?LMT8 zW-HdJO1KyGd;@)9bI1`Kp#AU(`=A8;O!@c)8wRa;yu!&lc*d!AvI*C&j9&la=q%P; zg@PdbKrC=uBEc=e+2QWa(_iM!GT+P)`gB+Ql>q1CBB{4bV@XwXk-yR4i(*{^#_Abl ziRFwueRfNw=BtN^cd7U}enMqjX~)7Fw}4LQ6~*7?DE7_Zn#EV{c<5-}u?W2+!a#&)&`BO@gHvA>pnM5l9pU+94 z;X6ljQCH&Fl(O_RU2d(h(V8B(jY6feK!xX$bB2X8q}{xV8{0girmVGn zM9yshLM8ojQhtkKF2kA~Ahv0MI3%`YX*PQ(L0ogqc3L+)#&>p0w!3N`Cnqm(0oCLpg35C;&Z*U3 zV#u&MsYMh-0x}2wt|%@lLHGeSj)xsgY3%Cl{0N&kEgdT#UGAx7lYiU4HNs33M=ht~ zvzo}i<>H2ZT_%vET;CN8wG{Vh>1#P3;G=G0#AO?SuzT#$KOj60xM~q~U>Z#mNW(PNpv&!Xwn^U@9S2qw zXe7M3w{3MZJB|WSePe$KMtkT@B&x3=v3H?-WGsO5sxa9?r**7ESNz7?U6Q3eQGvl=6uqS!OYzWg2tX@Q#9#x^F z6{Qnwx1X-^ERk=;%q^RnadNkYQ~Fd>W%upwLt;STRIW5oNwkG2+89|-p9XlaW|$@7 zeubNSO7empHQ4O1v6e1gW@ev@dqNXlWEr~!NA>GOOEPbPJli{;M+m(OX-JvVXBX-6 zGT@fqTVR3lQiJ}sEc~4OYrXtQl+>HC*6?z0!bxcIFg)79y!bd{$Q=V^JI6YXeR!|0gXxsWDpgd?_8C@+=KZL$cGa_r>~T9 z$D0$FBU$&8cc5QQytCUG<5m8i=jD$QqAZeCqr13ytvPI3lR=Vv8?`*=JIqZadzlbz z&voohM6|wM75_F>fM(cr$LDSXoO(rPu8Lv5JhS2~CspF9PNz)Xy=FDrZm z=Th58o%VZEsD4`1aL~Jo^hyicuIEye`Fp<|5U!N-Gau@7-MVshS_<5Rz^DdK9q=?6 zGwvhctC+(I*Q8$!VAzXy!wz}jQVJIC!4UCZHGoax$kOZub63!R*a!9JG7rwpKfoO3U#5tnVCfS$C3L zR|>q|ppFfsDGSV9i_npA-uB;<{Pk4i_8H@mCwfKnC`@cayts2u+f8!dlXWb~J}ulg zcj?|;`5hd&4kiut#HIpFpZbEz&*7CyA0 z-Dac`Ca%lcn>q#l1rOW%T#tU|=Iy4^v_5SrQ9%7pmfydl@1}PoufxWS}|p69?q+SU2`HPkY3(K zs3`*ULCOf|Twg#yhj>+o6$~yWXR2Yz`W-Ht32Xkep^=qXT!D?lU*!=VS;@Ty#%G*U zq zgaSq{EIDwOo0@na>|xvSRyaVBUk{ifaD(?da;Of2m z@$YNl`>T>#Qa5A%wFE;)I%Qb+966S4ngoHP<`4d%;yxh&CgrT930#Nc@tJJ1aoM7? z?nIn%QOana{ecqX7aScg_M5buO&ub|&hA%6?zpT-`R3DrYFIf$f~F!yvB|AK`k0c} zGaiz0g@Y(YFDg4w>NYoEkBNW&Je~QxfV$d0-l&m-jCi6V*b;vf`ghQcg0(lzmn@^09+`3q{J%mnMgHbvf8qrlAf z42R~hhB*&jKSGwVdRg)>zJchSI4D+tAjuUU(Xj<@^coh~K6|DnO=DDIzVDFqJJzY} zpeeUL6Zc$v$b!4HY5MbowfB=GYquP|H$1GK_meb3M4l^51cbkP=hlx#ytD<)as0aM3zDojR|U=)Bprng6OOJ_4s9GsehAN(Vs-=nlYMQ~#(!Tpvw zh~Vq65>u0j?3q8Akm>Nkq6@Zu5v1D&By?)^aci z`x_#AcT_-5|T{_lddTY?Q9pE3cr=<;h#$}`^AaAU5k%x22n}I(Rt56u=!43fY;!sAu z7Pr|dM0R7ZW-jVlkuF^$bEwUcIeKmA&Qhy{<{%vrvIU4q1Htr^2T|sL6VgV5K;0mu zvVG?GCe|e?z)9(JYtt1GU!mBfaHERYcWYx@(7D{xt_q_gI4UelNuLVO=02~Q zRdKoy+()zp?fkHuteg(3M3N!=gm}W2@aad3uW~;|pwWvn7^%_IfmKnyf~CmD|Hj{B__{zLrfj=L zWcy*!c>sozq%M?xdVr>o&KE;pJ4U;sNUD%htN9GNe0B!-{N1YywL%M=y#BEM8POEf zOmsdQe|Of$WaPf(QEH9o>AF}%T_UNwPV?f;p{=38nU4JJmL)u~my&@^5eXD#gyYze zKeaivw?DvOoSeZwTe%qyukrD)Yg=e1JwY&Twke3Ds*-b zu{<#S&1LQ}qrZryKSn|p8`<9Fj;%0|PJ*ARHTXR@n0=E&QFrVO@&tLjJXcR$(rbe} z`wB&5fy)NosnTfiJ8&=+Te09vXOOf>-!SlLKfOwL6NKSZEgeVebh#_w%Sn-@7$s~g zHAsH-yndQn&Hj`diocG|7Op4AKCP*LVzdZM zM+d&pKpqRTi~G0^)G)N*7En~H?se35>gb?gJfvVc#xd<`OHYt3*S=ZdDSYo2U_;UL zoB2B|^G6fQ42lk1?c{NwCkT(k_AoiN8xj>(p93_%`fz}X$wu383zoX)ehnJ-uGx#a z>Sr39REdMzKnc{;I-ly4db&tNLl*dp)UfNK>C#GHzlw94t0Pt{w2Ok_`CIkLv1tg^ z6K`Kdr&Sj1-!<7ESd6pbuE zV{wo!e+Y@gpFMwr<7c@fg(J-gU{OV7k1*@gy!kNW*nM%XM;r!CJV^*k7epMyN*;3eFSd;a;A-p;Dh78D?ZbE`rHQfYM^-vzWSgjYFPO|?=5nP9TAcFUP28 ztjh|8QpS`BRNm|NICu7n6+!qD?&uNCbAV@xR4i-tbqNSXf?f!`&=6ssmPOYhxXxlm z!%hsc^`4T3|Z>PR!#5v;htp%J=x<3 z1Qs)KZL$WNZ>Xn}rMSC($9!cGl4*Pyq%({Cidlh$vGW{zGje8%^-0?$Mzj_{vxw&D*CL@E5_@3n>{Q+tyqxQRe z>g-oao=*QFv>^tb&AuR@f+kjjz?xl~vWaioV8q|^1oisW8goH9Z`+sA-lZj2<(>K! zt(0XJ3)eJ=H)@Z=?ff#HRBa_}zIC)BkTfH^%SU(hdfZAR##uvyoQ04#f>AoKCi z9-Q}GaF4WdNp(ba@1Bgs3LZDmS0Z?@2zsd~3xzvTo?w|5=$B$Zg6}AZL9MH#1VdDS zIqWxB{%+vq+*u5IDl_zJisfb{<~dYWA`K{Qf9)ykXW00aYxOWv32QBP94}fJI8l%v zg!2S<*m=^GLp-o^P=7g9o)0>}@ODD_>swCH*SZ87jlV9A!rF91#HZ2r9~Wlx{aR=U zJRf*?nSwe#PucCOw2IjJ3qTIi*VEA--A|0(OsHRmowus-PvWA^C8{qOEv=B_JEIbI z2f}b@kHcmQ#RoPb(11YF3oxGB5{NW#%NlA^BJXDmVhGqdv!oUA@{-~pgmHYm?TTM# zW2mm2Z=_&yq~YG;7qJ{0b$AqjW|7lv_o?+c%&IG{S{?}9Jec_`8tQ3Q-||X4{qV1w z9hBM{nr35kt^k3^nw9ouzQ-@WGzR zM4i~t9BK6>9%Y8=pu}j3>tv|*0)q;Dh!@CezkG?Ptx%ZY|LvU=c>D@QL zWHBk*AFx}VQ)y-*xKFsPOlXm%1Ubv?k*y!Y;^)Z*(z@ka#^wuD$AZlh6Ge`LvKFpF z`x`>{yd-Rx^XTd;eQm7}u@|af5lC)3~H4B*EGB%gFmAze%HT>Y-3u2=*$AzJ%zNU*Y+IBztBj@zk(K8Q=Gh zn(Fzwu1!9<^AyXI_E4}U22p5A)@6Q!a!V8PCXmXVf?K2!tM~pG<{sj7(R*JU;=1X?6q6a;YrTb?!65)*V3Df-5I|3rs}5$0%gfLU0vBvmB$=+d$=OwS}e0i z-_fc?JBlE>s8N7n=)YrP7#&b(pIWrIK}h!?ehq^WR7!o(bt8f)TVQ9(J98qdR045L+JLSbf%hMllugoW`Q+CS}lqw^!W? zHoaEAUxDn&ttU!v08{CVvaOlv&0^ za98iJ5`-0S3OnU1DG_-=>9}rK6jxV2s>;53>lYTl@BNt)5~_41qmu@s`0G3{VY8lG zT3Oylp1~u^t~#78_Y%=ccH+p~X=R6^KF|-$gT$*zmQ+6XR4~Hs(cw6Mz-Y}KOAVvw z_rz4T)9CU6jJH2HbNJc2dbDJcXwheShWh09r4%gu?j?iTOd+qOW~GU@8CxnaBFiFI zF*=EuKyemuhR&=BJQdR@UVUTPzUNNT9A1aoW~(um=uyNS@gpQxNf-WVFZ-j9-MwD^t7NuAOzrsYhZNIv( zf+8VhT&P6yj4>%IXb9Lc)o8-WiY7SBvSWjB*?sg8Gyuq zEPoKFBnf}Eq&P{k%^@52YWV@=*i@9u(w?C3-mM9jXwetg1y+h>`I7Jtpo=PqY{cQN zR(uuuqk;m}T8KVC&a|uXckxHsn4*viz6LfBYS!cYAzFnxEeWaC!p}Q;zMP!2r_3d3 zDg27DVnk{3s(Ns7xUVeJyGkq`41B&Oi;;mc%P?=oYj_TN9W;(%Nx0Fp0m$ixp-n<=?j0mX>?<88+ibms5eyfpo8bv>i&1NU%QzkqJ&F6A& z?H)NdF~CBrt;i-nTj5B^1V_QCfy!?(;>&hmpnU|z(aik2dSt-$pmu{HY9Uy%73WmlA4Z438Bm)l#6ctsC-Tn_{*Xi zJCmVR*O{md4K!e>MIsD+;yQ4TN82F}1-bvfOF8bG9d%}eSqLub=&YE~ca7dV$uz23NdiElTf+C`TcDN4;!(gK!P5w@F0 zKW_RN5rLDlSR||Mv#V1$-=e)GJ#xI`M9XZj&NhyZe|s`N`M60KLlVXHVGJ-H z79|)!bH2?A12>R@hBTEt(utK-xFEbwKhE=JNx&WQLyj3nr0#S6;ohnb5wwKq&GCKF z*%Z&BkJt=Ty7)cspC|eHSVzs7L@77Tvzu zCWGb|?n9X~ANr-e+)ss67&~&tZql+tKO*O^2;c^WSK!|{Ze-$tU+0)0>!TM3PXYO8 zCMAxu+NB)5#5xT55WNKFqDoXeB&{z4h98K*-*c9f+SxkudG&2Teh(sX=T{lEC7|XH zJ*N07%KhaHwG%E5saWz?1JLq?M_jEM6#^vfS50@Kj=)x%egv=!Yc13x0p|N+oUw4o z2@R&YD1LQac6`S6vY8Up?$G%)CH*Mbn@&&Tt0w>@cwN(kE-40h zIfp3-Xl5AXg%JxPzfUy|`NVurXQey(zInVSYBEy#9kW-Y-mIXfPPOgBcD<|JV^P~0JJCt zOX3ssy58cUsk$!;%~$RRQ6#$y@dkTlFDsCgR^ZFB=E)}6ExkcRnkFYG$KZw9KEg(< z@G<2)4dw5e9FIFSyjDgP3$??e2cLV*^raxtgC{9&&8r<|5s0DR4Qn?@tbOdN{Dh4% zK74gUIgF@pzfjQciBj_OiM>2zKj+p<@kS)YPjR&)`TRY|4!@YAf#H*HSB7uq-~PL3 z3gQv1?kzi!w3LQ2@J!e7_>y6u0u=foB3%i5R?DfmHkBlpEY|LfT}i*B_w2M(Aecrs z;3I1!5|LR=5HFLX-7Aw5@CSGSPJW&fTgOgjNfQ!k1ISn!6yIE~-gHjUxz(`Aj-rhn zu7IQO$jK}K^qyTG)NrHw4RWYxkq*XJr8j2N@Z^jK*lHI;(EAeyzRor~)}kEcD$eXA zE`Q|xfca4l*X=uI6K`7)MiaVbw%TLsD{qRJT5n#r#(K@RC!56$%mW;ucHkDuQCzYU zy^RHb6b}tjBQU?kL*Qss-dLFbU7J?n1AdFT>jy2>-2_v;dyjuv~!(j%i)18$)!w&>7GgX1KIGKQBnvj z?&b0rkCDu+H=LCY;k!!I9lm3tbg=w;wNb$f{gt>8#C%oDNr8ESe326iF|JCgx9RFc z;KRkvfu8`Xzhd9N$;ic^`Vi6gBWg!UjH$D zCR8?@%FYoij`nXer%5w#A|Yo4ar0JIf75A3aO~amdS+Sd;nLjY$DkBG_=Wk`)1_%~ z72a}0Sq^da27grJM3Jbo&j(eX@@Gpa1DlA7k*u8Q0oo07x*(r7@&<=su;0mq*SKqn zS6J`vrn^sOYj-y+^IavEs5E99orzg@8J2~^Th;7zqAmLcjQ7E? z$KFtyZz95;jIgFeM~AM@V(sXG+Eh2va`Trm$_0oEvXS|b67y2X^^@s{EYz%aPf%cD?J=liTsu1Y6$o6^LD~R95$U+?@|g4J0Z98 z`N9NSD#US<1&k5NB9bpNX$GtPz6NMD9S`z`^v*N(62$2%KFvP3%}uJ({L*8F5|fM| zWaOSsrONg(%h+WHyG?x8V~nQ3yDs{+ZQHi(Y1_7K+wN&k+qUiLe%n25+cw|xUu*BP z&q;Q&o}`ke>O*~~P8WEsqz-0Yy1y~NozrMc2SfPI9ja#PVIzw z07C@0T{f#5FXfHhEqV_*Py$v_>)uI?qC__aN?!(k6q(>?vSWXlMec(^jD;l2k*%{p zZS0d^ejnYw5}jE#wES#C3zJ7wO{$?y&goW3Q-4l8?a`Ib$8-8q6)wXBiyo$*_KC&|&IhXU+35R0aCy~ah{4wp? zt9gH2$=z)7kI<8w{cVB?bo2mq$RmY=&YOqO2yeZXyK8TqBoxvG^O7DCBUXaoId#cA z=T6d4!uxKvmbsi)|64bSwSQ{#|x5MO;H^3pfT{Ss@AJ_svYb0!=mwhD}Q%|J!)9sRh}{ z>+F-AGcn3W!Sb3@%$=l6#n@UHOt(y6hf=C_BaCccPa@FwQ+jHMsD6zN*{OEuG(@bI zqoO10BOUD1L9`xPZMxJuCJ4xnh3Q{`Ni91_ z&ViC`2~Svbeg`z7`!!#MT9Pw1-(UJsEGh$@;R>$+>kg}wsWzI2{>RKXD0>d-`jmU* z7|R2y)MmDN7JuYSvzDGqK4BPS)rIn@`?N>c9Kj~ZuYPQGHWq)zVU{3wrbn5^MKFvzzfL#LCJP&jx@Z$w1 z1l<4vtf-b+6Z`G&_P*3)q<-<7(+`B4{S;-YCcbvwGp(4f?ecT3$eMm!iyk5UES=$T zALjv^hW}5yNYMq;Z)!8)~4>hzCs_;iJtsHY|c8j2RNA;EVTnF3kq> zm0n_YxI`qJhM`jZdJaVu;#{?7vT(uc^eVegQUPWtbc#D1&DIJxv6`ESVmDAyJ#oa< z{=CZb_mc%1)VH~%#6vk`x*6UcDUmVNH0Ob<|E1nYr-f03a}>l=?-R-~j3t{Al=iBq z>6Dasg@D%FQ;b!T5|in~N=3xsJ6l&OafViFEyf04B*PrDO`5Cqfoyru8Qg9trhDM- zIWXsZ8{!=BweH8ghv2uw`_VJ65J2#!{cchI{8{@^+YB8rX7?Nl!>P&D5H z-4flE2vn}06A(8iZn@hDW!)KKzLu&YudO@0c%m;vc!}bwzN)@x+qNh68d2#l-( z-76>GpN`4v!E)Jl17wj}_CoU$!Im3yENEj3?D$v{f2U+1L1*&}LKpf*uWV#Bi_PE` zO>~)adJEv-w`EbSX`H>7jwB)Gb*EpgHiD@2qEn(M8d5G9OK2D8HUDts7-rzZP}i;2 zzCi~aU>RV!#@7T74MvIgVNU!TNpF4`Sp>TzwuFX)pPTcvSTINW(bl|^ z96+YVaZk2z=_rN1H#Y2e8xhT}e8Cw=EGM1)gzNn>q){=mdv)W59*BcPW->SWVfvoW zp@m}0dP4UeCp82&8h~3G&Y2ztL$Xt^BeOPC{1wz5H@qMoZ{;PLsK0l-bl!+_xD5Fc zKiuDHzZ~#Ajj1LSR4`U>x}}}DE>nj-G+1UP(tHHbMgDo7yeK^0Sn=%IDu*^o8f7YZ+r9&%$m_B#NUC0 z!fFxZZxjb1GRl)Z4)~`CKDA?F=2piEd#?i9`2%Ot)3y0DVBJc*rohg|b9p*ka%l&2 zoMC?jzdK2^*mD$_R6^?#VUa`>j?4!l*A4qXmJ1M_O}lPnNJq?=d&m-sxU^o0ATTUb z*({1tcSy~XhWhw)FVAFDq{FiY7HLnUE?G*lMs{w|mbnR#GmL{T9GW+j+(X2&i3+$P z70$Gj@?ee98x=zAJ;J=nHRpIriGz?_lYO&2r>LQ1u4;2jxuIR0{hjNVg%fl=V)W`b z<4lHK_!F>;O;-B*r6g9V118)nMzlFoIOqm9ZWA~FWMaJ1*-U(ckGW7j)!+`pxJmW1 zF@u*C2@%JI&234Z^z@yt6%;stp;{98AviIi#jgAeX~*hEw@X5+s@C%wJvBr&kYCF0 zW#O-;BH|PBNm0LPXAqA&1|zpPWIm{Eji(_!ifKzpZuk`IQN~cpL!)uz6eCi{e^|UV zwl$y88oNJ_FNDt^;m_b|3M-?3-{T1yd-FpM(%&x$@4H_~9!(SjKZye@=cV+ABY^9* zgE|dDz8{ke48T!?2tkN;-m$XDE1u#!6K1r?`K!3Oe0N+K{Y_-w4oeWL=Fn{Z?0?#u z3sre9(SCjX_{1t)ryeGTcp?ySUWViy`NL^femW!D#Fhq&Cz~kWTMZx?y`6t&;6>tM zV*%cJf*v_3)fh$J750G*ARAMxcPxI!vm6F0OZgT}x>rVQAxldIzqNXu&(N*dOXSLm z$wY1q6)&h6%N1W=5Cv|z{Kc%hmw#609;K-sn8Kk77jRqDlFsV89fbZw8{6fp`(##x zmVN1QfdYw<#E4&UZvQAW59^e7Vwpen4MUpXtjvVtozBPaJLMlG#spirL|8xp3Tn;< zYGz{N7UQI+PZ;H1-qVdqUX1@!9|$ZL=gn11*)5fyIN`No2^BvAsaj#L8&Zrd=lQEj zbB^48*qrssC~5PidQ62r{zk!+rT|6eWN$UZqm0j;D2FjOniyTNcWsw%jDk_SI#7bA z%^4CI{0#K-rJ`$M)B!QB;N2HWs9B>tJ6}2o-6N+mB0|&rwf37I5;_#N*TEwRjUH?? z#dhKjuFYxl>eK~XoZ=3eJ?s)*I?W2ZLp?b;s;?-dLj(s>#L+ILcI6smy62cBB>eXI zw_t;nzn1wg)#JBFL?E1&K7YLt0;n#r)H_;0knqNnDtQqjYsdr9_SehE&=OICew!kQ z{{~d#eud(Angz5s%cRmd0q;`G3!Bo`3l!Un=32=}8617NdiuT7zv|BGTGf zhx|dZPnqS-1$n?u zSH?J)Xb6ftx-^BSn~wCPlJzoBl48au0rogP zlE4*lUv_=Hk1OmVIjXxrFT{AS^i|2O%{yL^Wb$ag7%eMo_{FDH_AuPX{VZ{+_cGAtpC|K*0UR{ZA5P7yStMDj z(c|>C92ZSwu7WT!5rJXQtBf!G<=}w$HQlq8myk@)#+Nha6RInBa&3$7HQ@N{AV zQV5mE${Ws}GNp^|3ySt`v(oM&A9g<}t^Oty;HJ6(kQ4`#k)cVx6RqPfd1?|pviSSM zwwnQ$8s;@AZAZX3NM9kcG3^le-R_4Ma^V3pnP`nR6@KT@3ned2S5ss|8S65lHVdH^ zW^ak8hRht?cVSXLe1mhT<=`Oo1=A4Wn2$m&X_v)KMx7QD4I;#30UiDP$`s$?$sZA} zer9i-P3n0Cn{_8xL;JzAAtp`0_cf93wSEGi;@>j=xkqyksvn>N*TFn+^`oKo^}-`V zZcusNe&mi%kJuAlYpoH zzQe;PF>^W-caKC&tHS5<=%k(9hj!tII2OCi`irsP`^++>l!$f&t!#1?3I4T;h;mJ} zT`g}ZK3_(*4M}Pz`nS(N;Sd)RUZl~4ye=}0e#lg{uj)iH7-e>+lvA)Y|IyW`OovN^ z(p$o~TCc&G1QG{Ame(Qwk|bFunVTAu>~EpbDJY@61ue-smV)rQ3P46#f?MyUE4gDh zWr0v864Uc;tH;dz*OAdNrK<@arc-4sg4I@mJ{AIzuC&}3vH_qj)CcSnXW~Rw)EnS? z?Z#0ZVSG)3WEL9Ow2GC>x3i+S;O*>HhDeUt)LyFvqdW#31Op1ejWQINE8*lIB#CE~ z(R?>0ylGkB%{wu~NCsspM{JPI=KdQa3o^~Dvk#J~s{Ef`P&bS)WmJ`k6)B2%3*xg7 z?O1BYCT?t;)7L4}8X*`iqRX=APkn2=#wfilDb1+3kkvR!Zc}F4=VAt1y`{3l?@^`V zeu#R~!wi}8irGBjxR2i9BVz-cy#SQLe~V=KsP%?IMX_%Ab}JNv|4!7*kQ_RQ9xEj& zZWeuY1){G_Gj+~gC8!F$Jze-Z-$!3Ak)C;qnyw~@8oDVdXju9?WdemTrO5*XWk0Q3 zgH|L4#BPhP9Ju7Mfr`|8*oqhu?&nu{NqoCw5NR8tHmtW!qR~Ohq|5XK&%#TH^EPUi zE?J&>>DnImvkX3{4ZWdxc7X4Rvl<2N9SSm^m*-ljPW%W|9 zwXwtJy|aChZh?!;AXV`?A~;aZ^qB@+t`G0={4u&$PnchzL?Zu;Rq_4r-Xv=lWS0>{ zFnzBH6g#->NMAwP`U}hW<@eo}Pf-l*6{DGC)$xE2J|#X4pwLbGKSK2Mg6}dhQ2l@O zN0qOT9lQ8g`yo^HU!i#alb#@9AW+_Y@L1GAn$zK)r z6H^a8TZIEGLZ1RX5z!ld*uxw%8_YGs|Bj3Hye%#fsh#uc(HK=u+&>kdAy~wJOm@v% zWaO-1Al+0bWO@-3tAAW*@?ZNt<2q?+QAg`?9RJ7@rPhiUWQemgkPz%Fr z>?MTQ>>U}dqDSGS>)+cmq8N$WQKX*Up;3PxieS&L$w?$D7$Mf_JY4e$G2Wq#sDQ9` z#G1ckk@x!y_1bmlF)vQ00yw@uyuTG|qv|aEC!82E((3QWav4Xt~jsm5dsCFQ5U)zRKj}=(lyJc^Fpx12%p9m%Lf4*O7~P5C?mCm;efd324YLsl-+0 zJJMxAy^qdbA}YQR7T5KcrA@#J{XO5_P7^akU+{7%8$WEa|M83`$E5gwmhMM;%V~wjVYMDn-y625u^9y( z(S8Sb$XS495DVzDQ(#Ua8pRIm05WPnTo6)k9yhS*N36MDIQ9sviI=!GWW`_?*k+gF zcKkoBngGESbn<2whhQSRm{~RjIYt!lb-Ll zjEMf<>JY^$tU*zVZuJySFv+iiOS=~wz5JgHZ802*)lUKFnN8hVz;nlAD)oY3jumD; zHB?u;hJW$hJIctgjhL>2JL?;&)9r9XV5<#64&1!K*otuZ`d+>3mAUhy|eAkD=Y&% z20?u;_d`aeN*xh4Cyd`XA8#t#FDT zLqcyy44+C*!@WWdG({H?ht85#Rc1#4!7||4CfQh#Fj`&R!Kd4c$KAl%!#S;{%3ju7 zIbwEIBR6nbh9v&R3g}^Cm1;)FEZXa_3rRZ0#_>LizoP;a57i_6)?q{}% z#yPs$*1qfTCpGgdGRR-mIL$D?GJ03&9|RUsTtw> z{&Y>|ZAWqFVv?e^FySZK;cz53QPCstt zN^3L%S&7tN$|x!DPm2eb8_q~fD~AH({mXB#9Fy@ZVjgi&S|jUbN?+G!6|}CU;AUmC zSQq)5e3R`Sbgnc&t~;YpB-qKd9@}mi5<%l8(X=*AzDxpS*9XoXYTL!1vXK>$BCLK< zRQC~J++newgK>`Q4b;*V8xY`$NPw2?C>ohsW_zxUqOCuvUp9`U<1rXDHS2v+@7QWL z)&DKt5wA}@et9OA;6|s5`9)dNF$Mcebzfn6&8o|HoR`U-MAdl!ucd#JF zJFIO)5G=QzuEgHG-t&87zJkq#r9!myi4&JXd&a9zevFxQomb1C0%80B}vgJhb|o&ivh^k3S3N_YPs<`iRDR~A?NQW zU<*t-+Q81)(3#1c?uA|cyvE=sxAC9OYVpu~qF4HP3l(6&6D(H`P7C2%ETXMzf7fD+ zF!VNppD0^;@?$1sAn3`sHa=3~8y3K@UH(gYgU4s)QD{ypa5qi9ffh-6M=Y__7{Ozh zM^&dJ5v0R}d2{+04h~ot9#6E?H&DV(2QxR=O2_&(ftkHPC-BUyeId(Oo<7#>&JYm) zK+5F`H9{12)$uRALN^ep0n8kL{jtyk#3dfs?#u7ZC>O0p!-vtH1S?iF==&nmRM+Z- z6vye9II`(A|GYtee0cqvK*g)M{{r+(PGK0?VYm3Bfva#H@nc;bJAyoBDjy z=>Z_0f$H_1S7xOd3(&$lhC61{04f+yIOib0o{bs(3i`*pVs7;A2 z@dG1K5agP#k!$OT(A9>iBX(T|Ymk^xD9+--L)au9Fp#+TbL>d3?PxuXbJ<@rpl0AO zcv&Ktn^t-YSEGbVI$2h~M|c*7s8pH11Oz$U?u-p%E#x zUHxImwGq}k98-cf*po#E#jic!`0f%2#vTy2*4FaHpL2`o|3P#b@~ITc0y2H3IFqIv zg7@#h+f46oRb+$rh9o@W^lo_@B+ApALzvwmy2(J*4-y=VbYByDFJHiD{f*boe}VSP zqI0Ryn8>`v-auSZK6rKW|H{@U`bc2XLHrEhiv`gQI8(yneA2)8)u-SW@*sCZQ$ogj2qTQFuZl!n7niXwFAQ$k!M;2k2uxHg~oVjGVQH!~q#+Hoaij zB}JR`G~c8urz*$z{h`bEZ-jSo>MA+q>viaZD>oi#8%w2kMf^b0zU~_Sf=!0Ma890PubKbs4 zb`s$)CXD7EN&P_)^uDaO?G>u#*~qL83Hb8_uCS1ZFpDLFYZ}*=!ouu7D&zO3g&s-m zcP=PE%lmg-?yTK?EKNrw!*3}ePLbS&upX;?OyofZ8cq!oTDhuIfg{9#x96dR&*fjA zY4LrSp28igx1}_y62QSV|9oysq2XNDw>LGEppVCmMw>V04YTzZzlzERDv-M(2xB(o zQG1z9h`Ri~_G?%+O1N&pcB4(p!KQxFl_u|-zZWko^ywQ;aE>#D*fPY^9f^D=O&Hl#2T{@JMk{d8e9d{&;OtazF z6#M((6FY16J5GBsK&ZfBmp5Ybl6+?Zms&E0(YU@6|6gpxoSGh?jrZg~_m&zODhj-1 zI-8!(JbrLvRL=zok`cx;5)(==re-;{loIZ75t4)+hNh&Al@mcnsiqVZt9n_YYFS;w z58v^UQ@rQ`Eus>f?XaIpic*arWjTgNDA}XEHC7`6LKzmTbosJ$blqw>BePM4Hnh|JzSS_O-IQD|>r2x=XDU1Neqh_#Nt z$CRht0sKw115Y!?+2V8(B)zH@Zdny^``^#&2I6lm5-t%`YVk+-Jlq4VlPJ~{Y{6%n zXQP1RU!y_~7oPK=Z!4Di|LBos&2`YG10x_rJ`8$t?qVN$&9=T3Ql)h_8}%qWTt3Jx znB=y?FNziNM^%pTRqPgF>9yV&IVxylMW`?)dQE7MGrMi5(TQqxSKd*C`51m>y3yby zw;o>2)a{;#AST@Dj~dE(dC`Xp!@1l5>jV{RjvO_IL@?AuSv)K`YPBwDH7qnfivm{4 z-eXQ`Ue#lB9l}s5mTIr})fUY4rn5B2R1+#y_ST-Cy)~1rLna|l+a0NUnzQrhY((SW z(l|{L+JEj3-Tpn_xeOKZgNL`jv5w`R2%03G?}u7L&)d*R4saRg%Y=@CME7Gahok+j zP6ovn2}}PVj)_}+qwW?)hZ0MdF~pG9$r{-zJLe|Ik%2=YEeKG^l#i3cpyMfhP1m<| zu56Tc{p9r+fNTx{eiU$f4NgIfif_8xkND3H`tw1W6c0D!G3V;B=eC-^dAEQ@MH%^e zk%)VaOE{fKSdUBa32EDUk~P7KREq1Y%!%XRA*8z7knSJjm!W$jQTc+%j;#Ae(Eym5 zi@xlH-MED;EB4N?eUFcRO?y0x4YkqOrNjN+L~eqpT|}Ov1VYR7?oMf|aL|q>8rnan zVfKQK6bNp6x0(BF3nKkQA1A2oJeQ8%lyo^3`$H901yLK>M6dqqmbAwbC4!S|jQ-;o z_1KX7SXDFR6iB%f<9%(VB&+*;V{Sf=1i{FdUvm6gBuT~nq+XS0%5^eY)HXyr=2^c2 z5sP=nLnOaxRI{Fi?Nyi<9XXBAy3(0yA^4QKkmN z1MynpBc7lz7><`S++`rJ%yKD$;mx;z(ksvdcR9RZWx_VjmWCp#mW$=8#pd|1;w#QV z0>`=4Pi?~qwHbxTWP^O&YV3~1iNQer>->oHpU9p0W@X;ISGY1=>jPC`r;xDVUP70z zhlPMv;tL7~JQ&PCV7%S*5iqlmVhPIxeqv#`w_x)H(O{DPV6MZ37cK^Yij z*U_}i@qkFdOzZKq_YOwF)T=G-Q<+Gsthp-isb6{}$BZ}sZY3rCJVW#$1Dqzjv`Ey= z;g?F0)Qn$_<{HwhwiU4$bV;UN(r5_JAovR-3V$pKr5<3EO)hp;a$htj4n@T7c#)S9 zZfTmrn6pv;j3%{~SUuLbZc1BWK;sZ<|IYPY&pswKz~x_x!X|2K!+t(*c8?Fm81a2$ zd{{4@VPkURLNT|`gHqi+1Ak7+p%IsgXSsH(4vCyt3Y%j zTbMdqgHQI2UR5sOfz>r*ngzY8k4#agFPKC*S-KoAvtA} zo#XSOt^KC#u59i5GUTD@hz)A;G7xtu?wVpK#U)pm0k!)g6W;C54y!+3oM2GZmde`{ z`vWaffi+Gnp{0E=_^=WO^P;n88UotBMD%U~(WII-2~nbLH6KohAmji&8Pt*yLJTPH z+&|(tHo(L618K@bu0F`WvIQ^{WuG8Tp7;1gs0C)$WD`vU2%+kZpHrd_+kF;iR6lB% zR%MIe>l95g+@yY|yBHJxJ$bH5DZXToB7J*twejEoMEoi0xRE>_^v%GLau0Ba%seod z5(B_}y5{;uB8d)=b&|1{YOs>UJh*L|N>`-lqtKf{dpHm3C=M2IEQ%RtUwwrG6O>Lx z+5X{t@J&<9YUeYY;$!#U%pjr;AtR)^LZo-}eouH64%QAe~t1_kOtcdO$p`jK3!!r6~;rkuS^2`8a%_Yw+An7|*edU3?9E!=)o z?Gp^s>Kc3;W3jH1J* zW3{h|LCw~|ykPnm>tr+DQlUW&68E?X>#{~;(QASODgF)Pl2oPiX=Ke6_(eu<_fbVL z__#Wpa&HVXOPzv^Iyp>p9KGh_VBu!JWvvQ|GX33fDQ%iYR0mnPs?7L|i4s$RpDy%6 zy^?ta-^w)zi|Q|0A2aw>La^`_fRycHNK9Oh-}Xz8rIjQ>~@Jyr46GO=gm3n?2Lw#`0Hq6#LJU*@7%2GF17VL){zt?&#}U< z*C`z+P3lH+*KaH#{^cLMkXOpbx~e+{;td4F=jwl#F<4?qxZ$Hmdo%TBu2vTO{f~mM*J|Y?jt`+L&#{5OpWD>tfqh*#+XqK zwSxjP&KMD$i3sSB2g2S%go@&o*28QC#Z}oQM@lMpM_&_7;uapLB@P$h@_RAdwW^TB z#%b6)FHX7>`t$E#!Cfi5sEbt6A$JW1O}hbwy0K=Sg3Sb!_~1 z<_QiKET_u)hcqzi5ue?*(ukP8rNvP{yX|nBf)q?(`@ALuBTM$60fKyr&f*P6nBgpP zmyyc4gV!nooCNt#UwZ$-ot`n?9w^w@@Fo^dOUw|_EVOIaie~v1w#YdwV zyKDC{(Tsr&98~13eFM+RS?AjiAo6WF*mS1T0Eu8Zi;%bUAkZ#|)dGu4cmZiUx~-xc zg3uX{eBhUw*-S*)Vm`lol zMhw1gy$`CsotiZ}iIyZUTj;s%C6KR3Iu-w_=WhekLEMy-w4qZu}h>n1eVV~2_ z1ARg@bMbAbptq^*5G_@sONovns1v11plbdk6Vr$Zw2#A*tJ(Fi6qZW0qq+bMLAl^02q$=tNKL}^@r<1t zQ`2zOOoYjh9B%M<{bU^>(T;BBo^u?TYjS!N!Hxc`?uDuxvdhHPcPWgg;djC+Y^Dsb0rWuW{?>ph@U$ z63a7zb>h7&e<*zmh`7xyq65?ZZV_zR|_{$*!ZmQ**( zkRKscXr>SANF-NdEn5HaPp!0U9aeADRn*mO#hmZq(_jG|FQTYVIMC8VR9k4_XCOs> z<~warPSk5Go33*s*YKpNaaftcY(unle1noM12edql*FI-fmS3l9Z#Wo;SIA_y)#>- zC~$J3#>8A9jArNFM2WAX&whz%)@$isH&J(HKu~_6{Av@#nWX2k9$hX%$B77xo9IX~ zn!#dSp+wVMA1F8o10Y9eqvJJQdkHPy(SXjG~Lmesr**%X}S8Wd46-<2^( z3>qb}sog}TyrWi#@4ba?)c;Vj^{FwV2|o`0rv*;w}GC}#8B1ykXY}B zEqWw|M{iyz4m-Q|1ua-2T^fV=X;QBc2>w2B4}5!k%7haC2Rwb-oeQ!73Y`K4eqMR!1}@(l z00U9Lmi~(dVM*Yd+K@1CC-Y_i*a6fz2flqaJgj;Ezx;5b4sHj=X(t0WHx1uz2UZ+# zHxCMefZS)hNkF-HgN;3Dw$hAaF12?U>!q47PLu^Tq}u~-KW^`WL~e<{h=Y9J9f5~Hg6h{iVQ}%E)tl{~#X{hQ z=xy*p%61!E-ZGzjQ{vChQ=q?vjUd^6ex8nHj!ItW$=eH#IhmF1ve+Kk$b zR)|1BkODzLl;yx7FhF2nU_j;q0^~sce;@mQmY21Yy@i;QxsQUAxrIHmoQhpVNy+@I96G5i_OQAG&UoV1r;^Glb0oA+har86xEzgH3_?fG=(%IWi$TdH;@wfe$?Io(GD z4VKCSt=H?LPWtAR%x*BZ@69c*sleN^1A_l)o)p|nqZI@ptP!#nWM2KX)vGrotw4zd z>^SOnfutC}pm~1?aIERcbMypAMP8S5HFS|=1kqlFEm4XA;`GA(#>$(DicyV;BK(}m zJ2w&UNS=tGJ3pbk(%^oMos*(Emym7@oBE($rRGyQC%B{ezlEJE?3L|7jG@|Qgr`VA z{^RzFN~hWicu;1x(&Za16L$4V(U@V?N+9#zU9Q(0yrvx=4X!7FDCY`6lVJ`U;)|l~ zClAK11{aoI852?8(~PZxKY-JmCQz9Wm>0zSHdn2>uA>`Gu;JFU$EM-@DH=5N<>17a zZycwxs=DijPTnl@xYF))E3|_eio|$5`X|%w(CaEWSoDKHo@0pfv>!^#_)6*_2S6Cl zZ8-CiKCQJB^K-xX6*Y30b8(2nw(Q|IDUTYKXt*GFC`QuTgkqe39GQs>D!W4r&bpN- z$jwI%HGg{wA;N(GQm#b%*Z<@tH9HQ^{VDba7aL?D0W$bfXUAg&M2Y}8b`bZ=ijDD& zmz1Tme@#RnV!Fc6TYVaG@j9F1g5z}yf>^!L;|62Eu)v2hOQB1WY~DkeVZzkKt4f!-^f zZ>D2!+Tl{nLq{5U4Ve$Y_BuJ^+k>8a8eHwhbuG?8Jv=xZH$-}3GD#!;Xm|X%*!Fz^ z1pSv3JDjF$li(mAYS#wURNgzs8G+cy71DUqRr-;1zJQl<;{uPqwnAuHj>h zLs82$rijz%QjDV*1^zrn9Um$^>h#IY3mMczq44)J>NC%=`X<{v6z);2dg>Qk)Em&f z4rE55pi7`U6HtJ~8%Go)-G`~>exADz>~8uwW@@lmgeTL=ZzFXHo7>!bJCY!V8r#-- z3&|<}vDArluBIclh|bh$^}Wi`yrdtqtkrN}$074-rdhoVM46`6TA&(z?r>0_ z6a}ubLGolc%UNdVTbz$?Ncb*VZmSVbDYVKi|8E>Lg+b;uG}QmO=p2*Il53PjA-jw1 z+0_%9u=c^}M!hLnmp}%u!J-yI+B852=Iw4O)~oC2uqBGxY-i0{Etw1H0Xp;No)mu; zeL=UCEXN(mlykG8X&h>IZZ%{UU^``v$Tsr14yY3bUS;*w>Z0@{u6$8 zi2qz#;_T&w;&t&2-3eVG$070vbtct_1TZm;6(G9^4+^NeY7DI9y^v@#(Q%q*X`*;iR>2B@6uKCk}-k{F%^=y zpuyi+M3>YX2Ys);XxgIl@BmvXK+6IPnORbs47;G2e}4@HbJ3xpPki7Adm%HJqEmJL z5e*vos%uj$FpdlS4-f3(X>>`=?M}NyL4U|02z57NA{fvPy^PT_MWF~0iuOv~jKb(y zJk=(3HTiLzdUI|8bb52;A14KBgZQe!kjh0oy3QMNmigPpXP6GS(xA8FG=tl)*sB#F zlntlBR(|!)>yQK@Mogr^!W1B@Ni=^0#{Jd_$U42$TP+AczwpU}59R;7>VV@k5xS~; z9nwu5Q)1xco08mNuob}FR%Si&--h21VgG0mn*K!HjT|E`0u6*fad0IHSYeot1do4I z_WACI7JoV5NP=8})pgSoZGgWKfxH!nEM@{0~JuOxV(p1QsNQliBtsOuJ; z-}&3>hHkp#AF9pqD!DTjf8slP&~-=nZ@dekrHC32_9F>S^6~rs7YV12 zVaLE{rflE~_5j)o=e(H!$zCK}t!Nk#-~7n7hVRjB7Xz$YviYVtaSjuCS(# zW1DQ5Cqrsap2m7-o760NJ|!03-1^|i``v@NK@GSdZPnk0DfqZ-iy$&@_N^3)gG!vs zs$Qpb1@a1qV@ctph>(ynK(L!zSPQBzp9Bi*+`i7{^ZGR5sm0&pL^^hF5ie5s`PY%7 zip6`>aOTx2|0%Vxw(y~1RM(XJp%J&smx_~CYt3y#lY4E8bAU5AQnY+`UH1&VKO)-* z*L;8FqBF1fX%GPAIk`(ySL%{UOX!RFSNPmJVfUANfvl?k;(gjTQOl}>5M;YLx|wY@ z&cnK{q*?}v_%FO0AVZW3SH)q64<#k z67IeZKyH4LmhsF^v(b({SlRCiXBdCo5bXvAmuE4A`k>Wi@pJA7=e-CRkKES1tIkY4y$yANOrr_A+mExri8FpXZncuuA5x+ z*N;0|zz6-vhk71-SUvBwHC+rcZxF_h=B^j=hiRq2a(|*zpGF*3s$xi|jH=%%eEtsh zb{H3~Y`Y}2vLrb;MVsD0s|g2BSF#NOEHxjK|75eenN9Tc)JC=xkD8)P3#>n@=bsntkl@s`_K8wzQ2}hm&gHD=s*ArtX-$ zCH=L}=sm6XyeK+c^XDg82ABbN1cOCW*p08ol7(Rrb6V5K^(*aQH-<42&YCp4lUQ*nJz#G!?_3JZfoNc*2d!cYkrMBb79JzW zI|1IvP=!VxS;A+&{cQCQKI8f6B7TAnWwtn$KYQ)dbEDCQRX}JY^1iPiqV&GRz(BnB z?A7qVk~eMWZ>h=)lkw9I3xAlOXSu1%$ACn_{YT;tA-6pqAQ+E^b&8cs^TtZtg*dc} zEHp826D-Wj?>*v1k$r!>19dS1mO-jjy0cuq;s$*+sv}6A4jrG+OcyxI{YT%h>w2%&@nX_nKOuniS{aESMTHX{SiNohCKt20Kw5+U6A_ z>P1Jv@MjP~C1#%D2r6d?!FbdC13#c&%2}9k=t^jek(bbieup53QBg+?L^1Voz{#DF z+FkRVR2yMaSPE{!&%AUPkDU-tq(BfCe?FMxk%R>_!(dy8vQ|Sd6WfGa=?Dbb=jx_0 zKxFpg8CmR!t+vu&$IZfympppo?q9spowyqVHP{Btppwk#js(o)9B=`mm!01PQx*bN z2fxPb9?z{RJdi*d_FPmbDd))lOoX;vQ{radsr~0Us7eYY!*2@{%0W!&{X@$w-MAMX z_q*!O^?&P^`~s6ri)6*cKR53!{Kbh2$ld~=AejD*+)g@A(#KceJb1!LfUw?xWf87H z-3$?_lO`%`Jy<`E!27w_H8#k)@YTUJtdAWF89tI%-dWe6HzOgl?}Ny@S{mk4hpb}) zhvA(NCEZFnSt(T7PVuAL>I;mv-^8sH z6~J@UYu+x_sm3w+qnJ$Yf;CZG{Di-R>V()kxst!F9_@in;G6y7~$~cz^g~(6fO_t3b{3!Y*Pg8< zD-9S11`T{QPgj4{k=cL{CM2I6PTdw5ykA~_ET!*8l{8-uM1bysP=uUVq%^u~SUq7e zL5!e>Q-mODbm*A?Fhz3sB|QlyBKM}(_IPGs50(~&VBIUq!rJY=@-V$zG>Z5+2e=!D znxph;koY^xdR*BbUfh|JyIs$#rVeRbwQu=0g9Lbw7)(-u9-Ep$Z{>OZ@BdvTh7^AI zng3HI^pXFk7_$8jF%-9Oba!>KF*mXQ?=U(!{Acgs@V|x+2d5Gql%M{AVb_5x*%0F} zSas5L-^BnPi!xciS8!|7%7)&fL7(-X4?=u-@tkc$+jz5*<)x%xIh_~91 zzrD0?Nv??^k(oq)!Ak8FSCW5`9AEef>^OG3th52>2-PNB#v48Pk9{*^4(`_^v}p-0 zTfDgxRLGhch9z~J<85`)lLUreb$Y!y#A^^Uj0IP#S8(O`@eO|iEVyA;4&%Hr_df3%eIHCK=6hChJYp>Efw zQwz&#R|AG53M%YWtvrJyHc+zRC(5&gF~;O^oP~4i(RuJ*LA#RR zt(SI%`1`3?Kt&a5D3er!OJp)I&ZBygd#-~rjE3PgY6Om+{NJ9B}>B8X|2-DSd9zZ0a0m+Hvl z#9HO|l00)FkyAX-6;YT)EzE?^w%=A(Oz+2Pi#9Rz?}|D9a_2I~{h6j&0kvZQHhOJ0070I_%gy>0W!+KJQnj)~@ew zs!~ttscVcm#=K`LU?qbQayL7pETS*Q(q)EEPj!yAxF@*p*AB3M!aA*Kk_TTFyeR0d+jtt)ueSHY3yvJ3EuefOfmeW>=cWyC1%$KL_{aQ&iUGq+lT z|F>go9Zt1<8G|0$zZnDlzZip1EgV7&X`0tDZiFkt3$hr(~3JfC^yK!h00U?8-b1 z<(|%1l9}~HGt{?w1TwnJ4s`Zd>0aeW3JBAdGXZibOEhnYiuUqp{{9MFtoNdcW& z$PP4@j`2;oRt*u8_zvbNzKaKlHqMrv3#T@NN>_X?T#1{x&?kbsEr{6xGMiq!1Uk>+ z(3a>6(Yv`?zXL{0LU(86n@Wjns-3C=kN8ezM+!Gqftx$BgU$W#B<33V$wSKIGaP$; z3@;a=#}(!x)-5Vm5HFH5Y&9Y|JKF6w4ex}j6_(qDuYTu{c#yBs?L9#^VT*D+1Z4Ti zq*Xr``~_{*p|AChtI*yBReREl@DtkPy)Gn2!d^Cv$8^OFy`-x(a}u;aYK6RgB>*^nS^E9V9XqL5AL_sF$DP&eF~ zY8bq48zXh}B32Y9Pfg^{3Pl47!+xhz*Es3s+J-67xT1vxDHtD0jz-XW!YB*EKIwlXqw}(MW=j2J??D$VabM&IUO{^y1_y@*&!(WpgFzk;x7}9$mTpmJs~8^nI`9z|X*} z9F%6R(Vz0uh(IUMeR2Y_a0yVRkr436{X#0|E{OgPB?7f!ezfy=@fg9Peh)=El#~=9 z;;_tLpDVVTzwNv&1hthV-ggZnuIcG54UsI7eRbPIP|4=BpJ!`HJzQ+7=(Io6AE#b0 z58S;xHcJ}pWqr7E5S$l(tWAm&(D%NsyJsBj!Becre9ANIy=jvAL)f_mp(9Z0W18*r zrDsFcCuYaxM*HKKXm7Htfr68KZxB9OumhsrH5b|=}peaEw5#rD`=GfIlW6&S%_wb7z$ zX`{Hvwl9=JiMm(f$}*%tb;H}wr(qXvsvP6Q+t1)i+e|B3G?u7)Xew8Nqw}1Mu;;nV z)aB)oNM@}5tc(wTJnxYJ^xf!HvB$Mfjwou9Tqu^>_|q7^A>U{ZGd-W1m^i`t)>Ovl zOOKl)?h6r7*S(91fNZ^7l0y{d=ekAq^kHcMhYJIw9;ajQ&kW3$XxygJP)C$dQdkk~ zpBQFJkvn8B&4+P}yP*EyLus;oEKpy77Dfxe$kL7VWpxQ}zshxC$?#h{-x@GiI>e`U z43+r|KKDOf-hWX%EKlW?%MOa|JUw?$f=1{a9iEvNv}d1Q6v#=&O&kDXPAvz+tW(gt zybOU5&gO4bpy{C$BIf!AGJ+@w}Xj$PX0)1l9YFY3gPo- zILXkUAdRKi=ZOp;PnyJuZU~W65$?m2;$sQOsXUy8vB^F0HbrGUVwZC7^YyXH=`=s! z&MfQ(Dt`2@#CZ2U{9aV&>V+h3h<|MRCE6ra`cd}h-{Ci%M6{aPp52i)AV3BAF_pCp0>9Lq=h7X3JIQO zB=%q?ZD~CNw@Nq$7+_qX^2M7fqm_*)O9>C#_HiEg+o=1=Z4`qye*J=7A15c>(`5rH z!;U|G@USy*>n@#A_HeB)Zao1rZXZRX8R(z*LgP9sdP_zVx@97wI}x2K5%U}3o&fLZ z{RllA0EX%UYqyLncOomF4#uEA!n$zV7czU9r^nSr@d{|2NwL;B!sNwY)Z9@?nMoVJ z4{W89&2pV#o|9E!pv)&%As>CsL}!_20MBOjHa~=e6z7H){^muYrr{){=Z_WOYg7eS zegzVZc!yQRRvV&#}7gPdK|0>JF2O@sYDHn@>SZan+# z!Wqs!J2KF_{`%CjxxoPoyjP`ygkHYPm@%7FJ?x&;3h`;}3>Ab)Zian`S2q&OSDzL@ zl9`~1;Q0CKBH6RB$lf*GU!HXD-eaq98~e8L_;Et}LJ|Q`ZlZTP8mqY<0Tu_#k`fNM z3Q^a)nR*G@PrbS`U|zr|1>O0%!e_vV|NO|vDpB)bAGjzDa#G2lr9jdbfTue!>jF6d zw>&@r4JdGRUz&1_wnWRH$Fyawq`#{HHy@;Zl4hoeLB+xvg~<-(A&aT6+Z$|b^MV@; z?6tWsI}`5JH08Fk*u8*VZ}eHdmiRk<7UacxrU`zZ+nBScO*)igi!L!Gqv5vbk?4@Z z5}!}pnoQCQ>o@Y#72j3AXk2E0Bzb2``@Lu>7mW~j3jV56eCtF65=q7W)R=&4tt^Aq znU@2Q;u=;s`D>Nirs^}DlE?gyvWcbyGN!mbSAt+oQmkmcV{#guNwhsoXN*PS_e8bm zQnh%cW+f*8C{~CC-82#~uACL(gv7hbbpOH{X5DYyS#Tc0s5sux=@+=nKO> zkLbKq1B;L2oL-^gn^AH=oUKaqdg189q2(Vx|U#lNl&DE@Cj@*6lh={efiJJ2iqqeXcmV;D#^lFpxz?6X}`yYbZw zbU)ZhP-V^FJ;n;f&v*bJgI!tJnWRNuPh6aR$s`ua)E{bdpQeVNFWx$Gq;6_!K-U-- z?Nz3hyi2qo6Ef;hB~ox%fVqVmmTmocg^YnHH-rz;z+KI6eS^A8&$=x;ZRa#~3~+3o#AZdQl(omP9DZr@4(T@> z?Gig-$S)M$(~m=IEXO+sK`Y9Obm#77!r440|Gkoi|0Lq7ez2mxP}eAf)EGa83@`-7 z7zxiLlAJ#hP5O-tw;&Q|NCn#l0{E2h0#ZPO)Y``Ks)HBUN$~u#lUm$5V^2WAygCi* zw=)?#MDDNeJ0F*c5Ohwx-x~qGv?qpqJeUVQg6=3#6ZCS&9%OI@>MFty4E#aR`$RZX zLVV2DP@8%*-hFH!Sv{!Aca~Yl_*+Dr#$YrF^DF`RN+1BCks>o{4#EJxu+9fUAm}A>^H!nsu8;;o zl`=~ukQvDrTEp}Ci**7`MIz7fyiZk+#*=EOlqD!5@NC<4bNYO+$8BAtV_CJG23j)V zynqmI(HT;%83p%vKOak7S!Fw~lb#BdsbCf_kRyhrgB75nk0%8y#mVTKOKJ4IKH8_~ z`9p*wqi7j`V6M>(P**Lp@y|SVZ8PbV8}UIB0tPzMv3007J|5u=kca`jq8*(eDdkr) zZHy%wESQmAx& z&;2%#!!I(=ZfD>aRXi94!kxXnnoQrQh*v|E+Dhcl1)J=qep5cK&=8X*MnDiCx1uK; z6U_y+y2t;6p!XOA1K+BZ5K1zq9}lom?*1?+%8O;kkx|b`enM+D#I*~_+40A;E_xdy z5gO;s*ve0l6~+LpLfwQeLxM=J*r5+1ko}6IG-v*EC-Jjq;WMT}>%d>;HZAJ3e7z-J zQ0}h35?W6VIFj@_s1(SE*ZI_ZZw>pg$e~-~B=&>L}z7RkDSH%CkyeK)ES(-VT89C6)8~wB1RW!5uyU5p_)afsHaf2H^RH zldMX=4R>z`uD|E-MoYQ-n1ZY^ZQ7GENqYGsCKRdLshK08H%!?k zJ_VA9&FeNAcWPs+3ca&OSD8$!J*we;`*V7hnU|^$f@+wt+r+r;hTy1m@of-T_WUNx^Z>i$le4`Q9E zOu0e<;lRMCZqoMELdDd1_p^+BrY?}QKZyo(+kL&CjC+ZDIJa47bTXlWZRfklQ5KM| zRsr;?vN#*2HB`a#ZgMmP4BIw8qXuZzw>MPFMgSymM1@9zcgdOC`>x+=W{D4~N`7+# z5I4-Fw~jx{S!I4pcdsJhn5zETHkz-EI0Bv*uTsBCs9{}E`KKU1Bp|!Bl zy>9j{PA0C*4)7eE2RuQG?6Q0e1%#3%x9z|Ay-CqMN%#_R2t|-^h?%DWe-c!EO5sRf zd~DjVRo3oLPQHihyB{LFr`?j^1yx(Xa;EMI!pmxV9gB&P(P0wPhZ zU#v88haU%!I*76R$U+6;z6s6?Ay=zziuV;R@soO8#>?G3B)l0W=3MQT&_14BIHfy~ zbV9T-hr;SEp-$#BsJ{C#06S0K(*Ob925$?}gi|1Zc+{Y92p3{-LLXZ1HT`3`Ub-B1++lOag69PeScLc>4E zBK;S#_!$QmGZ2j??T6yUsb6+X2CZbTR`T>ZfNtY=Szq`E*`n1#_Viaq$bsTM(*f5m zMuvzNI~50rZ;Ddz53+kvjO*(J$L&*>L^>xN5MOp&cp+#F?>{~);pf<< z33l<7G_aJul7<8+rf}8lXZ=m1Gd+p2GwGThRO! zk`FoJB(1~nHSlvr&b13uhP$JmGO-w~1F_k=&7Q6I`=xirgao_P!9Tq2{^2#_nb}dx zVxm(=($RWni~ljU+h_g8L=~1az$`oP3~cit|Iz8a3Au;H zMRzD)l~IjzgXHE!A23BCybJT*WZZPuI(;3Dpf9n?n0DSH70i^#C%D05>--1YYs^KC zVco1a5LOll>u((o-{7N=kr1umz6acQsTee67eeAiq0TZ&)2Hle)yv4X8Dv;C$(*+- zB%B}N1CP$(TBKZ`_kr!;JQS-XI)8`-OpvS5`d^8~`VV5&^z3c_$;Enx|HOv%=&xGp zb*ZAdm7*24K_9CWpY$?QqFBE001Ra3-!WAbP3YLuZGhZROVDg;)&#nH4U>>|{e2+y zNl$^Pk*u@CDnWO+k&$RJpVm}?^y#%lW(bD2(5|O?h7Y<9BxS@gV5Gt#GC5FL0+4Lm zv8y+!n1ys;*f~KLdzB(mc1ITkGo7bTg0S6V94ojFhpXW*>2R&tivM`_(0jo2)^%() zEPq6PdylzVRt!_ZcAgcaK>O+;j>L89=4XL2tQNI$H<%8iEuqC+qfniLzpG)K3*?1Q zwY@alIj=gD?Zhr(u{<5d??}27{uZ}K3)2oy{-5+oGRqA*S#=Hoj-b;S-Ii`yI~?el z*49~Jur^Iw{NK_*Q6WEIIL7)-HG#p69$MFqPwqyS3<=e(W9tJaRRfcTl#_-)DPNhB zkDiE-Wk(25ZFmb1+mQz{@+`}P_VXmwn-YJKqsoi;|7N`d6s4ZBwo!cRSgvbNLz{to zU}WsnV)+TFZB7NTy_z&c5em{VoXSbx(a$XclsTKxmD>j)izbQ%@M*D&hqp^dm~Bot z%ce+6e4*P7@p$z)uzCFfcrgoj0Z<9uQ(cDU4Px7&?t4u%QGol4t;jt}=u*(WNNrbo z1Gzz<=0j1xS*wPfI&(k|al|^v?Z9j|2mo94>(7e-aNJ_1)yCYfVJmfjyC%TGR*a3B zVLp?OHl*kJ)~>gOuK1QAh1bJq6W1vTTIi2R-A(S0N^@ z7!g${!&f$4n@{UBL$>6iX6d-hBXKR#@uNvQA%i7iPxKQxWKogJGpO+ zosg(Vp7X>!`sn!O>4DkFJLQ$T3SU5bG(Glx3baa${-*sEc}-_Rj45>lv{=Hm_1?t3 z0_UN5Y`2~@bZZXmHVHwcr)H`-n2Xf&V-GG>nFcNQ3U;OqQL%t zibBQS%+cr{>z1%tXMpLxRDn1x0wvP$Zl<$DU(q9n$EbxJh?b_|R6iUxB$a+W6QOke zRmmToujU_%B6WKmr@t4XMLUx`n%yGhj~k&sn69L8RV;q>Xp=L7>n*zPt&!)4ZVpQp zcL)}z@=r^IQtU=$@0PRrj?L5D0iy6j4kNGkCj=3*m;bW3(_=F?OaP0kGBx#jQR3Q; zJ9FDMORi7!?hEh3$BpnaTQJOG*<uKJ7Y}=C?I-+4(P-V5?t5+Yr)=nWyYEIjm9%O8K zZwrcFiIb~MAE0Rmd}*QgWLnetI3!R4XMJt)c?x`ZdB}hKMBSEK@JRKJm=-G_%@k&f z6}->mmu{Qf>E7$vx#clc-pHpb`6T>D{XD!6z#pbVt-$#rzL@6t*FgRMW?InF#=znq zrnmp>KD@Ve^xEjF6no!nO{sF%@E#Jy7MHls<3I#Eu`)5q3*XONoC%4o5=+gKLpfjB zx3hX)E#o_^XlH`UlE=w@c1tkmPYR%QmdU@}?p8Pi{0StArTanJ#q1E80+3Z-P9Lcv z0b40pR&lanWoV1Rd^Qe^$K?4!s1s>^IH2N}z z1*1P4IquIjGD-hXO=)d7z+m1KA4BugA&wp|q-=iq)Zpx_vt_Je0s?*<)44O**4fdBQnv91SFf(x%$?@~m6su)kk-e%~e=dFhI8x16ynm8a za;n!x1_;i#R5A9c=`W z)-gzzrR;L)S(YV#pF5MWQ|KOPOuR2wLPWFlUEC{S6qW%zeD%565PPHTW(8PQiU^XH4xHVX|K$_t*(SK?t9*ER3=jUR&7) z&6DBjUq?nCGYfwiW`N(%&QG_xpE=G;WQ(FRD#-dn^mF8N+8E2m{V{mp<#zKMrt^M+ zUU^QSQ9!xF?0Wl0dCZ5E3*V3;qk)vs=~qV-aKBSk|6aG3LDq#K%Og@rDey9yskh)G^g?P2_TwO{`n*p~ zLCbP1l~z&{cpi=Ka`HY7cJKZ+j?0f97dTK04g0M-*kHzktcJ9AxqVRy*o_Mt@r~bt zQQ;P$qg%>zj}8rEvQ6|C)W_kfA%dv{<8BNl)csau32A#A)c60 zK`%yoEYIi0CQWd@)$wx5gKe6Du85SBtSJX;el?gi1gX*f#)Ka*4$NQ(*nME8=L-b^ zcsbh|qa{=+XfXz|r_AmJdi0pECR}vFf?Wyp9D%+V?sMBwW{5G`8rHr;-o&~LOTy;2 z1!@gyPz&b2xigi&b#*cTR)4@P2O02$G{rqrWpFE`2gzzSJ2Oduh9b-hu8b<^&lot( zWH<(p7u8~5F=;`T_Ljvy!o`)K-X!J19#rMyJN9pJ3Z9>6=;Gt(>+stMw*Yo3RYv!M zn?Ss2>_{J5NAlWvUg91Ha^{%;bt)0U_xp^w8ppB?^Kug2SjOC7>3P-6D1U>e+F=8# z-1Ie}y+W^hUI@F~v(L{!Lh$%iY*>jn!IJ4DYQ3J*;4Wn1N31>ArpN-iF2<|T_z&77Y`5XUnq&LE-ZrGZi zDtHc%R`mD}cSs^)d|B@qf-3msn>8XTD%#i@KTk&hPct#WRc+s;zw>#mUv^aQ`Zi_Z z6!dqA)>C*v!jBNbn+gSr&jbTh%{{Z{9=w%aX-@-BH>8QE{S5kjfPsDyNQ3e+SVTcs zcOz5+%xxH?QJ0Sdi>@x+s`dT49PH@Rw%@BH6C*YpP8g3H^@(}f7`JTa@==4e(P_cB zeVItcaj4N+(^+wUHVXU0%}($ViS=2=--FZvyx6+;pB+5t-!XL0$;l^(>=cnKW>Nm+ zIc(?h(LLTaJJ3xt6J4P`LN$~v$hfyCUYtK>@bx+3Lm?u>>{JKMOT~4X0chO@t$Z>hko-nH#ro>YQvw5ZOya)wp442!7kc|zyx8m# zh5O2p<XPryuzWMlMaR!?qt2d1MMPZVy7OqeQ^agJ zB9zmoZiZ9WKS>Z``zR9jBj;z?`Jnr?Nfp(x+`gQ=K(W=tFVfJo9GiV38tr&PSL8mm(SVZsy zABZOa&2VI)RBCt`GjLX_WTI^8D#k(rFarh`cQFG^R52_?T-|<{tJAco>vWlPwTNDs zt~aD#It_cOY(d_pRWgsp%cJDd55`yg7>J7K7I=Cvqs`t8)GIkD>30sHO2}_w`R#Sq zLonlK6s~$j#b)#h_on;M9I~U|Rg(vEwN9b!&;+bg3eZ|fyxe)mdi3FY8+|TDPP2@A z|9gI1^l=;gWa3jt>=9_#q#=zoyOYA^%17ezqYzYkQWD&HunxE(t!{TIC%wvveN8=N zT%E{MhgMG-GUP1;c-4FN^WZt;Z{=n{6>n(!8eG-?+AdK3gMK4>dmH=z+R?AuXZ$VO zrim$rWSSsAl0&UbUdIWX^J&fazEQpAt*rz)@imv?5W|Dj*ksmN!^l;QG;53BJM@R~ zTZE#QDy?0Wgi}*lg)1{vAn6+*KA%2TF?M4T>>8$Kg30v}^@dr!VuFSIX8o@%33q6h z9S3wtlq{xLbIPp(tqco%i8%TpxDurT(FJHOX)GF6Q?ZvTPbcgx*PC@Mtn6DR-Q0X8 zVgvO|%Sv3oP05bka`hW2eT&4BQ+cH6Z{W(_c99Sq7O$;mIaPuqvz#2G5_1-=#m^WX zhhXbbwwrW+$w38YH@*_D)|_(aW=^i#XuR*h7i@|=(&VD>(c*fY#pDF$Q(3TEEmYF_ z(Hbf=*|L1F6r6)))0=kZ9}nT<$C3`F7~>dN+>B>+=lW)7!HTYARm&U{2G^e+S!MZ6 zT6Ilw=mtlp2pA6Upnvnx^r^3kpW^8(5V~N&S-u>9F?my(!K&rLud)30jJoM_a=Wg* zesPv!VABhFW55f2*zTf^0pjjTfR9amfgi`PqeNCkCB}tkA#6V6eWhux z!x5}cIum+u(+hc{Yl{UKg46W$667B6BMab=VWkWAT!k6ZEd8|hQSSSE3uCJjTu+oY zn|yh9)ZN6k@LUHC40h7DDclfO!buQ~9fYGt%Crob zm4(3g)p8tv<(q0hhF)v6hTuhu+8~JB+0|&;=Q*({+}H0%)xR_)=Hjb@7U1?a>gb~# z9^=3JxI!Kk4!f!BSd%Myxg1vKz!7I@qMh(~)dWe0Vn$Oa4PwhgAhXzXQUGTLz}T+C zn1aquxY)a{_LK`f(_>yqk8eRrp0*WE`j-66VcNlx-x+GuP6Xrc(fXE0?I3wP?%Bgz zl$}Wx&{g&gBN?sFs3?ew6z2xNS^u<0%_IT7=kJLYD~@wKI}g{rafHX3_AKAq)<{-_=)x)T5rt#(Dv`NT?Cs9j&+gZ>U!6&fqmSCFffX`h z*QKV$hYkElq76iNe-8A)7;#M_YbuitlqTo98$#k8ogCERsuwH!J5`beRoKMTDtx$W$$GSR_%G~%BJ@d;wY5?W|v79d`3q;u!#u1C!n5m%)d&ov0Q z4F)!0#gSA~h6gvt-BtvG!(8ayp2m3a3>Q{zZ9wyzTJn8Vn_iX%-Zb8V6Of40(K#8l z`G8qSs^AT&3^iAij)|4G9UWY%5%~@dJjVr+*_jyV5(!w52N0=l5EAG;eaaRa^V0Rv zCJXj*!eQNrRAj5_pNl;=<#H(%6YUn3&|Zj*4vzbG7|&c1jIZilD< z6=XSW9V^_oG)R{PnL0G^&30uA9_N1SEHZ>1^AUD`C_dQSAn}oTXduF1<1;mKm^G>t zzst`>?a)S#=aiv_;?dWzhoxL;>+7p9TM$VR@)Di=xicVliO30;AM9?y_S6N0ht{dt z#Sfgl%}r~?p2&?IeaLX^Y^LMn)T^xmo>>TaskMCfnG2~(N^?V>J@^9dBN>wO&&{Jm zPaqo1m!Js#^{xW#KLqtd&&u|H^z_^MOHc3rJT?E|$;60P3>2Sl)R8Q2{0#`i*k{3$ zYQVErvfZ=~Kv_vmwGIWL^ZIM(@g3B?uU?9DO=GG!kz(pALkDN4w3*J8-r7{1KF(JD~)aV#N?;|Q#TCn=>{ z2k7#!N}(}U`_LixaeUx^O);{sDW)Lp&|Qlbmfkqpp(EHNTCB-)>S@LOx~R4ez^4*k zSZR_(p|43Ie>KT+(ss4@8tO%`jPo*m@;FrAWwa`OT3pb0PE=$Gay@Lb_L3LiD+gO>x$>(dCe?$ePW&8l=9|`n)`V& z$FJS~{wNkzj&}SGf)X@E((>Is(SdKg(rM31uSZ-k=8jw8frrXuEswt_gwt`RIq?)X zJ=-mWY;&?7d=H?7zxIFhR6MC)|5s1+|EVW6C2@;n6t0l#RGCy!5>2NWmDDY+s%PX% z26K@c#^qB4p?K`=HBHB3I6pKRrNPvsG`fs6IZ;YYlg8*Bc?S(aN`wxCN@IP{Ygtg7 zw%WqH0&TCf=bi7j-FjQ9bF$WvH`zm;wssS*mkDmIC?Ww2o}jlZ)8Pj!8zHzCs3&+c z=PklbW9whvNYvX^{Rn(%8&RjlP1WYkBi57S^!Oq*^Um|8!+h}mYQwHC9M~q^?}}=; zm9tad1m@kYll~8UX26O-p^u+TYM(pwr^f^IfAr)aynOaYPgMV^C;b1^la27-b72FU zKmWww_|J>sVv1VK8Uw=c_A4b#jiME4{0bTPDv~mHqgUQsdCEcwl`rzfBtNnPO-{GL z5rv9Ngt!W6Xe75Y*M83DN}f-bICA5T5akU`?*a+NwPmKv4>a(n+Y;=8kQ(rJd&GjG z)DbgZtM&5-2nmJAV$DGXOkH8gy^d^qS`eM?DHTAnP=eE^5d#eV&`Ovq#j({SBia-R zhgFtaqGk-jLI1ilI+cnahAtr-^4pKJo8jQ^7(zs1K$(Y_!=;Hr-owCL;{DfJ3M{9F zluKSw`q_Nw-8*VLX^mOBTs&|lfOI|+1O7J8Jx4&UkvnleLU73SjVA+-mnAYHYRnYX5h27%7*kO$bl~Wo8cM2})2~xxT$pF3KotQyFqpmTq;$Ng^ zUamIKJZWzGcjQ2VIAASiTK4#T`U~u5RG8Y72tfvAlP-)U12`%T9JQG5unI2LHqjIZ z)MM6Qzg!;Z@Na#6h}`)* zlc7wGKetf^qj$@&{vR_>sh_MEHE!gcJBl9^S4Icp0mjXHxWrH_4z zkHsOzbO|^6`#Erx{!0d0?NOC_wGXncuEUrcNi4b4aFEllrYuCUdyniDxO=uFU#SDKIl5uLk3WR?*p&eR5yw4h>s7dp}t%qxs(LrX(PKHBz}l zN{@DhVK~pSdqlW3A#&Nzf`6#9!d7Bawu`3-LhKPo|O9k$Ts zK6@Cu2^nH4spL(L_3jJwCjl#$p3j(Vxw>4_|N6vu@p^gc`yWN(>pXk_rx^V=ceozNQ2x#8W*(-pzv%bVu8*!` zdGIX!;3S*lrH;k6^K>ie>9G(OxX=SH-c``z>8#0L7 zrp;cPM8mJ{#ew$rvNJGbTedPnh0^QQ0IX48Gt||U5KAY_@d(bQxOO2re@yfQXfeG!Vi{xg7!zGRrndtl7y?_;DQI{fWd<4YSz`4N=vj`=a@x{QpZlOy($3GT;5GCQ z@f#Q3zcEUc>61qW2moO2U!ULq>;fDtCC&8h_3YgQ>}^~ezP#Sm%JR3ChQoSmy!Ubq z--({pZx%@^9_PX zu&*%i@kcwhX>X0USLT`}ou&-ck<(%+TZJThaeX0^w-)T%?1|d_GFy^LGfw-4RxRY? zg(hLHang5BDEyDsR)sOV@?i_DqA^Xzl=Ka$3Ny#xMK;u-m5RKoiPs)nBS>ctr|0%H z^M`T?cPTAuImFT)w^RxZO$rOUGY1{l8mzF(xkafA4{c%vQ^@Iw3C!Pj(xiiNDyaj^1`g8?YY1xt# zV+_iVzxG>Ym}U>OY48#)+-xrB=yX{2w)1OD#_m6x7ZN2*jFM9%%F}-_&;CsXj-o z2SrQ~KhcV7LjB1WDR0nVX~v~7R!u}JiUa!V;>ZUL@{hjyPvF-N(iC*#F5I7h%i8CuyZ;nsX^ zS?w%?0BBuiC%y1xb%RNaWxK{;&RUSNoxG~qFI&umcsdY+v({j4`jLf6;zef;QQ<UO;QZD-_uM7~z2X z7#;glY;E?AzB3-DE}~!2uu_Usez7?X4l17t-O3MLG&e;!Y^YCuh!FGL9zrA%9!wV+ zD*vQLgDsg=@*8B`XAygx)*nTcN15g*QDJXz^t*JK^^1#`4Ba7s#>zxKft0*>u6gMc z(!gDkPZlHX)_v8UzoZlaNPGL2R3n*o8d-R%PKbcjKuhn5TS&oM z*R(*Y$S|s`k$LZz2vyXs!omEjB`HOzgUl`bXz7V4kVzZUtG+E=A+s$aaBq~b1ygHX z>O!lS;`X96+iC<`>UAux_Mr`R@}yCoH%X-Thc?B7F=%*cG@#Euo1HhaIM2f5hn;ah zc-JkAP~)t_7iVy{&OPb{=KXe~8c=RjYoe`WuHS3R_)cBy!H(@5oP37k?Z_z=+1;VB zUaNGGvu1uMIIpH=+OGIP{y<6*CYiQ&=r^jUAX|ozVq9GhG%r)p2?E&?NPU!>aI3oF zQ>cK*?AnUk9}US|D|vPUnE`#Q{SslDa!P)1D5%YzYTB%9`k;KWx>I78f^j&-Uc2kS zwMuw@=&HZfwZ{YXG=((DZw6g72MJLqQ)Mb>A0+Qqry+i4e3KH_oPu9XvrApD`r3a7 zvl_tf{+Rh7za!EUfnDC^#mDh2hHx}xM<|%+_m*3l?14StC--=>X7dp)P#jGe@F3xD zydU_LMhr_Q`_h(YmL2RQ`uC&#vCe85pP0$1USv#4b6ZD^E36oVw~)ef5je-(IH>qT zC_SMg#EiG5%hB|VH%~$L(klixDfw|^zrM4WyfR|Pg|gWn7_g1kMc?#Aib!0V`MtC> zVKO$e;!%E_=xU6=L_k1IagzG&W%U*qnAu6j^)fx{sv|KhHEyu0&Xg}3^e;h@|B8QL zF4QvE08Yj5qYsy!%axa6&<(QigX&!+Nwo*>o^h8oDmlO5emxa08QQ9k8T0UMXK{X& zai#_FRCB|A8UySEsLVxnifQUNZ*^MZDPt@!$;5i!ihw2a218m0MfyI+=^IOg)azI* z$c|khFdDsXIrZCjDl32Yr_LVx`kfT>+Hpk!cfc){)&{a@&B?B=?q=RZ0hy~Q_u9}& z)i@Uw<5-Sal>1gHDgO4ticd z2jE^9wO_@My{ZhThbz+Ys^c$f-B2sj#MuGQE@M9vu+6#~3QO$W7{Piz zr%*+aANM7oPoE}$NLOjGIr0b`(j(e=iRYN`(9A|MwyJ#Zwr~u;HotUtbyvShGl4-H z6Rd~D2nYPROzei~s_O2N5IcG3khnZaz-Sq`*P8LDL9&51=)Z#_i@LcggQIzr5JW8x zB}+ta=@bnQNc;@cEJ8ARxudH)XR&97NhIDAP_5L^#>N0Ca^vY*Ke-tMbV>bq(XTNN z&mOw1pjoAPVsXm}LrwDF9^>~gbAl(>;n4id9h}-0ux&&ksUuT;O>4S$bEB8$q5VuN zzIA^Sh>sWl6U8*d7L)A8)tkx%!aV}h2#%zNHXl~a7{>Q{*AlG={|6+yy)G!tkW*@(Bj?}mcMDT zTT3f>2+wp-S;H!vmsPfonCb<=02T=mMbBm80FIJ6(ZY9!Cb^8m(_frWvy|{uEeg_F zT7Zm`{&h+762z5&WJH<$}4JE%Pgs1#E`sPK}(HnqVt zyDk6%WBw&`?~U4Ss$2GDNsG)&0zQIUl7vBEp6}-f5vdbmhG3?yH7y|u$oW&A%fu!l4bLQqFG=M-9wCVe+@mj1nE#Wqx+DU$6O#7UDO?8>{dA|l(mUhM6 zK0c#Ni1$N*#u#xI;)bzHYL$D3?L=4w&Q<=#wDS(6{0nc?kGMmdulW@)={QpUJ> ze<#|aL#2I-=wN~vYgH01|GaG6{Z>56!wDB#4QSBR${KwwIU_AaT!pOdiK06KJ(9~fap46+eat#Tu| zx6Ei*q=m}1&+Q|)Cr`)QF@FGD3d;?6zHmDeQfA)*)tZ_?rA}bZ_=l(xmw-#D$zAnS zU1`i&CG21z@@%+sCU+711wZ&_Y9Qy)pu4Z}Nay1>1D+QsfB3+Z%x|?3%|R*Lz13h$ z7!G7D1U?hjWN?wa&1sOH&$?J4fP;8r-}5&S&*SY8GeHA6;9&A^mX_t3}{Z=0HXyZ#0D2~ zR3GUd$Z3KrhmDTlnekU_oSF07NgfQykn$E(>U+4M{(Uu=E}Om+QI!&fQkU({n6Ss|IxOwl@` zEm@K-6mvS4R;>%34bRR1i+m+p)zoZ?0$3*!pKDb>LZN~Tpd|Ghclj=e`NY4RChLKa z{aj%!uarcNa>H+Cr%)iM@Q!?NMpVP^|8#aIKuuh67{GVA7O-4_YDH3xDv*i+!4~8` z(?;ZMq_lzt5kV?al0Xm%K_Q?Bcz~j<7!R&k1hm{Of>5psh~a$>P$1uQqhUI5zuCuklqF(zo7RxB{ns_)KAuwz zYG+-ir>(vzAIl{#OK+axZ^@R)y!xb3+^i+D)s}qT1MfZ;Fhr#%Q`y?=+{7*Es)OM- zi!FYPbl)}AQphlmC!5z2D5c$*wh{7CUv%NQM>#Q~+dNhL4v~a)J}uI)GrR7~UWyF+ z?aiE^+q1rp9Ee`aW&$%g%^gb2mTtN{o@5;vtwm4ndK&F!t{JvEf*TOJUYq=ha_)$X zONgLaNY^y1X-OzuOky3l(K`S=l~d?RseYtw&t7g{Tc|s7e_iV#$6ri8FdI^JBb5Ar z2dII1^eAhU#50W&aF{6OpU%&s`?F)kwi;1@u@0HkF#NlxloyVFvx!*qfjBQy= zywX1G6uVmlInJuCiJ2ZwpV@FNhjnf@hb70<0V9lClFm~ugz4N;n7<iZ z=W^=KazjK_RrPi`$7V7bd!OZ{E8SVwM!30YV4l($jhiJVB#b(ZtUbLPe`4a?_)cq= zDDeQ(mRA6HW*WS66z8f-7z&_fho+|XG14_d)Q_Lp)q1q>NERvRj}UVEX0N6g+L?l= zLuDCv9e=BwYSyT|bZw(m%8|){hC3z|Y}%-Ex!A*6jN4H&@t(m=-e+UcHUxitdeK~} zoKvgARz>HIU&Zatg!o!H$ymFa{_t4LiDUURMJ8c+@{`Jg>QTR^@3+c-hEsa@Ik=q; zf+Sv|WxX5uj`5yRx0O3wJCeK=O#_mrE*zu{3CKAvWfnOF4XfBXJG}g(t#=-XoD>rB z_O5vpFPA$`nm-#hG-vmY!}zJ$q_Z`Qlb5)1_qx?~8Bt5wg7~_*IEf^uiYo~9ZD;Ha zn=3rnaLu`_Na*1T1*kKKl!kY!yJA#YFVE+JoRKfe51+J{d!Wa(Yj4|LwC*G^r(Zw) zYC^|tYB7t%T-jy$solM|Wlx;uhxXp^rN(E)_l}Z}S@qpNb;gX0OKqgm+Gv z@fY?V@;b+tT-JDYwaju6TG}--&@aiH)&PLOJxjYrpp2I6t9_%MJT)0ZB@iG6fiLzk z|9&e!u=Md|9`qAN5aX{rGa6X zumA711&@#*dNeI$sTB^(tPHPpF_8s;Q8fV2N0@}~q?(&|N9<-`K1BzOYb}040Pt`C z0X%}syDlreTpx=vrhmPV@%%e&*bf3a2+FNQPHM3(mIQDAUxko#)D@()RbWBza&QX- zWMc~bpMM>IUI1P!yausAh{bCQU^kAVNqEnv5rRy!d;^K>Cq|?2*24D@sHg2~=o<<{ zUwi$q(lc{}+vgzNmEM4e_ThC#rU?Iui*#Q~ks2C@7o@C5;Ea!@<5K&P&^)~EVFQ9^ zZ~jLfvvUQ#0z7+fj95Y48~WEJ5@;13cP1j#hrVx8u~PhK8y-qU{v5V#f&N2$8tuZP zgUDZ+1b^t?23*l7JbI;#K+U#7Z^$5`9eCUY`RB}S89Ifv+yYsAfR_G)sZT;HP!Sdn?^o2@6aWAK2ms4{eM>RGib+Q%004z3000&M003=e zbYWy+bYU-aXmxF3ZeeL`E^uyV<$7gMn_u{4aFkUbIkL0~9Dw+>7nYe`ogde%zU5c=JMXbLZaYoadZ#CyDx~B8P)XjtK&Ra1`XF zKLPiVmkS*gc&yT{&I4{3PVzdg!0XR17s6$9eG~{p15%KdQ1{F^%JumIp3B|qZZ6+A z&{UkiH_>SdH6J^d8tRK5L>}2X^~dIdzvkY2r7DlBGa0&sjE?a`g`4(=8G3_Gy@Go> zHU_N}n1Ga&0N2cv*zN&j23@MBv>QvdS6HlHe=I+4yC1G9Y16QQnf*xI*vqNc(`Y{F z)Nt#*xoMxW012Q6k3_y(Aft)AAR|DR5D-VCMMsmTLEZ#mgwlX%g78C;81RFg0+A*0 zaTCSS`w;$r8|3uffQ^MEqsrGzMwm+O9r=XkQ7;;`v;a772dq3^2OU05$$wzjhD~Ji z7j|{|r@6l4>hJHry>9N#br;1)@7X>Zmx$*sEPopw5n;)zEEkmX_g2djTJxI}h7A$F zm+N^C!WEx*Gh}3E5F&Ka!LtoBhD37OdotXw8VLONnd+0HP|U{}yYq|T{G5+8TKdi? zeDeW(5wiw?zY%Hrul27iM^ivr#bDb2IIY=Fv^@WR*81(-3pY~(y%~@1rXC;h>Jq+{ zUcY|7%ghf(p&MML!4pk2SI0JX2y6w(FFJXM8LqwJsWzP7>dSX$?%k+DZNa2LDUH4r zQ#7qBuIv}2pZX}AspjhQoN3|^=+!6{(1jhyfSC`QnMUa&3LJJNh)I=a;10XN3;cmk zRER7^Gt>(c_cqkvnbM&{tEitE!`@^`{F?|;@bPj&O2(?(pR)e;bW!4EJRxPwsuI}D ziRy`I9K92!a$;@~fh|upGSLY)sQRed9Mgb1KVZZ4J(;QWQI7IL$aTvJAsH|6K@yxy z^6!F3S?;GgRb+-2p3ylu zN&;_JE^%yg7>={HSi_JAoRVGlXcrZqgwrT)!YOXJ5pj3n{4H{U9=-yi|FZ*8b=M>4 z6IxB62%Hc2aJ(ZdFay+nU=l-FM!N1ru72(kipif*-2TI;wsO*o-n( z8XVW>Nna&RV+x%4-LDKDctgd@H9jPOA+62)(A)Uat z1i`sOcZ{>lG}L}@@p^cSG2x2T7&zj-Ch*m!)7AB_gE=RDXN8)FMl2OEC(RvK zO;1Qe$RvM*pJO;`%Wslm4Qla^t=0=JM{C9$4Sr_tTsq-xA9E7VrM-Pk`9l>&Aw*j; z2O{z|n8xp8rQ{7KOn1n(Mi{V}wJ$(@y(cE8SBPI9#y|wchyCWYGODV+oc3W$#ip1H zAwm;ri$Wr|N!iBn3xC$^x4i1wEP13)P;Gt3sD{@um0+x%#XmmLBo88cH_En7;iF~X zJ^F~^Xx;}D|94A&Q!{7d#Wb3U4AMR7ZA4^dELqnxi_|$0cfuMou?_(hGr9R1rq6f5 zb%o3j8K?z77TO7f(iAii$2Nt2ztQMUlyty?Qib43FHpykkNBXLbWuO4d*>R~`dxFM z>33OaDFaH>t*(d3Q8@I9gUO`N~Z28GU}>AM;;6%a_%LYjmY>IsT~iinfi6 zX-+>L*DP1I#J|fl;VhS^tuTuwZ9=R{FZ2#}>~+4gkqe}o%7$T+*WZ@hgo}bi4tvNi z5%_9$92G@l{vst%aI}gOY8S&o*cOLA#Ewdgv0k=J7}i(*Toc&I@!(|1Q`sc1` zUUsx!rh;DmD z{$-1mP)nusDxXoN1+rw^g5V%!tWOf9_Lax=jxmndMBw|dFi0`zf{;`ZgEb=5Q)M-^ zbE8tMd$E`7RRr!HDCGek)+EZ8JW%(Iods;&Sl6ykl7^FpnXzGJW@hGw@r0R~+AvL+ zu}K|Xa4#0X=Ze#i+!FQJ{Xm{=S^ zw++Pm3b)WvrudJ7t!16wI%2;Ir39^5hdg*%%3#0d;N9ejlwO8ZTj22D6MCPtZMMkm zv=_&q96XU)E>WwjY=3VG5+65g6`e#pl11Mk%lv9Wz|ZzVaN*mPmn4z4 zoV=gN;^=4GZ(ntHBsBLd(k3!V^!mnE2zIG(d!L%sOIh=<6nRj_Y@pxt#+iBLe;vjH zb&4L&j?BEe>~B18FLM>k$ZPaUChs9p^gAgU_^Xn$eF#|~V{}Wfp$Ate&@_eNKYl)I zq2-mIjD^7pr)FCf_tb->&BuIuJEHT)DzxM$(GJ*7Ukw7-7}$7sfuD%$x6H@E4)|;8 zrPHrnO9rATC;g%VEh$F4f|}f~?idO=GC@lH5xbOX-sd;LEwz*y(W+NTb)RhiK%=Rl z^2hPBpdy{gR^oJ;gFULcHjlj#@t&L!KJNemf%DQgxTaK=gXgrOUX#vUb8D78!9UC* z#B8_jJ*V$pgjge8)4YnW^@zdFWE$7gG;O01>7A*ATkLb(?)f?NW1oayJ@ z4dHP)W97g1km#A3pd)mkihg_z^7#^4-M~aHleVUe)0Sju%~`HPb|x39XxUf7-h1#5 zmoc_Fb}z1vJN<$^rFV@pl#Y9{-U$!~Y5&G0GG2MhOx1N=e|f_D{rAgWezf|l?$*sK zWIpP4kREeg0-ZEhfnZ03jYD>M@ndmmZXkuEZJ+_8j?kMqp7h1yXP;I<$k(~H<2E7` z;W}jGv?Rs5%O<>w93psi?oO#jRU%i<&turMUUar+h`em&V{f`<=KbktHVq8?H3h;OT~lBiFu_V8bLXNlF?=o_tbsk0EFY73W<;FNcZBG)rg!W zhY?gNb5gU#&pEvcB*F_;Gw2clN!Z0ySrmK+N;ImwnD)B9gr_AE1^35_svDK*-cHB# zcrmj2Slq#g><{bXX(c}<{f)S1FP0@JvaDbb%} z8V$!1^|Z?O)|l>znqTAQ(y}=x$As&a>_VZcciP_cG&rnS1T{8M=gPg{W8w=oOn<%UQWj-QL^%(s5iVGVEw?;enoj0V=8Mq@a>S!q_=( zkzp2rP)RM-%`8EW_EW9jcK7}~;lt%3F;W$P1vkPZ*-Q<|axk2wSM=m_+K?xL;;d-F zR_{WodSY2ZoutU>mGtbrg%oU=?>xodQT1bb%58A)POwS;C*PmOgxf zsk*KS^YCj7pWrSqMKqyh$&=^^8%B?mTFD+nQ#3^k7Q?{Ka$wbjZbDb!mr7B0O|^7I zgv*G|?&e=x6(nLS7A${Eu*@L{6iV+Dx-7!979$fuYm>olE%T$ZRg(5N?KKF(8Rv1v zby__3n=|xN7ZI?%(e?A>ep{m*@aITiuE55m*J{=7O@j)njPN^sqsvrzu-EiZ1j2kB z>Ut9GvA;L$e|ildVRwy-;EOSvF=38v-sXOY4u~L8_xng=9LXZ7a4U}Oq&TVv@<}bC z`0C8r)|VhrOIE?Mz^}yu^u&*lsw;hSb_}_rT_@4VZw+- zwV`Hp!RR@o&e&wq%(mCS#J1l)Rpdk=Dc&aOIPy_n!9Cf4|GpckTuWje@kE`N;dylx z79?xYYQW)h{@dcT=^5>a^iU?domP%O{Kxxhmiz_L+!>m(EjmBsCMMTR=B8oe(8J0e z+a@Am4+&(T>?YgFJvraN#Fy$d7@N%jYM~})Dno2zMS~Kh*vhXjY3Vcb?^=rSQb8Hq z!Sz;;eIAh=!KSyq4O}(0gEoj?GkPu64l`V-dxt%`W+tRiZx-v^Qy7YXf0*6dGE1oS zMj%Ho@N9QOzUL?aT5s9+|VV`g7YTT`TYCSsF(6YViJMU}h$+P{c8tER7d_Std^W#z*T!<*VhiJHk;Xqw3``+&bU}XAW1jmm+1! z?zn?8*341&4etV@g8k?_MSGWJ9eAA88&Q7|GIjo>M5Du{21yb ze#%Ktx!Cd{RQVG}0JL&*pBb#));4aJI2>AWgK$=P&b&lBemgE3&UcsEoG08`^$9aYf>$WI{1ZMBw*{!lZzT zMn4vzZh}W6``ysTQ>!S~;tpw3dKbdoT_(C3c1+FQu@VpOVd1FXVxb{APHET{CyJD*c57EX>}>X*m8c5R@fm}-t-LWw?2MkmTljRhS2@UJYbPnn z&*8Oec48QSE4QpnoCugU1#dj#g4mIUTIDAzDxeqkrE#h_n||tenvcryTN=p1WkhdG zHAhK=+?JdLe3|)gsCw5~8}7q&b-!)fiph2ahrn&uW#U})VP4ubL^NNJJ;X)U*IeI| zku)rYuSS@Sji1KS$2`aI^k&#)bW#IP_tNnpP`vh#+tFz^dbVU)iW%W6OFGJ3&X7^Z zj7S!C@L4IfqKracAB8#_86mITmOZmh`{BR@R%ghgiaIKx1$$>EGQ<^hgaLLV7)K$5JOM&(boM`Pf^m5jB-q#48)*Y z>x;LK+G!T(NF43nzqhXe8gh}4PNKT0nB6vOEL1H|9_2>B68vOdGc_~W9yXj{!Xs*UMA-G~2Wqp~EYyQ?b@W67w z|D?F5$-bp5?}GMTmusf`Q2;?O?K^c8*sEAcsuisPwc`YL%3QsHa^X#0IZmAr%Z|bQ zWL+~ikt)Wk_VfBTRTDD%K61G!C{Il{1l7bj+vj1b(?8tT$p-~N{ys*p@`#W@5dsvR zI5}1K>hJI=s<1|OE(KIOPj7^s;ltl)&Z#V1L9%@U6`-~ufB)7W&~>-FGVDAX19Yr- zcx^?05G|fZX|F-m++k3oD$;;nQM_em$`9R3C2t0V27P|7`C9V6E7T{!_(BU*wqLbx zUG&&#Dl$7(`y@UcY|g)FQk|%D_5V`qBx*RG)66$X^M4m{y`JnEo#i-NRG+o3L6cQ1 z!XFXWu1B3J&^J{(4sr57c&UYaFe;jWCkFb$WX^N?txx%L?w-Y(-MWAIChAJQ6yd*Z zcsz1YfZR3l%)j7`(HTy!18rEt1MyR}2nOP4Lu;E;p1=L1cy6m%$Rjclvs_$Mc3G@bIH~Ul$L6Hq)!Ca!Pg}cQFzfb5jqlj#-$xHrcqTc zKOI|VcZW4kHzOl&;$v4UGYS?Mx_zY2@bJ1ow?YO+#`l(H?3MQOXm(D{hl4}QYN`#U zbpO5wEJsIOJWmz~ddH{{E!?&M+PMK!DN1KZ zLX*`;ha+@S;bMv5w3VcW6DplYK%(nr_>f&kZ*t1Jm-jh4J9)KJ6oUS52$`8`X;~Sp zo-gj=GBPv@!HjnHQCwZDtc9Q(~sv^i?{47Z_?Bf{Kp{0eB1_kdHF4Gsep3 zi$YN0&jzuAQG{a6Zi8;TiKHWlbqQ z{01lV#|rlHrVx3S&!pt6YX52!HlTw#Faqx0ENf%z#gi_=;+J$gwYPU@L_-9mLyb{t zWKL7NgJIPP<0F2lC?I!L*7Ds5US4OE(NC55BQjFN0Q)~+~-Sql7? zHXC6nvD?bDcRvP=8?)J%n?uPr24?~_Dh?(Hiy>;#Jh`k_zm=fxqO1c0=OIZ2WF>i1 zC{=_WgsA#LxYbMHAzv~N1*AJ2*Hp~(l?mm4FJHke2OjjTRCmBuZ#0#yd+K=`#<)~a z9d)Jvl;D*VmS*sd@P#?Y_tmlJT%&ukv%BkD0hAoZ)G$^G8_`OQv#IN$B}{49sO{Mk z?7qP1fMD`0l2OM73Tb9fKu?*uQ4~U}m(xx<(>kL_vV#OvYs-x*|L4@-tqE|Yc`^}} z&~X>bTviJ5y?7ltRDJRNNFJ;LC|kikVaT`sH=a3M$5whLy8$S|*4EaAz~8c(=YbOw z6JT5cB6vf7wDjUcvIo0O#EKEo7>eeWKx-CXuV%b&`toKAG#{^@l_#L9u?@mjz{zEp z!rIZj4A<0XugKtQqgEyL_2shakJ8c%b7jErRGI9rGz5 zX!JA;P!fd zF#^M7Oj2f^06iWtJ58e_qv42))9K0dOk;%K!+Neo(iwnl>B8jnS?}IE^tz?kx>ij~ zL#xfy3gSz0>^!Y**mVR~h?JX`j`&er_4W6kj}x}YW{I1t%+hicFjNNyg2Cghbq~X| zimnMHZWz<|4s6alGzhoNQR{8rU#)%!Vmi@+e*UxrHs$9VXI*5$a}W~pE5&{L#%%js z)X>1?)z9Py- z07|KdcnMU`wvBJZ81#HXR>)tS5{MTs69WhegPOi?(3o=>j(`aO;6Q9IIIV`eHXifb z1$~u-1|1Hg(-R2!dTKZAc&#+hbP?T6?tXUyK|)JaE7F zKSM3PdfUemM(M)Dp-?R^EF=e5h~uMcWmpOjP9p%sGgp@?Dk_LEH6x0Tp{(|c z_Bb9yjE(2bj#H_qsIKLx12VxwOiWEb5q|9#P5tpWEFr1Sk6tS8%g@PSm$HmU<6^30 zdY+zR`4-XfK_M1O;zRLs3=3? zzSDL?(Cw)W=KYOnCx#|THWwm2A`#7gE;1=1LaJ>Oq3_+#tN`G^M^7eb&>eS}FpY!$ z6mT^cpdrWysr1YyL6`h95qz5VC6?N%6 z`lTLEv#TH5Ks@02HeiZkgz;w>Ci*mUA=NGIJ8`y8EcPexT0kYZa5zaxMW$W?sw%!h z6%2*}Zia$`3mfGxXqa3iA_2e)pz+b!jibI?w!YfK$a}G%vbY@|<(qy{Pk7zQmKQF8|2KM_3^xxX%(H9L*7Y z;HikIPG*{ys$i?A>U!fYC$vvrb#V0)_~ehn?UR$2YxKHV8P(Dl;z){e525FWt$1U$ z=11Z9!DDqWBPfZ`F-j~f;?crHcX5IOx4u&R2!(`gqQySZTsNEx%meQ11OJ+6}()F4_@0|7f@e=zcY;SAN+S0f=I z5h9gOkc2YDU%oXCrpPugazlp0WUlU&UkLE8Dqs7&37!F1CHyQ_iIu0W)Qyae9s;=J zmCu%k%jz!BE{A~E3d0xG&JP~25@NBAl##O*Isib4N=8`Ka;8125Zc?@gC=~lwmNu` zbsU8mdyp2&N|P z;$#NYvz_*IxvyK)Bj9f|EmgbBI@FtHYYuNL@wW2-Y{i>gzMCj5gSQGTx^E`7l~NjR z21t`50Yc&M*e5L;+ADx_V`Jq<+;Nx|f*}0Q%w?Tk-H*1{Hr5a5CsQQ~G;WqBJo$%uoT9&FKcGO;UF^kdtf2@Aa1I6YsrIV4 z)aNT~vGxU$tCYd_MI~@7Y=DEcKaB>JX&2!YE9aGskD_D-vIq0Avi5aM(AGjjr3Zv( zY8&G(tO}sS4RG>Y2@x$WIQqWdnimRS4r69#g?ZrwoJ&YbUR)H-Xqk4xtI#Cm%3wpW z@uL5d7)yr`+Ir8*sM~|Q-@Gv}PSvomPEk%sl!XiE3vWWnT^3pcvqr?1@=zHFVimw* zrSyW^p+pc3y`SW}LJN~s+4=;J9S!q~vJS#iSlu$!Wt=ruf=%VfmQ)BJD?_6xLxFj`5xerI&St_KNT*0GOB#&mQk2_`{xpBBgc>Azqek zldtTfCLBxUm~=@(AD;!xpveCV~p;bF3J`1 z!N-caMR}Xoz``dwQ}BGpWk2}a)=6wXtn(Io*^qd<&jqb=`q1G z7Eb(2QdmN~RcDq9(1Wfl6EkOO{~Yt;=YP>aAURQBhiqHg3m1dyarYP>|4Bak!= z>0e5Xg%zD$RZVT43Iu6h^lz)wSI=TleUrD=Kc#D*e=g@$N?>k0R3(RJg)QB1yOASw zZXxTy6Hk^xhxeV_>0q9{MOSjcrA|pS*$!x-YhfkhfN(SYS$@2Dc>zV2aa_|t{5I0T za{bb6g=(zC?j*Sqv`DEmh{>9M^YI9)_}H@$UfJI-^(gEz(jl7?Nyqzva#&FcX93(_nq^Q-qYMI~72=+NKYhU z>(JsOO5GoO@jfE;XZzUvPy4TA&&1xzOv%aK!OY3U%FOxCnEe~%nBNW@{4kUJuqODA z`Cp*ikM6%9TlfDrD*AV_UFrv7_GA6f5B_ia3zhfb<^L5W?%`r)=WJzf_iy+96eEV8 zxw-~h000S+5CEKiFnuBZmLLDljDL^P8$EEg4GI7tW&2Ch_$TQv*EntdhH-W=axpUp z+PnYTmC+AZP8_3lm_LltJ`Rlb4_7Fi003Q4d%KTuxO`RfbTD()|2N>zu~a4UWRZLT z;ywWI{{Tcd0|0-e`2VK#-@TvuFs!F&ceVWv4OmTq{_h<9Wk2ikx4=3B<*baIjGR10 zob275&72sV9Gw4-`ag*~|Kr9-=k+1~{O=t7L+bf&#=p Date: Fri, 1 Dec 2017 07:56:34 +0000 Subject: [PATCH 75/92] [Squash] Update lib --- .../library/WBToolboxLibrary_repository.mdl | 578 +++++++++--------- .../library/exported/WBToolboxLibrary.slx | Bin 535297 -> 534789 bytes 2 files changed, 289 insertions(+), 289 deletions(-) diff --git a/toolbox/matlab/library/WBToolboxLibrary_repository.mdl b/toolbox/matlab/library/WBToolboxLibrary_repository.mdl index 8e4a391ca..0ae80c40b 100644 --- a/toolbox/matlab/library/WBToolboxLibrary_repository.mdl +++ b/toolbox/matlab/library/WBToolboxLibrary_repository.mdl @@ -25,7 +25,7 @@ Library { $ObjectID 2 $ClassName "Simulink.WindowInfo" IsActive [1] - Location [2245.0, 90.0, 1595.0, 866.0] + Location [2086.0, 89.0, 1595.0, 866.0] Object { $PropName "ModelBrowserInfo" $ObjectID 3 @@ -57,11 +57,11 @@ Library { Object { $ObjectID 6 IsActive [1] - ViewObjType "SimulinkTopLevel" - LoadSaveID "0" - Extents [1557.0, 693.0] - ZoomFactor [3.428251121076233] - Offset [11.916285153695213, 10.428057553956833] + ViewObjType "SimulinkSubsys" + LoadSaveID "192" + Extents [1557.0, 726.0] + ZoomFactor [2.13] + Offset [0.0, 0.0] } PropName "EditorsInfo" } @@ -83,7 +83,7 @@ Library { "AAAAAAA+wAAABYARABvAGMAawBXAGkAZABnAGUAdAA0AAAAAAD/////AAAAAAAAAAD7AAAAUgBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0Ac" "ABvAG4AZQBuAHQALwBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0AcABvAG4AZQBuAHQAAAAANQAAAooAAABbAP///wAAAAEAAAAAAAAAAPwCA" "AAAAfsAAABUAEcATABVAEUAMgA6AFAAcgBvAHAAZQByAHQAeQBJAG4AcwBwAGUAYwB0AG8AcgAvAFAAcgBvAHAAZQByAHQAeQAgAEkAbgBzAHAAZ" - "QBjAHQAbwByAAAAAAD/////AAAAKwD///8AAAY7AAAC9gAAAAEAAAACAAAAAQAAAAL8AAAAAQAAAAIAAAAP/////wAAAAAA/////wAAAAAAAAAA/" + "QBjAHQAbwByAAAAAAD/////AAAAKwD///8AAAY7AAADFwAAAAEAAAACAAAAAQAAAAL8AAAAAQAAAAIAAAAP/////wAAAAAA/////wAAAAAAAAAA/" "////wEAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" "////wEAAAB6/////wAAAAAAAAAA/////wEAAADe/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wEAAAEt/////wAAAAAAAAAA/" @@ -97,9 +97,9 @@ Library { ModifiedByFormat "%" LastModifiedBy "dferigo" ModifiedDateFormat "%" - LastModifiedDate "Wed Nov 29 15:45:34 2017" - RTWModifiedTimeStamp 433871066 - ModelVersionFormat "1.%" + LastModifiedDate "Thu Nov 30 14:54:35 2017" + RTWModifiedTimeStamp 433954470 + ModelVersionFormat "1.%" ConfigurationManager "none" SampleTimeColors off SampleTimeAnnotations off @@ -1065,8 +1065,8 @@ Library { } System { Name "WBToolboxLibrary_repository" - Location [2245, 90, 3840, 956] - Open on + Location [2086, 89, 3681, 955] + Open off PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -1100,8 +1100,8 @@ Library { } System { Name "Utilities" - Location [2245, 90, 3840, 956] - Open off + Location [2086, 89, 3681, 955] + Open on PortBlocksUseCompactNotation off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -1114,6 +1114,247 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "213" + Block { + BlockType SubSystem + Name "Configuration" + SID "1774" + Ports [] + Position [435, 260, 510, 290] + ZOrder 95 + InitFcn "source = get_param(gcb,'ConfigSource');\n\nif strcmp(source, 'Workspace')\n object = get_param(gcb,'" + "ConfigObject');\n WBToolbox.WBToolboxConfig2Mask(gcb, object);\nend\n\nWBToolbox.Mask2WBToolboxConfig(gcb);\n\nc" + "lear object source" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 22 + $ClassName "Simulink.Mask" + SelfModifiable "on" + Display "disp('Config')" + RunInitForIconRedraw "off" + Array { + Type "Simulink.MaskParameter" + Dimension 8 + Object { + $ObjectID 23 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Workspace" + Cell "Mask" + PropName "TypeOptions" + } + Name "ConfigSource" + Prompt "Configuration from" + Value "Mask" + Callback "% Get the Workspace/Mask menu\nh = Simulink.Mask.get(gcb);\ncurrentConfigSource = get_param(gcb,'ConfigSo" + "urce');\n\nif strcmp(currentConfigSource,'Workspace')\n % Switch the visibility of the GUI elements\n set_para" + "m(gcb,'MaskVisibilities',{'on';'on';'on';'on';'on';'on';'on';'on';});\n h.Parameters(3).ReadOnly = 'on';\n h.P" + "arameters(4).ReadOnly = 'on';\n h.Parameters(5).ReadOnly = 'on';\n h.Parameters(6).ReadOnly = 'on';\n h.Par" + "ameters(7).ReadOnly = 'on';\n h.Parameters(8).ReadOnly = 'on';\n \n % Parse the object inserted in the Conf" + "igObject field\n currentConfigObject = get_param(gcb,'ConfigObject');\n WBToolbox.WBToolboxConfig2Mask(gcb,cur" + "rentConfigObject);\n clear currentConfigObject;\nelseif strcmp(currentConfigSource,'Mask')\n % Switch the visi" + "bility of the GUI elements\n set_param(gcb,'MaskVisibilities',{'on';'off';'on';'on';'on';'on';'on';'on';});\n " + "h.Parameters(3).ReadOnly = 'off';\n h.Parameters(4).ReadOnly = 'off';\n h.Parameters(5).ReadOnly = 'off';\n " + " h.Parameters(6).ReadOnly = 'off';\n h.Parameters(7).ReadOnly = 'off';\n h.Parameters(8).ReadOnly = 'off';\n " + " h.Parameters(3).Enabled = 'on';\n h.Parameters(4).Enabled = 'on';\n h.Parameters(5).Enabled = 'on';\n h.P" + "arameters(6).Enabled = 'on';\n h.Parameters(7).Enabled = 'on';\n h.Parameters(8).Enabled = 'on';\nend\n\nclear" + " h currentConfigSource" + } + Object { + $ObjectID 24 + Type "edit" + Name "ConfigObject" + Prompt "Name of the object" + Value "'WBTConfigRobot'" + Tunable "off" + Visible "off" + Callback "% This code get called whatsoever\nif strcmp(char(get_param(gcb,'ConfigSource')),'Mask')\n return\nend" + "\n\n% Parse the object inserted in the ConfigObject field\ncurrentConfigObject = get_param(gcb,'ConfigObject');\nWBT" + "oolbox.WBToolboxConfig2Mask(gcb,currentConfigObject);\n\nclear currentConfigObject;" + } + Object { + $ObjectID 25 + Type "edit" + Name "RobotName" + Prompt "Robot Name" + Value "'icub'" + } + Object { + $ObjectID 26 + Type "edit" + Name "UrdfFile" + Prompt "Urdf File" + Value "'model.urdf'" + } + Object { + $ObjectID 27 + Type "edit" + Name "ControlledJoints" + Prompt "Controlled Joints" + Value "{'l_elbow','l_shoulder_pitch','torso_roll'}" + } + Object { + $ObjectID 28 + Type "edit" + Name "ControlBoardsNames" + Prompt "Control Boards Names" + Value "{'left_arm','right_arm','torso'}" + } + Object { + $ObjectID 29 + Type "edit" + Name "LocalName" + Prompt "Local Name" + Value "'WBT'" + } + Object { + $ObjectID 30 + Type "edit" + Name "GravityVector" + Prompt "Gravity Vector" + Value "[0,0,-9.81]" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 31 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 32 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 33 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 34 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 35 + Prompt "From" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 2 + Object { + $ObjectID 36 + $ClassName "Simulink.dialog.parameter.Popup" + Name "ConfigSource" + } + Object { + $ObjectID 37 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "ConfigObject" + } + PropName "DialogControls" + } + Name "TabFrom" + } + Object { + $ObjectID 38 + Prompt "Data" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 6 + Object { + $ObjectID 39 + PromptLocation "left" + Name "RobotName" + } + Object { + $ObjectID 40 + PromptLocation "left" + Name "UrdfFile" + } + Object { + $ObjectID 41 + PromptLocation "left" + Name "ControlledJoints" + } + Object { + $ObjectID 42 + PromptLocation "left" + Name "ControlBoardsNames" + } + Object { + $ObjectID 43 + PromptLocation "left" + Name "LocalName" + } + Object { + $ObjectID 44 + PromptLocation "left" + Name "GravityVector" + } + PropName "DialogControls" + } + Name "TabData" + } + PropName "DialogControls" + } + Name "TabContainer" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Configuration" + Location [550, 86, 1677, 725] + Open off + PortBlocksUseCompactNotation off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "600" + SIDHighWatermark "70" + Block { + BlockType Constant + Name "ImConfig" + SID "1774:67" + Position [20, 20, 50, 50] + ZOrder 81 + Value "0" + } + Block { + BlockType Terminator + Name "Terminator" + SID "1774:68" + Position [95, 25, 115, 45] + ZOrder 80 + } + Line { + ZOrder 1 + SrcBlock "ImConfig" + SrcPort 1 + DstBlock "Terminator" + DstPort 1 + } + } + } Block { BlockType SubSystem Name "DampPinv" @@ -1126,11 +1367,11 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 22 + $ObjectID 45 $ClassName "Simulink.Mask" Object { $PropName "Parameters" - $ObjectID 23 + $ObjectID 46 $ClassName "Simulink.MaskParameter" Type "edit" Name "tol" @@ -1346,7 +1587,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 24 + $ObjectID 47 $ClassName "Simulink.Mask" Type "DoFs converter" Description "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on" @@ -1363,7 +1604,7 @@ Library { RunInitForIconRedraw "off" Object { $PropName "Parameters" - $ObjectID 25 + $ObjectID 48 $ClassName "Simulink.MaskParameter" Type "popup" Array { @@ -1381,11 +1622,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 26 + $ObjectID 49 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 27 + $ObjectID 50 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1393,22 +1634,22 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 28 + $ObjectID 51 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 29 + $ObjectID 52 $ClassName "Simulink.dialog.parameter.Popup" Name "yarp2WBIOption" } Object { - $ObjectID 30 + $ObjectID 53 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 31 + $ObjectID 54 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -1442,7 +1683,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 32 + $ObjectID 55 $ClassName "Simulink.Mask" Type "Minimum Jerk Trajectory Generator" Description "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk " @@ -1465,7 +1706,7 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 33 + $ObjectID 56 Type "checkbox" Name "externalSettlingTime" Prompt "External Settling Time" @@ -1476,42 +1717,42 @@ Library { "SettlingTime" } Object { - $ObjectID 34 + $ObjectID 57 Type "edit" Name "settlingTime" Prompt "Settling Time" Value "3" } Object { - $ObjectID 35 + $ObjectID 58 Type "edit" Name "sampleTime" Prompt "Sample Time" Value "0.01" } Object { - $ObjectID 36 + $ObjectID 59 Type "checkbox" Name "resetOnSettlingTime" Prompt "Reset on Settling Time Changes" Value "off" } Object { - $ObjectID 37 + $ObjectID 60 Type "checkbox" Name "firstDerivatives" Prompt "Output First Derivative" Value "on" } Object { - $ObjectID 38 + $ObjectID 61 Type "checkbox" Name "secondDerivatives" Prompt "Output Second Derivative" Value "on" } Object { - $ObjectID 39 + $ObjectID 62 Type "checkbox" Name "explicitInitialValue" Prompt "Explicit Initial Value" @@ -1524,11 +1765,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 40 + $ObjectID 63 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 41 + $ObjectID 64 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1536,38 +1777,38 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 42 + $ObjectID 65 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 43 + $ObjectID 66 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 44 + $ObjectID 67 Prompt "Trajectory Parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 4 Object { - $ObjectID 45 + $ObjectID 68 $ClassName "Simulink.dialog.parameter.CheckBox" Name "externalSettlingTime" } Object { - $ObjectID 46 + $ObjectID 69 $ClassName "Simulink.dialog.parameter.Edit" Name "settlingTime" } Object { - $ObjectID 47 + $ObjectID 70 $ClassName "Simulink.dialog.parameter.Edit" Name "sampleTime" } Object { - $ObjectID 48 + $ObjectID 71 $ClassName "Simulink.dialog.parameter.CheckBox" Name "resetOnSettlingTime" } @@ -1576,21 +1817,21 @@ Library { Name "Tab1" } Object { - $ObjectID 49 + $ObjectID 72 Prompt "Input/Output" Array { Type "Simulink.dialog.parameter.CheckBox" Dimension 3 Object { - $ObjectID 50 + $ObjectID 73 Name "firstDerivatives" } Object { - $ObjectID 51 + $ObjectID 74 Name "secondDerivatives" } Object { - $ObjectID 52 + $ObjectID 75 Name "explicitInitialValue" } PropName "DialogControls" @@ -1624,7 +1865,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 53 + $ObjectID 76 $ClassName "Simulink.Mask" Type "Real Time Synchronizer" Description "This block slows down the simulation trying to match the period specified \nas parameter (in se" @@ -1632,7 +1873,7 @@ Library { Display "disp('Real Time Synchronizer')" Object { $PropName "Parameters" - $ObjectID 54 + $ObjectID 77 $ClassName "Simulink.MaskParameter" Type "edit" Name "period" @@ -1641,247 +1882,6 @@ Library { } } } - Block { - BlockType SubSystem - Name "Robot" - SID "1774" - Ports [] - Position [435, 260, 510, 290] - ZOrder 95 - InitFcn "source = get_param(gcb,'ConfigSource');\n\nif strcmp(source, 'Workspace')\n object = get_param(gcb,'" - "ConfigObject');\n WBToolbox.WBToolboxConfig2Mask(gcb, object);\nend\n\nWBToolbox.Mask2WBToolboxConfig(gcb);\n\nc" - "lear object source" - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 55 - $ClassName "Simulink.Mask" - SelfModifiable "on" - Display "disp('Config')" - RunInitForIconRedraw "off" - Array { - Type "Simulink.MaskParameter" - Dimension 8 - Object { - $ObjectID 56 - Type "popup" - Array { - Type "Cell" - Dimension 2 - Cell "Workspace" - Cell "Mask" - PropName "TypeOptions" - } - Name "ConfigSource" - Prompt "Configuration from" - Value "Mask" - Callback "% Get the Workspace/Mask menu\nh = Simulink.Mask.get(gcb);\ncurrentConfigSource = get_param(gcb,'ConfigSo" - "urce');\n\nif strcmp(currentConfigSource,'Workspace')\n % Switch the visibility of the GUI elements\n set_para" - "m(gcb,'MaskVisibilities',{'on';'on';'on';'on';'on';'on';'on';'on';});\n h.Parameters(3).ReadOnly = 'on';\n h.P" - "arameters(4).ReadOnly = 'on';\n h.Parameters(5).ReadOnly = 'on';\n h.Parameters(6).ReadOnly = 'on';\n h.Par" - "ameters(7).ReadOnly = 'on';\n h.Parameters(8).ReadOnly = 'on';\n \n % Parse the object inserted in the Conf" - "igObject field\n currentConfigObject = get_param(gcb,'ConfigObject');\n WBToolbox.WBTConfig2Mask(gcb,currentCo" - "nfigObject);\n clear currentConfigObject;\nelseif strcmp(currentConfigSource,'Mask')\n % Switch the visibility" - " of the GUI elements\n set_param(gcb,'MaskVisibilities',{'on';'off';'on';'on';'on';'on';'on';'on';});\n h.Para" - "meters(3).ReadOnly = 'off';\n h.Parameters(4).ReadOnly = 'off';\n h.Parameters(5).ReadOnly = 'off';\n h.Par" - "ameters(6).ReadOnly = 'off';\n h.Parameters(7).ReadOnly = 'off';\n h.Parameters(8).ReadOnly = 'off';\n h.Pa" - "rameters(3).Enabled = 'on';\n h.Parameters(4).Enabled = 'on';\n h.Parameters(5).Enabled = 'on';\n h.Paramet" - "ers(6).Enabled = 'on';\n h.Parameters(7).Enabled = 'on';\n h.Parameters(8).Enabled = 'on';\nend\n\nclear h cur" - "rentConfigSource" - } - Object { - $ObjectID 57 - Type "edit" - Name "ConfigObject" - Prompt "Name of the object" - Value "'WBTConfigRobot'" - Tunable "off" - Visible "off" - Callback "% This code get called whatsoever\nif strcmp(char(get_param(gcb,'ConfigSource')),'Mask')\n return\nend" - "\n\n% Parse the object inserted in the ConfigObject field\ncurrentConfigObject = get_param(gcb,'ConfigObject');\nWBT" - "oolbox.WBTConfig2Mask(gcb,currentConfigObject);\n\nclear currentConfigObject;" - } - Object { - $ObjectID 58 - Type "edit" - Name "RobotName" - Prompt "Robot Name" - Value "'icub'" - } - Object { - $ObjectID 59 - Type "edit" - Name "UrdfFile" - Prompt "Urdf File" - Value "'model.urdf'" - } - Object { - $ObjectID 60 - Type "edit" - Name "ControlledJoints" - Prompt "Controlled Joints" - Value "{'l_elbow','l_shoulder_pitch','torso_roll'}" - } - Object { - $ObjectID 61 - Type "edit" - Name "ControlBoardsNames" - Prompt "Control Boards Names" - Value "{'left_arm','right_arm','torso'}" - } - Object { - $ObjectID 62 - Type "edit" - Name "LocalName" - Prompt "Local Name" - Value "'WBT'" - } - Object { - $ObjectID 63 - Type "edit" - Name "GravityVector" - Prompt "Gravity Vector" - Value "[0,0,-9.81]" - } - PropName "Parameters" - } - Array { - Type "Simulink.dialog.Group" - Dimension 2 - Object { - $ObjectID 64 - Prompt "%" - Object { - $PropName "DialogControls" - $ObjectID 65 - $ClassName "Simulink.dialog.Text" - Prompt "%" - Name "DescTextVar" - } - Name "DescGroupVar" - } - Object { - $ObjectID 66 - Prompt "Simulink:studio:ToolBarParametersMenu" - Object { - $PropName "DialogControls" - $ObjectID 67 - $ClassName "Simulink.dialog.TabContainer" - Array { - Type "Simulink.dialog.Tab" - Dimension 2 - Object { - $ObjectID 68 - Prompt "From" - Array { - Type "Simulink.dialog.parameter.Control" - Dimension 2 - Object { - $ObjectID 69 - $ClassName "Simulink.dialog.parameter.Popup" - Name "ConfigSource" - } - Object { - $ObjectID 70 - $ClassName "Simulink.dialog.parameter.Edit" - PromptLocation "left" - Name "ConfigObject" - } - PropName "DialogControls" - } - Name "TabFrom" - } - Object { - $ObjectID 71 - Prompt "Data" - Array { - Type "Simulink.dialog.parameter.Edit" - Dimension 6 - Object { - $ObjectID 72 - PromptLocation "left" - Name "RobotName" - } - Object { - $ObjectID 73 - PromptLocation "left" - Name "UrdfFile" - } - Object { - $ObjectID 74 - PromptLocation "left" - Name "ControlledJoints" - } - Object { - $ObjectID 75 - PromptLocation "left" - Name "ControlBoardsNames" - } - Object { - $ObjectID 76 - PromptLocation "left" - Name "LocalName" - } - Object { - $ObjectID 77 - PromptLocation "left" - Name "GravityVector" - } - PropName "DialogControls" - } - Name "TabData" - } - PropName "DialogControls" - } - Name "TabContainer" - } - Name "ParameterGroupVar" - } - PropName "DialogControls" - } - } - System { - Name "Robot" - Location [550, 86, 1677, 725] - Open off - PortBlocksUseCompactNotation off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "600" - SIDHighWatermark "70" - Block { - BlockType Constant - Name "ImConfig" - SID "1774:67" - Position [20, 20, 50, 50] - ZOrder 81 - Value "0" - } - Block { - BlockType Terminator - Name "Terminator" - SID "1774:68" - Position [95, 25, 115, 45] - ZOrder 80 - } - Line { - ZOrder 1 - SrcBlock "ImConfig" - SrcPort 1 - DstBlock "Terminator" - DstPort 1 - } - } - } Block { BlockType S-Function Name "Simulator Synchronizer" @@ -3098,7 +3098,7 @@ Library { } System { Name "Dynamics" - Location [2245, 90, 3840, 956] + Location [2086, 89, 3681, 955] Open on PortBlocksUseCompactNotation off ModelBrowserVisibility off diff --git a/toolbox/matlab/library/exported/WBToolboxLibrary.slx b/toolbox/matlab/library/exported/WBToolboxLibrary.slx index fbd2f293d35231ab7ea5dedd07e4f4cf08ac03aa..d2f615da634fff6b1190c48dde0c38cbd266a766 100644 GIT binary patch delta 62516 zcmV)4K+3;?)*yw_AQDhZ0|XQR000O8=stl<5d>?*krF9?T~EUx6#Xj=?=8@MDe1aI z&7QWzXpP1^g*I)vk{iQK zo8WUWITmNafXDK{mtcqJC+2l@|Bx+F8WTDWNgR@YX+~leQ#QJNPw>V2&hT*7CjHQ6 z$2W4*sRppiRC4Rq{&%+$^1C+8w_s$U`(zi?kgqyo{|B6f)CZ&)nX$=)#pEpD$)FEl zU@yB}OKCKoP5QzE)bYnvOrN@@H$8uX4)go7bmG6=stmyt^(N-=01T-5@c>=Xk`EZdq)ER8330tDF_>X?Y(Pv+qSYW{N2BT z%V(!6+1pV>-Q}b{%h$$z;@Gd{H1FBneX?i~lG#wCN>aYGtLL{rGXQu8NRW~pB~e%F z+7bqr!C)|$>zn_+pV`_i@qEj5e%#g@&25c1W7o8t>5tosVDfUX{oi|AZ_Zqk*r(3K z^=3u@O|@T=AbVSXn)c?Mb?q761O5(wU1;x(8ToO0WZV+-@W$|raX`Fd-u3q0htbRZ z(c$Uon^zYZ2;R@t!<=mI9oX*pGyg=;lz!=a_OD#tW_!+iW)TZO;K2o@J6ejHu@$%QvoVvTxh8y$`J>lYFy(lZ&g%g@eCu@4+vco^Nty z+@Br2JF#p6DhO{C?AK%Yy*CXD6k;8L;M~vqzL^U+)Wi#COJmVobLDLFc zkJC0XndDUHckHVpIP(r?asOE z2r``0hq-A4-|OG{xA(* z7l9l>_sT$*S06(-6fZ`BF`IAib=sY#-tD)Vl5vR51+Q=%y%CLc>Wn=COe@&!^t-8H z-@Gb7*c-<6q*xrm#B73dJamCkXG9!f!+pnb1A2+eTXTU8#WxV5=C%PlWHM>W6t#zc z`;SUS1>@hici1B0+{H~VTrYqfGw_fWw>%=gHFYixXIeJ8>(2di=h*Y${3PYYBtMxt zaN8YNrsV-W!z>NEd|4ydAlNy2xC$Fy5kI(a;r2cqv-Jz-K)Zw`8TKXdU3-DkCC z29i)=Ge9XZ&pnfP(petglQA6-NHQRQ_jIDATWWaLpOl``lqH?(nc;n2%w;X;qXK`W z+i%UK!_$Tr@OGII5RQDM=0GfC&zj>DM}Y??stoGNb?pN~N-w||f`wnufQzUMRneJ} zlL>DRwEFpj13PtQ_}SKPUWs_Z8+vz9DFj8xQ9gbN|K-4i=LMpuqYQhSY_;Gi-SZMCaYo>s#0^9QB>y2O*4~ zmevw1EJ2xP{uGz%5aD7ycVgjvDA^NAV;^1bvp+Y+WaKWqF*H8gzk0WS5Ph839@$R3 zf!hJD6!w71UpZv#dgh@EHy<#66X|520ZJb1wK{fh;np-H?am00_&A&cFz`D`L;NMW zpQr*rKKR>U27GA_yo5CrQa!YTD{xHcnY$$Bg7Q+3LJ9zm9lTu*7Yui|q@XDxAZ~c& zMw{@9{2+3$5zN|F2Z={vYc9eJYjN(-vs2I~6%;PXge`b`?_Am=3XC3q+ylpF@506f zRB)Gqp7GM& z2^Arn%Y2$3&G`N|U80b+kDx$Y49E*w;G^iEfmQ34^8e zV)?1f<{%L{C36~oW_2&Qc?}ikHF9kbZVnGK9j3+U=u&9pb#SSc;oYE@v$3y_= zU@d%&=-v{{LzMqq`rh>%HM=2dX1_cxM1yL$FZ=D~$w*BLK7;6Fk1F3<8c z(Pnd)tNhbZIxA>ql1?GXv4-s3q1gCmW9(jAh64|g8`ngYf~Rs4M>octTmX545J@7a z*qB#%Fo@@W9(u0tM{ppMqS49@Ik*z^zCCr}+P#6R{JrZKrZGo)C}cDCl)(Gm8l##i zMCz5d@PkV-wNm$_1Y4J|;DDiOd+!8ZxJ4k$Ms*8lvT&jgLbXnQl2oPvyatzWD_?nr zb6|fiCy|7X(edG6TPSgUaK_YIDFdnvL>mYk^Hbbnoa* z#ft|er_=MIi|2@ptyw4@moPReubevb1t8(qU`JczHTJ1%#lf2b(9Mp{J^euGb^#b@ z&;KlfcxTNlsx76;#jNfv*BqE!vT+$NM`K53*(C&n5b0HvQrInt5v9}|r5Bq79L$Fx>=cznY*qAC|LDZcB-$+7I(GXDx-xcx`1Ug>?3}?kG0Cf{;OGwVDtlOi}nPN*g zrE@q}QSaq9$1j!-FJ9|U0@znyWX@Yd(C(513(tvEG^}%ls|@iME648LMIj5NhMlN& zP|})BB5was(mu6K48#VkmO#b(#XwAdrZlgA^Eu;P@LmCS%s!*)+j3B@<^8pgi-~uH z3j@UyWK$9vWL5dRuE^&R3p1|q6>(0f-ot)CpJj`G zdBt9+7I3Lv_*m3cb$jrDlY*@dm{O@iCm=$OfH_igFuV!i z{uBdejO5YBDHBwr4lm<^oSZ@{XjyZR%}k4#EbRyOULf?kE|mvP9XLINS~<#@EZ_o= zX>lv}dlHOncTR8PMZg89^U@xuTJdauVTa(QqaKlov9JSb67$2Yh%v()8cGJuY+>n` z3@xY5t>M8NhTn|k2nvaotChHMxOB6rjf|e(vZlw*jp2-md0>n`pTOZ37;N&yVT^B} z-A}fAZNy5g^2IQK3X>ZJ9(9gPQhD(Z$M+a8Yo7#g#K$D>$(Of8Q~Wu5JIy#lA|{Ex*dj&)8&QjV zO+0s|!46DGp+FjQGd$X%g|n2gSu?!kESq>qF|+ix+aHgqTiCVhlY@nSg~vvO1!Y;d zrKI~&iEd!(K$pZY56Hyzn30WoiB!=SGSl1yn832|IFriYDV-yQzB4>0Z73D& zNr3iq%dl&K;|uts72Je>Zzt-`R24Y#+Jf_2tp~cdqY>9GG5$|si%)M_aOBYZ2p^G% zjnac;jf*dN;4cgW1lYhj@<1APrt}u|QS2_KI=Y6eryU$bdV3_7R3g)fy1869z?_JB zFIi8+T6%NlipN#azgXPvqq?Wu%!15Z6@>b+n!hjn0No!%-d*{BQL zO(ee2gDN6J$k6nl2**9Pa)4#~P0e4(Y)0^BNSn%x%9`SH@!0V}5RdI2mAKTI5qQ=; zPJdw=(cop%=0Yof2D(jb_fDMxf_Cf5rSctY&8;e2#EH=fWDG)~+NMNcsd=h{QGOi3 zmEj};11349s)u*3uY6@h&{qq1%vm<@NgEQW&`-5ED-osr?r2Ve@2v>>L`ljm}4Egv0?(o%tz< zr6%FG9|dMl_I=yl_dhC~bkx%u*Tg=v{2BEUR72R9xk{lp5#F^5ezc13`aw99gW21p9cQSgIUAs1Z zQ@;=D(DdHLGl-gCUqx^UjsEzmxItE=D0(nkHq|YEO^h)K_dms+Ds*&ioA|!8iQyBq zvy1PeQ-?m@naNvuNDMd#;N&qzjN?$J+(MTMXpX<^qm#|{9^z@=F)zv7unH#$n*oqq zD}Ut?SgE=1!$%5yhNuOJze(&skqLir$o-r$Z&cd@El~|c zg%0?CO-b(>I*Bpz=2Hi=Hw3t075aMb(#s??7jfeX6|Lz<6}pOnfcxT2{N4x_o?(N~ z1sJM?pu~*gUPm{E>E2aC6^KF9a~yE(xrT{SZRP!nXRuFo158U4+1QkO;^O>>Vx`if zIK_SrM{4|6S&i6MR3pAMJQHS1inNFzCzuC+R&YVQLuxJ^6iVY!c1+j8AOT2CW4^vEcF47c)+!4_tZ5D{rSoVc!&CKKiCi4nKkCrw!McN zQ3;YS=zZBs4B$@jT;E=zR`<$9KR}aucog~oBHS^Y9m63QBm2RLba7=+A6?I6YW{M6 zT#Rn4NpOj&HDHeW=)YN}7o>RLyDtg~5dysZctmckF*i1~TQ9GzK>LX}#4A=EUQyG8 z@<~ZHS2`<60EN?%Y_4)%vh7t)OcF-v%p?KSPE8U*@!T+wdM8H!t9W)8WOW+lBUYhO z22$ssGRW#jmBFbVR@VB$BXf9So*DOlX!;#lswA6+`=AV$KDQ(FW$~ws5_35IgTV-Q zRrz}EC|=JQDWTw!W`S7g_H3rG$)^*L-p(hOBIDc(9S{r~&Vn;7H)V)Ajl`7F#|Bf^ zppwqEiJb|}LW60!M}QcZK0nSKE;wJfZZ=*`v7b258`-L*aMIK8?-#T1Y47iU+qQd0 z%IHp8LR=R$o>Tnw~FcaMXI=!;U{mNZH% zXWyQp+3z#CMdKGl~`q%NkhRQ@JR}!Y#e$@*}ddXK3QQR z0mJ@ujo*|&gWz;Jo73DR$e7_VDxsv}4a8^lV$R(*qdmI3`UpFe+})ny?lQ>S#Ot~c z!-Ff^mnL#GJ$1(R!X$5@9}nko>aer|6}(lcB+5)>V}j|@>cTEJGJ_s}*-OGtmV-Z@ z)tSIYa(!!&yBd&qWLVw}zc%`?4*<4d5qOR&_k*bekSIfGtcn+TIEORK_lddeOv2ud zVIxl#PF26_L#ovqoxZy`eMfb6_1vyU4}L)SEpb8F|HCUyBS z#tOcbS7Zjeog5HQ^~q!k!cW1h_gPvM!dI!XI&o^1{5Bf5n0KJG9dK^$Z>JDv zWLOTgKM|z=$uEzk2?D|>N8`Ig>VK!wP?qsW)RtMPR4`EE?q^VcD2u4WV0tV#tCqt; znlXfOjPVDWjd@~;W;h_Eg6s=YwW$SR<6>)oMcuUHtO+a_7DQk68YtGbif_+y&r<`q z(~V-|9Dgl$)ygum@;3ycKXUG3q^IQQp9jMigvIg#k<2$`Jw@ZvK*o?AjuvpZy$57@ z${pYf$XigcP|0I|8E_SOuqvuM-Wk~RP=P)U7XDic4xKl?c{mNvKi!w;<1-_d6E4?V zPSC0bp-62)p{f?tqz)7aP|9FjY*KEY6P7AL<^&TJ4p+;E8{s%l%tM#R2TVg^+RT8& zJ-|!G8-etLmp9cK1U?VmNd#W#&6ZFnS~JBX^?3&nMv|Ri99; zzOX;>Gm5%jvQ0~-=akFBg&kqy&N&U2uL@3cA4I7qYe8SQ_QMFHZc(Tr)#oreL3=Um zV~rUw-Pg(3sR0|(L;cZ@sJbWusyyc*OSrp$d#**FO$y~076O6%IvWv0w1*zP@zBgU2j|2Pj>G_h#oXwZskTYZK zNwqtYE-uL*=rvLhMJ)jgW8F?oOcFY=$g-11HSW^8`5~~R3ZB9q;Hl$Xxt|Ho1H9ZU zj%WAF9}eiG5FHXV2mLCP9B9^6%D6y;v+VH3kV!^=DcD%Hihx8fwG<3*I|?3bc~+|w zg#2b!883SsD=iG9{)D)HDmN&lpw5i@Q!}je(iVBJrJ9HNs_-wR{*wSaCW>bAQ~<>s zhQ~HYpbjc|sFUAJ7503No9uc8S>Rv}9c7{t2mxwvCsiR*qKfL0LLd1mWP#x* zQ3arX(gPy7iMRLuaruw;|2V4%&rH_cZFui>#bk$)2tKo$IaZ()??%VA> zFZjo4jiKpPi_q7f>fnpsvbEMsFV~vegtrnMRHTha0cJ&9sbVMvl@U$VfU@GS8dT;5 zqj<1{@0LmogN|6`Dq`oKWoNH6VwiZGKk(Im0rL_OygATOi-?_UGQjEg!S>!e3-eyu zA_Zp(GM3rk9=j7h6@404P2*m-AN zV}$_U`V>s;Pn5!lNm{04^#RSqcez$MS+1!3~e^ zgq!O9`IUD1Ui&aQR-7ux=fLGKrwhoshlAm(!(mfLh9sMCTbciByK5y6KKlUB1MaxTvzoF0~wg>Anj z21_7ZDrX5{ZhOkux%q8xw1TU5z zs_c$TjEVASYlbk9c6R;OQ94n7=0J=Bh|-R6SoY{(nOUh{vEnNrFSMx1@|Ra9mgfg7 zS#^wYC1n7j97UWXg1QwNN1%9obK;TmA~RQ}$`-$Kr|_o5-+75b51+@M$`u#X`KdS^ za2g^Rm5i%YeR3Sqf++leGoK_nB=Av>r`^&fkvo_Yk^uC?a;!iJLuo;OMu|yeMW-qo zn3h;7OfVzZSAYy%Iz}}8a$#c1^g5}M@dgAOpI6Iy@6IF%$x#69Apw;pdq`(@lBX&sdPao$@OX!ERg0^wg>rzZ+O)PgSAGdr3#M^ zh1^P)Z^pMkWxNkQIWus7EHxI)ivLt;iwxcx?^hiH<%k0JppucodW6lUIRCwHL=U8B z=4zq}az^f%cOkhCK8@YkOc4$!!kh3jDvhB}0iu`6{>5n(cECZ3Q~wGF!3(_-1dTd5 zuSBZ*qy3APns}JHsZeHMJp5P^d?Z(N3Ex$!p(Cx5f)qEVJ%)LIc?+w7zmALQQABl0 zxA)#2z0+_#o;Ic|Q5z@SBjGRZvZ+NjX!V@8aTYA& z>y>dWEX*#dAfE3ugNc-fX{OJFR-el7NA~oBI_R?GY|_@W%L{LY?Om2UV0-UZZP;t? zXnMN~KL#E6wcqQ1YUyPA*(Ic=AC`yC78`pbcw|V6r5)eHeKfWLIOzeMSdMSfVT${E z!``GkT||D63u8{abI*#MJZ*S~`(tA+F1w1&LqxGFLsn#vHsvXseH$hvt`1I{eE=!Z z#|*OLn^gIOSWjS~>KL1zfvjPn-1Td-(WUnQRzsKn_FF-JcT+MN8#a-Z!o`x-(1vH5 zwF)XqQ%Q!G0sh7EdD11N<{vGSz5T^ScE=t;amL2-*Vndz;S|y4i?;R+xB5u78{|1M z^>9JLJ`*j`W{_%mcLS2VsO1rGAC~e%x?ucy5vpj4ifNvJ;K$h>fpd$V>9S@;wTbcj zj|2m@%LdzjN6T<3g$svOajym}#8qX}#w1xZmg=l2`ww{(v@aMMia0P_*Bq?F}Y=D>#o87d?E8HNSb4pX3`%qAH#Dh}aWA?o)bK{SN zw8iDZp{dth58GZ6(=+5WM4Py*B$KpqIHsH9ZFrEBtSf#k;SJ~GMUg;Q9y=6aacWK( z=8kU-dtu~sBJtI<2gncIN^&Mb;j7wJ1U5FF(<|_xpEQ_YJgo$8zMQN)< z*-1LVtGu9AwzEfMwzwBhEyUD?>76wLlVQv=g~%R% zpRyIkR-xZZ$Hcmy+j}Rro6%P!Xq;w{Bbd-6l_9!>0q|pysybXsAEypeatSsfSC&3U z;GqThbu@U{%l-krAmv@}-><{M_S;`e>RJcP!b4>i5`V zSiaOW^DjUN<`g`5I3mD!pgB+C$i^stSUClwNn}8nIw8corqx&^n#Z&}LCZqtuKY5R z+vSI#s-uj;`bv!=vAShZD5H zuk2RDnp10VDUM!-H=Bq?!tdA%+^6a^$qd4#u=5KWHGxe2Es}ySsF`^|4R+PYdbGG^ zx;@dPsag`cW~sP9{s0Lb|HcQaWFqK~;&VoXuRmJCsGw~ShTfpgC@wQYDP9alb2;z( zEVtqZns7}@BZ`U065_o(N9{I$uNM$rcZ+ME<4FF-pbbq)CQ0AaMFWo_@Cc~g*$`+7YTkD zu`_fBeSa)&R_^&$$Q8m|i|DlxffWI9HuaO|F6P8U5hd&f&?4$c!cjQ}VA_~FBi5Hy zd(n>;LI#hFd~{TLDsy5ExD7v zGSO#U6at|eDjH@)F#HdhR+im|5o7`tTx9;W)g1J8w83ykYxf5FjyCLeh1S;dIm!7u zMPL5gb!R8Wn9j1@X^R!s)bWl9Y25ehC0E@yytz<)KRP{nYfW!|J_546nc;l~TJ8^0 z#*+f6i}%6Y!_n@mjc9PxuqAuSW<|Wz*O6O6yVu##^!|?4>9yb&y(0nn_qj(MyJgZ! z&O(>9yCtubq~%RQV_1EM_(4L*;zz`A3a>fNF$FESn@#MPf_Dcm?UQuA(IqL8p>@hb zC97}UPW!1?Gh<4Bo?A0u@8)wRlP|)}Ys{S~`{+gHRhM%@$XKqc$bMCzNw%&!^+-oyaNyi(k_HN>49srFw!}iYGWt^l9^P`Y;#ge-twS6Fz;O+%UdXqMouobBVVAcbH49 zBKkVxLMMuUQx&)uigE}iB~p}-(`%W#^Tk{+apC0YYk?>ED@eno9#b2gkg7qNfU4y} z-{=LO3D8U&ZW%@r4}#e|5OxrHUE&L`tQ)4_6s@foF7gXWgFe%KB7qj%5G_J1wS{Z2 zJBzIwU^*#cYXA%4jDY*~B~eh51qyoFDPV`sw9%b^6^w7_tZyT4HqD*TPk#Dvsu89w z^=W%wFeO||AgyyEO&h z!`*9t`$Xk1;3!}A984x_bP%G+D4v9Z_QIo3&|Y{J3fc<~LqU7tX((t9_~AMpMLtoX zb+=OMUZvLkO05S)t*HRZ4%v++I77ngu{<+LLQu*+Lo)ZPKu{v4RT>K~6)M=swS)@% zD&zvLQa2)@g5SUgS8P6)?zI~T%t<0ta2LUUjM!Wraua&)RR)v_H&-{7uVH))vU+XI za)#gC7=iDiqheAB0f^^{(#s18NA^gt@Ek^q^{%QVuc_Ks)Rz2yTK?p8pX%gL8pY3R z9UBU*sesFmi#1+c7aWpGXzM){+CF&Z;OxEvRL=HIvrtl0c%jsj!q%fR(~_Y)4! z{{DM;?29vGJs$QCT*EV|f@dlGYpfqlsiUGTAd}#e;muNL_AvS(_bEmG%J4pXD!fx; zZEZeFp_k;daJ{XFSG1c?g|(kN;}+h3XUx^U7Up;lnpzhk?ETu@Y3{rnHU@fL`CWuL zSww9wGM%Q{TocjS1ye4jIP3#w@{6$iY|(zJ^h|eA)^(*LSfYa#A}YlAt{*IaOv~Lx zareOR;`ibiaTcrC=uYuQ8`lVBSPt=I8(!~_U}(CUmRyKavCyr8*%P@IdZ`7?!>wuX zmdeYMEU{O(Gx2a2Xs{^kd}%Fz)J?&8Dp*NhaV5v5C1WeOg|NMi%);pNqK|zLd`d&PfTymQ6sgA+jWYuc^rhPY-(XJnreCM36o@;-_N4`oyB5bd8TiMP(26 zsE=C5sv{Qdo_v)h@9QNODVB(ye36PT;UyPad`CR>V#^<%OD4Ny%B3J>&T^?nr4Dnc)=8(io-k)zfy-!L*j}C%Aaq=tG3hPgVz=89sZ2#~ zbS?CqLnk`=pG1q0b)y@I6U}8*6~g>?88>42DiiL+q3R~_Nn)i!$0)%{hv+Ye8Mbuz z(GgOHXsJ~efoV+?`YgeJ-pCuH`!LZb|ziKM30o{>yTN%~{Ho>~RzLpXOJl z;OTi}%;p!Ca~tkUv((2E{gEs9dFtIZk|+K)>?`# za0660R2oz#FNGCT#kbP3cNO(n26_g1gPW?;`I0x4F21Q`IUjfrGb4x&yhuGII?eQ& zfwPQ@?g>tEdW!PXoN9*=Orf7Ht&pKPi`lg}gQe>AlU}NCO=m{5Skd!bw%8$Gtlm^! zZL5UrX)1$~MvsAi5+U0srgq_zh3RUi&MmMK5@D%C0x7x&WC+#q251jaVnLL)%0MHO ziq3WNSh6Y(JTEJp2Vnli5HxEnjTWG3ZZW2+K{Nki-ik&L{#LTG!rhQ4(XwfF*5yrTTB*;{4~8v z6`q=cDCeu`0rG)ky_T5xs&VB0?ygLgBzp(wO&u_azvx353f0+js%-^+MB&6dNd*UK zRt;E?_$w8lq21$X=n8LT2^w?-G!*gfC&L#@KE?;q=wDijY*7_>CmfSE0NM8L|K%bBa1eff;#5Y#x!wbXmQ`MH#)zI zw4NF@@k_K-Z4-1Rl7u^<_o{7zjH@LYXL6lPKKYY{tcpNpNl_A$meR7K-8dq1+kHR> z`Lf~y$%~x&wqmwCRyCsx44O!Fc*#Y)r^mJEtY=?;KYK^`gq9EeN;Y;Sa?Yz&wD_Ye zJxk-bMDKJA#cXx(20`L#b*o$dmw~dDC7%f()ouj}lvP>-nmu(( zK(jC7LgJlNooIGuC4~92yeLOgok67u+Q1PjtY`l>;2^MFv5Exg|G*YDUPgab|SWPg0 zuI`%BBk##)`RNRecJC9b#+5DkA`SDFgXpz4~)-*B~75=bi}!}JeQUa(QbJyLptiG%kzWtt55Iu&yE{g zTQM!{Zf(89AiP_q#??&AWBJc_HGfWj#@6IPvnJYuyU^}1tvsxPua%8S7X%;T*gSAf zwD{yA8(T%_=BZ}GI)>R;#*YV#0i>I4J=1;^{j{O&jNPNN3V*RjBF;7HDp>d03D16lP_0|{@KZjA1*`utw+{C(l78aj>j+*2V z!{J$HIZ2Yin`6T#ywOQ=d!aG=G}^YX4_I*EEy!yjIDQY%*oz!|V%R>1cY%yN%V(b(07arSFJ3+9^UJ!*z7hqDXGq z@Fhk%&@&W;bpw7R5cH@qh#1L#JP>>`_uzRs;V5|K|Ht`{^DInmphdXaiMxFvim*^N zfe%)10+(mmS!s?PL8hGS#ua4EkpL%XUj{7oP%EHTQ{Cn!U}{wXQ{6gIa7zVD)g#+#aXx}|76;j>M))j$$x@1UM>6wv z;mp~2md>}zu__KvJ6HrkD!058HxlQl>C_GrRj`+*hSp~rqnSZeFR)c4x|U?;NQ$L9 z+W%IPLnGN1#E|D)4vD3gWXJ5%e~bBz$UbIr$Czs_i|{Y8C{mc&BU;T3h4{pBxC?rm zSdN)W4;6_jD$t1`IW&lWEldukf1$SsmtKB-=I>%o{lmDE-4LU{X(tAj3dM_vC#dGn zCjL0Xr_!z#i9R#|NZikhRNkD#7i#+|I8Fg27)25(jms(+h*2gZ?=p||60Th@_1_b@ zv)9xEommcWf|>R+@jh!;p7A>kYIx9iLi2=2bSLX}wS;P@gAQzes9NncnR|_bW~iUH zIIL7N#1Mgah|v&XfgcM$%3-~OS<(WmKEwW^nYWMNJ%4Lpxo981hjU`4J|esjGG|v* zWW-Nd;_y+jL#zZBoIAiLX@SZ89$fXrgcb+l#sWxV2IpKyw_u3c%n9jyJ zTwL$&jswr$-A%WDYHU#rQ|UBO@np<_+1_K3Mqs@QA9YrSw$=7b%|)Wt-d&w)<^%9v zbkWn;C7^9Rp8)jC^@wH?;8!*(iiq~B{@aU&wiTYD9qpFDYB0-#;h35+9uxFWW@@x> zIu?OBKtEWeeF1Z5Y-u?688AW3FmDZDhf|{6S;3741UJWjedc;9i~}(ZnCRTK9~^fE zG6nbLW z0hX3`$z%d215*$JeqpKFg%JeC7?8Z9eQ3Pa-os*cv=jWz2n-vJ%{%!0433Afqx}TG zjttZZTKLC*j`qVJ3paSZ@8F4p1BeF#=1*9~QmSj4z(zPOpb%*QH}d80xRGPS3y5zS zSlFJ2DS8@i$IW79IId+foq)f?M!*DJm;m2~OANJoG)&c}8^Sd8zV`g|@_h6H9ZU75 zc6xk#{OWS_v&O4_u<8(0Y~o0Sxxvo5HY~z%;m3S`-q3r!!Arf@$CT@Xm#vm|J`NhR zzb(_Xb~U}((Dml<6%N$Ej~m@yw>jwQTOTgp?P@ncFyDRk$|3~W4^UMDe{Hzl^c8IK zY|ef*e)s499n63H0e*jNc+4dABkzcQX!+5Hok4#fGJ2P&o~GH?-Jj(QNWXL^0ed&>jF>ab_5(!~~X+*8LS_s~u2HU0CGjRtcr z&Cwzbp(08T`@RfMTc{+nCZSZDTIo(E?;)30i${s36hd=+Xi0=b{e+W`fB%=Jb2%}d zl@xocnPJ$imO!%744-jdzC7Yx`b7@&tR!83I7CEn7wK(`7akI`>N?ZIwnDHITG1n> z?Bp7SlMs9utva4v)T-X}@`J=1g5L-xOtCJsYOE-YxiBgq|K6^iEN^^6#-ByfWCm0q z`-`Z*tQ+C``j~g5r3k*PE0IpJev(YlVrucgL<(XFxH#MJi`ONLMMBK+cz?D2mgUKR zO*HEKEy^1kzSlR`sldOK@J5_p=J-F0mh!%2VW~9kM6RDj9GUT=uHx zB3uHOS-HFxBAL9UW#yS#7?haesvxj`#4xg21m>P6%V01kVSOnSO6)9Ju#O?m2s>$e1v?P^&Ufi%Ppi| z>{PS5g_ONhmRyFU%;sYdnfePteND^edXq=rC>Y7}*epttSj?uV68jaCNFSLyg*%yM zPsIrj1#4B#kXZi#6m?aPww1FRF7d)xa*9Q{qRXaOL4sGG<+2B=Fo^nbGABk7i&+0u zUo2d2N0UneZ!M}j89g}T8_#urtUu$xqh3z&nDZ`C^DNOZR!{HjXf*p(wGHSult&eu%$j#cuaRo_D=jR#aG2Cg=LGs5DG4C6eg z$Reh;W%ycj7i!NfhnwE~7c9={+L}(`iv%onYeCH(T8y_(Oc0CCj&ss!(YO?Wmo3rswudB+&^QqVh*?4Ez)Q3G}-c9;X{9D0bPsf)d zL`xYnn&G`$W`oCGcC@jL9#rAqYtFa}LZK=#ZZSnJ&$#2xe8wGV=xAt%PcU-$*9iZH zS!_Lbu^j79#-HTcMdvr4p$nL-5ped57zYl%9J3WKynxxR$k9T7^pX<16`rifSOHId z1g`uPrqaQal^RQPkeYUQ>_VfNEL1v?*J^t;#*_ETn~zsivTab^%2yMQC7f3UkB792 zmEaLBoKFe<hdnlEgCCfB&;)8m6?{<{lyHg>(cfngwl-|4B z?({H|7l;%6Ce0Fms+S89Up&3{KoTyuRC@1$B$92D-n;blXx~?Q?@@T%ba za_<1GYJ91pt4OxgZ#lI$<@q!ohGqB8B=^>Zt_W(kfDEOZrhH5F2lk0fQ)ZQgL zBDd&AOYI#kxKe6wdI;AkwRb4*)Y|R#I;HkbZAjIX)Jjsm>eSv>^CY_#nx;hZGwjjN=xwE%^`P?KRB!R%~*lc1)`2(PGT!tD-Vi+Bnqms2L;VgdMHWfR?TaI zrHSxUsjg}F=oHr2Iz?9r2O8WE+ungzLO}Az!n!qoY=m`LlA*(Y{Y#sKuimj?+cY=w z?yl?a?qbioyN-MJTO8RM@xCO68980G zvziyt=@z_-rMhyOYN*$h=*sgvKF{RV_H-lSLNBV&Z_1~sT}IZQWQP)?L2u>QvhGknbiEnwt+}Sd0 z*O|u7V?Iz=*gqyF8>1D>Gy+3=P8!pO)`rfA6ZS=$VGdFkld%QlMPutDejP1h;m~+$ zUy29zKQvmPwJkk+ZDJAI)chNCPhQLcBd&)j;9OQ&foFlsVFZ8SN%Sn>!ecZb5pC;# zdJ$-MVG5K$@(!$SYd>HNe~!<7wvQ~LopyCiG{e3#9(?Uj;<-Dpy1=sI z#qutFAcHOF)^~AYm|u>~i*7|oOhDr>%LmQ!{RJ*2L0sX?eno)av|nMXg5Nl`;q62x zNHg>sm?6)!c!oAM(;a&EkdR#cL`tZCcoC+F?$nej=w}RcOAiy~(fJ}Jdt^+2PN`d< zO$;B?Ob|*BJ6H>%8E5)0_R3!Q&8C_XE4ls`EQJ}wCDeu;M|WjJf6&jpB`I;@D;gU3hRUC-QKF_xT@=adbyP2 zV1}(O;qZp@a3bEeyx-u{WkHHWk6I|CxKn`^x-Bh_r|S8SmPi2-%4W4Nb-;mTQcNkf zR*|-6@T4h_BGy<7VTdRCrcvtRk#fuopES==;=ZVbvVC><3iwJuNfPrV=KTrY&9bC= zIRO#xY`Tt5e&FHRD9Fag7A#7C#FrUemQXS|&|i9-6i+N%v+KA@hP=NrdH7cM=ie_9 z+5e>L5R2Jsv5qk9;NLGw5)Y;}c_+QrDDPmF+ET5SKk-kRn5+CfuX66GS09D}&EUm> z=V+|l-wOEVV+U?iebYzJ3P>E~SL&v(s7t1fB&bVn4V$XEXecSXyD(_345O7TO#U_rFzftca{J?3eMibL4gSp zgB6*id8;)h-!pXzJoB;h#@6X1rNv^o>JyhUPc84qao{^VSw7}YjKjgNF_k{eqra6@ z)C7hH*ErYLxLg&1Ur<$lQ>dqasR9i2yhU|Sw)Ht&X^b_S+gSo$pXc^aocZP(mGW!n-~Ot_{G*tOJh6_-4w*-LsoJLq{`)oO;kHR9OhXySP#bis6Ie%aH%s2<) zTUeCnngn-*INCiGavxBnv|0TomMVeOgd!R(KczjtfBEp@)k8zc2}1k6LSOHr(k5d+%Q_721v9*P|)f$!(+_S8d!!+|Zu#K9)o&hx_=?SL?iwmyUTxf}8EV6WbM*czlvQ&p4OE zMHX$i$aE)lE!RWWa#3Yd@h(2TYkApf>Al@}6)m}?nw_DA;X9oHE*bMPC|^?IsG=w5 z+$(gs2llRi;vgOeKFPyp-W+%!qTUp~I*Og_lae8Nqyy8EM{EFcB;!??h%^E{w{lqc z%T~8E;+{`@SbgHlMFW)ZRKD3o@m|>_^dBc|p@ePliT0{dWp^c1DGM4D6N5aOScpjp zTUZGd%Yy#$6Gx%E`C7yIca`Tqs6PMYXha;(m!*+^fjTj_npKFoerQWpfpO#7u%I9Q z>wf=rXp3wOv+s+%EmAqOg*w0M-B#%RJ`~7c`Fo)t@2EIsSf7dp%|^eacY9w+%CKQU z2Hr|)jJI?Tm$v#LDfkJi7&EuA64d6x3;n0#G@Xy2j)*eIv@!9=a3JIW>#dLQ<8xH< zFpUp?2`;$<0DwZ^p2`hgW}!P%mJx<|)<#c{Qjz>`Yj~58_yZHs2^eI!jg~a@1x!s1+dvb}? zZhkX;3p`n7HN?+GfQ3rMzH9_{%Jro_`4E_w2GPSZ21yka%)EJrQ-T*?_RZ;E4z zO?e7)W2b}Is{3FFz@=5Vgl$HzP8uM78IsJk*z0VNCSd9VndKH;*+7n4wQXRqi;JY0 zwDvPn@xJ~?qo*z6jUly`ms!)SBvEDFsZ?GMPauJtX#QiD|B=g+szV@+_ZzEe+{*ZP z4TInOE>LXVoEks%NxGON&Khho4ma% z_Rq_k8N52GcaklUT3yl7+AY2V3xox1qwpW5CARwi2U<+H3-48QRXPTuu3d~b_&0w{`lz86bWX3!Iu>TT40PiOnfk0f3^U$Ver_k>QpVO zW1n24>P{BFe#ZS@8Z7`?{8y1MA*Qe|Y-{%u>IQO)m-{DNT z+XHuo*c^hSLAvPHFukVxc2wlQMX`|9;Ee_6|2SK%F6V~$S4g(?wexTdSI4rYG_vgy~qRXLa#!3ezm=#iSe-TkC&q9uqheB-m6xM zwHy8Z-@RLB=flpg!TvrbUq`ok9kX_+ap_kvERKbHV9zC z;$voo{T3d-dr=0Ni#c!4{ox!-H8j>`DELep^d#hxJ<5V)4_CL5Btox~Qf+7S^T@wC z?ojfK^=MKfw^17>jba`yA-MC-uutzYz~>_=UU;TzC^%6hc};spXgpX`*BM|aGCiWv zC))vO^2P)lC?3hu)u0X9ja}v)u?;nqx_`;2%!Z(>ILF<;3=Fld=_9%!LNH()%!f3~ z^j58saPGdq?aRILVNz%%zjJWTR+~(ck_HuuJfw}s$x+fFHCtwqhenN@kP8J907Ri7 zFsQxbcM6&sRGh$1hlOF_>K-DblCd;*wBZ1+bdnDPB+#;qs{ZDh&9lXrMF|=90KWvb zPmIw-;8YkrN#C)U=iX#g()f2E{V^VSC0Y+MZZnJ{?MXC|=WIs7YLzt8aKKrc9A(CE z>?scP-B@Xbv0yC91f%kbN79)D7#E|-=cgGo_Pe^!uh*yaUhWRZ8~6h`H{q!7l57Ab zddVsI3}Tr{SP3^^SiX-}Ce30RT>szl-S@DOEuJQF_fpcAPc zmvreH61JeygR~d#MK&IssCM@bD3JXsk{2(HCy)Ar8~VD4SHzx#r~ddMMZRcJQBCF~ zb%G^&Cs&Jypog#jlAX#$zw~Au89X57z9|39@(4M!B)Q;o5>lm(8(7v}@2o}Hg?s5G zt?H7F>M=w^*MgGzs-UfWHD!51&&t!@l+{=ZVaJwMm(EpDjk)Bg8?HytIAdFyp}V3X6G7EVCa;;>d6~sZLCYb5K@1zu#)-1%nxuw>X6%2Ngim5}$4Y zeVLRoM1C77DZRWasq0aXMQutM=-O^P0U6fb*({3Elt)G@HdpfuBj_icETEwa39 z$w^oY6FgJk*XEoB?$Ewf*C>K8m_D=KL9g=8l$aB#ElVhr^~@m3oe_pD`&kc?>@0X8 zU79HZ;yG6D0u-Nx^1eY7ekOp%&mH@Dm`pN-&dexEa`_&EO(15d%6AOT$|97#<^n~F zH}vHSgrUK)*CH?)tELZDeQRFm3ZM9kcqch1=5BboQAZLFyL`%?HCuQD_3KsA7Y&Ze z%T;)sgz|RSzCo4xmN{ZMVm3d*WmpY_2vMqPoqHu)U3c$qV+3Mol@s7-yc#l|hoC3he~t+dCSTf<{Y|iPg!>QrRx6f(!S;LEni!S5U6dta3LaiRFDNHIiCv%$QzU9&=f-Z3{o3c)h?e#LH zMJ@tt=o}xPmDhGRSQL<}-)s^xiBc1@I-7h*py{q%Lu&E`v+DE|P3P_!QlYc&g(l;> z)uN-jl%l;8ruofQZs@b58eOZu46Zw1(2EXJ^SjkURj#>y*N(Og2gYs;GS;|X71C7t z4_^aR>jv^jQ%aFGGS;4oGo6u^O4OoAWt9{5-SUCB%}S%z%OaqG$xqnqq6%Ao$tpXJ z*A4n+pTV|vSq-NffkK$q1LxH8NHbL(vn%?vb+GTsEaA}_)b8Sn4QA7>*|oUus^#^= zp4?7*Mb-9F8q{uq?$a)y1!66+NZ?8wfe=#j;MU6eM8juF;mWNRq$y^s_?@fTzF3K` znoz0JKP5HaoE4B!Qmt~RssZY3WJJ#IXwlBvlsP=qsJ}WplA8oYDSx3gCS1rF_jQ{>8^RdN6>{_(!BzNCFPg3KZM;$Pv9F2 z&jsI&uqyzBIRhEOTy%j`UdMif2_)zUshkGWjZM%nm7L-v9Ly%sH-t}>ztCOv@Kw}X z!Sz52DEK10yZKbeu05V*#hhV>K!LcL00xCM>uexoNBFkx#e;Wl)AtQC!PA@@uC#0T zzCnqgmdEnOsymg4YP-R44#DRpR{#3hEq zUXKi_OOKm{4Y~Qc-9uVpzDcD%S6z^2(+rK4G^x{+L{~g?tGt1)Fa=Gxc-vyN5l>yE zzm$@6-jKo@{;Xi3jA)#%oC%u1TM@5ae^jhMP!sU9u5~AKg0uC?UWhYudC7$Bw5>XZ zqzy=J(J^fTwq8qMI}|cb|ID;1CR<;Wtr{+rFe|D{aqsF7A++a)bxryo^&`8 z=F`=UHXY|dwP5^6c(g#S=0P90YGw5OjgC?2(lZ1$qGa1EGYk=odppUoMl(s94Gh=? zm+~aGVf#@n>QQfd8#u#IHAk1}rI?B7`B#}ISVxc~lb>$}Ig~CtzPmBS zNn?y+4RI}{v)tK6;-ei+jB(5P*46EBErZ{Yef>ERLu@UhCn;K^Pa8TylL59QUw&xX z{&KoHnpdaS?3OrZFO`(aqhL73K+izHxB0c#vdQDC$P z{oA=i&R-|pc)I8L>R^Wa{eUN2s`1ksq5`SPCJM>Od3077BFE-O>free>h~9`vI3el z5GGPx z58C^(HrUg3*qQN4pgRKC1-YtO&*y7s+L+J%VG@|<=|De1Zo|qDb%2}1-zoc@EYuM$ z=OBvs2`uy|BO>RVMTM;OvNt6+lUb0V&ednN;hab!>Pu((3VRsQ)()(wQ0Ndjdr|g9ULl*D$+2|Uc)6Bfg)p~t)hkmQ zz0?^FM@yr{cvw`ZvjDCBMKxhcrlUZAN%SR&R0cV*@XGX_fF>k4{aRMvHSQhY%grlyNA)9+jq}k6zTg8AER2vgc21&PizLbY&Y7m0KYC)7EDVZal z{rXvOD|(4EV&CzRowNz(Ibeh%t7bB`Y?65U~=nA&Pj#4t+Fos#;iWO9Z@2b+r2uE+XYcK9KWkq4t#}7#z?1v?@&ZF zDXfPoj}#kt7hs$%jRLYvnSB?IOSP0=g92n*fHRAcjp(eBm1xYd8yiLGM^aWo3cMcm z-)OCKrN3A$MdB#5Z0ZK`W0qF*Gs1=L^O?*SN9j_6# zt*R)SFT*Y>(iwhIk{vy$y21f!?3*=Ahn&&^H0;}2KK>@_YqCBMt!O)wr8ZH2hscpt z%4E6MME4e9{wB!iFShr|OcUfwncdf4^g}qWFrHCtT3pBTqo@3}p&EG|=`a=VC*}KM z;Y85S1PrXm6-;*$U>;%LMMrl>$wQ&co>*mfx~vR(rM}BmoLXCKY^+mP#p4Hx;!=Xr zhFAwXWR)n}2v$eBS)FdEd~GqU%9*`d&2BA@N+zfU-k6GEJSnt{$)mUIeCG^4Z)Dc_ z4h^7$T)DFue&Exwfp;=|<-dUQYpuU=m3cLQQC!r4u=|OsI`Ym%e%t-4tajG@|z? zAAo)DU|#he=@t2Wxk4pNY}narSpUIC$5I+mVxKR$T!%1f@&S7cuRC5>q_CET1@l9* z#Src0H?6{cAm~gy`p#Cd=>i8`6@52ufX=gYagbTLtGXUpRZ`d`bpw#CZcn4=;WQKP|r_U(?`o1qCA1BUy3)plg zL7^YFq5IYzAUCoM3KLkAe749c;Vrjx`HHpR*BkcLkd`_B?zLpgb8)T?&ls7D%f_8FYW#BW zbSaqHEjF@On&OGU!M$ZNmXqmFUWGs2gTRlQe~^4tJk5ThdR#I3`I#w|(AT<_4#hSk z+1&wtv*HK5M*_05fz(I8tH1tg23Z;Mk#4d`z~aUsptXmUcN~8`z5ILuA{)|sn_F|g z2be$Hy-bG(RU8jL8vJ}X4QkYK?I#>sk2J(9%9 zXEp`Xn-fqqPaU>)(@abP^g{X_xZVB-Wp9`ML)pv`%=@E5PU{~FtE3_P;1!>v-(xiYV<3a1PFw<9#O+A=K-f(r%GK&i!$b4_6h% z{b`xnQN0#mwcfO?TqLVp)3u;1Pmw(EouRUQR&LHIC95BjTUsfBj6Fphv*H~j(ZyD6 z6qag`O5Si;ruDF~uk8R={iZAVDMDxM*G5Idcv3oeD-~6QQ|N7Jq8BD;HPCbOH8Ets zv$j5NGw&`?2~-t_6Rlk7DH7>oDHjnf`CiE=NnryRI7&IQU!d+@9@(?|bFn|d@u`Xx z+Q|erk;)7Y2-URB+2+t$q1d%%gMW$Gf?wX@*i1Ye@xVQBs9jCzVT8Aj8pJuc9pT7I zzfm{BwVP0?R%eHQVMAJ>dQi4UanxNiS=kWLIq*)aOzCkh#N*k%ft^|WM$lm@V~cA1 z`{D)2{AFVbB34`RRotouwAx(?-FIEB`pfNR47ko)U-_3?4#s1ny4ZDvLS)}an94te z(hUuS!G$Lv9kWwk7Sv6C-@3a1@)FAU;BMMiJ%80U{-qc=A4A6vZ|y^UsS^vXu4uD|F&OO($-lp z{i19BGE#ns_|K*Dc0{SOe$kG$8AsaItY;^;SWUy5o%R03v^?4DpP1FEIAz_=8DL!g zq@Qczx`C5eEn`hLHQ30wb{qxRG80X-RoACTv=!$xaFk4>+qI0AY02JGPPbX>AXqY~ zG%13PY=o(5(2Zx;xVG~@lAdnalwbvInYEo;>^H5O!;kP3`owfLA5{paiiVavTaX|5 zjpJeR#n9gRso)Jm`-9S4+!gC$1^Co;w)V*PL+O-a4SK=*i1{+HM^Ic**{Gd&UHpBH z&HwbK-DZ>4X?+2TFCQ}?5MDB;@K0L&<8d&cdXRxo>aS@3uWT{sL>v5Pr=J2k(5TU( z?|)>!>L;l`JD~^ip(i)B^fNoY?{A-vUrUsX`zuBTm(n^@?BwI(f_t{ z@>V00#(UBmEUkIH(poA><7PLOr8g*e1*1?wzzp{Oy?$ZgMftoG(U!uEBas&va7bR_ zr2bD9CTs}!v!5XrUO6WH3<~y5w~}2En<}DTN;RcK8w?f z1}j+!!*sZ9e=i}jsw@D6mrn=%RCs@E1);xgspP<11%l0-6<4~<$6a<#I$G|GU$Ygd z3!*Ew2DZbyHi{=3Mt^~ptXZ*1%h0eV zoIL;TcBZO`LJm1$;}CW>9Q?6XTRUAbW&2uATzxET+6DN$cMH{qxe$#w{}t;9LDXec zkH;@d)(|U>F~l*6qP1p|@gg^o39)1dY8qBJKc)ZO5`N!lvTCJD5MtErH{_tY8w}1$ zJx=9L^kQN>~?jew@6&mF{p0;T`_7|v9O z)GdD~V_2ytxP3n?M0IZt3ZBk}fE8|*gzq=sq^>T1Au9m1QACZFJ(}0E zcO!<^KjM6#7#dNaz)m_YgM~U0l5fEHzEam=Do8c@&C29VnsF2z%Kfk)R{u=i>$PCS z9{=K|eC`BnaP<9m5<9&;#^e3l{UGGHl|pmCJ{>&%DupqSK+&LLttn3%fe9b+fm*m{Ib6xD`?<^O?dy@5>-5S(&jcyp_ z034QXq*0Qfze+rZtL2U&w4sj@a;8;(9QHhipqg}cg?hEgiZiA!Y+b2WHk58%bYaAO z8P}nS@!q$nms(x)d@GgP-&3551~F=SijmJ|Q%gc>cBiOC9Yd4jt@8OV9HJ{F9OZX( z@`Oo?u0)Jx;W1d;UR8S%9VR3@mXi3v06h)6p>feLuWH5ql|a3F>t083m8H?X3Zjq) z5}`sdi^^dnQiUb#yJc7^&@hVhwl7UGUyS?W{-&yt1VF&Pp923rSlVIgA1?g4n~0{u z=n9Z-S$-sF-Ax953tdo$HMzvJO(O(J4Ex4lUXkS^YPgVb4=C z5+tAdQ3GcL!RB2rdcdHDZi(XBoS}h(%~8j9$Chx$BR46#CP1yoZZps@ii4g41h;r# zKThmWfSJ`mne`hUf;=yy7I1GnY!Gd}zJhij{9=T+?~?$;G?U3dO`M&WWI?A-xht-} z<4=%&5i`2_eppX+$EvtN;v&+iF)o{NHC)MfOS(VE{KvKZ{4~k1`!tEHF7heF`rxTI z1~p$4GdY8Pq0-j};l!}}ca*F|+#-a{}8Rr|6f--KH z0tV|+af|5+QMs1#0=GA7&ze-u>`_cA&F#3FL&xT;iqvuDZ8@$BV_|hnj09K8wAJ}l zvt#Au1TI91L*=EUD1b4XKqvB}U)A}qrgZB#@lRil$_HUT4A+4R^~b)Cbb8zewQH=k zxscdTpWZ0}hmQV_z;PGh19B9@Cmvkw1m0Dq>o?7#Yo!X3SD!Lr>(e+@99q^t-`8N- z?n~>_kpv*H>n#5!h-n*yt@~Q8u1cBX|58LoQPI2y+18AxpM7*m38zRFj7+$e50dvH8FafdwuqjGBuXXhQhwW|s=&C7jk zPubKT#_udHpk6i{-R`Zw^K?@qd6n#I_T7Fcw~D`4F&Mg{ctp2Yt4BYPZu0$s)SX2$ zy|1fHo#a{00}9rf%x$ee!|=^3(!~t=D#x=ehX!UWv;pTjLorFUj&P}Ny9LI{7sb5s zLMxTk04wv6ubPq_<(p>htU zeHAX&ql98Gt=c5+n25+n@5!E)yt#PzeVmdMLLYWmRboEdGzvdC|}qU-+m$hA0>%u`~1 z9M>D#Ud?v{<*;_53HQ5i!zpf|92bd2iKoe>902b^9yzs38Z|~bCm^i}WedYG7wMnc zQp4IP{PL=R-8nptB^~4dp4^9M=JSVRCig8LCwAVF#v++(w7_VPY6mBK5ST#SdD$}f z*9b2JVl_Z?o1M5jPlASlZD!e3QKQ~FpwF9d3^RfU95l~k=!j4>P3(1mP`Y|Dm4{`;tDRmFk>@eT*u*J_|Qgl%N%H>GYH3O?IDyG4Bn9Vk9n&bu<9oBBx}w-8k#Sod21 zAG1|(lk{(O#vterh3>k-v*=^{yFbA%p)UBAJ#C*nUcM^q{jVxp`FycojJw%I#sJ{+ zY17qnH!3+w`V6@4=%>rY6Q?6D0PSc)Bjzl2ynp)tCxsgu`-J9`60LlolR1ilz^Z1M z6-?aF98K&0am+lxG;hXdWb_73_I+sH!1O0z8mF%HQ7`(%6KWWxZr(hxy~Vt%X^o1y zH_ItCaT6`uh53`Z;w)If4FD=v`qvCT-bx3`3Nc@!pJ1!YJPub{8e#oNqB^eU&Ae$? ztaWW`FXKS~W~}x!CTW6{5=v*`mp$2%b>giA%E;fTi#d|S;44_Bd%lF_e&VIdR zxH)DQHn-D+GT5N$alYwn=*ss(vp)j*w{LgZJRb+r=r?2fBM!x#D4iLBf{-F%bO%qa zA~DI)sH1}?r_iRxelGQFfF0jU8gKkp@<=OMAt{81Rf>(@ufms1iR zuC9N64`L^OdPW)Z%>cUZhRzs%l>dyaa2T0ojY0S_7|MMj_e-`_s(EQ0hboSORCoQ+ z)~sGNm8%5wog$aq2P!W8i?cW=4m@1VOxg9z2GKk%(;XP&Y+R;MCB-c7XO*Pdw>QzF2M@pZ-}SK z8dapb@cu+)=>cwyHkWEN#4z8XxO!Nc260xN!oeHdo21&1ZFNX(3CC&c93`Oelqzt# zC!7Vsk|umYr-HmREgYt^`-+A+J%P!NSm)JFf!XxN7L^uei4}nkugLfti$so=(K)LE z#zdhr7xh;Dm}8q`74b}0>}sYJr6LnaYLqV_RAKRi90E#mgoNeo_@PDbtd?`oHoVGA zDeP~k>YpHEjQ=!K1jaDfK8`7TrnY=R!q26$0ToXlb!Y?>y=PLezn+qry;88e!m@+s zCYNt&?-!lKTHKa5ELHF8z*rHTNb9CQy__LklF-%HS71v;HX_+vlHh!ds@oG#jji4` zi6M1|vjYGyAlK`Zps-p4LE!RcsAHmLb0tqQxL?R%?(yHW3oI>m2L7DMDZek<^ugaA zN1}tS%QJ$7zkFMI*kW$uF%$h8dUDnJg?#x(NXH9CdxN5liz`0;6x&?Yh_>~+>APqz zJ$4**QgUN%4Aw75r_^5fdUyfuRd`thU$Jhket_@m-OnEeIEIq`Qm@w7&@`=pjf7vu z8FcH6m&}8iTJYwmpZZXv;jZ$Nt)TYN0bvH~=Y^)=?4r@sK@2BNw<|62?H~7s3mrB( z6b5a0STVKHVdj$Nr=TPk@(E+%P^~IW!J?h(@i*uB+<;re@Qmeue;}#1g|(WYk=Aj@ zBLK=c9*aH?SO$TS#=`7@bOdxl&Ma_3W2~6U^b|MI5qLslD=cl5_WjPpUHC!l8`xZ{ z#68LptZ8}r_w_r7B!%)KuTy+p+#KtfolZD7`l6og1v!LT2PUt=rP;j?Dk+y%5#yoD zh0O?-8Wd|po?h^`3v$Tg&RV^#tu5A(8o{^UZa60S0$E&fq*|68?{Q)vfZU-qYLa$4 zqG7UhSf>i>nOgxnuZM_{;cPBNw1DpFABg|caHdhj`Vt)EUwfHGW+#21{|3p<;y`fc ze1D{+7=ezXA|ZZlB%Zl2gZ#?`61cV!xB_`V{pY4N!w<-L>HbrT>6sOur;S299Ssfu^*_r^(=ktw zYr?hN9VjA)O;5-p zXUsT{w^wl-|J*>EdbLRdB3Up2&PIBjEHm?J*bq!5P@?sVNuUn*BCY0sEht6Y9#Qh) z@<}l1+#~|S9!(F}G%*5&PBh|?a-8Fb>`aML$8Q9<#2PhWGajg!p$88A8ehtics&Ij!Pj3u(wOb9$LV(0$f1bb0w`*hbZMHydWiO-`IU&lMazSw>S9v4A zVdf3j2m|>R1{80 zG5kgGt&Mx9<_giHgAo|cERRLFX5N=9IFHEmS1gmdhY|qTnOm7sG9fC^W*D{ah!4Wa zhJ|dKRX|Jw z2X$zUug}W|>IsGd2%3Nx274pfj7R-k2Y=A;cwP{Q=%q1liCq;dl*zUi{`mXR%lte< zTdxNwlS$Ny$z9PwmR?F-w*Xy*P+bzk?;zbJhVjwd|ivGn;G4f;F;Vymv|?f z&J=KAJ-{s{6Xit7NJT*?ki`&ghyJi10jBJpe<5Id`vyQ}qkw}#OcZO$-86;{rX2*x zK=?EmKop(@2BI&k*cx;{EUYJDBCOD4c|JoWdd3mTFZV5td)A=ebt`-IqiZciTFwub zX4f!soEz={%#m(DOtTT-5E_>tr1*=xnaL{jjV6OmFBlJn6azm@7$e}JjA0Bx|Bip0 ze)H~xPm4LX_&#-55U)Z`wE|F40u_1GIVMXh^$75;_O$ayM zC@OHd4=sEZ_cA_h20)*UZK&@xpfikun&rbv<=LhHUZ(V~ROC7%g={alhUgUH<{T|r=uVIQi}7K(70Wu&4P$6h%;NU(hZcU6n&Z$>K|HKRPsot{NpV4c zUK!>9j>R0=&l_Ca`}(m|RzQXPU~n|&a-c=oTwzvdl2Ffva)r*c0!j!D(Dh6h!7La$ zE!t|hn8OJ2r4r_xu;~XYn4?$a%FA*xlI9h0rR4>E+7I*;DZ4cIYE^anlr`stTN$+$ zN1hSDp6C4sB#FaD?D@O@nk@^cbKoup&`@|%$563`nc_htOjC1&4} zr=E@GM|eIj3BoeA-!b5Pd4K;5fHuHp>_YkWfr~H1BVi@ae5|SG;E2frpOGY|ZD52;?{H?!2kMk>h)GsLXTdX5PKqT1 zL|6MZyf*wM~P`IbPLn&hBi7~41rQR8}mi}QQ* zn7^Kzc@@sWn)PdhGFEaUfV)X^t#ypQRqiR^+Q^xYKWXv$E3q?C1ys?WCG>=O8Oj|n zXqVVgvw?a}X+3eb?GRySqYCs1nw3wQ`T-L6y zV&1LGh*z%*|3i9`fy~*==yhRGN1vCkf^=Z|LZE6*J12fS8*@P;~YP&BC$#N2vNPNi-5_Ih-CKqcz`BQsh#Y z_W*J1D*9qLM?2tC1NF8bGpvI-*c9?+&>5>}-x#HtgHj+MvO=~)_Yd(%oY81yA=^=5 zm?t)N%`<-5g*i)K73@&DX`=vnWMIHSj6{tY`xH97CzYO_@I<32pni^WaFlZsy}(*?Uh&oY zan#h!n;|nUd#**PPMuh7G-J1IuRO>}_S%*~g>wF3vN5L!m6?T9kg+6M$om&PK^=#R zhfZ;nHk!e=N%aI6H;;7D=8IzZ^aT(3%1~{}YuEu&W&F>apJIUR?%l5@goprde6@p6 z<6wXJ!V)znWUoL&|7Iord! z#_8?>MnTk?DmcAfxi2TcXnYZiJKKD{v-j+y5O;z(j-Z$70-T`@n$=P>W~4Z2354~e z#>Jg9rH~;v$NT^bj=j}1%tQeo8VICOrtO?mgB&n)z% zp#|^j_x|2EvFA3co>S9)GW|~6zF)*5iUsOd+WZgEf$MA`IfG$saz_!JLgr$j=eQf8{u* zFoA<(fvDBet-(!5q&Y{>sOWdKW3d-@EJW$H(d0+t#CIf56HNNTE~}=%IS%XBjEfbH zLyQL}p6vluPESY*6)W!%b&HxHLSOpdT|8rD*cPn69w#^uUX3c2C1)5?;6Yx(#~yFv zRDP-{oC5q3Ewrc=ZI&KKg*=D4x+WUPjRRM`s-Jh4Mo8nl0`2lsmQXYV8 z7Yt0=ttP8E6rceK)xY_DneMddQy3ip2|+ZLFO}fgV=Em_vrY*_N?GI^l8g9c`3glV z=!u)g|2QFCM+$@&kc1O=boPbzkYXRoU@HVryU!SRiu#d~kceh+?WewG1TxJ44}0#| zp(TCPn7}Xx%rI%D3=bHx-5AI06W{8hJ)0~qzjui-#1VJCxCTbMNo%59t#+KChEe>Z zmKB(VL-l<0jNu19?=)e=K%0i-yvxgIdEC>rkm5yrhUvINCc`?naKWwomMf_4A4vey zv*s#4JjX=p1X-i`oM%%i@hFtr$+R9B+wn$)kW&eJp??SGp1c!pi+av)PLx0(dB6fY9SdD4#r@T@^Wg#roZ&B` zK(11v7_{T}BReWOwScUqG1U2^YTlt*)w6GvYKl@ONXA0fmqS$?9l{h!Gezh)evH6;xAWu2_y}f^-Yc3|8 zT3c_g$HDSa=rMzOu!-?m_oE6>>DTEZxuj*B{-N~n-9?+yrN>F$Zb@V)6`S*$IVGoC z!??F{leWDnnYqneLTa>m1!pMHm-Zb8X_y5)7<3=h6b5oo50e^1p7d`GIm=Em7xJ`) zaMwFnOTBdWC}!3<$=@&p^sbpx3v=W@CEx9Tg{YVsxG~(|gJmoF%$zL&rCGec+;_n_ zkvgOZ#5Hey4AYV#MY+IJ+1ud3zV!k{+lV&Gli1L57>L$^$eNIGZ|-6^2S9_-%h(BP zpkxd1f2&-UbD%wmr)|-h9nnquIxW)78K4llV$9VpRy0!l8vYf3*fiEn9Ci|EP9aW) zJ+s0MGStkLPr53QxVNJKNK1&rFkJDv3bV(N(dbKt6m{+1xn^SecCT_5I=AQxwo=E3 zGH%H(jRp@arJ`pAu4Pt5IR$zQW^|*bI^{d^JQz~KDgX%oGDkh#s0&FMZtkS++_k$= z1D1|jpVg`cC*lXbh5&*bi21#nNoHg|ND)z-y6(Y0)@zz^GR?^b5Re8nqYSQ1>_5zk zN`TKWS=j=ieGJWwCYmI>kg1V?9e%0Q< zt!9$3m6Twloit~Qh+B$VzHd$&SFxtHPvoIhUxiVU_DG_3RAkE>BzRim^{A>1tiK72 z>+OI?ion3F=8kB3O+lZsXsvHyW8ay zl4nhaBS%pVh1pS&?fe!aYaj?{UXz%|KK zGq1wt;iF!C>S+rqb?Gk`%~$7pzRd~+HAep8oMW^HBxJNl0K03GCmx5aNUQpG1OBFd z4edhKE3LJX(yrmLUTdfZ6BN!2(-W_aA@br+X#3XHXzoK3u3`TCd}D@d6J?GfYxG_MfterU!v9x&bhxd9S1S^kjkvt z!c{f0=uPYcnJPP6(4s7J1(YUAyD}xkcv}cfX~!6Hg=bfx2m4~~&o&%4gx2**z?sq8 zIbC1t0kTF9d8|Dl5Rh~{GRg6BwA)E5vlZA{m|<>qD*#gexeV{nUva?~UKo3Ph2b&{ z2wrooq2cKVh^p>)yS2N!tTuDQ7}uP+Y()M{uJ zJ>{ZfP2d*ZAwg~H4@2x-D_Qj`T1@>tMCg!}lJV;Ko5asYuSD)&{>rmHNm_miB|=_*L2_GeIa0My63(v2$DB3{LsmRApW)Ra^kryX*|z z6FdHa=c&2;RW1J>u0;LCWbsGkU*i7!F3Y?sr)ps&FoGCD z=mnlgGAo%hNdd{Hxf@X$L>C7xQ7A_P&73$5YEZ&ItY1Z*y_!*|TAOs}$AfRXLSf>8 z^omQkotKeMxPG+zZPPKJ;c>im&s;a|i(5M2sn6s({MQzS-GC%PXf(_(z<^1%mEJ>P-d9}_+!f?pm30=cuRRS$>7Wt8X%)|1`U^q{($gGRAiq8Rx2FGWQ= zm(k(SlEaA!SO%KT6Zm^C*#mRK7!fri5SlLu(4Tw(r<--0W1CStfmC9nglD{z=Qi_j z563IfKHVX7(--ejfWMKKw>(lk@!~n#)V3^K&*hf3+wozl4DZ_?-|EMJ5b_AT1GbT< z?e$!nG3~hwP9^2AH+dpLEJkC(o8r>^k$_n7pb>^D4VbwAkUC%w7G~@p#yJarG=gXb zO7jeYk6#KIJ=@w`@zFLZ%#K{q9l%&{g|7v7&FVbt!@YREfIJ@mfSVxLoN#&J?my40 zK^VIb)5vN`=0RUT#X`)ozZnPeS-81C&bnk~ehQ=~#XV){_C!6!IQY-w!pikczCn4VM~n(lj>r!9|x z_95%qF|l|d0FCQulBKvJ8H@y`yG6ljCJuVS-aqWsLMr>>eZ9yjD7u zzc!mfiNb!PRPr`&{yzXiK)k=v!~#Z5AgOH`d>i;kZuFf$R<{a2XTZzCg_!*#sqDc) zxkqEZ0Ad~0>Z_)ID%8Qj5)c6_+LhHaG|g~bA4b}ER=%nqO2MMhYiQK^BHy)CZ>SwF z+-C)gUU0~-s<+&mB3AAIoGf5;?>_>nAC2ZD0)8jA7uAFQ(5&R{$AKTx6mMgIjka0e z48d7xK3k2ve|z9|M|}gD3r;i=kxE)^pn)ja8gOZCvGt074VPJ;H4Y;gs%*ya(D;6S za5DK2aU>KATnJp!h;A_j2dULxaXysqCNT!!}t&+ED+gMj4{% zt_MDqH+AKIMvX~@(UNeiexxBDFQ_gNSmjWyNQkwZ@bGS=BnLHjX)n7u^CaZRg!B}!eHK2hyVqAOUp_-UzYiGhN zN)+{fJQgvMBR3H50A456IL9@OuNH#Rm|3zbZN9TmDo%u<~Y zS>y#oAj8WxUnSMj6{4vQQG@Te0#qk5BU6}v&V~iEh2N(ma+!T%ORa8eK8Rr{|l~IKg+u1G42fjR#YkidSbC{y5l^T-#P-y-z8A9Pa$pX)pj0_Hc zOQP=R4MD69v(aXo;J?WnFW4`9;{wHXAA>XU2)n($o-6#4RY1KA(yq&;kS{rv<}t|{ zH)-R4a1Y#K_;9Bn>Ayc9;u@uO$5|&*nq(h9?+nsO1gLx%W22|}7TbOG3PkCxzkcx# zuvZe9O^L!l;yv;fn^EV;gqKZc%5jAN$jM8-dE4w}DT#tZ29$G==V=pWMPCiL91?U808h zXT#h55ABtk77!lrosRhIK<(Kq@yD%ZGl8@g`gIV5ZAE|fOg#vXFMyQ2S-eoWKFwIR zGY=rdEYFDtupTF6CKcOHG`W{M91|43TTAA$}z9Q1VX_zmFAvtsS>OCD(d-WzebYXJDCySeRKf2~5MNo&*MZ?_mkA z>?UeBrQ|HYDK+=xnygu?he(RHP?}^hK30LOg`h68TvYge8VXhw0!pchGoE8upZAx6 zn6H(8UrEtDsIL5NYj?#IiXwmg>)yHSrhJ20j_>bE2!5YWoAnm&^qWS18?Rnv<#l8L z_XQyOO!C9l5?dfOxjn5nkW8ddoxH7jTc-UDy@aa`?ziKYuME^Fn|4sPGx@}NvKQXm zGaEQ;&gY+tJv@1C_khtRAmT3xsgY}?B@Oo6X0w$yk_6N1|dWe;nc{Y2TAzN3(yJMK-q7k(EwdL5$ks)(RTDTVO6U)v` zRTN|-SSwT(UF|vC!1{=;3nBzVwC4l{q(F3yQc4L$?4tq%FRr@Xde4G9Ql zwUT(1lA5}oo})!)SmAkUctsdHLBHiB#VUUCQZ!FslE?e&jCwe@5)5W3(j_U#nm=?( z+@WNasQP2gC_Dzqs%aiMaF$N%P@mX*M}hPGOsq6sAH#87BM3rV@d-kqQ&dtt@LwM> zFP2avylAER_ivVe68=k}S{*)axit7fkSMzx!XQ8QGHUaq`Z65Ig&!8$_79f~eo6Ls zgUIi^V-bNpoCgFymtB&^+UmO{a?i}m!OV!|8@!5-c2}f9u=MU-YI%!XVMy;mFiLGb z9V5JYu+_H7Bl6SEQ``;Jea|!c8NyT|1l@`zPU&S)2R|==8#==8O(G5kW{owFrhP*|1U_}TGVdcFyN$MgWD>TpT`$P3WYygD(qZa)%X8uobKpA*t0qXj#fABL&D%#<~qC;L|!S$dU1?HCI0n z__=8Qr8!Z5V8k~cUC-3)oeIFl+-nc(O1ZgF2lGQY-2T<@%2plQstyRCC zT~Vr-sC*Uptd@L4oL0RlM`qasA(Smu-yA3{7;8A7zr47s#@z%=fS$G5 zl6N&`^5eU1EirAfsn2(BZ@u^$75;Z^ylnZOD&Iw~+!6Z6c5FVUhmms^t zk$D104sCdbQB2V_7JOUrJF)YbmhGRTd!8Ksn|65-8fc-gN`Xq=f^Pt+UWA_`{R5Zi z-kVfcV4)n2)wO;}LhS||%H!Q}Z!z}R;f4Eu4L^xd+I=Y=zAfsoE%XMbWxJSYul2DfJhV`QgB#(JM3~SkLhXo-z3)$GF z8RGxL&6~ztu!rgImx@wy6HeKG7(Errn`SejO^ra=7<#D~PD%guc&;wVY)2N2Mw4LLA&CO_9E3YRB>&eGSL_i& z-r#a~HS1M%>_|Z9o)dm4=8mEvh&}@`dpNGS$n2@gaZB6`1snrcJvqyNb0gz~PzRHH zDGVL2r3L-vqR}}z5M{{oo%V5~aE6|qvDC02jFAQLe6Z2-+N!#DK2#xRrQpkH+_a^x zxw~!Ehyuw~psq;)=3k!RSO!0Nh6NEp#MGujzMvp&%e7txmR$8ry z&utvzyelf$tbzLWnW*`HUHk{j*JVrVZOMJf`p;FsW5Y2M*u<4D=2FxR$v}cb7C#MQ z=VcnSQ}!;SH&+y|U&Xe<`y}%tC0w34MkKDOwLkEn91H!Ty;z;ej~5Q4maho36PNAx1t0zG5A zfhr6LUuE0x8Q!Pm0fRlF7db?;yovu!f+`VaT(8}IgaP-yG+VhCS3E$0wzaU*X!5dv zH%SdUoXexO5infVA?ARQ3kqGV53onaT+dJ_-XXk3Jo-`tPMa;R1$9A?@scn&B5ZG)D#4DKYo`Jzb0ci8nr6$ zAIb6{CP76)k4pMno>yr2P7hfajfbPn8T;lSz1SJhu$|2`%kf(-1{!9@d-@u$Al>+; zLvh12tTMoV>UDYQS45bQ0`zpg7vi`k;CkCZH;9-wzlWr*cq|2Ym17a9z4bx z%^@YKgjex{-i%Ogx=19_54MM39nk19e@+(8N4;we;km5#@Xy3`!x!g`S*)z|2IRPF zC?kY_OXK$Loy=>l)V13-;ABNF(1LF^NNq?BYKF2lZcRa!a}QsM%cUb7m2G{o`uw7^ zw0}xyOi@Ifu$pqtpd`r;{8$BT&*PKupreN71~Ws=zxnrM4t(KeX9o_rpX@w9+#G{` z#EH_Y*D+3B5_PVXTf6~OM8;G&HD-jApjY63LZ~I{pwO{N0qd?3OC`7uV?&|$#}suX zLw;%34&a}}K_pZNCP#7w))D}YB8*4}S^@u3&uL-p@o=c%`+`0K_zI%sHi9g9g%z1a zhlMUEDra=THS)hghGMk$!vFHbvTdUNj~fgMTQ$O{xwKzHldtf5+e z7mupv`5~?oz9Q^)o-_pvcjgJ-3NeKNS9nCb8dfoo zF&5li@1sD#K8Sozl~@lldQU9dDlirv52x;}KS+er`qr_K5jXery~w9u>^uTUw`8JI z8BR}$_)D1tyr=j9c7UwqnOs5hh+9!@7u>?HYO8$x{EU3G)}!81NyfCPk(l+}o_q;@a1KaQGEBIgO^PjNWRw?GHcAj5!n>G(B z*K5jZYBr0D2UVvqfT%MuxmCQ!U`23afK8?BM#+1Zh!qORhGGqZ0YMAuMfyhb!? zHT7;7DBIJ($iI?)xA0<2P_vm2uM{9-g!o2{wZ-YppfRqJBB^flR5k z@vYob0L~d@PW^s=qm&XLtth$KGRfG@)yX2Fe#oN^>C}s4kUI%Xx`(aeKe+SVDrb{2 z^(Z#1lXO4xE#qBmH-I#<4 zkrZ7UEk0>@bZ)&3p{4@&p95ikw-m)o%KbCpy@B#WSgdrA zboni^Nh$h!Ty=Z>rLjhIyM%g&7_XzoHPBUbKf>4gWeOjP;Lw`qi$c%nens*ZNfAfE z|B7R?IdWhZa2>dU)Rd4?%NIb+Q2$XO}^3mr)Gg&6DN6Djb{;D>)ba&ND1 z&a15a{g~^2`|JGsU0u+w;@yKi~WNoV$>l z(8~V<{^)!7dw+UP0~22UJA2=o^RxKlJNx7LedC<#yZWe`>I?g8>bJJG|=~rJV5H+R}Z0zw2AI!Q48`^ZR2z-;4XBdKZ7g zj-<)>{c!8F+xn|&#`GKF|GV|mYWTi;^y|Cyy}QK?{?qyVt2@I#qyJlKZPV9EG@u>h(fB?AU3y=c%|9s5ZB^ z3?GYP-&z%~=^b{Sz1c?iOJPrMPSRsYBen2Ze!B+B63>}@Q9-H1C zp-V#whz7JnXKRdksBk7uE;Dm6(~l#CWAjlXno5TLB|@}&N4099Hu-yApI;O4w+UN~ zn^iM9^-H||oZH}hTqIBtINd5dlrJi$gGf5t4anY~CN7dRf*{MiJc0p;RI*DTe)8sj zwj9~l&+bN-Ea@7u7(_<@_D%ekFx}+X8rUL7EO{yVT&Y!Z1dp7(MhZ@m=EP+JxqCv{ z)L5-W+pMDX=%!=V5JK;fNsH!7kUn3pG&^MN-%e>F{Pi9cpgYYzd54B$MpR7Czn9{f z&N4pbEN9APw-yCfcii>O|4NDCK_+?;^B7dQaalQ5P!nR0DoO*fW5` zvLJ|=Nw5Frm#)0F9!e^UXPRJ=S7RouxiscVsdHDFDt0H-dV>8~oridJmP&oiH)_L9 zd*N*Hg{V1=4mPm!BqO^j&MoJqB3K8}3LcHvW+qYov37+x5 z+rPlvlAwN1?Bl}Pm*8%78+yRr#O4#)$JoQUfB5aotmUl%^ubzY_$LVf{^RzlLc7u` zuwPn++|@fJ9eU+z!H90fsxSS2{(Y9)9JHzx7X_v(jv(tQPJ?bH6YQ(3jQ13)F@>)@?q7}{{rg;{;)aH1IL@Y1!#sc?Dn*O!eW9AfpZZx~@%xlWD z+ET>t!`64$&{5{)5eCzWi`RrSVo1$#}6qfUIIW?K>wSLwoPK z08hwtnXbF?H0a_@Fk4)I(Vq@`dY%J_`ZMt2AC(+{7}zy4$45r5Q~i0lJJ&-&SyHEw zG5~|47GS?&l#jrtp23fqbNY9tcFr>k7gg;)uT`lX##moZt>-R*zm!wI^Y-WJZ@uCd z&XK%^vynaMt;0P^78aF0)J>jPZ&$5j;Rm~43wxgqd_;1%Lj2Qz-m7=_SMdGf`9><{ zhFvz<9Avnmw}ANobhp!Uu6^*i=l-=$Ovl1Z#G}KbQC+xaI)fzq&sN*t%N@_xDZl?p zvCC@6Gyx0%po9+azeqv)|Cd72z{t+f!ob$)|JnVI4Qd*8TO0_!dwPNl^tAdDJR-OO zCqO2%sOYjQe57MR?0D+qjsF~m0|^CpDh9@62!Qf9}X zqZEOE?^HNGwy|RAS!99u$lqJ#MBO%}lOy0F3N%Y-fK5-16uz=Z;A{^WYS^TpnqzVa zW;4o}vPxp$1N;Z}s;$W76W~87N&U>l%vAPBZt?kgeLun>JfB~br7=#x=mXAbhhaL` zhX5td*}~Ee=*W^>ZQLC2K3ehCQ{C`nTcPiNlLoYt07UCY&nN;d>oG2k9T2EHPjEoF zuZ;%U&arp!fRcaogmZ5_gG$R80DQi|0eTk(viBhg+BWM>n*j{;5*Lk&CieF;0kO}H zc;d4HAZ`_&jr7wN?cfOm3PO$s4JeEMP<9s|$u@B(cYbTX@4G~J!XAW=W0&}I`vBE{ zH%9OoCFqWSOa2lMxf%{jki8600MS40gvjr6wTu5vEB_0?eTRFStN7EKgXG60;|EE* zC^q|5I3T;xpnvIazhAn7;t#v;Tl#*pmYtjYGf~b{`o{Fq{>EKI`;#pgRQ^#tzjYWe zTSN7x_?`KA`8ny8yY7GS%lz6#bN_{ZwO2G(L37Bo#x9#J7`o@%->`QxYn@+{e@md# zuF0Y#ugqYK#aDCXobL*j>AeWq`CjWX{vG?DHleUcYq#(pBUJuZBgp?ZBSh?+CI8zb zWL^G835_k=|0vujXoA%Kq-H3*GzehWU%c4AH}rTed!nlNpEV2>weYvbB&Ri3b|i&}y<#M>Zi!s;oqo;tLl7T24R-|ShgQSHbX98Z z#fo+9%OCtvugYiwQq&%}|Y+X&j zY0iDKhyCEnBwtZu&C{JbxU6mk&euX!P#yJXfQnI3MxFS@Wn}bTdE%9SCNmR^nt#Wh zG>0Ov9N^46JdIcwdh*(e^hiNZ4L6d{G>IlVT5x324R6nmK9S{{qC`p;Mq59~Mti8R z=s=P2p~bbI@`!#YrHkg$o=6nG)n?x7yo zsSE%od|MybQE8`Ev!4s&zB`;{*{(74V7+b82X;793+MKN-G;mYqCZe^Z;K?A*|$1? zg<%QSC49v5fj!=#dlUiQrBanA)`Mn3@pywuAg>Gbp6ApDG@zP)bJ~=o3yQ4^VMTe* z2mK{e%`-g+YtN<>ewaBDRwyOQtpZiMcX*q|geuuV2^mKT_D@i!#uabGz|s_Lg#k*; zMd3Ehs^sDhn27oZbx=B0%uCf!#{&BNnJZ5)+cX(jq>?D)kvT1bs1pBFM9<*6q)7%} zFB<65@R>=Ki&8~@VRPv!GkM2jn17I1l^$tb!4tQR2MWJQEhOmbr!}aUf7OXlLeV;} zQ)AgUPW^1bli25z0VJ+L<<#Ggm&vp!Ia+d3P@rNw#Q>F^T;2-^ieuP0@Ii@?9RRrQ zS}*P;Pe50gaxM&5CIz@w(UTXix;hIFTf@Wy#i1q!7^iK2jZzK_(Bd@N#tBzO;h+#sw~VJjmIU5;z|k;IhFUeCjGFZ#)Mz;=uN>*kR__nF@7q|jR4jls;& zIfR!YK-M^4SYnMK=ATqMRVN29DU;!%S9s=>1r7)8$pG-PGWPAe_Eh3fGROQ{{yuqS zL2WX`@btBRX5u?4<5}=~w-x>T_@|-#%Jms^G(NXY_G~pWM0L(CqzcdMYp*jJwy)P$ z-@&s7Uq92cpVm8P%`wXlD2tkTrjbp<{!;ikAAr9!Fa(R+Ok@EF8xy}WbZ)l5O6?_Sr7|;nJ_nHUo?IHp}$3oZM zE3+@jK|lv%AoOOtzg26Ypyk+4F3$BrGFFJCeS&W;xD|7X#eu-#%n=y{`t zI86k9SQWZ~q5&T-2pa?hYW@M(C^cr&)Q;3mthJQG- z3Bd;DPquH<5eUf1A()%gWA=#$Z1+<18=D2R`VUCD$8SbhNo8GQXOI+aoYWMBsiHT=_ zh_glm8>g8t((g)h*brnz`5M9a`q85RhSc7Hqoz+R3sVn0HRsC7+C~3>B$GlJv9K=8 zIg0+VVom1oOd`M-jtBH$D-p-?&tC(?a2sryS5M~#LQ1;xrCTnJ{t-$jzwX*X z`0cksxJ8OtQdt6?CfUEyfwK%e%Ql*wM#jpZs!#K1LG2ut$w=) zav&c7-1(FR~PSWS%RE@OS@m0 zV|KM#w8G4UJ@!DDe{G9|CI^vb5z3SUe$de|YD77_9+A?uSv6Ja3bYlO^3B=>{Q9Q> zK^x(eI^aG{mOKV@%XiLAvp21J4eE-~O8k&r0d?S!&D!eX^yJVA(X2l~GTJP$qBF62 zkkzCR0>YlX1@#Cp23m%CLTw*^in9OQ6Gt71Hx&s7`|*19{Pp!Lm5KUOLo@|IhDA72 zws5D1^YfDMaB=>2P-*>TSK)65kSMU!D52h2&Fm>f3-XhdMFWJb-lks<5mb{N+gB>TH+sQEo$zd4`6|8E8whfB%s9zv@JK8XAL10+I=3y>>qIbAf#TkPW{;17%nYoo+-g zi(a3wq%tjeRto}q1nw|@GfoW05cAkkLn;2NM`&wdrHRIHIv1T-p?b2EMz!Jh(HA+= zA$*fXk4{03cI6g^)2)5p63^JV>i9}cV3&~Dp`y{IWW$&Gt1-4mYAv zc8$jNCaFa-sfGvA6*6G-22{}wZCBa)Jav*QjI}@OM9JrCekn-z?S9$}$d2*j%xdHw z3*rN&94Z1T#)FE{7o!8{K?_yK2>=I94>^&(E3 zok;z_Q`@iG!mqJ^xmHwY6;+X9N(vjSqYdZoOqn#I8Z#xI#5%6vU<}U#+))x1L*heF zbH0YbB6Hj6oI?8TES($Ee73H)_)X=FE^6e%pFd#NlgzcDOXZVNbw0&xZ7Ky9*QQC5 zaEzv~{v{*J`Z6j5S!^8CAbXaxPPE(bJm{}|hGFC3K(qsYSwcS65_1sja4&np_N4y| z9iP#>+Z_Wt-YD-M_Hm!>PS9>;2%G!65PS%4=Rgi;^a0!^KKnjfid-S}rEe@i(?R}a z*FXtx7g7XsU*k&9?qvwO1bYx%C?386<4fp*eAhk$mbO=SPOB3Dfq@;U`nX`;>wtbK znQB?@gmh+qnezGE{7ePG+mZdu$dPWRkRdOfU=Ly>ix2AL9q{uWs{Sqrf!7)`N2W!~ z8yQl0*|OWI?UL6iv^_F+f)`7T@+2~j83Uelb|NVh7_STL>%BdiQ(hbf#%h;prsoPL z|5i6$Z_4lf#QFnElG39LOO{@F!TH#{hW-yq&M~@wvaQ|Lv27a_8x`BA*iI_8ZB$sX z?TT&Nwr$%t+50>AZaZzCd;hLKbG6x?-ba7?c-JDrII1uo1jbp2FA}Z;H5LQxABz&F znOvwwo2hDlIa+ofs5AD`@F;PKrf{dKbya=JWJzzAcuK`Q8jJVtP8&>3>-L!dh!F^@ z7TYs_n=y2NLVq=&b*V>G4P>FoLS5zxhkoy~?eb17^8rTpqvxu_?z}jaKX8SDeq?}d zJcCd+<=|g|f1LEXEEV5ZV(;Ae$-BAwt5H<;4E&A&4diVAtpJkmiJK~kw!;)sc?vy< zVN0zeQ^yxlZUe#xum+m$*ze4@x@>r%PyU)G>z&-Gm>9IM(kcXJ+>c9bcx<|I>h??$Z?X(EiC3 z=>EYJ#I2l+?Cg!c9N|Ac`^yoMG^}&kQ3f_16bK%SL?}U4k|a?Xr@2mhD5=V7Yw&%4 z$bzc(VgT)uy`H)IlLDAie#Kj0sk0nBZa!Y$=mhV`bevv~E?)kT86gr{td8yq6K;|U zBN6)Wcv-uhN?fX4C+TO^Vx=Rr1ER9|m3lDfvSoTb9T4J%P>qYYoagaUw;DLeY60x- z>suTKlayN|cstEpQaEJTvZk(K7O%vANLX(vt9w~KGD9mFwxED(ivSXPPmv;xOe|AF zEhMaFV>m0V)P9Y?Z9KKD#4=`8hf(J_W|q#6-oEu|3-{@|Tl`H3geO(M)f0(`CyJY#e`X06wxRDbCue?GX;=7DzaMXI|#Q zcAOm;CrOR!Qw!db*G7E*p$MjnWv_v`;=voD#mbHJ*>w2l z2n&K2w}<%K_k|kIgvnHM2kXS&167#IsT!etT z5zr0ePn;AqH3wYD>Lgo#O|~&&x0}a-%s#J+6VQhBhv#yQWpT@9x}vh!9I(6xU9}WC zK7(oW)|;{NRx6V$;TdUJtZ2EWa{~uTmg6HzI7Kv?+#J`u=;OyDLGG-rKDEQUiKUsOKAH;Qk;60i;; z0e5*eQy)&eLQq}l5?#>L5*{92G9hTt8CN$t2;(iywmR(h@dhgFf12eQZ1TnrZ+$N6 z>~4SUWoUeNYT{Qx>M02@W@z-*kXjwRijJZ{ji{f<-ngHCiX9w0N7GNN9Qt_L-*}%( zHN0Q>s{|FI_t&EO91!Ag|H+3K{=tVtjU2u_NWfI@uQ@@)+Rnh}Uza61*4yj|-W{@f zO>`|tkhVy{c|@hP@GmyodGYt>z+d-GB zBKcEtt4(RL<=Q=q2c=VmQ$lz|ETV0>Z~_sf!biE{yEm8Cm9tf?O(?Z+&xxDWnw*F2LX5E|R7Kv=Z%3^U3SAzueRORgIy`y;59QGj~qY#sM#t z7)y>d2bDrql4CqReuZ;AGI;X}(&K{CD7=D~PT~Bh1?m*CpMZjYk^_?zVS;cgdK&>^>6cLOJm+!*pQY3JR&DfN zA!p6o!AH=^I8((zU9`Re%|zVKKGfLswNeQ4uxBP{zXwXzqU7jn53EM*eKur471a=6TQsa@A&EgoPEDi z)WMd0CMTma)X3A%V-o*Vt&Y1t}R?+gsfne(MY-jgXvPeHDK z#F+AbQ^`_zRoJrwq99BXb?s*LGIXM=W{>&n-s;S8;;~9-rFZW3(MeY9Rp`4LomkJf zD}QJz4iD9!(&=#@z)Ssv>i4<@uD8yde??EDucErEVaACrDYdX{aXN&Dhfu9_K(bdx z-A_Sibh~6z^jmsw58~>yrBNH(MN1=p1Wn@T_{k!;Av{)K@OGX!f}fVa8?th(K?)_c zrjb3?GyL&~|4wUo!^6nC@mh8>0Yi#buk+$Fpg_y*wJtJaYIO%*#z9A0f+|C%;7vkV z;`Ik!?l&TMjwVg(>P=#R{CUA6V&5&QRbO~mQC*KQM=5E-Oy5hi}Cyv z&6<@q;iEl+xFf(zTg_zw{HDlNNi-|Xm&z&3i_ssTqLsJtnNJqib9r%4yMJM;Q?dv5 zL3{cdvpkdS`puzN01_EPCGHJDl5Gn_JXvbJ`A5`xM{(5YY2#K`lY zezYun96566$h?(EF#uqi2PF3zIkc!EsZr`=gL*DP!AH7#J2F`2+sG2jSBTM z7R*)IElt?szpNO4u}yK8Ouw0DcZ7@;%6MWYBRg7jp7ISiY4Af9bFhB59Vp^TOK z_(8RN#}*2YL}r#fHqiB0KF*;1&Cw2MMg^O-_^ISko#oDY+FkCWaWEcLG+9iK3(0_% z7*v$t7CE89Sn>*n6DB3vO#)Wb5G}vXQVHK@6&46qmE#wG;smn2;qmh2Z7FR0W}3a0 z0Ny5hV(YFQFfrF!-gSDMKoxJ39&L4^w!5_u)K=6CMD_AQu*PCK<7pBWEWc zGRfIu_4~@K$MJ!u^VgP4>Fdf0&}D`>yQREEXGoD!wIM$?rO*yuPuri5gp$izfgIY0 zj-mdO5jmzm7BI>%E9SA3fT*~hD*KeB3?OP_} z|6Buq350-WyC=T1ZI0cLihA>8y5G}`$3VqvhM=%j>tWQX4;d$H=MSn(^voWa-&Nf? z&MNyruT+Vk^&Ns-EmCgeHNG{Cp>kGz{KnZ-?MBj5CS+lIlENqg2wL_)%nl!7x9O@QlOB`NPpY(0brIzU27V{#d?cJKBtB%TsZ2T;X+JcOD(_Y0J4vfzI1`ni zHW-S>Jc&iV6!1r={gxIn4Pk(vSLF>MkogL0o2XG%F|P5^#v>#rt1))(X7c`HUF}A4 z$)s@9oL0AeQ?kGgwt@ESQl#)^W^0&sBa`79j9{jtFtjKWc@G9S%t=ffw5SPlUFWo zf8;lc=C{P^;P8n--#WzfoFG$QgTZItw_egcpFzK%#_V+u^acU|5QX?BsA>Oy5o#%G zXDK5mqrdvFAL2rPqpiGU^@;X-$0ypnWhkACqybPx%+j%BM)G-9@O*yatw7`9$kRM; z*pz0mQBY27ECzLAjIpmh7`+2K^mrU_$DYxE0cAIY1@$vpS2hCzD@vhTYb{A)=r+0)#tb zV<~~IRuQj)GO3Zsj|(=zRsH(Uh(b+NvN!>OzucmpNK_;j)Y3M;5JBf52nN1oBO#Pj zW;Y&St=!#SV1y^jrUQe2o{{{h)>N=d8SZlP8fAraY^FeKYF@bsE0TLQg0+m;Ko1H;PI_p|kHM?K3@7 z@O$Yvo}?OQO2WiulZE=@O4-@a*_;p;>rUHMvFuejrh+QLWq71seT;y&+E9u#G6F7FC!5o$eHR zA;u*mchHT5laUwo=f`>pJEV8DchLQyz|HBE9Zcex^7TWiIyj_{O|JwU|gBYg2*XwUw`U$<{q_ms23CJ?j znjI;Vl&2qJY`(g!n(^bn4!U*d#ZB$nLeUOY&A3h6V*rWxjBf4ER&8um;WzfkGUExg z2Q^&Aua&d3>?C~L<=jJUg%;e%LVDpoF0K-e`fsv5I-F;_8h+WIJF zpR5WX?T)7g-Edp!CgYyx9>}T}9vX`+VcYyJdXNs}qm>K2q%6UPX$6)0w3QGE0mHVz z&!7QX#`ubAQ44?sj;K&e@Fq2RbJupJW*T>|s^mL=-2-vWTy*2m_lH&XOs0Ja3CB#8 zn4{t-keIG^kBl61Y!Ya-4d9|il6@EOF6q%PFCDFcjrL`&b8akdajJ*s;MD&ST6Bx$ zz285CETL)V)%R7J_EFM@h(kDxghSjc8Tf;s>_Zwy=KOulnys{QXKd^(RNrk6;Vt=w z1TV0E+#HrOX-g3PhqmXTg!qnB&yYOrABV>BLLF7QMT{ts6gD; zLD|9NYUOn?J|cy_(k}~mSzCLA*8{|yOYM?>+J{rK$F#drj)>M~P+0ASR0*60<+nmT zuruTxH6Y;8TbFI=`p%FO-rU*ezW5UFM{HlziUp`TYkyL^2=>1%JNy^53Z|Bh7GKu< zzaTsQ7qZOapo+_V<&38CE#L&YAu0yO{g9@aUITD>hF{1c{R>(A)ZOz*h+5<3J&A&U zq)$60gI2OrD|~$ELAUn3sLuOBHh(FPJ>`V~vZtWSq{pR=fj;cn7Drh;)uPAU^Fl?_AId-fv_;($}F$6YTsmX<#XRCJjkaOp&sw zkQ7yxuOnQb#4(rFZ}4b?b}Q)F);KE%U`L7;J7n*Se|rnEsOM zAm~aJk1+?U&2|2V-|gNj*T$-Uu%!N`8389?Yr8oQj&F6y9n{Xc{W+=(YMiSi*GKw* ziISmhn0Lk_CRe}Z^WwU+1dP^i}eiujtwi3%k*D6y{hYpTEAB5ek;Yq zKTj4a{+Yc82D0^Q8PAU-bm(X|K(47Is5ddK1KqlUiA}!x-jnpGr@&N8)>>#8t2L%_|hQT55t>(XWLOe$p>8pk~rw#KUiWOo)Dlc2}ngx+L2D>sA!<$ORqS| z!pbDu##~_?^6Y_sW3TYikmBvbj}TxMYy35#Vk#g9p6Q04gH<}2sqpzwNxrbjg<6g# z#eYg%Nl&)Ep#A<9u_`gZYEz7(Wjga1@`j_9;IKEZd0A^zTFj2&gz=j0ov9q0gQ~ET zfN5wz-~M6%FE%HROs*}-(nY7XqitcRg4=`2#K!Cmf5jx+!elTG!`Vg8B1O1ux91(` zKa`waTjbq&Mc?5TqH&e?ri_ z(tzMq*NG?G%U91ouRYZu2DF|XFT;U3YFU=f4sBEz(KUv5koNXzyc4jD`jQe^i*%3% z85h?8jwqdx9RX$~-qC9WElxl}mxV1!A_)0$`Ww;J7@4o0d5jj0p>Qbecx}S}F z$s0CNKmUpY2j`p<<@b`>k|nP|@CK)o0^7B9%h7e4u#0}!1LGWIeOxvF`KUFL8?S-g z?{t}O_Y*Xwcx?ANksS2&L&mBY{>K@_`dQ?XxlDGEMm@9yWUm?)5Klz<9|xmadoIrFwU?+`rW=E)SU8dcIACp3qB6L#j<=8E%Ne?@b1VIY(>^-QWlWDI1o+K@~)*PBcSP z#qn!%GWDj+ml{$KY{@xsuG1gtSjP`rcPP``KuyPwh$u>r#%R##$x|b&-eT0EM;Euw zqV331PoHQsTp6Dk9wPoL!zAW7xNKA~i671*qPtV{ZP?16Xhg`0u*LxgAuWX=p$6VO zMSmPA;JYJxXJat(wXY)J~imeNgw8CO0Xr4*HHk2ZAOL1e4eR_KeA{_?Q z;xc~f9>wAVj=39F4H$}YXgmU%dZx0`fZm+EK2j+0gtw7??55($@qWO<1p#!rXSRh` zA(A$a1RO-DD?R!T_`i`Bo=v$&m;b^D+6%yNOS#Rx!MeR)|H>Y6HU2sZ$r-gj%Ull2 zA1DEDUmIY|Z2c<3FcPcxSuHa;FQVI~}nB{21<^S>`?w*yGnkbAD(`;On-W zgRdKr0UpnH<=Z?er;d~Im-e{lv(ui-{YKd=aZrtxb^3vq1J#s5$Uv%-xCIPJHq!;( zDFG8E3qvYfE{iWLCpQe*Pk_oh7rtf1e$S37A!=dawfnFRx1HJWN0#K0v8 zXZ^p#`U$O*g{ImGJiKnCreCE#`7Cd(O0X!Sb8h}+A+cz0F0Gh1Nmw6zsXiF3sJ$8I zcneC$q!@m@50l6n@+%MjT&8-jn+-Vx?gRE6VoB0)f=f1<9CRDDI@= z(Rlf*jeMJQBPac(1=C;;H@rC9G^rlR;j2zRQJN*%PYuNcLlw!9nyR-5f}r$%F7%l2 zTn?OljKVYDeVGcj%)Nh7oo&u#)EOrJ6q8V7c14y#gYKI()p2r$aAi+Qz1pyqBZ@Nub$B7ihy)<@dBnD&l~>NKNOi zD2zKkoM1sbx7<5C2Q<)p?knz3c;qwXTSJJ+i3$WBy-Vh=ej!*{t5!`n+r17pha~2_ z8ul0FLn1J95kuec1 zt?EhvQi-yyHcp9hvciPRlnc_y`Nm?6r_oMh{7MD}o&sQNg4hYRb@F_v*O#GwhYqv@ zk^;CTt`7yedV2@iH z5axOQOjj1(^uefkZ8T>kD#%TLbopp1>l#05_xPO!W&)_V1m7ZAQ*=qVZ^A9Q(2~im zp!;HWE)sx2PsM?=#k_KmGHuVMJNsy`-0p zCI|&EY1&rfRrOu8rz;J&cLxWq+ne+&+S$rKqF{4NHhYf??TZ(F+M-ZPKs|KCejolJ zgtYuyHYkO(5N#P4SLIqth5g+r+PUm`T}{?c z>!XbLYuW&WF&ABdtF|-MsTd{$H;;_UjXEH)74F^Q9Xl4q7oNjYjXMMmHjA<2UO7B< zJoPB3miPy_GW}m>Z|gl%Qt#M?FzZ?CMlPMO~{-)uRzME2;-~y3Zb-&ym=QL(oNCR;R!pH;FDL4V}kCHgV(Gy)_-`jzv`L2$Ea} zKf);Hu}MMwRgQci_hdh^N|)A^GUMX?n5etSczfRxzo#o27l! zqvbK|nZsrWvO#j=1w8Clyap&r7`M+&8i5HB%)KQ9P7m$8&)xh`6n|(FObu|&w`>vF z;0)^d7$~Ge&Lw?>$BCi>n{+-XB(?#GhHN^UX-xrMB$@*5Pml4YW!0XoB{V!FAH0_% zp)b*B7>()fUDX+J=q7jHsE2l;!{#`7czgw(g9)aL&MJrKglmwD`cvP7BY~kULkO`9{M_))SPn?4b0&@MbI`$%{TB z&hy8I4etC=D$5vqx&{&M%g;k2@Xqwj-|SF1kF79w3o#tt=XCGh`H@`x)L?TiESMc( zB!3Sl`OEb8mL@^aHvkn*TJ-gWAXHwuhL`)!la?R-&+9sNvvP#{)~4C2-ie^#egVO@ zN2aFMt_&aFqx8=VU0S8}3XOXxp%c`AWXZ?I^v80}{N0LTW!k1>feLbip&>|)AJQ{* z3!ii(w3*CQ!?!1+n*=(e75ScOe{2BP&lzJk*?I8PThF7(pX^A1oCLSXWqr`6MFNGbqb@L75KW*&=E; zb~8LK`dbi0Q5;EG+@3`Mwk6PqM-e*Bo4z|d8mI6R(k(JBF^fJk6PcUCrXX%2r?v}S zjEvk;f*^xGxR6Smu`iubOy3}216}(sG&a0x+4+Q-25^cK0p&zlBZZ(xfaw-FOC<+! z)%VB0jJ}wS4VPzL1Fn=+*j(;W*z#k2f_K#Zf|Tj)iM@-HrXd80@J1ThOKF}4;`XMO zODf5tjN}NU13cX&CG1$T>Pc-Ke~TvAJ6_EIu3wQmaioNjuvXfjgew?b5t+A70-@k{ z9^K^tFJMIOrY(9&l{crkGj#_+&PE?6+}jHvb*bpw z*RY+1Tg$2gw~exss-DEeF5*14OCzuDB+?Ik1tsygrhO#5sr`D-{tD^jXTovJuIgXm z4hID(*(zf!n8InDZ_;D#!QY8H8|MY>bjV9+20*Dir^g%_WM<_v%+_8W(N_$W*ZRO0 z+Q>N;1%}9$&ADzShdtZi>=UY%>fIz0X8BmqRKw9)s&bU=Ga^y7Z%GTQ1qEYM&MA0I3Mt^`sa4;ZC_x4BABebvDdoSkwWU?1+wZ3Brc#c&L>^VO@|_%p0d#L--I5 zzNd&wPQJe$?|Y>`zPKFGFY#;O{nK^0KY+HEefF<{B~YcN&^7((?A}=n=SscgQ|qT- zrbmhTn^J{MD2lQ0{qWJ9_-5&%a;E<7*%oS$E>pDl74#hIGLiJ=feO|1_u)ZP*moZv zjZ6>DlSh(+ipdQk9q^lxkgzLD*$Tf%pXLNI2}5`Fy8)0dEm*|k6i zilK4Zv6`TqehqzfP#6HGtO(obLoe zw*fc3^}&s9!d7#h46Wx}nhKUy_n)suSw1M3w_8QSJn)lhv&G3j-rQA%szGcC9Wj%e z9s&;!GHjBtz6LmFm4UN1XShCuSpl86is3tEnq?}bi?mB=m?w*4So9AFHS-Xs#UAEs zaOzr2QxO+(vR=NNyjcjtr@(sDG!w)h6h+d^8l}Z^U?5Wvf3l8ngwi;wnvriCHll=e z`yRV9oA9kh@C6>s|+_5vp(xlNj*p9=+3*!b^ZHs&0(3 z1UbS!jWw3`ldv<#;vO=I(VC920d$5edgKv(5QK{-c|zv$-tuvvUw~_mNWFy{%aiN6 zm+P0#Rp6ywhDfEo^9t+!L`nyhKQO#`L+l6(9uPZH(cCEPK&iZ6m#cC{qYG1fKXaTL zvGF?;E<(uAop=QsKLWh9+uJ?h#~Zy$Im}K)cBj@dXOagqu18s+hASK`$e1pjXS4sI zWbfU#cy{GfzReEm&H%~QZ#7f$7nE(0UMnbrfEyJ;|9)`5oNBMVr=?F-r=BWreRf-5 z?n(DYD8nbDS1cyJsro=d56qZPC7bm&>HSu20~1n~5pM^DD7bIj{<_JQ=md4SB{E@s z(UqfcinQ4!*kZyAjMtbbp-n&g5w#Clrda*ji?My8n$9{Tr3-x4=u`p?J8xy!s!a94 z3bihvc7_)Bw@kxzq*z!F~Ad0?3<-la&wv>i`{{y4;!K@(Rw|fzM6Uli1o ztS|G6Ze*oRvk>?pQ$b)ei&Bk7H*>)KRDa-~p{fhAqY5)g#}W5cS|?2kh3E`9r9OTg>E{w7?uE6E}lBHs6uL%c13+N z#6zr*Ke$g-%3slCZk(#unF5(LJYzj3Z_61+>K6ydao<^$w^ zHF~;4HLgg8JKRaE*p^pWg*Vm20o)4W^H*DQ)iu z`d+|-uO!S={Fe0><9~+#>2$0;$zb@oxTus?ugo23Ea}RHaWZeP>ni_)ZeFK*OmNqQ zMevkv<}a{u6yo%^UBxm93AWpKjpMYab!YZu9?`@pvo?{(I}P=+QDaMk{f%7!(bT25j`cu-|{TeOV>PZmR{EF6rCR<_h4rvk7|UP)lOgU0!CPkkzZKs-~cj zQzq?wqe}~aavo>TcJp~nmBLp&Y|qrmbA1DWUwed`ofyhv*)yQaI0JgqTpMACUy{Es zi_Z?Z0?**pmkgyYZ87*pTwbi^XxZF03rQ;;5sl16Z6Zt2_K8iHSC&Ipz|qLI*^=VW zF&aoUEYL8aYbUvR{W1|i0n&HvCuc*HGO5iK__~00D0l|*wf$(uaJSr8 zANaT&kB$G?&5$jt7X8Lo0?BDWT~3G2AZ>~{9C{A+Ylp!t$|hd=I;wzEI2!^Y;j)5l z9Rabsf-79QJRvMZ^Y?=X9}alkc1FoTz#LFo3=a)6!7UW~*jq_6`N86@*4WCcT7Mus zaOR<63_80Jt2$A~@gc(%j!gpX^Mc}*pPB}G17F*-@cr#y2uA=Fwn^5BXCHjSHN#?w zk9%ozs+_BoaRlgsG=rzR8)~1z6eW1Qf6lyJEMC&rs+LswC6CMF6SHYe1NC7a#R<@5 z8n|8-uo^VAvfgkQva&tOA-vvAxKrq>=I=EF9zl8##UeYQj*p-@PDba`a`wfai1zW% zSR2Y~uPhjvs`rq2_J)~PAH+CJibG^{*?VUJ?5*?{-4~*WBr_DIki!=le04fidt_NO z1-oKQ)fRFM|BQ(U$iQ-+6Y>a~pc}4pW(BL9RrZQ7te}5v3-G z=xg&S%vq+v*=LZuZgv3i8=XpDZ@_*EJmgzQni~UajKbgFFoGsZm?$W*x$=S$&^YGp znO_yT$1bhh|D91uv!DMFbKbmqR=;*#h@mx`?X{ZO7DS-O@|q*mUBbxf(O~mA{V~<{ z-0mO7F0I+oVeLpM7EazAr4Otu=|q&W{qtiT-f3?Hw6NDw09#YcDeVV|Z`bh=B)W^b zh>CT|qlnv{fJJ1ocTwBFBF(^2X)kWz^~Bqna-p^E^-Q*na6?w8F0@H9imsmoP9w!#=6yF{ab_{s zbTbr&+c3CE^{xIo`>ZV1y0J}|l^QE_DPjAv({B0dY>xMvQ{(x}LCe=BP}dO`8U3Bu z>h1%`4t{AI0s-1c!PdB+%y~LTDMP~3^@`!kncSWD;ZGG_RDC`bNv^KZX{_?XMlFv? z-98uvnEfbDtC!CG!x|T2xE2R_d0|#oHeGLJ764l?Uj@)A{Zm+1NlTs@nRA4aE#qn} z>gr8&d9!Si`=HEEFu*CaJSz&tY>J6J`?!YG=Zh2Lsrt=7nRn`FfT+b+&ZO$Z)M4a~ zZ>r2}p8*B}rRpW@;>ere=_7f|hR#wSF8jC3rJcjk9BmN?bC*4-3CcIFLaNX#m9!IL z6}Gnb@G_{VSIxVq^@h<#;)bao>FpN!GF+-?2CE-6zRLJI2FfD-Z_ufkGxh+P-=E5- z7JTz4?0TsU*>v-{VH?+X|ETh@r1bCtUtw#85uogeIcT~|MlKgD= zv;GdM_4%;*4C`CRKnokw4pv&F91&mRH|ll%%M@kez@g()=eYp zjll*+jk-^c&#^U%{1lc_0R4?L|3R9rvhmexS-1V9s*Izwn&6?SF1>dD^^YIA9V{Ce zwEMt3Mm*<=j;V3FrQ7s|<#*xrpt1dEVhgGpsIb|Ya8=G+joD?@%~oA}e9I>`HA=-)8+82i| zwlqD2f@m^KCxEPAcxN(LhpHjX9}x8pHbav)EPlo%6-I~#>L;#F1pe~m3>8?`qz

H9rL-+v1&yC`u7IiLdE_`ongQ-=FZxzoPdDLH324RnQs5gI;Il`GyWj^d5ZzQIn`t^_TP|_*o>m51CV8q_WA@iy0cM{=e04pgkbvWLFw#kIK57;gPK+f*Yg4zj^jDk(_eueqqlw(@ z^&pj2*{k2&pRsOCN=6>zA^i56%@^@KbZnfD=WJLM^)W555)^4^` z{c4hcrR5*kryAuQV*bvc%c#OD<^C$=qm{tQ&qejCcA^4sAyCeNWRI!N(2z5c5PACL zQrxL#?eSh!cPa2{NT80Zn^;So)oH-y=DW_65e7) z$QXlu)dEPrv(blNDTCIql*h|3@kJhs7vvaIu)e~y9`_Hy20)>w3_81b=NcUX@zbA^ z?y7Gdl|h&WKg(u9(6E`p%~x*R6)sX_itZ;cn)v_XsB$D*yn5XE%sKQFC#606hNC9} z(aFd$e`$hEj-)mR32}le;aCnXl{0!D(-5@e3TO)g@ARU3`RI;5TFF0+OX>qmj!_>#E$KSHPS!a_!p88}dy z|504)l#sZeyXRo*_XHR!bV;XlEX?`AH7yKXyCeHE_0Z_-#(!AKN5==VL^)DBsnSH0 zU+6Ks4%gyrNUj@oS$u#XD6zY-crY2`)FAtRf7|!hRA9_ttSAC+ zxgslN$?0S8nz#jgAD&d=DRZ`{9{xf!$gj8=VUsYtvvhI>Ma)# zCRw9|-~E3H*lK5ozZWQ7sA9aSKt`V4ucYP=V~ztg|k5MUkJ-{Et_ zieawcY<#zvmKYdIX%$Fc+~MxPgi8Cy6$jaAp#ecn9nUfQH39S7p+0>)-gf6ms`55v zYLHxi5tXv=B7wGwkJTQWvQ*K11`3?Z5))Q~9kiq=h1baNeGrDKcP;ccGeV3^y%+~C z{2CjA3n5mMI$E4b+@F-yWbM};UXCtHx1ejocYmu1QzV`$=1TBuWvD8m+M}PvY9`PR zL4iH5*~-+;NC@IJ_-#8TQ5-!K%7_QVHG?ao2jMy4Z=>++65s>(vREug5J(YvOM@aI z=@;qnu4f1GF0h>_`W^p#=)a8dh^`L^uw^wlp@1Id;U|8=puWayPt`QBvF{jBaSwk$ z1Sgzb?oE0k%XT9{f26~$|E#BK8`+2@vI3s?z$?K&pKD>h-I;<$m?cLh{K)Gix$?*Y z45ES&W{x@@Sd>iP^Tu6SMbp@hEhQ>P>Y)bn5dK7J52|eK$Hb1=N#xXvNxNVC< z^ZyW!5YU~9hHQ|?M4qX=*8Vlgk#P~*e=tMqMXfEe7QM`c)l0gZkNMYx1yBF{n}3Qf zhb>0LY3*AhlN563k5poZPg+<5!%Y4;?Xhj(6vPWBGyzoXnS2x6^b|IXNm-j`ujMM+ zhVU2@qQez4{L>WynPAcy8@mS=mCwH?Z)_r+I*vUZ#V2B~cBwvU%H7t8V)r@&jA;~y zXN)kXfo6`7`YI?EfV+2UI)$fb0x>X3hjfmSBy%>L7!@Ot6eNh4EdsPMr3{DRvNMBK zAb7mo!Eyk!uP?_WK-kZyQ~pU|Xb%^5NO2Y+&}7PmauOYVoV}6M3@bS(_;6-OQvuTb z1v*WbmdSFXLa9pov(H|S7edsm_Kh>;hCva*ewaoW*`~4a-ho-iH)--fY`c;6f!bHnbTrlv=SIK!QQfP8a=a8 zFti+T+G$_VH1KpvB)ZlLfgt^EQnU?Olz@N4N``c; zth7tP+1CUXO`{uFWf_p9fQdNusI3{IS{Y_ht<&bBbLAl5hvx>gSnk2tl&>fC^G~5C z&Qd?@q?NTRPJ!)3?aB9@eT1+yp=&4Qn`qy<<|EHUvBRe{C#GUY8ZJPyw!THE@zvx)TWJSrr&d4--rG%w#w^rpAq5k+dpXJ9xbg_1@ zC418-jxz(-Q3|1z;#W0G7%C5ouG>103vN!Baj^>}10iB;wcj2_rJJcmXr+aS6O-Aj zxYi%4w)Be+*C|ZuH(&}SQ{xZegbHDrTIG;+#5iv707wotH(0m>7Fwnr&Lgr-6>3%X z?>yQ~zp-iNJ2T}?+!RCZAS|$ierZl)_?D>nzY+i`cPUgV9=CC!T1pV1`)+y*VzWLR z^*uRxzZ5MkK^F#Ahi>HoSfbRFLHXF_M3O=%F-i&`FmAtt@MUDGd{L|th)E^6aG`%d zZ&RBDW5JWQVThGb|4M~MS56QGFGdCDewX1=GmF57QCq9Hs)gaFWXl+p+uCj#?ao^D z+CBz;MN^h+Jv}9Vg8n$A?1y&i#vwl*upoWn)Vw%KvFu<=gj#e|wAz z(|GrxJIN&PBgr?$`#5 z*KF+qBa3S{LRURAwyzrzN>p9}gqM?IYL3tc{`4n7FHc=0LmM^7q6(rBc)n7;;5N>b} z*OwfbD0jv^-U0l@SS}Y?`;KvAmSGjlW&KFmVX|hT?-iX?x2Q$#^0lUPy+|cX#|gqf zxo*i2dy4C8WVyC3^NF^o`u(()K{dLtq|K$1NZ*_AAy+fjCi{calhnVg3{KyMl}x!S zYgT}8ch8yjBn+!7Hnc$`PQHzQuia+Q|O^SxdpkvgsuE2i0ya?}WPq^Ow2jJev>gR{H*)o}P7?F8U&` zy&5)$rof{}`Ea{#8@qnCp1)dym{75*P0-ILptK!6Jwo}*)3+*Qs9wh}Jjrg8HBB)? z-tplr+h>AInlXv2%p4wI@koWjN`1aG#jq%-TajMB` zQ&yJCxjEXw6X9J-hPuA2_OS%Q7Rqducg3vbd8+X;CN&JU!Qo!;e!Bn#IKk`nX+TT5>y_P(2}KGybTD(qr-X2VC^ zR&HMjg4yB1f&=V8bVqr|5Th(f3&Z@v;R&xiI|iRo?Xq<5BH669+w5d^;+chr@gD+O zJ}*@z`jgS*9mTqeu6eWaNV7+KJ-uuH#Aft_%R+Ge_=x4st=69i!*VYe>oArL+Np?l z=Lz#RFL!OwDlq@*&+OS=xD7AV?m2seIZsY=pQ)%H&2EB z+u-la-KOvql!>%)iM7lu{e&QZLIK!>a2Cd=LP7eOC_Ec&vUq7>uz);zfK`9kpCu_0 z!LPhp2+Kb}4=qn>KXo{&I4`RFC3g<-&ni&B&tMie;IENl<~X)=6Qo&O%~d%+2*A`5 zbpW6r!>NQ^_i?bmwa;0sY&*yLl8V}h4!)&MM5j{Fa$D&{j%xEt-j@J8rL-m9wb+ZFLJ-saO#tb(a*yJQ zpii9y$B}m#=Cocz;X*-&oakFVI|3LYYDk$#Gg1}pEAU1~g(oy(!eLZS3>gshLy}WVyEn82rTnm*!VFrkL73MtTLNoarUJn+Dz zKNkteR;J+Z3VV*w)CKL(qXG8+D*LeymZdjJT9Og~2&D!9F#kXL+w%W}N(-WeCL{h&cKLXn gZ%5zGVGsa-{C~r~&F}F_o;FAe%?U|D3H?3$9~m$2bN~PV delta 63042 zcmV)9K*hg>(jbA>ARACi0|XQR000O8%zb@JLWtk!X8`~JzybgO8<$Kb2p)fZQqfL> zFcke2(sw9jbJGS`qGnH9VicqCt&}@fg_g8+jK3Ec;9M5p+H+3NJ@@v8t7BO>2hc_+ z86o2N$N|Y!CS)F=*JSP9BF9)JGgc@G5o*97XBCIMqFiZs(y9V&1sJC_l7{jsLVIf~ zim~B)D4FqEg>1>4(j~L)Rp)=WV*HEcfCJxO;1Vp$m}R&#bgRh`4VD?7EURx_^adHn zP(TUN8caNbf3>BsO$Aq9jO3Zxf-cQfanDT3qY;y;u4}KJ^}04c!SCD6OW&$1WH%}f z=rkW@Ay>MIHzL(cHz7U;!=X6k8d@xK+7k2>ePrHd50A+j#eq-et{;E6{vz=M8W1|W z`v~#H`_AxmRyzJvde2gkcB%>NG8N3&ZTq`B0oi>MXFJd$SADVzYRXp**#7~SE+KAk zmyjDeU(nz@;AqeX&~OmluEoTgFN41D1a@6aWAK z2ms7|eM@noylln*005J=0rdmSeSMRz0@)4AeSJ%Z?R9m7X8-__lavD@e`$ByII=MO z-M<3IchV=BaTHOzoOJH-+VMPb?ALNS@1350a%d5V9bBA10Kd?Rb=S`#4-XzqWdY0{8{=B&iXD>&a|NVC3&9P@u z=g6IT{@e_qDfu-G@^*uee>d;#3*Yqb@H6~%N&>?x zCogv__)YaPEmVn{Pe0*lsfQ7W9nHd>UMx z+jHo*-D-FH?RLA^_5_gO+ZHXt$a>zl1M|Y6JC4KJ2heIZD>geke?322y7+nXEqowG zvB|M{d%XYt&~_-Sh`y)pWq7su*65_BcyjSCIt|IG?=3jYuJy@wE$=44o!KP(_oIE- zlufedm_Z4sJv0hC%V*8U6kckJ@0|%^$T)2mkQA`5`cR&oA`R zX${7mZhIL2f7@4gb26I+G?YwZIBIpfMz_-+j7LU)&>I6U=(k4g)PD>kKffYP$aZj0 ze+P|KcJSO=yroSmi=w2J> z?EF&%hmy!7H0O)Wx4mw6G&GFSSTPQDgp3xAW3=Ltj@+qFfxm^@y+LrAD zJ;N+br+Qfv*dW+BcJxXcp3@*a_28mEn)3Baf9Jruge95I84WyViPNYAK=ubhQ)x3m zDYZ^~i~7o09^BF?8xTk`q_=FMm0N21_MeQNvXrHq>#^y7SuRv9*!u%NvhBAQ%HdhV zQ+VdgDacWQR&yYhsc$cEij&ZX6IBIu?s?9xsiYTR4B;{;X&|Ioj;i=fsmVmN2U`8| zf6;}VIyQrR>o>1tJmC$y<{0wT%pz`r%xd$ki)_k~P2<#D28>z2*nL@p56k%l^-pG# zkS>Dk#heW1nv3Ad3wM{Z8KA)a6NWU}Wi5|@==^JT(@Wb$qrNwTFoFrP*K>-6r6}__ zxWwhURJvH-o7s34zCBU)h_a;*_rSsN`>1gVRUA&;>Q=kn z(zSpK?OX)sp2M^<;rn{8$(p1wbwwr2t z%BW4sS5vJH9Cl_m-$py3J$Xl9SEWQ#HDa~s}H_t4J~21pRTC8 zxyRX0Y3onE9iqCEi7MVFwd@eDagOr<3C;!dRS@vxi@n(QZd}-BD+^UR#(VD)W>nEP zVvs-UxR|tuw?S5^`>J?!-$eY8`qYK%Rw>M&B$;W-ZX59eD-~KLU`Ho;A**Z};)yE` z3H%lhlh=La8wQaE?49Xaf2du{D7}odI=7%O8EvL*07kE+P^0oOVX&+UtvI#$0wf~0 zVou|{nx-(XvF5xco&&u~rf-dv^M)K!Z&rZcWgfQ&6)1?pmCyd|adA=swYyop#d^##; z1B2+g%Ck_V;Om^k$(6aFr$F8yMA8^4vHO)C4C;G( zz83^B9LS_--*O@jt_8j0TzYWrUcpuV!E;T^Tp&G^vKi-+!u#HyqM9i}>bbuR!ZUhl zXYNS_w$5O|AxG8b+e3KamVt0{)-|BX#);lZ)jGvVGMNVOe;S^_t$gmA?ymEtnnY4M zMmK7IGElus7Jz58Fcp>B67zxV-Z9#m7Y|BKM<-<$ z&pw^n^GH0dU~EiYIdT_EK*Dd~7FiaR`0T^g6{w#xdZ_jO} zEoI8ZyzZ^ge;k-xx^WdRN2^F~*%btX5ZP5!QrI<35T(@|r5A^W0?eM*7)U7RnLJe5 zm?>dF)V&10k%nZVA)*j|E9EB$bg~RN&dON;>L&D-ke*dlxBHW0&6aRV7jUlP-m7np zU+n;1y!M|Iu&=+!f@6oI-5Cv+z8kA(c;^~d8R9Qde~#UH%TgA~3_Ee_u%b1eMAH7Q zqJ3tYIEVvSt$<4Qi-TCfTx(t@3(mXXy#nl*f5+6f)u2Ml`&%g&lkbQS2FfSMrzExA z>hgI*lg}d-=0f8u{3d<`?NNBxW}iT#LRa_%gmzgg@vi4N)O3TLVAl?3 zHgzmOe?KBAdF z+>F%-iilRIm4tD)aLETPOqTdFOGL%CQ7a9 zf5mWs8k3uZKJ%kYQ+fFi2e%90Qk{Xc0sG@V1xM}`_3e<%d~Z%*e+MpU zsX&@=Gd$Xng|m{e*>k+)Y=`=3F|+cv+nG+8TiAsc(A}kt$3}()ZCSXZtMi~2OZJc` zQ+u49p8}Jy;Vz`;6;-7~wu2DZ(cRt^oql1AI_FVQTs(?H48wsw5Wi@T+}Q`ytqXOA zZeaRAXVkQI>CE%Fk&StY)X^7mf79Fyn82#=IFs7o8J#18zA=3_YbcfMNr?7y+jJU% z;|utc9bQFmC+5yn7dZCXg7aIi2e!A9iO?=_{?A~`Pj6Om6wu-b@6(u#vV&w#%P)E0 zFB}8}*wEhhK^k^1*)1BN*j-I^Yz=u&J2;5!_DC1)R3+a-2Rv&1W4dpfm#!Ct z_Ec+v+>x|C95)4=`g69sy66x$AhpheBX{CYwK0zrjCP{^$+0FnA_#nLBJoY`bP*Xr zMy3Z%IN`BX0Ib??X8uBEe=~tUBihtvRQ4r47Z2P31o6cFQHx6*o1t&t;`En}84q4H zZ6UN`Ox(=zZuBW2>~_vQCf~uv6;5I>V3Jd& zdU)>z+E+#leZGXpobA9))B$HgH#2gcbrd@~(UV3pKGGUq&|3SyT@u;dbf&PAK)T09nG z+Qu_}N$XA!R#mrykM0*2?i7?rt|m+E_eFMGVPwU3Y&>x7e@-TM^9#?xUz+#99GX6O zcm`1u9OwuxkAUDFC2b!mjS<2VR{GG=r@TSXfolCF1=ka=8bB5pe3fEsL_GADcN1a zCNV|ceB@%HhY&ZcMqeL1c9}%xB4J!%qBZ-fMpp?Ca9_NMKbYatHyseV07JD9l$ue} z>*UI`yqkKc0x^hrjsvcJ&$Ljgt-W8#40f1qfNP0je;b>2PePoZFs#&i6ld7a-b9c8 zYO4{unrg&%rfH*%PzB>qaLT_$Q1+{Iy#f_*1DHimh>Lmtn zM|iHUf6q{>d+wnhpv62qN__wk?f}k?=~9f5{piNJxGJbmo^NqAe>E;9SN1GC!z>&y z#~t+FtkMfIJc!+w1%*ff-hJAq*Y;Exo4TEs7j{T~p)U2yRfp%yG@*S`(#^HbN*X}p zw4|HsoR@riofDIW(K<6}0KHR_hR{4W9HiOFf04jyo*fQZpGL)qb*PksG&!govi?!! zaJq+;w?6gh0-l)1<}I3jC$=uhX5l_+!)4FyM1NW0DWk<44*uXU(p}ZQo_m_tb52Sq zxukg@R<=E#DQxo545YV{8K%fM@goNW(}A<#URIkjWSz!hO66mNt7}k6=Qz~Kg=V3_ zf3(^oKn~2FA1AI5oKHP3AFrm_PZH>jY}M8{=~?&>%X##)4|W{KyP?+RTlV6wprwU* z2^;dO=|^U6=#U$^FPOE7*e;plQ2KLWJ|`Xq+M~P2?p^#trEg0XCAPccT%y_VWXhvW zbexIeC8cz30V6!td$p-*xj_9+?s0F=e>uhNEd$`jYCi+*v)9)RXFEinfU;;dY;Z8W zs&tsZenQ{b(`d);DKsW%w2hQlRhY>_!667}2Bc~nc1roZ6wE%`Q6d4;`Fw%DR6v8^ zbTnVE+$6}D;W4V9r1A~KXZ3O++&1GqIy?UaJCxqtf#&XV$il>%x)8&IE8iE9f4Q0- zxl?Cp(Ra{~kMlTkd0K%Q-l|Lz<)*SJ#ms6=VOJZOLrP?Q`pB}wuI=g0W*OR*-q~ex1e`JYXF8#0-I^~bG_j^330=Q9GyI(M7-l8Y2b63e- zkIgUWDLpq`3lm0sp`ZQmrlNDc8_-sysHqTOre8qnion?Z?YI_m`7x&&zLn>64!fNm z5K#5m;tImg;k^8Q_X6hU$50|xsk1tHYL((Pn%9_jpt2osZsBjI5ocuDe=f8?l%)SD zE{~@P0>Y?9mGMW`mRqTGFwo%c=TIn%=)+)oEI6yS%R`zmgmQ}U2gJdY zvXq!E2&o|Zf>dphFlthLb;o-Xo9=1Q$L=zCXTzcMr&o7J(fMcl5`TSc7IMNBdMgN8^&m8GYgxS-7+#Ox(F(;qrCCS?+^4^<*RHQ_s1ZVAL%NRkZ#bCWmM*hJ9=>1FrizoVpEQ zBYJ2)`aaWF1C;>vf1fQKW!$H70;pzc49@%p8$BzWcq?`>RlXp#JJ|6rSL1 zheFN4eu^XqmUWdeE)d~tC%Q3Il2HaWk*#7N*-I@0Bic^FJ4c<>Dg&XunRUj?U&mSt z1F1hH?jNZQN*SnQ^Y+M!io$ed9&DNBQNAktORN7hfQX4=nLIT>F^A!S0}`lPsne|||8cohv~Cw&>&J1KC!D-Es z>vYffWn!rGG3Bak(Qi1_oTwAgd684Vg1vA4d5#I?n)rXUFa`b_G zf1Dg>P8H;H;BuJL1!Ud5(fHNgxJ{n#e3%@)sD906tO{{~Qyn=8MLs*c!(9_Z$QG^h zBt~|K?tnLN?u82!oCfB!K-4a~nJ!}Z=wZ@n_hioHd4#jWa=3Jychuwwge&DNDJ!p~ zV8}9Xy;oP(&oyGOI`ait8E#>K6_({1f1ud-WD&9uwwi#2#ND;v<1C*}$yCQe%QS!M+A$ z6c3rQ)bu6l#Ev(-~^&t&IfO``+{;%JhQG+;7vG`hAMa22QHd?@ zsp25B5CaYQEsk%(OiQf`LQAgKf1_ZDG_SKg$S(rZuQwR1H9jqMczh(}*1CLiz6Cnt zeGKTaiDT)pU|#&EPFrN~_H?K25GY5KxCd2?6xAbax8?cor6c+vMRQjZU65mX%e@Qf zZTNZW&F7kMKoR~-oKa;AeFhM{RCZ2}>aYU=Ql9!(ItX6qwIEp3$w@6zf8CkvoOblY z!^};EG6Uz~2a4b$wW3SO_4s7U zSR$FG-6P>I;p9{1QpC+taZftVL(rJ}VKVwH(X#19Hjrk{+c*oJ@%7xikXGWB6&o*h zn!`lK!!*}tN~_Og_#*@!<6^;hQCQgx`^T+r{;qC zC%&CHc{=b852ofqUUn6mM~LEAhN{RQYbsJU2M$b1ULBk@`v_8Ee}EZer&pQs2Z^4* zM%6JkJqB6BM!D;^cB{|sfh|(@>GzWEF6m@yI#g8(7fV`08UpOX)Q^cDu+uAq6>Z90hkmu;7j|-CanQDnPgG|et zE0E-6E%$-@@RT3Qe+A>er;&=LteEB@2!4X?Q8>5gnXYP9R+|`q|3oohyK1l;e?b-Je}y^ylHW+xroF+$Zzbok z=Ay^X|jR=xbbtSGPyx{`8C{hS3Vuv9tNzJLk+`+Z!EX{&WB)OWF zQ9Wqs&mXW1e;Y=2sBs`H+{y-+wpteYmNTwfswuDwPCY{mFFLog`Sdxy6v*LMmKt;H zXTts!@+^hP%$aRfHB=Bf3q3; zg$I0cu24ZA>uk8Xo?Mtg&YBRnKUs#ysL9V&g3A1ke`QljevjO#CZQjv<=-Zm{QN(e z3om#bt)3tSQ~sU2*Y|)iAz3MRAxY3%tQ?TAESAy|CW7S^m90``C)otgi-KC!&hFFs z@>aI3agmLlf|xkTMYX&N3BHoMav1>A^qS z-yS+%PG6Ctah5@jVnUNlhUf|gAdW?*>To4}9JyS{CE18VS^5HjM;cg^Zb}w?Z<|sm zFI#IbFl{Wa#}jaaRY_Y!Myv`cmUd3@b6+Uxf8%M^+_7{Urr+a_Vf9k8%)bOBm{V}~ zZl40DXlTT#!)ya&z zWuDA3bvuNZvkzZ*mt`CUO9n?if17WwsH2czGQH=vw35Iuc^BIUS-Oyz^~XvWm9!0`f6yD$86{nZg~+19I4+Jtbq>aJUjoy8*>{}!G$E<@Nmiq21Nd#s-^8vou(0S z#TI4EbGZ5T+Ow_C_)j?$tCvC-CLSt0;$_G4{L?WYgia9_IWM{@<%+Qtv(w4Je?_^{ z2GBUklrg&ze4^!O1RiS}YK%Xz=fB#N<+WxhDa%w0g3}^v^KGQ4(&7Y4xSa)DQ8d6z zpm6j)Ea#Z678@wwd6m?Np~h}QdV|M$IOV}LgD>x*!X46pixj_%*%`WnemIaftM+^= zb>YEODTg#Mn1VR z5p$Rk-Q=~1N<;^k=->YK=meG>VD5_Ne{|xmZIjsIAQOM-DDI?hO!Rpy3W3NC6%8{o z81aWnE6eZ07&3(lAu|8g>Gb+rWZd2&-BAzz9rp)PYwO8^7W|#!AOGQbfAd3g%4XT^ zb>#|c=6J`2G~s*pQmF1*{z9t0pB(MKvoEhc0kZwM>3;!Q9*#1`lM<;*^ugW3(e6to zEI4Z1Q9WhzB3|a_*sY*D=xq^WxJ7z{4ty|r3Xp%C_{_0eC9M=Jba}g5`btS#-V`*3 z)puwRri3hUL`=8zniCvTf6_v@*(8oBcz1}>K56G0Ly;mGT4y{|^7_`zte=WKH!taP zdk*Z~dd_9?Wwd#%g?q`rdXan86`W9VG~bZ!D``JVsA&s-aUT^YrDJsS&8q2nA6Ut$ z?OsRZ-0tPPfC?myRGMF!oV0t)SEk?HBKb3ia7@rfm&=#NgySNe2g6Rt;F_$nK_6 zG;{|74SngYtU!aIfrc{P{b2awE-7Ll!u}!|vKe$VD2MZJL&?9D7#^bJ)5SLqA{+j! zgX6Xal4H*rWspoAY^4l65z1nlO&)FSDzu$rp}_dYe;`TUU#nmJ>1fg7+eGXhm@$S&rS`~7Z zzQ~!16@939EM*lKG?D+5Tf_%;T+7aS{`K>AAD__bpFch%xDGWbud)s;9#L4dD(y#Fk{0Iv-!wNae?=X*U__IKK$D=U{{VYEuDJ|tI?wEO z=l)kR)VOLT8&Y>AMw699abk@X3Z?8?maR=HPj=wxH|*k#10P1(T9*F3D^L_zE8Kk* z?`*!igOYtM?5T#hL<=H4KfOq9>yA*n)|SXQ1q_c$>?>KxKYrJgOeW*7;Uvxh09;rvH^<=2|RM0lw^y(OI zN{lO68Yxrxr}GHptR`1>!0U)cJq6rrf5{}Q`+)kk>4@wrB=q3>|JgY^&3z9K2y|aU zHLyu6x}dIQyO#uhvBMynr=YcQenpAzU3kD)VR8h<56v&s<->;XBXzHB-(x|gPvs$EJ^JTw>WikBZqQylU|sv1jDYTap_Le>Q?u zh_&)D*@ECp99x9G%NCzrWNV`g-NFGm%5Iaz_%nF%a|V!Yw(*SoEd9^MM(E$Mp?;Il zJc-Z7@8su1nb2a5vLigdoL+2^%W3f9HS3Q3BRN{UAO39%YgG#hO-eO>pvg4Jf6JdP!`JK# z@h@L*z(a#7AlOmk5DAiBb26GOe0W~Y1PY!7|8)Q9J`0HDfi*kOCUS7A^;~ztCGmNH4!V3$`)RYA@+z zJHqJiQEX82j*^zcw+6V1U2FIk7TdQIQ@`uq!4q;^MiyZZu+~&t##_wav3gp z&s0+6%8IBPf8SgLOdB(|-Dtz1doo1;uCuZCmKWRG)6jRex3jHU8%)DgIZaeNnG0aH zx0t#ISno1Gos~&8y1qp`Bx>^h{D@e0zK9k6&w0dwtSvrhum2N5bj>W z$Q!7sUdS=%q0jVj#}wWv4?M7!p1qBj`B&945jpd%0m8u{Myfy~4Q>->nfy?-E+=Glgv+G0MTM-~phdtx* zj~mEwk6er1LN}e)?9a~*8q9?>$3pueMU)Zs9oMFalw|fSl4>(6joQbGI4-Z2j}lKQ zf)@B7X@tc6M3YZG|BV&R!^GM7D%H4itp`ixkf}HkW8=W^ovZI%z;W|e;M^xbt8RWABc`fhTyBZf0F4W zb*d7`pW(8_G~$8Rak^m@IPP9n*{(7ktrb8sF!Nw77PrE z-dv5&k`eJV1o|uAN;(82@K?AtZPig2cJuL-)yG2_f>(Ytf>n>i$|phL%uxqha<|X> zz*hY5Y=$eIm9r_P+AW25d@W>Ee;63n%XxL)&pMc6Mfy-G&yXA0<4>G*GT>UclwEfB zhReKM-UyLg-XeK4|phLRNTh-4l& z_asS0d8b$70IJ$04{aju$)k`S-bCChw`DzJ~epq-$2VHWi1%OJLW#E$x48 z&+53l3KODYQ3K6I9ay%C<>)L(<1w`2LduAxWK*HmIcuAUI^ zBz5$ShLOC8O}PY@n~9W7e=#NYD=v}VGk1!1GRvOiYCQE?`>F`)!g`xOfa0zi(RN=I z8m}`$-517+Q&eAq)l;k?!Rya*)dN);L|yL6RW@?jsIkN%*FQBE3m>@45D$N#N0-U+G<<=UHN4te(-^A}sq=zbqA89DP>Yh{UlZf1kGSw{~l63J+hpC`mr zM4~XptPnTRF9~UT(A0s7BauC0ihzR1orD*M%4}x+&;o@@UO%Ov9vjamW@8R6NwjEX zHqIKEI6DKzuvzv(Nw$Cj+a4F=tTO>}EQeaa3W6vimbjxVf3F!Li&x^nk!9|a=YI(n z<}_o1_c;BQ_0LhC@!?Ipm*Y>oZ3hXOn*({zk>hOwfh{^YFoa-{TFfvg=EP^O#?e<# zGTJW*hElWcTp33VwYEO{;@B)djw1|zbNuK0wg1Hq(l zh^msB$WV|ehs~Tqn-~fB+8X&=JR`r*klp7oVp&Z}0=u)^xB{k=AvTPp z6^uXxTBcFZkOfM5+A3j(&&Y&_)Z(mDZXO=@75(Mo5uv(KkfP3|d8_0G8%p72$ zmn?prz7GkAw~oaiGc!J<`MM_{b}D)dME3DdGa2RyQ(nLfpL(lVi^@{#{jXQIYO@_F>QwYnXau>RA+- zJefi>R6tyrVc=o*leG8&5YIK`mKO?+?9*`RyHVDVCYRKT7gU4GX+wQ8t$t?eyFN8M zGiOoyjAov9EQOB_xcZ>j)8$3U@u-Ei`tD8*f6?~Qw`N#|uMyS|nCL*Ok;dxDwU*G) znou{W@Eckym*!eF>+dXWXw!$E=!EF?B15GR)|}52PX3LM;G*w>D{tvo)c?FdQ8Du) z2AzAKad`gse^$r7+^%?k*x&U`-(pIgmGDn^KSZmevMr#q@U!X9GidfP=)CYPL;l+E ze_r8OwLZMFLWzy}EQ4N=&%(vFE?!YTKBpnpe(}v~c$xjmysa8xPV_+Zx{zV-xAs*csLQq>!ID_p9;!9Z zD=nzX0kquLN3z8AK-^&J%pS&5~Sk)9r`qI;c=*Ssp$@;YY>h70{svhidAI*+cxzFZS6r;B?8(jztI)q8KnRmyeh557vB_nH1me^FYRq!yy(ARa&FBaG>bVps71_BINc-0U$o>&uC#qn)i#@AFh<+FAXyd1`PU`5FB@upwz&sEl`rY0D z>$8G5F>JHi??$x{@zvugMzu09Yers;O5*DtH1aC+oCaZ6=N=|Sc2%y1Wv9-dFN?CL z@{zmh)0c%kVJdVCTOIbK<>4Rd;VUo0T|D_mZo0_kBs%Vf?4FaIe`WS&g_Dd+9%z@> ztaweWp}c0rLPIo_iKWV}BGppIVyQ-3d#x3PF;AJiUeV}25F+RKEX(<6K$n(x#L6ep z7*A4n0=-*6g;E3ge|L=P4@7FG3N%Kl>{O=@rG4R>{@t&<{1cppR<{Df2UvuIg&R&n zz`@M%Zd&KSbpnv%e`za>K2@v?wIks>8`zaUy~2F(XEgAfC0}jAoYDWhyr*-Yn&D2c z6MA!d`q4!bWmWO226tBmesUNS$L8DPo%8oQyCiyzR&m~vn~$}W^U&;;C4AKApmK=S zlmOD`4u_J86glWJZkk=C4oA&ERCCqr00otzF));AA}ZL_f7}d{KC>gmEiU8cq!>J*8OajbZeXBvwn?<$pTO>7nQrX<$6<7Q%%oNSP*HkFv+4UmLuBE0anLLT^0a#VAgGt~<+FF)kBB4yXH7HQl=~!U2 z^_>dTyD8sE-HBExL?SY*F;V3KT5Y0=8XvidmYozSMrG^2XBUnCG5rPE!xoA6O#WaL zo&)WAc9r2EGOKhX&)uSLO-Tl>wfSbO!RZ1~f5$MVu$4V34~kJqs=Hbq6s+$2o}x%^ zJ+BE~{EL^&6fx<%tUadsYi%5%tAq;;uBhW|K`SXB{bOlgn-0Q?Gzfct`x}`>uUTH5;6vg3{UMPjF`ZeH^uJKd63 zf3Z?m&I(8l`U+ink;fOA+@n3+h`7j$D)O5OSi!!D{U_aG#Av&hTOsTwD|fkNE<+FQ zbr*JTixts6!RpZXr%Yx2xHv?kym=}Pfv8)VL0r%)^BQZ-3LfFj=U4-kZwVf1;>SDG zA{)DR#G*5E>4d}%$(4Ze*dPLEC)pqVe+4n8nAm!Y++5kyD>A31E7F=G>@uJ}*}%M} z%uS0YP`zV6xn`1h1(8o8M=PEeE%wY1r<|An<%8g)foymUU5f^`Ppz#D)A8KP#Ca?L z3XA&3a~y0lIOH_*&_l#tvwCuHCiYY`TR`)9Zi13)6B9Cixlbh{AfG$80ny78*B6{lV&ve?|>ThE71D zIm83R(-384$@BkBaqjyX9#7^n$c`;T_?lcVWno1Ux3~J~K%2T=uH-nFW2-ATyx~0D zn76I&H~3)5!V=M=5egaZbfBefORMAQL2KhhvRNZc?FwL(6jO<8{tWMCRjK5HfQWZCTgT@h z^zm$z)L7;VmX%k|jjk#ao*wAmMpEinE?o2LxK7>U`^)-^IZfl5&dPPj#q3A1jwto$ ze_m9Slg@1NR(7p%HR(LHWm>I%;_JKYuTm?t@;$F}?wMB~h5^mtf5n04XsX@c8u;dY zm*Zjjrcb^d(j>~S(oJ7em&_bVP?y{pw{>;NouWs;lO|lCuvXRy)r4`V?zo8TUJjb_0+~ZGwEWNPE-`TfG$(;=x6qq12=M2imx_5-j z_gtL<&wT8>wQ)4de`v8-N9oI%_l%K)QFWg!2EdBTrHcGq&?%}x;HQnWq9!zb%$Cdb zHJ(sK;15jI6zM5ossIB$Z!q1HV}FTOn&6DIS}pPlbtLHO1Czzo^F|M=kx1*>V|Mgd zA|1yMmWXhr=XRceAJ21pT#*~_`;zh-r^EiH#r*w*i9E23fBYE5_isufmpec{N#q%* zTB+~9Qn)R{Z6Kuhp;1|qP3|HtmE&1p6-MZ>+H9J!wnc}#xQ#5wzm@?v&Vl$gqdo;R zfw&mnQ0kIfekat}1o6 z!bOj^2%f8+BDA4+w7z=i>s`E1sm)5pL(t!(4J?G!+T;gc569}33}hYwk;ZOV?{2q zMq$e6an;3r#0?#2?_))ja{xh+NC7R?F_~)~k5Q9o_5<9Sq;;jd01BpF#VQl1CLiIOkrY%RR7n9S89w z@JSs$^Jdov5%sF{)lu$bpOy^KBOREQI${HmqZqHwM3fQeg_Xm?U&@nq$|gRpKk?O~ z0V;T^*zB@+uly2*_Y<~I!CZY~a9}~x?#8xlCmY+g?QCpYXJc<{ZM3ni&BnHE+fHuY z_ujfy-&ZwN(`TyBzd18~`swFsjy^G{`;xjY%rZ3q0%0UVm_VMszc7%YA|z5>80e2E zP}=a9cl;PV{xX0&X_3pbVSIZ& zDVWNcxkJ8pJTJSkgOzirR8N|{AXsvF{%n9;LVpv(+Oc2fEv~j=r`bW3c_hc9pT`Ou z@67Yh%%@{x7~iUzH(!$0XLgqqRH_tN8B8pz`zMdtm(8KCEb`+2JwN|dwiCBjxX4wX zxq~{?;MX!{FYAG$L>C3E?nOvJifisMJLGh8RNu}V&A)SJPZra`U`W!g8{Fjf$75Cw z^9f_7J%-I0lHbguJbRsidbSk#_HhuOzOJ5HL zciL=SH*R`POK6A5%QHx+7?ZhR?bO9dq^@}0aBim(YkmVoP6mLIM8*E&koinwAQaByGwLhxb>xQwjna&u&aB_2L zsZIGpl2zulYxxDmXgs9pvdb-yAkci6RxSl@j?rA(=*TGUI)wT8Nh2Q1q`jpvjZLNe zGMwZmMDE9?^p7$&4W~+QsQyKUA@{GlV%hvDW`j4bnqVG@*X8#BJqTv27A` zu3&JlS$g_RpqEMKvJ4`Ql*jV-A@jOShljOvD%rRuOe4`8YOh<)f_~fXaStGljVtwK zUigFwXLZNN4y6vU{1gTru{`)dv1+ghAn<>(2Vzh_#-7KdlC!$hPKGboVRmh0NPnX@ zOo8?_votc?Mc3V<-ka?Z0?))8ME>yIeKrgX8SWu4N0BQVEADayOM_HEhWU{>xYARs zx5m&5{)f7NW%UQCRGXuM{NRVG2I@ObMM`~~ZGDWzp2ac1!65>C{zAB4P5Kcoe5uC- zx+${e)c3C7uW(LjlSB{z^;=&d2#fC_<{d4Finr%=d$Y-Cc^XAV$I+8850lfclUe*` zE21uEpF?0u-_B|N+qg97;^-kJn(Pf&CaTS6bk=mM$2jM*-jXVp&O=NRP zr$Lz9*~vHflsLHWu%DVE;``F4ws5g#BrVC4vTwM9jXE#@6=b;4HkfFJ_%Y!u-+S&w z{m*e8#O^)*A4J$mIVVRUeANE(wMQ(svdmhuak$H)mo=f?M>k{|^YLtYs{JeFJgQ+O zsbYVM<7-{bU|<*Gjz{B8Xht4?Y%`>ci0OLKiaeo7xHIFND-TW+<1P?1jTa~E2JU8R zK4o$&wH^im^u>?~p$!L)BwrZb2(GfKt0-q)4mjL?4HWgS^zE0xSF{g)D9SjQo9=x9 z_!)5F;Q@FGRUvl0nBcT%N}-pn_zmJj68bA0dCC@)wI%9u7;1k*lMB@i(jJIUIs;YW zW9~xBl*z6DDN{_qm%)H{9qCMf1 z^S%cJ)9Zur8l>jk?9lKj-kwTNiYY5b>YB9*N@>s1tDW|1e(T%P))e#LBRYBQ z3y9$`siF$0XA$oK);{kThM311jd-P6l9}||k+(g021V=<9pp8)QJIN!EbA)J$g=2} zbu0zN!)|)>b^wd}pegh1>0G;pzxBrcAwi*uEc!zMQ66u0CyelbFmN8iG-KhhRZjkq z-dmImQZ;cn5~-93cU_8v3>{&{(wo^yX0I?h>|cX^Nb1Chm4Bf`+}PWU!K8#k)Ne~0 z_*LSq7$22t3x?Q3?~MtS%poCw6~FXIHvNOLE?jNSO;uamc^p-9@E0|-Lv+nbj6J_+ z2wqc9w{kWc8*in^&QyhpS{6Z)@+lmGc#%FnXY$ev zi5++ zZu|f_LJc_>n?FgcJ+A0D74CsX+=El9=Fh0owWwcz*o*<$EQw3-0$LTO2sv{_xoLSU zp)6XdoQ>mgI;(hi^ulmDJ*en*iH0;cx_`iXPDHq_Fe@~%S@M~d&_TC;N$e71YNCnz zbJ6x?T;qOX-LBgfNs=Z45OQgJu?l@rb`9&MuM%v+c+pK;Df~hu4j)nSSHJXBuuSfr z^sbu=N*GC`Z)}-aU1V-kx=KKt$?eZ&9h9QZ^t}v(wD0k!J-&4eb-x=UENim<`sayyH0gOOmrD{N~YQsYC zFSSCOCS0iiC1Z+9eg|cbklbH3B4^hl$u`Z_g@{sQqY@b?A3qmjU~eVj-}yw)!peNa zd48zmC_V|s4msBSNiI?)J4|`FdPsXUoE6RVx&XwPGYxw42gvkfZZ0*o5Z4Il82gOG z(Yhw`P&}5ubVo1%Wt=*f*>=f|6hpaIGnO_qiiP2nwDpk%>DHfGo4o~j#RwfWOSk3m zV{tw`>?n9Ik#A(N>nY{X+MlpZdb`6Z?E<3eBu<@(fBxF(R^{1@+S&J2_-C>){l#q? zSgf`QsxqqCjD*n4(CzqM>|M7dpzWAT--1E577L+Cmc#%Ccu!KU`Ag!?>crbin+MO1 zH-=j&GpnFg)~#6e@jepOu8&#sPmPW|5u{h%TKnpkyU9E((RN04HFaiGaC#Fdg!*4` zOwF#;f3Ift#GAep3s^m8JLZI5<7m?-Y*|0X)d^VDf4KN?h?b#^)# zlB?s@6k3CQeOI98NOUX{6&a&VJY{?ZRfLlF+` zx~5@oI}n`TYQ!lohkRtV2N5caPQ6_maN=0O;iQ@sb36>(4T)p08HLfUcWfwpgO=oG zF4WoqOL~xnZ%At!c1X8aPY-s}VJEQWuG0Eh7_x_aw{P5&@W{!Mrd38u%kUxkDOq~t zn2z)x1TSju1fAu^gNzG7Rd||^)H;egmHn8`4AF%l0#N-QKT);cwbDwC4ZagR;Ri@| zQk_N|5|#`qjqz?;vF#(|q$WRmVo3XB!W&2cg`VSs={JjQ|0Lr1hHtA%Kmz>zjlHg8 zTPD80Qs~&-C5~-UyF}-#_0b}`Hn}=k6FctuyhiK%^(xR8Z~hfnH%p_gzv9mBMly)gly8T-FTvU#&j z!jdMj=Hd!n&Ad7bXEMG~%bTV0MBGdaDQvrVfzeGvG6wfUI!*o|V`0)%s;3fNru@zQ zCv55wli_QUX4Aa^FYtX*@;$VOCzz2Wpz0JhDFz${=Uj)aF#ccGuAF-2-6@JLad*a; znnox)G7Q8@Tceab*(0}PCZzlZ)ru><9hlX7eUHw_y(%sFZ5?)K$)W9?^*k^=#BDJ6 zl9FxG4Vv1KS3u>;z^Zp2hoq@#lFWicp);08%AX-Z7aQUjrY}bn-QRDW&FB>X)XJ?^ zt6mF}LGf`aAj+`HT6_x*P|1eQoCF9;FWK$?TE3Xgr&G)lmDCqhJG|hgDzUw1>{IsL zT^3J?dC52*-;J`Alowai6aP&)w!t6yau4;ozf*r|ZB~JSKtmkRK3_2xLgW`b4Ttz{Z&VK)SA!yNnRMBxk;=Q+&U zjM$N+8k0v43I1v9*;I}&vuTTguGE1a^{a909 z81i*o4bLm{(OTtT!C$C_z#gNDTl{qaq&CHG*Zj&Sx@Jax!k+IL^f1N4K|Hm5URK5x zcUuDVR)-u*^7bc<5XeOWnhY2k{OFqE`77pvy?;rKMSNmnHD=WOcPGSWSS>jw;yADPBxQ9nJ{b+zcFgt2 zUsrO8Ds^Xh0Z<)A+mz6ZtNV|z;nm!dl!KCFOrm7IDdI`!s~r7s+eJR?NmjC#`b(B& zapSNL{yHO%>dGGRnBrcss#MTLi>ue$Rze5Gm&`2O-@u8-(j3q{Gg^Y8BDLxhLVTlJ z#)#GX=Py*C6-hKxLOoj=Yw9Ic*CL05mVOu)u+aCtJ=34bg%tl!#zEgSnA*$&2UXyb zp~p*1q{U_;H%j51#4JF5AQqQ~C;u6rh9>MfpZ!6D=0Dv6sVSOnRC}6vaVJx1L7k;~ zzf?DUovy*s1`ceFc(3Qbm)F588pPsuC^OendGK6u2>XjCwRiBDq>?Pe9p?QO2Tzj0!F%Q+Q7P8%Vj0G{uS? zbl%Xn*fMEgx6IdzD%BI?OIZ=Bq=-=|G`zXa9ovU+@d8F3=sBcEFYxOcidpalwKFqy zGHtXk{P(EaE>zJ8jJH7wj@lHJT@^!js6?+5^PZ+9r`;q*n$_%NucdNIH0)|#CK&n) zc$7mnyNX&?d^HDWzg6~GcAU!I6eaJJmluHf%?-4BBSJ^t*ZkyuD>fYUEG}^HW7*(G z-OUb7><1FBFT$8M#81c!Y$?qCmG3IwnEorb3-bE;lgAHiqeRo=rC`wXAD&ehDF!d!EswK;{w z%f@hDNw-o1Kj=_RvX=Qw zz3{FYwW3IbopOqOzy!JG3S;&BgtCQbEu3i53Ajt|rsMzFo~D-mU>Vbhmud#3IylkxMf(&?H>JK=mg zTN8`8A=&E2fP_`d9XS1g5Q-7E9#tS3TlNn)Z+%x*QA3N9OO5Ua=ibGj3kwN_#0J7Q zV$QaTurhi7nws~ESp23drC;o$ST(B%^t>e2 zd}PC(?(sTjU)(Pq@bDikIAu#XOq9Tjbkag^MxNgN)@>#p71}a+(#Is8E`yz(cg(Hw z{#&LrCR>XnPV*2@Xi$whjCA%Haf$Jv_e`QMSi}>fQ)I;?)XoWt$l8}(g%NRe&g<7h zQkD+grF+u_pbZZcF#=56x$$3{PUnwNeT-4< zH2enDZB&zO2g#!JD_tn6|8A4PYV*2RJ@{6;%l@=NrrLlUrUT1E-Cr{bfu zf(ZN&@|K&FnnSGPZd-xXSc}&%Q$$9LLz?-q_m*xDMpmpjW8RQ+BSPULFdF_`aYOM9 z?OZZ|;p6l34gXZO-0xV4%rqa*tBi)?f8ewXeWT&FYPE^YZZ|MIDdckGyY z)fGc;IUi)H3Z#_1oAoknlwB(-x4<`CM%MI3%5DF7f-CAb`VJ-=BgQuqJ9&4LQ?lmB z<7GlK4o>xoi@3LLv`)pFD;aKXIY1Sb7_MqyJH*HY0YxvbaNV_b^ zo)gpGUfC0?=as5l))s8&7q_0xAa8Gm`^Mahe1y3JhIo_rJN3EAW-x+Z})Y(&R)f4*4fQVulM_M zy~HC8UP%JC+f#}J6wxpH$G-?y!V2tns=5ng*4RrjIqa^Gt!5kOF5&NHrOj$SrD(sb zdVI4#)jgBF>f{m8=FEe5Yog=^sp`yqvNe;a+7GUk&-%{{PtcXme&TOpWH$Z{G&anK z7QI)r(S?cE#3jq1yV4!}^c}t-9KH5<#z=fh>x;*Sh>-?n@LVB)iX7|{JU33Y4Zo$F}?DBpnuJFuYRwcZ(ZYs zK}D`%KbqhZCaunVc`FWVQ|(?QI&pDsI`na^sTb)~JKz)YiR)R6DFzjXpRQ20cdPcX z1AoIptdF5MSGsrK2ksbdfUN}K#vcj%{!E^*{}wom;7?WzA!BL3`CKW1ECoqo{N(qn z`F7UbjQ&%952E)iS-FMwj^Y}dsd`!X z-;5%6B?I66VHI7UZ_7>PSEhOCSdI-*Zbd0VlMQ?v+QuY6nFPo0WgFcbEVkmasM#Ia${}DMFmFmis#TEhu&I(4 zoN+MLOb@;KyW4dQJg;bGb@!@@y%r)GYaT? zInH}7tfLss<)*8y)amP*Y&~AZ4E$cAC%if{ecXGyeI8!^e7xSe-53VKZtD{tb3gr^ z@3wstaIbZll@T$j4iqUzd`e-``};MSG|M)2kgNyjjkj%9**Jf9v1+I#4Vx2b6%(lt z}rt>FBH$2T`-IKs_yHLN`dc0!|m~g&Svc4W$Plz$SKyof}6u*0L!Sz zXHwVhiatd#^&vm-X!Yf+vs zO{b7Hchr=i)T}vD-59*h% zp{m@NGNs${hmq#9?f887QZ{zfF8b$mnWIxGAJco5+Cc>K5Osl)n&oatb2JG*9#_nP zTO+mltzv3a*sP-yU;txkM#8@gWr%!IsxiK!CTux-RLLxhsiUTwJ0lAB!?1ipqN}Rz z*n_a|4^c71=k9Hn^xfOERATjAf=50TH72KL@C_+q$L&qVjSi6`o$NtBuPVSLY_S--sG}T%-gSd?58GPK z8Cn2K!zzC>HTvM>x4T_K$+kwrh6~~8Puv2&M+xi5i)ay<;>24DR;oSek}+guA6~W_ zrwR{Vddl=pKgmy^=aOi3mRerdQqeKfcdL0}QLzA?RH=_buDrRb z6%9Z04~FlU;KnJs0ZadmfSH)UG)3)ij7 zazQt>u0;C=D16H`{>@9RIqDa<56$-u2po|HyA<-%Na9-dp_nPNV#CZuTZe>LrZ)L# z{qZNdCi_=+(jWURU;`iyaUZ5=IXG1SJU{mb8sH4NDON3C9(Au|g5C;_ZNh3z{{TQ& zU%|pSwdEJM6?Ke+3xQH8n0637(HWPJkd_f32cbl^p)#QI3YPK|qt0#`vFQruiLmDo zTAY?qoQC_7W^6s+R;O!zaD}dV`~OGw;GEXg`RzX!p|gMHj2v2T{VSw)J5>v4Hoc%w zgo+(8#ypQ`E~@Nt3UdHLZVl~CXqcH0*!xpv8FUsGWHBu)Rb+1f%+W!)uO_S3F3xk4 zvG0-rUnp0u>(8;RZ*+Z~zb)F>1FBMSGbCFy zrZ}TV93&bG`?R@3cRf!&zBy=M1V{n~!gQr(3A2I@~ z;?Bnnqq4ILcajF>T@NEFg+~&T!-|0!H$uUGN=g|UE87so=QBb#mQSz87jA;9+&lDw zG@C+a_Y)P1jQ;{Oxg*L%tSh)j;ig8%6;0EAZ1%~b$-Dnx?UTWZsQ+9Aok9z?cwcbE z&Q#Wo2|E6s6QI5doZ#wQ`OCGbO1YQ!RsS=P9ycxMi2Mxoi>MkP_ApTLf}zCv!0bMC zj`D4u0E+(FH`0p4ioxzxDf2?qh1O4+c>I`Ue8p|Oz9RyZVNF|%P87Nx!&Pv4`KK&j z47H=9WO zxdwss$2u}zw9B||5G#NDdFDU3+x)q+-KC|Q;4>?j3}tC24w{(M9W>Hh{v4%YJ`0;Q z%8AG8kjem~Vn>Lh+JX`|PQj?tEryPV)#%yx;^w6#e3pkc!Io36jBMnW=dA>kr7v(K z@etk)vSb9NuA2lVf9%0r+;{mGj*rnb2+@iBoHF%YUMO5Z{cW0GBs{{4bXO{sH!W`! zgMQ#$DYGnTGIm7siEpx3j=ja7# z>igp`jn}*jDco4sWEjYK+obJ;JQ`m93urXXohwgt+#C+g5l*8Wi&d@7niJ*b_8XuE z2fmolAdm2+V0BJ%<3`85339pl?ePveHC_P~uGRw-_hH{NBL#$nG_uNE7l%`DzjVK4 zaEJjpG8&;!Rjdt?idh&Ntkro@;!|s4^Z9TgJ;nwL4=61x_@Cx~(2Q=Dwgy7k*Kk0*Kto#M(u^#kJ3NCXRC2Y3)TU%g4~VlBG~4|cE3p}Rnq%8oU@)j9DW;}-x7 z>SX|%3H2>@+|L~p&7dUh30d@AtC7+fNLf4g9pjl(;REHkektybd@YOK%wI4%>FqqC z8J>nFSd2Qyt32Fs?aW+42QS_mUbQC()OaPy`I6Xon=FujDcb8l67OE+R+v|Dj_R!E z0KEM2oA%=4y+y&v9d)%187}>~4msdvjw~~t&sf5aK7onLtM6vl%yHU(!PFk5bptJ^ zH@UKB!*$DSjGdP&TV~#0Swjq2(^$xBXgC!C3~;D?;i#Ho%C|*w)vrqC=@3q| zA7sK&7&c2nThd3Tf)J=4ZXj(G$t+$|y2Qt<#Tr9x;BXkCg+}3XaJqe#jR2sCNZ%ot zbUSp@KYz%Ko!<5=Hs$(#SD|atvBz=R9!I~zqF6B1W%AQRS~I&p zd_Ej}4F3P3!CZoH^yK4QG$^Vi{UjLlMlm@7EcNBlbffFN3%e*)(LIm{-p1NVnBzY_6ZqB=7 z?J!Yg{*%O4#yJzH{ZbPzoEHiBfW=xYNH_Z-;>)v9I;fAZ>z4UwVUp59_FCONz^2r| z#O=GD-DLlI3N-EUuV;+A3HP(OixySf;2a{;80D%%%8^9N2Tgcj$K{_Kdjg?FQ)UM` z@=u86W0B%e^eInamU+fkx_gx`1;PIX#jb8|m%?oZ%|rB5OJSqwp#|yYirW*1ch8yD zIb_Wt#iaQSL5l~mW!(5GL}VqI40g}&LwlKoeCCW@Et!EDL1jm!;d9_h)4|w0pU>X{ z%ZYd-gDi|c3wI0r)(RA_j;;>>d_rVHg|Z9=hq@gPp4&Z1(kVx-g{RwOU|&u94)5ur zbH+5;pZ^FU(;%a&K!vJU(jc42Fo$@F)U9Ym)3Af0Kkwt_9xONE?Rr)rs2b}nBV!SB zf1#iujZzT8=r6SK)L=KL_sZ0*zXQnwbZ#BV7x)$^j6%l_ljz8q=r!ZOJd1*>xEOZ?P`mRy z({UHDo~WV^xUs@N`x5=&C@nphxqoAK_wJ5z%FMcrW;(-j^|gxcq??4J23h7cpwNpz z{GPxbXNKwNEER#Ta)Q@c?jkglG-@1HndGf)?f5wBrse(N-TJ)wtJ1o&#$%v9myIUG=@<* zaUfjVGEqz0CYst}^=Emikl){kr{eFD3{uRlyhu9KnS$dsJRY(AtN3UH5FHQ2sNXB; zIgcTpwH-{nN(^`Kc_KF}2klO&T&pztE5#VWO3{^?f#X zKZ9}s0iMZX1~rrbshpT-qa}WZf4<)FsB4n2I)==foRa)^<)wvsjnZZ;b3_^SP4$mm zt#VpG3)4PZGaPBL8m<}^;N5W2k3B3#<4wEg8Lpde&fUoF5F~D=di@lgP*m8s%z67v z-tMP=nma2Fs}pbk<6`@g+C+yP@>C7FH}$t@fj6>QLRyT;=6<-Tr@T&r zy(bk;=Lv3bY~8QF#!8gE3eR~>L5`Cc?PPTXr)|6MBk{o5xQ77)aQLxY^)T1ocF1ty zD@IC^{S|@0e8NX`Hg|lZ`4I^^OaL-q@~mQ6d+wI{6}FQ43q5u!7rmrofQAgF$Ue3mIpX$d&uTkLR3#44^aa}hnrm#)VGzy31?QYuazKhmu7Gm5Kox@JTwEo zATF!_weB@RSFiqS%}Rlt?SNZOY#KKA(t#J<|7S7Gh6JM7h6M8F$A4Xnf*^lh1B)in zf4bYhzckscHl16oeoYrvieKij|0=)TD#zxnq0MFeq_lfoPGLgviKt)6-phWQi6v*_ z;;;T52puO9V`yYJ9QW8g7N(1HM0YHQ=7Cp^UBPELB3_QxNu{CWw@cEEJ<+v*PR{E6 zoX@mr!;&;kj>h%g+S;|;s$c-Od7%C23i>B5;6>|?1@9&L7J$g6VvB#;O(rc?H%FNf zD3U9Dnl`abq`Z+kv0Sy4B8)a{MtNigw_kuR-19OyNB9YnVZ_j<6kROA@W{XANdgjR zCQ|nUxfj8C+92E+eShk{*{0i|*EdE%odjM{FHFP9zU) zjbNXKNd80u#l7?fGvDS7DNNc%*v(xz36)Ey;#1)~*z21pc#A$qIUeJF%sPWN61Nhl zhVto#bWFY&C!~xaq(6Y3zGYcw@+B^D5hNTPLOvQ_SubRFmT2TpwEh=0TbrZd%~ljH zQBqC5EKh#oSVLMBP~bbCER1W6Q*Rew!i-m`;s?s#n9oR$I_`zAHC$4}*}qndi^)<)1qa)>{-SLh6e{QFbVWu5|Cy zANuYr;(DT1a9oi3+9WW0kK=Nkpz<8Bq4Kh%pR1k?r4Y+Qr)P=Ttjr@4-8UJkW7&mr z{YyI7a?Nr^VJc;AWYM;UilkGIs@~S&CH^r8%cbr|Y=BrrYC%5PDftH^obx2ns5W5j$PXvFD3L)Y{;=;fHVWI)I>nSS3Iue>JP=1|H^I{ zqLaYNv1$0COiv4zvkhDQ?G&**sgxrl>|=0@i`obAY|gyN8xz=*t53<1 z75IT|3e1Pxl)g4dF5!1m4p;lzx^Z9vUz8JKk3W*>-Fj`i5&x7#A#O^S8s(m7AzNbx<>riwTU&9Q@P=UEo7)qJ#E&e);fs z&a}|~I%^gwIO`qVtc>!n`vz-eTJ`yjOVv<@KcE*yNb*jfz3oJF2$H$?jq6p!(=>P- zMCt&g*XC!TQ#v=E_3z1WD0zbIf^jYm`arU19Ms~is7H_Q2FC6!V&qw&c`EPT zh~gMKdW{x!j@_qswC##2Am-Grk-Yfh3$UEE8JQ8roJuPEPJQzq9V54oi4b^m&8=@~S z5iX>{*g3Wql^ygrZY0ZFP>1=WSX_g^m8-Lx0Irunp`bylv=ZAU=sN0pGPGJ%E*df? zm3`|fjM+Ml@!ym((&|dy4$pi>G0%vdvfbbeB!%*Tgn5f&+Buw8BqUposLsOtC}1{; zjmScB^?6?dgen7RPs*uHG$r8F8;>P$@U6AI!(DNV`@zRR^JcYg2_-M?Wec3A@3+7! zZQ>EER{r1^$tjyY7mt*5&~GEZE*Dqco+-yeUe^+y$toU$sYWScrC>*diLsI+&6fR!VUo%KFEohxr^kHPGDhlg*^^_i3DZA#&k!TEMgTpx&m~aj%qXa*YIh# z^RhdbX}r#Z$SqoT3Z4tSr3u{GlNK6KY)UL_aSJbk^&(MiYswxqzJ)38n(pEax3$%5 zrd(;2)tUB-oaDf**szi#u;e~pHJ=(+( zU=bV%K_cRDFI*X4>zR;fmC&ebm zW9pE0C{1lY99DQA4a?`v7IGQ~YcSNYIywm7!#mZiq<*;Sr%nsp-Ar>H;T#n69^L6I&Zyb7hjA!p0C+nY*Bj-~kwp+>ee7(@^=(W@@gM=EvJoLIJ3zJbJ=bvO(>5JCKv%me^_)EM)vcxF^C62 zl` zyaNfjY38xTH!&Up5QyZ?G{NBW)1i9A5az0_bu5_@?E*etLmudLvSJoek=eJ#hfE?=9`vTgZZen{LR+?e z_Z`HlajV;tIS9S19mEX&GgJefaoBcIes1ovYU)B!a440&>F-7E`?#iUhiMe#Zx7GS zfKgC#SIRTv{BE<97;#pL0MLm7TJpVij#o!0?rI>B)(eHqW(aKhVR3Y53ROAKKa({4 z6H;x@KV-)<1EPU*v~Y$S`k~%F@1j=!t0-51>Bt|=S=iKpkl4iznlqVA$3QCJEk>9t) z7|j8$G)w46zBaay;>=%ng$eg8N(sgTUl7dj&p(%6>Ey7y=b+z#=(?~&C|X4%fOxQdti%v`&Z!Kjk5}r6&*R zng-b*(M!EvzT^LKB-kbJn|3w5*(?gw@YB@FAHvxC^Z1TQ3s<{OJ;KCO2K+42ZI&@J zFlpbXuT$2Y_jaz!2>K8Sk#Hf(4Y_w@m?1)D#l<1FH`|N~dmDDyC{6Q#=N|9zgsVc& zyK*%KRe??(8o`^$VJV8bfQx*vub;UfC2|*}sr;Zs-}=)A5{C|z7@sHo7p-!a(aRc@ zzwYU^wwc{?puguyDcUtS^`6Agj1&lH5<{cQw& zb7z7iEOacNn+uT$t@+FHyByuVXAlN#X9`mA1|p zFdvPP;m-1n`V0;<0)`Sz2-4P6FU^yJ+sIg`28GkX9p71E{D;&Ut53vOu+7|ylT>Ti zKBwnPKqCcu;^nvpl0Roty@l_3L*mWSkzt2IP zp;_#RY0Tkm`J4|Z6a4U%4>ZNZU22F-9&N7AZ`nFOQxBE;wLE7~4pG1dNdOK8+a1G# zo<_I5M@$}JkpxWpa#D0yX>X15GWSVAn$b$y#*H6*;E}^=G$(G-Pk5G0n6(AmIU+wQKru&_n{)obG#xmswl&8+h}MkwO)A5 zKtq^{hQYwi1S@reG{_&ITC_5V%L;1O`>flF zT(JTejk0cYX7?&JjkUdpo%Me4_5o32#Ol{Pq+Cklcj=INRY;fDZ_I6)ifM+w#YjJ+ z)vw<#H^^-;O;b_CnEa|?(0N8OQA)FKPo}Ze z6@WECjNc?$eSn<%xUT75g%R<(8nvl6%KhxT!TCDuyO%jpPl$A;{`DoSq7(kFki?P~ zTaCpf%o)+DrM9QRY$u^J0omp}PA64A^h_M=)Jdpx#Gh=gM86HS<;HwnUuazLG^G#5 z$j~mto?a?ibst5q9=I$$VdBw$!5TfyA_5MY@Z5C812^O8{hg2Jg>A$9q;FoE!z|s} z-428zIlZ~jl>j4spo$5;6K6}Ka1Muk71Tz>^Sx-e`CPUzpM3M8Rh*=$eRiyAJv zxeISP&(uUWZT=--qP1+qeTz{E-V}{K{)3(~mE2WQ8`z2P3$!S+#GTmDa5YqA&vnt_ zu{TGuy2Z|If6iCCm7`|2VlQlscQ6jWx6}^p^2PWlFJvem zue5Kl!7!FXOr?G52fQ<8!kw`b2BfrqkuewV+kP!C#?}|ksZujeH5&{1{?StJ-R}a0 zF$Jr{GASlN_;{b}}|G~cVZ*C}{v5Fa9In&??+SYwuM^gltvdkY$Kj|23%$B)RTq(8uGYfZQCCJ# zJ~cGKr=!s@oz0CV?>^?K`R<vhli&dxDvbe_{k;33XOIwIshDzGK`<^V5pGr@|y+RH&MHdl=&XQJDW=8?R zGT_-J*;tVu(<=wV`&YDUN`+Uv0k zNjk>Hwduz8m&-=@jvyPs z$*1qfTCpGgdGRR-mIL$D?GJ03&9|RUsTtw>{&Y>|ZAWqFVv?e^FySZK;cz53QP{-i_s9=jqW|cS>tC0$GXFU&<&c@K1{em>bSWOe=>1 zqQB?O4e_-5Uv7du+j_VE7(iIyJ;E70p zmh31RnObIhu8pFtKdE0fj-=x;7&SHPeNyk(YB$yYE#BjVieGRktZB5}1(2(Efld{% zdJi6gHIB#gl7YWbJ4+hDzw1`>4-z1c=t_66AjUhaZA1_(x1O%V-o4)Qdt<(W&4s6$ zNyw$Ge>5?`lx+@qw6{6>B}OZ(&6-D1j8wPc_~?8+-Md-5OYs?KA>*6BNWmOZzgs>f zU1e=0Nzo{WE*%<+0m#@2Tuhv5x$!!Q&JYm)K+5F`H9{12)$uRALN^ep0n8kL zfBmu01H>gB*zU{k%_tYGM#G2Eo&+maH0b*x(^S{$g%ro>m^iZOHUGRpe|&iTn?T74 znZ-*Ju+(aBh1^2tVgk#gy$QiObi}NJ+~Hy+(wq8x)9C>qpMmQ2o>yk284J+DJBC8k z4WqqtKPDfk;#iW|+~02=W4WXU3=E)Uf2Gq+PIh#%;g+OI`W{J`DN&n9cY!YyO)$(F z2Ycv{zJJ-)ta!pc$q^<3BJ+ODiVmoQ3hV5^75elqUB852kEVGrZu2&6<;R*f#@hAs z9N3pKY85**&tmD5P=^ir5=~4@)x-T}zKV<7Bxt0Se}<_e zc3lQ*keE>@&f>yD*d!h>khu7B>`1TeXg!T{*GRhg1i_c3=ne;uC`{@36w&@NMZA`D<54D@z*#ju2y*;i2`HF(;BRA?m|!H0 z;K9r5W5vwgDuaV`L%ocM-}lAVfA>=nH11Oz$U?u-p%E#xUHxImwGq}k98-cf*po#E z#jic!`0f%2#vTy2*4FaHpL2`o|3P#b@~ITc0y2H3IFqIvg7@#h+f46oRb+$rh9o@W z^lo_@B+ApALzvwmy2(J*4-y=VbYByDFJHiD{f*boe}VSPqI0Ryn8>`vf8Ib`Qa*Tf z^Z&}$C;CWW(n0(T;EM&(4LDQ6;(XG-_|>Q(00kl|?B(tXo@4zgW>`}7KqjFj?}Ssn zhEaGzBf_*KJ7~^FM#$F~ItS=uJvMi?5R9C)hr|IHXEwcH*d;}q^fce3DyJ&P`2C^F z_iu!Eaq22L4e`y;_rFY~zzqmvuw{3^4Y5vLdX762p`MM240D8MC`A?|+ zY_9afW~-G*W*hSw1j?3bFn5j-jL#=X`tB@Iq|$(HBG;)87;3KXw3@;|G?~ z^DTh|M$nC|^YeD5$LagqqeX&nK?z`UagOMNU;-I9gkp2vzDRZwf8j4CjOHIn{Xr4* zzO1+H6{_ah$gBXLhppVCmMw>V04YTzZzlzERDv-M(2xB(oQG1z9h`Ri~_G?%+ zO1N&pcB4(p!KQxFl_u|-zZWko^ywQ;aE>#Dbq>YsmK}V^k6cnp^S)yuLUBeIG@sd-#=mIUG z5}fU@pGt~SjUZ(?hDRvbqrEj&BLYGh7OQmmvUGIaZzeVVNGe-Q1ANWFtq4R@moD6>Nqe(quC}MocDPoZTI=MdNf6w=XXIr>2L9BA)yH{J8;H5~t zt^lum24XQ-j2#|vi0?ZEt@&|d1s?R`cN=}@`wNz!H0Rr4^f$qYn9x4neUk5s9$9mJ z?VU2EC-#5g?5LINf~pTrmy}_M%-%g(1&e%9Xm4Q%Y8`!DV}eGAwT{2Xl&9SR{7tn3 zPcz2Zf8ul!B)zH@Zdny^``^#&2I6lm5-t%`YVk+-Jlq4VlPJ~{Y{6%nXQP1RU!y_~ z7oPK=Z!4Di|LBos&2`YG10x_rJ`8$t?qVN$&9=T3Ql)h_8}%qWTt3JxnB=y?FNziN zM^%pTRqPgF>9yV&IVxylMW`?)dQE7MGrMi5f6<9*bywa|g!veLWxCPeB)1-3&D8Cl zh#)51>5m%9d3n)?3&XkG0P6%5YmOW>heR;cL|Hs6Icl{oX*Db~K8pfY%HCs6YF^c2 za~;A^Dwb-m_th56^`^5l$W#+5Rrc1NpS?Acu0tjvPum@-dz!QJ=xjve;LR(u74n0Jx4*HD<(~+eB%bewT0_s<&`Az(8RyG{j)Fw@V=srJ{jN?1#TN-n z{~(TuTYaPM7Dk5>OP4Xkkk`o?*(y8dCdiS2Lm@2)P{@>zlf$6nDSb`Xw{@;;ly?2( z^%#I`4gr1?aC;3-L5zxTy4#QV&kp+Ye?giQ4>#j6=jyTNwwk|rw}3`P8TopVhe$_Rg?M6dqqmbAwbC4!S|jQ-;o_1KX7 zSXDFR6iB%f<9%(VB&+*;V{Sf=1i{FdUvm6gBuT~nq+XS0%5^eY)HXyr=2^c25sP=n zLnOaxRI{Fi?Nyi<9XXBAy3(0yeF5&S15o*2uC%;8CUq!vpbJ z<0GD+Fc^-PGu&k$u*`BPg5k}#fYK|_19v&RU}eHK&X$HEs+No8s>SB`u;MGuLITIR z)lY513AGu8$Yg_j-D>QP#fiZ{{_FgR^qF~ zfL7uQ3I{wG%s^ng-SiPM|AKE1i^nZ@MG?UUE~RKLSCdz-kf(UAqd$tZv7!SF3aV1Q zdDYJr#+*hOM*$4v zeoKK8t?<0yl4Lw*l$Fe+e~Aox7E4#IGq^G*x&7IqDUk{q;HTyBQ)MEEWu{Tg;8oep znQhUY#r;_n#aGGWh^g{x4gE>ZUWn|2UPdW(x0dme8~mYHZ*=*b@`!{JcFY4@C*~QF zR#%;e(=PJOyA&)EDHT~>c;A{}%D88vh_;WMuX-l($J!U@T)*{ zB3qa`TZ2#bjb2qQ;DOaOW10oMs*g-jr!Sa9Ia#_KFSA}Ef8ZvGb>0&bYSu)1>r~SE zHu;_7^P;W&rtGe4?fWw1q3MVXYVtA=cPZ|gVkpHWSC|2{`yvzG?avOYKVO_+P}P>o z+Z6i)EmDCsPAs9NeK7d25(o35vuGLu+P*~eZUWJynl=ehqHQ%FPKY4n06iJhk`Y1- zDDT`q;y5Lx+5X{t@J&<9YUeYY;$!#U%pjr;AtR)^LZo-}eouH64%QAe~t1_kOtcdO$p`jK3!!r6~;rkuS^2`8a%_Yw+An7|*edU3?9 zE!=)of9(?t)9M<09AmV_^!t!#A=Dzw2*1j1tX)IwSxN;mJ6gz%1ZZ zD~zJUr(?CRi9yZQ!MtGl80%y+-cq4K4HEab3G1>(W6^7Z11bIu74X zQ-Pl@^h3Rpc?I9fH3*C9FIpcn_*Fu%@D_lS?PEwxT#w)OOOWK;khB(CzS4#y)0Acj zoU+I#u4WX5uK)PVgzN3qw@Eqrhe@T9?PI~py>_JlBs7K^+hgwv40E$A5BhWwu$A}pE9&#<&f|JNYCV0 zvGK&aSzDgTzxo>|jObBLhK}Y6KAT(fuiUKof9gw0;_iJWnyq1FYQ$HF!(PoWu6rnC zvi7$|5M8jCa=woj&c^-gO_BNRc8O1=e+{D-=gm3n?2Lw#`0Hq6#LJU*@7%2GF17VL z){zt?&#}U<*C`z+P3lH+*KaH#{^cLMkXOpbx~e+{;td4F=jwl#F<4?qxZ$#)A9LAVY4z+^iFzOMX-L}$*n7*aOQ9rxwaGQb@Okn%GCIll(_MicR ze2UKE4M&*aEOM8T%DRKsDgvAY`A=Va0-teFqTmMjGrm)7@xcbjNf;2Rf4jcZjTQ@j zPpdxwjJj-eHf3?95;w!3lH@rJqdfY--glK>l4;zxJOz%f6RbtIS9=&Ri1!j-fHM1G zR{zO=jw-ChN23|LYxgqIjDZatROGFF1JBA?=i3h;@@+ZTbf(h)iC{U4khk<8&@PD8 z0*gy{0cktBt)d&`6@87*fA8g3uX{e zBhUw*-S*)Vm`lolMhw1gy$`CsotiZ}iIyZUTj;s%C6KR3Iu-w_=WhekLEMy-w z4qZu}h>n1eVV~2_1ARg@bMbAbptq^*5G_@sONovns1v11plbdke-qP)3AB&HlB?PE zuoRX`wWGQK4MYT;`zNzl@EpQvq9ASAX2`Z#+Fdph2bQU}LKUBx_e3mX$-S3$55|v>*%0K=xq|qGl6yDy)1tyeG7=V%{pxBvA;@Kf8Oty?bBAmxUUWFwjKY9 zbmacAEMQqT7)~^-gwLzGL=n^<6seXS?afE!V5wkMB$OXCQfIZQL}Ix)ynbML0Wez< zTCH063#O$0WoK8GR5#0zA0bs}rVr~#Bv)fCTL1A+t+Z?%R&Uf*)YWapobTb&U;!O3 zqNq<~warPSk5Go33*s*YKpNaaftcY(unle1noM12edql*FI- zfmS3l9Z#Wo;SIA_y)#>-C~$J3#>8A9jArNFM2WAX&whz%)@$isH&J(HKu~_6{Av@# znWX2k9$hX%$B77xo9IX~n!#dSp+wVMA1F8o10Y9ef1~3yU3&>F-_d~1ndJa}zA(y3 z(3aJ_9N83{<{A`HG2fLjM+_PzvZ>ufro5w8i0{3HZq)x!vh}Gptx@zo3I2O%YS3fq zenm!psr&i8&!KhTm3_EUWa(Lhu?c2xYO_Mb_h|#38)|_^{&j^21<{ z>U9D42J^Rpp3uZl)%%cG?}sgVB!)+CUMLPbyY~exSR!2-gZMLv%i++4Tf}qd5>{76 zPODG^Gh6#>$&(XU4cDW%GZ#6O8VEDdBP3Def1fRk{Br2s+1Of8UH$VuHvsGgzH@^C z5q~a)hc1kO+1SS)4Z!K{U2{sk?^R~t>28qW;Mp$lWA0pOQm+sQ{yuOIe0zM#gcAP; zJbl}p3$g(UodN}ZUU}yRF5epf15v=1{)+}-N#L8>kT7s3^JW0p0n|AMzI`@4ta<>y zfBbNw4sHj=X(t0WHx1uz2UZ+#HxCMefZS)hNkF-HgN;3Dw$hAaF12?U>!q47PLu^Tq}u~-KW^`WL~e<{h=Y9J z9f5~Hg6h{iVQ}%E)tl{~#X{hQ=xy*of@Hfw9iT1f-dI5PUP* z1{$$H-8u+X2Ynj>k(K43VcLw^jaG<2L68DLL6qgdAuvE-U|>Mz0s`bf{(m3)f0mcE zlf8wQlev$AlevXGvz(2ig@cK^jhP#>l#{EMiL1E?8;i*Qcgp1EX|=4q>3GP6e-d!3 zg)$9bBAKM{KxSZ`k1D3oHx6khCfWQwlEB0yX~bo;OX|^-4xt0@(%qh59Vwnekk8Iu z%J%I_S#W>mrfGbq%o#)FnidM-kE>cZ`6NvraleiSFb@3bl7i1z@7yrejvsetg3G5i_OQAG&UoV1r;^Glb0oA+har86xE zzgH3_?fG=(%IWi$TdH;@wfe$?Io(GD4VKCSt=H?LPWtAR%x*BZ@69c*sleN^1A_l) zo)p|nqZI@ptP!#nWM2KXf7PouB&|S+1?)KLc7dcAzo2=42ym?F$#e7sNJUp+Qib|*23V2Xvw$kMre=QSs^-9s0Vbw|? z^WI&q*Brd29Ul#@CxIyE3PF=$4jbZ&qU|RS#;yhzmR=bXQQy;yt%5&*)0`$ynGl#4 z#QZi_t-7wG8%?m`*0jf_;ruBYH1y@*#F%d!r?RTL>xNF=Ec3Y1?sO}(gBps&cs=?j z)9%pgDmhs6gFv2Re~9z6A4<#kO6nm8Kp4+$IP;P|t+f>MbHDi&HFB79afrjV?BO>l zj~bR}xFC2aM$+4aVw`^*nTZT4yF(1lx|Jx%%|{M3e|ric!hrx%u0;FS|Kue#I}XqN zDfR{z8)P8?GWb$w$72OViU2uw5ckW9jq#0_l%=zOO++AKf4aiZTYVaG@j9F1g5z}yf> z^!L;|62Eu)f3a~6=psg?Mk*#g>A!sQeu3UAoo}XNZ`$Ef%tJ>Sc@3El!S*^iuK|MS;95+OIVlqi1{%Cjnx!Cr70R;V*6g!-zY?I(1AZpkk|AQ2i|F;yf zCT32iHYSd4|L5<2+mN{VziimbglIH3lrX@`0Dmfie*wd$nSTK{&t0Uei6dXgyjr!A zF|fbJi-~w{x5HmS;Kkq-aI=)~c{xwEvZk)#V~j&l%QdEm)96x+qZkGLJVqTKDn07- z$;}HH)I_21_cQ7<&$0R@+dLHRQLTFF7hKdE(7g_1Mxmffpga>$fW;d}6eHb-spfv3 zyASMcfBHFQYOq;^C)3JrBXtRz+uVCQk|2f}+tzvu$tnM_)QOI3PR3cTrX#k9&eUo3 zy~@$Nq#v`a)o@_PA@gdcS-lKInWolSpc;Mda8REV1+KC|@?<#6S!U>4oR4ov_%2#* zs}WBrw8}33ZyYp*LFP3y)c?8Y9FxwHYm`MHf4htA+0_%9u=c^}M!hLnmp}%u!J-yI z+B852=Iw4O)~oC2uqBGxY-i0{Etw1H0Xp;No)mu; zeL=UCEXN(mlykG8X&h>%0)c7&Kq);`P;^4m=3topts{RgWIs!s}&%W4X43Ye)Z1lkOU$|Or*iW z6d z=8})pgSoZGgWKfxH!nEM@{0~JuOxV(p1QsNQliBtsOuJ;-}&3>+6pMpOoXe_Sr*sAK3WsA!;iQO= zkTO89n_E~5sxO}e3hdmz&gS#_G~ubm-{V9&c5e|cQuz7Tk)w*me|yw$=G7|yDYdb- z@S$Q<*OdIB5x2{iij!7r&22-Idu@wzfHOE!w0w76_YA#1BHIYpe1GMlGq3n*5CG*l zxl2=5>XJ!I=!^MR_}n{T_m_Kttg8RwecCrs%c_GAWV<@LnQb=C!@91dS_X;uFU*LR zu<)?CEmkW+ol#M|eO0AVZW3SH)q64<#k67IeZKyH4LmhsF^v(b({SlRCiXBdCoe-QCw8s8^#cw0EX7;2*? zq&~v#&Ixmw1;!63)yPd$$aTJePOZG=2j}O{dnK9qxJ9x>$5o}E0xy*Ocp&90d?FA8 zKa0KrX&8Z#;8n9mcLgE!1`exqhDdh1)FHBSNv4FbS7-W&_pX~<^w*C&TEGYW$cK6! zd{{m2v^8A}e==_n#*gN%7xIT`rNDB3qEnwn99F7gNT-ad-zt3m4)%5!7p`o(B(<_6 zIXFd|-axAf2TxbB4FN1QACv!Nv$~rnWYP;+j!cS3?WOXlhz*0~(oZymXO50Papf1> zu?}0Nq`K&AQef15?h2bvC?lGE?DDGmW2v^ZjarA3e`??>E;x9m?wGtK{k6~NJ+1e= zC^}s8=OMBb79JzWI|1IvP=!Vx zS;A+&{cQCQKI8f6B7TAnWwtn$KYQ)dbEDCQe^o$eB=WwmAfoiX#K1tj_w3d1z>+s@ z=x?dY3zPBF4hw&npJ%zL%g2C3!u?0$4wL0 zF(e0vmp|UP6X1kUg>2?*aYDYIgT}-f24D;C)>=jsvkKs|F1){+#GV!&cJCmmGbI5Eb|g!YA2$qvlewC-3keBz_g#8@4?$J;1dHv~T7c*^ z8rSo7;a8reNak zYUBOijA>0eZnB{Cz0$*+q=Kx7UBfXzfB!9t8U_Vx{RUYt$KcY{k2OqfxJ}k&;B~|! zcSHd+TJjLML^|cm*!s83u(y`?np&Wm6zAeBm>M!^r%1h>CN<~=J5e3l<`pCAMMuH# zXAnUpW}e~*DrX46c+>p@KcHXAS(tI?N@$Fcm(YiPhaiVhQAZ6#G4*l4$(@nfe_ivP zR2yMaSPE{!&%AUPkDU-tq(BfCe?FMxk%R>_!(dy8vQ|Sd6WfGa=?Dbb=jx_0KxFpg z8CmR!t+vu&$IZfympppo?q9spowyqVHP{Btppwk#js(o)9B=`mm!01PQx*bN2fxPb z9?z{RJdi*d_FPmbDd))lOoX;ve^cUS->LoQIjBksCBttE6UsqM>HR~?E#0^m9{0QI z&h>xmm;3^gO^am3#XmRiE&Roa3&`FApdgt3joeN;PtwO%;5>N3NPw{3fMpS`LEQ`y zsgouuY&}>%j==l5*floDy71M(HLQ;v3mHC=SKe9Ipf@8Sv+sk*yILCNe^ZC7V*-ca zoe(A6N;z36RN7AQquc5WjK;I>f$GNcj0>vxn^@BLIt%gnf~eer_+kha(?{RLtrQi& zbJT0zF4n2WG5MpIOzwg_2k|O&`s)t#5A{m$6G$VZU2aR7Aq?ahgm%(!o;Kkfc1(B9 z=x662>$Vr^m5}9)^YBx-f47TISS>p?eJ*>Nd}vUIpo-2$aS>_q(sv$|-8S24O|d_J zdXJVRN9;T4&oo15L&@!reXf}IzyS2y4I1hK#lOQ|myXva+Ls`jye|qk2b{3!Y*Pg8< zD-9S11`T{QPgj4{k=cL{CM2I6PTdw5ykA~_ET!*8l{8-uM1bysP=uUVq%^u~SUq7e zL5!e>Q-mODbm*A?Fhz3sB|QlyBKM}(_IPGs50(~&VBIUq!rJY=@-V$zG>Z5+2e=!D znxph;koY^xdR*Bbe_q^~le=BdtELWVT(xicHiHCsj~Gl+fgYQhL2u=G{_p=?C59A! z_?iDxCG?U1rx>#R4>1(CaCCQdvN1QY|L-t5Is9ku;qbqP4+p0b9+aQ{fnnEyE7=g^ zFj#fcbl=4Q9*Z(rzgKW;)5?b4qd}kbpASNOdGVZWMB91?f3yf(pIE<+ZNo29+`otgcN+Ii)BBRyAUB!sE z+K|7!v~NkSi6W7iM1R3b?G;y&e~}zt_zLVecD$^#0q6+TCS1lFJ^7D)Gh+_!*Ce!Q z2`*c_xfE2$f0`MFC3T$RZFSO<1cqOAdc8TsYY;Px1y`$AaOL;$4SxeHxM5cgOx4s}STne>;EM;qoU1Odb3umH6Y{T!a-Z z=c&}s_SK%Q75XrDMNl{WbCb~@){ZI3Li8EZ^Zup~Sp`qAmZZwL>3%eIHCK=6hChJY zp>EfwQwz&#R|AG53M%YWtvrJyHc+zRC(5&gF~;O^oP~4i(RuJ* zLA#RRf325xh4}laSU^P;YABOiBbb*Hr1_p_WJj@MkH{dv)}>Qf2RsWf8tDb51Ko3fyE+-X_(z*!dSl( zq==X5$m7IX<@b_2b0U#bJkS+Um_;qjgwM9$R#r^!$7+iIsbC+3`>P*;cX~g znAmXU#snKoVP}Lspa30KcJ~nc2s1K)a~y)z0<*fC?GDdk_TTFyeR0d+jtt)ueSHY3yvJ3E z?aD#;tq)pNl4c*qi`D_7@)lVY(D3YjjkWP^!MJ>y47~kvwSD)Z!hNXrvt`66?#JH& z{c!!FVl%f|g8#Q;Y#mOueHnuu+P@hC{l6H4n6N+o?{~Ncl0eu^{G+46m8?v7I6B@R z7T>1M=Xs1-V!M`Heb1Bmb5DD!%;gaI4W1?l`iSnoLZ41f2Pl;WR!A% z3SiU1dlbv;$~+C_p3Yd3ne{|7)5|2`8M}!juBr@w3wk}KgiNL{FJr6tS$a`{o&nN+ zMLT`7SpFMi|JtbbLGIZA8Ko2XlRgG;1lg0MtVEOST3rWRU-tXuHP($&ZDd8xy{9?% zaK-#OTyG1Nes`Zd>0aeW3JeTF4GGmyYpGxmFDkllTtiDZYybh&IlaoeQTngGyI?E?kM5xzHzq zyDf;>0WzCjyaYPW;?S1p3(>o|TE7EEOhR{O1dw0h_wnkRWa= z=LQI(kWK0L$hARGH{63<}n^RjkkO8sQ-K^H7>U*rc~L3<$v z2ZsjFrl7`ye?cA)x7} z9$mTpmJs~8^nI`9z|X*}9F%6R(Vz0uh(IUMeR2Y_e{cyy#iU!N}7qpauA#sf2>W46VUg*uDfR(?ZH#5$b8B( z?7eA{fBHk%xdovkQ0ilv?enE)L-@AG8}N?{-4n`fP=2+9MBIOKA;y1kArT|TKMo{d zruVlj2;0~j7&-iRI>})8N+&vcZ91%!2-pntN+X3{$0212WLB?$%!~`velVFS56hR9 z43K7vpez;{KTfh@A}-%H=EwUEZk^)_SZd7Wf6y3-AX@+{dwbckexUv?` zV5|l;w}w_6&MEHRegYL}(A8^T8j#m(A%ToFqIupHZ49Ln_*2{>kirm$$}KQw@LGNeFt!`siNVHa+y9OJ~>&)`bi ze@rV{G?u7)Xew8Nqw}1Mu;;nV)aB)oNM@}5tc(wTJnxYJ^xf!HvB$Mfjwou9Tqu^> z_|q7^A>U{ZGd-W1m^i`t)>OvlOOKl)?h6r7*S(91fNZ^7l0y{d=ekAq^kHcMhYJIw z9;ajQ&kW3$XxygJP)C$dQdkk~pBQFJe~~+6FU^N>jJu%z;6rJ$eJoI4fEGpzz{t{# z^<{MlZ@m)#ySxm65YFarRiNpi6e8yO2IKN6Y1@Le!(Ynue_(5Z ze{B0D+9Z0j z)NB^wZ4=@PC_!pB86mk%*4m8q#*(Dl+*3*T)h(1ee=TBV5`w03^pLQKe{7GZ%M6{a zPp52i)AV3BAF_pCp0>9Lq=h7X3JIQOB=%q?ZD~CNw@Nq$7+_qX^2M7fqm_*)O9>C# z_HiEg+o=1=Z4`qye*J=7A15c>(`5rH!;U|G@USy*>n@#A_HeB)Zao1rZXZRX8R(z* zLgP9sdP_zVx@97wI}x2Ke-ZN=;+_ES>HP>j8~}#u0&BO7EO#O+pAN>LKf=0j+ZQr> znWx9qMezz~ok_9QIl|<{U)0=DNtsC-zYlDslFf3RVV;v!VW7+>S0NvL%|vIJX8_M; z_BKC+gB0h67yjl&p{C&^r00(n;A>O`SAGQ&vwsaF%>TO;h}i2nf15eF{eRp*#mZ*w zzuiDRjHDSEq6{MGMK6JjOiBF_7>Ip`WpII!{&&sxs@rZ+B{fwAROrUD=XF+&hdpCg z#yyRoL^TxQErvph?%-`4PJ}1YzRsgg7G3wrWB4IR)u5`30S*J(DOlDjOaUc&LRmCp zgl2#HQX`6|6ZJA9e_1HO8XN*CpfCb4y*}5XyZ3Lmip4Rl=W0dd7(@Xs)lU01Z4)9N z_5;y^FIZ_V9?2+B)zJ1ef8i7eP(Sw?a81O|3UWJ^TT(W6N2?p|^rvv8?Az^woL$R( zi?O?I6-C*u`%DG`!0e|@gZ(}>xRFL~Jp1j!8O}aCGSIvJfBMw3xxoPoyjP`ygkHYP zm@%7FJ?x&;3h`;}3>Ab)Zian`S2q&OSDzL@l9`~1;Q0CKBH6RB$lf*GU!HXD-eaq9 z8~e8L_;Et}LJ|Q`ZlZTP8mqY<0Tu_#k`fNM3Q^a)nR*G@PrbS`U|zr|1>O0%!e_vV z|NO|vDpB)be;>Fg4RTV+prt_47l5ZbFzW(20Jl6q0Szc{bzhotjkZL~pU1Rit)#!J z0XH9{eUfITh(X1|8imOYK-__Ld3DC#q9NCTeg zx82nw-nYy{_}#(t5F5Q-7XYz>xCsSDwM5LWAn46ag+M}n?3XAVXosd>!i>nnb$K4f zmJt4@DAy;)GkVq-PDB#mCQMJ9)ZJx+ovy&dsXedZPPq2(Vx|U#lNl&DE@Cj@*6lh z={efiJJ2iqqeXcmV;D#^lFpxz?6X}`yYbZwbU)ZhP-V^FJ;n;f&v*bJgI!tJ zf0?93Ur$_|eaR#i%G4ifbDyS$pD*4za-?o*Ye3f+7wuOIS6m>4E7eB**_6V2c)je5 zp9m$^w1POakDbB;W}@=VWS23jFl&~ul;u(e0a=Q1O*T#1WElBDCW(F!M-m9m7rR#7 z|Ju53uXgB|Nh-eq5(ov)^GJE^+L^p1e--iJ$?(?3 zE6R&>=k8|0**quzy^@CiB;u-mu%fP37(a##Fa*XJ3C|>woIesx`i%^?AQEUu z1=|J!_>}MhQb2>$+Q#y#gBRFI@cgoqTHHEgPe8%EIt}Z$GZ{NX?yv7VAD4*`bWXkB z8v(wwCx(1HmMFty4E#aR`$RZXLVV2DP@8%*-hFH!Sv{!A zca~Yl_*+Dr#$YrF^DF`RN+1BCks>o{4#EJxu+9fUAm8Os?rWCU3+NxHF$X<@e1HG|L?HeR zYPx@gTGGZv(#YB9?>9C&+)uZRgcD#YN(VYC?oJ}+jVpLe6YuDU8G}KwVei9GU2>{5O2{LQmz>V_jo@a zOI=xIJFkTDuF(xp zS1q&g&pdW*GwGBY@j(&-20GKRb*MK!9^nj-hylH#9i1R4&;2%#!!I(=ZfD>a zRXi94!kxXnnoQrQh*v|E+Dhcl1)J=qep5cK&=8X*MnDiCx1uK;6U_y+y2t;6p!XOA z1K+BZ5K1zq9}lom?*1?+%8O;kkx|b`enM+D#I*~_+40A;e=d3(BM}FDQgXX z{Qhp*JwGrDf0%{iMXK>zNr>2drbK^ADK8H?j}zi@%Xtsc86%#55x(g##5{a$)qOdz z+DCvP*Qh-8f5zGD6i>kiCj_!F9ma#^4l^sT`EtWi7KuiUddsdU$Ve9UmN;|UE~>a* zL}4CuuJ^|)F)kUoqi!^uw7f_FKh|r+F@u|fqwXgqZvLRmNGi{)pFdLF(J@0pRxRix zkJs^sKin>T)nbgWv2QRlPquJgntDh;nUgCbr@%w=fAJUN)4b>F4}SQOZ<~LQ(JJV% zAVaoyv9YGbPk zy|YJGnM|uas^Nb7b9$DUm#PnfYM8Ox#JKK;;HY)v5?AAh8yFZ1Apb~s8?a;VKpQ({ z+|b+g(@nh~96C;~jAWpcMcqm@I3=HgE#Tx{e>JZ)>i$le4`Q9EOu0e<;lRMCZqoME zLdDd1_p^+BrY?}QKZyo(+kL&CjC+ZDIJa47bTXlWZRfklQ5KM|Rsr;?vN#*2HB`a# zZgMmP4BIw8qXuZzw>MPFMgSymM1@9zcgdOC`>x+=W{D4~N`7+#5I4-Fw~jx{S!I4p ze|N7U;h3uubJUy!5z{vwl96Lh&H!z60bDjnupa>4r#|@?W}&sP(Y0${%ntAz zod-NYi|n#|3$@K!yri*EN=Ju{sL$M-SI z^g9JuL(RUnf2@T;x~(L5&I=(|t8R+-6)y3UdR@lL-903{87Agj?Uv9!o?SSlJCJljv@wUmf9fuw zPUbYIzWXr%J5S!z00JJjd)1Yt?*cjP!<~2GhcEtd!uE$+(Lhxf?JsIq!2Y+JhyS5g z!OY6Z@{cwDFUU^)MV46%RB`QR^*1y54sZh9P!$7{AxN_v?_sz?!#~I({TH(M83z|L z5RE47hvLPlUv^9etz@rO^7J}@e{SP50rZ;Ddz53+kvjO*(J$L&*>L^>xN5MOp&cp+#F?>{~);pf<<33l<7G_aJu zl7<8+rf}8lXcvL&B$}^NneMhriawn@PT4+SeEA8vZ9Od(Yq(R*iKLDJ zb!m@}xVK*vpMX@e-wV0zUV+7GiYa_3Rxryfy;OE(wK6r{ify97K9Su`W;{ zZxte}Ld$z(Rw>lzy#s z*P*2jr!wf4i(V}F@rO8e*!9n;c>r@YMvD_iIzkbB!H7pQafm`o59>Bp z9e48eFayA-ffs-DR3AEb_qe@JMU47c?zCe(-i?IHh&3wC)G}q2k$&%byd@_ zo?TA+b8k^liCDmZbM#$~EnpyqKx-{l;YK_S4tk}=_!5*-4Kyhc#|+Q|idK@_*sA1nsZndKAd(f}V_b(38n3iVU;Jlszf6w=hQ!lFXI0kg^3y97PccerMSb71kyrk!~x`IaMkt z<5RE&fA8_cRqy!)?7;-<0jvnUqoNyn3U9PkaN{kRWr^feXcy;D{1@N3$#Nh z{}dpi)Tdb$n#1iZi0C-XJ$~J9!vO`P{d74O1>~@8RJt;{U1vz^>fc4tKd2rZlWEAG z6vtkojXC;jQ60z`lOKi`q*1*`1zcn6a2Xyi9BMJ*Px z8r9HmcHJz6OIDHA<3h8G_GwZ_`fWzCmta85f%(Mfwk4gCw1q~*T9#9Le_IhxhkbNT ze7R)q!!Ymr`RmC=z{Uj6NlF)tzMwZN-?J}Fvvl-#=@+`EoVjo`wJTV&#$e0S?r<;2 zS%IfbTP~Z6HNq7;v`|TzStVC`)bfKdq7e4a1o_ej^m7~)1qa(DWuK@L*q41_|2F^- zDLk?}y>L!=nOd)D?tjs%8o)^pLcVxsSK1`1zd#x`Rvv;Mo?3dKDuBmMmg2{UTHx}n zHbIzMcS;yV;_8iG)`wXr#*@UGxkGXihg%?!UR&&_M(6irk;D>sN#A)}lW-PhhaiLD z4uw(nS3xFN`AXdMHnr(Jc4lcCxDaqBf|(GbGHBw3H<)p zCHCx$Pg3&V=9xx2__G#NI|JH2aP0tc!$d4rT9|0NV~y~^92HxxTAf_9bWs>X|KsSE z+Taj9PyV`2A9}Ffp#HeM3-)$`;2c71kApDTE@F7+ZHJjv2n+W&s07TA#%ktAUeD38 zmWWXxH}hhnbwi9;I|f%nGo}f-e`{`^ei`A@4eRln>5NO&Be~MD5>X>0dYbx$8h%?jFt-9H@XUR< zuO`BNST!cY?Dt6!9@H6I&yp@7YSRZlRGADQ z)Zo-7s0)|o@Bx-}P1Y%2+uyUNjD}sywlbmHbu~ zfr*WmJ#3_YL{gO;VZJ4#k7dD&iPq8^Cz&FMxv%ZLCybAW=Q!X~bSG8&PVy->9fOu= z2F)xAy?gE`%`R*EVi$0^(Q(40wmV)%`$qOD@x|MX*iTq0Qq%uN(wlzzx+eJbW2QB~ zINE=OV@7FqHkv^jExlnD~A zrY}!eK?1BTl>C>(oF;;AMczKI;AaILLkD{EVEoZ;ME*hc8!xC{U0b{X^-`n#3Rdq8oP>&{KBn2<5 z=RDCMi{-6hrU+of>0M-KcMV9MM6nWn;Guqz;4SvC5xv?LPB+PYMJ3+*hm{4EvrX8t zszGvr`cpQkv+J@J;%`mm(q24Vrt~-ba~gGKbQsnz7Dvp9`-c^@DpS3Lo=PnMgYOTg z@{C3|AW_Y!a!nipYPL<4>AB))pqIi#D)4$+@|4`~Y6}3dek<_lP9ED~oHoqX@;g^m z`p>3Ffos6_DwAYd$(7TEW-2)#k0+@?<($A$wwv*{uxQhx?l!IAQ7|qeD~R5Gp+1>| zeg7&*yMvNo%yX?Gi;Ku!?BI_0v~Tw@;+R<|+baXG{D7~ux$HHLVWU3D%R02M5L8|R zU34R+o;F|uVkYU}LSI6hkOdZiZRWo>H>=Rrna4FNV-i)!LNop@^5}f*vWYb{`o-k2 zf8zFlTl(M^sOKr4uO!$pbmjFS;W-_a0=pMaQWTK9aPeCLBS>*8WEWV|pS~Suv(utL z4lF?t!9KBhaYR+rPJ-#;;Qj(R;FcAEg?O;#U=wg`TESlt%wRalAI3;Eq>7l4b8sFF z+(l|8Ut@Xb`E{KfZkp}%#4c+S`eR~~_yGI}X~7L_*fh_W&-H_D@%#g%H97rGYpeZb zsI@)5duXrOyvD-8{2I9jaK9!IUlo4_48962l~FwiVs4%O@*}w2ezV6;#Svn1D#F5l)bOkuj0RPQHoJHD zDnYNuz~bJ=>;)MG0}3=mO2g$@_B)8iEO1 z0W+XGx4ku0n!?7-V1zYyE&96It+<`Ft^kBd5Z5X=k-o7hGOU-DbykF%<{@f*;Z*PS z?{tEor!RP?VbE2iIzKRqq!nFqAgy?@$T{?`+&fJM*=7dRh9@UiQ$t$&v8A(tRV;ju1_KCx zAxs-Ut@|33p230xdvI;x6p^b^TQEU1mQCM)dp)MtQ|P!12I@jT;sx|#-8gS4nT0cL z;;i<)Lr$qb&hfm^{_DZ-xib+DxLxwh#Ksudf0J+j2559avci@aQ!aq2n>}rf| z8(esfdxRA$!Ghp zJ)QSY{q+2+2pMejoEpr8o*{MpjGb3BpFT_bW$lzeN9o~NKl6+jg@iX+Ou z;NE@x1N@LBgZ?sWhze=Ald6JD+hP?frNx0o)iUf#eh@D*H#Kl@HXiODzKUc!0H=yGdH6magcI^a$)9`p-Rqq%dHB5N zdrU5K6BCr-S7-@zW&ow{W3GQ=F7WNL^UTY!pz0Rz3$rEDkGHo`>17L;-97ipf7=3m zx4K-`qczBSudAV8UP~#+_1$A8#D-Lj=n)aAIIYeWOKQUvAw?!*!Vq?qUy&5Giv7-- zGHcK*z0b8!4h!(WcF7i>tim*Ws~2fz7k6m+{hFZj$iam+3b6XeFnOXM6mD&iEg7?w zF)4f4`<%P1Glc2&q1C;9g>wA$2Dj)tEW%29HpYA2+ z(S=W#>rIw+aIK+XkAdKg-BiC17dl3Z+!Pg~p!m0qCI|HEyS!t7orev{HBbLANDzvw zL12na$ z@Yzn7#R9Uk2Frs*sEl=9L-Y=eFq{%-#=)dO)ye~##X-H&q|oMqW>gsD7bpa#I}@m! zDifWU&W>Mt)lzf$rAvlOOSoP}El06FH@tVHjnHnX8gty}RMGJw;^^;BtnkQl3=gkg zMKinb%K%y~>I-*-0_kykqql3&3(|tX)Zir;`$ge~XY* zy_He6z3LI#iEHfKsVRFVBYfrfOmuR_Rl?L2Z~)B5^k5z<-Y*aPT*vk&W`gMU79Th| zD?ghIir+zgq~6}RA3vK5bzA12^joD7)S)JsM1qMTHL`kR(Af``Gq1f$J*PD_VBGg? zX@^KdK`ZMfs~SV&YB8+VQF}a(VfWg>g=sW3x+%dbDw-j*ENVm-xJ3MU{OU|@#wb@f zr2wrU~uR3~YcZ)Q9NEfMOx>612$r_LvI9Q(u&UfN=loF5ya0>=Y zIvjPChBR6Q$}9S{ELZyKD{YFMZ669F&?ng`X`Mc~iP#;dCtPaZsNqBv&*BUF{mEUo z1SC9+x*BsXwLsFQY`h{AXN=mBIV^%O1Hh$HYnBUOLI~WPqZg%aHQVXjOulx@qWiWV z(QkL5pA>zT&SRz6x))AJ* zcC@+c*}Iv=KxD0n+7uod#9AJKrsDv7#|c|B`QsW$h4hwE{P)m%|dQXOVRjI9A}&<0Hy3!5t~= ze!O7`?2Aqa_9ER^^Rv>;hYzfA6{?OxGDnt=r~C5GaO<58Bs`oK)tz`5LkEWNO`^Xi z)V|7Fl^@IEZbwG23tnDH8iXhd%}q@z?W<@6iYXaO4(&F!sXRX9X0&0i9Kbg1With; zYgc+D-@w%ucqjK1+xlZp7#m7rM=9`d5_%{lr2lor2@i0RWhD@*XWbIIFBY{)6u!N& zVzGI~)j++yb}O;c$4Y*BSQUt||IGg9ya=D*sPCg)m;fE2tKv!{iPozFPyMVP+1#=) z=gwmVOe)MsT!jkWXiAi*39#;>3}g<`zg|0(9ylxCzTQ>)oD9piWUMC@XD=k3+lns# zp87d$xH*uxhi$bi4|a6B@SZAhP2|aYvoWNdoFj!kul5X2id{2TP8A-7b_UU>`O_>h zLk8S?b{l~~8w)hiRu_?U|6_bewaKH2JD#b@^W*GQaGwIM^lg2J1Sm*KDhdAad|Jt) zbvY%!17CHUkFvAAx+jQ*V5qKPX!(o`JcAzR`bet_#rDk_A#FM^yr2>PHtc(X92?d^ zK(u^sz3);(?rJ!Y$26?WMK6n=%hQbdR8{;%!Q@OK#e=xk;}|@a`AoOBwJNC|d_GA1 z7dgcEfhM6t`RaOh9WZyZ)~uf+6;l+qSrvfJY_wKVIvNK5DOm_F>H$D_9KdpvBekYU zLP(}K>%tX2#LvN7KB&Z`{oqkcqyQjRiTw5$scvU0_>iUb*H<-5FBM{!bvF<-K746`3%ljbUsJMjAHD*P?RQdaL`oYzzD_0b z8v+9F7kU zYBcwwcJi4bK8OCYp*|@oh+UGyXde|`(QK~=oLyKs5V{GMEk5mb8>?g*cm_A?-He+l zEWw%I6@ZR8nBW1~4M4@ezD;zW;AufLXmG^xFZGtK60L7)PV9PKJnk&HAoOrytv;+o z$MW*B>X$Z>6!Kq`oX-vxBKL@K=rqDByMgCr@Zhl3ij5J(?4B7p>yg~?7<}Jxhbx=X zqvPeO8jxH~D9?%(pO*~S3TbI)kvzUvkQ-9$M8Lz`Op&Mp5zcg4KGgS9Ey%S1*ptZI zI`9P9Yf0KISPBWsQrj%R@0(im0 zyY=}!d6EbI=|5&-ElsC_q)EX=lpGDsP7)?D`o^)d73TAa%noI6l`nP2$^E!oe`_kN zMLjJ8k9p!3N1uIw z98+T*bt%#Hylxam>MrMI0qHuKR`rDQAAse^S7&)ELVp>Go`z+jXhEG634m?FY0<6a z6*pB>NDjj~FIUJzfSr$P{gKyKO43ZDL{nb~p4n*8BUCB8hlr7wCY{;1fk?r(U8Xzj z7trMeIt!7unH%_|XM}|r`eo$VvF8k(yRT8sUh?15=*$mK=CQh+?{6v$wOF@L1VA7P ztJvb-9lnKt00ZTE_hq4JSF9oo*vhu#5zWWfhDF@h4%ZJl$oJkkT$)NlPjgUXZg=gk zc*wsMj8F#JI%TK)*U(RcwBZTp4!CGJS2O`LQ&Fa{}(@i3(VO$JI5P z+?X+^04q+(!1BK&jc7J5C26^&(Q|xHNO&RXV1!_4W8ZmeO~vfi&B1OETR>g&S1xu^<0}c)le-X-a5t3ZKPFuN|VYS*y&Df(l?@y zS%0KpL0q1!RUXe{*%;^}0PuKB)a~;up`iLxN%{G+oD_4n=WGa?CGa!6|2h|SU=*n} zjRQJ(_e@JJ7gLCC`3ZylN|VU!Ui5oc$8%B`I)(A?D49SbsGNM;0CGsAOmI7lr3G0V z%bMTpnRKo~8mH4yEYbByA{xLaZ=dgd>Fa|0`1qa+6hT#HQdFX2bsOKOjT}Zg7mZ|?yY)cW~nVy(hr#BCFdwPma z_r_yJv)sX3>r~hqJLBJBIX)P<+#x&Wwo{nh=gr6Z=h7hc&feEIeEW?jsX#VXpiK#) z$bG8*#NH3N50L0Qfo!Ad9$FK1?z@zQ38rniP_yD;2X>?)(NpOS(yb1=U-P9WzgY&Q zgkRPJCub>P>#lQ_Gdo&cpnj8|`J7!fJLq~9pO~Q*$Yl*n8^aw$QxfMJ88<>a>H^L2 z@xkSg@+||Qb*+@*)q>bq`|p~AD@E6_>=3_HS4t<^0Pv2xLT~qOCDX6K%pR{kPBq2} zF-q;6w|)FJc&7fvLRtrL6so?kk>cy5{|5nHo5x!~lfLL}_qvpf$d66ALqs~xEyR#> zuF+exosHOOV=fR--ZZFgq|zEy1|@ujtY=N!9N$f4r{x)>4@S&O9`m}dg3vJiM~T{q zc=(rsIN^tJhAucY83Sr=_JZCd`|Th46!$5Y*?$o}Yc?qu&c&wchrLK+8> zE%7zQoCWIM%k$3%q1fRiuMg01&6Qgj))$9+JAhzZ@q6Zv89`}d-}%c@ZCtIf=N;YW zK3NW{CR5bKyRatRrdvs(o2`pSA5V8ls?901gFT@(xVLQ*NobA{`uq(eO;-IDJlJHW zOrSzf|6cL8Gd}vO`3Ik0iO*^G&@SEz0K9(kb*SN-?q`Rn>Mn7P@+E=aOz_M*i z>@?_48Uazw;#LejxIJRkYCCmlEBfo^wkaxmT)>+vN+qhpDY9A@I4_|CT;X*%cm?9* z3pf&WvSwy|QbC5`nUMhzbJ;$!1Dfhz8vx%Ami#M%)C#;@FiK0)GH*|2;YM8M@U7Ar zy)4n8x|@-J=jTS2UnbhE%)%jymn%TkO8P9zD=A1al+*W6v!(5B#M}VcM=%Sfx!20v zI0M}L%ku)zbQaj?ORpc8Q6KyWuit@KnYWIbusU2;waWM9ohELXCQ839G{Ar%RREr1 z&MpEdfFHqo4m5TLf0?l!_Z}7pW7Gv~)Kk_(XCR-5I;j$)RI+Z+4fu+Ilk1?OVO6iP zhR1*EJy7L?h^fAT&l1IIuh?^m!Bq$Qfsm*E1A!MdUU<`_uDu1%XUvmuPjo3oFWS@@ z^p2$ph07KrAW6GpFt5T2FNoG=6ab{BsTT@3O`|8IbIsUUr_Du$ypMdf#o4*4eYQu$ zdtA)jJ|^juizEpMC?JCy{k*-OD-b+7@|nl$r>h;XD_b4B-tOI%$-ix>p+jEQ-7ik? zdl9)SCz3vvVrqfJnl2!*QmMmMZWxfTl&}^$HU>0G#%JS;4`1&Tz^1&&e*hJZ5)bf! zlJ#}J?(QXcS}pBk+J2vAlIN7dtt2cNQEP{gc{}@vHM=U#g zW_t*8f_A5-x8fRJBxqBGfd|OJz;>}f;;-RU*H3kbRlp(I8iA{fUql>FsOz#2ZM%fsDIK}N7ZGF2(ER7A=c2B;6y zn)Np(2jfgq3X-R`NR@5urFhx~G-kik@(lEH(WFi0atT%VssiYH7oNFBO8Tm1!zk5O z=vkWtJM0!zUm3PkdaNVmXWhBJV>!&7HI~tc;I`a|PxjiTB}z$;@`2q0Nxz(+z907bzX}+VGk% zZ4sK(X>=QYz5xV7;H<#21u@OGfcpl?$6zNJY7;x)+VC*9JaHz8j$+EA5mru#ej#kF z4cdcMA3M!!x*#A6T{Fs_J5$#nsc6%#QG;2n_{N;>$_+;C=^zhoq@bo%1H1Qx5UE2k za|ERW;X>fh(5KVP-eT9n9JM!BSeReDtkC^!6C_;+pMV^=60R>!Vtqqfxu>QA)VSLP zVk-MLFkM;2bpNnJ!{0|iy+vnI`7J@Q{Lj8q$ zVKNi~SpX&u%}=p-5PgQ)UtE(Nb7b%ARYI{8iHuV!B}03M$1azQr>LlOxE*5u(MeJM zfaGqETF(o##eUsH1q{;bRo|7|zG5_B$v_ED7{+w>1V!Bl*64(pStXo!K+J9W>YM%?>UH=v<<#I?Bzl5=m1Tk57ShD8N@n_|5 zG;z)i9*5;P3V5v1M=Ksx4`G@+w9WGU0YCk6E5cE@5z zJpx>hQ=@O}6g22nxg<21`B8D!m6~nVz6yN{N+VNbw7Q*hRF)HIhsGP}=pwQ*sw_Z* zY@kT`CTBTRbsnme`;T93Ms5+pPw3Ekx`Ac@`&NIU7-l(1`#DgR&*WNdR@=Pi`!sf{ z7^MX|a*pVAUG}#~djQTW`&L@UK%ZDcSOF9E5W1|8&`MM)rZg6WWVh;N#D3;JNhoXC zf%1#Z>cD{428em!hwRSu32p^oa^R6Ip3zZHXA#Y5-Pn zTl}CiGUwPfXZfoL6<-1AaCBSg)WTylhl0?{A}s_5^_!zfUvE=-H?z@LNaF?}R(;Hx z*xsX9q@+&fTTe5qAv1f^p^{(rxm9$ZsGy*nW8(X@=@SN4`i9i#6EojsB`Fgfn_Yd? zY%(M6Bco8_Pb9#AVVQXyNPgt52!NQDJC%}VG!Nf+7xYJ$T&e}~HrFwYjfSi5z>g1| z5qq;T4*TKG*4)uA#jzCpUe$TX4+r!LtbAI`Ez)@W+GIBfV+U(0~r8`!phZsF%2tMCwvPI4msQnuvf;i)L%qje<0RgV_gh zAB6q02CZR!?#+pfAM%|A@b8Hb(8e?L(+>pCotkDc_Rk|q*5fhqSHt&*hY$CybQ%Jx zyCBW_nND07nX4VF0WbbCMX?0J7xH|CJPLow-VNl1u>=U=qE?5EKtXbJmdU(38N7itV( zKko}7jq2>62`chTMiQk*B$pAjzd(aWl>CHSrW0oN>L{w>F>f#rl_J|kRjgT_9~}jv zb~?Jy66nANbCLS;SOC;9AF!*Vc3SWyOWW%TKn;(>{6QUI9mYty8ePen1RvxBS%Qi!4rM1)pTQb^ z@mfQvf%<_Y8y_rfY^EJQZ8yx1B2i`){AI$fWYF_>n}ZgTuoQ4rx6gdAhT9Td?^B0m zF^`vQlGT>i^A{Il$iqWBKN>Yjhy{OyCaD^2W2G6(m%jTcCaD3PWYRTwa|_&+ecLOb zub6O6egG+Bszav4cehfF4eGL^*Y*CGjRMVnObeAjy_O^rj(I?T=vdZiHYcFZ<2mSb zqsz1Ve5bQ|i2?91f4Ga0+Gp9QEko-GHRqzJIYg74rq&vp{s(*j2m=~fY|iu$C^nIM zVbDE{q9b}}Nk3chA0e44J;GuPdOiSIhu-K`CZ}wd&>Z87XuK8@i)2iZOo=!r8eN%R4Qs(282IQJ265@ zoKfn8pMW?5X1j<{DT|aBXrhZ9RnjM@36_yiS=S{tBW2bgd6XZsSKQ}T4zdS*l>UG{ ze^biOSQhY+?JMV+@#xtHp_%G7vcu0`Bpd!B5-^J8hn zg>(20Qkdaa)fI@-qG)T1OF>U-8;e;~RwH;^VF$RH9vk~)95=b`Yl#z4;lAuH)A;bZ z%sBA%?Y~RJ=4Ffu8b_q%VNjP;y&05+;DT!qFufAsWyHrXFor;{L`^!eY0<<~xwRad zq5Lx??MDJ#;rs^LfGQ|BI7ztFv2j9%jaMruFzjp9pC8CgjP#=QXM!N4{X{H| zW~dm>ORC=l;&w?U#4;3vYeZJ9aU$(#n+8~D6o*W<&RvtXQ!0#YF#&*dV5Z6$SgvjT>A!p?Nd`v_CsEGW@K@j(LS|6*ADpHv5j|>wwgA&B=8`fcB5wtWFkmQrEODVtWAz715?Vdl#55y0 zaDGNlIz7>3h1~{Y&;?@WKn?JBueG6o3L%?VH8$$7?#_6jo&$#Jq%Qxc1pcwAeR|{&4CceLNv;Wf=JLp#Q9Jj{)IJI zh_xDE&D->WinTD|C-Fs0%77LqRZwUoEm0b`%C5^%f?q?jX6t)0?Pg~^KQ9Mp6j?p$ zH%=!n75taNT)wCaU$M!?m3>`WU#xcey}cwerBs|Xu-W{2Qg>@71nuoj^Y)6&*Bs8< zd9FDtDZd)+iD%xtlKOqGXQ!A<K>F^VNCS^^B#C(hSxo2d{RsY0f55@DqvSum0 z#coEPx67t3NflP@mO_+iY3l_f`RGQkFo*+|kz>Gr_z+3)6Q%RAK^ zClrbHT#5|29r`xL+yTktMs8WF@r_?=Y)AaLD)3h3x@BcGz0`zL}0ee z|5eg=Ip~n!Vk+F?Rr^Fp2zKSCU#w^8x|!08g!{Oj$IKB%h3ie3fv|AR;7d=Z z+I8~gn&4yCh$-B7;ar>5Vz+V!;v#kGWqn3C-GoQWgy(BXuCZ2IN>S;`8sWDu@Bs0p zsGLhx_!ZmE>DlRPm-9FQbT5g=^koHp;VQe5CV%=vmIrt}Qdy@Av&3Mtblb}D4gNtB zp^#xJC}3EcVgbx|hS717!R#4%S7u`D?RO`r_R3mt7=1q|w72h_jskK#WM|7?Ba_iJ z#`L-g#PS5Hby-A{o+5WbABNK=6z-lC-}sXT2>qHWZ*GWgpTStVhbAcsjrNyvm1jDe zKOrM%d8~ujx3$>zg9Mld_S9SIeu7>u!GWzn1tf)&BmoSQ`RSP^iyY{98qWFy$4o{3 zJNkV;Ti38bs8JDZ7`G|w+QSEqm^ovaTpfG-AJMj&vfYdPS7=?@U|h46wGkNv@_8E$ z^kJ@c9AV^R%fO`3+KIC&48a%wC@lI&p80V0GisQ*F851Ynfkl~WDGm0S}XnXx;;Yr z7>5>a|LH$fz03J6p=Sv(OeU6@31t;UBr&bBBvmW=8mc6>%jvU9d5tMTc=Uo11+Wg2J$e&>2^jttCYcl z$u|otEq!KMWD{AA%iCD-YQB@ipgxa7a{4fU(; z6DIsac_`3rHp`tm)`zsBx0G1!a|h&h&5ak>!2rHq3p$nADpf=3VrQ}XBiFORuUcFa z8eLi6cN)_X#&4`*6o#IElO}`yDD{=ywoL*;RlHug+H(*B$@B_MdvM=k?{k&fQh0QD z5&_-la-fN240y%x|9)8+Ofk5?;j7lUdAdJ~YTOCJv(ZrgKG%ApF{bgzXA0o5vzoue z4!u@v6gRO&C#AJJy>za)VJpdO1ip55a7K`oMbbh&*_vO$XVLPmJIr)cOP(LVfS0p` zCx^OMbs4E@G0vR@WG66ABIY%xd*_ceTLbL3^qOzTn9B48zO01DY^|80hIKYf-zs)` z+DsL)Ps5&f?@C6^M_ytR<20Xk1YAd>qh)N17dNe>G?{u*_3kmB3IB4BrRl7CxV20> zA!}{2G0!tjWUm7G_w&hgiRVYBURC)P9GyV9{3e-Q|n-V;tiUW|2 z>UddjG+r$fLKc1j71u%l14a*a>{K{iS*2Soaa*C8#KQ(!FM$FI4VUSuGF_gD=SCW!Ki{xG*C6-e2{LECA==tuvyX zlwJSu=L1*qQmCJZC>MR{1RR_&%;IW^{ph%oBjt~TdEV|DL(o8T`)>(?CTH*-5MFQl zXbqtq-1jwd6bp0$cM6i_uwHxR2IWr+TmosaZ@gC9fNv2Woa@1&pmF_7Fu?g9gw6sL zuUAQo;7qHq{Wwt}zQ;EB8{ll(7B}^Qxiutop9z$#nHdV!DBrkPIm?&+Kc)CKh8Hf;3m_G*Ho7j@Y&Enq;BcMA8Dk`ve z8odDiHK2}Ru-r`WhgBwEbid4X+?#es1L|@Z3%=ieJ6?Z%krV16oOo_aSI_W*KoF70`xyM2y!S&V5n(dUm4->z4J6S3Me7a zf2}l63Mk3{R)#5{l;Hm%Wx}pqU4zVlfD+S4D51Fj>(i%%!Uf^5PV=FJA|smohq-i& zK4Jm}0?Ggd0z&;a+JEd{^Pf>TrS(%n5fl9 Date: Fri, 1 Dec 2017 07:57:05 +0000 Subject: [PATCH 76/92] Explicitly set the velocity representation in iDynTree --- toolbox/src/base/RobotInterface.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/toolbox/src/base/RobotInterface.cpp b/toolbox/src/base/RobotInterface.cpp index 9755e4d7a..30662d2e4 100644 --- a/toolbox/src/base/RobotInterface.cpp +++ b/toolbox/src/base/RobotInterface.cpp @@ -410,6 +410,9 @@ bool RobotInterface::initializeModel() m_kinDynComp = std::make_shared(); if (!m_kinDynComp) return false; + // Explicitly set the velocity representation + m_kinDynComp->setFrameVelocityRepresentation(iDynTree::MIXED_REPRESENTATION); + // Use RF to load the urdf file // ---------------------------- From 98aafccf308d38e50c9b71b55c8e76397ef9595d Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 6 Dec 2017 12:05:34 +0000 Subject: [PATCH 77/92] Fixed the generalized torques conversion of InverseDynamics block --- toolbox/src/InverseDynamics.cpp | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/toolbox/src/InverseDynamics.cpp b/toolbox/src/InverseDynamics.cpp index 49b3e8386..d5d0ab1fa 100644 --- a/toolbox/src/InverseDynamics.cpp +++ b/toolbox/src/InverseDynamics.cpp @@ -7,6 +7,8 @@ #include #include #include +#include +#include using namespace wbt; @@ -188,9 +190,20 @@ bool InverseDynamics::output(const BlockInformation* blockInfo) iDynTree::LinkNetExternalWrenches(model->getNrOfLinks()), *m_torques); - // Forward the output to Simulink + // Get the output signal Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_TORQUES); - output.setBuffer(m_torques->jointTorques().data(), - blockInfo->getOutputPortWidth(OUTPUT_IDX_TORQUES)); + double* outputBuffer = output.getBuffer(); + if (!outputBuffer) { + Log::getSingleton().error("Failed to get output buffer."); + return false; + } + + // Convert generalized torques and forward the directly to Simulink + // mapping the memory through Eigen::Map + const auto& torquesSize = m_torques->jointTorques().size(); + Eigen::Map generalizedOutputTrqs(outputBuffer, torquesSize + 6); + generalizedOutputTrqs.segment(0, 6) = toEigen(m_torques->baseWrench()); + generalizedOutputTrqs.segment(6, torquesSize) = toEigen(m_torques->jointTorques()); + return true; } From 5480fae4cb48ca7c578f5aaea16023adcece9c23 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 6 Dec 2017 15:46:13 +0000 Subject: [PATCH 78/92] Updated README.md --- README.md | 132 +++++++++++++++++++++++++++++++----------------------- 1 file changed, 76 insertions(+), 56 deletions(-) diff --git a/README.md b/README.md index 34b2187de..4478dee41 100644 --- a/README.md +++ b/README.md @@ -1,67 +1,76 @@ ![](http://drive.google.com/uc?export=view&id=0B6zDGh11iY6oc0gtM0lMdDNweWM) -Whole Body Toolbox - A Simulink Toolbox for Whole Body Control -------------------------------------------------------------- +# Whole Body Toolbox +

A Simulink Toolbox for Whole Body Control

[![GitPitch](https://gitpitch.com/assets/badge.svg)](https://gitpitch.com/robotology/WB-Toolbox?grs=github) -### This toolbox is intended as a replacement (a 2.0 version) of the [WBI-Toolbox](https://github.com/robotology-playground/WBI-Toolbox). If you are interested, see [the migration guide from WBI-Toolbox 1.0](doc/Migration.md). - ### Main Goal -> The library should allow non-programming experts or those researchers just getting acquainted with Whole Body Control to more easily deploy controllers either on simulation or a real YARP-based robotic platform, as well as to analyze their performance and take advantage of the innumerable MATLAB and Simulink toolboxes. We like to call it "rapid controller prototyping" after which a proper YARP module should be made for hard real time performance and final deployment. + +> The library should allow non-programming experts or those researchers just getting acquainted with Whole Body Control to more easily deploy controllers either on simulation or real YARP-based robotic platforms, and to analyze their performance taking advantage of the innumerable MATLAB and Simulink toolboxes. We like to call it "rapid controller prototyping" after which a proper YARP module should be made for hard real time performance and final deployment. The following video shows CoDyCo's latest results on iCub in which the top level controller has been implemented with the [WB-Toolbox](https://github.com/robotology/WB-Toolbox) running at a 10ms rate!
- - [Installation](https://github.com/robotology/WB-Toolbox#Installation) - [Troubleshooting](https://github.com/robotology/WB-Toolbox#Troubleshooting) -- [Using the Toolbox](https://github.com/robotology/WB-Toolbox#Using the Toolbox) +- [Using the Toolbox](https://github.com/robotology/WB-Toolbox#using-the-toolbox) +- [Migrating from WBI-Toolbox](https://github.com/robotology/WB-Toolbox#migrating-from-wbi-toolbox) +- [Migrating from WB-Toolbox 2.0](https://github.com/robotology/WB-Toolbox#migrating-from-wbi-toolbox-2.0) - [Modifying the Toolbox](https://github.com/robotology/WB-Toolbox#modifyng-the-toolbox) - [Citing this work](https://github.com/robotology/WB-Toolbox#citing-this-work) -### Installation +## Installation -#### Requirements -* Matlab V. 7.1+ and Simulink (Tested with Matlab R2015b, R2014a/b, R2013a/b, R2012a/b) -* YARP (https://github.com/robotology/yarp) **-IMPORTANT-** Please compile as shared library. Currently a default yarp configuration option. -* (Optional. Needed for some blocks) iCub (https://github.com/robotology/icub-main) -* yarpWholeBodyInterface (https://github.com/robotology/yarp-wholebodyinterface) +### Requirements +* Matlab V. 7.1+ and Simulink (Tested with Matlab `R2015b`, `R2014a/b`, `R2013a/b`, `R2012a/b`) +* [`YARP`](https://github.com/robotology/yarp) (Compiled as **shared library**. Currently a default yarp configuration option) +* [`iDynTree`](https://github.com/robotology/idyntree) +* Supported Operating Systems: **Linux**, **macOS**, **Windows** **Note:** You can install the dependencies either manually or by using the [codyco-superbuild](https://github.com/robotology/codyco-superbuild). -###### Optional +### Optional requirements +* [`iCub`](https://github.com/robotology/icub-main) (needed for some blocks) * Gazebo Simulator (http://gazebosim.org/) * gazebo_yarp_plugins (https://github.com/robotology/gazebo_yarp_plugins). -**Operating Systems supported: macOS, Linux, Windows.** - **Note: The following instructions are for *NIX systems, but it works similarly on the other operating systems.** -#### Compiling the C++ Code (Mex File) +### Compiling the C++ Code (Mex File) + +**Prerequisite: Check the [Matlab configuration](https://github.com/robotology/WB-Toolbox#matlab-configuration) section.** -**Prerequisite: Check the Matlab configuration.** Before going ahead with the compilation of the library, make sure that you have MATLAB and Simulink properly installed and running. Then, check that the MEX compiler for MATLAB is setup and working. For this you can try compiling some of the MATLAB C code examples as described in [http://www.mathworks.com/help/matlab/ref/mex.html#btz1tb5-12]. **If you installed Matlab in a location different from the default one, please set an environmental variable called either `MATLABDIR` or `MATLAB_DIR` with the root of your Matlab installation**, e.g. add a line to your `~/.bashrc` such as: `export MATLAB_DIR=/usr/local/bin/matlab` +Before going ahead with the compilation of the library, make sure that you have MATLAB and Simulink properly installed and running. Then, check that the MEX compiler for MATLAB is setup and working. For this you can try compiling some of the MATLAB C code examples as described in the [mex official documentation](https://www.mathworks.com/help/matlab/ref/mex.html). +**If you installed Matlab in a location different from the default one, please set an environmental variable called either `MATLABDIR` or `MATLAB_DIR` with the root of your Matlab installation**, e.g. add a line to your `~/.bashrc` such as: `export MATLAB_DIR=/usr/local/bin/matlab`. If you used the [codyco-superbuild](https://github.com/robotology/codyco-superbuild) you can skip this step and go directly to the Matlab configuration step. -Otherwise follow the following instructions. -- Clone this repository: `git clone https://github.com/robotology/WB-Toolbox.git` -- Create the build directory: `mkdir -p WB-Toolbox/build` -- Move inside the build directory: `cd WB-Toolbox/build` -- Configure the project: `cmake ..` +Execute: + +```sh +git clone https://github.com/robotology/WB-Toolbox.git +mkdir -p WB-Toolbox/build +cd WB-Toolbox/build +cmake .. +``` + +**Note:** We suggest to install the project instead of using it from the build directory. You should thus change the default installation directory by configuring the `CMAKE_INSTALL_PREFIX` variable. You can do it before running the first `cmake` command by calling `cmake .. -DCMAKE_INSTALL_PREFIX=/your/new/path`, or by configuring the project with `ccmake .` -**Note** We suggest to install the project instead of using it from the build directory. You should thus change the default installation directory by configuring the `CMAKE_INSTALL_PREFIX` variable. You can do it before running the first `cmake` command by calling `cmake .. -DCMAKE_INSTALL_PREFIX=/your/new/path`, or by configuring the project with `ccmake .` +Compile and install the toolbox as follows: -- Compile the project: `make` -- *[Optional/Suggested]* Install the project: `make install` +```sh +make +make install +``` +### Matlab configuration -#### Matlab configuration In the following section we assume the `install` folder is either the one you specified in the previous step by using `CMAKE_INSTALL_PREFIX` or if you used the `codyco-superbuild`, is `/path/to/superbuild/build_folder/install`. In order to use the WB-Toolbox in Matlab you have to add the `mex` and `share/WB-Toolbox` to the Matlab path. @@ -72,10 +81,10 @@ In order to use the WB-Toolbox in Matlab you have to add the `mex` and `share/WB ``` You can also use (only once after the installation) the script `startup_wbitoolbox.m` that you can find in the `share/WB-Toolbox` subdirectory of the install folder to properly configure Matlab. -**Note** This script configures Matlab to alwasy add the WB-Toolbox to the path. This assumes Matlab is always launched from the `userpath` folder. +**Note:** This script configures Matlab to always add the WB-Toolbox to the path. This assumes Matlab is always launched from the `userpath` folder. - **Launching Matlab** By default, Matlab has different startup behaviours depending on the Operating Systems and how it is launched. For Windows and macOS (if launched in the Finder) Matlab starts in the `userpath` folder. If this is your common workflow you can skip the rest of this note. Instead, if you launch Matlab from the command line (Linux and macOS users), Matlab starts in the folder where the command is typed, and thus the `path.m` file generated in the previous phase is no longer loaded. You thus have two options: - - create a Bash alias, such that Matlab is always launched in the `userpath`, e.g. + - create a Bash alias, such that Matlab is always launched in the `userpath`, e.g. ``` alias matlab='cd ~/Documents/MATLAB && /path/to/matlab ``` @@ -90,75 +99,86 @@ You can also use (only once after the installation) the script `startup_wbitoolb - **Robots' configuration files** Each robot that can be used through the Toolbox has its own configuration file. WB-Toolbox uses the Yarp [`ResourceFinder`](http://www.yarp.it/yarp_resource_finder_tutorials.html). You should thus follow the related instruction to properly configure your installation (e.g. set the `YARP_DATA_DIRS` variable) -### Troubleshooting -- **Problems finding libraries and libstdc++.** In case Matlab has trouble finding a specific library, a workaround is to launch it preloading the variable `LD_PRELOAD` (or `DYLD_INSERT_LIBRARIES` on macOS) with the full path of the missing library. On Linux you might also have trouble with libstdc++.so since Matlab comes with its own. To use your system's libstdc++ you would need to launch Matlab something like (replace with your system's libstdc++ library): +## Troubleshooting +- **Problems finding libraries and libstdc++.** In case Matlab has trouble finding a specific library, a workaround is to launch it preloading the variable `LD_PRELOAD` (or `DYLD_INSERT_LIBRARIES` on macOS) with the full path of the missing library. On Linux you might also have trouble with `libstdc++.so` since Matlab comes with its own. To use your system's `libstdc++` you would need to launch Matlab something like (replace with your system's `libstdc++` library): -`LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.19 matlab` +`LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libstdc++.so.6 matlab` You could additionally create an alias to launch Matlab this way: -`alias matlab_codyco="cd ~/Documents/MATLAB && LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.19 matlab"` +`alias matlab_codyco="cd ~/Documents/MATLAB && LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libstdc++.so.6 matlab"` -A more permanent and scalable solution can be found in the answer of [this issue](https://github.com/robotology/codyco-superbuild/issues/141#issuecomment-257892256) +A more permanent and scalable solution can be found in https://github.com/robotology/codyco-superbuild/issues/141#issuecomment-257892256. + +- In case you compiled `YARP` in a directory different from the system default one and you are not using RPATH, you need to tell to MATLAB the location in which to find the shared libraries for `YARP`. If you launch MATLAB from command line, this task is already done for you by `bash` (if you edited `.bashrc`). If you launch MATLAB from the UI (e.g. on macOS by double clicking the application icon) you need to further add the variables in `${MATLAB_ROOT}/bin/.matlab7rc.sh` by first doing -- In case you have compiled YARP in a directory different from the system default one and you are not using RPATH, you need to tell to MATLAB the location in which to find the shared libraries for YARP. If you launch MATLAB from command line, this task is already done for you by `bash` (if you edited `.bashrc`). If you launch MATLAB from the UI (e.g. on macOS by double clicking the application icon) you need to further add the variables in `${MATLAB_ROOT}/bin/.matlab7rc.sh` by first doing ```bash chmod +w .matlab7rc.sh ``` + Then looking for the variable `LDPATH_SUFFIX` and assign to every instance the contents of your `DYLD_LIBRARY_PATH`. Finally do: + ```bash chmod -w .matlab7rc.sh ``` The error message you get in this case might look something like: + ```bash Library not loaded: libyarpwholeBodyinterface.0.0.1.dylib Referenced from: ${CODYCO_SUPERBUILD_DIR}/install/mex/robotState.mexmaci64 ``` -### Using the Toolbox +## Using the Toolbox + The Toolbox assumes the following information / variables to be defined: -##### Environment variables + +#### Environment variables + If you launch Matlab from command line, it inherits the configuration from the `.bashrc` or `.bash_profile` file. If you launch Matlab directly from the GUI you should define this variables with the Matlab function `setenv`. - `YARP_ROBOT_NAME` - `YARP_DATA_DIRS` -##### Matlab variables - -- `WBT_robotName`: if not defined the robot name defined in the `yarpWholeBodyInterface.ini` file is taken. -- `WBT_modelName`: if not defined by default is `WBT_simulink`. -- `WBT_wbiFilename`: the name of the Yarp WholeBodyInterface file, by default `yarpWholeBodyInterface.ini`. -- `WBT_wbiList`: the name of the robot list to be used in the Toolbox. By default `ROBOT_TORQUE_CONTROL_JOINTS`. +#### Creating a model -**Creating a model** Before using or creating a new model keep in mind that WB-Toolbox is discrete in principle and your simulation should be discrete as well. By going to `Simulation > Configuration Parameters > Solver` you should change the solver options to `Fixed Step` and use a `discrete (no continuous states)` solver. +r +In order to start dragging and dropping blocks from the Toolbox, open the Simulink Library Browser and search for `Whole Body Toolbox` in the tree view. + +## Migrating -To start dragging and dropping blocks from the Toolbox open Simulink and search for `Whole Body Toolbox` in the libraries tree. +#### From WBI-Toolbox (1.0) -### Migrating from WBI-Toolbox -Please see [here](doc/Migration.md). +Please see [here](doc/Migration_from_WBI-Toolbox_1.0.md). + +#### Migrating from WB-Toolbox 2.0 + +Please see [here](doc/Migration_from_WB-Toolbox_2.0.md). + +## Modifying the Toolbox -### Modifying the Toolbox If you want to modify the toolbox, please check developers documentation: - [Add a new C++ block](doc/dev/create_new_block.md) - [Tip and tricks on creating simulink blocks](doc/dev/sim_tricks.md) -### Citing this work +## Citing this work + Please cite the following publication if you are using WB-Toolbox for your own research and/or robot controllers > Romano, F., Traversaro, S., Pucci, D., Del Prete, A., Eljaik, J., Nori, F. "A Whole-Body Software Abstraction layer for Control Design of free-floating Mechanical Systems", 1st IEEE International Conference on Robotic Computing, 2017. Bibtex citation: ``` -@INPROCEEDINGS{RomanoWBI17, -author={F. Romano and S. Traversaro and D. Pucci and A. Del Prete and J. Eljaik and F. Nori}, -booktitle={2017 IEEE 1st International Conference on Robotic Computing}, -title={A Whole-Body Software Abstraction layer for Control Design of free-floating Mechanical Systems}, -year={2017}, +@INPROCEEDINGS{RomanoWBI17, +author={F. Romano and S. Traversaro and D. Pucci and A. Del Prete and J. Eljaik and F. Nori}, +booktitle={2017 IEEE 1st International Conference on Robotic Computing}, +title={A Whole-Body Software Abstraction layer for Control Design of free-floating Mechanical Systems}, +year={2017}, } ``` #### Tested OS -macOS, Linux, Windows + +Linux, macOS, Windows. From 47f3b5a83f8f47214df0aa8c75174cac382324fb Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 6 Dec 2017 15:47:13 +0000 Subject: [PATCH 79/92] Added Migration How-To from 2.0 to 3.0 Also renamed Migration.md --- doc/Migration_from_WB-Toolbox_2.0.md | 82 +++++++++++++++++++ ...n.md => Migration_from_WBI-Toolbox_1.0.md} | 6 +- 2 files changed, 85 insertions(+), 3 deletions(-) create mode 100644 doc/Migration_from_WB-Toolbox_2.0.md rename doc/{Migration.md => Migration_from_WBI-Toolbox_1.0.md} (96%) diff --git a/doc/Migration_from_WB-Toolbox_2.0.md b/doc/Migration_from_WB-Toolbox_2.0.md new file mode 100644 index 000000000..b194665b9 --- /dev/null +++ b/doc/Migration_from_WB-Toolbox_2.0.md @@ -0,0 +1,82 @@ +# Migration from WB-Toolbox 2.0 to WB-Toolbox 3.0 + +Most of the major changes delivered with the `3.0` version of the `WB-Toolbox` don't affect directly the end-user. Under the hood the toolbox had an important polishing, and the small manual intervention required by this new release match the new features which have been developed. + +You can read [Release Notes](https://github.com/robotology/WB-Toolbox/issues/65) for a detailed overview. Below are described only the steps required to port Simulink models to this new release. + +## New toolbox configuration + +The `WB-Toolbox 2.0` was based on top of [`yarpWholeBodyInterface`](https://github.com/robotology/yarp-wholebodyinterface), which configuration was stored in a `yarpWholeBodyInterface.ini` file. This file was retrieved by `ResourceFinder` and its information was then loaded into the toolbox. + +### Store the configuration in the Simulink model + +`WB-Toolbox 3.0` deprecated the support of `yarpWholeBodyInterface`, and for reducing the complexity and sparsity of the information storage it allows configuring a Simulink model from the model itself. + +The new _Configuration_ block allows inserting information such as **Robot Name**, **URDF Name**, **Controlled Joints**, ... directly from the block's mask. + +### Load the configuration from the Workspace + +Sometimes it might be useful loading the model's configuration directly from the Workspace. For this purpose, a new `WBToolbox.WBToolboxConfig` class has been developed. The _Configuration_ block needs to know only the name of the variable which refers to the object. Its data is then read before the simulation runs. + +This snippet of code shows an example of how to initialize a configuration object: + +```matlab +# Initialize a config object +WBTConfigRobot = WBToolbox.WBToolboxConfig; + +# Insert robot data +WBTConfigRobot.RobotName = 'icubSim'; +WBTConfigRobot.UrdfFile = 'model.urdf'; +WBTConfigRobot.ControlledJoints = {... + 'torso_pitch','torso_roll','torso_yaw',... + 'r_shoulder_pitch','r_shoulder_roll','r_shoulder_yaw','r_elbow',... + 'l_shoulder_pitch','l_shoulder_roll','l_shoulder_yaw','l_elbow'}; +WBTConfigRobot.ControlBoardsNames = {'torso','left_arm','right_arm'}; +WBTConfigRobot.LocalName = 'WBT'; +``` + +To check if the data has been read correctly, it is displayed as read-only in the block's mask. + +Furthermore, a good sign for a valid configuration is the `WBTConfigRobot.ValidConfiguration` property. + +### Multi-robot support + +The scope of the introduction of the _Configuration_ block goes beyond the need of a simpler toolbox configuration. One of the biggest limitation of the `2.0` version is the support of [controlling only one robot per model](https://github.com/robotology/WB-Toolbox/issues/37). + +`WB-Toolbox 3.0` is now capable of reading / sending data from / to multiple robots. Multiple _Configuration_ blocks can be present in the same model attaining to the following rules: + +* In the same hierarchical level of a Simulink model, only one _Configuration_ + block should be present. In other words, you should never see in the display more than one _Configuration_ block. + * _Configuration_ blocks put deeper in the hierarchy (e.g. in a Subsystem) override the previous ones. + + There are a few pitfalls which are worth to be highlighted: + + * It is legit having two Subsystems with different _Configuration_ blocks which point to the same robot. They can have for instance a different joint list and use different control boards. Although, despite reading information never creates problems, sending data to the robot in such scenario can be disastrous. In fact, consider the case these two subsystems share one link, and configure it in two different control modes (e.g. Position and Torque). Sending references to this link causes unpredictable effects. + * In line of theory it would be possible to have two subsystems in which the first one refers to a Gazebo model and the second one to a real robot. However, this case causes unpredictable behaviour for what concerns the synchronization. In fact, two different blocks for such aim are present in the toolbox: _Simulator Synchronizer_ and _Real Time Syncronizer_. They should be always used exclusively. + +## Other manual edits + +* All the _Get Estimate_ blocks need to be replaced by the new _Get Measurement_ block. +* All the hardcoded digital filters (e.g. for the joints velocities) have been removed. A new `Discrete Filter` block has been developed, and it should be manually added if the read raw signal (e.g. from the _Get Measurement_ block) requires filtering. +* The `C++` class used by the _DoFs Converter_ changed. All the blocks in the `YARP To WBI` configuration need to be connected again. +* The gravity vector is stored is the `WBToolboxConfig` class. If an alternative value is needed, set it globally directly in the configuration object or scope the block which needs it in a Subsystem with its own _Configuration_ block. +* In order to set the low level PIDs, loading in the Workspace a `WBToolbox.WBTPIDConfig` object should be configured as follows: + +```matlab +# Initialize an empty object +pids = WBToolbox.WBTPIDConfig; + +# Insert data +pids.addPID(WBToolbox.PID('l_elbow', WBToolbox.PID(1, 1, 0))); +pids.addPID(WBToolbox.PID('l_wrist_pitch', WBToolbox.PID(1.5, 0, 0.1))); +pids.addPID(WBToolbox.PID('r_shoulder_pitch', WBToolbox.PID(0.2, 0, 0))); +pids.addPID(WBToolbox.PID('torso_roll', WBToolbox.PID(0.1, 0.1, 0))); +``` + +If some of the controlled joints are not specified, the PIDs are kept in their default values. + + +## Deprecations + +* _Inverse Kinematics_ and _Remote Inverse Kinematics_ have been temporary deprecated. They will see a major release in the coming months. If you need them please do not upgrade to the `3.0` version. +* _Set Low Level PID_ block lost the capability of switching between multiple configurations. Since they were stored in an external file, this change is aligned to the simplification process chosen for for the configuration. \ No newline at end of file diff --git a/doc/Migration.md b/doc/Migration_from_WBI-Toolbox_1.0.md similarity index 96% rename from doc/Migration.md rename to doc/Migration_from_WBI-Toolbox_1.0.md index b73a4590b..a89c8c6b7 100644 --- a/doc/Migration.md +++ b/doc/Migration_from_WBI-Toolbox_1.0.md @@ -1,4 +1,4 @@ -## Migration from WB**I**-Toolbox to WB-Toolbox 2.0 +## Migration from WBI-Toolbox to WB-Toolbox 2.0 Given a simulink model with some WBI-Toolbox blocks inside, the general procedure is to **substitute each block with the corresponding one from WB-Toolbox 2.0**. However, there are some things the user should take care while doing this operation. This guide points out the main differences between the two toolboxes. For more information about the WBI-Toolbox, please have a look at the [WBI-Toolbox README](https://github.com/robotology-playground/WBI-Toolbox/blob/master/README.md). This guide follows the WBI and WB Toolbox blocks partitioning in Simulink library. It is divided in the following sections: @@ -24,7 +24,7 @@ They have already meaningful default values. Nevertheless you should take a look The world-to-base homogeneous transformation matrix is a 4x4 matrix that maps position and orientation of a rigid body from an initial frame of reference to another. -For back-compatibility, the transformation happending under the hood in the WBI-Toolbox can be obtained using forward kinematics blocks as in the following example: +For back-compatibility, the transformation happending under the hood in the WBI-Toolbox can be obtained using forward kinematics blocks as in the following example: ![](https://cloud.githubusercontent.com/assets/12396934/12293044/3337da3c-b9f1-11e5-959f-b40418b5469d.png) @@ -43,7 +43,7 @@ It is divided into three subsections. The `Joint Limits` block is now moved into #### Dynamics - the `dJdq` blocks have been moved into **jacobians** subsection; -- for mass matrix, generalized bias forces and centroidal momentum computation is now required to calculate explicitly the world-to-base homogeneous transformation matrix and the base velocity. Furthermore, the base frame pose and velocity and the joint configuration are now separate inputs. +- for mass matrix, generalized bias forces and centroidal momentum computation is now required to calculate explicitly the world-to-base homogeneous transformation matrix and the base velocity. Furthermore, the base frame pose and velocity and the joint configuration are now separate inputs. #### Jacobians There is now only one generic block for jacobians and one for `dJdq` calculation. The link with respect to which the Jacobian is computed is determined by its frame name as specified in the **URDF model**. As for the dynamics, the base pose and velocity and the joint position and velocity are required as input. From edf4a58ce02c6fef01d667a89a48441744edbb94 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 9 Aug 2017 13:52:21 +0000 Subject: [PATCH 80/92] Included the support of a new DiscreteFilter Block --- toolbox/CMakeLists.txt | 5 +++++ toolbox/include/base/toolbox.h | 1 + toolbox/src/base/factory.cpp | 7 +++++-- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index 62cf9590d..b89fdf5c6 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -93,6 +93,11 @@ if (WBT_USES_ICUB) # # include_directories(SYSTEM ${iKin_INCLUDE_DIRS}) # endif() + configure_block(BLOCK_NAME "Discrete Filter" + GROUP "Utilities" + LIST_PREFIX WBT + SOURCES src/DiscreteFilter.cpp + HEADERS include/DiscreteFilter.h) include_directories(SYSTEM ${ctrlLib_INCLUDE_DIRS}) endif() diff --git a/toolbox/include/base/toolbox.h b/toolbox/include/base/toolbox.h index 14f5a3778..979eb6b93 100644 --- a/toolbox/include/base/toolbox.h +++ b/toolbox/include/base/toolbox.h @@ -19,6 +19,7 @@ #include "SetLowLevelPID.h" #ifdef WBT_USES_ICUB #include "MinimumJerkTrajectoryGenerator.h" +#include "DiscreteFilter.h" #endif #ifdef WBT_USES_IPOPT // #include "InverseKinematics.h" diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index ab7d9f9be..c78e4af68 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -40,8 +40,11 @@ Block* Block::instantiateBlockWithClassName(std::string blockClassName) block = new SetLowLevelPID(); } #ifdef WBT_USES_ICUB - else if (blockClassName == MinimumJerkTrajectoryGenerator::ClassName) { - block = new MinimumJerkTrajectoryGenerator(); + else if (blockClassName == wbt::MinimumJerkTrajectoryGenerator::ClassName) { + block = new wbt::MinimumJerkTrajectoryGenerator(); + } + else if (blockClassName == wbt::DiscreteFilter::ClassName) { + block = new wbt::DiscreteFilter(); } #endif #ifdef WBT_USES_IPOPT From 73c1c4e7a35571018f21066cbfdeeda0a38150a2 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Thu, 10 Aug 2017 09:16:25 +0000 Subject: [PATCH 81/92] First working version of DiscreteFilter block with 1D I/O signal --- toolbox/include/DiscreteFilter.h | 44 ++++++ toolbox/src/DiscreteFilter.cpp | 230 +++++++++++++++++++++++++++++++ 2 files changed, 274 insertions(+) create mode 100644 toolbox/include/DiscreteFilter.h create mode 100644 toolbox/src/DiscreteFilter.cpp diff --git a/toolbox/include/DiscreteFilter.h b/toolbox/include/DiscreteFilter.h new file mode 100644 index 000000000..be47c7944 --- /dev/null +++ b/toolbox/include/DiscreteFilter.h @@ -0,0 +1,44 @@ +#include "Block.h" +#include + +#ifndef WBT_FILTER_H +#define WBT_FILTER_H + +namespace wbt { + class DiscreteFilter; +} // namespace wbt + +namespace iCub { + namespace ctrl { + class IFilter; + } +} // namespace iCub + +namespace yarp { + namespace sig { + class Vector; + } +} // namespace yarp + +class wbt::DiscreteFilter : public wbt::Block { +private: + iCub::ctrl::IFilter* filter; + yarp::sig::Vector* num; + yarp::sig::Vector* den; + + static void stringToYarpVector(const std::string s, yarp::sig::Vector* v); + +public: + static std::string ClassName; + + DiscreteFilter(); + ~DiscreteFilter() = default; + + virtual unsigned numberOfParameters(); + virtual bool configureSizeAndPorts(BlockInformation* blockInfo, wbt::Error* error); + virtual bool initialize(BlockInformation* blockInfo, wbt::Error* error); + virtual bool terminate(BlockInformation* blockInfo, wbt::Error* error); + virtual bool output(BlockInformation* blockInfo, wbt::Error* error); +}; + +#endif // WBT_FILTER_H diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp new file mode 100644 index 000000000..9045446e5 --- /dev/null +++ b/toolbox/src/DiscreteFilter.cpp @@ -0,0 +1,230 @@ +#include "DiscreteFilter.h" +#include "BlockInformation.h" +#include "Error.h" +#include "ForwardKinematics.h" +#include "Signal.h" +#include +#include +#include +#include +#include +#include + +// Parameters +#define PARAM_IDX_FLT_TYPE 1 // ::Filter type +#define PARAM_IDX_NUMCOEFF 2 // ::Filter numerator coefficients +#define PARAM_IDX_DENCOEFF 3 // ::Filter denominator coefficients +#define PARAM_IDX_1LOWP_FC 4 // ::FirstOrderLowPassFilter cut frequency +#define PARAM_IDX_1LOWP_TS 5 // ::FirstOrderLowPassFilter sampling time +#define PARAM_IDX_MD_ORDER 6 // ::MedianFilter order +// Inputs +#define INPUT_IDX_SIGNAL 0 +// Outputs +#define OUTPUT_IDX_SIGNAL 0 +// Other defines +#define SIGNAL_DYNAMIC_SIZE -1 + +using namespace wbt; + +std::string DiscreteFilter::ClassName = "DiscreteFilter"; + +DiscreteFilter::DiscreteFilter() : filter(nullptr), num(nullptr), den(nullptr) +{ + num = new yarp::sig::Vector(); + den = new yarp::sig::Vector(); +} + +unsigned DiscreteFilter::numberOfParameters() +{ + return 6; +} + +bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo, wbt::Error* error) +{ + // Memory allocation / Saving data not allowed here + + // Specify I/O + // =========== + + // INPUTS + // ------ + + // Number of input ports + int numberOfInputPorts = 1; + if (!blockInfo->setNumberOfInputPorts(numberOfInputPorts)) { + if (error) { + error->message = ClassName + " Failed to set input port number."; + } + return false; + } + + // Input port sizes + blockInfo->setInputPortVectorSize(INPUT_IDX_SIGNAL, SIGNAL_DYNAMIC_SIZE); + blockInfo->setInputPortType(INPUT_IDX_SIGNAL, PortDataTypeDouble); + + // OUTPUTS + // ------- + + // Number of output ports + int numberOfOutputPorts = 1; + if (!blockInfo->setNumberOfOuputPorts(numberOfOutputPorts)) { + if (error) { + error->message = ClassName + " Failed to set output port number."; + } + return false; + } + + // Output port sizes + blockInfo->setOutputPortVectorSize(OUTPUT_IDX_SIGNAL, SIGNAL_DYNAMIC_SIZE); + blockInfo->setOutputPortType(OUTPUT_IDX_SIGNAL, PortDataTypeDouble); + + return true; +} + +bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) +{ + // Handle the parameters + // ===================== + + // Variables for the filter parameters + std::string filter_type; + std::string num_coeff_str; + std::string den_coeff_str; + wbt::Data firstOrderLowPassFilter_fc; + wbt::Data firstOrderLowPassFilter_ts; + wbt::Data medianFilter_order; + + // Get the scalar parameters + firstOrderLowPassFilter_fc = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1LOWP_FC); + firstOrderLowPassFilter_ts = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1LOWP_TS); + medianFilter_order = blockInfo->getScalarParameterAtIndex(PARAM_IDX_MD_ORDER); + + // Get the string parameter + if (!(blockInfo->getStringParameterAtIndex(PARAM_IDX_FLT_TYPE, filter_type) + && blockInfo->getStringParameterAtIndex(PARAM_IDX_NUMCOEFF, num_coeff_str) + && blockInfo->getStringParameterAtIndex(PARAM_IDX_DENCOEFF, den_coeff_str))) { + if (error) { + error->message = ClassName + " Failed to parse string parameters."; + } + return false; + } + + // Convert the strings from the Matlab syntax ("[1.0 2 3.33]") to yarp::sig::Vector + stringToYarpVector(num_coeff_str, num); + stringToYarpVector(den_coeff_str, den); + + // Create the filter object + // ======================== + + // Default + // ------- + if (filter_type == "Default") { + if (num->length() == 0 || den->length() == 0) { + if (error) { + error->message = ClassName + " (Default) Wrong coefficients size"; + } + return 1; + } + filter = new iCub::ctrl::Filter(*num, *den); + } + // FirstOrderLowPassFilter + // ----------------------- + else if (filter_type == "FirstOrderLowPassFilter") { + if (firstOrderLowPassFilter_fc.floatData() == 0 + || firstOrderLowPassFilter_ts.floatData() == 0) { + if (error) { + error->message = ClassName + + " (FirstOrderLowPassFilter) You need to " + "specify Fc and Ts"; + } + return false; + } + filter = new iCub::ctrl::FirstOrderLowPassFilter(firstOrderLowPassFilter_fc.floatData(), + firstOrderLowPassFilter_ts.floatData()); + } + // MedianFilter + // ------------ + else if (filter_type == "MedianFilter") { + if (medianFilter_order.int32Data() == 0) { + if (error) { + error->message = ClassName + + " (MedianFilter) You need to specify the " + "filter order."; + } + return false; + } + filter = new iCub::ctrl::MedianFilter(medianFilter_order.int32Data()); + } + else { + if (error) error->message = ClassName + " Filter type not recognized."; + return false; + } + + return true; +} + +bool DiscreteFilter::terminate(BlockInformation* blockInfo, wbt::Error* error) +{ + if (filter) { + delete filter; + filter = nullptr; + } + + if (num) { + delete num; + num = nullptr; + } + + if (den) { + delete den; + den = nullptr; + } + + return true; +} + +bool DiscreteFilter::output(BlockInformation* blockInfo, wbt::Error* error) +{ + if (filter == nullptr) return false; + + // Get the input signal + Signal inputSignal = blockInfo->getInputPortSignal(INPUT_IDX_SIGNAL); + + unsigned index_element = 0; + yarp::sig::Vector inputSignalVector(1, inputSignal.get(index_element).doubleData()); + + // Filter the input signal + const yarp::sig::Vector& outputVector = filter->filt(inputSignalVector); + + // Forward the filtered signal to the output port + Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_SIGNAL); + output.setBuffer(outputVector.data(), outputVector.length()); + + return true; +} + +void DiscreteFilter::stringToYarpVector(const std::string str, yarp::sig::Vector* v) +{ + assert(v != nullptr); + + std::string s = str; + + // Lambda expression used to remove "[]," carachters + // TODO: what about removing everything but digits and "."? + auto lambda_remove_chars = [](const char& c) { + if ((c == '[') || (c == ']') || c == ',') + return true; + else + return false; + }; + + // Apply the lambda expression the input parameters + s.erase(remove_if(s.begin(), s.end(), lambda_remove_chars), s.end()); + + // Convert the cleaned string to a yarp vector of floats + std::istringstream sstrm(s); + float f; + + while (sstrm >> f) + v->push_back(f); +} From 79c0c57118de4833b8c690d92f1dee7c56ee8b38 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Thu, 10 Aug 2017 12:57:46 +0000 Subject: [PATCH 82/92] DiscreteFilter: Multidimesional signal support --- toolbox/include/DiscreteFilter.h | 3 ++ toolbox/src/DiscreteFilter.cpp | 66 ++++++++++++++++++++++---------- 2 files changed, 49 insertions(+), 20 deletions(-) diff --git a/toolbox/include/DiscreteFilter.h b/toolbox/include/DiscreteFilter.h index be47c7944..234af3da9 100644 --- a/toolbox/include/DiscreteFilter.h +++ b/toolbox/include/DiscreteFilter.h @@ -1,5 +1,6 @@ #include "Block.h" #include +#include #ifndef WBT_FILTER_H #define WBT_FILTER_H @@ -22,9 +23,11 @@ namespace yarp { class wbt::DiscreteFilter : public wbt::Block { private: + bool firstRun; iCub::ctrl::IFilter* filter; yarp::sig::Vector* num; yarp::sig::Vector* den; + yarp::sig::Vector* inputSignalVector; static void stringToYarpVector(const std::string s, yarp::sig::Vector* v); diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp index 9045446e5..fb1b1874a 100644 --- a/toolbox/src/DiscreteFilter.cpp +++ b/toolbox/src/DiscreteFilter.cpp @@ -25,13 +25,15 @@ #define SIGNAL_DYNAMIC_SIZE -1 using namespace wbt; +using namespace iCub::ctrl; +using namespace yarp::sig; std::string DiscreteFilter::ClassName = "DiscreteFilter"; -DiscreteFilter::DiscreteFilter() : filter(nullptr), num(nullptr), den(nullptr) +DiscreteFilter::DiscreteFilter() : firstRun(true), filter(nullptr), inputSignalVector(nullptr) { - num = new yarp::sig::Vector(); - den = new yarp::sig::Vector(); + num = new Vector(0); + den = new Vector(0); } unsigned DiscreteFilter::numberOfParameters() @@ -116,16 +118,16 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) // Create the filter object // ======================== - // Default + // Generic // ------- - if (filter_type == "Default") { + if (filter_type == "Generic") { if (num->length() == 0 || den->length() == 0) { if (error) { - error->message = ClassName + " (Default) Wrong coefficients size"; + error->message = ClassName + " (Generic) Wrong coefficients size"; } return 1; } - filter = new iCub::ctrl::Filter(*num, *den); + filter = new Filter(*num, *den); } // FirstOrderLowPassFilter // ----------------------- @@ -139,8 +141,8 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) } return false; } - filter = new iCub::ctrl::FirstOrderLowPassFilter(firstOrderLowPassFilter_fc.floatData(), - firstOrderLowPassFilter_ts.floatData()); + filter = new FirstOrderLowPassFilter(firstOrderLowPassFilter_fc.floatData(), + firstOrderLowPassFilter_ts.floatData()); } // MedianFilter // ------------ @@ -153,7 +155,7 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) } return false; } - filter = new iCub::ctrl::MedianFilter(medianFilter_order.int32Data()); + filter = new MedianFilter(medianFilter_order.int32Data()); } else { if (error) error->message = ClassName + " Filter type not recognized."; @@ -165,6 +167,9 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) bool DiscreteFilter::terminate(BlockInformation* blockInfo, wbt::Error* error) { + // Deallocate all the memory + // ------------------------- + if (filter) { delete filter; filter = nullptr; @@ -180,6 +185,11 @@ bool DiscreteFilter::terminate(BlockInformation* blockInfo, wbt::Error* error) den = nullptr; } + if (inputSignalVector) { + delete inputSignalVector; + inputSignalVector = nullptr; + } + return true; } @@ -187,23 +197,39 @@ bool DiscreteFilter::output(BlockInformation* blockInfo, wbt::Error* error) { if (filter == nullptr) return false; - // Get the input signal - Signal inputSignal = blockInfo->getInputPortSignal(INPUT_IDX_SIGNAL); + // Get the input and output signals + Signal inputSignal = blockInfo->getInputPortSignal(INPUT_IDX_SIGNAL); + Signal outputSignal = blockInfo->getOutputPortSignal(OUTPUT_IDX_SIGNAL); + + unsigned inputSignalWidth = blockInfo->getInputPortWidth(INPUT_IDX_SIGNAL); + + // Allocate the memory for the input data + if (firstRun) { + // Allocate the input signal + inputSignalVector = new Vector(inputSignalWidth, 0.0); - unsigned index_element = 0; - yarp::sig::Vector inputSignalVector(1, inputSignal.get(index_element).doubleData()); + // Initialize the filter. This is required because if the signal is not 1D, + // the default filter constructor initialize a wrongly sized y0 + filter->init(Vector(inputSignalWidth)); + + firstRun = false; + } + + // Copy the Signal to the data structure that the filter wants + for (unsigned i = 0; i < inputSignalWidth; ++i) { + (*inputSignalVector)[i] = inputSignal.get(i).doubleData(); + } - // Filter the input signal - const yarp::sig::Vector& outputVector = filter->filt(inputSignalVector); + // Filter the current component of the input signal + const Vector& outputVector = filter->filt(*inputSignalVector); - // Forward the filtered signal to the output port - Signal output = blockInfo->getOutputPortSignal(OUTPUT_IDX_SIGNAL); - output.setBuffer(outputVector.data(), outputVector.length()); + // Forward the filtered signals to the output port + outputSignal.setBuffer(outputVector.data(), outputVector.length()); return true; } -void DiscreteFilter::stringToYarpVector(const std::string str, yarp::sig::Vector* v) +void DiscreteFilter::stringToYarpVector(const std::string str, Vector* v) { assert(v != nullptr); From a49d7b9ee497181eade148d73b05f7025b13cb85 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 07:07:55 +0000 Subject: [PATCH 83/92] Updated library WBToolboxLibrary.mdl: R2012A WBToolboxLibrary.slx: R2014B WBToolboxLibrary_repository: R2016B --- toolbox/WBToolboxLibrary.mdl | 4378 ++++++++++++++++ toolbox/WBToolboxLibrary.slx | Bin 0 -> 536459 bytes toolbox/WBToolboxLibrary_repository.mdl | 6100 +++++++++++++++++++++++ 3 files changed, 10478 insertions(+) create mode 100644 toolbox/WBToolboxLibrary.mdl create mode 100644 toolbox/WBToolboxLibrary.slx create mode 100644 toolbox/WBToolboxLibrary_repository.mdl diff --git a/toolbox/WBToolboxLibrary.mdl b/toolbox/WBToolboxLibrary.mdl new file mode 100644 index 000000000..9d0e733f1 --- /dev/null +++ b/toolbox/WBToolboxLibrary.mdl @@ -0,0 +1,4378 @@ +Library { + Name "WBToolboxLibrary" + Version 7.9 + LibraryType "BlockLibrary" + SavedCharacterEncoding "US-ASCII" + ScopeRefreshTime 0.035000 + OverrideScopeRefreshTime on + DisableAllScopes off + FPTRunName "Run 1" + MaxMDLFileLineLength 120 + Created "Thu Feb 06 02:21:39 2014" + Creator "jorhabib" + UpdateHistory "UpdateHistoryNever" + ModifiedByFormat "%" + LastModifiedBy "icub" + ModifiedDateFormat "%" + LastModifiedDate "Fri Aug 11 07:02:44 2017" + RTWModifiedTimeStamp 424335764 + ModelVersionFormat "1.%" + ConfigurationManager "none" + SampleTimeColors off + SampleTimeAnnotations off + LibraryLinkDisplay "disabled" + WideLines off + ShowLineDimensions off + ShowPortDataTypes off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder off + ExecutionContextIcon off + ShowLinearizationAnnotations on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks off + BrowserLookUnderMasks off + SimulationMode "normal" + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + RecordCoverage off + CovSaveName "covdata" + CovMetricSettings "dw" + CovNameIncrementing off + CovHtmlReporting on + CovForceBlockReductionOff on + CovSaveCumulativeToWorkspaceVar on + CovSaveSingleToWorkspaceVar on + CovCumulativeReport off + CovReportOnPause on + CovModelRefEnable "Off" + CovExternalEMLEnable off + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 7 + Version "1.12.0" + Array { + Type "Handle" + Dimension 9 + Simulink.SolverCC { + $ObjectID 8 + Version "1.12.0" + StartTime "0.0" + StopTime "10.0" + AbsTol "auto" + FixedStep "auto" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + SolverMode "Auto" + EnableConcurrentExecution off + ConcurrentTasks off + Solver "ode45" + SolverName "ode45" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + } + Simulink.DataIOCC { + $ObjectID 9 + Version "1.12.0" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints on + MaxDataPoints "1000" + LoadExternalInput off + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "Array" + SignalLoggingSaveFormat "ModelDataLogs" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + } + Simulink.OptimizationCC { + $ObjectID 10 + Version "1.12.0" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + InlineParams off + UseIntDivNetSlope off + UseFloatMulNetSlope off + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + StrengthReduction off + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + ExpressionDepthLimit 2147483647 + LocalBlockOutputs on + RollThreshold 5 + StateBitsets off + DataBitsets off + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + OptimizeModelRefInitCode off + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "Off" + AccelVerboseBuild off + } + Simulink.DebuggingCC { + $ObjectID 11 + Version "1.12.0" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "none" + SignalRangeChecking "none" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Classic" + MergeDetectMultiDrivingBlocksExec "none" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "warning" + InheritedTsInSrcMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "error" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "none" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "none" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "Enable All" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "error" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "warning" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "warning" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "warning" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnconditionalTransitionShadowingDiag "warning" + ModelReferenceCSMismatchMessage "none" + } + Simulink.HardwareCC { + $ObjectID 12 + Version "1.12.0" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 32 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "None" + ProdIntDivRoundTo "Undefined" + ProdEndianess "Unspecified" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdHWDeviceType "32-bit Generic" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + } + Simulink.ModelReferenceCC { + $ObjectID 13 + Version "1.12.0" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel off + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 14 + Version "1.12.0" + SFSimEcho on + SimCtrlC on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 15 + Version "1.12.0" + Array { + Type "Cell" + Dimension 13 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "GenerateWebview" + Cell "GenerateCodeMetricsReport" + Cell "GenerateCodeReplacementReport" + Cell "PortableWordSizes" + Cell "GenerateMissedCodeReplacementReport" + Cell "GenerateErtSFunction" + Cell "CreateSILPILBlock" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + TLCOptions "" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + TemplateMakefile "grt_default_tmf" + PostCodeGenCommand "" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + IncludeHyperlinkInReport off + LaunchReport off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateWebview off + GenerateCodeMetricsReport off + GenerateCodeReplacementReport off + RTWCompilerOptimization "Off" + RTWCustomCompilerOptimizations "" + CheckMdlBeforeBuild "Off" + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 16 + Version "1.12.0" + Array { + Type "Cell" + Dimension 25 + Cell "IgnoreCustomStorageClasses" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "ReqsInCode" + Cell "InternalIdentifier" + Cell "CustomSymbolStrModelFcn" + Cell "CustomSymbolStrUtil" + Cell "CustomUserTokenString" + PropName "DisabledProps" + } + ForceParamTrailComments off + GenerateComments on + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M_T" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + DefineNamingRule "None" + ParamNamingRule "None" + SignalNamingRule "None" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 17 + Version "1.12.0" + Array { + Type "Cell" + Dimension 18 + Cell "GeneratePreprocessorConditionals" + Cell "IncludeMdlTerminateFcn" + Cell "SupportNonInlinedSFcns" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "CPPClassGenCompliant" + Cell "PortableWordSizes" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + Cell "MultiInstanceERTCode" + Cell "RemoveResetFunc" + Cell "ExistingSharedCode" + Cell "RemoveDisableFunc" + PropName "DisabledProps" + } + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + CodeReplacementLibrary "None" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + GenerateSampleERTMain off + GenerateTestInterfaces off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Disable all" + CombineOutputUpdateFcns off + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + SupportVariableSizeSignals off + ParenthesesLevel "Nominal" + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant on + AutosarCompliant off + GRTInterface on + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + } + PropName "Components" + } + } + hdlcoderui.hdlcc { + $ObjectID 19 + Version "1.12.0" + Description "HDL Coder custom configuration component" + Name "HDL Coder" + Array { + Type "Cell" + Dimension 1 + Cell " " + PropName "HDLConfigFile" + } + HDLCActiveTab "0" + } + PropName "Components" + } + Name "Configuration" + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 963, 135, 1843, 765 ] + } + PropName "ConfigurationSets" + } + ExplicitPartitioning off + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + BlockParameterDefaults { + Block { + BlockType Clock + DisplayTime off + Decimation "10" + } + Block { + BlockType Constant + Value "1" + VectorParams1D on + SamplingMode "Sample based" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit from 'Constant value'" + LockScale off + SampleTime "inf" + FramePeriod "inf" + PreserveConstantTs off + } + Block { + BlockType Demux + Outputs "4" + DisplayOption "none" + BusSelectionMode off + } + Block { + BlockType Gain + Gain "1" + Multiplication "Element-wise(K.*u)" + ParamMin "[]" + ParamMax "[]" + ParamDataTypeStr "Inherit: Same as input" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Inport + Port "1" + OutputFunctionCall off + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + LatchByDelayingOutsideSignal off + LatchInputForFeedbackSignals off + Interpolate on + } + Block { + BlockType Outport + Port "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + SourceOfInitialOutputValue "Dialog" + OutputWhenDisabled "held" + InitialOutput "[]" + } + Block { + BlockType Product + Inputs "2" + Multiplication "Element-wise(.*)" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Zero" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType S-Function + FunctionName "system" + SFunctionModules "''" + PortCounts "[]" + } + Block { + BlockType SubSystem + ShowPortLabels "FromPortIcon" + Permissions "ReadWrite" + PermitHierarchicalResolution "All" + TreatAsAtomicUnit off + SystemSampleTime "-1" + RTWFcnNameOpts "Auto" + RTWFileNameOpts "Auto" + RTWMemSecFuncInitTerm "Inherit from model" + RTWMemSecFuncExecute "Inherit from model" + RTWMemSecDataConstants "Inherit from model" + RTWMemSecDataInternal "Inherit from model" + RTWMemSecDataParameters "Inherit from model" + SimViewingDevice off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + SFBlockType "NONE" + GeneratePreprocessorConditionals off + PropagateVariantConditions off + TreatAsGroupedWhenPropagatingVariantConditions on + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Terminator + } + } + System { + Name "WBToolboxLibrary" + Location [173, 232, 1453, 953] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "black" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "273" + ReportName "simulink-default.rpt" + SIDHighWatermark "1772" + Block { + BlockType SubSystem + Name "Utilities" + SID "192" + Ports [] + Position [364, 17, 462, 114] + ZOrder -1 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('utilities.png'))" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "Utilities" + Location [173, 232, 1453, 953] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "166" + Block { + BlockType SubSystem + Name "DampPinv" + SID "104" + Ports [2, 1] + Position [435, 153, 505, 197] + ZOrder -1 + BackgroundColor "[0.848000, 0.128048, 0.320035]" + RequestExecContextInheritance off + Variant off + MaskPromptString "Tolerance" + MaskStyleString "edit" + MaskVariables "tol=@1;" + MaskTunableValueString "on" + MaskEnableString "on" + MaskVisibilityString "on" + MaskToolTipString "on" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "1e-4" + System { + Name "DampPinv" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "mat" + SID "105" + Position [50, 53, 80, 67] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "sigma" + SID "106" + Position [50, 93, 80, 107] + ZOrder -2 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Damped Pseudo Inverse" + SID "107" + Ports [2, 1] + Position [105, 39, 200, 121] + ZOrder -4 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + MaskType "Stateflow" + MaskDescription "Embedded MATLAB block" + MaskSelfModifiable on + MaskDisplay "bgColor = Simulink.Root.ColorString2Rgb(get_param(gcbh, 'BackgroundColor')); image(imread('p" + "rivate/eml_membrane_16.png','png','BackgroundColor',bgColor(1:3)),'center'); disp([10 10 'fcn']);" + MaskIconFrame on + MaskIconOpaque off + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "normalized" + System { + Name "Damped Pseudo Inverse" + Location [12, 45, 1279, 3773] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "1772" + Block { + BlockType Inport + Name "mat" + SID "107::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "sigma" + SID "107::25" + Position [20, 136, 40, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "107::1618" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 98 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "107::1617" + Tag "Stateflow S-Function WBToolboxLibrary 6" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 97 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport off + Port { + PortNumber 2 + Name "DPinv" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "107::1619" + Position [460, 241, 480, 259] + ZOrder 99 + } + Block { + BlockType Outport + Name "DPinv" + SID "107::5" + Position [460, 101, 480, 119] + ZOrder -6 + IconDisplay "Port number" + } + Line { + SrcBlock "mat" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + SrcBlock "sigma" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "DPinv" + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "DPinv" + DstPort 1 + } + Line { + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType Outport + Name "DPinv" + SID "108" + Position [225, 73, 255, 87] + ZOrder -5 + IconDisplay "Port number" + } + Line { + SrcBlock "sigma" + SrcPort 1 + DstBlock "Damped Pseudo Inverse" + DstPort 2 + } + Line { + SrcBlock "Damped Pseudo Inverse" + SrcPort 1 + DstBlock "DPinv" + DstPort 1 + } + Line { + SrcBlock "mat" + SrcPort 1 + DstBlock "Damped Pseudo Inverse" + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType Reference + Name "DiscreteFilter" + SID "1772" + Ports [1, 1] + Position [440, 260, 500, 290] + ZOrder 83 + BackgroundColor "yellow" + LibraryVersion "1.386" + SourceBlock "WBToolboxLibrary/Utilities/DiscreteFilter" + SourceType "Discrete Filter" + filterType "Generic" + numCoeffs "[0]" + denCoeffs "[0]" + Fc "0" + Ts "0" + orderMedianFilter "0" + } + Block { + BlockType S-Function + Name "DoFs converter" + SID "1771" + Ports [1, 5] + Position [240, 241, 385, 309] + ZOrder 81 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend\n" + FunctionName "WBToolbox" + Parameters "'YARPWBIConverter',robotName,localName,wbiFile,wbiList,yarp2WBIOption" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "DoFs converter" + MaskDescription "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on " + "its configuration.\nThe DoFs configuration is automatically currently taken from the WBI list option.\nThe robot na" + "me is taken from the environment variable YARP_ROBOT_NAME.\n\nParameters:\n\n- Conversion direction: specify if you" + " want to convert from YARP to the current DoFs serialization or viceversa.\n\nWBI parameters:\n\n- Robot Port Name:" + " Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name s" + "pecified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the por" + "ts opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of" + " the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Conversion Direction|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "popup(From YARP to WBI|From WBI to YARP),edit,edit,edit,edit" + MaskVariables "yarp2WBIOption=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" + MaskTunableValueString "on,on,on,on,on" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "robotName = getenv('YARP_ROBOT_NAME');\n\ncurrentSelection = get_param(gcb,'yarp2WBIoption');\n\nif" + " strcmp(currentSelection,'From YARP to WBI')\n direction = 'YARP -> DoFs';\nelse\n direction = 'DoFs -> YARP'" + ";\nend\n\nfprintf('%s\\n\\n%s', robotName, direction);" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "From YARP to WBI|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block Parameters,WBI Parameters,WBI Parameters,WBI Parameters,WBI Parameters" + } + Block { + BlockType S-Function + Name "Minimum Jerk Trajectory Generator" + SID "1747" + Ports [1, 3] + Position [335, 73, 490, 127] + ZOrder 78 + FunctionName "WBToolbox" + Parameters "'MinimumJerkTrajectoryGenerator',sampleTime, settlingTime, firstDerivatives, secondDerivatives, expl" + "icitInitialValue, externalSettlingTime,resetOnSettlingTime" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "Minimum Jerk Trajectory Generator" + MaskDescription "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk T" + "rajectory Generator is approximated using a \n3rd order LTI dynamical system \n(for more details see [1]). \nPositi" + "on, velocity and acceleration trajectories are computed.\n The main advantage with respect to the standard polynomi" + "al \nform is that if the reference value yd changes \nthere is no need to recompute the filter coefficients.\n\n[1]" + " Pattacini, U.; Nori, F.; Natale, L.; Metta, G.; Sandini, G., \"An experimental evaluation of a novel minimum-jerk " + "cartesian controller for humanoid robots,\" in Intelligent Robots and Systems (IROS), 2010 IEEE/RSJ International C" + "onference on , vol., no., pp.1668-1674, 18-22 Oct. 2010\ndoi: 10.1109/IROS.2010.5650851\nURL: http://ieeexplore.iee" + "e.org/stamp/stamp.jsp?tp=&arnumber=5650851&isnumber=5648787" + MaskPromptString "External Settling Time|Settling Time|Sample Time|Reset on Settling Time Changes|Output First De" + "rivative|Output Second Derivative|Explicit Initial Value" + MaskStyleString "checkbox,edit,edit,checkbox,checkbox,checkbox,checkbox" + MaskVariables "externalSettlingTime=@1;settlingTime=@2;sampleTime=@3;resetOnSettlingTime=@4;firstDerivatives=@5;" + "secondDerivatives=@6;explicitInitialValue=@7;" + MaskTunableValueString "on,on,on,on,on,on,on" + MaskCallbackString "externalSettlingTime = get_param(gcb, 'externalSettlingTime');\nvisibility = get_param(gcb, '" + "MaskVisibilities');\nif(strcmp(externalSettlingTime, 'on'))\n visibility{2} = 'off';\n visibility{4} = 'on';\n" + "else\n visibility{2} = 'on';\n visibility{4} = 'off';\nend\nset_param(gcb, 'MaskVisibilities',visibility);\nc" + "lear externalSettlingTime||||||" + MaskEnableString "on,on,on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on,on,off" + MaskToolTipString "on,on,on,on,on,on,on" + MaskDisplay "firstDer = get_param(gcb, 'firstDerivatives');\nsecondDer = get_param(gcb, 'secondDerivatives');\ni" + "nitialValues = get_param(gcb, 'explicitInitialValue');\nexternalSettlingTimeParam = get_param(gcb, 'externalSettlin" + "gTime');\n\n%Inputs\nportIndex = 2;\nport_label('input', 1, 'Reference')\nif(strcmp(initialValues, 'on'))\n port" + "_label('input', portIndex, 'Initial Value')\n portIndex = portIndex + 1;\nend\n\nif(strcmp(externalSettlingTimeP" + "aram, 'on'))\n port_label('input', portIndex, 'Settling Time')\n portIndex = portIndex + 1;\nend\n\n%Outputs\n" + "port_label('output', 1, 'Signal')\nsecondDerPortIndex = 2;\nif(strcmp(firstDer, 'on'))\n port_label('output', 2," + " 'First Derivative')\n secondDerPortIndex = secondDerPortIndex + 1;\nend\nif(strcmp(secondDer, 'on'))\n port_" + "label('output', secondDerPortIndex, 'Second Derivative')\nend\n\n\n" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "off|3|0.01|off|on|on|off" + MaskTabNameString "Trajectory Parameters,Trajectory Parameters,Trajectory Parameters,Trajectory Parameters,Input/" + "Output,Input/Output,Input/Output" + } + Block { + BlockType S-Function + Name "Real Time Synchronizer" + SID "1657" + Ports [] + Position [155, 14, 280, 51] + ZOrder 23 + ForegroundColor "white" + BackgroundColor "gray" + ShowName off + FunctionName "WBToolbox" + Parameters "'RealTimeSynchronizer',period" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "Real Time Synchronizer" + MaskDescription "This block slows down the simulation trying to match the period specified \nas parameter (in sec" + "onds).\nThe bigger the period the more probable \nis that Simulink can remain synched with it.\n" + MaskPromptString "Controller Period (in seconds)" + MaskStyleString "edit" + MaskVariables "period=@1;" + MaskTunableValueString "on" + MaskEnableString "on" + MaskVisibilityString "on" + MaskToolTipString "on" + MaskDisplay "disp('Real Time Synchronizer')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "0.01" + } + Block { + BlockType S-Function + Name "Simulator Synchronizer" + SID "1658" + Ports [] + Position [335, 14, 465, 51] + ZOrder 24 + ForegroundColor "[0.490196, 0.000000, 0.000000]" + ShowName off + FunctionName "WBToolbox" + Parameters "'SimulatorSynchronizer',period, serverPortName, clientPortName" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "Simulator Synchronizer" + MaskDescription "This block synchronizes with the external simulation on a simulator \n(only Gazebo is supported " + "at the moment).\n\n" + MaskPromptString "Controller Period (in seconds)|Server Port Name|Client Port Name" + MaskStyleString "edit,edit,edit" + MaskVariables "period=@1;serverPortName=@2;clientPortName=@3;" + MaskTunableValueString "on,on,on" + MaskCallbackString "||" + MaskEnableString "on,on,on" + MaskVisibilityString "on,on,on" + MaskToolTipString "on,on,on" + MaskDisplay "disp('Simulator Synchronizer')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "0.01|'/clock/rpc'|'/WBT_synchronizer/rpc:o'" + } + Block { + BlockType SubSystem + Name "TruncPinv" + SID "109" + Ports [2, 1] + Position [335, 153, 405, 197] + ZOrder -3 + BackgroundColor "[0.534601, 0.470279, 1.000000]" + RequestExecContextInheritance off + Variant off + MaskPromptString "Tolerance" + MaskStyleString "edit" + MaskVariables "tol=@1;" + MaskTunableValueString "on" + MaskEnableString "on" + MaskVisibilityString "on" + MaskToolTipString "on" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "1e-4" + System { + Name "TruncPinv" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "S" + SID "110" + Position [50, 53, 80, 67] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tol" + SID "111" + Position [50, 93, 80, 107] + ZOrder -2 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Truncated PseudoInverse" + SID "112" + Ports [2, 1] + Position [105, 39, 200, 121] + ZOrder -4 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + MaskType "Stateflow" + MaskDescription "Embedded MATLAB block" + MaskSelfModifiable on + MaskDisplay "bgColor = Simulink.Root.ColorString2Rgb(get_param(gcbh, 'BackgroundColor')); image(imread('p" + "rivate/eml_membrane_16.png','png','BackgroundColor',bgColor(1:3)),'center'); disp([10 10 'fcn']);" + MaskIconFrame on + MaskIconOpaque off + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "normalized" + System { + Name "Truncated PseudoInverse" + Location [12, 45, 1279, 3773] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "1772" + Block { + BlockType Inport + Name "mat" + SID "112::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tol" + SID "112::25" + Position [20, 136, 40, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "112::1609" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 98 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "112::1608" + Tag "Stateflow S-Function WBToolboxLibrary 7" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 97 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport off + Port { + PortNumber 2 + Name "TPinv" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "112::1610" + Position [460, 241, 480, 259] + ZOrder 99 + } + Block { + BlockType Outport + Name "TPinv" + SID "112::5" + Position [460, 101, 480, 119] + ZOrder -6 + IconDisplay "Port number" + } + Line { + SrcBlock "mat" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + SrcBlock "tol" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "TPinv" + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "TPinv" + DstPort 1 + } + Line { + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType Outport + Name "Tpinv" + SID "113" + Position [225, 73, 255, 87] + ZOrder -5 + IconDisplay "Port number" + } + Line { + SrcBlock "S" + SrcPort 1 + DstBlock "Truncated PseudoInverse" + DstPort 1 + } + Line { + SrcBlock "Truncated PseudoInverse" + SrcPort 1 + DstBlock "Tpinv" + DstPort 1 + } + Line { + SrcBlock "tol" + SrcPort 1 + DstBlock "Truncated PseudoInverse" + DstPort 2 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType S-Function + Name "Yarp Read" + SID "1632" + Ports [0, 2] + Position [105, 74, 165, 121] + ZOrder 22 + ForegroundColor "[0.490196, 0.000000, 0.000000]" + FunctionName "WBToolbox" + Parameters "'YarpRead',portName,signalSize,blocking,timestamp,autoconnect,errorOnConnection" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "YARP Read" + MaskDescription "This block behaves as the command 'yarp read'. \nBy default it has the option 'Autoconnect' acti" + "ve, which means that the user \ncan only specify the name of the port ('Source Port Name') from which readings are " + "desired,\nalong with the size of the expected data (e.g. 3 when reading the torso state).\nWhen the user unchecks '" + "Autoconnect' 'Opened Port Name' field shows up \ncorresponding to the name of the port the block will create \nbut " + "won't connect to anything. \nAt this point the output will be always zero, until the user connects it\nto some othe" + "r port from command line by issuing 'yarp connect [from] [dest]'.\nIn this case an additional output, called 'signa" + "l' will be added which will output\n1 if the port has received at least one data, or 0 otherwise.\n" + MaskPromptString "Source Port Name|Port Size|Blocking Read|Read Timestamp|Autoconnect|Error on missing connection" + MaskStyleString "edit,edit,checkbox,checkbox,checkbox,checkbox" + MaskVariables "portName=@1;signalSize=@2;blocking=@3;timestamp=@4;autoconnect=@5;errorOnConnection=@6;" + MaskTunableValueString "on,on,on,on,on,on" + MaskCallbackString "||||autoconnect_val = get_param(gcb, 'Autoconnect');\nprompt_string = get_param(gcb, 'MaskPro" + "mpts');\nif(strcmp(autoconnect_val, 'on'))\n prompt_string{1} = 'Source Port Name';\n set_param(gcb, 'MaskVis" + "ibilities',{'on';'on';'on';'on';'on';'on'});\nelse\n prompt_string{1} = 'Opened Port Name';\n set_param(gcb, " + "'MaskVisibilities',{'on';'on';'on';'on';'on';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear au" + "toconnect_val prompt_string|" + MaskEnableString "on,on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on,on" + MaskToolTipString "on,on,on,on,on,on" + MaskSelfModifiable on + MaskDisplay "port_label('output', 1, 'signal');\nportNumber = 1;\nif (timestamp)\n portNumber = portNumber + " + "1;\n port_label('output', portNumber, 'timestamp');\nend\n\nif (~autoconnect)\n portNumber = portNumber + 1;\n" + " port_label('output', portNumber, 'status');\nend\n\n" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'/portname'|1|off|on|on|on" + } + Block { + BlockType S-Function + Name "Yarp Write" + SID "1659" + Ports [1] + Position [230, 76, 290, 124] + ZOrder 27 + ForegroundColor "[0.490196, 0.000000, 0.000000]" + FunctionName "WBToolbox" + Parameters "'YarpWrite',portName,autoconnect,errorOnConnection" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "YARP Write" + MaskDescription "This block behaves as the command 'yarp write'. \n\nBy default this block opens a port names as " + "the \"Opened Port Name\" parameter\nand stream the input signal to that port.\nIf the option \"Autoconnect\" is spe" + "cified, the first parameter become the\nname of the target port to which the data will be stramed, \ne.g. like \"ya" + "rp write ... /destinationPort\"\n" + MaskPromptString "Opened Port Name|Autoconnect|Error on missing connection" + MaskStyleString "edit,checkbox,checkbox" + MaskVariables "portName=@1;autoconnect=@2;errorOnConnection=@3;" + MaskTunableValueString "on,on,on" + MaskCallbackString "|autoconnect_val = get_param(gcb, 'Autoconnect');\nprompt_string = get_param(gcb, 'MaskPrompt" + "s');\nif(strcmp(autoconnect_val, 'on'))\n prompt_string{1} = 'Destination Port Name';\n set_param(gcb, 'MaskV" + "isibilities',{'on';'on';'on'});\nelse\n prompt_string{1} = 'Opened Port Name';\n set_param(gcb, 'MaskVisibili" + "ties',{'on';'on';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val prompt_string|" + MaskEnableString "on,on,on" + MaskVisibilityString "on,on,off" + MaskToolTipString "on,on,on" + MaskSelfModifiable on + MaskDisplay "disp('Yarp Write')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'/portname'|off|on" + } + Block { + BlockType SubSystem + Name "errors" + SID "714" + Ports [2, 2] + Position [200, 153, 260, 197] + ZOrder -9 + BackgroundColor "[0.300000, 0.580000, 1.000000]" + RequestExecContextInheritance off + Variant off + MaskType "Errors" + MaskDescription "Computes two kinds of errors. The first is just the difference between x\nand y while the second" + " is the ratio (x-y)/y." + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "errors" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x" + SID "715" + Position [30, 28, 60, 42] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "y" + SID "716" + Position [25, 103, 55, 117] + ZOrder -2 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "717" + Ports [2, 1] + Position [95, 27, 125, 58] + ZOrder -3 + Inputs "+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Divide" + SID "718" + Ports [2, 1] + Position [165, 37, 195, 68] + ZOrder -4 + Inputs "*/" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "x-y" + SID "719" + Position [225, 13, 255, 27] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "(x-y)./y" + SID "720" + Position [220, 48, 250, 62] + ZOrder -6 + Port "2" + IconDisplay "Port number" + } + Line { + SrcBlock "Add" + SrcPort 1 + Points [10, 0] + Branch { + DstBlock "Divide" + DstPort 1 + } + Branch { + Points [0, -25] + DstBlock "x-y" + DstPort 1 + } + } + Line { + SrcBlock "x" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + SrcBlock "y" + SrcPort 1 + Points [15, 0] + Branch { + Points [0, -60] + DstBlock "Add" + DstPort 2 + } + Branch { + Points [60, 0; 0, -50] + DstBlock "Divide" + DstPort 2 + } + } + Line { + SrcBlock "Divide" + SrcPort 1 + DstBlock "(x-y)./y" + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "holder\n" + SID "1296" + Ports [1, 1] + Position [105, 152, 165, 198] + ZOrder 14 + BackgroundColor "[0.537255, 0.721569, 1.000000]" + RequestExecContextInheritance off + Variant off + MaskType "Holder" + MaskDescription "This block holds the first input value during the simulation." + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "holder\n" + Location [12, 45, 1340, 980] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "s" + SID "1297" + Position [145, 43, 175, 57] + ZOrder 13 + IconDisplay "Port number" + } + Block { + BlockType Clock + Name "Clock" + SID "1298" + Position [45, 65, 65, 85] + ZOrder 11 + } + Block { + BlockType Reference + Name "Compare\nTo Constant" + SID "1299" + Ports [1, 1] + Position [90, 60, 120, 90] + ZOrder 10 + LibraryVersion "1.388" + SourceBlock "simulink/Logic and Bit\nOperations/Compare\nTo Constant" + SourceType "Compare To Constant" + relop "==" + const "0" + OutDataTypeStr "boolean" + ZeroCross on + } + Block { + BlockType SubSystem + Name "MATLAB Function" + SID "1300" + Ports [2, 1] + Position [235, 37, 305, 88] + ZOrder 15 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ParametersOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + MaskType "Stateflow" + MaskDescription "Embedded MATLAB block" + MaskSelfModifiable on + MaskDisplay "bgColor = Simulink.Root.ColorString2Rgb(get_param(gcbh, 'BackgroundColor')); image(imread('p" + "rivate/eml_membrane_16.png','png','BackgroundColor',bgColor(1:3)),'center'); disp([10 10 'fcn']);" + MaskIconFrame on + MaskIconOpaque off + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "normalized" + System { + Name "MATLAB Function" + Location [12, 45, 1135, 3068] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "1772" + Block { + BlockType Inport + Name "s" + SID "1300::24" + Position [20, 101, 40, 119] + ZOrder 10 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "unused" + SID "1300::26" + Position [20, 136, 40, 154] + ZOrder 12 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "1300::1609" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 86 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "1300::1608" + Tag "Stateflow S-Function WBToolboxLibrary 1" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 85 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport off + Port { + PortNumber 2 + Name "s0" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "1300::1610" + Position [460, 241, 480, 259] + ZOrder 87 + } + Block { + BlockType Outport + Name "s0" + SID "1300::25" + Position [460, 101, 480, 119] + ZOrder 11 + IconDisplay "Port number" + } + Line { + SrcBlock "s" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + SrcBlock "unused" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "s0" + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "s0" + DstPort 1 + } + Line { + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType Outport + Name "s(0)" + SID "1301" + Position [330, 58, 360, 72] + ZOrder 14 + IconDisplay "Port number" + } + Line { + SrcBlock "Clock" + SrcPort 1 + DstBlock "Compare\nTo Constant" + DstPort 1 + } + Line { + SrcBlock "MATLAB Function" + SrcPort 1 + DstBlock "s(0)" + DstPort 1 + } + Line { + SrcBlock "s" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 1 + } + Line { + SrcBlock "Compare\nTo Constant" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 2 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "wholeBodyActuators" + SID "224" + Ports [] + Position [250, 16, 348, 113] + ZOrder -17 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('wholeBodyActuators.png'),'center')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "wholeBodyActuators" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "667" + Block { + BlockType SubSystem + Name "Set LowLevel PIDs" + SID "1752" + Ports [] + Position [745, 230, 820, 280] + ZOrder 41 + BackgroundColor "[0.827500, 0.576500, 0.603900]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + MaskType "Set Low Level PIDs" + MaskDescription "This block sets the low level PID values for the robot actuators.\n\nIf only one gain file is sp" + "ecified, those gains are loaded at startup.\nOtherwise an additional port to this block is added which accept an in" + "teger\nrepresenting the index in the list of gains to be loaded (also at runtime)\n\nAssuming DoFs is the number of" + " degrees of freedom of the robot,\nParameters:\n- PID Parameter: String specifying either a file containing the PID" + "s for the\n low level control, or a list of files (in yarp Bottle format).\n\n- Robot Port Name: Na" + "me of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name spec" + "ified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports " + "opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of th" + "e Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "PID parameter|PID Type|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "edit,popup(Position|Torque),edit,edit,edit,edit" + MaskVariables "pidParameters=@1;pidType=&2;robotName=@3;localName=@4;wbiFile=@5;wbiList=@6;" + MaskTunableValueString "off,on,off,off,off,off" + MaskCallbackString "|% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(" + "gcb,'pidType');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0" + "]');\nelseif strcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0" + "]');\nelseif strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\ne" + "lseif strcmp(maskStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear" + " maskStr||||" + MaskEnableString "on,on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on,on" + MaskToolTipString "on,on,on,on,on,on" + MaskDisplay "pidType = get_param(gcb,'pidType');\ndescription = sprintf('Set Low Level\\n%s PIDs', pidType);\ndi" + "sp(description);\n" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "''|Torque|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" + System { + Name "Set LowLevel PIDs" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "1000" + Block { + BlockType S-Function + Name "S-Function" + SID "1753" + Ports [] + Position [125, 39, 185, 71] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'SetLowLevelPID',robotName,localName,wbiFile,wbiList,pidParameters,pidType" + SFunctionDeploymentMode off + EnableBusSupport off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Set References" + SID "1767" + Ports [1] + Position [645, 230, 720, 280] + ZOrder 43 + BackgroundColor "[0.513700, 0.851000, 0.670600]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + MaskType "Set References" + MaskDescription "This block sets the references for the robot actuators.\nThe type of control mode is specified a" + "s a parameter in the block.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Reference" + "s: Vector of size DoFs, representing the references to be sent \n to the robot controlled joints.\n\n" + "Parameters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the p" + "orts opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in th" + "e \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by t" + "he underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Bod" + "y Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Control Mode|Control Type|Controlled Joint List|Robot Port Name|Model Name|WBI filename|WBI lis" + "t name" + MaskStyleString "popup(Position|Position Direct|Velocity|Torque|Open Loop),popup(Full|Sublist),edit,edit,edit,edi" + "t,edit" + MaskVariables "controlType=&1;fullOrSubControl=@2;controlledJoints=@3;robotName=@4;localName=@5;wbiFile=@6;wbiLi" + "st=@7;" + MaskTunableValueString "on,on,on,off,off,off,off" + MaskCallbackString "% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(g" + "cb,'controlType');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, " + "1.0]');\nelseif strcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, " + "1.0]');\nelseif strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');" + "\nelseif strcmp(maskStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nelseif " + "strcmp(maskStr, 'Open Loop')\n set_param(gcb,'BackgroundColor', '[0.98, 0.98, 0.98, 1.0]');\nend\nclear maskStr" + "|subOrFull = get_param(gcb, 'fullOrSubControl');\nif(strcmp(subOrFull, 'Sublist'))\n set_param(gcb, 'MaskVisibil" + "ities',{'on';'on';'on';'on';'on';'on';'on'});\nelse\n set_param(gcb, 'MaskVisibilities',{'on';'on';'off';'on';'o" + "n';'on';'on'});\nend\nclear subOrFull |||||" + MaskEnableString "on,on,on,on,on,on,on" + MaskVisibilityString "on,on,off,on,on,on,on" + MaskToolTipString "on,on,on,on,on,on,on" + MaskDisplay "disp(get_param(gcb,'controlType'))\n%port_label('input',1,'References')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "Position|Full|''|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,Block parameters,Block parameters,WBI parameters,WBI parameters,WBI parameter" + "s,WBI parameters" + System { + Name "Set References" + Location [535, 41, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "521" + Block { + BlockType Inport + Name "References" + SID "1768" + Position [55, 48, 85, 62] + ZOrder 24 + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1769" + Ports [1] + Position [125, 39, 185, 71] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'SetReferences',robotName,localName,wbiFile,wbiList,controlType,fullOrSubControl,controlledJo" + "ints" + SFunctionDeploymentMode off + EnableBusSupport off + } + Line { + SrcBlock "References" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "wholeBodyModel" + SID "209" + Ports [] + Position [133, 16, 231, 113] + ZOrder -3 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('wholeBodyModel.png'),'center')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "wholeBodyModel" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "309" + Block { + BlockType SubSystem + Name "Dynamics" + SID "369" + Ports [] + Position [364, 21, 471, 128] + ZOrder -1 + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('Dynamics.png'))" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "Dynamics" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "219" + Block { + BlockType SubSystem + Name "Centroidal Momentum" + SID "1694" + Ports [4, 1] + Position [495, 101, 680, 164] + ZOrder 72 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Centroidal Momentum" + MaskDescription "This block computed the 6 element centroidal momentum, as defined in:\n\"Centroidal dyna" + "mics of a humanoid robot\" - DE Orin, A Goswami, SH Lee - \nAutonomous Robots 35 (2-3), 161-176\n\nAssuming DoF" + "s is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenou" + "s transformation between\n the base frame and the world frame.\n- Joint configuration: Vector of si" + "ze DoFs, representing the configuration \n of the joints.\n- Base velocity: Vector of siz" + "e 6 representing the linear and angular velocity\n of the base frame.\n- Joints velocity: Vecto" + "r of size DoFs, representing the velocity \n of the joints.\n\nOutput:\n- Centroidal Momentum" + ": 6-element vector containg the centroidal momentum \n (3 value for linear momentum and 3 for an" + "gular momentum)\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n " + " Set an empty string ('') to use the name specified in the \n Whole Body Interface" + " configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- " + "WBI filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Name: name " + "of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "edit,edit,edit,edit" + MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;" + MaskTunableValueString "off,off,off,off" + MaskCallbackString "|||" + MaskEnableString "on,on,on,on" + MaskVisibilityString "on,on,on,on" + MaskToolTipString "on,on,on,on" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + System { + Name "Centroidal Momentum" + Location [0, 23, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "248" + Block { + BlockType Inport + Name "Base Pose" + SID "1695" + Position [20, 18, 50, 32] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1696" + Position [20, 53, 50, 67] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Base velocity" + SID "1697" + Position [20, 88, 50, 102] + ZOrder 26 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joints velocity" + SID "1698" + Position [20, 123, 50, 137] + ZOrder 27 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1699" + Ports [4, 1] + Position [180, 11, 255, 144] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'CentroidalMomentum',robotName,localName,wbiFile,wbiList" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Centroidal Momentum" + SID "1700" + Position [315, 73, 345, 87] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Centroidal Momentum" + DstPort 1 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + SrcBlock "Base velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + SrcBlock "Joints velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 4 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Get Bias Forces" + SID "1724" + Ports [4, 1] + Position [400, 202, 540, 303] + ZOrder 73 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Get Generalized Bias Forces" + MaskDescription "This block retrieves the generalied bias forces of the robot.\n\nParameter:\n- Explicit " + "Gravity. If True, an additional port (explicit Gravity) is added.\n Otherwise the vector [0;" + " 0; -9.81] is used.\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 " + "matrix representing the homogenous transformation between\n the base frame and the world frame.\n- J" + "oint configuration: Vector of size DoFs, representing the configuration \n of the joints.\n-" + " Base velocity: Vector of size 6 representing the linear and angular velocity\n of the base fra" + "me.\n- Joints velocity: Vector of size DoFs, representing the velocity of the joints.\n\nOutput:\n- Bias Forces" + ": a Dofs + 6 vector representing the generalized bias forces\n of the robot\n\nParameters:\n- Robot " + "Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to " + "use the name specified in the \n Whole Body Interface configuration file." + "\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name o" + "f the file containing the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joint" + "s used to configure the Whole Body Interface\n" + MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name|Explicit Gravity" + MaskStyleString "edit,edit,edit,edit,checkbox" + MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;explicitGravity=@5;" + MaskTunableValueString "off,off,off,off,on" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskInitialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on'," + " ...\n'Name', 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb" + ",'/S-Function']);\n add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S" + "-Function/7', 'autorouting','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gra" + "vity/1','S-Function/7');\n delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function'])" + ";\n end\nend\n" + MaskSelfModifiable on + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList|off" + System { + Name "Get Bias Forces" + Location [354, 32, 1634, 747] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "255" + SIDHighWatermark "1748" + Block { + BlockType Inport + Name "Base Pose" + SID "1724:1725" + Position [35, 38, 65, 52] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1724:1726" + Position [35, 68, 65, 82] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Base velocity" + SID "1724:1727" + Position [35, 98, 65, 112] + ZOrder 26 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joints velocity" + SID "1724:1728" + Position [35, 128, 65, 142] + ZOrder 27 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Constant + Name "Constant" + SID "1724:1742" + Position [20, 157, 75, 173] + ZOrder 30 + ShowName off + Value "zeros(6,1)" + } + Block { + BlockType Gain + Name "Gain" + SID "1724:1743" + Position [135, 180, 165, 210] + ZOrder 31 + ShowName off + Gain "0" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType S-Function + Name "S-Function" + SID "1724:1731" + Ports [6, 1] + Position [205, 24, 265, 216] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Bias Forces" + SID "1724:1732" + Position [325, 113, 355, 127] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Bias Forces" + DstPort 1 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + SrcBlock "Base velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + SrcBlock "Joints velocity" + SrcPort 1 + Points [44, 0] + Branch { + Points [0, 60] + DstBlock "Gain" + DstPort 1 + } + Branch { + DstBlock "S-Function" + DstPort 4 + } + } + Line { + SrcBlock "Constant" + SrcPort 1 + DstBlock "S-Function" + DstPort 5 + } + Line { + SrcBlock "Gain" + SrcPort 1 + DstBlock "S-Function" + DstPort 6 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Get Gravity Forces" + SID "1733" + Ports [2, 1] + Position [605, 200, 745, 300] + ZOrder 74 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Gravity bias" + MaskDescription "This block compute the generalized bias forces due to the gravity\n\nParameter:\n- Expli" + "cit Gravity. If True, an additional port (explicit Gravity) is added.\n Otherwise the vector" + " [0; 0; -9.81] is used.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose" + ": 4x4 matrix representing the homogenous transformation between\n the base frame and the world fram" + "e.\n- Joint configuration: Vector of size DoFs, representing the configuration \n of the " + "joints.\n\nOutput:\n- Gravity: a Dofs + 6 vector representing the torques due to the gravity.\n\nParameters:\n-" + " Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (" + "'') to use the name specified in the \n Whole Body Interface configuration file.\n- Model Nam" + "e: Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file co" + "ntaining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to con" + "figure the Whole Body Interface\n" + MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name|Explicit Gravity" + MaskStyleString "edit,edit,edit,edit,checkbox" + MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;explicitGravity=@5;" + MaskTunableValueString "off,off,off,off,on" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskInitialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on'," + " ...\n'Name', 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb" + ",'/S-Function']);\n add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S" + "-Function/7', 'autorouting','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gra" + "vity/1','S-Function/7');\n delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function'])" + ";\n end\nend\n" + MaskSelfModifiable on + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList|off" + System { + Name "Get Gravity Forces" + Location [354, 32, 1634, 747] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "255" + SIDHighWatermark "1748" + Block { + BlockType Inport + Name "Base Pose" + SID "1733:1734" + Position [10, 38, 40, 52] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1733:1735" + Position [10, 68, 40, 82] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Constant + Name "Constant" + SID "1733:1744" + Position [0, 97, 55, 113] + ZOrder 32 + ShowName off + Value "zeros(6,1)" + } + Block { + BlockType Gain + Name "Gain" + SID "1733:1745" + Position [100, 120, 130, 150] + ZOrder 33 + ShowName off + Gain "0" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType S-Function + Name "S-Function" + SID "1733:1740" + Ports [6, 1] + Position [180, 24, 240, 216] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Gravity Torques" + SID "1733:1741" + Position [300, 113, 330, 127] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Gravity Torques" + DstPort 1 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + Points [41, 0] + Branch { + Points [0, 60] + DstBlock "Gain" + DstPort 1 + } + Branch { + DstBlock "S-Function" + DstPort 2 + } + } + Line { + SrcBlock "Constant" + SrcPort 1 + Points [4, 0] + Branch { + Points [0, 60] + DstBlock "S-Function" + DstPort 5 + } + Branch { + DstBlock "S-Function" + DstPort 3 + } + } + Line { + SrcBlock "Gain" + SrcPort 1 + Points [13, 0] + Branch { + Points [0, 60] + DstBlock "S-Function" + DstPort 6 + } + Branch { + DstBlock "S-Function" + DstPort 4 + } + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType S-Function + Name "Inverse Dynamics" + SID "1748" + Ports [6, 1] + Position [190, 199, 355, 331] + ZOrder 75 + FunctionName "WBToolbox" + Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "Inverse Dynamics" + MaskDescription "This block compute the inverse dynamics of the robot.\n\nParameter:\n- Explicit Gravity." + " If True, an additional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.8" + "1] is used.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix" + " representing the homogenous transformation between\n the base frame and the world frame.\n- Joint " + "configuration: Vector of size DoFs, representing the configuration \n of the joints.\n- B" + "ase velocity: Vector of size 6 representing the linear and angular velocity\n of the base frame" + ".\n- Joints velocity: Vector of size DoFs, representing the velocity \n of the joints.\n- Bas" + "e acceleration: Vector of size 6 representing the linear and angular acceleration\n of the base" + " frame.\n- Joints acceleration: Vector of size DoFs, representing the acceleration \n of the " + "joints.\n- Gravity: Vector of size 3, denoting the acceleration vector w.r.t. the world frame.\n\n\nOutput:\n- " + "Torques: a Dofs + 6 vector representing the corresponding torques required\n to achive the desired ac" + "celerations given the robot state\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot. (e." + "g. icub).\n Set an empty string ('') to use the name specified in the \n Wh" + "ole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole B" + "ody Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n- WB" + "I List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name|Explicit Gravity" + MaskStyleString "edit,edit,edit,edit,checkbox" + MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;explicitGravity=@5;" + MaskTunableValueString "on,on,on,on,on" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "port_label('output', 1, 'Torques')\n\nport_label('input', 1, 'Base pose')\nport_label('input" + "', 2, 'Joints configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joints velocity" + "')\nport_label('input', 5, 'Base acceleration')\nport_label('input', 6, 'Joints acceleration')\n\n\ngravity = g" + "et_param(gcb, 'explicitGravity');\nif(strcmp(gravity, 'on'))\n port_label('input', 7, 'Gravity')\nend\n" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList|off" + } + Block { + BlockType SubSystem + Name "Mass Matrix" + SID "1633" + Ports [2, 1] + Position [250, 104, 390, 171] + ZOrder 32 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Mass Matrix" + MaskDescription "This block retrieves the robot mass matrix.\n\nAssuming DoFs is the number of degrees of" + " freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n " + " the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the con" + "figuration \n of the joints.\n\nOutput:\n- Mass Matrix: a (Dofs + 6) x (Dofs + 6) matrix " + "representing the mass matrix \n of the robot\n\nParameters:\n- Robot Port Name: Name of the ports" + " opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in th" + "e \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened " + "by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the W" + "hole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "edit,edit,edit,edit" + MaskVariables "robotName=@1;localName=@2;wbiFile=@3;wbiList=@4;" + MaskTunableValueString "off,off,off,off" + MaskCallbackString "|||" + MaskEnableString "on,on,on,on" + MaskVisibilityString "on,on,on,on" + MaskToolTipString "on,on,on,on" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + System { + Name "Mass Matrix" + Location [589, 68, 1869, 783] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "248" + Block { + BlockType Inport + Name "Base Pose" + SID "1634" + Position [20, 23, 50, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1635" + Position [20, 63, 50, 77] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1636" + Ports [2, 1] + Position [125, 37, 185, 68] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'MassMatrix',robotName,localName,wbiFile,wbiList" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Mass Matrix" + SID "1637" + Position [245, 48, 275, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Mass Matrix" + DstPort 1 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + Points [36, 0; 0, 15] + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + Points [33, 0; 0, -10] + DstBlock "S-Function" + DstPort 2 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Jacobians" + SID "202" + Ports [] + Position [217, 20, 324, 127] + ZOrder -3 + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('jacobian.png'))" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "Jacobians" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "322" + Block { + BlockType SubSystem + Name "DotJ Nu" + SID "1683" + Ports [4, 1] + Position [590, 170, 755, 265] + ZOrder 67 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "DotJ Nu" + MaskDescription "This block computes the product between the time derivative of the\n Jacobian of" + " the specified frame and the state (base and joints)\n velocity vector.\n\nAssuming DoFs is the number o" + "f degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation " + "between\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, repr" + "esenting the configuration \n of the joints.\n- Base velocity: Vector of size 6 represent" + "ing the linear and angular velocity\n of the base frame.\n- Joints velocity: Vector of size DoF" + "s, representing the velocity \n of the joints.\n\nOutput:\n- dotJ nu: a 6-d vector representi" + "ng the product between the time derivative of the\n Jacobian of the specified frame and the state veloc" + "ity vector\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- " + "Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('" + "') to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name" + ": Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file con" + "taining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to conf" + "igure the Whole Body Interface\n" + MaskPromptString "Frame name|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "edit,edit,edit,edit,edit" + MaskVariables "frameName=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" + MaskTunableValueString "on,off,off,off,off" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('dot J_{'," + "escapedFrameName,'} \\nu'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\np" + "ort_label('input', 2, 'Joint configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, '" + "Joint velocity')\n\nclear escapedFrameName;" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'frame'|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" + System { + Name "DotJ Nu" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "391" + Block { + BlockType Inport + Name "Base Pose" + SID "1684" + Position [20, 13, 50, 27] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1685" + Position [20, 43, 50, 57] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Base velocity" + SID "1686" + Position [20, 73, 50, 87] + ZOrder 26 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joints velocity" + SID "1687" + Position [20, 103, 50, 117] + ZOrder 27 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1688" + Ports [4, 1] + Position [125, 4, 190, 126] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'DotJNu',robotName,localName,wbiFile,wbiList,frameName" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "dotJ dotnu" + SID "1689" + Position [245, 43, 275, 57] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "S-Function" + SrcPort 1 + Points [20, 0; 0, -15] + DstBlock "dotJ dotnu" + DstPort 1 + } + Line { + SrcBlock "Base velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + SrcBlock "Joints velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 4 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Jacobian" + SID "1663" + Ports [2, 1] + Position [380, 190, 540, 245] + ZOrder 39 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Jacobian" + MaskDescription "This block retrieves the Jacobian of the specified frame.\n\nAssuming DoFs is the number" + " of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformatio" + "n between\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, re" + "presenting the configuration \n of the joints.\n\nOutput:\n- Jacobian: a 6x6+dofs matrix " + "representing the Jacobian of\n the specified frame written in the world frame.\n\nParameters:\n- Fr" + "ame name: the name of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the po" + "rts opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in" + " the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports open" + "ed by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of th" + "e Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Frame name|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "edit,edit,edit,edit,edit" + MaskVariables "frameName=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" + MaskTunableValueString "on,off,off,off,off" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world" + "} J_{',escapedFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n" + "port_label('input', 2, 'Joint configuration')\n\nclear escapedFrameName;" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'frame'|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" + System { + Name "Jacobian" + Location [208, 105, 1008, 627] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "237" + Block { + BlockType Inport + Name "Base Pose" + SID "1664" + Position [20, 23, 50, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1665" + Position [20, 63, 50, 77] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1666" + Ports [2, 1] + Position [125, 37, 185, 68] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'Jacobian',robotName,localName,wbiFile,wbiList,frameName" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Forward Kinematics" + SID "1667" + Position [245, 48, 275, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Forward Kinematics" + DstPort 1 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + Points [36, 0; 0, 15] + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + Points [33, 0; 0, -10] + DstBlock "S-Function" + DstPort 2 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Kinematics" + SID "176" + Ports [] + Position [70, 20, 177, 127] + ZOrder -17 + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('forwardKinematics.png'))" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "Kinematics" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "326" + Block { + BlockType SubSystem + Name "Forward Kinematics" + SID "1647" + Ports [2, 1] + Position [350, 103, 500, 167] + ZOrder 34 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Forward Kinematics" + MaskDescription "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is " + "the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous tra" + "nsformation between\n the the base frame and the world frame.\n- Joint configuration: Vector of siz" + "e DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Forward Kinematics" + ": a 4x4 matrix representing the homogenous transformation between\n the specified frame and the wor" + "ld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- R" + "obot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (''" + ") to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name:" + " Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file cont" + "aining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to confi" + "gure the Whole Body Interface\n" + MaskPromptString "Frame name|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "edit,edit,edit,edit,edit" + MaskVariables "frameName=@1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" + MaskTunableValueString "on,off,off,off,off" + MaskCallbackString "||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world" + "} H_{',escapedFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n" + "port_label('input', 2, 'Joint configuration')\n\nclear escapedFrameName;" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'frame'|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" + System { + Name "Forward Kinematics" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "391" + Block { + BlockType Inport + Name "Base Pose" + SID "1648" + Position [20, 23, 50, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1649" + Position [20, 63, 50, 77] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1650" + Ports [2, 1] + Position [125, 37, 185, 68] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'ForwardKinematics',robotName,localName,wbiFile,wbiList,frameName" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Forward Kinematics" + SID "1651" + Position [245, 48, 275, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Forward Kinematics" + DstPort 1 + } + Line { + SrcBlock "Base Pose" + SrcPort 1 + Points [36, 0; 0, 15] + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Joint configuration" + SrcPort 1 + Points [33, 0; 0, -10] + DstBlock "S-Function" + DstPort 2 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Inverse Kinematics" + SID "1754" + Ports [3, 2] + Position [350, 198, 525, 262] + ZOrder 35 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Forward Kinematics" + MaskDescription "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is " + "the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous tra" + "nsformation between\n the the base frame and the world frame.\n- Joint configuration: Vector of siz" + "e DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Forward Kinematics" + ": a 4x4 matrix representing the homogenous transformation between\n the specified frame and the wor" + "ld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- R" + "obot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (''" + ") to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name:" + " Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file cont" + "aining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to confi" + "gure the Whole Body Interface\n" + MaskPromptString "Base Frame|End Effector frame|Optimization Option|Robot Port Name|Model Name|WBI filena" + "me|WBI list name" + MaskStyleString "edit,edit,popup(Full Constraint (Position and Orientation)|Position only constraint),edi" + "t,edit,edit,edit" + MaskVariables "baseFrame=@1;endEffFrame=@2;optOption=@3;robotName=@4;localName=@5;wbiFile=@6;wbiList=@7;" + MaskTunableValueString "on,on,on,off,off,off,off" + MaskCallbackString "||||||" + MaskEnableString "on,on,on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on,on,on" + MaskToolTipString "on,on,on,on,on,on,on" + MaskDisplay "escapedBaseFrameName = strrep(baseFrame, '_', '\\_');\nescapedEndEffFrameName = strrep(endEf" + "fFrame, '_', '\\_');\n\n%port_label('output', 1, strcat('{}^{world} H_{',escapedFrameName,'}'), 'texmode','on')" + "\n\n%port_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n%port_label('input', 2, 'Joint configuratio" + "n')\n\n%clear escapedFrameName;\n\n\n% if strcmp(robotPart, 'left')\n% prefix = 'l';\n% else\n% prefix " + "= 'r';\n% end\n% \nport_label('input', 1, strcat('{}^{',escapedBaseFrameName,'} H_{',escapedEndEffFrameName,'}^" + "d'), 'texmode','on');\n\nport_label('input', 2, '{}^{world} H_{base}', 'texmode','on')\nport_label('input', 3, " + "'q_j', 'texmode','on');\n% \n% \nport_label('output', 1, '{}^{world} H_{base}^d', 'texmode','on')\nport_label('" + "output', 2, 'q_j^d', 'texmode','on');\n\n" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'root_link'|'l_sole'|Full Constraint (Position and Orientation)|WBT_robotName|WBT_modelN" + "ame|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,Block parameters,Block parameters,WBI parameters,WBI parameters,WBI p" + "arameters,WBI parameters" + System { + Name "Inverse Kinematics" + Location [0, 23, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "312" + Block { + BlockType Inport + Name "Desired frame pose" + SID "1759" + Position [10, 13, 40, 27] + ZOrder 26 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Current Base Pose" + SID "1755" + Position [10, 43, 40, 57] + ZOrder 22 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Current Joint configuration" + SID "1756" + Position [10, 73, 40, 87] + ZOrder 24 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1757" + Ports [3, 2] + Position [145, 4, 225, 96] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'InverseKinematics',robotName,localName,wbiFile,wbiList,baseFrame, endEffFrame,optOption" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Desired Base Pose" + SID "1758" + Position [280, 23, 310, 37] + ZOrder 25 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Desired Joint Configuration" + SID "1760" + Position [280, 68, 310, 82] + ZOrder 27 + Port "2" + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Desired Base Pose" + DstPort 1 + } + Line { + SrcBlock "Current Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + SrcBlock "Current Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + SrcBlock "Desired frame pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "S-Function" + SrcPort 2 + DstBlock "Desired Joint Configuration" + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Remote Inverse Kinematics" + SID "1761" + Ports [2, 1] + Position [560, 105, 720, 165] + ZOrder 66 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + MaskType "Forward Kinematics" + MaskDescription "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is " + "the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous tra" + "nsformation between\n the the base frame and the world frame.\n- Joint configuration: Vector of siz" + "e DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Forward Kinematics" + ": a 4x4 matrix representing the homogenous transformation between\n the specified frame and the wor" + "ld frame.\n\nParameters:\n- Frame name: the name of the frame. It should be specified in the URDF model.\n\n- R" + "obot Port Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string (''" + ") to use the name specified in the \n Whole Body Interface configuration file.\n- Model Name:" + " Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file cont" + "aining the configuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to confi" + "gure the Whole Body Interface\n" + MaskPromptString "Solver Name|#Dofs|Optimization Option" + MaskStyleString "edit,edit,popup(Full Constraint (Position and Orientation)|Position only constraint)" + MaskVariables "solverName=@1;dofs=@2;optOption=@3;" + MaskTunableValueString "on,off,on" + MaskCallbackString "||" + MaskEnableString "on,on,on" + MaskVisibilityString "on,on,on" + MaskToolTipString "on,on,on" + MaskDisplay "disp(solverName)\n\n\n\n% escapedBaseFrameName = strrep(baseFrame, '_', '\\_');\n% escapedEn" + "dEffFrameName = strrep(endEffFrame, '_', '\\_');\n% \n% %port_label('output', 1, strcat('{}^{world} H_{',escape" + "dFrameName,'}'), 'texmode','on')\n% \n% %port_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n% %port" + "_label('input', 2, 'Joint configuration')\n% \n% %clear escapedFrameName;\n% \n% \n% % if strcmp(robotPart, 'le" + "ft')\n% % prefix = 'l';\n% % else\n% % prefix = 'r';\n% % end\n% % \n\nport_label('input', 1, 'H^d', 't" + "exmode','on');\n% port_label('input', 1, strcat('{}^{',escapedBaseFrameName,'} H_{',escapedEndEffFrameName,'}^d" + "'), 'texmode','on');\n% \n% port_label('input', 2, '{}^{world} H_{base}', 'texmode','on')\nport_label('input', " + "2, 'q_j(0)', 'texmode','on');\n% % \n% % \n% port_label('output', 1, '{}^{world} H_{base}^d', 'texmode','on')\n" + "port_label('output', 1, 'q_j^d', 'texmode','on');\n\n" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "'/cartesianSolver'|12|Full Constraint (Position and Orientation)" + MaskTabNameString "Block parameters,Block parameters,Block parameters" + System { + Name "Remote Inverse Kinematics" + Location [853, 51, 2214, 1013] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "375" + Block { + BlockType Inport + Name "Desired frame pose" + SID "1762" + Position [10, 23, 40, 37] + ZOrder 26 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Current Joint configuration" + SID "1763" + Position [10, 68, 40, 82] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1764" + Ports [2, 1] + Position [145, 6, 225, 99] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'RemoteInverseKinematics',solverName, dofs, optOption" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Desired Joint Configuration" + SID "1765" + Position [285, 48, 315, 62] + ZOrder 27 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Desired Joint Configuration" + DstPort 1 + } + Line { + SrcBlock "Desired frame pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + SrcBlock "Current Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "wholeBodyStates" + SID "206" + Ports [] + Position [16, 17, 114, 114] + ZOrder -4 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + MaskDisplay "image(imread('wholeBodyStates.png'),'center');" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + System { + Name "wholeBodyStates" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "576" + Block { + BlockType SubSystem + Name "Get Estimate" + SID "1671" + Ports [0, 1] + Position [360, 212, 440, 248] + ZOrder 53 + BackgroundColor "[0.513700, 0.851000, 0.670600]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + MaskType "Get Estimate" + MaskDescription "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of f" + "reedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParameter" + "s:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports open" + "ed by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underl" + "ying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interfa" + "ce\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Estimate Type|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "popup(Joints Position|Joints Velocity|Joints Acceleration|Joints Torque),edit,edit,edit,edit" + MaskVariables "estimateType=&1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" + MaskTunableValueString "on,off,off,off,off" + MaskCallbackString "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param" + "(gcb,'estimateType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510" + ", 0.6706, 1.0]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745" + ", 1.0000, 1.0]');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0." + "8706, 0.1333, 1.0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.57" + "65, 0.6039, 1.0]');\nend\nclear maskStr||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "%disp(get_param(gcb,'estimateType'))\nport_label('output',1,get_param(gcb,'estimateType'))" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "Joints Position|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" + System { + Name "Get Estimate" + Location [653, 318, 2086, 1271] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "1000" + Block { + BlockType S-Function + Name "S-Function" + SID "1672" + Ports [0, 1] + Position [125, 39, 185, 71] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'GetEstimate',robotName,localName,wbiFile,wbiList,estimateType" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Estimate" + SID "1673" + Position [210, 48, 240, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Estimate" + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Block { + BlockType SubSystem + Name "Get Limits" + SID "1690" + Ports [0, 2] + Position [475, 211, 570, 249] + ZOrder 68 + BackgroundColor "[0.513700, 0.851000, 0.670600]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + MaskType "Get Estimate" + MaskDescription "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of f" + "reedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParameter" + "s:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports open" + "ed by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underl" + "ying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interfa" + "ce\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + MaskPromptString "Limits Type|Robot Port Name|Model Name|WBI filename|WBI list name" + MaskStyleString "popup(Position),edit,edit,edit,edit" + MaskVariables "limitsType=&1;robotName=@2;localName=@3;wbiFile=@4;wbiList=@5;" + MaskTunableValueString "on,off,off,off,off" + MaskCallbackString "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param" + "(gcb,'limitsType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, " + "0.6706, 1.0]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, " + "1.0000, 1.0]');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.87" + "06, 0.1333, 1.0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765" + ", 0.6039, 1.0]');\nend\nclear maskStr||||" + MaskEnableString "on,on,on,on,on" + MaskVisibilityString "on,on,on,on,on" + MaskToolTipString "on,on,on,on,on" + MaskDisplay "disp(get_param(gcb,'limitsType'))\nport_label('output',1,'Min')\nport_label('output',2,'Max')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "Position|WBT_robotName|WBT_modelName|WBT_wbiFilename|WBT_wbiList" + MaskTabNameString "Block parameters,WBI parameters,WBI parameters,WBI parameters,WBI parameters" + System { + Name "Get Limits" + Location [0, 23, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "411" + Block { + BlockType S-Function + Name "S-Function" + SID "1691" + Ports [0, 2] + Position [115, 33, 175, 102] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'GetLimits',robotName,localName,wbiFile,wbiList,limitsType" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Outport + Name "Min" + SID "1692" + Position [220, 43, 250, 57] + ZOrder 25 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Max" + SID "1693" + Position [220, 78, 250, 92] + ZOrder 26 + Port "2" + IconDisplay "Port number" + } + Line { + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Min" + DstPort 1 + } + Line { + SrcBlock "S-Function" + SrcPort 2 + DstBlock "Max" + DstPort 1 + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + } + RTWSystemCode "Auto" + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + FunctionWithSeparateData off + Opaque off + MaskHideContents off + } + Annotation { + SID "1213" + Name "WHOLE BODY TOOLBOX" + Position [244, 157] + ForegroundColor "white" + BackgroundColor "black" + FontName "Sans Serif" + FontSize 12 + } + Annotation { + SID "1214" + Name "Copyright 2013-2016 iCub Facility Department, Istituto Italiano di Tecnologia\nThis software was s" + "upported by the FP7 EU Project CoDyCO (No. 600716 ICT 2011.2.1 Cognitive Systems and Robotics (b))\nhttp://www.c" + "odyco.eu" + Position [241, 194] + ForegroundColor "white" + BackgroundColor "black" + FontSize 5 + } + } +} +#Finite State Machines +# +# Stateflow 80000010 +# +# +Stateflow { + machine { + id 1 + name "WBToolboxLibrary" + created "06-Feb-2014 11:51:26" + isLibrary 1 + sfVersion 76014001.0004 + firstTarget 26 + } + chart { + id 2 + machine 1 + name "Utilities/holder\n/MATLAB Function" + windowPosition [1152 -205 -179 985] + viewLimits [0 156.75 0 153.75] + screen [1 1 3046 1050 1.25] + treeNode [0 3 0 0] + viewObj 2 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 9 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 1 + disableImplicitCasting 1 + eml { + name "fcn" + } + firstData 4 + firstTransition 8 + firstJunction 7 + } + state { + id 3 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 2 + treeNode [2 0 0 0] + superState SUBCHART + subviewer 2 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function s0 = fcn(s, ~)\npersistent state\n%#codegen\n\nif isempty(state)\n state = s;\nend\n\n" + "s0 = state;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 4 + ssIdNumber 7 + name "s" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [2 0 5] + } + data { + id 5 + ssIdNumber 8 + name "s0" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + linkNode [2 4 6] + } + data { + id 6 + ssIdNumber 9 + name "unused" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [2 5 0] + } + junction { + id 7 + position [23.5747 49.5747 7] + chart 2 + subviewer 2 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [2 0 0] + } + transition { + id 8 + labelString "{eML_blk_kernel();}" + labelPosition [76.125 85.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 7 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 2 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 2 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [2 0 0] + } + instance { + id 9 + machine 1 + name "Utilities/holder\n/MATLAB Function" + chart 2 + } + chart { + id 10 + machine 1 + name "Utilities/DampPinv/Damped Pseudo Inverse" + windowPosition [699 -205 167 985] + viewLimits [0 156.75 0 153.75] + screen [1 1 3046 1050 1.25] + treeNode [0 11 0 0] + viewObj 10 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 6 + disableImplicitCasting 1 + eml { + name "fcn" + } + firstData 12 + firstTransition 16 + firstJunction 15 + } + state { + id 11 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 10 + treeNode [10 0 0 0] + superState SUBCHART + subviewer 10 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function DPinv = fcn(mat,sigma)\n% Economody size svd of mat\n[U,S,V] = svd(mat,'econ');\n% Damp" + "ed version of S with sigma\nS(S>sigma)=S(S>sigma)./((S(S>sigma)).^2+sigma^2);\n% Damped pseudoinverse\nDPinv = V" + "*pinv(S)*U';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 12 + ssIdNumber 4 + name "mat" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [10 0 13] + } + data { + id 13 + ssIdNumber 5 + name "DPinv" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + linkNode [10 12 14] + } + data { + id 14 + ssIdNumber 8 + name "sigma" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [10 13 0] + } + junction { + id 15 + position [23.5747 49.5747 7] + chart 10 + subviewer 10 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [10 0 0] + } + transition { + id 16 + labelString "{eML_blk_kernel();}" + labelPosition [80.125 91.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 15 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 10 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 10 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [10 0 0] + } + instance { + id 17 + machine 1 + name "Utilities/DampPinv/Damped Pseudo Inverse" + chart 10 + } + chart { + id 18 + machine 1 + name "Utilities/TruncPinv/Truncated PseudoInverse" + windowPosition [649 -205 167 985] + viewLimits [0 156.75 0 153.75] + screen [1 1 3046 1050 1.25] + treeNode [0 19 0 0] + viewObj 18 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 7 + disableImplicitCasting 1 + eml { + name "fcn" + } + firstData 20 + firstTransition 24 + firstJunction 23 + } + state { + id 19 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 18 + treeNode [18 0 0 0] + superState SUBCHART + subviewer 18 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function TPinv = fcn(mat,tol)\n%#codegen\n[U,S,V] = svd(mat,'econ');\n% Setting to zero value\n%" + " Setting to 1/S(i,i) singular values greater than tol\n S(S>tol)=1./S(S>tol);\n TPinv = V*pinv(S)*U';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 20 + ssIdNumber 4 + name "mat" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [18 0 21] + } + data { + id 21 + ssIdNumber 5 + name "TPinv" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + linkNode [18 20 22] + } + data { + id 22 + ssIdNumber 8 + name "tol" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + linkNode [18 21 0] + } + junction { + id 23 + position [23.5747 49.5747 7] + chart 18 + subviewer 18 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [18 0 0] + } + transition { + id 24 + labelString "{eML_blk_kernel();}" + labelPosition [80.125 91.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 23 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 18 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 18 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [18 0 0] + } + instance { + id 25 + machine 1 + name "Utilities/TruncPinv/Truncated PseudoInverse" + chart 18 + } + target { + id 26 + machine 1 + name "sfun" + description "Default Simulink S-Function Target." + linkNode [1 0 0] + } +} diff --git a/toolbox/WBToolboxLibrary.slx b/toolbox/WBToolboxLibrary.slx new file mode 100644 index 0000000000000000000000000000000000000000..63ee8648630abdd844422f49136f288b536344ed GIT binary patch literal 536459 zcmaI6Q;aT5w1(N(ZQHhcw{6?TZrir;wQbwBZQHhO%zq{`lR24WE-IDOP32whN>#0= zmVz|sA5>N!L9PR8)9Gxvp zoao(ctbLT`<$@SdztI-l%qN{QgX=}6b6SQd#SXRAZ#2-f7F>3R98sAoOoIG#Z zTiNw;CI+|z*@VWy3V;RiC2E+69>F|i)qik3Mwrs;g(Nldz+oR!B&RCFY2f6wRP(BV z4x7amM7p%{x|>yl>-W7V)1kCNtjDt#$QrLzPumQ?B9Hxrg-Y7~Ofs2bxrX|(auqb1 zjEGNO0K9{7K}Gs3hl$TpyBPdlR=N;C3d#I}W^Pj7rcE)1(e6RBRKKHfKzq?HC|AdV9ntpRGCMTLXF?{A_j@XIJ=N z<~S5|S&#f@iuiv9;r+kOv2pwV+G7$sX$$ffR@9Gdq6bBQwt^bP^{R|oiocH(9Yyv) z#KC=PHxVontE1`I$-8!k*AS7N_6p_Mal5)mpkdsjGv%ukR~oD4$_O0NV=Yx zYsZHAO<8F~iMPQV|3DAE`Glc(4IVR~6Vj!vl*!RdSq19~5}qim&PvVe+NJlW1lJQKj91i4f6lL0EoIfo7g&8*xCM1qUz4{!v``V{+ZLa zc(H{6kHUtg;Pq0twOWS^Xeru+{OM-Rx#LKmI#QiB6u&R%>vqF-Ob;M5^WN+%4c&b1 zS`XR_uNj`_UbrI%pI=JOjz(~X@-0C0GK}}dwK_A*ijk^6A0w8Itk3kp)WEh|4mRzh zD7Q($ukNreYB`{VRFBo$((JXgKeaJ2R0s7zC{GtzKvCM#gs4_r- zu>RBLWMSiCZDDK0U}$Y;WMyn&VCHCG^FMN~eZ1T@ITCJve^7aL&iQ7d3eV`)vtRJ} zxo@mSdr}tLxw{)Vn;<2x6pBKNzRoxsbHCMq_izXWFObOQbJm+^_cbX|q097DyT4~o z%ZquDSDEoXPq)RYdn%E<&M-@Oe>~i7V)b6#ejm+GubYh!FBkARZ&Y6M%U-m*Cgx*G zy1SVObhdr^XYW?4U-WVla@`<4NdC%EbW|ev9OOKfxW)3p>JcEwF)-}*w978U8Yj&`zy-aV^#E|xBzt=DnVimb3nwMXk4i)Urz{p!Z* zP39l)ldz*3hUsl@Z%^2KcX$I4v`Dm%wETMbIy)HY98ETkBG!!j8oZXwM?&2n?;x-~ zHmWbDG_p|+3oUSF62nk;m)CAn%>=G=ua_2hW94_VX6P1wbhtSqQ_ZR)HjMv+6mQ=+d+~8jm`-geSNRzy{Mn0dBFrw=A8_A3ZBqEBE}- zrnx_@tAAEL#2c!oqA2xq+8C)0N=lcJVqBhkXopUpK( zIYfRHnVoB=D{<-&<78r=h@E5f8J%Wy6KCSm(&A%OeUY0A;Suaru_s&QKXYO9yVK** z{H76SSJ2VRDXw6L&uHK}o#m_dVdyNymTf8Ls@C(w7_Ru;b|}FhOvhti6e?V~9IM!l z62rd-%U-eCR_k21U_rR})~nsMy|LP!BA2T+dAMEDFOA`48eQ$Ejs#H3)rcv9Kq{n!_u{5^NS;pUI|&V8uJ z5`3IUzPaHCf4=L&di!v0@mjKN(XN(j-Hm?|ru7{F|7Ni?kWYP?BU9FR9aQU0J$t#% z#0~5=;bAB~00K8f!aXbpg0G*1=1EvF%{G6YX=;QRj33Eus?` zWrOHPQDV^1H_IrsO`Wp>gbt||V_UTq_&W4xhlhBYD$M4$k7=IBNVeTUl4CUOfEj|O z5Ys=OrVT406@{}(SmT^@I%_P!{U_yVoEgu2KjEV0o#MEZ)J$^Jv$`|)lvxw1g7-kY zwMSCJn%Yjj-e2iRjz(ud zt6f9pnT-HNQPrNrSrb5k#RJOMB><#|;i?rZ;WBX*ygE-tc2sE^~@tj~7UD?x2J#5D)j5dWzJ}oUe zr9r1Sy$`0qG=AqGl(i`u-=5TGwCvtpik-I}w$y+ z;N-D;a7fhI2%z;KTWitm|bD+!2Wb0B*EeC0$UKNiivh?F&4mvI)9Ecc&=1s>|Sx zhJKgyPJ3;-{_=vM9wNqBu&@de+ZN|76nQ7icgN34~VpX26>qyrOYfl)+|^-9@_kuK5Sn^0L{&N%h_3gN|A^V|Q)=ffHcpN3bJ* z_ZOGc_8!uofXB1ii`0+**&egsVW;f3dH(7bZA6u^#26)=gj5-4Fs`-(c zar%eX<6*x6hM1^L6dg(00S@yy8J&i0xlZebQphl2wOS{o_-ZyL=P=O0-ej#l%n9Qt zmSAUc(NVT(t!u{T<$@9q4V77fJM~yY(Dhb<_N$W58DC~QG;(a{@1117>N+3@z(>;B zx05H5P^V_RJ-&@O^p|Wypq=U zy@PwetSqqP<#zM#W^7G9BMH@f^KXEUWcg+uY|H+!g0XOzByM~tpa(M7r6H(@3vO^z0$U3J`xL?p^DEgMWlH4~Zzq>=MVt;a*R2_A4(l2+y+d;l z_?yk?2A492yNpA3=O~-o%-CEG^tw%;M$zSXA!j-Oy!Z2SgXdczx6IyP!(9QWd40yC zM4u9mUIAj_k^j+BCtW#_FJ+;1_-RqQgk!ADeV|ZP?agvgQ ziXQF3qvc7Hi1?RHPK9uL$T<$Jd4~}q&V7aovk3BlUHicwn(Zkcu|{twe|Z#3)K#*Nr2%vRn&j zJAVawi+f%N+{m*Qx2x>5pE1%D;G6m zyw~Hk($Q}|H_wDU@))xTDsTGvAuos;7v|q7Zyt|+!G5LBE7@`pk~~3p z0S+ZAMjfcVFI08k&rruSXBtxd!N?*)v(i3DEfri9=0Rh0>B|sZ3`pJ@nCAd#99M*V zu^2-lm?j{@jIFWnoHx+P^!Y{i8z-=fk~*-D3U}Vtz>ARXocMUYR&PtB$H3xn%E3BV zu&l^0Q+DRfulq#
t-t<+(jwi8pq+#(PA%k!Jn-aW7CF8@Tgpc;H2-wq`SJko)|}dfn{x zdy*Y5 zF}$qdr^+3h!CGmDx_2y0rS4_k-|kUQ@1pj_M7+)6S23qQN?Kv>X|A?{A2$#Ov4YU_ z*H8|!`Z(<~DnV$Ni8>)H38rn$prB^?|CmeN$I{Uq4lPahE!=o;l~mS(4&xKs0h?kX zU?#e4`5z~O_$N=q@vm17ZhkOABf*Vvgp?I$aO+Rrh~f;TC`?~6U@p)K@!32T!bt-; zo@B0bdK-nW9l9+mcm;h+G}}nq97H6eCTwib$W)IyW3)~rh#-+Gqwz^KIqr@{&AHC2 zavPFhRtJUeTT9ha%lF`4^G_80+kk@f2{m{@?K;27W`R{##=Tl;nV-du_fGb5j)x6z znA~`UsD)@__(uefIEE@{%DNtplR!4>*mJ6j{0-eH7iV~jJUnX=PtT!JmApkjMtkNa zVOF>&jYXb8v6)lo&>_QoZ~E3%VMoc~b&^+j zFUiPmm{|#53*Ibym=vfn$HK#N8rj}T_QJ9%83aEtz~NSR1Jtcd#^dN83raRz4ca); zQr{&x)9#*Va-86F-$R~8ENBZ8TI5QmR@emcLDWVzM0 z+q4<(&(^}=Ol0VEvYN9uw&qMC7sOljNw@Gbw?>BevS&W280;8gl2EfKR3+I+xnA_d zVVxe5?0_X9Y1q^G{=|J!Y*gLLH!i(X2^fuH372X|`F7=2UZE!xcDeebTuT`}-X7sM zPl3iVxp13!AbHgD7l!xZzO{(va&o{`!~{z!J(mf?nO$-8VRe|0UG`F zI$2pU_%m$9C^k`>Tq1ELu{<%I`BZ%1lwKzkM&@BAojR1qk4}%>F2SSTGwbOUaGC}9g~ke z?N_lU4(jaFPCsurLw`=h0W#+Iz1m+v#iBA#Mr}49ZR~Sl|%F6P8m$J8^sy}=oyK+Mnlv@IP8Fw{|m(eV0pULh{L%@MrxbJH6_gTHy? ze#yOVP*Y1BFMBj#oP#+hhZP?Cj|0OHUN`l^XrXRD;dPSM0*a7+b>ojw(01M}5PAg+ zsASlC6lA@Qp8gyTJ=p=gq^66%b!>QOdD0jW!fLecrH8Vb z7xE=Re&m%H5%!Oazd#p(YbUS<#O%-aOgHxOLi(bbf#h>x+BGNx!#w;uz#h2+Muqow5$P=yjJD&$LlS!uhm)x_y^2s$`z>UBaKewbqr4dW zAP2xu-=MjNhVCTO(=q8SnykD^bH^*@MXAkeu{vNyeTA!3vN?skpuWLVYvhT2z@N0I zs#G#5Y{)onrLHXP(9}HFPMz9|@Tlf5Ja_w7(O})M199v*?!&E+i{3jy2^IF}*T6NP zs>+w69Wm-8B|XMjlun@5z=K0Y`)~}|)S8JTHrD0<3KVGDuU9uZTmq|Dn4h8KzW#5P z^-aP|b4bd=G{3(I6N#`!rj~%6O+CvFkK($fWKHhqG}>@kW$k?YROl}S{Kq=U*5MJ^S3crq0x7_P zK--7~X9qUD5dfV=nWc0!JzW?juFb%vI&JpWli0D9sXXFP>V!~Kk876K^}129V~r6G zHRfbG2y!|oN%Rk7^IrE-B_Ef!bS^DVfz5r0xg#`-Qv@J@CgUS#1UW+%^Va>En%tLk}pEW48HY3!Qc=2Zc81Pt90Gk@PD1Oxb#uJYrEmuNbvy;YH zWVNdEW5ugC3s%9+@N;8`UT*Ml+Yb(1B6zgGeVoN-&YcBOk}MVV|# zy@(>e<8ra0P#`0e3BTfobBKB9jZ8;Ph%`1cbaHM128!fGEqS7xx&u%ygi(Gu>?u zTQW2B>^^~I_Gh3brG(9%q92SNMy8; z{E93|#9%ZR8SY)WTKtQeiI1N@Bu2ZBkIU()5@?qD|&B8O(wD#K#|r|6WvY(3Qq*4rx0H`A~f z>kdwawUgoDlaskBN$FDdFBQw3l-eZuL}hYR{w1jfFi#**DD|keh~vO*UQel=yvq1J!T z8WyBp{Dpj-zFodRYm9&_`v{LEHnf(ma8#oEk1{g--6$gSRF_$bLZv8HY$#pgc3s1K z)1A2*Dv|w=uJK6J?ny+KTc)h<-P#U&PW4o@3qK&6M?Xd^^stA+dQvd9)Re}WB3A=QIX zC}{QRxmyXR>^p=H$^=3v*~j?-uF4;?YhYi`^vqFs@ZBISyJ6z%n(jN3N+LN!fh~37 zVpi9%+aAauBofVx9eqv#S+k<-;U4sPw?wW&wR3a|!O84K)tqDxDVQB@(yoo0$%U~$ zP~7_{w&C+={b^2;#+{X}8>q^Qe)|C;&k^e=^d#TMgzuk@@9fu6Y?XY{DBt^H>4pl% zFa=T*FkBtu{Q!ljV2F0A*g>GD!A{RWMx84yZt9JEn>JaN%B|f^^W^JBSbzJ0f*?Nx zRam}?z$))GK^G@)nU&Y*EktT`bnoU8%!Zk?gl8@ zQtzxHQ!EeAQNv;=TeEi;*0qJ8S44x^o$|i0S8FgNpKvYzFf1;dx)^K9Wjt#xfhp80 zJ^e)l|24MPU(!xei&`~tLqiu&F7QWVK+x0`zlOGV^E2qknI)DMM^*O}7Dy;Gbr!pm z3@!LUbMq0aRLU{FC{ootpfQ70H~5-*gz9jw{89PZ5zLo*@Apb%J>VPSkY3K5pqkbj zVCN7fn(`VT111mJ$i9z$mf#kV2KZ;Fl62u69V)>?{qlB?IlcaDW&48x3e^WoH0BX5iwrSpjK zb$~St64WLD5~Lu47hD9QgTPXOl8*&F_RnqGXa3df+ftDnf^N4h?Pm&sls&!nldN*R z6q5&PmgF#*DE4Iz9yaLa;m3oXP@Pdp;A_-I7B0hhISam<_8~4)uO6iv0FO8RTAaz0 zMm+nIY$5FyD#gBvhz=#;?&_r=L3By^=II$wxaXx-2>OWFO4VQ7@4dB@m*A7jQ7>Vo z!SbiJL67f_2Cx1#5swXgLP8nD9%$QY*Bp!;?7BiSP@3N^bTd=Oo*7*ZRUx$;R0YYpv4WTO+@X2EomR0(h_Q+Cx6rQUPtad=9<-6?uA>42+7)D~rC=dZb$gpHK zh0WvoN@wjUw%0KYlI|cWmX)~2@$~3@sbu#~`TlL{;iaILVK5BhU(KYpO53{Cd{fKH~ufYmnqHF8( z680gVNr)H*RjL;jPC46hxOB-Ryt>ic()$&B6&ZZjw{ zefjEHEi51CLwCE#@0fv;*sstUPU}QxnitB%!&Q}@2$XTb#A9`9S27wzN`>}oj(zpQ zFazLrhN5OcH?8!ob9VNF#L#bQvTJXbXxPe|kFSqJL2kjK0gQx-jF&>4JrpFE5&CI_ z!=DG=?{4ndP%yk6gO&N}+##*Chm)qFO-hqR_4<*X{nK4q|C^EY2u*}hhjeUQ(c=`j zO@a$g=VbGcbqIi?)u?Gj;uGkIxy4=mLOD#+9z{1th^i7clxD-ibwEubpy6SK8$_-- z#W;wc*7nRe@jvPAg;2d);|6p1!rB!hc-lXG5}H82rki$S*o`Hl@TrU7?Da{+JJN>r zq{e&o*C2UGiO;mcWFB2)bZpoT0<$&!;6GhJc5})Mm2xxJ`{Xuk>&OZ-M+z%eNFe_h zxwG$rb+b%h9gZdA+2`S*H2gEE6oyO-T})ND^tlFV)_oClHR9ef7wY)5{$%j_u`J{UvGd3-jD{heynH04FEG%Q3l z=vGNJ5HQU0tdY|i3~R8!QEKE1f${u}Lu*Aos3-$uAPUbtxLc!S!!BG`(8*1=`&@969P4Jw4_>DTHCk#)1#qCh3 zF7UTTQ&OD>x-2vLi2y*09f%AbxQ4m0@IiVM6ptr$71I;RosLv4STd$W%vyHgw^CDF4!{GKEFO^gvp zlDNPr0BCQMIG(gEj-TGzdX+Nev1%uh2KM1I&f*6_voXn-m z=5rVdCG?Pg@y%aQ$2X0Xa`QB^n8kgOq#yousk%E(n(AjwW9B@XCXF@rFK02o4Pc#0 zqE6l6_=CB{k`E=AGXhqWrM1TXVOmGl1eNK!+OiLCpWsI|_e#Zxww-8wOp);TwVGIn zwT-;9`ePJb$%RFXF06Nd{nL2&;1HtuT96Z+LTUyMJJ@rvZveQHzC~~M@qT2HV+kst zs`=XPOA{{oJvQxWTbk!6C+c#x;7<{(ZRVKIJ!v9mnC3SM`~tz@{f@v?8WV;~+_w=9 zY!b+FCMmBVc)Q+BQ%b=IbL#0tkLdBeXwVKJun1%%iKBvs4KI0_h1PEJ^!V9tO%w3Q zk-Xytp)15^{a3MQ8kmMm_)8psF@z==2pqpgNM)caQeiWyn=6mB1$Tv%xc&&eW*zdmfjm@Os-& z&j0ph{g@(Shh>DuO?esaC7_FDS`mvMlcU6~aOd)cY6lOyqT8(wMGs6ZN$5ZjVerKkfU%k_24 z_(;GjCu`hYQ+0lW@LtU?GRD~(PG;!F)1Q*d`7$2}5rGuv8A&Pzf8)9*8Xg&|ut>nv)BWsN z%9FdGew!}u>US-ms;k+V69joe_<#QAU-ly|reWO*Ku|^X6hmc!>+_PqzrDJZe)sNc z@9{E&E6)c~zg>Rg3$AzbeBc(qQytmbZ+~q5x(p6WyO5-7vPi9Wa0;Yx=T*50uJ!!V z?1}+cF_*6R`W`8svrTVFsGlpow!J4Iv-L>4!!(^F${|p0ctfAR-ZF}jmJx)4Zvx~| zxx3z}@cey~ZKQ{?fGtMBOn&mZv_&pAlzaZW&Rj~k6U|$aI2$xvIeqo_^FsAPEj1v& z$X##bHQUrp-^%qe9KL*TG{~2vJr1lZ*LbNdgugQ;A$#Gh_>rFG?hz|IL3_~`cCCF! zZr`7YHd-emCnK$S6P0!mm};*4urx?dju*<0V#3&ZvUk<$+cnpS8++QfdwW#A+O&J; z;>cMop?w)MD@DoVA(S{V5+}O6;$AHCL2MA4I8D6_I^Qy7OLT~FSWeP_j5;VW*;_n{ zI)=t_F+I1!0+YpeDE`hxvxseRtK zrY)qhei6wZfXk)KUV9Q+s$4?u(@wkaZQB=}Zxrcl2TdIAj!L|Nc6D?Nf7s5V4D+-h z>?t2CHk~a+Ff=w&YE{gxFpDYmV@Vf}C}iVY7JkVOQ(bl9|GYdSql3N65%7QKnRm!#At~Y!3z0DuYFC@bDw% z)&Mg`+Le+fDxj1A0&EB-EOkzVgz-&{dUb1X%;t(SeyyJFG!R@bnZdE*u~OPUxm ztw^D^C7kE5iSkSBJcS)g>U&DDDJphLhEyXo#$nVH?J1aSwJ5#Wy-^ll9dTg9yArx; z5b;5-Qlh&&yVZ`I{H{;T%pFLz5-y!oJ*HQC%s3#T-nsP+OdJFpxX2g+=LTcFOZvKK ztFKi%puv5eAIijAPB%Lxx-_r%C<`yWD$*V{0nO^ajex;8gwJA3kPK)-O6RiDu(}sj z=8N_%Ugpynlv$YV6Jepv93@ z8ptp?%qA}yA)Y4%GhGc=jLfMSeo@~7oe8%ci?4E4-7Zyzuem9eS}u@w2>E+1O;J z%v{4~Ed#ia-yIHlbhy3E{AgzG%THYgjFuj7v#8NpyN%*r2cTlgnR(SKhsFje)Abc8 zOn4LkANmiNBa`n>-~L8^uhzfsO8LczS^E9rh{b|NOjnHH`369axA<)YL=uf>Rv44e zd0mJmDw9MnECme=JH^`ly2xw96PlP=<8TW{p4FglS~JhTmr#i?$7WL>xV1_tBzu=* z;cq4flMm}Jnkj6Aa}Jep?&w!a%_o@?}Mvzqf`lZ0vOM!wgbHN~oGI!Gmy;R;td*BNo=JF|~t0@2Ve;_dzH< z3f3>Zbk)Z68BR_@L+W?~tL3vV1GA-#G^Dw%KVkd@WAqwiI-6y^&{v}BHLc9)tr0r- zxhp(Y1`E7sG1B)Yj>Jb=SOma{fM^{v5BW=kj5KW3kLbZUhGxxXu7SrKvFqBRC0>^w zq?}VvWY9NiY8Ny!Bq?MagyrzF%bX(Wcgs1mckJk+c-45;su^kjcttoA+XJq6$YSNY z-ZdGYHt2ewBrejm~!-GE~^+%W-3N?iXK!komwkIs5YqmmTxFT za7I+5W!(T`^7Mx0m?ToS4q4L77hb28^fT z2jsA}7O=Hrdnsldk%d2H>2SJJTH%Fu_>gnennBtz6lid{;h64DMc)klB9dRn4~OI5 z6ssQgWmYB!0cVN`IaTI~fWZApg)dEsB^H-rbqg+9Ot$DTuX(Q zg&{1lmAT<2gEj0ioySx|xmA-#Y+L-k(j(p*ek#>-_n{@G7l@C$^E4szKeQ#wJ&eWI z1cMVR?lN>R;n)zs=(D^2*kMyvFd904@lqoKkYtyuL(eylhLzr6&nqY1{3a}h2&SF z2DZ^Z)vB>-34MQ%ND!20bkN)UmmNL@Y^+Vr>w*Fo`Ir6I+K|RS8vRu(x?s&DoA;P? zJNMFUJ?t*_ZOcXamLyd}T%kgI9R>ivoHT?wWhrXJI?nKF#hUKQnpvjD@hWH*BWQ0@ zsFAt%sut*-&UA9k%|u{tE~QM%Wd#j{>qVez&NOPBK|U#ZJp-}_11;=zIr=61_$P$eA7i!UN9*WuIM)JZ0>$w)*_JD!vA4T*N|s?7&v zrV6TwN7F}qjTkPd^j%x$m2EKn3*)Pr$KDFMZU1%JG?0>FsZ@C!O{s*o&P=rgR^YTK zwv7zrAJ3ZnHF50EAI}1)hNjdu(s3}}?^p5E;WkV7{Nr4mJrE4$*1|u?n`28|?N!=k znq99jdp6zdu93wNnNs;oZp&@bi=0h_=Z!Wo(p|B1%?wQZDT!UKruZICLD#Y;PDW@fn7?ag(Gb;~X2 zS%ig+D>dU;(o*4)H;+u2);vZ@j)&(@Q^|;~x@y(*GtzD>e;1o}_1Pd_vtq+|)m~pk z=e;aB08A0%B+)l`!e6`&32H4jX`)!nHSe=$)-khn?8m$bg$K>%T!9(rGVtbRtf69slXWJD zW?#}05(^glFk2sN!Vm@x+%!7#fbexIryF-=$*jZhNxkbI(n&%_B*C?J zTK~9z6X9WykAhA_>FZx<`Bs0@cF0~gwutrF`Vz+eDew347<>0lv2DV4%l{a9mRf@0 zyMFWfQ9#nscY{18(N3VQ6dDSiq>waWX=-evu^a`^l2_9uO&vrRIY`GRcvxvbBi5cn zpl$esm)ervB%Ga-d8GI_rGO!Ev=@ej)56y$ioW6^SoYGA#L|ilx8FPui8{ zD9U3i4MV4pSd(LXJA2%10&k@fElg0d<0OI2ST+<je4Ni-L{!|3;?S`Hc6Aj5(W zxtD89EqZ{b9fZR2MYl*SuK?NBANo$#%bE2M)(YIOd36Gp*(fS%o(;GG^m~B45gB6;^Bi(%shgq%^<(t*R@NvtmROz5U&!| zxeGzJmVr?aONuu?0Z?`A(X&D;AU=`PWWF!*`AS2kE(jAH@d~7cjXgcQc=ToFS8v&6 zNObF+q1BY=M)I6%BKvqz83YWJm)*UPw!$vpjQWWt3}wq;>x02-`6fi!RcuWGbV4Qo z$YgF1H@c5ACinUMEKHu!-Vhg9}WkP;ub8`++s6?>_90Ci8_Cz29<`a+ZfS@ z8?z|nnX@QP5T$$$K@lOI7oPB7d3mxJW96jo(+JLEZbW}-HgYVS7PDR>+MoE+4*z~3 zR!SQ%gwv(B&w#odY(pX90XsD1+gj1*Qz9Wyz~CuHg`cldw`q?A;zt6;qFD=4m@8@J zGBy(PhE{V}R2#?=ykrh|F#2R|*M){Ln0xz?iAP ztz6rRt7@4U95`Bhdv&kym9fKjqygIGei=TJ7S}(H93{-l|A{eoe~wu{txfc>H6a?H zeRZz~cJ@{wA{fT#=-7)#d&qDtP(lS{^O2A3`+456M;V&U)>mU(V|>d$>=AOz7#)ES z!7!x(%!)W9?uLV_-48eiTqOly=iz9)$j(yPA=H|(PsWbWB#vFuls>JT%;luwB3wPK z4ga>9jx^bYwmt5&G2RLtEcvDKsgx2eqEbbnG_XKF;3akpOQz)LTT znS2q)vZqgXF&{*Vrj$y=G}!Lw{Wfd}YB|VSryB2c8eB@GY_-nF@;`#vXUi78M`HEJ zibSl=*2_)_+%&n}31jI8jp~Zxx6(q|HM-)jc$I;HzPE&3_~?0E^gDzDf6gvC+Q_BH z@mz7FN23K#;%3jd#cJtf@^M!trHAm!gQz9j3agdU{5vT_o(R`&;E;Nxno_ynj6u1v zO1D&J{;0=+SVN`nL6ct;-bcx+7Qv5~c=nZUl+nyK6NYK)8D1qLi_kun_fA!dpM*L| z22I4p$q5YwY)}!BSb!e;T>|;Al(B0mF2|J_jvksTH|Q+%*5`55;aFCKK<9SW94^Gg z7^GZm@JiqzJh?0VpLl1ms^^CrWhj|DE6;2m?;h7`#uNwY6sIlpsMYxvd7J+w#>dPO zo`21JFLB=woud=^83KdI=?Y($U{@b6*Sz1RN#fxo%e$#aBa}RqHlYyiAMsSoYTl@8 zTZ!eV;DZJ8{3q(LzFw`Z6vJF!pqBV#5Zs66ucc!?5a)E zq}#ozO+s`^q-BbAgjCr7%GzrZH+5t|;_U-yiG+lyz#4V_<3L(w#$0~zD3Oc3O@9`h znL9e|i63xN+EH)vR~7^Pv}7|TmB?}((gJxdHL|ECyF-j6wWX11KCLT4^qZ71X2!FYF+K*;|8B0-4%k)WaN<{Ubch9Vl=SlUZw6X0dk^Hvr}x@F+` zt3m0!ueBzvj#1vrt18AO)D$gq{5tDtxtpF4; zCaO3#Vr4TpE4o-avYZjY7c#V%rJ-9c~(*-J*DFcGb(T z=i=n<6*4$1QAhveISj=+!+`SPkBRsVxl7^CdNF1jX5~^o^qz#$s4Tk5>9GVwJ+&WO zmDI|*)1_eft8>Myg!$y33lIIfwUS41;+QWHY2{>zEwQ}|ue>H?iv^JgB*ivx1!$~< z5h4xurFRM=uSW$9p|T92UH*Z9vmQJU!5U)LHN3h#OEHQi(TIe=MQ@5FN)CPFv+G-q zH5)eY-RIp)L^o1mz* z*NYKqO(9K_7amyX`1>lsouK6Y(x7_-x@*k&jjC|dZuKa|3jH|@;@1dRTI3W6OE1f$ z7(?rVC>Ky+vWu?2?PMHlE4;SSofy_%p#=?y3DAHE&1|5$f=HUMi>S!dF#HepIIa|0 z=wi&Zw0&Bq1WyV~SiwuF zcu}=4dQPPklF@?Vr~FW8%GgiAGEj5so(idLELg$(kR4J3zb)ogr;HdVVwSFFF{B%P z{(8j;R`b5*Zgc9GcRSZgG5Li%#Zr*2R=M27{w8MFK)K1`rDopEfc)35N&?p= z0%4_p!*Q9;d0US8?nI{*VWPD9GotxxB0i|slJ%Dsnb>M2o?X%Bw}Ry%&^lzdRt&$k zxkDmx(&e8`t3N854I)(VB^+sse1o2@Qwyf!(v-BM2Z<^N>2gHSToZNB1n|$!v z2D7T8zCv-6#tGKR&~(E(Vl?^8{7a60ZnQ?S7A? z^uN{h>gVC?2fYCRw2c}uR-k(#S2!ZJP{lpm+fhj1>l&kwBP5D7B&i+LY-bQWm(^ZR zA0@qy>HwNRfktTdc42R~8YR1btl2Acjs?3DLH~_JLBOpcsW5dk0_%^U7mG_9_v0JE zjZVVx-;KTweu#QuTWc9`R`Q!^5{LN^;f`n3RfIpCe+fcieN6c>z@btVjfr&Zv8WCz zLN3E$HdOUSL4L>o;r)J?Ca&Jku+;$g*LgeYa19(gnyWmZeV`#U+xCc+OHsWxAnQsC zvZ4-Db$DNz%v+weYPz9Hw^W{S?1+1Mw@0Z8Pum`d$XvrUI*;^-$uWjHp#xbSqT&uO zcXQhE3gjH^@ZKr6+DyaaR1vitCD;+g7xdEuB#bOgP2o}ewy#h>Kpq25|IM3#>ci6O z5GubLo^l2kmCk9y)wBy(-vzi%I+&PI=}B$+RQGhxnN!nes;j2!d8iP~7Yi$dx|VG?c(!WE(&qXaNP4>qZT{6QA!_wS zY7M2eMU&64AKUxo#(+T8>~fPt+0FIGfkArbgRNe^KryaMfMYILChjI}#ug&59i1f;B1YkbaVBLxf{0% zbA6{7IR=F;3DA+)y)k_qe{zq&{e8aWbx#)mFiHEbk{ED5tI}*M_7+!r^m#XoXG%2= z?Z|5Xb$L=mjpsgzGPUR~@go!A*AVCY`@Z~B@r^I+VD|m_7^xt36PT*&G%YMIx?HR3A$2z@C-t*xnXQ`k%~S+` zvTpKxX9x0KX=m4arKDq}IHp5B$kJILPh>(zsWlR&CJM?C$Ha29L)rOWLI&jgldcFD z%`Wv*em{?IAC~GAC^?kSKMi$ORrC)|y@du5J?q{omwZ*=;MVcdaL|fwlTJLuFYb!$ zzDOz7JI#bPeR8*^TltOrRH``OuqZ1w?F1TR(?&{$yf{!+lIDv^2-K}SMJgTLlEYsH zceL3J(9D!whQf8?3&=cy=_>!uF4I+_5(l&U8zwX}*G#U{8)m+Lk%ft)az~rN`v*Wu z%!!zENEzgo(^riV;IYn#1S>?HD@68F4%u^h>nRz20N*v!o}5MSqR4b~@xtyvduI1* zI$4)I67cuVhX(O`&m&_?G%8clN;%1$eVNw|@PT;feV6Mv;2&npGXt}DmvKt00}?D2 z9=K7B`2QQ9kHmlZX9RFx1nth3qkst^5cMBHdVdJZ$mzdYSN?C1UXE4n?n-%aY9Y|w zNPF;qqVzD?0s;^n(0j?(l7tBvR+%vP27R0`*~ayC109)(nI8%-oNj=Zfw$6y%$FB8 zPK{ijt~M`Ufv~54eWPLG-d5ZgYc-1nc5O_u{iOUNQo9QU=uH!jC^;NXn#wxklUN+F z6Vv!EN+o-DOeAYqtgA7z2c%aCmwzucFrKHKTmr>dAH24nP8!#z<&gU5(B8nJ9?BH30 z9-EDk!tP5L&rAN{Dcp}UBSI|kzrd>!eJ(+*-iR|(DyrXmbnIR&ka(b0ZoNVsdC7;h zw69p$Os#GH)&4KvWlT?YUkLrNMfL*CW_1%)nr%Ca9_fX>a?{w6s%RGA;4!@?hmwGD$cKS?u zSn%0c-tEQzdn&@zpOckKT_m+w?bi1O8+!plf z#RR?!Wdu>vCaE*zmM51nzw-SmQ=Bci;C)}vfylVO7g3CUl<&nE@A&{Vccb7RybP4z za#9_~G;`Qrq*=TaIf+#hnyU@Y*G#8o&k^uuQGKb? zv&@3vw0KA5WG%_!hA_{7v%?i$iDu!KRLr|w$SchLMD79CSTTO1cUX^_jK|mIW@03d z6G%&yQas> zsoQwiWbKn&Sdk1oFr7*eFJrqL=>*`LzM7lh(TGOS#=q^TlLkC($gvaV$t%MW29Mrk zazt$+*Fir>S8{R`?j=X6rLS)J_GFYhyuxxL7LQ|bk}dI9J}Z@fJ(t~+pXu>i%KY&- zNG@UNIvcVO3aErL0@EWhVT-%5g@~!y-p`4Qy;zXx+6pC^n?(%(| zySLILuDFZxK9eJQcudYw@FGK*A>tqLyuZXW)^mcy^*kNNcIHnt#^p-bap5i#Yw3#6 zDY>AsY2WOo4=bZbD4Le?Iel{;a6v$3|69;8m;8{i`d~))N92AUo38oWahyORi2BsZ zZHWV>sp@Yqsz$JnpbAq1=^FFeOkj5HL-%_m-HEz zDOqA~KnV?he9+aQ?GkT=WI(EUnNuVqLWL={w~R)v*fgoo9Z`Qa)y#wrF9b5WnLJoH zuvF~FpDVKQwK2OSPRBb{GoqehwOz#>rqIGg~pv1hEl{Wx2)Sl-eFf9u{mI zgWsmy5hd@VDUH=fOq~VHhtIW(t#H$tYN0UXzT{%k+|~t1EAdzx$HN&a&ezi(C4)WC zL^~T@b4UdKu4Pj+{o5myD6`qh=yJ0>ifYrodj>6AXAlPVw_^zE5X&x!7B-M zp_Jv(*|T7x2QiMp!3HT@KHbK9N5ZTZ1T2TbSeF&xqk79I3eDx{5|E6-ZzLV~F|ky| zDgs-e?JBUD4uYXTJ&>I;AK;C+&R$zbn%G(D3J0x;igGRbkp5*+W+kLp8Z3Efh7+dZ z5DS6oCv40^&ACjN%27aV zO{RA#hH6jXj8H_PexOm?y;=kA|&w zw(5v0s)1oNeJmrh>3SQ8j(jrHik?S}lA0iDR$3KT3`PB=+UiJ@86U~U*gAJUk4Dcs z=(r#;(HvxFKp>-we1NhA?OV+0FUA3_PiIA&0b^~ZMD^lyj}kuCGej40(#4~iO6IqL z(fAL?+JQOpqWI-UL@{=NGp}!BP8&M@sqs!4I~OuXR@b66uD-W3M;ae7IdoT~4T;UU z56vVP(Jl#!SO3}j$?dp~lrQZ9VX}IXNqM*BK;d5-A3*cbxgA?3K^j6Ipwx*JMALxF zwWWtr*2VW~AddvD=4zn#y6^B;aAkVrhuGbM0x~P5hKtug;?@reQjxR_$F+9fYk1DB0m5!TBvu?{(pMFk$%w&WoUrNCxL3@t$2$I}wC@xLb zF%FV^FT)lMm3=)!H!KbQ+_A1djhj*zq2@7_`TXES#cP;Tk1kO6D;$qRkV?Jn2!~s% zC@n4q>B#L`eP6_bpwy=&eM83s7lqq7Z}DGa4)Ttr28Zc&5W?_8H`fo!UrNhJQ8vF6 zM<=RdafXD&Fu9}(s(8mk+dk#)wH7clha=DuH75lFAUArr4xrx(*b z;kIt9s$*JKytX`oH@fd|9yiE&M6yl^jL-O-%9?XG)>U8h9=I=nnf-yI!=nQWxS_NR z6@v`K0I}k0r{j|t(wc!SQ+%;x(H%O5)yR^_zT@@1IC~1tI{d>*`pNy}z zgxtEU3mTjoh>o=V(T*VPd^tL|++{geNp6^Oyjew*H>xasd7X~-r5aYbsntE>ZYQ{nLn?y;M_N=5xs*LClOQx2p#r&Uaf3Ip6BwNomlYytS zBPn<2AZV8BZd+!&H}x7Pmvxj>%}uqy1u2^L6?i<*Z=w`%#;}A_TAd$!cQ5CsyUUPe z+xqNz4NK8LUDG1-jh6&mH(~L$cdMBTI`Nf@g`Wl4DAhGjo5{wqmb z%UYN&tUt!inn{_bZA5bVIBer2Z_^}QpF!to7h(&;+a}#mj+N5^Ij%KwG}FLB(ipS? zFN+xE(B$M^Yab?`L~jx$AH!@C7n1`Sumb$2(&e}Bg-mLfB*alx>W6-ptkbDFC^01c zJID8MS0&jcg9&MIj z->r2FR>lWMP5r{3*|1|*Bg6fDL4!9~8S z{@(|G+43cJ3n*lw^k=I$g+43`_YEA%Gw5JZHtpq7gd}tlkM8ACy2vx=es}yQG50*> zjgom^$AP*;CiS&OiU7J15bdsDY1kVh-c%TL#7GbXcg1`%!#WZ45&RrkDbUYeSfUrx z84OA+64sR)w3%wjPPQw(8(TB zE7=DyC%UUn_wI4B*c~KFG}B^G6{}ZX)uDGgWz7)A{rzhhWJQ;FC%b>dh&SPsBM7NV zji(~`mzp7JAdKzrKgfg(fH)<*K_HcQ_h#hGk(y-uZCxRaX*BQo^7f5VZwcqz0L;fe z;jES-ro6wxqvC$&Hxnm4pxLU&Xhz#>@NOApK%O%=0pcRN2!_>R2f5Z$aS51zpX~KQOY?c@Sslbj@n*b(&62@|w2LWYs!pX(1eA>?tovwi zwVH1=Y&Wh0&NnRMNScyVAVdL&Zfyn_#$lX|x~EAbaaNRC3(9;xa<= z=_o;9Ap*n9cKX4X1U_2E&sJ`6)RB82j4tyJBt28<)k3Be`^uj%m5I$srl^)TWd@`^e8`UXEo?ZvqRX4`$P`QaGKmR{S z@u%AxuC?`s2My7d6{wukM=teZN@fh`v1JsqX6a;n*(}PCJVjyBy1>U%g?*lFeYYOs zad*WG>z-3{C}pEu)Wrni@I(Wj8Y=_G9SIsXOsZ zBa|oM#&PGV?6Gm}T5){J!|j)%65BH)4ceQGpm|YVX;Pue^DB~k%?v5(=?Sq*qE7AR zctPQVSej4wp0bV71NhWYW(T3Wgvv^Gmldr@qT%~F!83fG!fm1EsTI2_6--5#6#Pl5 zc;a;`6iDHq-V=xV=abEvOGOT^rva;<^Xv%t&BhWQ|Fx&r##`qE=u52RMq_HkQ<84|XZSK&}^Q zCC&0(c}&-lRL<4~_F+JDFovySK-M~7h6UgENPhTIn@84Ag54WP`Auk}gt6)gkpA;g z+|UW}PJ(^M{ofpTFRjSE0`!cBkOrvalUWL^gW*_YiP^4+d%p`@TNVG&quIj-ZwT*o z<5KBbTp_EqDE_IM)?RCI~(Fl_+5KRmrK|_W&atxC?hiafbM5!(|ZrU=H zMJZI{hA7+x#<7M1oF(;>m9K`hrWH-~k}+>9LZvhgk$L;374;teo*~Foku3x=-Plh6 zNo3uzAeWoYn#~N7*{9Jh4zD7%P2yn)uhctIVv0U0Fgz^6eA34OA3y{&7Z@h_@o7zu z8uh~q_c=~A^6t>3+9kz_M>fduAvQPKw!{-Yw+&3J-O-+8h)exmU|_Vroz$h+IV|DU zquDw9i%74rIm+1FcA&#>YX3V-LtO9Vy)0$CH-wRe28yw*hGB65QIYW%7Z5yr?Pzt1 zHN%$vM{cQ?+JqOb8YSwGh&dE%^ui zn5-ilr<{13#|ggEa;aE%XRiowmd5-I*>*^Xuw=uhRwl1&F|K9DZ|w>#b^qw;yE%r|%K&Dy=*qH45X6#{DjEbp~6@LZ`vO70HdOCAu zgP%6B@!X*g3?CuZQ;O3b_b)8RGG5g16)b9mFw#c%o!0O%EUthe(<)3_*JpR5CTX}k z)$r-Ynx79 z30a&5F-RBQR&Y{$KYH)!&7f{-wiFI&J9dZ9>O2sGuh;d&x^p(}GBk{@gr0j!DxWe| zjIWTNdon!V#xabaw)wNafggq}A3JW#S5iGNsJox>M%GuR@dTXd{H8?W zpHG&?kF6hBC$i1t(>+$saWLpX1is8mXtUPog1^T*t@s5Wbi1JLMu@Dl2rg$-A86&q zIXaW4(>Ij21XJ>*O^x%{c-w5CI0d980tOa_rgIfgftU@c(h90-)0o2nYCauIM;;_x zFgKtWd>Xiw@)yTU{o#)*H|c)+v@O#d{CRq6G*08FbM3lH?LDhQt^R&`D-fi~|77AY z%)x*EdxkWqU#AP>eWbZ)rBSaUmu{BKw{I-$3?5FVcv!NFZ1GFr(UVWcsFb#8k5QPds&;Ge3?HHX<;o1TBuUMW29W+QE3&}fc|{mrjGAej;}#NOJUzb_{g z6y_>rJnZj~pN1G2y}Dlx*HRI*+-K`cQv&KwoY`6eN#EsCwRSCG+jJWLLADRO>m}`c zzz7l&g9jdQJ$|+s@q}8M^UrNbN_0`QT;|jAW00$#%0z(!)1D%hUh;&^4BbCfw$$hS z8L}fUb~3mQC>6GO_7Q-U%A6=Z3g4I{w_mlp!UOZ^Lunu6j_c^Xc%4fP?ZqrgrN*;7x>2)Q zZuPBM9dZZ{87y8(*_58-zSP=*nk8SvC!ATYmU6v6B7zVnl6M_aH5 z2G|~p2@29nr;ysZ%)q@D8u%Y);i1VPp{&{`n=l(cqqL|xqR1|M zW|}_1HL@sq$$%iCg|YrbRd^oa!_5jdF|>9OsD6I7&Q6beZv z;Zk*hX@=6!K6e%PA2as78|-})UZCRNVbkkh@gq*Q@3Y-r3QGWi z?N3rH%I3WxuKQmVb>pkvYx>QEFB;8AyU7Fk&3i%M@NWHoNB(5j=NR^FqCXPI;`_t^ zJ)(yJ=g(CFDaGLB%3vJ=$@`+8+hKc%tJ*9dWq4aV?x1WoXfc8yP?qT5`Jl9@U=yW9 zhpM<{UHI#8T!@uz75uINwO^}ZglX97r*CzX>HBNqIAM-I;J3_du7oe(dW1Cahm;|c z9y_XncV9UJRV?K5eb~g`wY6SQ=3uu7ctb|>&W!Ba!`L5!;@=H6wATwbZ8!9iWuqM;{!7j=JuRoN zI%r3$;k?YZDjEd==4Kh1Uz-JZtyB_PU&Z-&nNQa!N-=BrtstGGn4#+@b&2%%zmrEt zE(=H?oW@k+hPpQkh+8d3Z*bt>>?1=qW!X#{yPsvfb~tbvv)5;w~7HuQQ5-_r>S!Pw{ytPj@j_P zZ7oB7%xEYuK)?u>#INmGki)n0hFdei7A;)qb2`LL@}9-3y~93W7fE;bCdtzI}U@iPyd^q$2g zO}7n9Bjl`(6*gX2YRBF36fi=0L*7#klBrLyz|ESgRK_x4 z^i=*vsY121fpVvdJ?YotBqOSCQV`h?r89aKQQ0|T?QHeIC zhvJ`yQ^X@ufy9wI-!Uo)Zq)WFBKkAYM6GPf^B&B2LFr7C6CSnGrMC9FJo~iDH(4j9 ztlaa~(T%Qk#C9JXP@Q-5(I&bnCcQnC=sq%-UarXV)-+<<92kk^?=hTvhBiw_GW$1M zIgp)q;tDQdW{(|>n6{AYm?QmfJhNF0A0Ujk{n*%AZK&(osOoeoF5i1!N}X58TWZa8 zkv+0ml)~b1?Bt`J#s<)LD{+ClFcaxV-11kHpro>h3}aF2dT@5Y!3Qr>pY=}vppiUc z2&op6mF)g03n5wxygqJcaD25VUkS#dqeQ5r?uPL)BY^kE!W^wuW>EF^>2Jm<&MsTN zn9Y+$qKKCdMk%k{#ZDrVYn_o=U_81Yo`Am%4t}S}5*9Q~c7_3l(Ccyw0&##C(1^jp zhwIT88q43jMW1dmd?g=9df1zo?*9oX`F{oO(SDSWh4g42$M;N0{xvYdeAsiNb%&te z5jl>L{n_8i9mAqGry>T8C><|(<#NHBD-$~mcO&gp!9qKazJuKo!=fXBt@U-pJ>Eoa zUQ%5+xvXSFpZd4DQu+#+h!Gyl%A;|6H}6?Ipdg{D^B-(ZO%(cR@Uy1$zve z7=HP``8wc^pZiW&3c8tv3PSh8V zwaOkEDVJ&Gf;KN=#+>0}kGs*T0utEsb$s~(lLD4WXTeNOsE^6z{V60V5v56Y3X5H zQ0eDiSbtmmPYc9xqrIY+hYiU+S=f3(G{8x|zq><5j=Gx{V!#}RtEgoHx(@XFXelZO#7(5KO4F{RNJ zd)4{C6*K*7KYq}%ji#?O8Lh^0HnW7K5R^Op<4?+cmMmqg!DOD=>A%1Fe~)3gNNvQO ztIW;!g8%t(F;1X^a_AXUP)b#zW|W4HTvQX&Fw<(M%K0fgj~B_?`|SA2$*ZO=e;c}) z0Ps2gx?gVm87-x-VZFL7yvR z7>P~vZ=e=eJ|d|mo-CHo`Soa6ubHzXuNsm87e^{R2{Vf$*SD>7y?*FApNQ_9gJb4m z(?U3?o7Yr*A#}jB!``Q*KRwuWM^G>NDWZVlC$4S0!Xy132VSpT6k0K-5wTuD7Hx6f!5Av2QblsvmVt-Z(cl< zNT%nS<^HaN0I$TAsYcNgUbYdfs?$Gecn}?($ZlAk@O}Aj zE6M=r`*CP2bJ2uuZ%P{d~u;qGqYOeH;7#q?WA~#un@*7u zp{poz4nu!M=0GB&yC?dvQ-t0BzzPS9Gl$3wV={!$PYyZJ1yIwqIt(ojFYQ51(EsrP zQv!$E!y)O3D5HTa!<=hDo2r?d=rPDF-8-bW} zR{+9-GZhjoIK7QYFjNe5z%CJVb6W_}P$BNq7v5gP0rZr@h}6W~6Zu@h>Q-zc5##Cs z8-IdzROfiIX>j~m%dQ9vERbBtOHz8p>HAjI`d5w&FMNo7Zh0mM(^ZAf&e> zs!!z9&p?M?k6i6b?g^<o)?qDZ`qZ2nw;m_u=zbgDAolmav)$f_Z&TGOq zPXx-e5=D!hc5y7OU=-zhL&u5t0GYJ#|D1^4XE2JCjCY=4d({juisoiw8Jp^fqJ47u zK4tvb-X|gt8)v%`IP2q)qPuyIk6R(;PEUZtQ5LH6mO|}RL2)0C<{%?ST8zWQ4Y(!j zt;~M+#hXQGlS{M&TY7OK!6y$ET?AM(;R+`@vbzlXD{m9m|K?O<6Sgn}!h07Fa$t{c zuVD7|zJ+_n(gDd*a+LH1pN+C%Z8-&x%YsUtI}BIP{DJqbGyq9f;?n!#&ZuF50x#XT zcsL`V3RHxdH#-Uz-_R@?7b*l(KFZUAC@fU7h{f!vD+}}tKpX5 z!2KN~n-eTSxU;33Z9~av0Vv+u+0@P6{OlRj4EEX>#uCdWklf<$4tdc|uoPQlvc6bu zzK)U0lyUtQkV=MqNXNPfgpf~jcoM7o#m6>wZ zW9evmS`#ZV-0gbyRwD3%e>J~CuhNP?#nkM{(&Ue2qOy}O&N+kqrqC|aM7dSC3K54B z&kWdaDb4onl|fzdRLE{jUBI=w=~7u}fAT0`5=(gyV*+~`$^6*ZZ>oD;lS z%<+SsdM42CT2FudzPz2vEG;cvpJmn$k&m84Piq9GbDtglTMP;HnGihxKAhgDHRzPB z8xskOourCba~+WK@eJQApu27)-B_3nK>Xi)I-Y3$^BoXCKqPEHKp6i&pN_MOk&BtR zt%KWt$#ir)9o8k006V$HM=G?ZW8+WMMb(r=fwtl;NZpi?F-^U6(RS2= z8-(aUMq=DF(1ECCs^-wzkccuHs7Nvk8~JAI&Fe^Fyd=Zz>MIUo8Fz0rRTl9Sms;E3 z)hAMqwlTQ->DeCXeW}%#wmSZL;bT#%N5TN0k(WwG>%C7QQe6Txzrj%KSHc-U+{lgh zB5V@kEOGbaV~>Mi1wu`1_K*zo*7}96;hAC>F|Nb5z$j8_>>ib|o${=l`7*S9@-);A zT$p7Bt#gSWk-_SDpYU+s12${YtJkqLD`Co^n0JU*p07O!#Qm!YRn=C2wlwhZDuYp| z(4S)OvRa|Gn`hyWW!up5&fUxNKsmVb1HmZTX_1`R1;Ht$84y*)N_i7n6y)4q(|Hu5 zDT#7U;OKj<)?6^Pry48Qmp=U0u3Dz8HK4_JOT5D=76dG*-s~oNkSmM-O5?_Ku6Z?b zKdJ99;c5iFn_Z2|)|qpcnzOA}dy8%sVvhP}57|O}IXa3jk=nxJuVzi*vk4d38wt-$ zBXDPNBWnEeXC|;~(~p_G0prOXyp#nQu*_K~Lmg-pzQ?zL!Vi4iq>xPIb+L!woOR1j z920jDUp>w@qz&+rpFe{x3H%%}&8a^@0rk$GP--@%=}Z&JEk&)jew=aTs}tih?HhVA zkfVU*^_aU^gbdMQ#T`q6o=fO$K57ml3$g;U`*7dz$}ueST`32n%>yZGWqpPEOhiAX zYc&GV1Np}ptkE;O2}?PP4#oxnHL#XN$NH(CLJOUx5B#d?S3?h_OO(sIWdYTMeD|5s z{D>h6_GhF&?K-$MFP>I?10y>2L-ty73WiWsOgYAH`Wr3DaFXBnlfhx6Y4R#eb`7Im zomhMI@SsR@h%~mXe(mgOs?U9@>gqh}V;k?LYX08ari~95W3up`Ygx^S&N*FdkszE^ zvV`C(f|UVcYTE3e!ir-W^7v!h9!_lam|tf26vJuy!5&bx#N`KX1S+TdoQ%^Nbjulh zvO#|;Kbn+qY?6xGS{GU*F%trMgRJEQda>nNyY%{C6#gM>d-XSaTpue@_c-|3Xiq4COTTxiE~o)RK$hVljyw zjjCAUBc9!(lQMPg$Br4vv&0yBs*EQvoCNI`jE(7Ott-h{u&%$=v`tkgC$px8ri$)=eR|>7+-XQoYh#VO)Wx;=*9(`! zRm9&ivztB3KG&{`jgDw+frrcmq;x=MO@AP%Q-X`A@YKw3dhu@K?bQe7Bh8b2=|WlN z)Wz^F=Xy)pl)Z%owvFe2_a4F_@q;)!LKqc3h-j8hqdQ_-s~3>n?0}<@XWki$EEGYQ z#GykY3@JWz384*NmfH+z%M)W9UnZjHcVUT!Iw`;#I2-|*EwpX1nnfcGR#*(G6 zp`UgZ%e{v4;ga02nXI>!<966D0gCWlVtDRJB7|piJ?pGlOv6!HV;`dMk{Z2Env&Ku zof&r*A)b1d28`6CGbe6A(16^Dd@Nnol!VrM-sfmQL0j`VtCR-Kl!jPS23)r%eL-k= zwEGP5nAc60tkoXlRKFymUmzwV!6kLH%Iz+*cH|8rfn~5rFX%$4G?z!O#ASIby5B9~UEpTpAYxPh z#1JA%O3FT@0F=OLL^W3IH`uFxTQnik%veZ{5f>6I6OoY;L>OeZ;0|bON~7PLyBY_} zDU=y-2`cQ!Jtzqr#itP~VO;rO&QCfcKF@1TwGq$E_Yy!0A;(rw4M70Z}SO-L>VD zy5#SV>Ns@jEjcq236i?o<`vQcZ@W|X$c9c1lNAbjfE)+@YtdkgRWYdSuQBgLtIz|c zjb*!iDqB4*gs$rc#{X^ZE`CQHF#qrZrh@_jq5haV9T5ln9}YYh166lNGiSa3*t%ww zvHvgvekD_Bu%WJtsHwr>wd3g^Jc3qXv!ce!g|EFo{qYl~u3!^8pL^cGqb(d8#;Na5 zYjR8Oqz+ZitMo3^(;0hNlljdkM&byMbyJt1BdaVsT)4(zh$8D+o`A3PSCM83Ut6*m z@$`q3U=HLrwhnrpzF_3JD_5sVvs+LM%s7q{uSY*O9entRw}6a>@AF= z-|T-~?OCq?&OE&)zJX(sY!YuniL-Efj`g>!LNT`uI5j9w`(&@p=9Jn@&r7cV1k?BOP0Q| zy{%f`sKYtj2}k%g9SdsFy=f)JKL=?gCl*Op3I^XQoKaG6^E7ekpMcZ{rMPS;_JT#F z#c=FUMpPn@pUe=aYAh_afwe_y;@?_EY`UB;H5U4WW9;!B!o7>nHagDRWAW_(iSL$> zTxPjt|G4g_nzXo!8->1vB_s%j;oCTwPI2TJ3IMHJupXySv@vskA)2 zztQ|0)WY!zNfEqSerGV5 z$!HPB+z^=dK^|IBqaO9xvsVFy!pmH#a5oEe;5Et=j}VlD+!O2WIPNlr>|tLUtkN*f>+wG-uk zOH>D|a1AZ|AoQsHd6Ff>!^<1tY{AX$W2(1Z>**FC`91=44(~DcIBl)Fzke9)`G$PI zr#g+F6l91OQJ4Ee2nyjr7mQH@;$Fz9rNsgd;uQ#nc<^Yk=R8qDb#E z)do5_mtJ3AwX+6!J-tZx-=To_RJSOrj}L=PZ-Z}KsGO6x8OryW2kk&8FrnRzw;sOx zotpgYcfe90lib3tK==EK?^o(OquMVxU%&;M!jS=>;p$>D)fZsHQREJ|Ap|@-GCbm=-S|em+&sL^G=6OO^4<=+87x>;9{>6LFc@($*tqEF1%Pz{zVE&bcKW`f z?o;<~eA%~WeCKwkzC9lx9vFEZZ{QzOPkg)D4bpEO-dh_gwj+Hrp;?_t+vY6YwvI-8^4Uz)o7+qAvk5#W%DMq@U5H zZ_{n=7TLFi%r^j2;JoJ>z~2jquL8I=kH&Zd3@nFMuaDjdUjTPjmOIDjqX3K1JwUMX zm+wwsPnXO$ZWLfG)K&K4UZ5zI;^*C((YHE%B~P|=?)_Ql$_99A0hT$x2x>JFjrQ%n zEl+)ImK%QNQ>2RmU_;;?G`0L2V0xyGvMSI_xa_1LnRuS=Zcu{BCal<_k^Im-hBPwh zFmZ8;DX$(Bh?4IPhz&mFV zw2{0<1Or!81n(#HnN#p!@ifsOYr80J_`M>z~Q+XE}CcDv}E9oDfBWhdfzs=87x|@~Zl_3BDXGq@3gageHYJ(GLjgEKQgJho)XI*3<#ZBkMD zn9Zgltgcnzz49H)&3f%(1^c4ceGoS=jy0TY%f?wLm^oA2bNhQr#L5zV7c&LJamn6W zc2=U1Q;Xn4(?8i!pZU0n$Q&w;mthFrm(vfMum+4A(b?PJ$y-mMgcdM%f0Gb)Ih zh1IraW;`nE(wW4}NINd2N(o*7fimneM>fXVtR?@vODRja+;{30qQ@YzhSIGOZW)S4 z?BxiiUal99KkHz(uG*)fj5}NU%t<4yJ7PMFgk#^D>ftD*RP2|JIQR7-kAnD`(B!=v zku%S=WPo+aB_4jCQXK?J*@2#Xk0YVvmR_xQ`5GDKcuj#Wv63(+$t;Xh_X0lyL zTEc>$t;_U>)7<8QCqzwK>@D%_6zN8?a(L@=we?7tLD}tPlzlB8v)>PdrGIMT?#wzOl939#;?&j%bdA3uS2oM}4YU%pipP^}SAyjL`O2&^< z*C>xL@TT@!@}IVIs^|QvRCZS1@m~Mgz;jtbb44~2t5mw~GNs`_mrWQU?_PQsi2Xr2 zGoqANGl@Y2kuCx=)maQPu%>)Z&(UfLaSI{;g@{%#FdJ=on*MjWw6_Da;`6w`96HT- zho5eieqn(w(Gj+~plXny^>w2Xx8$oB40?p!(t|I$fCc%EdjBX;26M(v^?+@aP>BZ=U3 z?1pQU$BD_4)?I0`!X0dYI8t}rjAa~1KTK=OUy-}^G&W=qnT$c`_E+FidP?721*c4WJ^s4&_#P@5t;M05G|jpxrs!&zj5KjwtSquq(Y-egeuUa-`+xiTk3zkcIr_ z2AEfia*T*!Y+ofg$lRk_nK#in+c%Xx>*|%d-!-KffP5YEUS}EKch5%m;O+F-4ihn( zyTc=5EUegHh9KBih%Cz$A!H~Kj>;oPGI-s1 zhxKZsb@GF?8zuRKn#dS;E%uzh)P#Th;ZxK%(-$!IYh zJ)sj;Oj1NZSu9ifJ?s-BF;57+vNhlINr{?LNB5uOGeH?^iFF+K@FiU38Ca~H>9ru1 zq)_j@AkEwy3`CegbDC)AjtP%zU8wOcaeW_;dlrdu{!F7*fC zPL)P8yOEk{7Qxg*hzjJNBF-&u$0FwIjhBNp>v!DngQkRnGno(-qUPC-VRY>qCRf{| z%6VozD&lcbyW(?3iWNnEmt}B7D?e*~^8GR-C5jdDf+lAf$hyS;0xi^@kEh~IIW}_6 zU(r8XB{JDtWw7WO4+N`6|5tUbhEUYD6|-R=0;2oTaE~*2@&FnLmI4B0`L@~IYMd9I z_PQ)>@vllpbUzekTBjgsBNPn7LAUo#u_32nzbUwc3EihzFyVr{6-1G&7_PuDpS-eu zXW@5Q7Q2wT41h^A4O~1iC&AoCO z2Y4q|ZPi9u>#sG0(i&|pxON))CZD&y;Q3ex$>sc0DAohxE7h(`FHn_=Q~OsYg0F(} zdcu4pZcQqeR+A~)`0z8FzVt? zLZ`xX$7di?OL0}YRY)jWOVnPL%f;F|sxwXE~!5M$ywqdn%2&J33Q=E)xusa$+ zm2q&(GNIcv^CXFQtYIstgHSi8GhEaF(=k3pv6Xs>+;dq*mx+ThqQ)h?fl43n;W~fYYk?@9%p6|c|#UVz1~`D5ib0*RVpsZ~gFYq|DH|CJ6D2U3wRM zd`Feo&iBg-@g0`W=p~?wZXYhnk@iE@t5{Lv)gC0?Sp&B zxG;{$2Lu+dUL6vIDo)BrlLJLzv&&?;>1iw>!&S{tR|A-O8P+9lxT76&f% z)zFFQ71IuX>_}Q>6wHj5<0QP*3l^w3Ot!nJ&}MmZ6cF?~-@%jlS<(|A_O`dt$0+#f zrX`vpZ=68alZ9=w6o17N5%e6wi6t}NGK|a5_7mCgrU}30iM)o2TMXBYx5<6&K2QX+ zAOWL>sifkhW_JvO(3lS*9?e6ZX(WiNI|14xB!yD_T|@`d!TS+aeg#Z-8)s1a_AxW&!JHClr3W3~ zGm3u#Q`X4p>8nP=`FMCeqiSPyHiCOAq+b4eu+jb!4u_yo1nD22)i(4J#g71At`VhC zJUtMKVzVCOjBnLIuOHqDqho>=Jjty9{b94`{G$gLoNL^t2QpY>HC(5^80;fwD)s)d z+?f4Vpw}{AnCad>`9fvL>6D-KO6ct`FA%nLEhfLl2`T#92;x;cdDTc(t}ZG5THiQ^ z?D5{jW9}K0{8GhsFufmf#r~ua=)o2GC#g<|#{^BGs_!N(*K?vvT+=dUQw*W^KHX=_ zFrf92vj)=pm9>VwzJkHB(hB{;QvET!MfAeci{9(O zCU*_9a209MiefO7cm;I0MMO}$fYcDDcUBqC)pArf9Q0Ogxvd|IL8j|fH3f9<26W9P zQ9N3WX+b;SxG1ahm-OI=Rq7^J8RTVw?nf!I%DwJ~U1r#?*L3gv8T#2Qz$fYU7>K

1!FGPFt%dtY)#YOkPIyvZr&ny5>6*Az zcY3|GGJ)!RP*xgR`$6GqmeU3)lJ{gd7g<&1VWQx zI7+&36SEqhSQ3Rqz2hq3mFqAXH{kQ7(}wWMopIPL5ZU#qjVPhH>FcM5*XCTQ zBF7!kgt&EAn_EL9pg}ydHHgKhsxz}m;0lIwrlFEq%Zqq9Sw#JPr`yUV|3merPZc(15E|nC&ur`6$Ko~Er(wmp5kqqE{dO) zUEI=|IO*1-Ot!_2g|0DUz`!VeUk`rw5s*JrMTleIUd;lzGEXhut{Qd8z)M~BYj4ht zRF_C@f>~n#4-UloMBq z^=EH^At>a~xlAfxU%%65Y#R^7V)xqpvp+u$&z8-Od<0FX-WAqKgqen>!}y?m7~w+h z*|t_SkS^4O6WdPPze=|YE*xV0y=38sUe5AQEwZ{5f9upQc5A}KaBFEhc1|;&LbJDS z&KR)!pKoCtHyNH$Sx#&{@4E^ttr)6Eiou~e`CL~%8Lyq0N#w4e_&%FF7w2qL{E}g< zuhHFc?%n!{CGb6ynSFZVJS`$Jj~^^0a_&bm8M1B+>o#(gy^=bXXz&+yPlb^U-If`Z zpX8I_Kp3Lw!QWINZmQO=<_`?LPb3)Dx08O@oMT^X1rC10(7Er%NAb2OlG~;&i0?n7 zB6S*?V0-o)=#4697spiw9~96kKF8okeVe5Y>F1X4;Cj8CET2@x-o<@>5?#}07qTEj zXsfAJk=JnR)$Lw0L?{&i=a<;wRW}Nxdq9t7@pDz_7u+F(*eP-?fF8((sE6Q5=f1KM zoVirNnZTJXwTAqi+xYSge`6WRni+vp)kRusY1`IlSRM!{QPj9NeEyLoVeqQx9F_Z zRe-Vh3b}aGcE}k5h8S60;w~); z)*=-RxXT3oa%Aw?lea7rcNbrW{_^9?Qb0^2*6Rz zb&SJteEG8kq!AUUs-d9Gkcga^k7!7EDMJ`GJEFuM`lFKwDex7&# zvq8hyeefrU;$&Lu)-Sv#rN0ivRk){XNrn#dXihI-%KHdp zb^cT3Fjk_89yV8OOvfHT!dq2#fy=9KW~e%e==I4F%)}=+$z^#hKzkvuy>|$q8urY6 zXu1a~5WhqmRAzCd9@#`l`~}+<3x$(C{R0Mp!YP3wtyZ{&*c=gpN{j1Vm3o=e{9!Qe z1iEsuF~|v`|E%YxjxbT=Uu2CGC#q9eCPr7dbf{4t;im{jy{P7@WPW-CKQG;rveR*_ zZan5s^Z{0kdID3jBRO18%5 zEQY1Q{^>7a2w>xL(KPTy7;Ilg{0kw!E*bJvyv5UMUoy`T>#Xu^mE5Flhn;sfLT&Bb_fW8WHdzb_WC9oUGPr*EG7fu^v4$@8n^V` zdNt!Gw^^uFR=h(1MdP;JZ>f$_V@SUD<%3Kf-T(WFQ=*fuMHBkH9QYfOx(#GJ>s{z;~9MP}5_^ZUuc6GJSu3 zk341RC|*aI8Ae*yY~ij6>__Q+j8@R@k&mBevf{Y-6E_9<>r*UFf-B~AG<#zVHf%zU z_0XegnO0J~X|q8r{!15jyRIxP`q2ss0axp@;Q*!ep+zw&|HY4I)sr=4^2KQobpga% zL8yM|0pv*rWzKcw$VUljo(qRj2O)_kuAmm+R+ZXMLM6XY>417ncc?AFrG*#rRcZ#( z9863AjhO}43Fz3a`CN-m6lgI6Lak0p@37z-_w>1R5&3{4gUJU?edZV2JF(Z{Or&_`HMsDzP<5l(c?nhd5xSTyS9zqoj21m|b~Q?UJ5T z*(ct)8&B9)XNU^ePVr-YvK<6gzkSJhAtw_A8@(@kGnX^Plnt^y_a9gzyAiM&tP$$u zQmD?2U%)KHB>fR^ANXv}kl*6K8NtT7gm?NgW$A4xH@qvp4)KdeW%5Kj`9PSwh*PFF zjPPqX9B_%FL>M^u;0OjZH1(6Y)eGj&j#Qj+Dc5@P#1BVO4e7fY4T`gY&83-GQ9AY z?B4N8kH%_^e+mX~%co_ZQ7`+cfPOvx`_VA?ibVodo4l3NI$o~cl_RCSwZA-3c!0ke zY(LLhNiT!nuXSeBvivADsox~WDCKV!5qf@IScZ?rr#w=sxH5O)#+JFwDh7qMdl1r? zVbNK<@Tx}a&Q--)ha0HUJBd5cbT^KtTze3!I4wozVKX*DEqL>-KffS~x#}MCIoOje z9hCPF1HmG6JyY5K@Yx>Rd_AeIDjLZf7k`6!aIEtPxU0D(7xhXTqP_<0Im9qBGpaIg z?Ubtg{aWp2xLr;0Ncj+yR`45kqq7m_!S7W4<7N|>VMMJV?J1?Bz8Ca8t z!dXZk=@s#vcMn&Nacxl|;g3iif|ICFzK8}wet&h};4`murMc!*gZ_>xw)N|cY_G`` zTcziT;kzPbW}AauaoSbO(H?w#``=bd-VMGzn&-Y!<&;Z1(-U(Rv!Nw7cmDhgREYZS z`w<5Vw3ZDyMZcufAqxiHv)WSe)MKqpy`}+-aWaNzDfF3y-n(%b14K!C3S>&w=uBT? zMz81hMa2fD1LZ1DgsR`8mrUHB-vc}2bp!ZU)CpWKJ{YNg#w7-bFUR{}nQz%dZ(YnP zK!ju|te7E^N(r@FnHs`{OBzR%w96eQnb;qo^&Mk=>>kH=8^S*%Pio3jxmw`G*^hoo z5FoT|f&>?ljahsC%CpAnvhkS4p()#<%@@T=4BsMft^O!#O8HG6UHA?S8uxDXdX?a} z7Wd~lK*gBvTp!a0wSNFjqt!3<{RIF#uwKcc zpexZU|6V8%w$zZfI%g~o764G0O-6uHxB`M(23Pdp@SmRj+{u|~GLa%2@|01AJa4cd zKDJ#3H%}nljqCxaFm0dX;RsE9OFUeCQ)@^ACLGDdj7*JfK?3LcU!jEu*$%<*$ugwrl_!-iXV=Xn@VssLZe&PDtt9Ehsytc zCW_>Ta+kGlloE7eKUvBj4rRUiiE}yhBfwl&U4=TNoxqOEEAHjgzo7Y>Kj7StIAwjQ z&-W=Xh`=W{cfsdSz=xpaB1Ce+reC%~e z2K~rE3Y>#E+pF2!yS@bSde|8@H&wwNtBPZKr_Z0WkGua+ znzwU^=R*#m?>(vV2-eP=mU-%=E+?#_-oQCiE_{4_f=Kfez(?Xy=Oa9O^h3%$;xy`( zw}F21NPdC0a{@|%-h;ffGGh(Prw?SO{h%?Gi3e^;TVt#O0{>h?mx-02GI(;{L zKaPLI;bz@a{E;6XZ^4PZ*GwM?=AdQG57C-+612NA_UZ_`5el7zBhD8V3a}*kr0%#Yk%1ethdA2R{lTw> zX)cPx#6sZqn_85SG@i8piswQh;iZq<-=;xcHXeT4rSVbb7ke+}Sz@`?O4q|Zl z5>yUsbr?+_O=)wZ_?gz{^bp%51U!e)iA?JIKB6pPSp$4atGODa!jg~FxBh-37YB9W zkY!dB6+^w0aGmYdt8c=h;%%cihwJNV#53nzGU)wQM6IuqOTvt(mJ*IOnV&{8IFpv8 z6wq7q>57?biQO*7Vn(xFzHVV-W7)z~&@)5Srw-nGP-j2@tJU?i-O@RXLpD@?6%_Xq zeDM70!9VCeE3+Hh4-)u&^G)+qd98ULo;MB}XHA_5pupc5^Nq$!5GE1GZf9U>9!Bao z=^a4VV@@J_Z-q>7uQ`sV6}6Gm4Z`9~R;R%EzW#0K7x>ph9yvha6#|_6 z*>IbYJnrhg@ec$BzS&R~GV~%|GQDkXKXTy0Uym|Rr-GPADI2z|%TMYRhMB99c|zGs z9Ok=D(FcRg@4HWD5vD~vc$imna_`WyLi52?z6{Rn9vdbGFzgCFE>2Fqy`RyzcL}Jt zXHX~s^3v=%2c9RPq>REz6F$OkvG3e^UH3|1$-%QCK0j0&+@h8m#Xrv6#ElIEfRgg0 z$I==c1+t+_N6)R|Gnmk-O3zt#T#oZgXM-J_2HWS`fklh$P1f`{E7>Viq|`%9StLcY z4=hw4?J1ADF1{BC$Ww^3JH-1nT>o+)hgiof*%GJBW{NFFKkVWy6kqKLw~CKQj)#UJ zE+&-D_{zridV4t&P`NB}c!oYE9I2g$k+@Rz&F!Uv@e6*)%;;aY_lNZnK=8-JO7}$! z-6KXADhb#g9Cbrl$GvX8;@0z8tu`8CnnxtW%`#RAOiRC|fk6E_FyWBPocaA~pgBHk z-3T+h4*3Z(1)8_l=;aKUfnZ$Tr2_@0Yo;5V6$b^(cya3mN42a+<-RiTh=rdBJDs>2zJulQcEu(V zl7_&mocGzMi}W@Ao%`Qim{H-CsNiFwscQK2IBlKiCD^h`17jcl zhrb>G&h4L3RnqHZ)w2cTr6M$me?a@!14H!tOf-oBUhP4sRy6~hdRO9mBYOMg z6$F;msXb%^==E`~20Y%nyMX)j8E*=raj9`+AsR`EbBm~z6OB-zMjwzw!}HH5K4wp- zj&EfRB>#S*;1ADq?TPI@HklKwWrUw#Y76jP6lDK$=-jS;I^=d61 z;^}J~wt9%BGBK^QWEPsT{K+9PnWW24Xm)i7CR!=|#-&j1?+O^e!W=1MAXYSLe)bDN z&eRC3<^xonng(#r?ToYyd@GLl2_@*ex2FHyeH-_-ZVh1BGNBg?tbXXx1vgzQ4P*?8 zSkZr#cdlyy6S8o(eS8{P-5d9QJ z9OBt-0S;i8%@XX5&sS2 zTGE4RBxU$SdIJ%vby(0YdX9Wch0k6^tWhH-(tR}yQW577|7empe9sFNnxDxpP0s>! zr2?TWAV@K4eCF55A5KN8F3mdA9q5x^w>(A1eEs#NCz7G|P9wQnll=@t;cm~IjE)sP zM;bobI4F2Br2drzh;vBPLpf5mE>3JkM9iG5#qdyJ3mI7=2pOWa8JcZo1+6s)ycCAOCgA8G?2p zhxP>?RWf-d8OL2hY`l5Z!Yb@c@0kqMSTW%i3BF!)Q>8eriRGs=OMu;wxB?8fpIf=O zUSH%a5pMP?ph%{ zktV3DMFhHjA7*>+^2L2MUdv}B4N_F*-OOiuDTIt70Ls_YnAKnIo`gCZoXptyYm<(!=hE*K>z20jN0>NO&uHkAy`|Xg5#sAhSjLKK6y>|B|>ek^fqe`Eph zF3@OL1+~bESHUAq7`)*(iUL(sA*E&H*0i??;9|_?iA_7`PO1;_i1{iE#!1WUNqXy? z$@e6nJ;igvQKyaWTncAZIbfOK;BmV{0(rb^+It$4TVgWhgQI`zlb~AIEzC;b(!HBT zRG;_L6UnsU8I4Z>RTrVRSKUh5Kj)* zW+xkfd9BQa{m7>{C{dr@Gbwuh(R%wW=wHiLi+G&Oe4>ey84CA>C1tez;}#z&oRT6+ z0W$2zoHmv|qw`*^DwP`ZpNq5JM`pMTsc1m-!W8cAbggw`KD3${JCv0P*$6L_^TIdX z1R%2RhD(xqRS&H~rfU5d7$0P1m`}kiao>fJn> z{#hem!29f+B|-IG3TA7!s0l;rrWhLf_Xn zrr3d@0D7^!fwIvznz;cY#GKnA_o#8@5ri>W>#?!}!aIz#@I33qXB?m9ys=?i{#C!u zZ-X~^ShjZNH)TLu&j9Q@@9OXU>9bI|_OiloVz9^_8#<&%?)h!gSKZ(D`>3-EVqJqE+x#y2N+?)&mL z#P1ZP2u(f~oyC!X@zX&8I25a&9J>Uq^1r||WT1Y=PG{=7zRt$yvx z|J$Znu-#L}KIwA1YDLrI9*sa}sw<5C30?K;)eg(ZBGVAOTh;&@RJ;VdJo0HU-|+LF zrwEJ-k+ADYz+O=*@7>ACusIdvG@nww zgE~YO!l}ObT3O;PrmP z^(knPUk$3Mtx@cJ0%-2MeoiSsLRc_7Z?jVHm?;h9072=Oyw@|?4*6w%(!;Zg;+Qjv zg1mSzx*SA6oW2`2cs(T1)}6;85r>DX6?~+S$Dm$3J4G@Rh%w&DNOsf)SN-%u zgHR)j#Q2J_CT>1ifS4G8Re!GeDM-a)F&Q2qP0&QLlxcFUGl4IcjNdmVKqf|(0Pb^( z@ZAHOW3Br_-rk=&V|>T;=z*o|o%%hzAG13Wf18>|@EDFoL;3cWWlFyc{e^2{uRJT| zcH!Ocv)k?$W=&uQ$dVAtKG}iOL^R=LwQ$sTpo93&4?5*b`j~bOP(U`$vMmD6I6G7l zs&XvglX-4^6rgX?vTeXQN z{Pg}5FoBOb7p5Vq8X0aGobU^tDAABuj;W}dr`8fpGxD2aCX=#sz1^c(&Dxc%i$XNz z|KjK@wp<0GDEdJRa2o~*?#>K%mjGY?=r_&khNSA&xqBy2%=@uUZrD?M%KI&MuI4A; zrb#2U&V%`**W6RNGx}Vxgtj908fF6*xNG4}E0mUbEavhP@+dFm@fF>J&U`O+BsS-R z#hc(wsqIw-{p&isN?N0=k>&3v><3Tf)Crtrx=JBoSoa88$69?eUM6%${LhFm3lWFD zSoL&-a={3IJsujfk!YD6{`g@YvY+v3v-4TKBq1%`}J93P7uWN3FG$ReTKKt zRq-d=yk&%Wb3%ytHzV1cHsZ4CL!^CpZiep!nMVf@iRHfCrd%iSN4WXNNSm$8@I9WF zPK)4Nzz+@q!s$!j<^Cuy38rA#1>}d@L}-Fbzu=5`eG{iXNV&xE7JcYZ3+yUJ9nD6Q zOyJ)MwjhaR#=unN%7};cQLR%FeRsIRu3x{tJO*~YJ@QxS*qAqg`MfA&nR1`$s3v=7 zqrEys`92)EEa1!M21FYTD`KgM zXZazK5u8KZYM+WWe?VmHYtCY95@4KpQoGK%&?#&}Rd#6^zZ@dk+dD``t;CHL67d}i zL09S4zVYLV$kfpl-f)=0=)4{?3zw{Zq`3b4-hU*8*v;GSf!`WntirPL>xm?H57FO~ ztF%kv#&nTd80THv<882oNQlRRZ;{46kttt=4CAFcS&ew^rPc7g$LB+FMEE5q*M}dF z_jD?1%@Y!SCfPR{sQ#!R2(-rWxSV0BC_|ojUhi9*WsRt#eYB+B`wdR&0f*2yV=~U+ z-`z9iw?RKvW8DzL&d+jh@veE~S$R&2Kc2sLi{rmMJg2fQ;L~E0nsm1uwGNh+$P*Yd zo%lUvFyqnL(oOq!#1qLesHdd-NS<5H%VX90u}0RFOCz>?13y*% z?Yt#0j%xrnJ$QmPJr>{(S+k7!EtH=&8FHW%_jnj9Xc9=Z(c2kujU2fF)LBh?4zpec$DeVcVbj*yd!Sgf>_I144`7zXsYOSp! zEEFBaX9##atbLyR=t8<9#I6vn9N&A!+=4gjF8{-H4obJt)S>g^B#!2?)ZOcBO$l0p z33*bAgS_Tk=-}R-NLpErW{L+r1=tqO4<6IWrvS3dlbNLiQ~FF_b0zv8+hwraWl_3A z$AirdGbOt5+W-A*yS)%CW9a?n>+*s5 z=WY^OwfqE^#y1WMuIT@+>o3OLHE34$z#wjMJ#JWz{lffKe=I&V&SaRzn`F|diJFYa zSGfy&4}curRa|xOyQivh1o)u)2vbM(j_ZC#V^uZZ1&|IpfetiOR!KCc`%@OiN<@c) zgDh9*4=8wgW^wGnqjxK{2zL(x%qTx-OPs>EQ;``7y%SK14ioEGw89&oeMC|jrVPXd za=pi$eL=r=o;OD^tKV>N4Mf8pYq2|PxBM$rHR#b(?^%6@*7SsUfm^Ey!;zo!Qsukr z#$nn4K533op#_c=OS4=|mlWN#PDT8L!b&j&hN1ZPIa9&l0j!+HPmLvsPfxZnY`8<3hyL!U3Zsn{|<}+fJH7 z7Q5iJ&H8co5yagmyKr}7?y!e%=Q;|pecxwa`Ak4`ccJ#JO+<~6k!61&wbK3g`Fnj} zO+cmJhso;xLzvfxm)p#6;K9p`;PmcZdRmIzMJB$>DcL?!W7&7segDL_GIUbEIO}v*d%M=7WeJkhr_W z<3;VnnA^q^{5rbxwud}BuC}}`+Kq6PunsB6&Uq|rlH&R;g4bv}we!Q`ocy`FDX(T6 zR_{j>8o(Cy8X{%S2R3z`x37bv=7=~DDTRg=Qj@6x?oC;56P*Eqp2#P^D%Wj6@}bsh zr9hR(3Q|Y1kw4?ikFcUZH}`Y$-UaLFIG+GDbCt@GvDRw~Bk5M~3p!zKyP;CoC`-f}n(lW?h1g7wU$b}o1`{ta#Gc>xHdS$~ zLmbBEXCL@!SfVqzj2~23;?Er1Nz9`~2~ebjTN`k)ZC5 z1`b9!5t8jTYbupc59o+bz&seKpBWufrK!SY)KQ&{-$sKvZ>ULH&*Gy)@?hvxTpV`U zpyT@ou)D35=~>1Ht1st3{1u;j8S)xq+nn$hA4bN8R_$$C#%MlG*b`)@_Q)+WwZ51i zdPSxmCdmuW{Y1J3oXE#YqKLI7>Hcd&0x$~Vso9q@BwVJ$N>j4hUGFf zEa;o)ayvG>Q?6{2*m`r919xNh_QQaDd4li}AA3Iysn(J&(!@(_Y){>Y$-*v#u*JtY zDNV)2z0~(!|E+lh?pHDrj~_~*?#5mh4z$|a2k3q(24RyhITM<>P}DR^V{r2c8R!VU zzBnB<%xO{)s8#ucj1+}ME!Wk8^n80+A)4v78rStDvtu|VHTu-fWW6cQ+;u466^?6` zMSGF-rgPs#H3|srn~1YI259&IkQGhvnBy>Grxtsvesb^)0xyH-830R8*)Jyv{r!H< z|Ki@pg%em*n;Vdk=Tqv#^1)uiCJ#myp<~;` zTE<7UUqYEU97Gs7?_+7U&sh-Rwg5FQ&`UGW0)Z%9y+cj5or?t+Z7Ink(h(|-R<(b$rFMquGnP8dq90yU;4pcB5*s!ICz^mC5wyYu-BeNy}Tfq zY|>eKGO_9si&F$x2Hi33A7lE%#ng3ufu6T5)YDPTH>}9E5iu(d5l|PL)joGxp6q(N@H0( zAC6zM#|JJf%JdX}-x3~vLZvyTezgw5QUlHH<$O?G^joteF2xR%{Yq7$DyrKCeiMwj zQwRH+un8#tz6@vKbyDw87G8#SKi@|kk^3UZ0S4s@cr;AWgbSa4M_DexvA`e#-@1_^ zzVoB7k93a2!fEB^5Y$tGN&Y=9GOl4Fy>^DC-h$wPW7rQeZ%Eb(Pqf0ljw}yC@VX{1 zIz@zi=Sy{m+119Z@I)v1glG6OPD}oMB*xdT}t3&wS*JV+@ z_GFEj@>n{cn+#L7%k4@U;gx8eA4Q@`rAq9g_ZYt#EBgHJ-YNVX=s`1(n*Yv6EyV3l zax+daVlwg|bV)_MD}28fzPeG+8+EtLBSC@Q(?2yJqiv+KkKu`N@w-Cs>YHtGV>E_3kwv3+eg7?`1 zI}~@_T)Y4ZK=r@x@LK0Oihdz!7 z*_?@r#%X{IV195K81O9tre9k(DZ+>fFNiRNx3C2eM^o$`Z2AVrHatm?y z;#Un=&T=}E^)4X`|ITCT>(!{}fERY|Xve+!Ym61GsUO3+=ZP>O=^ltW8HOmkU(HCn zK%vuEMGDoPxG`-=WMtK0>?o+(A`w zXLWKlgBLOpb^RU->J3QIlcR&x8A)AUPqY>hePV0xrPO`ns_;l@K_7m#9vK2xs?e9M zY7t-6F^0^cH^&lRGXkV-yD-ld#TtaE4%Mfu3ok6<6!lWEA{ErDjhmOGMWGQd%p=Cv zAJ7zgVAd-qAIqxGuW4XOzW?fKG6wuGF|ai43y9XF*p@tg6XmBDpu&DngY2I$zzL2j zsdOt0p(Ugbx5X^PT0BT4*)K@TJz)$K;EF1bpl5`xeMVHF-Z3b4;29!?jd;U8Y>iFR zB?!Oryx%$fNMo%RX>f218K=y_N|=l%yjv%pHY`_gD{>F{l?!znxoCz4Z9U{{tHXfb z4R-B-sW?zaln6JEV5(#ToM~!F^B&CG!e!QmP2#^kf7y5&2tbS^Y91w78bV!z)qUhZ z^X1-D>;V>&YSKHudTg<=0G=E@Vh)P}hs`C`qA)vG*8O}r^{ohGDI$G4`D(N@3*-uw z|Fbv%vMn!J;~07>DlgKk#P&9?HmVrFQru+jJ=>A>C5-V!fxLBBm(q8;D2)GPZ)>}> zdMrMJVHv|GK&74zi_-b9Nh5>WMPvi?sH722o15ev0i@A$kyEu2Aq~o@JZMsvd_EuP z!^p1(crotUXp;a>B$H7=+dW}D@9|a{Ai10e8k4{AeqC@=ow^b|bCSb-cT}uTCy$PA zvt%c+5pDb!-s!PiR~(28zMErh`OnC?r4jploxRAKPxg{r zdO5dATfVj@^+Y|9GRlv6Gjw^!bstd#vFB*Z`7&-c+k*>zLBI4cLjMt}`S>NQ!xnBB z7mTmhWW~GP;x#;{fBRE}VWAw2{CwmJ*1=LE{UXzDzSj2&P~dS??b|db>eLr_R@Fl< z#cZv>`xWi-w3Dx1GA~@+^%vD9tUgzr$*5nOk`T;%31@s>(KV>lK5-Ey7+eaI!-Ak? z(j-S;9u)pTl*Z<-p)`u8IgDcS_<7M3>WkjDvaSpcNeSOB6*VEYlAsO0Cw|l2ZcBTc_)TrqUFvGEIb;~Frz6PLXgH#i_QzfLJxap!kabrh@i;q8w%aUB$`^OX|#F% zGN=_gv9j7Czvg&JJnQnvk%g?&N@*^HMc4Kw1G6y;!-){&4mOHxj*dX->SEx*Q-HYjT{ zQFa+d$x*QT+1E*3I1|=ri#IU1y1vBA=njpb?4yRpHf3gTr4QHMIaPoE_SW=^vmH$O zdBp5>ZPu;`X9DtoZkyNaRWHUUg&_4+#b=}U z9)U)v3O2}M^~SwAv%&-3U@2v-lcmw}LrlZ^*(r`9g=BNEv9uFhkbFc=K|yeg__)H3HY2VXd?gnJ zDZX9i?`^l7&}-fSznKH%A8$H=BY(8VpPhxYwVW!eo+-ejU*P9exUS1zva>j*<=s%e zEn1Kho{(g^v?UwC^Od^Ui23Q6i0}#g&Y2(1ZdTnd`=5@Mej?m}g=_R4>DC{~AcO|4wObhu>;@x?iS*1x%dwA z>+D`Y!mG2fYcqbRWYi(b@sHk_qwYcBa80o^(sf45f7GUUpDTLan4&M>U!T3 z%llGPKe!yU9_LnJpEW$x@@+@%RJVT38dDzDn41vGUI9)q-w_)i!^aauk!~*cj>kUT}l2xD{XO(((GS*vL-ra zwcFXK2y!VPhH~_qdBX0H-082MipSKZIutjWt&6;eWcm8bZGATc)!I>^*EdUO9O>G< zgT6R)PS>xPlQb*LfOWDpDyI~LUT-PG!kfzel*+X4w0rjT?0qS~rpQY&JmIMy?8N=wtr4#+0Hkhf4)l@GB zvYyY~so@_aYlrKO(avMCSw-frugcfaL3}KmdkG_rCJXDDSCF#ECr1eQ!nfTc zGRFa#mHgZ_lrl>5Nl;7PX^pg!4A7vSj+stfXLCku1C0)0+a=Z%NAwrfLic3RR>Qa# zuqa=U6#h_Wd+#9rAd|rDP4S+B97s(_F%TM&2g7aGn+r{XcL%4p$!W@arcP-H7B@96 zE}QVZ!j|mIU2Pixr7FFF?W{QKV>e}UuG&U=kmC6PB7Xc}&ao|~9bYb6H;)4AyeTVU zq7=D|1o1HG49+#n7&NBb*5?u%ppT2cYJ+JxGBtz1P2oKnPgeCPaM05W-T^vgOdj|d zoMZIzHN{un*RWNF%Re+MfKCo!acLZEx22@l=5~`rRCf}r?rmxj|(-gJW{0K89y zB|{!rGkolvccXW2jQLB90{k;wym_a|koXV4-%@nd)4Beg2_-9sZx4NE3< zUq8NYM--Ggvd;$2-pB*Ng(7p&)&<&=Bpl?B*S$75wDr$LfW*Z?WB^lNsd0jProa3T z%prB@R-tRM1WLXD6Y((T`$B=}1n4D&(hB9{C<}Ujj!@fwzDcxFC``B13}NZwGCPq^ zlQTUBnb5@efFvDpbuX?kHdgnczf(OTcLbBgavc+oaERo!N<55`L*T#wj(I zIJ){XDWUoUBwvhoY5WniSrJ3LGCwXtGnUnp@Y$&6M(XhOGhGJ#4hn1_h_cv+C41YF z$^bk-!@qyuAvP$F3kU>BfS61$8`yc84#{=m1k|fL+A}@z=y`WUeO&yEShR_*EY~9qQ+ekPW?Csi zzHYSAlquzo{r&lf0E|XS;+Sn;tKOujL6P%sCR_k8k_OB-gJdnAlcms=1KaS3W_&`~ z7&BGy-Hv}bFjnEM?tH^paE{JZM6MAd8BG~f223%8^pCFOv$hSZPCB)zQG@h(6wzI& zM@d&{?=Sf}*83S=AZcIPv^sPi)5YvO*4BftM}KeKyg*_I7@%D;s|doD0_wE7(dclp ze}Z_v9{~o8WZTu06CqZJK%+Lf9%wBNM(^w%8DgR-74VfJ2u`4uhdS)`ckfi+9=%vW z$n@GyG;^x|1m+HFt`q@}o7^F5E(w`uIYX?7pK2Q}I}LF24nv^+J}2mdc{avKzA5&r z{H>_Lc!Utvio$h_SU3=Zhz2SvL*^(q?yGnzc-W(zd|VS1DQ`bu`2Z53ySQtADbB=R>bJ@EAyzmJ%O!@wW>p1|kW(tFOX ze7sTo&c56`2%BZdTT2A&_!f%ZegD7`T+N}b-Y=P_X<`?rLT;WsczKn0IlBo%Qg7v9 zes1>y@XyX^Jd1#5N>Km^c6&*`4dqTD=eq2fckE-<`wb$AGkQykHX~jQzRL_O?rlAd zx_BfMcp>b7%LhYW&Xkfz+EE8V6_&0idR6vp9QC3DlA=a%?dWMFn1@kNUbq^?=uE#L zE^QUoCh;*r^uFMjY{cx4iu7-xy-qk912nAdYm%@9=zse&&|U_^-}-Iyc+P{-@(Oiw z&DQVpp-$s-zdAMEbpFkXh0e#`B*6w%I*ggQr9jrL@&$$$;Tt(TKFY@0Ja9j-M_dsv}>H;)Nj*kO4Z8SN#U z&X+rPue$&p=v6m{iFpAVDGXV$jsWPymM@2M!cM?+UVq322=BHGrWHo;oEqcA)rVj@ z4%X*(R1tTbfHK8jlS{lP{z6782LCxACUlQ6UGl)=Q&*CfIcG3Ir43he(D1F9=5+UXtT{WtnCO~|V z$e%k~RSL_rp@+?iPC3{c(2H0^H3be{&W-(*$cdU&m_mw+T8g~dgQo;dsYSXnyZ|di zV{$c6%S_Wb31|X}x%6s~FS~}LJeWIy^7T_Th3fsy_S1l=pv>Bd>n?$H z=D}&ipE_Bx{)GG%(#R)vwsaFN|AQy{vK4n<`q8=0djOBVt2=c&)Sg9@w?3=o5>nr~ zdbU~-IAhJv0=3@1+}1Hh3Acz}-!{ScgMAo)dcMNDbREesicW_07%wQCxxl(E5>k2v z$RNXqS~&bKr{XlQjNSBR{_fHTicQiuwc;h+xs=z4uN|Mk(-9{lP3U0N7lh6!Sgv{7 zXYIf>(Wol*ck`v`=SnJzVGo6#-g@_z2!lQ)!~C`Vu5h|PIf^Oa@sDZyyK)JPGsGzw zKNkTKmfn-m+(fD|PtT(Fwm2;W%T+Bu*>k>vjb><7s#dZn}C4J+hmihQIn(g#vKG;a%2$= zH{S%c>X!#nRDY<|+I<7Snej&h>K&YWZ`td7@yeH01|aecfig3zFL+(;&_g&i z5i(-rx7n+ zH4DDx)X_jHPFAgvz3=$YIR0QKTyEF7>kUC$2z8(s*>?pd$%T;~6kg2yAy!+^UG3xL z4N1`VeoAF1mE>#j9GTAktYA{ZlrTy@w9MjNkX}%SMCEC7fhrK}I`F?rsfb-S6j8mz zc=L%DX%CqCfkhUMZs+ST4O@JP!k?Z&CQOq>&je35Ifj_pgAa#~_ruMg8DOA^6R6l9 z(-5-~#Mu>cFc;|-w{bc#e8tWc`b;4Vp(G@n+_TI+mJrP-_9=}|gOm!NG+$6%5g9T& z$W+9qNIHZH;MdoAfG6igldo%RWT@#K{1kt5%sJ@7V}MAAmrTB^#C?Nq;QM$b=ubfd z``keW;;FA5H-L$HqWkhY%VUM{c7FDjtoFXNHr=*g{ESW>M6KEz`1tgd{Q%Ax_=0&( z7s#s6hDd$(%R{R$M>0b5l>$lBuMX{4!2-9l{;M-9gXUS@v?id-JbvRwmqnOcT=9!x zr>6vnZRSZFE4PIMTi3Amm6n((JmS;(;01RDh^0rV)Pg$u98A|=+_T`eMoTuV4Khjq zIdqvTW-||O%1lDzcZq{c7Ty5e%HN^Yxto*OnOYE7)(~qcpa>_k4ylhGS;y}?!LNj^ z$G#H67sujD|GzgCNufn`Bmv3#7w^vD-?n@enzAixh|#W2q%DtWo@_%^6;<;dDB2_> zq+VuOgKL`!Q8W`Cd=a`4=uN_iSvFgoM~zq zO1L+U4C5Sf;BQuf5e1&3+L`#XX07{zQ}-s-8~jSklJ3(6Tc8`-fzw%q6-9uZ%WyCv z4K81+goucWYy&W{A68T)4jQSG(E~lZE|3bxn|BvYpJkPysOi=8*CKe|&`!4bVF#q7 zdY*3(tws7g=Vdz)2&+{9f~?smb-}-#K=OTjs#Yr4zcmCy=$1APC_G#i#5W>0H2V}k z!7#{bjO&|FqsUYzBU&_Z^RDR{Ff#lZf(@~La;$1Rrkh#A%M13h*{4G;jUT3A#uwnnCo-cb!!puM9k0Tj>Y^h?3@{={=LA_;YOfkAs$7_xB6KTsVjIy`{ zu~PRl{#J;yfjIP`a(S1_NM?%aj^9~JTKQ$7Ujob0x%5t;(_U|@nn7M>bL)}iz@&%`j92F?}$GAZ~QR$jB#R|G}-LZ zLkGbJ$)S4k&CaPmyHm8Xz7{J(ncrw*R1tZYw50Pk14rgDe=?3nB|L+n7#=eJi*^^) z<}tFBQVT>kiN`QG7Q_34AMPZO<<|?NIVC4ffK~d4zrr*M@A#pJ4?_Sg`~W*=17zIBE02ujNk(-AoGtT%o3aU@k=nbbL(s% z^C28^A906&NYT@pNQT+m6nVa|7=B0S3%M@-JdqfqE>O=pnXlvDp0@_V`Zy^>8wQ)rv1G~?MOmm8N>5CATSQGO2hB`JORk9o2`W=zg(-(L9 zof$}$EqWAUb&O-*^ZuMcsa2M#1*HgdzQ-rU7BsNX){)s%@0jjzjnTVwedSR*@T5@_`d*CFeBN$||vd;XKtW z**TQ>20pOapB6;~7-A92?0Y`0YjSx)FB&i^5wWP<6{}Ix?oEBjVc%vL^UL$S# zO8q&!;&(kd4`xJZ!qf;%d(3`DFY(tf+I|NV>1~?jwK%T)4K=Csu{+HrCp2 z5a!0;~=^o&Rg~@}LqUg&4iHf&+YaTe-FSs#yX1pv&NX-_~4`J+ihQ zD*Ht|AMqS1$~bGxo3sNu7c=lP?fk<4XD)3Av<;)J^`aXgZa&>Ka^l5w|CJq8?vYAV ztBj_0>ORA|D?`-NY}}=buuqo@f+U1y;K7OskJu_|LJ->)XG(dYyY)jNxQ!GIVo?^T z)QI8f0?OgOY+4GfpB2qun1W!^cldifh_see-JCD{b$(eQ%=1NHdWk71X>K6Sy=2SI z(_6kOudnSq)#&R5THy-mw##GAI9SvoDJnBOu|mH1k(R1-6BGnr+{FmGU-3#jw4dJ$2AFie#qN*couaYpB+PPQ%XQN`=^N@K2`f(L zssqgz>w~Dhz5MCrau#j{vdNQ^(jq(E^=`vr*_I9swp+acmo~uxfug*l&V-J=+?!`m zosHr?<%BDcG7Xq(*G@10D31Ycd{PRiNSYqL|0w5GfkVm(`fvL{M9Ff^F95-dppqNM z3h#P98Rsa|-qR84V%Ru{f9AZPE(!6QXav^t%xiutNi#DC{eIL5!XQh*NZg;h1{>s082pW6W_8A#@(@huSG{T0I`HkO9@&-}wSeoTG9uQ|n>8*VTC%_sJ;38Ej<~J>FxmWKrZfCr z%@p7T49u5S3*zwUe2!gZs9Pr^n9lJ=FcLfq7X>(Kp=qY{G}Rg`gE}=R6febvAG`-( zJ5(A*?kPzZVxUcTZbLVxC#abpr@JT4xAB*I?yowT&|oO(?t1=o;Yq~vRI2F9g6r4< zSYZ4J3Zt>?@x~szV~T?HHLP9|88ILsQA$|eD(9aGjbDm--`w)JSM>=+7?cPS|9fcB zd3SD3N#7WHM5#RVN`5)xM_1n1=o&>EB+z#p=yMxrqLD5x^Lc<=N8lqrR1JSEoeUno zrap?JKS~FtS*SmpMA5+0ABXXGTmD(E4lPLAN8NF^`eQND*4#!5n0biu)`LG0X&Cd6 zRGZyTsjk|vt{`cEG3==@ze>_=E8MPn|RVE(AUv%m(_y#X&#ns1%gAz9_g=shzVaF;J~6m#zurPR=TtgRRQA zH^|Utvqog;zvl-X)?O(2nY>jDhG*sIH2Iz}rMEghreOSFDrS@1gs~Mo$$%>0l^qK| zTkq6BvtDK7D_)@<&-+@+-|f@4ig3ne8%(vvE9JJYS4i0R{JlBejLo1@KxEB^QJN4f zj9`wgm3&oG!tTf~IE}wBEj7aTsLaif9ng39HG89eK$ECIFlJ96|5hj}=Dv7Yq2R<= z@OROpdXjV=VI+z}G3FdZ3!-J(CkRMx>9zmvFAz?twCL)0WU{(JGGfz~L~73%j2R*M}w4oXhcxM0O0r%Qp9XQYkmWm->(?ds#-4 za2_3z5>YU&I3S~}8wg3OkRnCJB15Ih-05{EO3pd^SiLz~G3|OZ_p;cYfFhlftuv^LMI$m@_`iAgL~b-=8XlcP9o* zS{lPw<#NwSk+#+H@!5>|OA=E5R(xq=wN|O)Q#8zQgKwDiwxv|Gf}eR)I<^Mf?#iOL% zw{38ip2IN7n>ayrcC?3oH}r#BM^L=pU}Hr+Uz;cQ6|VipqJSW>OcR7`5q)lnP7V%? zQ05&S^om5X-B|mAZmu>(?vOVry{61lH^q@*8T#I%90O1A@|UrK#YNRyos;gpiVj+$ zHu9dF^`q{sKd871h64y=5lOP8!jr^&=*zfYsqgX^yWB zmeG+u`QLYhh5>?MYXTHB-N|t{kodlBw}pFo38x z1?2D;Rd9wqV|L*Q#=~GDm+--IE=qoCoZ5a{@qCf5+NUOr5Iye&JYY}Y)KX)cQ%;w; zdyVZigD5d+7t#XL1&_2jIch_v?x_>Nb7Po@^998+CUK@Qo;%U-vJ>GDLYv&isS-aw9L;oEUzC zwRzc4IsAM9>~m^?s^w<$#suWh>t-||T-H0Dyy8ZETJr%EF`Us0t8-vbor8;5@d+sP zHz@$;?^*+8FAOZH_zHI1o8(o@4VkCOHDCC<{xKDfn~QJqhiM${rQf6ii_wA|9gz_i zhRf6H_;e;gw9l)TOi=R&HFt)$A38>F@*d;M`$s4jLH%T~^U;b33Z9JqMEdTVU8l_NWMnX1tN zXf1R)dZ4f&AxIAEtskbZ1$u^45P!^`emIn``s6s#y;O@Yji@_kTcvtEaW6_b(PXz~ zz3u#!05v*(k;!MA4fY6-I{^iJ+of56pWN-p{WFL>j#_of zR4B4;wI|z-CR_Uh1isx`??WzYn2Bc7RR!131CkHp`ut0@j zo;kwq`Vr?hC#0kHtwDL*7SozJIBYJkcqm~LcLn^M7xfh-9`&VI1~>jTCz_tG!#XyA z3sFD|M68C$#Hn4KQtBhIu+8JShpl`46)Kd_BWj$sZ(S16<8Q#eM`hB)#TzbwCp>`g zQoHNzUNuvdtTdSOk@1;z6>s}u-4?8`;;ioOna=KtXxG<=0*sMobXlF(JLf(7v?0hc z@B4KDG8$2Wm0ZlvF~GeD8+1&uXzLAUQAcz_`T~shOIWz3uO9jSjdq-393iACU1$)YFYs3D>XTZLoI=3lec1Cf&J# zok=GVi+3R`I#AWFK{6;XZy2>4jL2oyIYLFDf5g(b<9CQ&$`O{-csE;fpa9U1Vz%6J*i$2tH{CQ3@Rx41lIU)XZjc_v~*D@H_V3Edku1U8Z+AW>0{=` ze&?G!?sgYp#c#6`f1JoicowAKexsEkvTgnix|Smt3*NTpR!H61&cBB$>0&CZh>B5BN0=JmG<#fV7z6PDdi(%8*GL_9rH}!v+8~@ohbxPwL8Ss{=l=eHqke;N6k??% zA|oYzNLJ?97!;IrixwfYPE2 zCqe8;YiZQjRU;ds3NhT?f*$Hg@9s0_!dak7Yxjj_xmZVY38Ak_yPL|!0E8jx+;2cb z?^w+CRmu}~Z&nP6vv7ci&v+9;Hoxej?PlDeBmyJ~5hupqf?S|xM1ZVJ(pEU)kM?T* zVK{vFn@9OsO>&%T6Qk?b3tk#z0O`OoawC7nPQbq9kO_Y3;_XdKCkAE$h+`Di?ckL@ z3Vv$vC{2@e<*JT*9&Fnml(_16WIRINmNPja4eMhQBk*XD7lc*O zI|h`#SkttbA0{oj%!oT(3BO3_^6eOh0c`6f3st}Po4I@{degg;ybM}ew1#wMX_Nx& z7T%e+b(hHS>}_bS<{SDU!nkl9{>OwNIAMyeTDUkPrs7=QTg zDUiu14I-FjFfLyw)f?_7%4}gV)xpou5{P@3cO#>hj#sQ5Fs@PZMwqV{DM-(W6{j5SaMphpAwq3zk@GJTV;WH>5ciy&;*Cb{oE7I(=PMzI33yWp;v> za#=E;g!>gjhE~oNA9wjF7^5-uOy?i)W(M(*nbsibjuc*V4=~_+S&r}}k|Fl1Bk)b` z139U%U<0?FfJpRq;p+UroUaAc`n178SpB+1LD8r*OAI2j{4q?(EYE^0Taj0$6{+R7 zx^5^s6c1`hB#4g32){d#xub=WMO`7}tJ4^1m^JY^;^uFhReeF_`OMYgGw|N_!Ef+Z z$l}WBX~%)k1|pX_7+0KEGx_PmBnr-IpS^k~`sNo3A`kmeBsdgQ;AGWYp?fS?-cg5_ z^<#DIMxUrp>L(OmAf&0PnB#?4wZ-mbLJa3JR-)H;R}GPcSVoCj>cgH>%@5RQR@t5- za&6b)-DcRN9tbTGgcxSK_$7o1NeU~+H5#YB^&BsBm;4OL%b?{u@m%GcO;Fb4-Uh_O z+=*I2fy4wV85b;4?5%ljGrWvlUP71TDpmXrndv@Cg`0A(070#W)@~L!3|Q)OWBi*i zN`_+}*EBfRLBHnRf(^?RtzPHuj_nJ&(DBY#P1r$ZNQha(2%uMi{K=9K1W$0ny1i>K zk-8a|H;hVP3Og$BbFDe3%BNCgN{3qcM(@)k{L|uxqq8lr+Met?vIfqw&1zvX=+vd% z+qq8Hx;w9kn9SsrIDMWwTkDa&vWCHM_b4w7q&A59pkwaGoj5|@`k#r9H}A6K^(ZG8~zr`UDB zr$r^u;Gq~B0QP(@RjQ8@H>RV*l=OWD8Zj@o`1QARqf}SxY3ScN82zn4Y$90FK5wq+ z23Hxi*l(isti3w*4dGZgt5Y~=fR#+QXy?YGW- zO&2<4k|8qD4PP-wlkydI72O+{VHbEKLbbV+_7{5w8Ud@Ej&7 z9nO|jb$+eWJM!4NV`E|Jy`N}kQK{3K{r#Yxx8Yo;N1$RC3!%9&l3%zCJenu&auWlv zFh{rYQW@Q`Qf$1&CsZ5bAZi2fVHt>fn|IH_P{gAXkR|@Sk9)8qbbYf3M5-}fpf}0f zVd^%**ns}4=3l$lZaD;ZpO3yZA~9qVj+jq!UFM~|#S=QgG*LsIZd|n1M^!J&NV2id zct{r(-7f57rH~bU_xrw5D;Cg$IU#@F&O|5CPqIJl`Mt z2*4LwmAz1Ctf=8}1Eio& z`P|*3{yiS`j;RfZx8L429dlL18uZ4)c3BvsUq)i z5MCkL73p!9i40Y|RPVqzvnWMG7@8ymWjp|o?oyo!)6y-YTN-fHYKj_-Q(S4+B26bd zjgA)}%tgLzJJxMcCeQ%sdwUP?`5&25(~n_P&gVIs)@d6cLjcLYdu?G*3} zkx1ir>|XFtZ6sd-YYIVFgV#$0k%-JntLOPIwcVT|vlyP8lUmZG=q4Y$40f%W)z1vn zJ1X}$a15??NCcGtJVkxo?izfNgb)RONy~{b*ejTFSoA^vc@0E>fVln+Sr2AOmucXv zAXqR__J;uA;xiYZ>a|MH7pR@3W@bNi$?^-MPz>X_4a1HKbgPe{*6|P4gbx6R1a|?H zb$YxeW@WT~c6Kdj(&@uTrJGlJTAivF#nAjzi7;s)0g!8YT-6P(aqWRsRme@2u=8Ub zUtHl{J6Y*r03IUHxm6NfQd?No%&&8N+H4y{Q28JugZ+|FGSklA3)%BznPQe$0do$S z^jj2cy#$rmiHQAMMlyva$%t9U{px;E8T z(DPCH15*&iO{>7^Gkozr2{s$WGTwC+PXqZl<*9>%LJQC-5ioDah_F}*?$E6Li8coQ z*#=-iMd*~66QfNaO+E-U{SG$I;%A0y7w1i>3_ymKZq{)RogB(zDJFrzgu!~{aif;S6~e%u(go<7`HD#Wd(YGReIvunc_xYx zpOrqNxym0Js33Id2lkE=ry6F*X9p2Y-W+{T>svoEuMzVv&OUZwI8Y2X`QXWcVCdvZ zt>ng|Fl$O5%^jrnsikoQwsU@|e^!D^#>wdC^xFOVyW zU<@ckK_5(au$nuOuO^Mg(OpG_5cLY{)gj!V^?n0rL0rTu=A5+xo8*u39{-$v`m&~w zmi8fGLQSor@5P0i{E9*pN4E6&YVcSKUJY%j9U&k8Y~NnEe|)NW8V>QuB9$vFMu}l% zY)RjK-?te&szc*2n6~kW!Z1vtwQ8tM?JN3&BFH3)xX|)zp9PTu{t&5Q==-vy))Xxt+@?)_5fJE5LDytOU|=zDyRBYa7l+L(k*|RBN79zk864`h1ZI`9>Dmj z#Bs=`j0*HlZ#s>_Ux?EhXfyQBx)obGudI-$@Qb9{QKHIUdf$CW0Sl@(Ri669?k<_g5CgItdwby^ zn}!Q~_fQxA<^ctt?ORQlVPaR_H1rx#u5Y+(un-T)&ZxOQtL0J7oic$R<1ZC5Ily`nE} z(vI41cDnWI1!@j{fk!*8v}a8R5wz`F=?>c_l63aqK})?UK7>aIL{D=TbC!P&U0~aM z@M%JG-(TP8U_kMJe8aUavxXTq0IO38H^qNgk2EqxJI`tnEzNmpmb6^SFEfEUTeS0$ zPD0dJk-Eb+O`E`D5v3qmy;bY;r&VTciG(l56C%4i6+aBLfFAZHl6E_U`JP0oI?bZ^ zJMk;!oNOOkSUT~BVm_Pgu{&pxfx=PMwjc~d^Gc7K`fpW0GjNt zD{O z9M@m45T3$?zX-Cnx6jyHr+++%dc$TTL*N%ST+=zwoOe9VJBc^Q%K4Ar0e63>&pc{k zIQ!5ua&$fy=-|5%oeFHbhtD)f5+|PXS1F@m&(9#VuQOap5V)aXOogiY`k}k$4Satx zI^&zdEtD6&MOQdLSS(l#YoRr?qBrc}Poa3>;vh1YQJ>4K2H+NcC>Jx2%Y4tIE%{_wHk!;MdNlq~e&fJJEt>YFN5knkpo**K9Lwx@#EQP4b%wHXmMP_h?2 z<^p>iSj$Yp&DWpt11g2NBjc}X$p`OG*#96A+M25;hGg0}8-6K)LHFYb z)X>3SvPZDI0Cy=~3SaAAjvIfkiX(68jKXTXTTksMjE(+&dI|3n?zlgV#)V<5Tr=Aj z@gi-LTPwldT<`t1V-JU+auN{J^jXf^FiHyqg4{QA)3f`&Mw}g!spbz|)b;ckC|A&O zu!5#)A6AJ8qyKfi`cy*&y9&n6W@K%h%lm#8d_3xb%ZWe^RF4M>F30 zGU+tw*{zp73H>{MSP&o+*3(ZVhY|2Ca~L5NQoC%(Z~`cabDexYm)wu%eq6febVX{s zW;=17&b;>g-hznfwCg_AkdD8%FplZu(j}+waS!!#|BC%|BFPg0#LI$GM^ZbMn|_ZI z4|bFq=eA?0lWd1yU3P?VI`Zn&^AA^b1n^Yk=3O_uF?-L zR{Ye9Ii(Ci|IRa2V3;gVL-=A$`?6zGqt};jskZ<&Naa8(0VP9}hyfwRdP37?JIW~% z;%xc<@fx|^6lo=3TWnw;fAi#SZ|#<@#;xk6oYs))3^_UN9D|kCP11l?sAf<{5lb2EhtiCkc;v&%_VRQmp zCy>gGZ=cXa0pOzKHV(FCX0EJdMzgU)`Q#4^>39^C<9>o0y>b&c_n8ZHsSGdR5k~Lt z!x*cj9-J%tTn-40)GciP6blA_FTYZFTaaitHVF&dbxQG23?EtKh3aU+#KvoG2Iq$&`>&;PjhX4E-o^x|VJ>*LFPyL$` zO}SIIVq5RUj_r+XkHp)PVYJjXp6u{F9NHOVY)2BJI%uiD=NxFcUb}EY9D7<`$=>-| zU)yAk=i6I&xd?K0K?yMxW$dm}ME56;k*P+FGV%#NDjo%bQ;$SeIh#r}-456rLNloNxuHKJjk^s=dq65o&GAd-0{<9q11&fyP}0WU3K83 zhEZp2B49G~EB3SJa7ZG~mNDr-M)&XN2b+AGr>mY>pngKF0=B!PMH z$E^N+*C5zwz+|<|oP5HqVzJt5p_8|G(t^}ECt4(D#nnvMoXD?{wI=j?J)3w)udUXU z{cLVRn}oUz%cm-S`-X_a=X{y5yMFPPOCBJMVGE3b&3UY2_rOs~YP&4;g)@W785(2f zr5?OeF!f#x^BMLDtJUK(2?y}%lTxI&bml2>cWr+_Q>f~^quKA3COp;jfo(RNjL!jF zAa4(iw(x2qx+BbbgckD}B#W^*0I2v=HSu$YOprN!1oAF%?rleBBRbTFP;AP${jDtG zAUW?VrT;4h%b9fOYV${lc#AHZImxRvv?mgZg+PQXI0l%IC!&f08&PM5-h?1O$A>~6 z&3oMhbhfs2esej;Qxx6lYkd>xNMoN2#eX>@_&;XW4@U8XIbWP68TCYnb59HG|cZfQ@-r_x$P7qx# zq;-Gk$~}r5sw56k=xIQx=0$)>w?cQ56zTAe<~ zI7DA%=b5Amuv^Zo2$6Tn6%AHZm*A5~_s__7`PAdL+&O54p-_JWJ`gqTnq`yY@wlGf z9z1L6T9PY~8WBC>LZ=vpV;I+W*sshJq!?&}F=iO;*c(Zmo>&nU`bc$`4=!Fcizq>9 zpmLqPK%2&pm)y#)SE>-^=*sbOb3T6&aq&NdxNfqpM#jdbDazz%VOvt##HQ^6b=dAVmh%wiDoxn@Nd2UthagZtH@c0hJ?f9? zy|(#f{AAJaXAtfH{@FVzdo}iJFXPj!C#eV7Xte=bjYg_h<66n`1MC7>L0NOZnlj^% zmon|k2sdbbq%8>F0+$&k#w_%r>(4r%(pd$Bb28pUdrnpVb~SLZJS0G;OY`fJN2j2t zo-FT7{fIGnTxy5Q)oSC8&tMOzUEZ6&_D?#Cq4;A{m?(GMKYQe*sib2PEj4(crIk`Y zzUQKG_L+SJG9@EESZ5XV^bc@j#mk2DVVIAPD8G&0a74#QP}yd)81bl2H(H~fI@1LnwiP}H)d)xX-zc69jS*1D^|5zD32`7|5PVZ&54tXEGf}v!SlT?*h6RE zPE-Ey_V1Mmsb;xYI`Yb23KG+~hJvIRgXLJbi*S(vb)^s{~ongo@}|?4NmNmH$Fu;%nw3q07u37vLWm?0KXbXd)GgL*(Wcn zmHaK-VZ|+mdC0v6n?t=9mR}(6!qV|U9e6nD**u>-Z*+y~@DQvy-?;PiWX|JPL2 zoq#gQCS{1A5SC838wr~$xr+SG2nI+vCaDHD3Z?$$RfF+ zk$CM7QXW{}(YsRfn@}L=@s6)P_4)LrAyZ=kL)F5_Pq_N)SO@w0S&#&@hVla!6D@&E1OgXfsd(1z?JBsK;{?XDc8;=OwH%@=Eb z4!|+LUdzr6KaB#LLd{-*hEUMFqNeVmznBSTk0^YKtiq zJw3T!n%QkQmmn{kCP9r8t9u7CIX)WBq5UlmIg(?4*3xh-mx0$9gZz9%>&i29;-x+R zJ$N_&4y}_`YzK7(ay$AiPS{6%VK?5#o6wwqE@HsZ@*xK?&(_9Sb;CM<=inQRChn+xQ#J8Mr!JP zZl1V5_1k&D+BUShqf-3f-nH{$53&hwSK6j%(zb4jZ7|X2RX+0Pc;=wWnTI8L*OMO{ zgojR;18e}9xc*zYy;@tv`mo=y18Nue0d>NA$}XjXn%aXMa*Hr0I1AVWCFL!Zk4ifg zFdg@S6pRqV=VgU4ek|68QC~n1&{Cc4>O6!a!${}DL?AU$h;(Om;t9`vuAUj`GT@ES zIvZIdyC@j6UnWBR;|BHfY&&K6`MRrQg7mgunac~nzWpzsGbHt9uw{Vq^vc8R6sXH+ zIMoc{|Lk6V!|&-vIF$^U^u2U=@~$Z>J)xw3*DKY}&jfJlHIgACh`oYyu}WcB`#wv; zwxV|vm18d}bAk&yqoZvxKYK+`HNsI}HfjVq6@-~_GNwc>8Jr#z zYo9#HS3mDkUSuu=bV*b$pk9Zi2oLI-%$k4TED)+}@3nd(){6==okQFg(qzRkH5`5@ zpqlfi8^h186kFKU(M#E(SB}u>|H1=v$QQwg$KgbK)&Z)cxKjD12RUPQ5jSFW+hzT0 zPYyY;uNE(^c)yll;}2Q2LR(ADyTc5AeU&?+(i*{akYCY^pK8(e1?9d?D?F3@VcvGM zZ2{>8(ahXrO7<`hEk0{~K>h$zK&-#Wqx;-*cYG`Wq+7gL6S3A2pILgtq}QJS#1W+D zcTbNRqujp!%;*;zb>6Ngn0%U_m1uuA8?=)}1R~+Y5RHlC*;&mWc&p~xPxonT!eRZI z#X%$@K0D!ifdL@kP#z4r3z2mve{hLmNnx}~ zTh!Ly{eb53Z}<6T$qSqDpx;$VRE)3Frs^y65xYA=fgKjanz=g)ezNusMWRmnv+jFy3MaE#X8wstxL&kEOijJ7kr!eDC$sQX_cy)f#DUhejq)8S)h*hjKPGp0F|CZXBO4OV ze#TX7;+a4uNTN|2y01up79&zQ@AVo9aN4_NzW(f*MsCc~W8TMGNuj1zu9pAygR$zW z@|?8jJB?7`v|m^tZK~h7*$qV>6R!{@43#=h#V7(zt!5i)Pm*;f7=F9@DI&x zgyq>$Pk=>*_Xv?_rw=Wwg+KO>dKe#e;_bsrQ@}ar1V&p2@M3!ikQqf0mQo%Xw2 z7NWO%G+G#W!G(ZX1)aY{s$9MSd6ll+xvz#c$szV8`V2Con&9nCMSOU( z_J;vS8i>ZFV;Y$*w5zPTHq-6QUml$C+bO9K^M_Q%tUjc4Dm@mF9|_P&7{bJ~x%K*Y zky$~Y8j9fC)NGKrPU{G8fa&6VYq(06=iKFCAQtbRW z)v6x7261nj*lv&1j+JmOnC_O5Yxp^{QR8?4C71SgJA%K2uQ=gKkh_VnE9_`Q;IGFvSnS+b0KW$ETS^izaTIx*-x3{nY8Ls<*Z8 z*xd&6g%iznpg$cKOK&4jZm?4pk~o+!+Bh|CjXjSMWFytcDDC^BMKX_z=998Bh zI+orm)plgy5#bEkd0n%>zBB*WxbY?~`3k8Z`jAUhG+ua|7o1E#M}uak;oX1xh(&(u`%)s_P9TjdG@`Pu)P@@x z_~Cl}0O&Yx5Sgxu&6VCU5ks_%t(WUHB-nK}EN!{-uiWH-JT%dFq$Q>gkJpdT-JGv7 z1Plk4U?OUxb*2&T*B3o*%D;rHOgDKz>y}cep>4ILdPSa)7nPk~xI+a_cjqLB2h4I` zZFNVKW*BETq^~3Pd=#GO%Rjwc(nV8x9jtcaH&0hUnXYBxL$j~EGslS`VZM+)4CE*= z47~KY^s@{06J8(AX%hayUyTASMgO>zb(x+;9XwiF?ybLhvb&5;vg*B3p*LRZxxZ{jFmmRdP}6b&bfcnN8baF*cu@&-Y}1ZarvYFZ2fW`MAa$8*-8Ka255=Nxqj& z18NX~=1!rx=f*xq?zp5cO?!>nYU#PQ-bM;M!nlPa%tlEprTxN1q}vodR<;F7h5BBA z!NVA~*V?A$>s7QP7`veAjLG@>${6_x;tF4XkveXBLv@){GO#1De0Dx5)cUro^>_h( zn%DLO3NMhW1;}gKp8i1g7BaHRDfO$(-k@2=#lQQ0(b$@{`3T zjryh(sZY|>Dy9|4c7l@IZ&WB~ax#F#H5!|qLogl2Nmt2c!s7CmpWxX_K4&x)KXoAw z6o?P^OP(MIFyKB(Uy}3)s4WjBd+(q+2v- ztDj~F+^*TIoFaoZ@`4S!`ZR962foI7F4_ynVUAuZ5f;px)Fzov1L5?bDEK?BKa9As z84g*%av`t7@F)cCdf$DgGT6pB{2H|y^QQvoN5=51RDTNe=I@CbuKmj!dLa|ddrj|; z3$njRpgWCHX73OHhpD>@h6!|Hlt|R&Utom zWICC5SDso2Uhn?zNdf*@vZTp7LK-!``I1f8H2PIf+L!5QmTvA$Za>~uekeY8Q}>4@ z#*i}C#2_-hA4b?G(BVEr46>4p(gbe)AuNmBiRkfU9~9+$lJM`s`_z9ii2IfCP9VB9 zh5nf!5GD1F+2*ax=}&L!PMIY`22Zj{qN%L)6L}^5I;(s)q$8M}z5Jf+T z0Xg)LoO5huP6YCi>+i5VY!`|8AB0cQ;GU`oU{k z3Hf1Pq?TSb377el=snwz*eqQnyx>{ZM+W6SDcv5H?q^9X-~_L{M`e*ayx6Of-rd(X zzd_AaKDOZ;I!3RaN;GHxd}uR7vWn=3PYBO^iULPT+>nYVp}2U4iL=6Pk`f_Z%2%#D zNWdi6CMr)97wrm+(02IU&OaTpeK2ogH^H_D19 z|K0Kih+`3oS8Se;K~Rx{{_s-P&!lO(zrAHZ8UM5&#{9@!LaTWf_!++_l1ba;aAQ$> zLj`+He-2#rx$0D+sVW-5;oSU+7GZqyF>)BGrB zfww@d%55=4=fnX^##oEM&_tv1j{YoR8jn5n#kK?H-s#-SLA8Pn91klrw9FWbS7tt$ zCZ*?xLp-g19V);F6d)@e|4>cJhg}Q|FH-A}XqNmyEUW?@lo%0=m+U z62IZg-36Q@c>8zg`U@2=r+OCU4%X4elU&4l6eafgvoi)v&NzP0O6SfUKhBn!3HP_B zQcdJB1&yRtjV({Vz^NyB1{)}-MEPbBo!t^}aH&5E5d%^hs)9R3atsIS{0LExs1uE2 zOe>>#A#J>~W4sV;$ZC1TEPnMiU+A!*bqpZl>UeA+;PQ{>K(7yS_fXlG*&D63U64vv z0F=(~mt(;9Q>*zbg74RbC$C|br#SWYd}6pqb>m%|6%i)!4~Slj-^l2&d&hAivU27u zL#D!xxI2~)zuh`MCu1(roO!D4OWh%;cwj=36%QoTV+n#EAYRFGvYsG=x{@h;8e*@0 z;Ow_CuXS3)d}LjAF!-9ifZ2Qtqb1`dXlZDX9%UGRmp?9|vZT1!rC*3Knbug_6KIq7neVlR&$DlbC*Q?|6vfuFUTFO znJw%+2`h|<4Iz`$++PZ*o4PM@yv#gVAO4I;;%aT#)XW!&^;T%HeC2hnjC0&+{kZp{ z+@DH9+f9^V&L)W?u$+D#q@kC&uM=~8oAO`S7M&S>%Kc^e0>=b&o1rvVm*ymIgntuS za_D%UsO%Fj=t9dIv*lXgsC)E)~FXrPon$)wv$zkKYib+onz3i zG{6bmXc{?_xJ>Pw&SRPTR{p7tize2MzoFiHB5g?S;P@E%sUHwoGSp z`x>^VB46ZGHD6;UHF=~3BZOx6okn>9J>;QtaSxTl*L;3R+5vBE9E>doG`j!34*+(9 z7v1?O&B7?OuMWwS<#0b%fV!pXv$56A+p;YvDGnPmTn60(yV^~3{D8sKveGA{6tC)C z4(0>7QF2I?o4o&=AL}JR+||zWbB(f-iPb3`o`cQ-quG4hFqi7Pd-5LtL)4(9DX1J+ zXie~t!qFMXPW~#&TZj6)`+4UimLArJ-Hd#w1>WAbRvzLtVmUsg^ieyVoPeC&CN4G# zPHtskjV$5{W`qx57!K~3EhfYwA&EmC2njvPZTGBr)E!_EtUXB@C% z#@_;bVmwbwQ`D(3HjM?|>@9jtFtT+_N;QU}@qPc}Y zmG(D=8V72Q@wbd7SNy^{N4L)r**&Xe38WG6VMr*t8^X#uzV_!g4(1B4x~VPO`@h-{@!}X(jprUteowMm$&G;YS=`)(RB(D0 zcF1z@Dcgy3)2Z!7^UZAEb$uO8{SbLpQ!L{MHFG%Ag5#5qm-g}9BBx7gKSU8)z7C&X z3B22$8ZM`8c9rs3_s+Uf$!T1fI5wOK^=W8{N=+^n$7)GzT z#hnIET6bn55?cxwx2Rdk$tDf^fwxvlSHgUB5Ks%%4{j-x@B4Gk#?5ixm-Cr-vVIco zdiHrRY$bWi#ypB|e=xuI+FBVZ26so#Y_)1^UfBB7R$}qUR1Lj+9(H*MX z)l!F@adP9X;VN{r01=-j0Y>2$z7ZRa^dWJLINm%HF^1gd?2jzg;X-VC9UM_>IBqK; z7I1j?Yo{qnEQIG|m8KsX{wCk~C_jMLPR@e^Wh|)F=ef1pqLdtvB@#qJneVevDX&NC zkMC#ry=Qe&{t6Qt%tt`5{jcshc4kRi?=AuRDI4)Q49=VdlKWa@ZJG?Z-6z4_*_<%| z*EKGrM=rqPy8}W=yxxWXBgccr+2lr z0pIP@^WGe8nD({0b<8#oe3lab!CgbnM`+&Xw~znN}PcCH!H6Q*ZF zb}~$#Xn#9=7S*!>6wH)A2|4Nvh6{xD_O>|Z?C7Bgz8lAwQEwW~Z}SVle4SEC^sD-7 z3%e+^lIdGl+5M6V_*#*lyUjt~jVP5^*T()QRrB>jhjWZZbq(6s$IMIaxZjVl;#D%+I5^I}QtC*4SU3REE&^;y?u{r`mpm2`M($mSj~nsDr8;B=`{??ZCXq79Ku&Y1 zXxotl2}Nv~CyO9;`hz%f0T{oxbKh0ALn?Ve4)Cm=LJ)(krk+QJ;G^6_;7lh?%QT}n zyx^}@W(-*#G^=)}*V_$6gRgX7GB81r5dUKowenZ#nbZd+7%7Atw0S=l%uqtr|DdXgHrpKfgeKnPTd=ee`zDb9Wxo z@Dwzz(P6B0y==YV>Lp-UzVX`@#q&jK;lEq|!^IY*{}QImwm7D>*yE;c&;n1y_{-iv z!=+0@q{yRBSBLJI%=e9XJ_u-x$oJo(qy$c%e@`)pDd%T0T+#qJzO4)6Y4dzvg#iLY zSu3{!nGckYN<)CZ!6!)*s;UfQEO^b5GKukfKr52(G1 zp!W(lZ)3##P1`ZRcE2%;MG|96#mcu`=BHSU!`oAqr#s5%dGL1uD)+@hl7qpc0kAxw ztZj5J0EXH_8Oy~I@+{KXoqI>f#p^)0P~<)rK>s*oxP!q^wJT#)oPhhDN@FON=e-s7qfEfwufqp%;h%$cD}?0)S6 z0C3ivgcEwfzblfHCeg3fCu=WtP=OGXexsQ42K)KlY)6F+sn$hpFB{$;NXV zqv46SWQ#2>=4KTk#aTx`n-m3uwi)^?vpMIzs=pMOIqKxEVrPC?g^7q>+;$Q{(859Q zHG9$27)6YvwoIFRt@(bxYb*-9ai(JUy}l-zxpVD#0Sb5V_xgJm<9jTz_13+ug=*!Y z<$;V`bF>q6^E@;#pv0)XVPrsS{|b!d6KUFxEL}4kA^Lb%y&?kYZ&IL8QPfCT_m3|b zUE9&AvF0tBqNQv*7)eTavQL%Vlr)#}9K z2(l|#gG62oyz2wlftJroI6T=Im&;*F;HAvsYOH_n5lnVeriLgdnX?YalRzh z*y>t8d_vfLl=*bMO&$)k$tl-|W-enzN=oL6D0T zO{#UrU_S?Osk8EY{%TNw9cCxq@5NyeEpVNI9dA3$n`PiLS1TSNho6+g0Xzl8x_lb{ zNkk7CLsD!mCxX0qxqeOtAk(CNUj(P$HQBTIQdGxfkT;&s%--49XwP?u}kvr@jaq@Qq7DOJgi26mZ=cJ2~y;Yt1S z(NFV`Noo<78D8+VB|`3jPRiCz8^7u>4&RM1X=4jOZ;PNS&R=rjB+g<)EM9#2@4n#n zVb2^VBpU7PK-*c?)+gBfsc>S99pLFn6b*`^E7rgNqfy?hQ65V6mx)9&Aev0GZ^m!-x?-BBpf=3*J>6t_#HQWW5TpVAvKMs=$k}t*Z#)#eCrZgjI$}9ZI|98 zU$GqE!==Y98n9Me-=o&&f}N?LrKgl5T|$ST_D}v=WEEKixx?4D!chbj=8qBm61p-q zME(*QN10~EJ2h28ht-i6&rOUWagJ+d03gDh_i#3)+an?^GmBOrSQ{q=-Yf-fs1aI) zuy58PR;YPty;imf3!km7R0aSN^3A+;h?93I@$$$_M$Nz9rbJ~_#FVoi)0|(8Ug;uD z!twAmZ_+@d2;vUJ=CTKznm6-@)vjCAb_pOXx-vSn`s+&HkEMHru@rHxcW$0RlTIFV z2%tJx50HcF08+K&?7btg*pmL#r5bdF-H>uWH0C|ZpRHf>?*8tzQi7!Gz1Nn$cIP@? zr5a9$_>Kutl>A^{uapk<_PGx*e$#N7_`lQzPlt7fK{xx zk2yYGD+(G9<7%+tet`hD9cVOpxi?u#BWKd4E9iRty~5Z2uA{C}X7iOmX+(*~fNDC}(8JUE09@%0IGjxqAro4b~e^e6p# za`G8vO^?c53oeqI^C;FkL-4AR-}7L!T&CND7RL5eWjFH23Q?jpZqRrFIRYWBg%yBl`z> zK8ysDa2F{6CFRu;S!~HQz>npHzOF^>xgb9lVj9CHOX}wnZ1etSGDon~0~M01s_0MV z!_FWh8jsQeN<37WIH6&`_#)6W#~~W?@lFK@7yj?%$+-B=zi<3awsRXv< z;tTIv!yQ@iz<2^hcK$v{*W0oxd9#5EljQD43iEDN=!o>In9~v?C=b1TSa!^_=b2ZE zD;DPV2X35w0;x_t0`BfV0l=C`#8yx^KO!+i#^jPY+N54Tjl9_M-jUrFfYgaqt_G-T ziAR96(ehue7-J+6VDq}OmPlf%55bSQNZ(aFA!3UgErZsC1*Di$#`GxT`C(zWzxb9(D<Ii2RPHpGrsp!xJ)% z!UeIv$!y`K2&{R2njZv=$UEfx^9viM4zz);vRBgy8I3a;wv8jsS+eG9N=X>?O+Afy z7v;){^owV-%l0)#`}^+~It%Td^)tYi+3sM5te3z8Q-<6Ouj$O+^P7vY70o*ZUAPR; z#bKD_D)st==T|SlWYdYgi;J-RemuQHsmVpfZ$5qZfpfPS#lA{I*X;v&72(i9rwt1z zi!F>wWg`ai;lHDv;Kiu^^yfG8V9r|794~8*w16)q9VE!bv^RJvBI8&Q{Jnq`z{Pi6 z*Z>kncN?4|hwzx&htg8sc%bs^#Nc!a!4xj|{9{fTPf~{{|86Kq?tn!UnC9ypoY4l% zYf|xoX4}{E0nb~f!_bm8jKbQvjPKwY_oFG|9i<7dPIoc=`Y^6PLh2;qFNN4lQoT>; zL3BY4G6Zh>@lkE4Ie*s|9J&lR-s|KM9;=|1_$6M77Js-5*5r$U_nkw6s|kE@g@;1) zrTII95oc@lGkje1dywZ~E?=D&O_*yl%37+}Xs{e_n5SYHWz7v)a&hHuRGyWhkSeU( z#+G!^4Up201cMura6BwPhE|R&w*VXkuQ+?+d4UujSTUDSQ}+`uZEOZKe?3|)KW^N< z^G95rKo>3Y+<&V+l-Kwz2-FViGkLRSvQ5D^L3Z}12L`sT8dKqu(wClpK9@9695Hx% zqhFCO%AChDT8`R|I#EP`=La)llX;OK6DU3!V&5Dia1*pjsCJY*oubAnUb#Zr=10dK=O=o`;}!3MBLw#~opEwEkh`TV6WRQ&PuAjG)W zK;>{#o4H<{C-aCb9%J+2M-pGyxseyUyx8!|J8*x-Do%qOlYEd|sFONB8{Xg~rD>lT zj6^}3AW8oHIk-^5IDAU2$mdvjyuL5<=mS>Tdm-}X$s4y2eM}xz{TAsMi{td>Ra7%- zuK_;MOE)Duq5?Xd?HUQEXB4u`QvwEKZG|_&DNzi*d|dCTgn(5bA*%Dw@r!S(+_6u@ zY3A`Q$$A&6`#op4|9rmkN?3HhFUe64255aziFxvCs%lE6Z%drQ)PucbU5#Nytm~c) zb(l%61z#^fS3WRrD6Ans-!qf1AADiHo-kgwg%a7v=Geu+b3q)_pR2A2YrpM|h7}ZG zcnyEhrTaP+v{ztI29TjojMRNjpKnJwXEFa)>U&w($#H!($~yAr>~+A?@LY#l`H<0t z>+~(}sE4`KIlL=Ce!?BGmbZl6nVc5s_R9g4Ka!es+(4$H3=9K#-EnSJ;aj=cRY9op z_`u7(ubHQMo&D~@oE>~?NV0n|34rqs;94KGPIN5su2CkvdQQj&@mAMLPC9|Hy=Tnmq_zvw3DXPLy`q29@lW!788-u~w)$FPH_z zpKuP&1P{(f*uG8i^;C@3L#5Mxk$>gU&Z5-kci6~#{1+*G#e?{uPSLjR9{R-ijboEc zwxP~wyNp`OwSjB>?KaFH=0k@t*#B}6OO;Dq>CP?SuUVbp!fxD7xtBi1FCHC00R;O@ z80ReMIj~^s$Uq6FiO9nUQZSkVW*D~mlei=tc{o${MtM10vRS>`i*CoGKC;UD<10GA z(F#GP^ZFe>T%s50_j^o7F1|b^yYqM4SN#57zMT5JNdQ0O`9hTOK%0DiE-lO&4F*xN zg1e7d`y#x7A{D5=ysT7Kdb$~I!B_FPK~foba|kndy+{aY`0v?qC9p3&fjPS|Vwm~1 zDtC$Y-<}ST>~2yN2m4PKy4N)f{GKXgtG|PM(g!$Y#CAPUZ^M-Y?z=a4ORd&4puE3> z@umR{a|NC+y^h&*Nl2l6x?|juCmz4MD!ucluSa0*81GeGdE!T_B)_3V&c^|217?5I zs;sVE+T<`6WQmomzy%X9icb3re^Lclfmcf;=BG0_nj7{8Cy^1N0uz!He(Cy{uOf3| zd1YDN(P1jjNH@IP4QDgxLeg9%(C2W@s zuC_dE_q7i0)kH{dtrpl|m(p+Q<#+`)()+dGV3Wk;1Ka2p!XY~WnuHK9y#}$J=$0&e z^5)8Cuc%o=)}4dJ()w4fsZHWOxz5L^zeQV;;u4qFIc;et(fAv0L(bM>Ds<1Zd~7k) z3vEAqR8o|_1CyXN_WiL8mW&?(y=X$mA-Tvfn`hJ>YJaG?68Dw)`cYqS2vY}3$KV~! z*;D%V49|X9V@aJ+&;*d_(z$+9cFdE3_;qWrysM;Cccl3FZiTq^!r|~f^MhuZR`i1E*~u!2wP%<&4o$CPkIb+(v~@GW%IPY3xfGq4b&Xe#J5p3l zp&@SH*NlwxjXmZmcqO-aee3ViseZ14@{57&>2}rY#UqWosZmb$1EgO3U-G z*g(2kLb1moHyBWPf~Dr&`VlEn(i2h~DFzO%_DpO@xOr>VM_kxbfJV4*Mlj^X5;BWr z__=Vbv+V&j0oHwd`ouP@u=>YU?Wkf>kQWXc8*%6 z6)P4c^+otS?h7GXzQyLtY1h0uQy_C10tz(_{FpDXsXxBLGRZ7Aod4A+n+znJbu$Jh zdMae)=eXuYs7dGGik!AlWGUuqgWp9{MX5@$pm^5Ol}3Z&a%rDgiPOfZdO7JZ&)f=d z&00Pdjb#vKdFu<7dlh=)eCyK%s7~l&zEAgD{hq}0^rd^}G>rAR2&+W?K%{VzuUV7E zlYvQj%?1V3E4F+=F);aAssxJp zfivqs_`L=9#>|JUv>z^5c7>aS^PFbFlMoVE-^dICcvEqhNHZRy0o&I<^`o78@*&C^ z^_~Ths1N^!fY!c^_4hwIP%HYqegCqdq)4=VwU`4O=t2hAOdMnnmKp+)BT{v=~ z!^)*t^adWl{rbewkXH;-b1p&oA&nFc>YG&=wUIUT#Cbk$`S28_ZE9t^Tj-PL+*qdt z-u?75MYP{um)X&x4e6}1drvs_hL>xDzE9*ZoTe;WYs)3SeJ{oA%NnVL9`4+)7^TGD zHo_Or3q9<)Fmhua^(;av0XM{}cWYda^KSSt9)y=nYedrqX!%KI+6-;Ewhwz!=dXL! zfb4tN-;0ICPsr?56meQe)PC81VjaIP?(b{rTZ1;MSZ@5orbt0mBevw5Yw&pUf}+>y zYpAy^b>l^9-0Z?!$P=vS2yq}l5LMZN^lE^UaO>jNB6_{Fk3BeZBD+}{Vl0Ky+Q>7@ zkmwZ!euCmt_)Eq`O%A=eFiqA)Il4dSYhD(^*YSE(KI4Ipl>0Nt`onr1*5Rz-e#*Nv z6SOVaSNkp>rPzw~C1vn#(x;;%xUU=yn_V2zwz^kf^l* z-1d+;>p;Y0Y9BR6uWR*8ObJidoe=fSk&b(F|9-s-hCtoz(gDqSEC+LgWbpiw-40bN zCU8~G4gKU2Lc6KAmmk5oBhrq$DeV)heJVObEqig3W z>dFM14TazoO#CiT#hgU^UcmQsIT1>lBGJ{%1mwsYFq~!hZMI*6rt$h@QbAg zqz)bg*VpYo4s2XT!*lVa-<=`^`z{`wom5E*$+?JmKJ>hSvY*q`T_X$Ah$43}^Sfg_ zg7?VV%_H7Rz~}5E^VAqck@o6iewn0WkgFFKW&h(_f}EH7>lp}K!9hPyEa{gExn%jW z2Q%14aE!>of`*u_^&hpeu{_(vzF^BEY~9*9($$ft?1zK{U2<|HHtx>>Qog7=5yp)t zbHB9|W}ZIMgX|b1|0pNW$zs=AcaZCi^K)Zg+XzvdA{Mf?q)$Wm_aop0G8fcykEmIp zrWee;q@><g zDJc+xRUW}nY9Pf(Z=T7sHGwJJOVT#_WybY|7W0HF8RN?tXDf2F-YI=hX|7Ihm!hG} z%sVjnYPj}yJy=C|yaB2CAkp|x2xUrMmA=}TpA)xsgNnVl%(Wlfzwp#LsPTD?M7f7` zvNpqD0(nV;)q2tf4LNxh<VO!YcQ((28J5aH5WDK&>&xJDapq-_yOy+#~(q2crb) z3d@s*N0+mHeLRa8;}gH6a_Ai=k0Q0qy#IPapDirq?-=15hXgz5nVnMh$=iVjh3%ng zjx-iwnd!CUyM zeJ}hk*qYfFpKj$wx!cYu!d9Lw3yAvjCBCYeG2Ukrx$^y8Vf7&iaj=THkozu}Wi>H0 z4gdi_{=Y`-w~Ju|ax2YzG#Fp9JLrbbhJ1|k)F6i3-pXeC^&YxgoWL3_)J9BFAC~$3 z5F#%ZM@Mi@F*T#}UBIu21EkP`PlWNv6gH4(%&pj?_L-{#ckl3S7foi7JCIAMw&D)n zdG(LZtQFBcWkm2wc*Z{KKaNQ|3gli{6KeR9%^&9P!NjCGxHLKFEwf*l^GM!#S9~h_ z{Uogww7EYHQ4^lS8fsI$4=oM-b@S@o>m>R;8`w?keA0e`b=u)vnlt*k!RWL8Au^!I zD;rI0+xtQD$&5Jx`5H?XzH=`!p~~IJ~-)UdrqvJf@FN`vGMTHyq zY;h8ub6(>|SJ1X`(-h05r2`*b+S4UKANgo7>m02OI^@vTQ<*r1xXD(3rJlKX`bzbF zwUF?$b)K|qhoI7yzl_YR%5|_RV@IHIMu9X6-E+*LP&bSshVW41tV#cxYE=| z+cxfpJsT6wTmx?$I*{WF;1c#bXphnAwq4rPD+h$ut}^~jTGV>hgM&K-`SJ3{9`_ad zOm2(}Ty!4lvuZ@9kFXoCkF0jupo*v2Cqp;9~(Nr4i=^|6&4B=YI{3*?K^|cekxy}M<2#f z0|=ht4o1VJ2R{A8GRvM!=o!5y7ZqhMmj_MV$-5$PS1gTG!auJV<}t&`jRn4*>YkQcfDxAIA8tyK&y6;-)vt zOXXkpkRJC2Vhwpju=6X3sr!<68~YAX3g(cDZb|3-u>{Zk{J~*8vonx!`gu>b`!2M% zicZ5~UTV%^OqQa3s5eG@aP*QAULpOSRcCLU@2!5Sss$IUEzi%DMN|pR{3{J0s*COxc3_h3M@RAK;8&*P11=f%KrY9cA4%T`-8Wm|eRI zuqhwD>(TUnrC1vI-${9;R{q4ntZ7sO()~`|+joE%!hA!Kh7C$pF zFRwW*MEvE4)Sk-o`GA}_E$VvY3eC|ig_B~b17TwFE~lv$;K>(9NB27?USN6W0%i}9 z1w&rNpXXL54WPZU$qUY8s<)&%W<_fs8djK&*glf0Mhe`SmI`CxGJP)I|5y_*#H>xeN_heFeihvMU#3D`BeN z+L3MVJ~BS9Pt=CN+=D)Ch*^!c(JQF83#W>!dbzsY1ZX=5D1u{a~r-mYC7Y3phg)Is=`S|^^gETsYpp5$YiN}tw zvPOE84HxY%=msC{*Gy3?w|jfL`AW(n%##x+Ce~y#vFkvmxY$VubaBlp+^DfvM#diz z|Iy^mVkrLPvC<+#3zb4S|B4Ln$i+6AZ8U9g8T#oW_|f|62vKN|l5TCq^cVEmi4IAL z%B#jkb#$qpH#~9(GUX`tOhxD75fHhGG`+soO_jk$-cm{4m@c719099WT(dRcyA#8n zpN-k);32_IW8pXIZU86xR3eMtrP-sxDuP^zZA1$xfRRGFa+UDUB>o)sQL_Luv!4$g zk=4&H5)A~D>hwH?05GbkApAWIUR4X+d@@**ZNhw@42<fR)OU_hLH?3a~h(m$Y>=d3HpKK^`>9;q`5v~^EB1l z%myVTva}`uOc|vcXHQ_=2af)ym|OJr3}S0P^p?jy`H-HBke`nG;>0HLq9eKY zE{0xbS**7i?t^M0Cfr{7d2qqiB`36CVBUd2_Kq=1Sg1ybsHi>lV(uzq&uamcT=X+R(N86hz+`&C zZ$AnR2ZD@x+(k7CJXJvKW3c^QVul>I#yapb18*P=@F4i|V3ew8rU7g<9xB6^zdhte zBC`}g^I+ng~s={KYY{rYwy% zi4mm16Js;Pq09Y!s)_HMJaC+;tR z4)-GeKro30KYSun#^es0R9{#LLK(#sS?{Qjk0p?yPs1W-%zP99r?ofZ_pOOww#?ZD80X<>tq_K zMs#byJOu-cmJSADVTLg(tDzbUrt_@?EH$X`@$PBSJM_;xpc2fODWkF1Tg@41v&l5| zv1EBn7y|9C#r;-dEOVSPOLrAWmTr%Zx)V@ov{sS`Y!HlyQKcu#X$&_|;_Fr5elRC%-3- zMWPG@Y*rJVgb~QfC*>-8J~ZAeu@3e^{lV{U>6xGoVDviW2+3**U5#CG=HZ)cLCPDH zFX(KHxE$-Z+C*9H*Ub82%ynA$rU(Sz980%}y?2_B#1KtGN33O$$Lirg#a#V)=lLTR za-%5Q_@t8onEICC71CdM5I7+Q?&@K4A4g4ju9CBf2h7%qz5=OvIb}J{pgZ0zkfVHp z1>J8(vjXg#THg7D=+n)4!(l_$fA_~RUF+7PT=ZUR=?;Dxy=)4~mPnpX;BgY)p4?`L zFk9ryzMyGL;YiHqfY5nwRQa^BcI9{#rNVC@Zi_wj+*6ROJ#v#xdB<>(zTO;JIRvHK zd%moLx*EyrUQG*b36~`C@O7QSJpR^_IhLpsd)w8}U*@A<3OP?7%l;wKn`e5}q4mkJ znR|+$g`@$mr52~zAF8$jBlTz5tnzik0nD^NqBPgA&-5&Trz)l=*Hajiu~0~?lWB`Yq(&zndEBC|2R5}ElGhWh<*?Y+?HtJ zUf2$|!kw=lde+?sN#2WyTacMe2U$z<#fE<2MozIc`=KW(#7j`HJPf&^gHhdLbLcz+ z`Bv-~fiLuz%$X3Rq1Qay=Hr;93LN!-mUl zYU0;xgL+Qayd=TZj$*l5$LN<`bN^_2^X9ecjd5K%a2$sVIExv&=%K6UDLzugK5_GP zYHXua zEAV)%k;^i}Kj_gY!+9A1up_5UCuieB3!f5gzrW-&gctUz`PUHZ@4(bE2>U6R@X=48 z@@;64?HDlA^cKJ{nip0<_)cOx{`(R~=Bm5*4^4NFH~}15X<^Ts+r3d^q&q1uK^Dug z6#O3VNNDHkpn1ICFtMw!93sz*_zsi7>W9I1KVkQQ?0!R0tgz`^4ticB^xr zn0ureGzwK%0D^e^AILu%;hE#0+7YZn z1__p)FF#u5ld0@T@?l}Gh`QVY%(oc|G~24<%ZK?jZ*AnEnS zUW?573?Us4+&F^BVb_FPYWQWt(?|F_+Ezr`6vp>)e<-hf$ZVq-cj@i{)m^pTe)Irx zd{WG$KH+f4o88w0qF(6oA|Mjd6}KfeFQ$7D9YYXF;jGg;9A6t3oXlwYJ=d+G+rG8$ zkqMGlXjOiaH}C*R%6x`5H>BUg{)*gOK&Jn_|!Egzz%AY8G!D;@fLcCa-J=z%zzt zjNs(LZoNA(k<)h|RZlf*h8sL}UE2>YIwvmv_G6YXM@jNKPA#k^8N) zdwxt`2|8fw_J$AlP!n>Auq$^HdY4pQMXR}sAw~_El+7U7CFygF$a;z0muGi7{OT*o z7QZXVvpn5JRu3ZvjDF;}5iQZFT_~f#2=8hX(Yq!BO)QHS-8gT*Cac)lk#1; zhoypm6u?VrF4Em#=%inU^JPtPfN�Spd4!&iSzF9urB8>v_lnvh>=~NjAuQh@2Ii zso-7cbVSTvH?>NFL0nIS{e)e3R)d+Ff|ws1XvQKj5GAM^-O8Vc<-(ppwmv{`pX{q> zdM1*1UfSL>5yBiBeh#kj>qE|!^q&y!*FTkaZef_21km$XsCEQ6i+65teAM(qKHe@Z3@ zb;uf@vEYFLauYAme;Co0YU>tNO{0yyMV^fBaO@l<^-@}Wo?@zF)Lxm_3k#daxe4? zg>)eFLt{kJDv2?KHAwc0K4^NP1I2o-PdtM>P{TlFM(MHMR99?%h!r)j>|AKkU4cOv zYS-?}q_W}!tyv{dPiJq8nP%ajPtqX44?eaE2KC^k#z{NBPFFNo!3VlbHCU$&$_OKO z-zqo~Y;97}=$i=gWcs;paadaSjEt~%k|B0f*LCyc4&44@%$jlmSI)$j>E{5}(OLEO zuGo8evgUxQU@V<>Jl8L%>p1yb1VXgXL@vw2+35TYDLM}$&~Wgva|&cXoV4K_#kj1w z3CVdq1xIXTYuD*g$p*{$BzIW!=~vZhylldJSiX*zp_g(j^UQQ_tO%^Ll15$nHP&fc zv;J{xt6b3K8ZWIR)2GlmKWugmF&02uaA zGZX4x3TO?Xt5(tO?AdMB(^apJ@^X0Z9!A~$Z8j`_@#UG)q$yZ@EK`FBsF4251M#nwr-o-F zvW+Liyj(eRR-646U?^ii0{8kojJOzM)MjMVmj?dW2|Vik19V|~EQQ@u)DaJ+38E=r z8K3MhBzLU&4JVBc34lHpnR8P#o}YD?Z13z?iU!NGbXbc-zE+@l3?E4j&{~(aVw8Pq z#DSTs2QlF&=fOism{1Y8PuH*3$9L>n+Qb|5%y4k`1k$?IIIx|XX++SLxeS)g?G|m% z$*ry9HJ=!Jyw(OT)-35*`931zvlNm)!d3WZIlWN4a1sqm{l!oV+$?p;kIax^pd#bG z7K;*l`?uS`S0Tn~JGjyIAqvES=HY{tm-A#*F8Pe@4Pl|_5<6KRH9}!n^L_ZBJcG~uvp!2H2b#R_-=A=lX#j|!8=ipp8m#J6}bWsUJ7$~fy zO3J)er=v=;RtYX4jt)>$Jp$m&AA$Du7f@oe`vSabYcSmykve1`-V4{-W$5Xr1RuW&92oSH%a9Inh)etMK zL{O@$BVbGY*AZ@NAURN0%cm`xZPU?TQV=$1C@47H2C9v~zI-@f-$vE4(h&5-Uo-%u zS4YZ@!qZ28>wSsjj!X?YmKsyyLtn32O*>5lp}zFCwT@{6_&C=Uu-FSO?ZF`5mk_)1{3a3pe>|)dUbj{x`A0}1gY5**0(V$qGhDI-M(a|7L+Q11#7e zkwLv3ur+#6@Qd>Q)RDe?pj#NSYzCoQZVpnXv2KVV*%T7h>pF9XeEO4 zXCG6`b8i|jKXP}`abVpHh(FoxHT*eF2L97aFB<|5!p;M`jX8`#d&fQ>esuQ6@|pE_ z*1(#v{8xx7^QqwH3WR=^egvYmfdK?xICncRUErIvrQ863i2~>)F+tAwf`kD?ueCfd zMfudShR;uFAB+~|EHmYlFwYg-y*M6ZP?FFy;e3HeieX?%#>|9EcnFu?u?df7sL=Y= zK#FzM8&5)U^rNYLw z3(Bc{h$}|N_ULk75>x3iWN1UOAjrf&xIuju{IeE^q2UpNy~pqk%06hwiMHR})U;5J zzi`Pia?Ee-+DIRe?u>|2x-rm$7hAtbv0s`2*Rww`pp+y^uty5g=7uSqH_G<6>y!+7 z4h$f`P+^QG;|~~NA3?Wc%~H6GNIv8%Wc8N)f)W_wXf)(79Xa*NE7`lTQY%%~|Q^d&HQL$o2+ZCS515 z;a;8>9YY0;3#%sOGcOjF5%ZUj6XERw#)4-wy;uAV_hZgHJ>&M>G(Fgk* zgDe|G^8V33AgZh&?fcvZ_OC;^zv1gfVBQn)?`sU=R2IC+cFiql8y)es(I}{+25N$v zla)g}8a;NEbH>=L*b?ZUC(x@rf!pR`Pp;Eub}^EK`?SJc5mBK!Q_ZoR-g}qiquT1N z#TSv8Geu@fx@wG8253N)tp@Zj+J9M@5gSk7TEGGk%SIc@$1nz%gg{nw-pdR1qk8XmaXF|RgjO*JgRMqE_34xu*-FxXM@?BuL z)`=mb7fDdH_;n*|ev%gpK3ynJj1exMg|G9{wBhI6JVYAF*)8T+b5tHNoczYAMA0(w zsWw3aJ(PxObq#ai^X=LEdu>Hw>d)#TIAHH1Oa`Vo|( zaceUr(N8ESg0A%ojk}eDA3v$M5}dXB03M7G>7)>_q~6c8P=dgp^zpzqZ(bnHOA_~N ztKqUBUM4KZK(E)b?U=ijASVN^8ovv-t)>4h7tZXz+;b?}_=(A9+HI1tfHM1Sz#)bq zkOFu#=hSgsApio{WG&1*rhC;O9MZKLz1ET@{?VJq2wZtNDTKoC-gMY^S^y56SSoaD@S3N(U^S&3OiE;{BWf)Hf(oPoME2SHSv^7f1L zLkQSv9S6FkEhJ)<4}h8|52o@*EQw?nSuXL!O87=WD(-svWq)xZcivgcE*HK1?a|Il zO#41mO?>W-Vq?D_^TTFC;P)WADf1h8_AQc5_gk+CNhkX6!=zoqwX~Q3!hB8qV1&6b zEHUUB@~3vs0_9%cm+r2{MfZB??qlvod%%YUI2NXRhmH|=SRDEZ=;0!7wQ*z_hMe`5KyJwLE&te~%z<=<`J1A(Af_fq0sXv+n(5sCG zV5j{7J^%GLuZrgvEWN;2)qbyJ7%qmk@9cijlD_-V>8J8Xk z7kw=2S+n&a5*|U2?r+x?#x`bfeZ^`MFC=zz=@NXEqCJ+u@uDSiZ!Wa{I+LF2j8DV^)cf(DJ6R%~dJCy^^7*LXK zZJ`Fi>Z>(x1}fUv1?E;|>mTkDMji=ZyC6hHl<`BL!8KYo21cwqtFuqqz0hPHWefmZ-Olw>@$txa?lUE1G4|lqoF!X&mFMc-eod06hf-DmHrB;W&PSnUHIlqpM zXO#p3r63ka%4{B&T(`a`xVFRIE?bf{AtotW0XU_M%v^+HXfJf8UmxZ7)l&^h`*v9x zWV2(Dm^=(y22GrU6LI_NpKG^f#~@-`r|B<0f1vW?*7Mf;gSvo5r+^>U5XN{6Uhspg zep4YrC%0sH#j?q6^0n|)LY-%ND)mIh2ilFb)s1NU+?Hz}zfd!0I3YMA_zKX}WO!UF zmp2Ysq=_f_`f@|YEF7g0N*&tOV>DhXQk1LDLSp! z5SSl2O7Y)^VI|khNqgmCy*Jndqtk(fY4u@B3~Z|k|MqcLFLkL+AG`#SuQP@&4jsM6 zcC}v7U)$1_!LsB%|1Mj&nnlCaJ)C@u(UKi=Qq6jMgl`7E8KVr}V4U`=z9f ze6pccN|)#OQnqoSbemybGPok*rmQGS+Qm7 z3U4}+jbgUvf-I}laeTcNaji4uD|>2eyui@zOjiNkg3GuLW*jc*O8Mi+OO){6le#Y_ zSSCSyRNUhs*^*J0k@BjB#?zZ~3qfMH-Z~&*gm);ju6U&Ksi^(T2ZZu;B;^y7PuxPU z-D+fh6S?f(%WwUU_sf!QM8pDB@f?b#2BhEikdlK_5NmgoV`{IwE6GS}XaUTEHC6Xm zHr7ISRbM(M6jOoxs&XUFc$U&HS)~dPp~8g?dXNvsFW(-B(G@A+#4@<#A=!Buo$^n% z2qLgm#H=rQAH(P-O;`k=fBV&F+yZ24j}XQ_m;=%ar^_I&X9-Yu6UFE3Xi)gXrG8nX zK}O+bGoT2QwKTs)jC34h?M{Ak&fy3&z7bc5?xWudhfB*pnz9p%{o;erB zn_=8#5Yxw|n^>9QZs++f>?i2^UU$JNVT1;Ppmg6OQ~&D461LCO^$}}Oz+^x3%F5>* z9vJdazy)X)pykcaUI&TCTo%CaTD)4DjWc!mJ;Aak#&)0+Ovm+Jma2sfp0vIRg18x< zA}K#yb4p%_4_AtQdGucoK^b`~RKPNkvrFcsl?%dkZ7@XBudr4bslx=$6I;~hwSgdm zj%elmw{!Sl{(f6WI-5dieR52MG+4@DR?ejpvZ8kmzTllS5`Qm6pqVplb4H#)!+VqS zse3!L43_Nvyh@4Lz@yb>yOK3X*Shb?FdW0UUx)RLM0s5H>#J}M8P`$noF^Yi7Xu~^ z!(|1u8(lx5YRR|l?|`ow+=KrCb76)Payh7g3+Ly}aDw4wcZmT}U46_0b2c@Kp*N9D4K%#7pvfkp5FhJ{wQ$#%=b*(nb z@-0#nf4Q#k3AMk;;&Y(n+|i}F+Qq)%^JhYA#uZWi-hy|qClSy5@m$R$e+Y~#tL0nE zQmSiOBW?*JRajgMp3VjV<+K`#(se~<^umL8@6@9+xc4uV4D7%;r0q+qeH-_y$ruf} zUH8@Z^3H&Ar#!orRDoBSW@4eLm0%^L9^==j#~50vuQ)o@=k4@DhNzX2`z$m}Fjcl6 zrA;ec$E(Une$@yEB-6PfRp~#Hy-PGt|4kkFlGa9u=&_UFxw{?I$c`%62bn?3O<$X4&gz6 z4&mF;(1lNsdf>H$!i}*IAP^xKP9L+bB8O4msp)c~wRo3BsSpP_p<*73WypCjS5C*yx}GG6_C_TfEN z-B=LMc`j=;?8NqhJog^RiOpo2{!9TUQ&C1ptJl<@yxpMXqo|-!tlBN3qOx zy&(8pdOQ(HwkzDV0Q79W7{M3qAuGW*;_^-Zs+v*#Knk*q>}Fvs1u%lfmQdKG2TqXa zfLa*3I3e%s_Z$WR`(>r!`5Hz~?@*Bj!n5`wKvJD{=(@+?870U3aN~ztPY)nc8yUhnF)Y~6FaV`eK5d!d1Vp}+M(=9l`WZ$J3PP_|2jQ%@Y*1^P^# zsgnTO*PYlLYd~yNuQ`Ys)2gWc7D`Wa?Oa06&RTT9jw40tZv2KvL-#_JdA}M8eHF(Xq-PB9QQ5WLHwmebUk1aSX%F7qO>5VvD#fM!=0qAEKr_4`vlBygv zaCc@&3+Qj@p2;|r=&K9 z0`G|u07Y<%#EDdCga+3mA4n zOp%reQHRu79b?(<=4J#95kD0dvK%CrYa5|CBzkgsbdfxO;D_4IBUj`K%bW6eZZ5wx z{1l|-eJ);=9Y#^vLsSbJ{{CaHS^X+nBvH$y!X;+#CSa|vH}%t5X3EEdm(@rtp1TRD z$lp@ed_FtoIi3Y2%DD1V2hv9S5}e`u6@l{Bz3`g8KEtD-_WjY@Ml-S&cGY+}ZG8pH zrjoNrsiQ3DW!d7Lg4~qgO6Z$?yk}y>sN?rq8CbS+Z2x?4-_rx1vjKsOPRU{b9M5W> z!=7FBtH1B6Tlzx}!ZJFOmH)Pzf9&(a5)KfFwQE5xR|T_gO5#_E;1$0gb);mrUA>YG zQE@8Bze(%J&B|a@veNHIo-06v3yI6*IoUHUz-N%HWEa+?9uU<&DO%;mS9%x<>Eg=l zYM(1Vzr}%w3;h9ByX|cyw4+9Oyt{?pz?OH>ujJ&Rzs*NJjO(r)EZXK`3!wdn`G+1T zHMnSMk?Nuyz2@a<51qmTJ!}R4EAhg*ITA$tngXf%jqcR|t98)HN6SrMkZ+`maGQKjDGUCbu z$VyMO{dK?3J1`;189y=^G`n)jd_IsZz0)1G#W&@5QDY z_TTkfCXij%7La&iI_TLS=qhmE@bf{_wi;$AjCO+Q_$;HZ;C291T#0Fu^SO04E#58X(ws(M=I81ubg@`If+PiO-5Jj-5xU+DArXpdahkm0gGI-Mf|a>VPM| zje+$+i+9As{kQr~jr*2k5ecoE5tCOGa{N8!M3j4M*^W~)|zW5Gp?9A zB%P8|ZWKIO?&pRZScReo?O^)+(3-F>Q>L;0_7IM0Q|Yf5L8Wdc)#pgZMDs2>?{z%F zHr*$~7Pla@!XMp!d%(UB2nd#L=4cPcr~HS3SKliy^gzh>=-ZUI7{A^4hpkbH(Kf>P zKleb-WX#oDGIey}BNq;tn7E1&k>nm%xOJP3UJw+voguO*DBp4#a~~id#YEikA*(Pv z=I8Kp2mw&fB;W=HBM(v@7@RTCUI`?Hel8uTnh=QsH2xi+9u0uRy0e?fed>@s`q8J;$44e>7?5GmGXv?mfLzV!i+PIjREPGKI26d_>t8cYD2;Wld zZW;{-7cq|ld9-<<2a0+8h2^2Z}s~gb{Yva$EIS4i2P$O^{5T3OdS+hhCQ89OvkzTUctdFBHCHIj6bO ztBo3Rj%HT~FG4XRt9Bk$&EJ`dpJ{-IAh>kO=RAWZWaw+Odv7p`w)-H9k1ORGQYBF%@to^1bE^tw(wGeNI>G%+;=jAkYhl; z=uxl5I!p#=c*kDZ3uJ;zPXJA+=vy8O&Zv;TUlTM~2`}m;P%lUJOM=7fx`=Jg{>ae< z%nwHt0$;gs#&x?VHVP~8%T!o)UwW>F36pe?S5jNSV!r%E#cIqZ&!$4_>M!dr$N|q@ zE2Rd=FUP%){PX@noCx8|>nMj`^t^^$FfVgU>*8q9krEor&2I}%r0+!oR7r&V7;{;c z!7Ol~-dB;aJfPsw*+EJH)4tnmQx{id(h;7wV1j7klH?nozp2AjvSTE#B41o*N-DO5*l(?NsUB)g-;w zF6v+pNe9DN0Plm`i1*JWiovHs`~xH)YgyGE-j!E#6;r};Y`LlktlUuzoUNHaA<6pO zXceXMlrLW5;?u}0|61N_lmqm_sfN{2pNFwtXAA0vkbVrId@>r`t$FSdSB*Dl=y%llr@rC+<=Hhai7~SDy_hTmrC%m>F>(vC}df5MZnX9YAIM_ zUL90MMP1$I?Bl05Z2SmV73glvo`^V9=+)7@w=ou}vF07QL)!w1O&Fn;FlTl+5QryA z%}46(@%O61cc=`oQTUGKe#(-tFJYwjY@$9^t^Hs>?lX4#VdUpBJ}_IX$K@avfCCPm zPr{g6>Ym*3nnW2H~#N4s!D&_{_Zhb-&ITmHH#Ia0vw zv|o#Q`DWRYH_~LJlvUl=7_l|bM%w(aha9HmOJ1E}x#Z}70VEL{mtF!X3s-(g|2nGoeqH;aaF(7j88C^GKR zJeZERy?5k!tdCRSOuTvvU#YrPF?CBHi>Jr9H@n4*=upr6h4mCTO@{HHlT3VvJg73Cw$Xu~&<7c`km|@-JMy?D} zBTlTY0s5UB^7YOVkwWZYPl?>;48O;jK$umRe9uCAk{+P%F9Tx}%3O@Lj~|ek4nu0c zmLwnYF+a%lRLf`ktTwiJ68xk}0#WRxlb%s3W9*!@h#@m;$V#$teZjCD83Wg47(nQ= z6%FLNr{1tl~6c< z6mDZD0?nv35nkEIPqd;w^|lQza3vY}d`n1MgFy?q08Y|<`ei_o8H{3~JfoD(IFIo8 zsh{gS`wyRGOi{WYZ>G@35i4;a1Z7LeTG&AMJ8QQnSWw4ki%N7Wzzg%SwiPA zE{9MRaC|%l-~w)B?LL0<49Lca_Kpuj{_DVVc8z_`unX(_&=7jD|55GO+?X}pqXajyk+03 z#bMlT!Jqh+QxaQ9BhI7;oJ2-mrYU^u97p?s@&f@lE|R3T+D8xqF#&-goHainYiI{7 zL9Yunq!G;y5M4#HdLxt)EzMW=mL|O}!q^XK#K5#-A#d876ab<1hT7Y>t?TMgaorpB zrV#@Miu`%U77040I(@9bF@sF2CKQWU(mUqknMK z4uf`M=2(JQFA?M7ODKQ)%>*D_b49bMwx`B&xI=5jiXh|i9jc)@J{X~S&LNk%WS-YN zyntp(9s+3CiRGf@jK-y6wyCXWE0n@i$}Owlt4@@Xcwj!I0-ypI$p>vg;ll`uAZ=UM z1z*1R-PE)Yr)yp733S~l=CkIwFnG)NdhswVg>DUe9J6QO@CsIPz@s#X>`aR5tAcC= z8 zlhccYuwI!SlmrtIsn>OgSa!DdJOP@B?40234#qR0{by~-Xe9-74{OeXwCbbKYJ;kt zlQ>R7rhe{GY*J9x7x)fb(#eH=N>KD{8@P}>mq11(doA*X`~o*2JM=Cqlpwf z!%Fsx?FL@|wlD-UxgT=X@{Viz*vf}k+GLx~En#F^pR?>{>kw+N^+@6S&HNd3jUm9A zJR>|{XpQb#VJVuzGy-emE>L?Wb)f~CteEWt9Ff6Cv*EZYLj%}Ipkb!=L4;cW%*H$o zM2_=C>cV=HdLToOMeo{eJ(dR4YhSd7-F+D`!D2w{OsEjs6UqM#0fa(Vnr#K3!~yJ7(Zl7oj!9v;)L?y3Ni**9_>>eL*(%EK5P4Lfxkr6uc$BZ z&S`HFn+$_o+=*k}v>A_!)fVKTYZtL$BU8Fz!a5MLmR*TQdKp<8J{@9}C4_`#@ z2;b$D5)h9r?>(Eunk#Ng>hD(~Jk4?-Pdt`btc@Hh{C9NmQ%K4WRi2t7;k0^WpMjYBsGIV_i=PkZR=meU z@qim30gd7h%q?JD-f$OVqu+#;Tp6|W7SI8Z(AnvS66$T|bS3RYFj}V9WLf#QWR4E! z!wYETVqBz71=t220731o&oVxv4hl!~FfL+zwdwWx_H47xm1w@ELX!mTv>(hyzMN`d zhu2$1Lw@i_Ir5D&d@~)2Xa~AgD+h!J?L4Ko{U@$qVF=X(op~tTNF^9B+o4gs=WoNgPSuD zx_xKYa@fG(N>EGerLgh{w*-NHiZAI1=G%O*37J_QLt9IY&t<`L$qRV&vbJhNQF}ph zSzB_W-&Ea`IQ$nFaf%JMnP$JFDU~2<9SU81Z7IvqAK0?B+mvi`I$0o0KLS_I9>eNf z{PHe1vc{+VZtxSkey6G)fcPXDHW%C=Yug-9f$V`cQ&LEi@hb{+LNd>G1l65|3?!yS z`a<~Q($81r)>0MPp=)SZOc~;##@aZ*gf_l#7Ku*CL~m5RK%NC>EfCV4=Rf&Pg0bxd zyH5B&C8z!P2w%!Ur`8rJS}w_PW@0J{Mp(_)10q0vGqXI3fgBBvH(Pg88#uFA#y3); z=ueAbOz*U{hqBFm6qBR8g!vlbPp&gSx6O92-DwwwQYNUhdtH zf-=v~iAw^LJ;qy5M)7S#+~7G#q;hV9NQI(|0|&9}n(W!}esgWTDThlz5=Px^96t_@ zMU25nRxr;7 z+|q)up1lBH={y85_ShV;W?xfeDwa;Dw+(wp4+#x<>uC8Ywi|l_Z`-kj(k90iQT^&+ zEf^Ad+797wSY#pcm5}6302M&$zvM*sh^MmCp;0XReZB6=g!?7qM>{P+Hza+{+LW%A za)L)Xd6ynC!958<^er_&L|GYS7_eZ#X~pGI#%eIL+cDy2;AH-D3pu`e@K9lC*bX(*<>%O`z z8ycEJ$t)*QjsiZaIj&`SqG!dZg{W5jq0oRYVwZNS?;I}Z(lWVWM z(3Ny%o>RZ~N?3jMQ2ZglUc?{OykYguKxs|%G=t;lXx*x0HA_(>$T|wM7FU~PtvvNH z8`*B-_`6GZCAgN&^IbovE^aJfr9{6v=^&#yh)%t=_2r0kvgFRRoP1M$begQ(dL1T)UaRO+42ilH83qS|)aQB)VUBcI0&o1>KX` zavjTLfhxSMvFgdUmR(LU!Fv#8n4&l5%FC#R4=!Sf1*8qSa6p>Lv-=b7hz%SC*I0)Ht@bu=4W7X-AUF&=#f zS_7l*J%nvD5+3jMXz4H+r5!4#sEV$u>!RIdMeIEX=zXwZy;pCIBzL`{IN+_oLF+DM zAC-8~~AB z+0uqDsKpAXV3$$ic|9V;J87VK5^eIMOOEl!a>jkm?t}KQ@Qj-8SG>)q`W#&I4DT^wvci^1K-k<3Du<2%~yDi})eVj-J725gMUOfyV?j$7w_xr`gfuxx<0*hXb>R(G>su`iz3xYZqeZ^KjNx|SoC#tSJ(<+@#8 zQ>f!SaV0=Zka(yTt`(gGgMs}5WcU#ujO+lcB4(}~n8pMW2suZx-!I7q+5KJ-2p_p! z-!?{Xq~OvvclchN-dhMEiHOnBOA$W$Ok{L{JnAkT@T9l)k@H7D&H82JkI`8x?!;^Q zZp!x#jbAbm?4D6|O2sj=N(R*B#<{K9>ML@KOEi*2c=2aa zlY5$%wKr(pW6%y#tfX#iZ!M^Zng%+5M<1;G7^0vx7ku#Zb(TV!Cu8Oy*7k50rR-mh z>G`?umGy`@PLfadD;D}0<){;R;%1=a=yDE|*POm&r3{wVvI(q7>_;6h(HWF$qd)}R z?q~jc`RD>cNxeU)TdrWFT3I4jyWn!+t?gDc3a^;@-ABfJPWBCu9VlZNyv@{LYIrw| z#a{X`pjdul58{Lxry>0(h2q%r5<#^oF7J0_!i!G8>$*N_N{vIdQZj9+6f;qv$}vCbZ0SxbYIbqoHxHZW{5qM`RrKV^Ne7-ki3Z z845EZQ}ShcyJCc_zfZydZgTAi={eP&38cl;1R4Nj^`NGm+zf=0PS4wQe+l>ZogcHn z==;DL{3fUl7+(HS~xmBb;IyR~tG-G4xq|#pllih6U3D+$am1R}FUYgX0^R2Q? zM}+SId*77-){1BfHm>9aj4-9BquHum)JeDyoC71G^0NEDeE6G;-cQtgNhAc;(3^NS z^T=pmCm1iO1xpjv-y}&SXCD%kVYfD#rW@vN@q!y+hK80;C+bnDiTQXbFwi+O{PYT2 zN9YPtv1&5t!-DdCj~<@%WCF*%A9BEk$I&2qV5XnAy|FKoi437b79P7N3wh>lfUQI) zVVUEMcJ<#qZ3&rD+g%PE;DmN z70>WtA?>QBeSM_)246@He|3hjDFq*=5qk}hs4gITyn`$Hwx#&9OdcP-HBM4OT;NMjp3oopnRAJZ{yZ;(Zue&@ zz3()JM;46C!K3oV;v!uMJLfLR8i~9S8B#HO_kp!;93oglNk|n?~Z^#m8 zk9+jG#JAQ*r9;N2hgaWnIOgx8fCU7)R+zvnpBMo&XG;7<&}1%Zse-@GQSo`n(nUaR#Za@-oM#4hPno!mBXX9(ZsXqV8#e*gNj|42@O`UCl2{EtuZrBKv=S1IyS{e8iIRDWM^{O;pl zO`p|&_LY5oL_a=_|NLIY`tN`HXNUjz{z{9w{`uW@ZSwuq^&u$c&se{|rg`kDf-$R`HlQr`v3d+u@&)WY^Puz z!*)u$u{qlc=dsxTe*FVJKi5A#TAuqq{?kn7nbRudUnNC+DezwZ4oc0b0YJ{379 zd)vkF_t%<$xf_2ZX?j-vQvEN_{NATE`}IHn2T)4~2s`GcASMX`04`wx08mQ<1QY-W z2nYZyI15Vv00000000000000I0001YXm4y~LT_YwO>bmnY%X(lXSBIz&%{cW9`;uT z*Iy)XXPJ|{vj*8@Gw0a+#+-BJuQ%^#cD0ga7zU(%@v=yEbye}yIZx>Rm;dYPyT2Uy zvex79w?E*2hW_|VKBQw-59Qzf@Z9fTsXzX&fBl#BDF1TS*;f7S4}|zilHK>u-NRe}Vo2L&*CN|M8c1j$!@VAJw)^{{;lk^Ze%%{pWEh zK?H&z@E!agUH;3})kFI~>j={{4gUSzKmPS!%D)tK*Zu8}VI1;5{<3b%*yexxBkAI_ z{kO}%{$sW8#}!mm;A_wG0XnF(>q?C#?#;aSm!-n^8fCBGuCfFlJ_Is-=|Ew zdiv`W|2gP?o%cVkVVvT$-tNE8_iyX@kE{FZzjt`!yDjms7UR~S^kp!?GNp}{)_rX@!y&^n14~Be`}z>Jpc2jJMwfJm%rvk@t*u+A>hCM z3t0Z^zhrr_{_DT|`7Gw2lhp4le_o*fan`>g|MXYn&k3P_Z)y53>U;Yi&3pIx`+)y8 z&U^Y_2mbHEv@hL%`ak|Y`hWhnX#F41-(UY&_J0e?KU4q9Vu<_`^54afrv3^0uhGN) zLlCilYiRN>>f7ZX4fek-q}cz~kYfKWq{ZJ~|6@qu|7`*Nds4o!g8n^l&_9m<3loz1 zk2At3`cE+N7ZpL_|JK6j8^=H2`1cdy|6d5H|NQ@5!~dSI|07@|`?md0;G(a$eEIkL zf4}PLw|O!0{~2}oe*#wj@7wTK82$5r{ka!)AD8*R!!J$#@t0}I*L*p0W}V&;+woS9 z|Mpz}7@U4f?8W6bQg8bwkp7oy$&0`Jk;Pm5U;aKII1T0hnZ#>OVEV+IvRw@4>hj!Buv*u(c4h3qeplA<{@2zAgt;rtvl-9l z!**oGm$8~peM=3uGOc!=*z@S|lbHoXizGS^7w8MV9~lxJd=-t-)d9WMBhN-ks{ipf|3U$2!_W;&ch8QCB)-dI`vX=>A0ch^DE5&_ z=WX7B7^?3{H^|o4yP}K95C&gshx2t_Q{0uO=Y%*F8&DMgS%_(aP#!6r%BwwSK9z~#` zx5iq>v9XUjNL~8(J8?F0+(u*7ApC z_sAe`-%4xJ$)&JW^Q*g-PDa-bLH#c@0zWQlG_of?fO)@j>2aO;@K5Z!`$s0-&yo?m zg%1>`hi$q??=(X7>C9%22p?@d(3j10PKr%EvY)sGL=nNa{9yn`K)Am;Syk!I<4=xe zGH&`BT77ys#2*ip9IXBI#&HKEH4+qmkU|PEnDN%#TcaKiaU02Av1_E~X4B?ns zDhs@kdvXapmeRgmxb~3mCKioYz}vA`qa8)OQ77r6)6UpZ_U3l5-XkC9zzq%O_?yQP zS)#t;#^4~m5b!&{_0CU%JKn4rY--P(NeMqxO?R#KojpvzvBFsLRtt<>fZ_9x1&{Xe zB11;R2SZt(4#l<%W}^Sbe&&1gN9ZcP9O?1vk|znQzl+26-(=QkK{;DdO?Ia7+-2)@ zB$g69e;W`T>`nJ;sTw&J1Q)sirdK;T5uOwuBfaQCr{%x*R|LocnWS1 z;MNFiv4KYM%K44GiO_?Bnafr@-!(TOb}3#$@WoSTR&Ni~IY_(Ne+g;N>V67W<6En& zO3NP@Sa#!ZNk6xbd5|%UDB`ygY%Eh% z40U}~`OI4(L|udRSsbU1$=JFho5Z9Qlo}rPsF<}@orIs(XG(pnN}}f2Pk5E;zcA0i z8sgRV8q@R~zIPKoybFXtu*;;;Z$Q4=R(&6Emz;*Ies^Bqwa5^f>XE6$p+ zir#qmh^`r4CZ407i_m^Cvy$1Dhh%7Y}mZ#Zp%vJ`DeF*S*^ zkrCyS;WJAV1_FEMPuHAfUi^9KMjgIJJ`Z0)39t=mY=F4ZfYRkb*fb9R zCj1r^nX$(-vE(eL_*t&BennoXb423#3D4OEh5IY+dYVMW`UGjnjR*4^Handfsh$pl za1%nsKee$PV)+#N^Y?McKgUs&T0~Ui{BsP!TbI=~l-giVFct0Ks9IZ}ny~_C9T!LG zyrq|4*!48BV{`ORUEIR2qH}pE51TI1`5J7^g?<{at2=(8)o)cT`plQ!oN|u^1_)gj zw1Rjpy5X|}>ig>)?u^a}0bH3}G+NCccW?JqjYCx)*c5n90DxciH0(6Y1J`fR-p#h* z6?qooK>Qojn8J;iRsdT-t(98#YR7SP5d4_NX&6PSZYiiwL_K>p645!a>&@`Yiir+l zlQcWKjbRje+vR&AyEN_|8oy1f4MOzw0=E&6qh|_V^)_cv)qZr!`8|inCO#7Ys5F5MT3Tu0%`Z) z8PVXy7ke);Y~ql&oyfHVB>~>+t;w+3JTjB_n`=$O>BZHnG znJt?p0fn=jw)CnG;I}SUCsP1Vf%xMb^8V&1x$8r5 z_yK5a35}@3I4|G$n&@X24Se{TxCHzR&-tL2TR!Hu!|4w9z_U2O6$+2J9|_4+xrdO# zW38?Gr5c?V9`>pRQ`}~_ziBT#NWs`2w9-s+l-=W;_-wZ$B2{8_Fb$$XLhO;EWsI&7 zNy$6r8WxbGAN1InPI-(tkk`s3;AK}m&On+wxmi72uFZGu#-VD1xi~=Xp_nR#D6Yx@ z?z|kDPvqMtaKG7X12oodT=l!Hk!C1c!;JCeiM5xrAd;}q*tias0~yt68bL*r7{=1r zs_(|YQ4gICrc1}LvLpy1Gb+ti^}wZ$l9V{^-MutK)sQ*$+9@iELGy%|U0<^uZG06# zndiYMgz8Kv8z1wUZNw*a0S4BpBzc`|$e~;INP6aJpsQeSA{X2{1loy~r#3HF&;p z7_5xkLNeg_kF*c06g%GIozHN$R?zGusi4%mV?foXKXCSsg*$via^3qhDbPzzoKg|B z_%WNXFE8>*`p$*m!SLcB7HsxRsB$Gbg_;sh_lx0i?I|*ffO`0x2A&Ri zop83OPhk!#g*pZJ{ZkWgIk$=M!(CAh6W9i@2r!|POQR!oV6WZWnGJv3y=tKD0Ek9^ zF6rf3Y7>pbyF45MSL-zdYx1h%BD75pwW;Djtt`K2YTTqd)Wt)G5w2#zRMQwU8LQ{o ziWJfEt3AyXoxTzJ$j-|mFw%%i#TWV$6!_~^*f#$R{4Bs(PvoJOtU=a<%e&UQpJ5dQ z33lMt$hgWEv#`Ph33DK+qB_#HeMl>$rQLLOax=0ZII!z_Bz5d8^rlf;H|d8^E~vD}_D1ZWf@! zoT;$|tD%47S_9NKAK{X!Fw^cPY?}JyF=GH3?o{a8Wh{Sh;922uTOIZN1ty>7LU==1 zXn`!*^Fic7C zHKOKb$jpJE1eAr6JVIJ3ZN;PQmn_K9#JB@nLQRQxc=wZM%fI9=eEmiU$6g* z(&yqx{_{B`s>^7`UxCEUznkJdUeJa?w7F%&rcl+;pdsK zGtvS|Ysf4VNYLt$$4EC1&fWy4&7#LR5S($YctZb)PqTc9NZ1avD(%9I_82{^h#sj? z9yZ3MH*x#6C?xY`Pw7gd$^q#kzZoH6`zktd7~v9LY5jn;`eptHBv%&8vxLgUK&e_^z6EqFBBs2*RMYj?~vLURu zEDw)+O#yt9O?%LXPAzFZQO|R1BekAeuIoK2PGT8g!t54G^_XJ%Q@%6>P+*=?J9 zfW9maK&lc>kS ztylb#*e)p`=E}{%xcHkT25^}^5g=eNj1H8ufifMv_ zzIgH0XzDIn13)feLMaWopo+ zGH@5G7)>p=%MXvBCiDW@c;-byfeVlIxBP`szmwDtrL7xP!Qkt2%p^6A zIbEcZ;F%uqqNYcvJ;t?dBtyA=Q>s8%N!(!?L`pTMlr3@A0RvvXF`<2L(ZtHFqCG+fTQs-qnb+yd8?x%$GDnx5 zv3oKUQ5c+`DQLoA#1LkIa=&NTs}5lNhagbu!GX9mLv$$x4f`V97sxIhvb!EpMw~S@ z8d#=oBS^`ZHNOV1tyK-d7~+6+O$4KtX%XNe%MFLtKwvOc>rmHeAlTgnzr-)5EifQN zsh(Q~g0fT?C+&HbVyR@D{Y_HHiyK?@U+a`2lNiuCQ?)#fX)v`L_mFTARg2t5?C!;m z;n=SP(A@&8N@9pU*#IFybB2P<8EQ+7*}KkI+!@duKySQp#5cV)174r5+ae9J14w>^ z97dp8ga?W-bp)pq*FF5!$*>=HzIYQ6?j2Q=*5xQ!3W@;SE)9CJ@MMd*EuIJhsf|Vb|=lg1xfLkkaMo zfTGH!2Sg!nLD2;c8~+0UW%X4}v$iPQ_`Rv!8o`t;#{z3*4bH$`Q}#+3}3mTL8p z9B#yY+V-Pb1H3rUM*{ zKxfXj%aLYLp`QemItz<)@Jt$CPdtKMfcAkQtg>`;-?6^gO_n73G^G zVE^i2+&VPnJCR3c2B}Me6KZC!LA;;p^x*QCX%Js8iW#go?|%|0d?omo;hxcd5$e`p zBPoF0YbX-zhaO}_l5B$6jbx^IrnNZEa?XqLEVAg%i`4XfsWCEP8rm;c7{!mKu#ZCQ z^u&@QbF(MFpoS|r(H2rw7(AZ?f3a-m44Wr_(AR4DBiS-F#kGpchmFiffPH+4-x<~< ze?H+2AlFQ!`fixHgR%jBC>)fy=7;EC7Q_Hnpnw()v2X6@BYyFULTryW`Pvdl%cCH1G%4 za+~$6{T`yRiclgk$>3G$;hcDbMLH37x8QLSSeBv*IjpRJIf%b>f}6_@$}MhMyL zN!!z0>_(p$Up#6=cj72t_e_Vy*{onL=^^3Jz|-`1#lobI7mePf+C3xR1H6+7Iy#sX z?!K41Z&u%o;T*2Q=`(z8de*DiLM60^5>r##_-Es2MKZaOl)8jztq?PYS`LQn+QLJL zgn621<&wiGuYyy81gpCi!?W{ zjhv#Uqj$sN253V7LH-+{I5l*;nY{jFIP@+-C9#xJ`lqJr&&$tql^;@e`jg?FV(P@) z)X3z%{ehA({W)&bNeI4^u2HrayKE;_1zlVMxP&EN%LdhV&E;3jlwloZ4w&83ZU${W zb8O=swVVkB`qk72wD-tV3Gc^;kir!JEpoew-M0JyqMpnfwEMhd2s)9ABq;uB-_P|- zOjcG!L55~e1>s|=(Zbbag$6Gn;T4MD;(!hGMX)V}kGAC=j_=VCMBz8(K?13Vp^$Q8 zF-*8Xd4>dGiD4;+OLhFcOFwS{O-fH=fD`8~tkD!wz2=w}HJ*`Z*^NEREnLPLVpH;P zES4<2Pq*T(`RD%SNjxX_65m4rA29i{Wyjd$S-t9wpa5EpNa9Vf>gSWM-cBdV077xq zNpr9s^!O_66!F@8#fQw5GZiN&>gmJFp(!e&B0TZLyzO-_1Ov{lvD!y>-K)(3ZV@0NyZ`eXOJ{4HZYBVaH+43-En0=9legqU>7;)3#k4=GnqcJ_`|Sbn86H zho(v1gUrJ10s z@?V;pqJq7BbM_iX!FB%}5=LHY7(?QnV}PD|VWtwH9?)LSQ%^|Ve;G2(29&iUq7&t~ zkimlAJi7Z`E`${w=TChUi$*Sf@~MUjuWE1TFQPOA(r?&zCDZHEOeA+5?@6^|2+ABSClT(V%?0_Y=k zi$5{K`lzTkmPXOGuL_LojT{Jxz=1(ZuG~1lL)7hKkr9exoMp<+JkX~UL^`r08NKo& zUw@0bl=TxG=q#KC2KXsLL0$EUqM$2!bzqJC_n~oUUGvxE8nO{h87iNA}{LQ zzo)Hzia@3afZ^CF_z)y(K}3gJ37=j8(72zH&pj{whffXi6CQ_%X`~govPS9O&7mZ( z1kTYNZHE@%+}S6GPYgb|nau!(j)Gv~bq^u1-duIf9sFuyAI4b!2v;5q6UFc!eE3{A z4BogF!gz+93;@uc4w@~v>>>xkUjra06{hdAl8*gQj>xGjK_h-fhBpYLz)SF5Uo$Z1 z#@5OJh=Y4?WgzOx#)^Rxri2OQ@WjPr&fkva5-$ZqrZ9Wc!vID3R_^jWY#^~TqzDE-EeVvhz+~(|emdsQM zQo>INxlr4)+_-OfTCZe00^OwCiJqtDO_;jDavD(GUDG!MZOR7qFY;agv!TTqc0)$8 zXog8gkr-xugUPAn;3j=t2UH9MsM;^V<$QP1g|$lP8owF+%cdFTa+8Zp3Eg9rltuV#n1C(z+Dlt829P4XaYSd;b`WS8&Z|@W!8(~%2PvOUcDw^ z4TQj9(Vtpz)0gMi`_~$GM8!tu^?aFEEquuz*9@#zXGIzNE}>y2flMte@lkcS8^hYs z2Jf%=5EH{Ng2orcGgCA^J6$%#pp!;n&WcoJ?O-#~S(mFy!%gMVR%eX2PB_H7p z-}QgcLh76IeH2jk_L)Si8sPjYdXi`CF-6Vjodz&{$w+>E-`ax z_Z}|us##9tRlNoy+VbajC%B}k76nUu&xB3Eg5os*DiHoe46x!iCyR%oH$`>g#$h)Sv~e{g&$wq zVX?7YaAL?|z#P1iA5K=3dr=x>$xlI1SF8Z#U$ESYH%uO#^ff z%`FK0eU-)T`#xaO;H3gD7*(3++zhDjgHTo8q|;rWmv=hcjN{5Jb&S$Fgq7EvhIit7 zxF0P=8Qf1}s_ka8X&6a#K<(lQSpYB=f9vy?m1-+0a5RYVCelmnE6dlB+dTamrLZA6 zbD*sJFj?w_D{EU`Wm*h_k0r(?O%iHk^fk#yxk~5$(&yG2a1JpoG5WqlE?qY9j1^zq z?Sn>=t)06-$hMR5(!D8Zbwu(p@lGYHZ3OJR!#W_30~6@zBI&mnjI##nB15I#X*6q_+UqX-S8)vh0sRXoX(E}lQB~@t>xv}uAYEX^@Z>2V8 zKHqBQ%=I_Dg8K~8u6O_fzx;QiNPc05{fvw!)HrRbjJeR1guBO9!@m!hYp^Iq5A{~;dO*CLRIy0$Ge6y_(v~^Wh|fWM zUT`6t=CsXr*|tn5>$_23xLe(QHsvv}PMat6RE0I_=ph*b&BTFz!L&S%oXZ9>*pN(RirU)TSi7Mn6DTSsSt9%QG!)c7 zGR6Gt^P2Tm$K)T7=ucw99Lxl)F$W@@r1S>dt(;?$&!4|h5La(^mpKvjOOs_NQQ?Qb z%nnPg5p)yi3IgRiCcOq1tN;rW%t|^Yx!IalRSACUM!m@&XCf2@_b?cEMgf2>B1rTbyT@55qW~&HBo6!cgU6hO9QbT00mfbSK2j#JXjX7XE~` zyQ28pw8`hw^PlVUyOe3H^9YfYoF;T1!&Ur4^=-bLz}2*uLSc@yeb93#E6QKDTDykAV#?`TuVGToGMbR(i><;BMP;3PIf zZ84lvXH>&9cxhJzr3UkHe z4cCB*@z|X`1DsTDLEp+CLnCAZ7voz&*-J5G^G>yTHzi1QHaQjMDTqPz`MqL#qZK&l(64@{O9oyvL+EKQqYtEhjF@QEp^k>}{i0LUSk_s3%92e&( zM05@u-?HSRd?u>OB+ro}V9?rS-Ai0|)z3Cl8eGnynR$3S=1o5;Yk=p`sW^Np;zUqmyQR--S-fh3ipdn-yDQmQ11wF;#)@t=i*v* zmpip%8v#1o3yqnM}-$QGpf;I8Pp%;z$~YMq{{?4vub)*9qImN#=2D9nGOZ zE!XE>vEogvJHn-IORSZDCcDejrEz2kSI?V?$~>uzPv;KSTk2sqi=t*Jq6OlEw7)5z z60XJt%4pQx&3z*LNFUex>2D6{Y`HHX-7eh>AdGx~INUDgOJWp2ag z@Oz)X=u%|F=kKB;P2*G78sQTb?f9^k z&@BQR!l(!aK6o|ft^umm?%FAXK+os4l-k^xRp6%BbtGLP_U-i3m@Y{EbIsY_O%MY*PMxG2^MQkG=b z{e;(PB*smTHxUC)l)IYPV<3Nn4(>;Uw*F9D=M!uXK-ZM>A{HS%P{9SMusr*P3Ehs zIUT|KAE=x@E%8w9veW68uwg%Rtj;QY0ukyE5U@UIRN0)55l*j5U4)urfQ2^Adc8lT z5a8szq+sUM z*tiiN-xL$8XGuy;J;$g=Vvs`tn|^W~bMaT4IF^zcgOz=kLjUGcUgT7V8pUV%g(nSy ziP7LdTxb9b86OyHetYQ{6528N#t7Xf!?EGgsD1+G^3^^=+Cw0uwdSqy$+H~l9z4|c z*6ChIc@?ze7IQNI&!}wZ0Q)Vd?`9m0)swNE#@PW>1d`BZY*`Bh^+rhjE>UF@2L!fG zK$~w5=kqKiog)h+__>ohVYY}PcTl#CmR*@iGfaTAqAz_TC6R(#+nkKdv@*u|#kW*2 zPDI_4@hJ2e`j%flA}MbSnLFdBDHLB0t1ZQun5{~l%~Mj=h9T$?SEGlA;#h%lXKSYb zvaBQ1ix$1Cr^iokB!@$yul3UxoIVb$9E@xNyDQ+mJXSV|J6R(15wP^)Tuvz zmetvnbC&EiK0`jrgUevNXB^*S(~2Kj$5C2&_ZVu-%RPHd- zZgxb{K<|SD6zGA@5!RG_p*s|S6Jp&(X{kwO048?=|0>u?s=iE4%V;vR7wQoDj056# zd-@?QEO|_gS#_ZRox;&yy+JT|F9c`15b;q1&eVh-OGWZj#|}ge2Nk^f=uJ^J3MB%_ zCXKo}3a4Q>k6dAMh_o@DbeVN2w=z57e)#6hauf4@ zsQgMwS0c7&$(t0xqGfF>9|Bc+gj17vgy=OiE-?TeuFLB7bqPd`wXV3$#WFpDWaFpE zZ`U%d*mQ0i#X&9UQZBkDI`#>?7%YJFFpU++;}`04SVJ!|6mLE`ChIq}=;IV-Z$kIh zygY@@4}I*WNI^Lvc;@H&guLMk$ph#wQpkarhwh<0xJ2*(ehT)NCtHf)WGl#O#r}-i6Mvcr znIOaK{uW$Is>CKw{aZPyx{@Gy6|Rzd-vvL^CCd8Oxy{=Wfi2J|+rYnKV~#tV2T^~C zT-W>vEG~}Rs}F1n3;R{UuC;|M^&1VZb*%Io&g);sq3Wy6w!E=nq=o9Or$`JO9=0vO z(-4-Ejx`YC++yN1T%KNC?zkqM<^tFWR7Ar0)L@%(yRhOWzDxA-(68xv03A+4TN6bv zsc5kcqpviZ@0^-k3P5q1g;q7DsuO;Jzt6cP46B z8{uw0K5mc2fX|)p(p*0Pw~;6gS5#i3@T8Qdbs&LGsO~?Y`*^{$3Ya>k&7HmON*ySl zYs*`Ou-afKJnado*c{)pUE$sL$Xz28yuE6T-<^)(B0l0EwSOg0Xy~rHJ_P3=1j-Pd zmp@!J{0+lmPx(QI|4b9vZvOW*^L>)Md(#QS`Q^Vu1qTT}dadeXukP%AoBX7$WB;0W zE3#gJ$mM|^_?9p)A8MF{=-4dWI}7&Y)oIxUzTCCqn@P%^M)_%s4gKi6e*O0JNMV{T z??1!=)Whq3L&0Bvko!0Y%9|bqjUoqK*&U_5afiyE-yK&Gd2iZNrT)pG_bq&fNoH?z zt2pb^ttCQsLeX95fEk;JZ}o2+4IWK?u;<~l9=6}gb$T?n?wxD0x$u%NK7-=?+7~$q z;|V%Z%b>*_{e0hNS4uIlCn@do;dTYT^Q}NL{H$iR^}q!dBHFkPBb#| zlQfjx?I9HW#)zXr%<5FtMw}GiAUz#qSo&4oldW}H7PTlot|BgW_Y#YbJxR62mlmPu zCLiNP(BnL?!3}-)Owue_16lh}kcC{Ybb1C1%BnMYW{nnSOmgOwTwmdJ3>bsPb@VNL zOA4N?KQHAL<4~;gFr|+|Eo%CfH!g4tnyt%<_E*|uBfiK5&j!Ts^1t}&8!olG>Mf}H z4q2V>nopG0zd}v4Wk~ROK0zG?+&zKN zMTwW6vPo&*^uSs)ldAbS$S)RzK+Vy7yj(goJtj$RO?lVFyJK7E-U zASz0qFecYw z9HrR$tui`r&A_8iRbn$_0sOk41L`8di3>iwF6Hr-7M6=r;md~b_?X*m2aIeXON?bo zr>}soCOGG!{o%h&FpsBGlmHpbj!()s;%<{xC*|CO5%XiLcaOTH=GRL?8~o=SV%#*s zk#APf5siN&&S&P7Irq6Gyn1R35XG3MFqP4-dS3^hxt7-KTtZRU_e3lsY!^#Cn241d z_mbe97_+DZ)9z2JwX3+|cp!ZEk?2K`NsDLIt@x#h{6~6L=U`w*Tf$B%B!P}b5q%%1 zUC9@9NcAG2w2MS?GViW?{mm`>zChsLe5)ehpPp6*c$ZiOlR{qeD4N!QpHkRXwVgQ4 ziY)_1haj|0ZZ{74@5n=7x%)O%KM}sXvQ}R754Ia{RmWEo@G-kZLqAzixN?K1-P>sJpti?mfZH#SC4l^kZkki-9Wn#eJnIo$Fi77(;MIl1lTmWYbpeXgrAW(OZ z?(cCEPu=_XSLL6am~Fb@d|aaDHjV&9?1glr;v4OEZ;AyU?|}v0JEdK=+-+%pugE>% zlY6p?dd-8PCo7XabrlOTgCe8ywO4a$USvzsI1X0uA*8)^*IVt9Vrl#}8pKno!i_MUDB<`F(7WtJ11*Pct_~@ffiTM6=zGD0p za9lgrKfj)(rgj(ISJbRoS+oc48D1L$%je7!dH5Dzm);C*CEeQG>x^dSQTxghy8g(| zP~=Xe%4#?s$Q%GRI|I&YTAcbBr`>IWkC#jKrcriQm&En*vL;IX|IN`^Y`F>rQS^ft z;5G~r+zB?r-JP$0^qcldW2vgMcM>l4^WYlcO_AF;2KE`p9taDY=%g;MY-|AX!NS&@ zgmr<0Gd{#Obku3{P3r_oueF{tj#L_N1w=5Na2wehlNS=yCW84YqQ#@uEsc>{G#*(8 z{Zc;dZU68Gl9g&L;`ii!4Q_S4x<{@_l!ZS0L=J(Z4ShOa0#+MSE3=w^r_Xy0$yCu7 z);mS3I`J>ng2mtGGem5uK%pG(n8YmV>(#-7_dmYZ09V5njrJ0thk_r8s%ta&M0Xy3 zuhibP=h;_Fc=J08HJWEZpUmEyZLlxETdZ_+Q@Q zh?3X}MOOHQ2mG_M;j}%nMQH`FQgyM(0N%pqbz}GI!H5I{!G%G2XH;>!DJH$KQ!A|l zX_H5ve@*QN^k=YDQ!ZU^?gI z!Xx3r(b|wkj9%s__p<#`pYsEhpaLoMchdX^zLFE3DE6_jmvCx4tR=!P9WeYfziY(> zP?6li_&U>|;(3zURI!VP_S?NxV0OEdkmYcF17kLVpA6Tu$vBp^0W7()Og^Q{dF003 z)%R1Ezyn@jMx>#jzjK zWKG=2$QXD|FGZ23W_ApdVg&=YZJ@4WKf2iL`r+Khyc@cFJF+!iE~jUDV&QP)=(LOg z13>)0B3}zv?*b(RE-=|RLHSxTbla@pJ$6h^A2}+o&rLGR{9yvVwxG4?L+TK}?@@eJ zFM1?L;Z1>b6vsO z9W$8vpnqTN2Ub%*9U}}A3XK?@X;&Q+A1I!ppd|{rX=m{33BcUrlezZDDofzjm-gg8 zp8zF40{2uCNt`Q$f}dk@4S6emh5%(l-J4*q;?J_FLq2IZPXxVFpiZ=O#-}J0u^bE> zZVe0r@09sC$AbexT_02lymDA|fVQ(RxverRb9g}GL^lN*Tf3&`qe{5ClaCoR9_%ckPPJB z@ghFY@4F6a>sA$?qYyMgwMD&XTSNKW=O?SA1AurC>r@?NWe1}C^8i~tDa0D5=^j!s zWE(#jin2H`kA6M0Lw=@?M_3I^70Zh&7BS;xXy@`?GfcCdkl-wUwc#0CbLwWhq=pTW zv>Vr|{$sMz7Dw|?XUlZZKPUl5sX23eMh9_%uRIjJ&1izc{|Sfw&P@vm$5hgTZ`@lT zn{D$B#h`N61n(V?95PjI!(22rHV+w7?ECumb6G|Grl)4P0lt^4FgZ8jDAuO=T=R>K z;*tCVK9nHNAs*?leEeM55!muDPdSf%0$7tjYeK>zXaQL;(JG zO6bgkkOt^o{kD0;&w8c+zlra%rE2azf7_~3e}?BM^o~^Ar+h^eD<@_}mfe<=AKHua z=QnhOX`d+p%`v`rjb{-dKp4XoIx;5UWSdRnB$@Y9Z_noD<(2*4`NiD zX4C`FAu|^>&z+#N`?8gDkLjrI!>Ce$T59XWL)c!-ME)6_rJT*atn>JG=hf-;8OSNz z3CTF81S5;=@#8|J7VZ69w6ej7+gBNkX2(DD_q9Yv5QcLchcFV<+5vG6Vvr6VyqXtM zgC>+7I3uxLQbz*0ZWO|sdonD;NtN6kg&>FtU+llog9Td`@;gpE3XLyE-qWRU3c5WCQdny`WpYA#+qWA9lT^N%9v05s=>ZP0;_QJ zBUm4tYdPC`5G(@F=4^81_L7b) z#aTALtR+O>KoOcHm~>_$n)752a#L=etmv+@Tc_|j>{uW`Nep+tT|TN{>o{AHFl?}* z-zY=pe^b|I=kcOvO&1ow&N^%hNg4D~ji+sYI06D`BV8}w?kOphgG&nj+?@$BZlS-0 zg!4R#y0=K}@aXcCm$BZY()Fy=%toca0snFv?|}0hacrhUDH-Smo#ld?P_m_L85~SI zJ8IL2!5I?1wm~%>8)@=^Jd?Cq#3EE}OEU_|y#06K!pee$dJ6PpMck=yPja{uPs%|$ zzC3q6zIy9PdsihqnwIBh?%SDD?`tSqZ<)ErXnO(KZ31RWZNE(rbEAIclrjKMk+&5Geo> zxZD=LdBsAznR2dW2D>jl2ji&?re7Mf|L8#z8TqYCgr-41S*&WD+>owNq3ZW*w@ZM- z18I@RHE{yRQ5X-EWhO% zp9(YKstK!OPlr6<3ybb^mYQ;MT%HfxZGg0N zPTGZ>!Mo_jxKO2)O6q%r+k6D4TI1wHowM zKW@>zHFn*?n|NDtR`uNFmO+3Y%pnRylniW`$MDMbmaQ{oTdL%n+jT_Xd79w$dF}$e zkGTiMRn5Ps9p&&M7)A6=gVx^HFFX3?H`FM2z-d7}y6$!UBm1yCS=o;e4&F0g5q~+` z1^wJYRHuh%_H_}p0*rQwKtB-dXLs>K;edI$M02S2hd7E6-9@J5q1UxS=<&Bsk#l*w zE;~26c4l9{Ij2qVO7G$+z;K}Gbl@`C4v+1{I+A-FRt;2m=jZQ6jUeZ|4aroYdl&fd|+Da6V31Y)m$GV&)OK8bPS#;Ta72NnM6xlxm&d{;vjI^ z^m@2kvgl$JDn$ezPR}eKZxA6P{EYPQwsc0yb_IW zoq)n^i0;W?r#+)Xx?5LqdAh=w%f$-9hj6{vW_etqoBPrU=A?kRYKKFGK%?pHxehxvm7VDCy>aq8c#GQ zT_04|9F~7hwaJusN)zzy3kKifV>3zOG?kFSwuk*<6oW3bc|}3z`$3l#FA}uw?P5{G zLr{`3#y+@-yWBZyj)bl%02O%jMICEBf3-Q-n$xJC7^2@O|9VqjgT@Ylz~6dpLaQA>dC8nhO_?SY zQva71;%Hk`_)7Ir{gl9>`ucwKg>n~p4;1;^W%In1J@PsXdrwhQr!!=Hrm^ugtaXjd zvr_LN)96R&bWgDTR&0@Ls=rOwaV>mZF0lzTtR$MYYy($8-l!Ysk7wR0R#H&I_Q@QJ z)zqBZ@St8w!QVDMbeKg2a*T8{uRNG+*BxDXHR1UK`TKD(Nh>5vcamEtXb61a#234ZIo%;FVT8){sgA0Df8yz?(4f^ z*x6Yo&Zk83?%#2Bb}r5Utsp!rU%|CjL1X5Lg!*^PV4*SQYw~lvh2P(lTo0H@PHRT} z%s*eC%4tNRc(e+8*=#iyE{~MxJkv@c^~*i(C*g{I1?4GKFsU-02%N&|McjOODqA7I z=kxhUA4azM@9&tJIf?JxRze*b?5}6o?F$sz(49nIsZv_OdjE^fXYl<_SeqD9ko&np zH;!;g#MGliM><)g1u_DhpThy#k;qh@d)nWvxBXa?TITfMlXEd0`?}g(La5pDxchRv zHQCHsY%$b!t+NF!@+M1Wa`4Mu;7y1YGgBRJualrv!zgKZANxTyiSVyGP2YzzQcg_^ zX%2g{;nxk1J6)jkZ;42UCfLAyEQ=Q7bR&$7+$`-zp3iyEonp&KNT9YA=s@-&-NnwE zUem>mzakj?TRnDJ8%FqK+M1X&O9~-1<#=O2pDRbW0%xpX}M=0FM)qaDP3PKh5ZJ2 z(sb6h@|;W(y-+fORi09=W|XJ)D^tVv=QkIk`uH{rRzl>5T$Kfs^rM~mpB;ejH7hvd zC0yWz_Fqau+K;3LCET6lcaKw4+|8NV)eE&E#b_eJgn=LOzaiQ7TTbxrJ=j|tx4zrT zar?kH!^Hrd=AIk5Z!D=U6@gyl>*q_c`|@el-&g&)H^(8?w6F<7wzmx7(*Mjf5<#G0 z>%n3_K*(?$rOOU)dw005bkx6#tVJiX@L{bIDUV>YmAk5CN3M2R5Vf;dJ*=0Gqk0% zM34PE3ufTVWx`J$gt^2|9R3_f?zWXk08?`snbzNtCJYCPRNTU)J#?*&-ibHj{2 zj{T12NDyaq$RV8zBMa6{@6HJP_OBK#kABT$S{L)D__cw*u7H(@X=;|QOf23;RD7}` zZ_zty0CKvEb`7`unP)}vEl0z?lgBExDjZyY-`xE zNbdl?+pd>Sd8UZejGj1QO%0S%GYMZ+i2Z93gJiFQ$y>-fIzL2HW30L>G`3dTNYbAF znu2B6FD;8x+LbXGWx(q=f+>-Z_)+Yzf4i#;zJ7Okhf6?h3JiNdYavY8(RWjwXqazH z`@4@WqX-1@96z*7P5By}ggSW+kr~kLkp_AX?wG<^d%4Ivh;B$*Q0!()0ya7w-?whM zMl^dGlf7s7Hq`iQPgE{yY;TcO!w`fWikM9G7C>%R^&;{I@>YSXcH2y{d= zYRpDQ6ZBXX`@-U@L^@OsrrvWUt8Knc7f}3iIQ_MnPP%v?xB&G;(Xg9xRTJXuo=lTo zMu7^9%Ype>UnU|Okty%VNj6^oOg3{^92f&-VQ7dTB}J!L^mUyj`-6FMC!93***Vfg z**QP!F6xzFki! z&0KQJroK$s=|P#Kc^6fzlmFOUfZ_-ulYMeIB|=Xaed}cqzIpVr$Lu_~=^1QtWel$( zePXno`o15x9GGB>@ytQ!vHkspehX>x*GaxJ*z*3t+w!D*Ib{xX3P4#~tzsiW=YzV3 z{9dsja`XvWjMVN7dLHV+jS@K>^0oc*hMCt%{1v(sFbsD{bZMdarM#ja%6b#7(0S6O z+qKd}z6wTM&2M)E7l!;;9YhFVT5T+};oI}2!v_#g>7n0wV88S+-)q%+^=ALZxbC+o zP>R;LmiC@F|HAD;V4^e!3Wql{R&jS-8SVz*S_CR~XJ>)7;sLjaZf>~%*Yz>&t%mMM!i4+~u#AteYq{7ihF75;BMnwfb=ey7(F<3Xgm z9w>rDHlj=&!5ivP$PT&%B`8;I1|(I0yyD96@n9g3zA9Ucp+e{nRAgLS_{ls84Z=WQ z(8U~>8qtM`(A)t5&OTDYb8#`!C2Bq4KcuxT^;5*x-U&3-m^KZQ7uvF$;z0(ZPl_;9 z;qR;q>jS9hU1zUuq zfj>i|f{ZjKv7(o6v#qcG--wHq5Tr}aFR;oV7H;UnyyW@AVN|{^V1hr7^c)UprYzNl zRv#`wwB_kuq0Bn;0~kQn(EXf(kELJcxIFu2{Il6Yjd1sYleu>Sfp^n(m3~KUNf47) z(Xpoj90#yWbo?<|kJ$ahkLe@q*{@f{_m4|5Fo8aD-ul=$ZHe6G<;Fw@vC-N~G5Jvw z?tEu~4t0c9^X^-;!2_=C;scTCiz{77W&U^9ywyI&2~`cYHPGhm!<_NGE+uCrGeV;j zxHzpqn1lcClaQtM40_bKOdre{oXxr9V4b5XI8k9#df3p!OlM7zbi+oevpdKa9Tp1? zUo{s|S(3C^RBME=RX94+_7S1(`t|$o>4uIvqF*HHi*`xV@4~0D*qr6=)5C?fieGCj z8l4nWUH}^BLQ<>}x=G7m{~W&}O%oY^8~Z@LUWrton+aOx0;%O8_h}GP$NPg~rBPwg z`EA)FQbq6GwS=fBN3)^BmE;o0pBK2dsg_eb9cB`0&d4Vq**&jI=9}?Rc(Rbo&fX@} zKTFtzE3A7C$gLD;s8$tlTeG#kN7JVTKmbt0t9+DyC+5~kX=o$h$`_S2c-!iWk|t2d zr|IitQfU5mYx2@Mxp*gPCp@*1m9{ipn(7!(e{mqf^{Lv#@o{SfLi`ve>ETYnkUx7M z>7NW*gVy(5khSX!B`Rus80VcesU(U@nqrqGnS(K?lbO~XPoGVE{VhPjmd~0%LG?Ne z!{V9Yfk zL$TWQOd@I;MHSPtdW`olsutCZoO*wMxv!vo?kE{`duJp7I5&d&msRHzd}qT7xqFk_ zJ0uN7rhSHfdWOFh0M1X(7{C~*)%r4*7D0bM($$!!aO>*7oKyxXaKH{od~!Y1mKaX4LoQ_w{w}ch=WxV6aFN2nl+8A#%@T|?>h#Sdm;I&>dR+8aMg`p))&ZW_;>t^LkVG({JG%TPB z2u*sta?0*m@#NN$6>lB5mST!$69m;^q+J&4!uDF*a}>o!^F5*#;#OtE%MBPnJ(P+>bbaV(mg0FUg5C&)Z4g*w-w+k|HQul~O#-_KaIYk-mx5?<3|2*4?8;xXZ zeBr1KmHjO*!JA0#m@NGA77`Cy1%dkGvC7Li{X2SfFA#2vnz*BsxXMXXWjPSSB4L5$ zPBEZCNoHvgDNE{YQ_WZkJ+YPkZRz3LZ3F~yANmdL@u;YrFy8H&W5y`y=2O93e<6=n z(3XQ4THKH;h+O@OQ35qjSQI|RJV17n5d&-DUl)5jB=+XW&{*KA&SsLnKeW;lZ%mQ0 z;v+vU;KJP{XAPV1K~s>lvb554z>c$NwbaG zMDzeQ-kMmkjD=?@#OapQjP`BFb>K|b0oZyrYkOAV6XZQmyq4LQBK zFYA04P4ME!a!9nD%}79Cz6s3?%n6|i3<@LaM>Qk(BW2`?h!X~~FZ=T-a_Cs`BxH{A z3~r0z7@PbD6p8W3U~A{wo$@5&a=Y#w#CX1gSTu~;>sD;XrQA>Ook4G5#;^0uTzk$f+)L3gn)yEY1HB<1HJl^>UWG+EPR!IRRPmT_*f$PEFix;LffT#qBib0A( zhe=5sKDSV4Q>(ri@AU17LiiHP^eElBd!_GwJO*N)RZPSMn+B)XBnX~FTVWIaNC}3? zrz2w3Z`+LzX&PmJsK|2Cjy{Y{>g?qhgxfo)P#lTbRrR;C1r>!HoE*fY#xaBf%yyTw zw5=@AXGR8Eaqe#^bmpQ?5S93!dGHk-LOq%%o%* zGzF&Skb-fPW`?sbBDj1ZZT54kRYO_dCA3Xo`Kev%Q{?!H7@0KOm&O6&PUDk!X^ZDs zDFA(LME$;0La0&41E5DlXV|}!J7cWwZXSqJPPu(&W&KvUpuE26w0~XHj!8c}Ki|EB ze6omY>0|ud@Te#r%mN5A;`^~(Ruk6Yb=2=by!tro3f_tD=fpeP1W$&hvWz5MBbAn> zuDKc|G1s&SScwv)J3YynX@Vvpb$@lZ7{>q|2{}exQ$6Fy7Is@AUy@jsP+}9N1Evy& z5=q#9)G?s^ku#4oO^AZ&k7W_y&)oAd`> z$Y$*Y==8hoNpM8YtikXpBC!?Z2zW%V92Kd?op6|-DR0-tM=!x8RE7K6Sa+1gksewn z-F}g`Wii&s>I#O}F5QB`stY52-aStd2K50`LSPqL)#4g?YS|Q!xwLj`NOqL!C(0#Iy zdmVp$KGBMs?A(w7qth&C#-6^?32x*pKV39lt2vb>B4+6zofrbp#{9WN8+9sM zzaK5i51D-=-^`eBdZu0o4^&eo(M2k*?={-Y2cT#GQOcjF(O(OA+UH>B@zAJhN*DqN zOZ(nFM;m<$WZZtjnD#T8ehp-0s9UeUgW`3*VH5XTT?1v&#L5R@mE&j=*0LIHKRDfg zhP_D0DH}}p?bCo^rY|7M&Vj@4F_*74hP#C|3He1u@okWD0c^?PbRI-D#V0~=!MfD8 znosV0Q4a}9t6&YGJ_EAz4tLcgDSF({lq3_R_ivwT3a1}<-qJ1+EKdqntp(sM^v&&0 zwIcM)^_k05>H%b0BOOzjw;&bYZItQ&KndS$m%*e2|qg&nkDe)L`=&K-^5X+ev@zyCL^_~Lgxz*wAr}FcQaz6L>p85^`T=0H3O0H@RKElu6RUfc*5A-q<1}lAFsD|B z6JZ16Wc;C6oF7k0yBll1z>&|$k6PMnuQ){J{D>$9QpgCO1)bmp3R5|{xMU+*;H8X- zKKrH*JT7 z|5M+2)Y-kfcWEy&b~y==7Tq(MoIk8ZcE4Mx(&}-gefM$$<2BjeAUt|VO;>t)RAc|Z z1&!mMLjrf!G|A9@8-}LhF6{z_^mo&&-A;MqmjYSel!HAMa;8^wEc=+hvaB8=e{&~wWu05_pn7zS)j(GF0}N7?*C1FNNjI;7(%zCf#5mc~MsZyH*Vb>w z=gOVCx#ZI3%7r%61f2N8*aFSVrt6(hZjHq>c=6f;)AY*Ey~mK&pt52mE9$rs(dl>c z5q`r@#yBdv_;9WU<7esdl&jr7))yo$s&pt~eo^X2?oPrwUrhP|sJg8A&xw9+xQZxQ zwqD}CiZHmlpnsKdZ7O_kqXXJw@zy}~LuKa0MeetVoB-V*zs84Bud5B3e?K*zAwE*_ zOin8AU~{?cvgI%4jE)N|citZ6=?HA)aQ#WZ_nnWpp#b`9P{tOuxlewOLo4M3y}Rh=uRzs~7_8qo zwk0BKB`R#zHRT#}BdpY__$KDLc~YaXT4ctTGv%DmfN{)FArmomT9rZ5ECo|4Vh6zE ziY5dnjF9xrCR359kaiQkF6^_l+JG$8PoU+O%V4?Nv+Dqd7Q| z5I9xdRVewEhRYfx4dum^sS8HD8EKn+m*rR+#5(tf&Ie2PaF>-OM4P_HGf;qU>jAXP za!|PH-Wz}CU3gzN)u2o=S{NAP5_^Hu@cIwQr6 zH!|RRl}NN@*iSz$?{d}7ybOb*0Dy1)_Nyn+@jNjhq~Et`ov^y1Lk`Bd!Jf9c5VfR~ zdHsIMobB5pRF2=yML0U)&~ixJ$Gv_{-|!MeS-MH^0*Ov-@E;^TIxfdlkG23 z^#_gjUYb3D1@p)KH|lZrfjntBQ69Ox$D;p*sdQsx_Dw%N{&A6Q0bzGfp*#8FI({=Rz)%)uS_oW|EXu;J^H(?1T;jA%#HH*a_Q6r$A*fP0gRyJf09@x#w{+~D zms-HQ$j1@usV-R+K;qaw90Ly)bwSg>*IjeaJaSASJw7()>ot8J5)EZ5h36*G-*#@^ ziCVXy`S{zHBTp{C$p~V;{M;1PTI%~P1u2FVyS7NdHa@SgY^Q7&p;L^=HW ze!DT{9M{!eqn6?sLMs+1tW6l zDU+?UQB7b?>(1lSwI|`)3;f(zc|r?T~_CaLku_Hw9G=2FOaYo3(=#3tbhx;XQAOz?2E2 z&mN55rK7S|3{JHhFC2FCADV492Q6$)_ZbxKK>S|v2^jbtAprXu^%%?PGm$)?MVzvB ziA@E2d~q%4U}fN;W)K3$92Vq*Fd=#*kPpVD(hzSc^(acvs02vifY+rAotaQ^k`?`f zVKhkIdYRd@i0m&Vn7i%f%R8|(_yTe^v~SpKH^*%l4Z}B0gc@6Udt}ktz@)0{?@=y4 z6&Ie4&qtNbjHUn5BRU=!g&4_{odcsp45(VdPO_1VLf$CX2S z&j~Qo4c}m@Fx-jd04|F)0w_IkeI))0DQp7JUxfblEX2ue@H;^)st{9EGOklyXBQX_ zU}4Y5q<)sY9&iau0genlf47S%f9q)I`zosrJ`hk$dly+=6D8Wk7#ibvSPy5!`f$vP znsS=C#Fy~09f!I@^2+XT=G#Si&Py?pDWW0 zwGgcZZL>o6+Foo@glq1MHvwac{ApOZ-tU;@IUGz2c&8suQMh;)L-Fw&4}-BO`(r> z#rXb}DA}*kZw$M+6WL1@Tfx1`GdA8cIIWQGjV$pvzr(tharpbKu-x7h@%1tOWjvLq zY5E6&(>z<6wn6Lg;GhWub*+mNN*84lHy)6_UeSLh3leYG_>!VhKqC|vj4^h~vuHx6 zuj-k)h3$n1v6qC+70Joja+$-JxawKq{t6SF25C)W4JoL7lb=ucXk0JdsPL@^CP&Z) zY4PuP!K3papM}NQvZviE-uV;0Ks>6A?#5?I_Zrg#@^>E(+~EflzFPIAn2?%oLH*=M z{UeaCuVeO2El`IU$DH*)@%t*qOvzre_288b&OKi@J@jbAL&3*c)}e_w+ofwpwh`E_qsHA9@4DEr&}-A@1$Oe>=sHwiAyw>V0w1L~fmlO>O9 zdl>Mo{I&tq(4v9I8%c;KA3Khzo{LjRT1lK(l>a>u^Or&6YImdOJM_!05pJ?r-iD}4 zyU^`W`8}iEUqAj#^6$hd{m1)%4QNa>=0@s)YA8TT=G`vJFT@rHOxw!sC=c%V)lUE2 z)Bu~ee$o6Qe`QK|M6Ys%<0-%$_aC#EcQ8aj5Sq;)`+_+wv?WUi!>X^B2uqbr*=z?H zZ;V{S8?xp_8*heFR|aNR9|RkrZLvDq9wl5E+EIh(VaI2CY>whD@b8iII%5L1Lx+h} zG>UosND8kvH>xFgV&IQ%@NxV+iSm)looY`RH5WKjk%ZXbUA`5*IAL|KGDLOU8K!Ww zcx}h2mrJ!x2B^jbK}1mo2|RA}z~7e(*Lm~mPs&k)Lr(VqS@z_L4ZRl_UtqTZoMBG! zJvv?qN2Rm?de0bTNi!%&C&2Daa4NcY{vItEv6xdBzjMJf)Kt@ph!>Eyso_HXGSu=3 zqK-Uw^tRV9m{QP*5mF;`q7_|#CeFt(Nnm1H_)~E#g`$jMz=Slva8m+?S>e!!Voma)fR`SP-h3nS2bOgh`*$0i)qk|F0;O%v0`F`@YS;4x zybN>CR;d^zH&cCjn8KDy1ShJ}rFP%vf(D%NrxhRW*)c!;96zt2IvT*6mkzhg#Nw|B zmXR@hmcfc(bZs;`hGLbuPC~|(ln%@Z6jz`Sy2OcKtH<$ z*i*2{{or3sVPjnC{$92NoqYj1?)-8`KzP)@$wx{;Z;?B(MR9{{u-ptt7K=0$v2bXy$ zWym1g_W6g#bfa$5x9jR#zyjnagL}dee~*F}-;fE%2tCqiSoA_;i?uZQ^f14;BUPAX zo}*!59IJeBv2VogEL3o4g028PIWkTY`?o3USHF4j zPF!AeQI<=7C6!ReZ*{=WGM^?zTB!kK@9<5L>9aAh@C({6Bakuk>-}KFwog{VAj27S zi%UPmo{nF5ZZbrC&iTrh_+x^onq^It`JG0j7fEi~(nQ-aLPoZb0puk6NDF0)BWj3O zoWD_B#FKa-KXE^>JVijmWp=Eqi6G^@M$2v4`ti;8Dn!Jm7KWD%X;S3q0=+GHHpu?N zF3LZS&SJ@N7>c4FwMZ_4MvJu1F${R!%TxX#yf_X8($w z6q}zwMVsKrYmAiJk!=!>OjzUPKN&x~1d*R@B5Gm$pm8mbG5|yuC?Di5{uug$bf1sm zWfej-#A;AlihqGUNO{6Q&TzX>Wj*2hPf0Prod80Hnz&kU=1E_LFjUyfDH&%mH}Zo$ zXrZbnp!IFF?$MLi_$B>7|M@hE!&rFbdQSOBiihI18vvD6^O6A*C}03U{7St@mld>7 zRm72F!ah_|ymnS}I>3MOjOKGP(JJ9>Sd5V0E{6YDvU`aRdgw$TVu1XvikT)Qo}1X* z11jc0(t-&4n1&LGLTQnFKG!$Ny-t>vu_vq<=*rgbMfk>fEsNyJ9Oc7K_btivKx(X$ z$4eaYy^PmG3HL1obKGS&#CX3t#HPyWZ);6N+;b^t%?qX17En~uo6$DACc*+m95w?p zHImm6Vj}y6J;)IY0kgpFS!PTPE|oGvF-0x4dT_~p<^#uzVkBx7+R@w4^Js-{7I_ZcE1Ch3nV2ow z0?c9x(J_9Vqnft)imAgU5v{|EUQA)|_{e|xL!CMGcGwdp3{+hT<>AbaM}UVoKYW_% z?D23udxDIQBmCnQQ7^2S|_z?Q@K@hzM%s&1|N=jJNvu>fZ_3F?=>|NCn9^CTsZA~iP^qVJ2 zK?(T%2EOPIA|24Q;GeweWsVEoRnIQ|`NrwzR-`4oeGFofMmxce8}yjNzvG_;;$Z)< zvS!e?AD*iazGDJt;?NQW#>iL+7O^=rp1GVsk#kDaNC!l7? z2z5*ekOnKk5StQd;6VUvypG>Y?QzRDEwSn4tDMOL+Wal`qE^W$q}&1t*oWZf@A0LA zzFKq&QZC826Lh5WhA|a3C7tY2DqqDXoW|;rk*X}n65|fewRigUYH|)1;I?t|Zm9YH z+}fv=RqD)MuWSVi2F~^C<5ky%f_kCc&>ydlwep!v;jp~FJw=+3vS;Hpr>7_mlkFqZ zt${Dy^p1SX6IqZJn5DxD?NiPPLig|;nLF{#An+No&sj>GpK$#Lf9H6Z0=u5|Z50bX z1f(DCX%?DbJ>!hCL(F7P+F4i@W*qtbu(=aTdB^kFOjC0tj`N(>d{^3^hRAMCj$a5y zNSqdl?QZ_YN_xji8fA!0R*7k?f>h+7HIDPp$m8=2F8zW_PH_)GWd!Da*(mHh*W@yFI0_+l30OWh-^G4H3xKZ)QNh zD#boTYIGMl_omded?3EjZVG?TD&qA)AeuDh{>zuJiMvoKRW6S=LEaT52T?g$Ma2=w z`GcUpBO=5%v=C4v(QriW+1Uq*&O;D`E7#JBW_Gg+=x7ZW*$;f|2-{8MWB`FAm|tE6 znKMTsD9w{R*#6E!;fmhMC?WdJDdJrX;(T$E-NJR_b+ZIGcvVQ0oiEVqyD1S-;-Thx zQ`gynL5T4E8#NNnie~TsgM`kLKOT_k8Yw5hmbRZLQ?}ZV1VSxY>&4hE{@M} z7TZYT;pt=JnYco4<|F|t-Y@P1NOlf2sLNk|*Lo*hqSs2k!0_1pOZ>-eXssITm=HYk zSxUK4PxK?wfq*1fZz392lmbQJ(enVTpOr})uQaJ=#P{0<(iZ5bZi+XSV5Dj7$Vk%B z&P9PFeFvMMBLce={ahoV-fe(b_x5iY_%$}U^|q>Bo9ZJ*@^i#*wRD>}j%Lhb+3xJF zcK)Q8g748o`uB)H(umLH3#v~|rAUQpjNXsnWTaDxPKx`naKcln;iZ5gXz1~i=#0`b z_1FOjdubPQm_?0ezP+eDE{#o-J2|REDWMR1S{x@J!2t?md}V1AOQXjWC^uQwCGN%> z;o4a9D<(KA7-T+5x012%3VnYK4K@cszeoq!BiCP7rKduld_{2X&RmPBA9}us1bl+^ z7b6dHxZ|^s_@M0|VtVDQpP&o9{ZUFGw@-kx>-@0Kq#-Sd-$nA^)4)Wbp+5TAUdNAj zr=%Vii!JI;Vz);XboE<$W~RJsz3=R3btn1dzDJ-$TXNN)0wYF+QHKgcTkQS*%b=oJb0lX?7~zEz1p-d~r~qh5NpzLuXIf@V+1dc7C9I zF(~QGKV2FfXdFI+abfI10i1y&^$(S9xCvV|qZ-*hJZx2-49;|AD3?Tz;aZ=>JE#}FYtKxf`m0w)I z1h?Th<6|kRt{B4j0xw_UO&HQT6%7WPNY+e>Sg5&#x-LnMvW0X;-gv4nQof!|(lWt> zwae(G1RJcOJChI+a}=OkecqY*s|v$*EL4$&Xv&~Gx6A<6{jRBu&WZ4-mJDar4YT;v zTUOK$MO`3-Qj=kv-9XIMHU`6+_05Bi!6EKSXnl+eg+Sd41yJh2u@{|khdFLqy~>^` zm_f=|GUu1pVXzD;b^Xy~CG}le3*zXGRwK9&1oEzj*_PNwi>#gyUpu@-cQq1ZpbR@SW)+p*juHjI7CF#Fk8_$j zUBIg)O^nUv+;5FGvZ)$CiU0v;fMqMew+PACy zEX#%&J-M*AofXjm4ynddw|ax|p->pIg@|3Ow2RQuG56s{jW6q%B(}=GX((qKt9dL= ze$`!qHJwv9TJO!Y>5LoFO(vu1R^M|qVPFZrhYL6Y;`TJZR?F^~s`qMY}Y z2vAzP1^Tvdn_T3AxSfY`bZFRM{W^6$wQxD9^X6;HAi9TW{1;(y@k>9cY@s~ zcaC;KV}@=7M&X9oj}T@-DMq0>vw&^EVAtU18VlfE(_&V@gBI@QI9h?MlTp|QhUz>8 zi8NxPq}@T`>*rwe>U`jg>ZIn-EnL-cBrb+qf?*ZvXxij>YSNKy@kOb2Vn>! zf7MgX7;PV2-?L2!U}8%Fe~YS%Aly=|yW?dOvRn^}-3xUy@+YBf-*KsHOQ<*zO`P9} zmF16#vd*eC`UyDaQMHGx%c0wEu;EVW(fi?a&CgOeIT6pgi|eq#6ZE%I;LphW9k|uf zCsf_n0(fXL`m+KstSP%Byp6Fa_wRX4N%zUBF5OR#=_}ps5i+Q{U<-c*TT-Ylru@P= zOz|<6QeQ-;>Fn(?3CFkgi2R5)-i#?uhWaeO$tW?!?@iPT9Pq!h`tag6dHLH-(8)8S zFJ%`^ngY%j;|oRA1Fa%~nM2@&7Kp$ZRi1!HPH~}AAG@xV(K77q_-q%<*amsjW4W-&@1 zNT}^uof|-@?9a@zc!P9lfe%=AkL!oaLcx7NrF4mgoosxxQPg*lvTQNtCOebQoi-nU zAODyHU1vL(^}P?rC6KPCXUGIlL0(FYC0)F#)bZ{dSIpj(^HfN^84F4-AtV3vv(d`Z6tpT(&y#DiObspGMd zKI&29?~nlYRW0c`!@{=`4EGuIyzd0p_oX^Pg1d54x)>?sDD65Ca!#x-YiQ)0dlyFo zC^h_ zB5dM)wQ_Ted+ib_zbhl7*&QGst@113drH3>1o+`xqFbO4X!IRrnmNv{2vKXl+g;>+ zOWn27ZT6Lm?=^47b7#$ae{>{yJD}KWj=qs(wV3ScXP1jC#Mixz-$E@HahoHnj*=Kr zhA4*^dQ`*&2wd@#vBG#wyDXkTUShC)zj9?mqT%+WuPHs!^*_9STOZ3h>(Sv_8v%LR zNBC01LM)PXoO8aPxOVJ}zJx4H63fTmUNRm!nfl2p)Q|VN%r_Fm`H@MF$=$<#ajEH1 zZDUDeymkLG=xe6!$_;%ch00@rRFsD`UuOT@I5iw!Jsat#&QK(Xf`=62Bp}9L8d|A2 z69_Og0T>ZOKa_@&U@y17t%e(+TWwQA3;U4f==(DmWQcb$Kly>hkRr@&pzsg0^6;GA!8b{LseX#<9|4`3I{R=YeZ+U z)^8#TTmtirxU?wV`< zQ(;vjtEo4UOGC_5P?ZwB{r*;|BcL2XbciEzh{Olt9{hwmd5jwRoa0-jPIODEAfc1O zhZKejx_Qd$N#R`D7H>go>Ts{*pG!ygywBpa@})%D!lJMs0+gysypT>>Fd}s=RSPHd z7y&w>we4o0Cpa*pcD`D-^^8EVJRp??(*!(POC~N_SQz(Xxh*2ckeYuiI!|n~DSg52 zQuh{n^j6MHWFVqUrv?kn-tMp1P7p7YzzBb9OR*7W(r+5&fVb2vw zt0jR)P=Hq^{;!36$?8?(8!EYMDZ3QO9D>^?$wlP358g}v4tZgkmzn>tobO4TtlYQ` ztNSTj2``(v>~Let1B-+V%tm^c;5W-o@DKILb2L-Z&KgjdGInMV9*Tc!$$m@e7ybM&ahD{+ zsT=^Z&jDWGW4xmbOd!wq7=-}?UK~W;&w3YRf#)5Arw{WOEJ!?kp}i=bJVNZ{lJqmv zhZgG{r$=Ama_yn7%_akH5Q9Zj)tC$)1#^>I%zK8!frETu}# zC)nOrX-I?=whqNl?C`7s7G?RhZd`3%VU{P#;b1>WE9_3&S7GW6xy zBqM95omo!%i5Y^n_{EV^mvZD^*G4jOE?ZnuIg9zOUi9@@4~hu$8gmTNCu+T!kP(6K zv+PcBxVfzM;=mk2uf9)6Xv^zd1w17utueDvLoI9B#Oaux7CCJO$4ISJlv`a{NRYnv5(e2q3Q`y}4$2lB zqh9j$D!%n)ENVj3&$W7&=$TpQ&T=a#+U-0>plEhSTbMpI_jdJYmGOK-LSZA(tD`6F zOK5#w<2qq#(41M4H9GUh9gnTh;*aptvqekd!8o}n40RVy%5ZR&@MW=1r4_tNiIo@_ z#1ZtPu~47>Ca(H-umR$DRchas7Q%a;5$>I-Ci##-fc<(rQoBdZr`Qpt_XXt^2e;9^ zji#2iFytP+6Swok10AG3mwZ~WcM;5R-#`8M8)o`fF`HuSMeQ|L7QvyMlHu1~pX24M zT*J7#U99gWAoi-v)A0s@ZwK0km2^OYR+rqNBtwXArWdooZP+qyKs5=I{Y1!N%v!2_ zud692J4m{1>c(^{)s3m? zOQW>1+B|>r*Ao^^3QY^WQP}P@^bZBiS5h$fQQ~jyLntvNSIU*9=Iu*;D$=v)bRc=( zJc{u?!a(Hef=a&u!(KdA(u^7r8^ zkVm{cRO_Gv9KOM`k=ZFBgnfK7;glG9Ilasb;V=OQ0rPiuPmN*Qt7sJ-GKIAcX2lQA zUIbD8GF%hia1UgZm|&agKT@!!ky^>1t_yr4%|+wa2@h$!wPHQcG~FuY#j>cG9Rn0} zTd_gs#z)K0x6ySqqSS(LCpX6WejVYx(=e@Aeu!R>s}B!1_&2xUVtyKxbn?HAHXhPe z-&A!K9myp@f9Dq5Q)X~orcA%tgh>x67VyBBpdUXz@|Ihox6JHefecT2 zW$UpUEcC9(30{$Y^Q19iE+aa()t#Inry{)=U!Gm?CzQ)V9LNVv*B%yLQy6)wj6B}U z1YnNjn}k$mSip1SgDAn338v*#?wLPL~nCZCsh(f6{bZIdyLn%sRn z)0~p}I^LbY0bc~J-i8m`g#JdFW&@Jt0RBYXqRLkDhkQ^0!I3y50-A9BqpUTmM}lK& zbvv?Whv4io(Irgca5jLmO)SU(jV@=Nwrf0{G0sCoS}A~o z)C7_=!cJP98#0<|XnDaEb2`dMDy_tnkd+N9^yu6va`&=?LM)6N`hV5`7&p~On9LYB#@sl=o=)M z_TcI}xjmG75g;BDDA6&J>#pZXA0Np`lO)KAa%1aD3j9ImaiP=EbA5d8Wz_zj-0Cxl z7{6v+#6OlQUOvNjr3t^KGQwJ~U>sths}?GQMoiYnYAr5OE2dO>r6KNdZrduHI)C5FnbW1@0Ih-jgBu(}z;w5ziz&*wE zX$@mHijYzPOza9qF1OLHZBkRKeY)_FPQDhBP8!6_8*!F|j;No$ErC%jd-sU5eE3JO zG_nPly&Wp{b8GMVaU%X{Q0eF5hWG{)=!eK=nHpS`)PiWegfd;e(Y-X zJLGNt67*sEKE_bN#rAKvZa(?p9F1bQZpx=M!dSqqqdojd;8mhbsWxCa6BfI);DFUV z(9T_D2$s07e99?w|x`LyYxRVaKyI_lrDIR_sPNr=C{;@LfnJk|3 zr9rG0H`&~##aPWC8pJ%3yEM8;pCYcQDE%m{rQ9OK^NmP9R9&ln8?qZb>edHgtGnD` zByb~*WEBi=!&R(Zi<56KwG{cPNVdX(W2}f@fR~U8m;Qcj*ZO(v3V&>JI5A7#4d7LL?Tb%|+On`hYV4c87uYBfQUlb}Ax>PdHvX-$cq(Bg3i`kSiWkY>{2s!;KHx*F zG&Gw#EZl<;MoZ7}OXnP&(2= z0r@4Avceq%CFM7AXWqSXXIrpH*&P5kK*+yf@l41Dl7T2K(JzV!^S|qnIFG$q6G_6` zO-WEFHtY{J$MXUX-}I9FIP*{1h8O7V5w>|YPFM)tPQEr|2j4v-&5h25crE5D7N@R5 zrEpd+9{&3>7rP@WoRn0VnLbwhYYvrp$x)(xI$Y_Q})P=ISF_(wSh1S3cK$Zxj$ z|wWQF7q{Bs>Q z+3WC=11`>VXc1QlW?5;0J_WS`16dJ>H+X}nBjTGY{l$ zO2&hajBZMj)*xLjk_#Pit7g4Lq25=+{C$l_lRD5zK03W;z+Rp;6mTaNE2TXloc7t| zlr*03H?va$+KL45ms5DRiS_v->e4WfFcQD{gfDJyS)&mgnFZ^%DT9Pt;jt!9!hy)t zgr@|ZVR%K6dMMcF@6@PQokV$d{`OZanBTPHg~7zxw{0SjQ%@{X5iWg-PA~jBR$uVa zZIMxsu}Er6Yl?b}p0SycPU=uVb65;!xleRHNZptuc0{Gn-I=za>mr7Av($45kfxCO z8VY3w+UEIWl%&g3P+RhIhtP_AGmtpnjQfH5Z??~|s(ZLYxFw+2*Srjpe}>Kx8+r8qXZj zHqWPt9HxQngWxW6>ry!055Sei|8jLA0L`>NlPMj|8Xeu-zu)z%yW*#()%_>5fD#%; z$MSZ0dm<@810ea&7h|L$!kn}Phy>y)kSd&*l0I^bxx!8WjxfZPJW%^YLq3fwA4VP> zswXx(!f#d70E~44+eTD=j+qW_utdVtWRhjb1AJWZOdCwRhmQct$$QEg{l1eW6L3Nd zgut7`m;{r1yp}R8U>c+q)A3|z28l8pkcOEg^_)Sj`W>t9+yFtXZnkJ%7#|Q+UN?g$ zAF@Ryza`E=(}6yLhc}*fti)eWAQ6eLe)TKo6CL0_FHRLbrN_`>?r=Gl$Iy-b-iRi_ z+U=nPGG>MpZX)6B#!wnHS~*?FHYvHAKIFtkzWuj<($7kVCDa+&L&1e#pKE?UO< zdpLWs2*%Y4fjj7l(O<|T=|p^4xtr>&Q6Qja(lhUp?Pgtf0NDO!8Vd zMkmngh@ih-wncx>zuqW4>ycYNY$x`kx{%Rv(`W|GXL$Gl(4M|YtZ&>Vou(it$7iqY)TBH$MnUv z1sS`in#E*+#5Q@t{`MxvVg#fPPgy*OWWzzf^$5mfcutAr`W3YnJzzJXJVIeFDwP>f z#iXU4i5K7Ut=@&ELXZMT!hr_`8GFuY=M_OY$jQ&-Xw@2 zDyhd4j1L*JL7}|P;}Pq3#F{EP64m6-Ce`&-)NURYb~1r35%#*Sy&+GH?Cs$Rte>3z zI6sD`FC<{p@QgvUqF%DIe#e~rv7&L~ef5_q#uGXB-rjpWT*sOOzaEi<;(F2MryEgW zUyh)q2z)N%*#>Q6fjh{UnjW9k8zLeOwQE`>T}ej9N#*h{kG1TWo)o8vc?oDUb%a?- zNM8Z+L!Q@C!%`&cS_*Dxtt0*YDLJ_uCrdmS3>st@CBn=}g`pGvX7c#`4In zjT8ya#k>IiSgGca1vwzIW(=jFZQDFiN3XoFy z;?3gv>l8>Yv8y2az=@J^qE|=92|M>XW#5_oder1RQ$9jlq&MB0B$SiC$Eu`1Ls6fB zb3Tc^uS!p5(|2xfkP@KoYQCROG7Wdl$bGE>o@WavzP*lvq{FGiaKP4W_of1lf5$l> zmqb+cV~h(EflgdKdAzKqe9e13zkR*`*HZ$}S%f);na^CSJbb_Q~rU}TW(-$@YLIYH7GyzRE0GH0+$O)q}f)aJ^) zWRy{r1B*1<-~t_=8+xU%0Vl$a*%@=;Z+k|G)Ri<#>Li^T8`p^1lcG1*pNR)y$XuD4 zvr}T1twYbN5d*X?LRPrjb&X>_ZFe&gqo$ahF|MB16-!u4dbH#+J3#c^2@Nj)S9jkTwU_m4>!i4~PV0eoRh!5Z^GLLjA$fjHL{ZkYuVL{e3ix^+vx zRWP*R)heeV@hI`v010_{`O1bsHh#X0BSg2bP{E5wc~d($_}lP7l1ICE_OPmr`!}^o zpJIZB92Q1-Y(RZDr+t0A`;_`lBlcAk8Vz`@cfP>~z~%Mbg$s&&z|3sqFpeFD;r!q% z%IGvehMv@0KKzI0auKxhlEeo;$2lecdiN&*Kk~SOLZ~3~mFLZ;OWq{wSaPwbr{%-O zPpJY2vO&xWyN>V~Z*>`lTO|JyOHX*H?Bn7I_AnZFGEr^u%%=eOP$}&owBWSMx*1|; z?IA1uXfGLjI#pBQNdU-Drtc9jW<3rnHWDC{IE5Ye8@jmwufIS4>j^Eh_M_;xQo$C42h^!L&#?+Z^{ZN#bWYV+( zRP5wLc|66WV|Ct!yr{wMTSFl*uGnrw03y!tet_cLhmWJIFDs`~OSKG_(Y_ijns=;g zZFQon^UltGx|6A&v_Y+St$mgl3=L;$~N;G<7zt0*j45Ruf~+~TNTI^f21xmEAN&}C-1sQP^aUYmqj9ZHzuUbTs(Dwm%tA=4 zQ{U_CazKaID?7*uZo$sR{qt?DEZ2&XA>iu3H8BKUeb&ID*sJo!x|f z(>*wx41^^}I#l{$rP@OBQq!HmkB{29swM^*D!58v(rjCs2}s1*A(j3w=`=Qsq6XW_6m)KC-i zlN_2?9!LigRPkm(rY;L1y&g@ZeQrW>ySIIDf=HrmXiP5d^SA>rT|W;ycLl4B9$kh# zz?4wX?YA`~**I+>CDOjGf5qqi`B2W{{#1)tpU>PqTbbVHaRa3Ba>>4!_6EZx7L0S$ z1-ioyqbt(AA=uA`yiwUB?EOK z6^ph#-!5#W25yeNF?VnK>hb7Dd+^Z!?l1@u_!BUmd~meH4H2!hU^Cbv&^Kn z;0=@To$b$&{a(=%Kb_7dC;6j3eL34-sF~0)BBq;(m+~gX6#JeB8s~PE13&(y=N&B1 zBn31{>vzl*AyuBt}`=jztfRfJ5 z_>W080-A0wz#&VdW(5IRng6s|uKgGwqCkH{J_!=f;K$9Th0wGJ=>vX)yh4BASbv9? zn+ZGux8L8HMJB#-{`UKQ?hZ)C;*PZFyCpQ=cbYUGk2NSJxps)9ZY+`(gLv`#TKUJ$ z-TA>({sR_y`}sx5=q1OmK%&^cp><0>NK9}JKr5L0?Pr*9Rw2~$b<5Nj2d!>t8#dJV zcY3}Im!ofyMSx}FFKtqBx)*ccI?a>-*zv3G2KM6)3mN<))~HRyJ0w_-^nsb(w$ZOq zyK1>w%xgI!y;cG;_W&omQ{0ZRwcO%t7HlcL1ftV=Ly5zaMLpd}#ZcC}|CL(ZZiv+{ z1{)pJvRdYJo<1%KOvKY<;k}!0CE&sK$i@I)s*TmzdAHgU?%v_jPAO;6wS6Gkyq?!X zngS_3$fs90f<%5nm>>36cR4lFR5A%IIS#(;UCj{oJEfxZrez>F77o@0W5j)+LUUQ36N*F+=lVCey7Hps=oTD2=SIq&rg z1hH3wC!Y93tAvG~=usQxwNXFYtP;V&|FWRuQs^}?Yk*@wZc)VLP4F3!1rr8SBD)Sk z5xU2{_^oM+EStK^^0iuyg3^0OZL?bn=@tBe;Z+qW!aO7Z;tubvqqSy)7pX8+bi2^3 zA{m_s$H66_;DT_)*bnE7qzcQJ;qYW3nqgIy(SExcRm0Z`;=wT{?5ML z;ajKu4*)?n`T9e2u%@FsM#uhk(PKIfE`l>-5*p2vAk;=0L_+~kThu=r$GT|A|InrXV*(EZ-tk{ZkHW(7y=7^YR`ll?tW}hNSDjq zErD2g(;gk~jLlS~QBV0YH!b|W&)-Q~pWjD|!#Fjq9>jA<;4Za4=lyn+PRXmYd6B3s z?ouS$=`L1BN{7UP)*21j^7r{*R#QcR=*AI;465E4x^O1jqY>p+z?AP7#zGJhrquwA zW$izX&SSY%APS-%#Dbib1c{t8JF>_*e*MF5W0$L3(lB#xcOPjOfMS0P9DvS5saL6{ z&5|n-1qwTlQ0Te`qE79&M>m592%Xi#MHil9Jm4acXLGkK?EC$jK)~=i9bcEQ&eN9u zXT%>Ww>jA^C16@(!gGk!FJh!jO8PggM$oJmZUuh5F9-ISu^{6RUX(E%UtR^Q{~kkg z_A>A`NQvc>MA}%i;|jL47#8uCwNCT*=bAl4BgR5G$Il3rcWj?WepdhVj63JAWom~y zV@q+yN#TVm0Z)veqVeY=RO=u3j~_^F?7I`?rx6o27Hl>@d}d~RvpLcqiX&pngdlls zD-l}uaI-VDaY}=xyzbv3rZ%oEJ~dVgrUCFnLFc1x7}o$hc)!AR!d`oS`@xz-FvX{2%LFt}t#B((@^QyNPPE&H`T|t)%K-}9`Dbq_p04lJ zriS6+qyz=1F9L$6j9_GhQ#@~H9vg(9-XW4GtP<3c@=egr!Qi?*CYiC9{I10veMfcu zfbI#HLl|SLr2HyZc4V{wChY=+39!<=CeoR&tesR+0`lQNwoc}6cR}-6Vj-8%w-Z|Q zwB!onxL5vgw$>oAF==zM%b&BI-*;lPCfxQeBa++t>7q?dQ|sQ5srxN7Gox#&E>{-K z0p9aaHkprReY=Tztq}b5Fm~}x^2Rd;hhKnnb1Mq7eWJ~KsCH3VJAQ+V&bg#;0k;(0OdVB^Mn3@B& za)h@ir{p{L>!d$xN^6f&Re=0+?(uZO>2+(t!6y*?wvZ@&JHW6G#xdSOvlWNR%=Ied zW6I29xTHS-TW8t%B0aDq7|SVoxB_@-;#wH1|NPKMks-16b4s%<({0^Iayr{;+uYSB ze3u#;h%f^n&MQ>V{Sqz)S-SQeWj`p)7U137lZS7sWN=Q{BeT4ebHq;Q@gz^k1IYYP z^bu;n8OT~|W-y|GPk4_KiMWG+5o;8G!Bx8*v6_V6xUu1-tb>7nUmFX{#|3VDMvd16 ze_Dx{poNmzy1E5lW1mnuud1ih%qil%;J{3y+F`f!e55`+EqQZaOi&<#x0VpoaiKT0 zU=~Zc&jN=HbR14ns_5Sno`r??aY(!wBpEnSUO!#5h`Gpo=r7#zPOe(6yWd}yr9Oj& z8jdjJW$!3Zj(>3ZY26)5<@l4DaN9JF{1UA;D4SWwd^r?s;^NHr`cNNEBGkC;wcLMX zEz{MC4UQoKhJy^yPnJ41t`{S%QtKD~83Zkvzjpp6(P`7)3ql{pd%9W5%c>4H=H&MNO+r|4aVjkRfTJ1$3pf3->${ZbqegNwUk$ zSzmlYe7%exe9h$Yo4xc9aG*&a`+3=8KvVg%>624^w|n31FD<1u@^h^ixo0b zs-4DDV9E{jGZXO%wMVx@UoNDf5T+Wh_&bdeC)I~a-*<{0CPINH7-9)9Th5X{L)N#5ybj>z8I{dDCk3^mzUceGp>V`&d{4QEE`hdG#Bgvas zT_8UC8*?sPS%0M8JY@I8!iSKr59l1*tg5w-S^Qqt^V4+PJjCKF;8-Z_fZK9cXuy_a zIh)3|J*ZHIwvD&`F<}iu)<8J20_Sca<$ox;3 z!*n?-gyc>>DaP}-F_ea${MtljvveS`L{hr>Mr!p^nUN4V9i+P{)g}*` z%xel+gz-kQK5V?+cLcqC%mu4q2Yk{(tvOW$X{?8qwo%50Q(?&2;llp z5ZF`F!+9P8`+J9Mb5kLr@vPMY%P%rKBfLfNA%hunI{D2d`4hIz@oNVfMAR)#=m|&DU*BY8fuw7gA@ZoiBgX`6L7R? zIm!&(zSmpq%NfZXEh%^ql4=qGzuh_`9z7VK4v@kN9gMG-6n8Yb(7Vh>2>a1}Acta5 zS@CPq06M*sE{qeoCW6gVY2sBGa|a66Qnk&tKO;S@YW`76pUNr&Y@6XNBTkOO@^tt8Q& z)vK=GPAe)Rbp51EhHMz#DXqKjUR=K?nu}YxqA6Ete>8lEgb@lr7|Xz41Ke&Nka{W1 z1ba~4YyvqGX9Bxv?nYIB)FX|MG(PD-@d~Q_N%9c_I>H@HFaqi7>ui; z943nUDxx8}kHz;Expd**2x~RA=Sgsxg=t~=PMHU7(7=_R5b!Dn4FXs0J_*v}d-caS zq|0uFjNC7d(n$zju;g=!GDqzk4$I{%&l#k8bU5;?r^~Tz6yJX+*u5Z%`Qt{yII~PY zl|xlxi(2I03JC5b>f1LPB0gKvr%SUs$GOc2lIi}t&+NW~&UKeVT>DcYzn?d%R$TtW z6?$caIU{`vB$`Q~sPFlrf9>GxW}9VGz4g}xcZ?#hlwzuird5~sFnF%zZuB%CJln{d z2X@$}&=CULp&#P?ydB`W~ZAE(>v+3(+b;U3e!^-yO z>(%rb6HKgz9=V^g5?65cYqH;JqilA)z`i9q7iPZu;-{^C%irWGj-m8Ay7~9K;;1Xn zg2+&C_B}HGaD0t-EVQZb;P{-T-+dM54X$WCHp+S!7b&I&Zu&Qdx&)F^WKzsz&S1?o znlDnEsRat*Ay`oUSOCUoC$364IwLN|@A-;BsK@WtK`+GSiuTrHQY;SQ+5BP6BXkNb_M z(DC*q6+Q(PqIhNtE;eAG#sb=euPLIuW54ivYx&>FT%&x%FR2%F9n~~-_ zs>`C3bA0)@+5HssGEfCscr_juey1rdJ8AiU%Z6HHJ z(){=jO}?v@v4|5WqI>NuWB5V+w--A}KrA1nrsz<-knYxCau98LS77nK&xK!XaHj48 zfrm$)E#BsZk`_izk?h|EGYgOcp3w*{T z#Kttw*fjDh6{J%X#fGN&EewA6NDnCIdNKI<35N%G^9r>kJ+li}0_>2zqlL{O`EINt zGSkq@9yKZv6!@g(zzpEx&_`FU4h5taU|Y%7&7bJrOfbR4xGtb$>p@{4MV_R@zq64^ zFidd+EAp2}cDHyG7)HHj580&)X8V`NP1e(cvrdCFINL$#281?$=diAvDheEXtL-8y zl(Rm8%u!Z;;gZ*akwR$FD5c zfa0EqzD*CqrvVgY8WV=lJV{cYQV>KZ`a*TSjS4Vj?d5yq$nE$tTNSRVPup_1(De5B ztzx>fk(rTBhiK;Xup5{d9zd1E5Q+*Yrp%Iv4eU_@1~s6*U^LrFX?kvb2CZOClgT&!AMievF2GQ9J>Z@EOHAjCU~&+f=0xj zogFbR$A*zuaV|=Qj0=ZJ$s}Msoh^&+m}8rou_2Sk?=8wsi!N;dn3M>&?##KbCWdjz z&nXY}%9|6mU#~ag`oScz;WUhlYQt}c6c2S=8v1?QO!9Nh3%p(;&QwOh>uSn_1Ofor ziRQp2W%^6Emv~a7UJiSle<$8XWTLHLby8cLEN6GG#~*@6Eq!tn&bdESSXZ-T8Wgzr zr!2DicZoyC-k4q_ht_*t2Gbxd zkq!Wv@uHA>jPu;Yv~pg;6-o{Fzyh`sG6AmD{;GKULy%eVhgDTzpThF3)TVhCSeR03OI zS1@y5*DJg(846X^0PeuvEp(1L>0NbRB!=V%A z;3Lsu;A^`$MUW2ygA`LQM?P#{;(3v4nX4@J)l zy;YnR^av3?eBOu~sz=F!4qxAm5mx?WsCM1cE|z(=%;l=&8xypTNym?&x)Nqqlu8NH zZajR8aBW0H{!KE>tEqY3lp5=QiuLC*ZV8}0J*#SqW&uM?x;^yK_xQdB=3#O#r zS!wQ{+;!9MnU)t>!0uDNpp12WbNUN*-HYFsUpQrd`Ystebo=O{Wq`fYZs-)Yag!pn zdZ#RoKTlHN;qX|5bZmT!uFG)=uNwp)BH>^U)-&f-d;4scc;H}3{>0EU0f0A!Rgeg@ zdF#vJED_kT=|{kX@m28Y)I1WWq9|yZ2K+ncHaze_ekl*9`6|ti!jQgcbjVSJE z4=;rEPW>Cr=hSV(bpyYfXNWRG)@lr)uF6n*gfRlHwY6V?q*?DyOn+ym1LTK~gdVrY z0)mC;o=qKv0Y_M#gTVm;YcOQ_J_yC;W<%y}dYD91)H0$9mO2)6BxSd~nx-*8Jv`>| za3E0PTXU(&W{8Sqd(?Xs%~xwJf=wMQm^7&JeS_I`3yK1*%vS{&Q8v1FvD;z$bc21| zr>PDG$0mmN^kMEn%$$DLRwcZ^@hL55&-qs>fl)d8lJ%q=WtTC%$$;W7W_$cC)tpiy?T+f(^^6KN^J}0nMB5|HA`P|9yR);Se$qTy5Y4HM`8x ziMVduI!LG=7rHr1pxCiqF9>1?&g==lR-Fb!#Zvkvs?< z*_(-RIBc_iF^?~ggSbafBnG8Wo~3fs4a2kRK8fP_dLBQ+&%sr6*DzESmAugKxF$Bw z5b^Q8s{v@PI~xDC303O%M+QAftgx*oqZWH2~1`rTZ4s zcCcAt@K-t?tos~{a)a~b(gidg#k`-ArtSkC?r4+V zhQZ03?J^j|mZwRT)X##eMW3IsU_(C|2%A?=f0{0c=hs8#P`-E%yWw-ys~N?T;gLfH z5Ol!(9&;?E4`rlq^5#h@3 zVYm*iBFm&iyOpM~Z)tc5SZg?h>;7OG5%ql@xP}@;ojO+H%nU)ShZG?{ z<4!BZkY67@@pnr1^qDXy;|mtWS3pg~od6CP9_(A7Ags&J^YZcvfdVvwzR0XElyR zMdZW}2fAYv=AA||z13q`ik@G(8{j2#@F>i`oG_T>=Y&Pf=V)EibUZW>uM~woJX<$v@QvhM` zflA%LTZs!}Myx77=E zOnd{r8BH=T_$x9zUdN3eQeEb3JW!VsYN3-nA=9p0U>W+Z?)a+Sn-e4csN{27Fh<72!}Py;d}Ej2%>LScY?7UFt1Syi1D|DSD-}5fzUct&>sb^m z$N?t^^7fN?Tz%^WebqBJi_kY~`9uDq+ZN@p#rHr1R$*LMmCXe8W=&bTmh!h-Y)uJV z&`0w?r06Gjfw@P0>`TL50tBdlh9SB#=0OUU`(Uq2t|-#(2jrfn@0le^?mADNce=6) zW0{P}T>6(66d1?8nw&H+D-l%Kq(xKN68#YnC5&U70>8C{aWr-RY@$GGeNO=NXMzME ze)~Pt-q+bt1owU+dj`!zY}KF@UMBiNfnOlaxPF%F<~XCvQ7=Pb^GPpBNrL2maaVT(YHga3?V6(VT^c=0o^n{Br6D zfN}uf57dB50zU3(pz@}%qk$f&WujoimYa3=`$SV}T%EUe+Cp2?JD=I6^$x(Nc6b!* z7H7$&V>By2SUrniU6^61;s`yJH9Sb38N~W|Uq&yRAaC_% z@V_6o+~sF1;=U9Qd{m~P-3S4VP?RnD9j_$SZMU3F ziDa|G;CdknooMwb`CgIKR>bpFU=As`gPToE@F@P>xBO!bBV8d-1_|bo#kP7hnSkRK z!aN}U9+6Awdh!&OE*!Ch_9qFQsKfGvZ6mk?c*rc`Qt^i>*#W_% zgL{dO%;Us>+LUmCs?7pgq=@)$pT#EL2+k7OcXx`f6u5({arV;y6+r60mX!S*pdNww zo?+LoKLo$jTXfz4tRfyOyi*ljM~@2k39N+4XCX2vy!;Il!rxPRA|iMyrW5zP-EJB? zD*)I!lFCGttUe6Q8zhkui*cW3E4k(G zh8$T>*Dna>Y1vS^n~_uAp%E`aTy6kIqiXi+7|zU2eCRsFhuz|j+YG7=>!P|f%h6|A zo|9eTF<34_LqYi}OI)j-)6LNd-DhT!d>4}jj5PEjUd@_>F&pXRO_`DQ6@IwX=@*+0 z180To^_OAV5;{KpIk)GVYMx3aA0d5c4V1rK`n8N;5Ix3AJ|h?CgKP|~NK5XJRGo8gZvB%0-yhx=I?=e*kiIdDn}Cl2kZ_hgL~1O; zS<5GMfi9dACQ9EX7JZ!Y>KFWqTmD;HJI)$!DbTfXs@XfGbu(bL%0(>(uFZL$%^w_Q z_;K4_8V>B4Rqh}Fxlyqg#7|;;^W|ccb&2*o>Zb~}o5mX&P~2jv92a@h1C~!Ne#ktn zJz;!!c|2x@(pF!NqF=%FSkUANws_*?wtf%{e zf)fS=kdo9bzrvHr0bHs8R&`z3f%j7=I}j|7 z34SS%z*ytbdqgMvePw~OFCr9l!>=R0mw!)Nz$XLf#Vl#RMQ;8AtmW@I3dRPCB??Er z$IWMk;ua4idWJ6(iTrd&uK(g5Xg~le<4<`V;KE6}W6F5xqTZ%2Z^X6B$)#{hV7RGd z{|-#%;i)JZs@F!!@I+W^lH!@Duedxc=-kYHOe8ysDu3@B;CimMi8Rs*c*4wwFcy@w zgm&v&=TXB)lkN@44XVjAAv>LMJq}V2ybjRvDfUE&0cYv&2bwor+B5cWTjqNNpFjwS zl?}AGb;Plx3eF@sA3qocCA&MwQv~|cz!>0I6E`C;l|!j!miWr3s#AomQ`6e+-c^Ua zf*Sy_P3R^{1@PDv+%u=lr30A-!Igs~wvd4LOwkvQbU?=KL!^PMqAdj=Oq~m}TcR8f zwL)>?WAY zk7EWtk52>*o2TJvZ7rwOpX3v0`lxXfA~*>Q2L$-WtRxj6dhN&=Ec2=o`8gNAW?7Jc z$@v$c9FENYz+h3d509m>09?(B7b7!lK4s9lxR(9+QjJy6fAx&R84LYvP}Y7CC@~-N zwtl4Wt6La+`NXK4Mz4YVwStR^#g!|`JEh1bjA^X{T=2P86AM@c*SMo1vkF3DkAvk6 zrbG_&iPm6HJPC%A5qWiRLyB~PVFg6}Pb;uwHK&C{M2nlh7O=#$vo&gu2=R5l1wFAO zfSYR?$RE(nAd=rE@^%hdWKYO8?_hd<_Gx+I*+<+ovVx<(%AVk|c_Xgb#p}XAmFOb= z4FiXm$SYu&WJX9wKf-lHcC;L)oLXK*IEW zInXbhPk!&qB-`7AG2AKG56tE=RVkS9qK0Q}J@4N57pmOL!;#)G#zTs?_<#~j6w^mn z>5J@hl6Ft&gPZ`2HaV=TZ~#9F07nxQ`#4{!l^-{J0Wac%l@D6I_2bh#SYhPliB$B6 z{vn_xEvOI#dN>G(1~Oy7aXf{Q4NY&|$2l^fix8sq^%X`NRqvOOuRHeH!$Cnuy%sEh zT==GOefyAzvZEzYm>4Lw3Z65S`I@H?z!>s#bwfD?xJX!!O)muu0i1=`5;)5YRLZsM zxjEp!`7chR-~kv;{@jLtOi0>;GCIIas9{{-391Ua_UV=tM z9Y={rAb)zq#H7|YGQTRwU*Jp3!ILtctSwK{EKx7=jE@j~2@zZMi!j)dK3Nd1Y*583XZ1-^7PuvGooUO| z*#21rd!05JtQY{uX6pk&(w&g`b`u=Dc=#2v7WYN- zG*WBlj@AaOG?ytZZ()+?Rp6FJoha`x>HEIG?_^!?n9fZkP}g-a%KmDLkL*zv#$vn>v&F5+_+I-#FKM0nlr& zMno)j3Hkl#ad-Dkfv0l-XPA{Td*Iu31`Bd} zKTIt2{Inuo(4Udwh{@l}pu%zZLb_BlaE0y!XRmi#DvklfM_G&w_agi5#UH|C-7!PZ z<6B`(2&@-*f0n_`cf4-9l9;_;c}`z)weEdzDhQCUI$`d<2>UY8Uv|uw(YRHAV?oGVqxhk zIy8xCO=)j*$`a2=TKi8n4P6hwpzA!^3z+39OBb1p&x!Exn3QYN zQa4mmDX*iD4t9!8CP1`%jp*>ZT&X|Kua{ilHArDfb|Rv#@FL0XW0eZYd<0;YhgTgm z2rcKWwonBtg~O(mFPV(qmfr=bXhJ%2=4FaWHZ=;~rQIOB`9&?@98w52lWX5_G0B0p zg#|8+THK6vXZCL%SvsT^n?+LDpz9|&+C^|0`nx`aCkk|GkiqiQMv7wcCiTQi0PP!y z>HrsUHK6Hl8oJou`5djiar+Y0`6cWk{1WoCF7n?-ULg5YfPQiPl%aib+Wbrn=@$)? zL-*|6AmIKq5%x=)+22~Fb_Y%4!*$}rX-Tds&BHB+B7apXoC7iY@X{inuzi`&jKK7$ zW)$Xdn5gLjuG17ptFQH5{S&4v+ASp`c5vCr*Es&iQ6awUD(YmQPHG39hwx3}l zyOySV``pg-R0mt>^(=RV0;*_AYKJHDSeYjK&x0gi#2hJz$HbELKz(@3giXFlps5`5 zqrct35Ct0L1F`Q`S8A@C|GV#ueWOb8`c;0Qz@v?~mc^8Qs~GQA zj&ZT@IGdN@4{Q<$PI$h#TO}5Y-JM94QD{%xeuq*Rwm0#|$z^|Ihhvj;ZHk$OH`gJa z5R{(rof&KRL6!pK@rQ@7$aN5_*Q+M6 z_N`3&pJdj1MNISvdf?V1CMD3rilWVShjw$m&`*6yao~6CPA_CC_A?mL;wy(<0%NrZEE%C$8ioh*fks_?F$=rhJH+OMhl+BNmo zN6>-!ywXI!=4RvMrJ|DDR^&P#zIiIru_6zLH(;YmzYgFN)?u?3t~PbbZQQQtXL0Jb zn}d+G%9saG0)WRh5!DJU_B=6AuW)IB?Yb?|TZhPyD zS_Bqj%3GQQIcML2u^r5@$`NJgWn#tVwKPtwEcT+RGJ9wE(6Z0Th^42A zYL#%?N|xX_W9cDm+J0H;vvRJXo0EpRI+xTuNT#0>wJdW?K;r=78Ubke+i3A}yF+^v zE2e~IC}Xr3_T)X?qIrIfPs~=#?-OC~wJp^dTIO=(nMsUOp?^SX{WQDzI1wytv7q6_ z@qK)N%S)2_t?_gIkciR9ue-zuVr9+nvE>8gXpL%Dh0Q*PkW_zr`K=&VyG<1LL2kAn zQNtJidm*$&bBqLNh7lEg0#zrWdkChxv#+bw-|X+J4fN?GPlRY<{E(13=Dih_IA?X? z9n!iBg%3@9hQ;PjB*?NrY!Dy$u+C{PAb5-T>$%*i2}Sk&jq7^>$T*Td4YKN||INC-u5yBeQ7(&pXatUFL0-Gpap z*rE@E(gjdJc>0ztEQ9eqOic6SX+l8=DD}vLqCp-(M=~Y#%_?@bhldp44=^)kbh(cv zU(Z=9w4bsphUaMf=oxB4e3rfQBa)1VU7|Q)P;<^#)MxB&hr8AeLn^~?fZ3y!C5tDH zARWjGyG0~}T7-EQ`{o)AXi9hCBTRrjPcdNe(!O-GwZ)%&7Y+^m0eM2+8WeoCwc)t07=5;=`Et)2pMy59e^$>eh-{(>Up&{j4P z>tL_PX-c@ayB#8ZmKP$ji7zBI>cCrJet;8ch%a<WS@ps2$g0ASU}JK3Lr>r686Ps=IWv1l*Z||c79pw^^6V)> z2y2hS>g!T*a5P`FzsxWH@M@?+{-qJ^pudfIYjIfm+TU|gi4vQZF$51s&nG-b!7{J& zJ4NJ+Up%@z?U}0h<4NcweZT>QSXx9E2K`xOXqZVn>sx>i4P53yr2P5quVd&jW|bV` zlj}`qNnX354Fj4vdHk8818hw02iXrE1^0pbe$z7ne%rAjWc)17jTb_;rN<3=M7}%o ziO5KWX`w`5McNc1Ji)(1%t!(ua`?l8jz>{c=SIs9EW|PgZ)yMTW%VvS&&xzU@3I_| z%e&OKuFy%2Xx7`!k|PK&n#`^I$U?Grchn#?15A-`uCGTiv?0z)2Wol0ihQwPXX9QYy@@jZcH7#a8ei z>)7s?o0{jx*-qj^5AQW5n1|zdpGk*{gYSo8=F|vl z@J>poMZVP(l@Vk6fHG}W&f;*kV8wdoUW&j#9+ z!YbMropj3a1-BU>M4EK0^1OMw72D z6uJA-;T4PK=Y$Fuoxb_wteNT?iy_YF0?+?2#9Oo9!&ZE5;~vAwv-$g_44bKERC)_$<2fLsWlC*^`&uS^@`s|hjb z<2`*rS|)(JCe27Bg$Kw~OS#AWCYgq`nF&e>u>v;2L2w;J5PwXJXHqqiW} zhRzjX^VrO!ibUfE%3;`XI>pfmnN^$z;fSiVL>Lka@{=>vN<_pnGVjDE{~(@d#kRZ0 zXwqlZ3Pj0hJ9@)%m35>Nmxw{Fet3eNiCum4Y@r?>5L}WQGRg!sT?7Z2Tt%75<$NG% znQo5vjp{;djtAX{?9rig8(}^3c>rBjrQ8@)w^f6;kTMJ%**EH_J>H4j+kRl=J(RC7 z-glqJfM0pyUe>hD9%IcN&(4Gr!3YRL#|(C`_xX76JrIhmpGPmM(}P&lqHLL-@AAV^ z?hN!aW7`Pi4LvdjjBr#=Gm4pTJ7S$1_W-ImJg{tCyK4GrUIL13p98TarJ==2p{oPqM!rKdEp)t?04)u*%ahPrizK<_HTDHh!(p1 zomN{iWfX;>PN!ya0c~dgc@nG3rwU#=Ose6`tmzyON*Js9i0}$yKJ)ECum@ecpMv{{ zu!?*xLx0Yl(lcq{*Bl{O0o6VPOP6therozO0tvmaP4RuBs*zG=y02H51ZPVcO$ClHa(4x z)h3>Yr2)+tIyb#ZjI{uqQ=}z~ySbaoBXqcMoY|xmn30ARi=tS6C}7)FMc_oyE>!vZ z4_i!wz7Dsr+0=Lk8C^|{4s@|!0RlzcLQ!VhxBXHy>e3UaY=>8~9V5c-LRY@{MEJgz zIl}VUd6T0oqdqs$2}VP;#0=yFF?;mVth{G(-JA~ZmDI!xJ+`&BQYFYJajG9E3)SU! z(j_9F+|bNAmi(l$Q>h^4j&xF5{OdO^L)iL>G7;AvESCH25rsCPEBo^b)ej=nL^9Z9Uy%9rD zHSsxJK#*b&5c@GhAQ)n5o@X%Z>prL}sErH4DKc|ojTC}R2I^XKBCaRKM@w`Z-0I{l zouaH)+|=uVP$aBi0@lmY?xIS*^Q*@9C#<3#tf97-w1(!Bn!nH{M{wJA7Rh35+Vbm) zw_U260k?wb8rHUstupo^j|E|e!>yu0NXGJ!%oE@=vIwZ1ur0=C{-^`23O3KjsPE@F zfwuUH>Y+ol)S`yWy3HCwrNH?(3hh%gckc<@XT^pJCzaQ?c53< z3h^;&Ln3e{oD*TF(Kv+!1XT+DONw zH*1D5Vzz=V#?z~tWCnTNH4ugaJ_89Y76}ffvppc|RS+FrMoTL2a1Bq?TWV3}HYrh& z-*&jKJ z=sA1pU+kXoxUEMQ@`j4$e4=nsB@Bc=QS6=0OqQc__!uBYMUyu?QeOWc@sfjOfH6F>Vb&7Dv+DtlV6>!sFVBXGYS{LHM%R%-&ycZFLn@PrE zM;rt$$0eHZO6GgU9-S3Gc`R*_Ma%Ib=gh#m$38CXug4Hm3Bv%vOGCp4^g#$zt7`@R zs)BgvKJ^w{(t;=AC%x^0c+@a!2y`J-boTT}MXEApv&LnCOd7`LhG{0^CDuI}^7ytf zW@k~z4Ogaar7gd?^0+6}%xjOM>BD zG~fhBKS2~17zz%mH1JisncM&;91i4x`#5JSbI_Sg#@FTgTdG}}^uYBEcF`cKZs-gj zT@UA#tt-T#Fh*9aNA(V1ZrqAIExH)FN!%7l61tc9VWW3~S5p6RtuWUDKYOWF;JB&^ z*M{fqb$;4y$H;AAN-da!0#+C5=-u^z93>zkGr%B5b~dGs;Ha57$bRy3bWdixkfNNv zqW%3;luv}J3%TCt?}r>&Zx|0FRDh8P-juAMHLIAq;%PWIF8E3TZ@Tq8j~d<~vq(!5 zW-^%`qpW?2%E<|L3A(r$MB~!X`u!>xiX$o~Y^H{6s=?f_5~dc&b-AskAC&@>cjS_r zTq1OQG;#v9?FJnfMS`)v73+dS2uH#jJ9DpCkt1I1VhZ%c?+Jl*D4 zMGIv#=ZqL!dT)K4F`&42M{d;Nnj`%h=`jyA{tSRSk183{T%@RPHe^zo_@( zEU%WavYRP91KdS&^HHk_PHqMT+>@SXs3cLWvSjlu7i?aXY*sVlTkt^tV!F_fO(aY}61! zYZ^xLO6$e^FnEUIUHSP zSM{-8ZD3IrOEp-C=mea)>&>VwzujaMCQtynsJtu4(~>E1hGF=VwnW1<`K{0S&DOgOQxz zLh9NgE-AP$Wi5-?#x0YpFh*=UWk}^XO?^5X4l+9^H9XHsp;`n3TFu$ir*&2liM@$n z>K>zDS@NyH(8Ln1MfW@!3ZRSjL*>>(*hFVSaKbiWTJ0aIR+JJS4!NpXSf5;QeuJgfDt|x9G&>xHyAA$ zMH%H{?ue#ht&$ss8OQ7r=IA}yt|F{0d)>mKz)%JG{YX!Q9K2trj?c9G#9mLDk3Xrlj3UeV-}>vuu?{B2EbI1*oNRsn z4(<|L3g<6Q%}qUT+U#;ZJifHKXJr;OIwH}rH zS0!>~v*5*P&WjYMw^o+r&!1mE&YxfC?F;_%54imEk1Q|dKmSPEda&Z9`cY>;zrHt6 z{Oiv@hHncn=)YtCOaAt~`te|x|86q$ck|Z{|Iz%l!}V*7e{~I-{~W9Q@ooD3yYru4 z>(u`JZ~q+dA74L;x@~`cb$yqA{pg1{t(Wg({rWL4Q~%C?e*LZZ_4=3L_qOixG#-9_ zCF`>Mm$m8Z?&sI1Uh?VR_Fr3V4L*K;VgI)N|8aib>+Jj3fMJ>9ZZ7)i1Nw@WsXqRW z{)T`z`rG#`!Sav)bQAanc!mCJ%}_rc$X{y&IOEssexKGBOeEj(uFtZsA6uR-{q%cY zfU33pHTA#F%&%qM%0K_-{{T=+2MA^6xfLec004(10RT`-0|XQR2nYxOEI12G00000 z0000000000761SMcW7^HWkPRcc|l`zbzyXGa&s#my33J=<$*Yu3YSWPo5GBH(e3A9wQp<$s-B`^%osOFi_z z{|fyX{PmZ-Plv4T%in)>9sW1+*Z=j`zbt$C%TZ@*_4}_d{%49Lu&(>{mnyHzYW?FB z0mIbKslCn*W;lQU75oMK1p?vc3H|!ZGe^Jt{%f_aj?;d$?{_P>tBBE z#rT<|erEZ3gZ%5Pzrla{4gQ%B{AWv1zbMb?zc`;P(tG0t=Nw}Jl?OxxW4&;Rkq z=>PT)wEhS9$K&tI{tr<8O#ZiF2>%KGPZ(0Hg?e+1=&75Go!z`wu#HwGm6uQS5fvkv?h1wqOGXd&bm<&O{k zd4T`_gOL2U|L+|BXT1LJgpq9P`d`pRSFic}&+~u0YwM?ZIP(9AI`m(V)&Ki8{02XF z{Tqb->_y$hW&Th4rHEgD8RvY-=RK#F@qyTi*LwKJef@oK>PfMOmmj2__J>ISy_)ml z_g}MkjsN|R0bgTZ{$EMFz-#3x4))dM!a2~G5_{-eDST) z!gqz|K{0s;lPaoo&khBo?9!AhRF}-lx`b&p=9I(po`syLe+fC;oo^R< z+cK;HB#;CK6@A|EId}SAf8Y#wI&-H>GsH7^hMC4LH19$)=fw^DO{u(&H*<_A4i@<6 ztT4T4YGTVkl%f{+e3B}owd1b8yVsg5Fm#L6o!L%{C|&TptZ*cOL`eEUZ9y<(L-UoCbpm(k@?$2lr#=xhJi!H&)4;D-={gTE~1nB}24>_cP z7+VG@t@F=z(3nD)ef`=qiN?;NzFH`|CxZdkX6~WhrwfyLxjQ|U95!}SS$qr+xt(3; zmM_@c>mH;hU7Bwyd*{H-q$qgkZv}&n0I!-Qzn;sd~>0^`eJe72+-zq!V8u$s$mT8V2Lu{8l?juQaZ7I~I%$M)Tn4mp{174LU-QIPED9 zm_o-4YbpU(A)nOuKD76dSGIqh{xzq}Yfg_b6$Bac3k#e77(^JRl7oi#GS*$V94qv_ z;<>ehc8}a=+bS7UDDU*}`+Bh+Ewn@n-Csz5MWWJ#%$i4I)-2Hg`|FL}-ICjTb6_V4 z>Xu83yD9O)s)~7-f&g!m?+v#=hM2+O{$`ZnIrBl&2hs5XbFe2}3@N}RVTa$i#9y&~ zXAy~;`3Eo+Le$J>O!H?<=CdZy@UVj&hXBf@Z$QdxKqH47`br_dg{ARU$$b234GFg= zQ4OTN@cEioMX>vh_68R+&6?zslCMAFBR-zJRXbBTzM`FnIVz@FLb+|ZHy@LeJZ}Pa z-5WpLhkeiBor(3$fN=c~La}}Y{yv9xADTUi`|Z%^IalfI#9>3oB((UA zbu_ba6ds{!Uf_znnDH&V322=e9Fggr(Md5B$KW03yApdu9iEN0ZGnHrmrE#^M0aW2 zcU?mpxQr3Rob*KBNMs}V1OMqV5)?fIF;BLpjrhx4-Ii_8x7*to<8ll8=qQ`MDWzy6 z_e%^}P>AuGglvFnRIqY=P&nhLJ=*QLYD@+B+SX z+&-br+h`wtxpAiJ;>depGJ-Z1)w^_&4;fkecC{wV$9z>O^zk235$dVH%5ecE@%_UG z({k0Jlf~GTc{%$eT%n<*2KBX6?kPjcTWll2Fo|*uzvFe;BzHRR4{*+m1B-^V?)P=m zDB{T}FiXS{%e?hUskfkc$HUPQ+|U}L=wrTQ#dL~a8Y%e;I&0+c05=W}eZdJRM)vvR zK`W(h)A?IJ&{ zL%V{CE%mChVMxoxiRIi8O|D)kFbR z52apM<1;Ei5PU?bF|olcHVLM8r70R71S@=n^ypv=L&+f@^NdS~a`E{nR4roSz#s&j zhEzMTXDElp+u9ZK11YVR;o9h~bI6JX2T#wQ*=iHiLOy@!Vv0X1RrXMu%@Fv+rxbM4 zOFxc+W?s$s$2{h2_8GD=<1Ryjt};V*DO4Y!v!$1UrCWtB?tQ|zM+D>$>9+B#?5#MoVD3$XB$4{6R&|O zE@n8$u&?$5ztQn{5F_9x`sT@Sc@BYhFKhE=E5m32AEdKGAZId60O`}z%Ak6ziDaIf z-td(`X`8jNcRDgvBCVwny{gH{@{H@~=qGfRNADy-bped>)lEJ1 z7d_e_oHH&UYJGiHDx(cCJ1TWl(FC1Tl2ygDRt6|f2o^Y~dd5J5klr6yc*^kE;%x%n zB^v9TOY=T7!68jax~9RxIjbN7hF#Np*g#@K2jJ9>@(6q{<|=eET@~kA(+V*CgV`e4 zkz|;YoAc7u7kxXp?9g)kpe5MqKy6Hd3O?TETw%9_PL|)YacyUu_tcU#VxD0CgHG56 zcz?_*Fo8$YIi^lq(XJ+6l*F-u9kEa$1}A|IVWEsu=-1sZ0W>qh$MM1+t-^mB@dFFT z*-I-2x(m)&*sO<2a{1ANS2Lqu&fj+lg(mFo6ZXsjN4Jhj%ZK$n>Aj_nLhP`0P| zn}hQljWJcUNpWhBD=+FZ%PH++9&E;2@x6uxP6<{(8ynK%eHhF}>l(~OC;iw?fF=XW zaVoKvt1{_fT>ODSCK!=R3%P+lKSSF`Z^4K#BgRVx&?hBeXUvlKJaS+f6Jx|wuqNl= zdD|j7T@5E=y@sb|jQ(QX`Baj>-MdKxgzceyyt8>FJ^g8-6EYq;a{?GR@;pikjnNBb z*~(iP#I9`^AD+86zSd)R*y6H%Y=7seke3-Y+=YsZHdA~=4o+9kso88rU&aA8AHpNK zd)4jmo`D`Q3{n?LTpkz-9(t|;IVn4dtYa{UnWsJTP@^+87GZ+=>T>UTx$m{3qIrag z(L0??bGbtn_plS3l*S0IFfE#}Z_Ni-gI}{A5xw+Ub9u}kt+Oz@QU%5!lLt#kZ|c79 z*rchhX?Y?eKB%ad@mK5Nbv)$rW|ISWcxzdM$nK(h(P%0Bc+X$)#v=kMO4oOmwx0V6WXZ8?J~RbsM%6;Gra_Q@1PCIY`rre z4;*H7tZ8TFLyIbJ5Z>0Px7nS`@Hg!;_1n}IWybYV%W^|d-#f>>=6UX$SNO&e7?(c` zbv;#KbeEFynh=5?%M28{lvErL9Rc=5pE&T**k)>beB@Xj2Ok}C#xBNcz!u&`89j!j z)Vv;Q9-g?RS6_XPLVH&?Sy*pC!BB@}da(%zvau4D6L!tOZ3rg`BoUaQR56EG*|P zBXYf8o&BQARH+j36LX#rb59=Oere<4Qg^R(JfiqrUuAZ=_w@!q;Eb6PgzV`|7K0lY zxH%eHSX-5T7tAc8&l)=0v}|09$n$>adIQ`c4jv;!wrp~`Ro|mNOh-WeRc7|y@>HvV zjinrPeY`mkMNVLEY3Y*Ou6=;5OiIg?fu@d4a_2#EM#6N-hh~y0x-Sc0R*94&0?QL# zW{eoEzq@LyxeLA5+M(nq*cuosRvtt^{&@5kCA=@_18Sp^nCBzJlMBa?Zs83L6zBW6 zjn1#sSM|dsF**-Tk^JB_urQlb4_<`7wSKInawc>~la@TrMx_cpw8o7Ac)tr#U#5{m~A8S3aKfhC>imPeHjE~2OO;v{0b~v2vK$L$lfmSm$wNj zOFC#SwW32656hO6&nAg5y3SbS{NXpJ*;O5&@UEkcNK!1r1zgDZ!c8A}^P2QJ0Ui7B z-5*bT(2o>;Z2o*{xi4OjLA$%9ZHJPfPEOsu#y0t~qYq=4<{*Up0L=>tUp2kjGY`eVCR;|x8Y$CI<0072eXup(3raulY*P3Mq7UTPw8+p$ zF&-!tY&L6*^Q5_-V3$U%lrjSP#gZZ|mBj!LOincYR;+5<@7fzWZkK|YgfaB8H?wRC zl#;jT8MQ}ZhUrAiA0xS?Yd%ALLxn8fHc;YAPv(9UoqvMpT4yPhfnN;xA&(xSgM%JUhXh`!VUbEe2s35l6#osESz2Va zV+)T_%1L>In_nrUp3%|EMK=nP`r#vxX+vjB9YSiBM0^TU9cl&>2gC`EQEG2J-*zhM&l5N;RLX^)Rgp3`rN*bJdqEK zPHZZvge^aDt}$9p#7z(!?ucab7ND;L07VVW_Rc(Ct*J$)ZU%vCAlT)-?xcMs<{LEQ zie2o(2X5pWgxJASu?pS!yIn)XxUK+$A0?*F!FL*`to8IK8t#cFF`5>kKvxJ)4(ypb z9C%kI{PuI8;Y2CMLk~I}_XS(dqiNpuW0Fmo0>O~w+HsjAl{4)SE>QvnlVpG5RpPD7 zotj~ddtLzP;usHYV(vG$v3of-@q#!xC~yXk@X2h{V=+k`Mi|GHDnxi=4LOH_SlA+3 z&Nz=`Bo@Hd$Hjf%#b^#0J^mLM3i(N8u5&g>nX%mKpP)t}Y~sH*Kk|L(&f|Nr=&j^P z8x^j1VZ!A|MWiFkYa?e+nwEWegt8al`8+TPtYN|zLwe*2o-|^XJ=_UoZK213n$>7# zfuTEQDK2k3!Z!-b=D;Rk0wOPUkxGHwwp7Wm4{XsaK!fy`@SDeO-v^V_;Y)<;a2CHq zUC*yN z6BCz-kK_=3BcnDS3MvNF1M~2P(Z-d8GUb;KFf(FBY#FBcl>atE!D#Kr;TzTI8ro+e zqP1C-yO2YsEG0ssxW3}9tRX2n7-ToHiCp`T+Y|4?{)TkgG5I_Vsh-U6>QGKtV5#(( z(`{l^)k%Of$5OnDXppgpP`m0byga$q?5cK`{|xmYa2U}VTf&SbFd>J=TyPi0hruOg z4Ewk_VqWuTL-KKYf?r~n%Q1YxH7|Lhy_Xarg(mrl7ZbRpL9U*}Co$R>d=aIQo{-8A zx?T%g;%He$ATb2Oq>Mip+gP$1-i-IflD%c8jtBkmKwx1`R7k=?sy`M~qT61ow*nJN z4;35Y-jZ*>rXFWX45K@MRXeon9Xe3}}S2EfAUZ5w0&-1D1 zG=WOK@&eVYx?NG1U$i|0*LkQf^}3w4$F#L3%8>|?@I&T6Ot9T%E4m+|&l9h?)ivLR zN|qhwIb{cp3<1>n!;M?>Qm(ep$)Ibiz`XCN?~`3zLyyaHwqy2*KY}X@63Rn&8H0WC z;ELd}D+!D;Db&*<8GQVwyu->y2ea5&X{Epv*!Y@JZ$IAp7PW&|=zhEm$_U{sd}n(| zI-w+El;l9ktdL_|_=0!e#%^p+a&f~vpB~K+2WC2W@7;T#&f;hCl3t7$3`GX_340KB zYFhUziU;3cOIyU0-_0j?$**{Ig;qBt&0(>)Qtx*zV*1DuBbl%f5TroONfB|MxxiHK z*0Hg`Fl_40)x-q6A8QGrct}(8sFZRtf1YhC9o2?}4F>nVEDO-{$WqioDqX)*JhP~@ zNpkxH0mT&#R4TXT#UyF7k<{#;jYL$Cj?iu}0}G(Pk>%qOx#A_Kl7K84PSdOK5|Jk1e@i90S2EE2DmTc{)A4*!5aP=(irS|{hbxJq`uf=$QL&Ci>r$m7Rt@Y*LIS;Z`d_^BauB0tg8XpX;K z1Q(b*8Q0$|CYeV-nL59m_UbTdm*)@Tw}ITKCZS2h+|x4wNRa0#MRg1KI#Pwu&8H{2C=7#N@%hcS*YZlg>yXe{|O5 zczeYil=NuKC+fZWn=*SZr7XbCRwjb{o|DbX-EIZy`*s%bW@c3Ydu*@NzqcZ5pLn2i zRC5o8xP8gI74P$Hcdgs}&5Yo;p7gong*cb#%RF(TLTSj|ytgq9%=O?4p|PG61DD;m zM!M>PB5eY4zGJ(cEhhp%#^QR^3+R~In~RGtPl3ocD_|JW@s63!!h7XHf6w@(NJ*vd zkg$Cmh?g~h$q)l%(&DO3RpAEq-5WB7BsNn{=pK9!pENTq(AKA%lzWO-#zVklI+A=| z;v_>3l~oKg5U3^- z@*<})(9>&m*M}J7xko&z-4Woa1&R8(N_^cdSjGq^d4SrYYHA`yH+et5V?8yt-Y|Uf zk(90q*=f7P7}(y9oA#o1{a6Ago4FiHS_DEpC^VX>$9FR-_pjOlN~FE}$PPLBoK*}k zwSF|q;ZVX9?-^HpwRxXKA3hBQ#D9E2V{s-mal2Ubj9u7@(u^h+rD@xj@0r~*;;`1O zG@Vs4J2p%+&)I~zH>XjSk~h=W)}ud+KFN}l#KVrwA|l%G?9ppBSs5R1ku?WDm018~ z3U=t`I5u2qI(|kv&92+-H1mj8gGc8Q*AYysuAZg_&5d;$)&-3f%F{``P^N;6?S~Vm z_aqA7K8|l9dOnC!0Ug~wMU@EX+I(uVM8#Rm1HF3B8KXky&*|=wx zG57Jq1XS*5qaQw;lVv#IP8UAW)P)?c_X8V)1W%6Vcw@OA;GG#BxMu}tPsR9b_v^EN zl1~IpQ>7bj|FXg9@xFE&O|4vshHYyP(PA>>8!R07nrIv1A&`b0t^=PP=lAn?t^0oI z_{3IagRJqgVk2@1DAqoD$}{@uf+rg!L_Q~2-E=V-(_4n@l?j(5O5Ie+eZtGA}1xa`nbiwV?Jy{`(X@VWTfMT zd}3S8s_P0>VRTzg`f>o1&BrlFiAq!&!V1z&y>UKgl0?bnqxGQs5OZGgBB?^0Q#q|5 zi0i$fDKLDzFg(;Djnl|ic%+a#h~%9;Akf+Mta@4c3Y{(AI3 z*)@qewTYcC0O2C(s|vPspRN%<#S*DYev#Mdqgk0ppu~+Aj`Nib9D*kL-jRWg{ri>f zV+`B2+kWW)d4uh==9bZfuvut>2JZZ@xz5K(4wsb496#Pzl=0Ep4KK(k0hG##x|_1~ z^XL~T!-O|=N{`7vQctBf{Ck$lJb&gUC4u&dvq#H;C$5(CClp8^&M2(s+K;-HGEYx3 z7reK@$oWS)%tohRQuMy8l)I1cBazIl*8KvIFB3P)+MLA<5Po<$HDGPiYrP{@o7$_7 zQb+gXpQGw=An*G7(85cYEZ}p#dI+TL7<%w^SIV2&92NZra5D?%V{tv zeYq`I8CIS_07@b~@R3oP8ZFi3(-INcVI%P#L}6 zx$tLh_h=ehE?E_Gn35^ecxW0hP%X#h>J(W8Cr7$AETZId+Fn6gh$h6B^~K+DxT4(-YWQQlW>Yd{?znk>W>2noRFZN-`Id|>QK@|! zee{4g)K@nI9c>hJzxE)vvc{%wBgO`BGbB~KIRnZ~7Dm!L0KNfl4L?b9rhS>l3?us`xq9<7Jo4wg?uwR~39`4wGVr!>e z32S9S0@37tIJ=NjU(u?T)9vJrc61$kSG5f``EFpSq?x}sXyb`x>l8w0yj&J^Nm4Th zv7hi-!I?TbUagGI72b?r(_|*=j>%%9`ySm`UvvYHIw7yvSxoh2q90MjJXV0nNK}9OR zoU5F?R1AP1WNk*3+`Lo_h|m4=_6)qS-#2eG0bi)!b5EzIW`{du>+06YpJ$+W=ZIp0pXee{~KES)^21snI?GNsF`9b?KII zZ(wt&XVZ@E4i$tB&ZQGykLk_BUQDk>W{#*0QQFv9y+_xl4vi^pm1DuR;@C)4zfby6 z9S-HZL$)|HZ`wRbq%@q;t8Y%Reug97nOe|KbB zJc7b!-lYjzV7LT5#22Kz_Yg49g+jhLo1b7Yt3tY)R`m^|j!zlW|Hw~W^&XmdJlBuc zrtqx_#P_zhIK845JnI-17AU~v?}keZR;6MBlg2*tzWt-WYrPh-caD*&${FLyA2)i2 zT{CKIA36}@2KhGe%BIp;Za8@R1#Eii!=OzG;!catQ|5I5SuuMhOCw1Q8knQ6<+TrC zy4D>v9!k9MHP>IjTzm!To{qeQ)fh&LBUh5D7r#bq{K$i3^P2 z^GeZ-?jzg|Rx?Nb4mIj=HH-i33pc@Fa#XwFZ$~*gATn`&)5UpXPZ&cwi3OrSJT^K$H$Cz8$T7>5Ky~rxdzWI) zuV=uZ%lLLHil3zkS=V|;T+X$ru?c%`kvf_^LQ}pP!1IcGN_+Yqcu6N1{PCw#=`jIM zHY3SpY@e9KQ$h%kUz3tH5V6;Hg2+T0DP_X8%o9C6=Sjp>ry7ZCkT*$l4vN%MyNZiZ z!*A!pX5lM2&YFW*7U52Lx0Pgss7$dy6?K;rdYRf#kStk3>+hUZnlwy10Fl`HYR_Gy z&|ZM-0yGDL5~bUgVV6ofZ^7WIXaH<`WyMs0ude`qMldgtnGQ0i(*>mcj)u`Qqxf|# zm}}|D^yczA>}MH4{y-Yg$78BWoT$%}X5z#^pz-xH{BvS`W%RF}@9+8)Ba+a{2o@{- zW3-J|nGA4I!&#t;zl+(81ofC@@*_rtlS&WY9bva=hkY~V`3=8?|dJ<&+d-F?Uj4Cat+43x&G9!RsFb{&U^&&KID zrb9#6yOO{f;Qn$GKMaBEqDmixGvr zkRt=S_baY@6uF>I_7WCpe|>Egf)b1HEcacp*v7jO(;p7;hRYEQ`qH_n*HBCb06;YLqI!(OpG`ZVzvBO?IMXf~PN0xf-AzUv$L z>ad@zXK)ZMg`ng5g3)eH&Ygj$XQ+tr&IG%c*zk%fTU?c?9$ijV!SyDjaPF2AtWf*} zK8L3qupgM5fu=>`pxj7ESP%7Uhb5QoAdY4~Jo3?1SzJga4r$`kTEQ)^#^n6SQSuAU zglc~9UbeX<%~J0SUuta!N@7f(gZEN81uD5=UdP1gOl?7BGKu&NZgi~eG^_7)>TM1a zKwN5}DF~~SgMh)&&p9kDxE@sDi-ajP8Hi!$i~PMZG5a-Ksn5?I79IVuC-Fx#)g*I+ zFc}thU4g08VMGyFLNVtsSspXnMe36B<^@JHhFoQM03}HG{Oh{J6N}J?u{!pCcr#Q20m_1X#|*z*o`nveBK) zm~E|7$ixo2)5vKR2+gW9Z3)O>)$k?Hb!I#|`s{;xt}ZK=b9uf9vTd#S zM0d|YDk5}kz-3H|q)}}-Ek-ziH2Mx21zfj-u1`~nP2xDp!4n&U^c%hJ8$*pS{VfCf zD}xmPb{03h2J9*w#oG}{L?$^9Y%j%^4Y25!CavE0qV7|s7bPV8f_};%pfc&p82ryh zk~z{%H}Y`$Q(_6WWNoM%Z_mDv64DA0#rh;5^al3`q}4rL@ewWk<_&KF=7EP@Z{#Qm zFZk~G+7T1X_i?`yRbr6h9*aV{MW}=fRlhStO*)?xUWPs1_8mqlc+d2^+LZ zZVDXIuT7ep*PEByo>vR5>vlOoHtgj##Jx7442u-QzTyHwXNo7BGAOh}I*J9oJ_jJ) zSU@i1AgTgt$E z(+@kM-&rytPHK^M>H}weZ=9XgPTOrsrl;Q}ROTV<5(w!La%TmBt$>+$;fl;->z>W*NbNdHOGd%B|INwU|imCHuT zbK*ZTJdVBly&~63n}|&hur(4>vKR6G{!*p_C=w0t$vKVaFco9RJsn&O5g=27Jt_7l z;nB__laH+LV&?c%d~kH|GJXeTCLqh0?IQO$h(`k^jENwe&I$k-ovvm;fNo8i<|Hvf z>qxXtsRAH5H5@r1`+y-hIZV(zDAF>R$VUUB!d8C0&ZGhB`x0y1LOV zYKZu%4A3R2pN1HD@S`rXthHMzWwK&aDW3`g+oAEH7GZ%sN_Dj@=&Ug^er<49;^qnq zl$jm+40=j0alQ8xwPpPX~<^jfghsMCmSt6 zEv^kFaoY+x-zcOE1#!ZRPYT@MSF;cAaJ`Si9|DZLNUFUCRYts$*5WZjF=f6oeBP5Vqv+STVkrV++RntxP zBU6k>awQLzH$)Df(ND_w>z?0%-8<3W?qr`!FpimqJ=8QICW*hZAztpdHCdcz3!sy! zs~4#f;)(kk&b?ZG!&bbY+ijRk5YG48qJsiM^)$n~9g^hZz!-gY=?nO1Qarj(R6Ja3InqlsSBs63 z;4^Lp{o(SNTn-DP0ap9GiFyneIsm=B>tD#4VHqmp%$L-%xJlQPE8Ho4Kif$J*T|Jh z33dfv$TpDooXs`}@NvQ2WOP(Rq87{O@7G2XbVlF)P~z_DaVRWov$PXm(v-TYMR`;f zw+NrkzO9NACpR%I2+xG-I}GQ7dp|18M`$|-veKnq8v~0xD{)qk}L|iNsQO)xxdRmGYLQn!jJffU)*G6TO zgUf!=SK@FGHJhK{Q49zvjW0q66NP1I>XC0EftS$2rvM-;gR#G`5JNW6_fu6H01=ko zKDc!?%iyQz!?ClC%NOA$fSQjfGU7C4axO_~{Y>fQKzX)8K1Vf=DqDOy;M21PQx~3u zyM4Mr#JvymB$e~t7+cn2JUGtK_w0h{O?Aa%c@+xLOfg518*gw0v#Q|Hc6$)7oZl2Rp;>24sCGYAb-6A+sY#7Z$dYye@)i5YQLF>PvIU z%SQ^@zGxw$s~LAY%6t6l2E_eGyT8(h0+Z5_*BEybG{LB;(Xvw6w*{V|LxKkLm?6eH zVu&>?RH#~VzHt*WGYC*$_qe|~0Ep?DdYR&2dM%VaqX3iDYjN*xT)$)7)vBN}cY|JM-I<x!fNE~Oit-GQgSA*NoqRa{`T5NWc0(t( z!$UqJfI-RWq-_xQsDQ>PXHENxbj?--u_Vp$AZJImj!*4sEO#@bGe&ihHnHW*sA=x2 zU?AD@*l2W~0~RnBF#7pLDc7Hn1zv9HO?VzohCRHy%E_ZQpiec|-y0+*Dj}B$O0P6T zZ1gPLw zdu|U6B{O%VKC0HuP8>d2{#sw6{$j_5n&%fZM{VEJ4^c5H5zh=;n*5J82iSIJFQY-$ zoW5!40{mD*84A&PJ+x~GF(m|lg&>#Xg6Xo`D+kpVuUbT_8ie9)NxUOFHza~!`3IYG z%!zg*+nd_r&>%gQ7>#giTK5x-W{2~75l^Q;iyGxl4WY``4Rjggbv6u%0)qvwRDdUm zRsdMhBOXt+<*h66;gsJT!+4kpj>Wn1tVxO4*31<<%Y8RfMlg&SWVjnY>39z~;Ze|^ zFL2lj&Y;84PS$K~`&0UrGOut{)WyaiFt#$q1}(h{X)y;aZCrvd7dIuV z_8W>8bxIi!icML@zta7!lOX-ess{Q#&0q?M98QFXf{J6 zxYxxcWyr_?Sq`g=z%S2{MKXPILA(fm@^FR>|cG8nAtSBN#{# zrR~bJ(`}thGYRXZpL76p9R3j)n+p7l`W9N_s25(>JjfkhJ@$3JH@Lf#3UfV_Y&^pvdWCop;0Qh*Ak&;vD zqi3(tpkaw8?Y!7h@P(#03fBsU#THK(<%-33Sx+y*Dk-{yMNA%UEX^^ z)xG*Ns3;6zW)koKBO2Li?|P>h;N#$pTx-331PlK9(ND*4IDuum1QJJ4P(_&8TT zxklvaM=>f)P8U=FU{9trUBxu82Dtj(nBbrvEeRz+;@+f3REP3D^VgA|L2J*k$@!^n zU>4a=YPU(GEDmo|@CtN?oXIz?^{SIU$Z6%|4Vc+2&{V`pNCM-#>aiOB{BnL-s*Bi@ zpPEQysG+`csKmnUKnEERuMHeEo8A~+`kEyL6ZI?+;5ut^B0fNSnullwhETdI0WSfQ z$XB@Ll`-opS_!YmL&$cIGi&;>rOe&lbfUal#`2JgO? z^yj1b2Ths|PmL%^5geAmk>X?SUeKOlC81y-M-$&5%h9d@WIDnk%V3C}m1^y@$}_P!$F4-klW)| z;xQl$Fu72TI}Q*4@}aQipiMJ+-f`c&e98GL%q4utb_Au?S3-b!Q1oOhaM_@< zniqx)=PQs8HJe@)jLyBadIQ&?v2u57*&JBAs1+hSCGg?1*xq;tVoO6JJc04!c7B{+(pF~*e) z_p;gPI$;JasHAzXSDL7nUq2hUO%@ay7Z=+wFmundAAHYaSE2e_HNgaCHm0>Dg;xW5 z$TI}LNfgDC5UkgOJ1^)inS0ly+0mwS~tVv@R<^d>TVNro|bK_Bu zZppq;zw>3`O)t$8n`wTsB&*;Zl;H7~ei1d;Vu<$}`-km0*MXl8c`rX$i`%9442iP7 zhs;>~LuXx^Jz&tNf(BkgaUp9*{GB5bByzQgXJ?S9{;KA{zfL-nbA%`Nz9msbnNmhF z64&6tz{O(ywU}NoNv4U4oEA2HZb{|`$R@!QHcf8slYgg=Sz6nhU&O~j$xYk$uBDw= z=w&N#3hq3HXO(#%kZv;irAWW|D&j#K9srNOi9gFnc?95v2*|A|I7-ULQV?&4%SqB= z7b#MkGL}@2WcQ9THm%zaCg5}QfVpK?Qs}=z?g|y!Y%v`mV=#*ce1*5=vVE$@Ej}3$ zyq2%>s~LBZC1%eVeDJ5#e;(k+gTkm=UkdQu-H5A@SxD@BvywEGv%5(5kQaLSY5>vG zB&Fy_W@=i5Ca%{t2kHk}k&@)d;iDOns=AS zxpGPAT0F}bnt^aqe7OQXXv8(CQIULXvrGWMPNGLxV(Ob`v380XU??0Z-$y-|pnjS6 zF3ooZj)mGCM~cBLy-wRWd@Z!#{rt6b)~eHDF5aKbxGN04YNiSoKiZ48ywz=>V`AUN zLb1ks`*!|3>vwq_+Vm|FldS>tkc7X{Cb|x$Px8;Kz1L4-fR~#y+_x0gUw{R=sc zve;0o$R00hcD{TpskgSD{)~b~n4$-`ZPF#A8=|jQ!?(?tr+GY>iZ{%bBeao!uAJfy zzoK@1i!q0wCbyH{mpy`Ju3k%{Ri>QRJ>Ylq6S-arc68=ztj7C*CZYAs9Jy1fb(c2V zbAC+IQl`(LfUwh?Oy6&LIc#+x)ayLP_}QS@)~Qn^>R|SmdEOHlVUH{$MaZ^)9+_SZ z5d2L*R$*j$wTrL1M?`hj4q7P6419Es=EvdqI5~$vHPft7MDN;8`KM-p5%VR=G00#| z95p_M0|c*cAQ#$ACmIEk{6@vM{{VuFUYmuS)JDVS((-;tErA6|N`ye(GH?B2Tg=(O zgW?2Te=NDq#`(Nu=OPgfJf2iK5fR-|+$3q7e~YhbSk)XJS^?N?;>TcAt5aaCb8cb$ z&(tFRTUu}$(BQFxJYXK+63R0jnaw8VuEDlmL6;400#I03#SBW{IN)zgfJHn(4=H0l z46oCjjmIu$|GL$NroNQzj&U;uKP|NS&>**=AT?Uj?~%#{6AJL)fgQ}?FCuGC9|bG2 zbHX55g8ox8=|=cB$3+c5>&XWu(tG)nxaNHk>yK1B1flLrp@fWRcVv?Mpq9`-t9&Y@ zgl3${Uc%o;NcEQ)yvU>bY$Ir% zmgoUy{0-2SAWquRf^qSCpoo(MYRG@?9YxOKYg@(2DX@w7ieopzy+wmgE@2TC+cm9) zjznA3@Rrs{$Jp%0r23UEyOl{Se|}Ws5YE7NS_G_XI2Cq$%I3;y$`m6V5XLeP3_R>Y zMcZZZEKgVE?a*X!*amF!lhi@t!nc+xAtNhPwm6=q0^Z`WI)u%xW`-|;nB!dUy?6>P zIT}<%?+{0^{#YN7s~94Mf^8PUlFPw(7Z_Jp*r?j$NXp?*J^~zT+{bVPG-L_I=k(ku3;#qR9Y!uTAB)v zyf9X@_4gM!Ftr%0naF`%KG1RrKocJ`*@wMXv>zya3kpLk+0)HDNd#ZMpv{}}t1yQf zd0k11&hq$vegMRVJQa6HhrX&TV297eOU6p%_Ipegl>&C)Lk^-wFIm6Xu3gq)zjp(Q zlu+yi6k6m^HAdh@wrg-9Il#53Wb`=ah(6h=s9FOA;5gPq-Pt zFe~rG6Y5xgADS2x@Q{p*chr9m<{P|yBKUXzbiPi!BJPp4!TFzW7DpA1&q6-TI($~p zN9sWDxKZAU8q0#ZDrOyjVxTX%bH$Aya3=;RLr0rVj6N|u`N4%ztM1F5&%(uHfEEMC zV8DK+M+M~c-@JG(MFo^yMPOFGh7P0R-Vpb^;Nd~o@2$V=zgVNfGKbFt4-L=|LD6k| z;aBZA!E>2;+(`Y0w&DCX(E!wSIU2?Vj^%Q>NSZd z*yLBcRF3C)S0>bS+GM44<=zjC{c*!50U^0D%9-}KPnONH z3`iB{posu&`W$BM5)9`4cGGkSEqNdab}22ZgdvR*L-aNxlBy6u=!&j9c6T^|{gbJu zRDgh=d|3xr<`W6P;~F1xQb(Os>!8jK5t8`R+Cth#BU-y(hKf#&l%EbAV-7e$VFm|e z23;}hT|M|k*hxo*sW9ifPo+w#F2Qa=^X-11x%I5+r2Eo@eAQuc&F+r(YOwi+^Fd2O z>!_{FhKPoCV}W6nMem$hAv;C{%fS?5ZmWwWe5v?+Fh2dz=<*cljpg88lpo7#upanK zV6Kv1fZt4tZh+VUpzqgLL_dDk9nu?|L`w?XZ0R^=k^H8|LtKw}kIdvbnC4)Z_8H0n znlD84shbd**ce0~cxrAau#x!W_2PzYn9nJfX%iz!?fuy*U{LGKdKBXE>HP444-{P} zn-RKGrl?7?c5Y68d&|BcooNI?u2_U>{f!;R?V9CiK;EYxPI;sN{4>z0vI|+bzYQ(` z0rmw}WQD*;Kr$+pvlf8AJ*qlA0?9wBFnyr+e^%pTOnN1l#HPGWF&tQ=Kee{xJd1t6 zC&3hkf}ahuS(Rbe_sn5j@ zCh)J8phOf%z!1@vS=@6^J@k^C^{}Kx%N9R3k|AQnCd{j0IOKM~=j2OIL*B z`|IXh696EefP_n3fkHXlNtZOE2fe78EvPRWVq0SvkX2x9DMKU5b*Vn^MP_`ru zBvM)ZzH9=GNvq-XvE4|&QV9A(q0JXZ#tnagcakL(7adI6oUICW7*RCA;>bV;bGHwn z$CJ5H6=zR7Qpu$$yh@f#{zBXpr-SHs&w&eb4WV<@ zQYwHW0|HHeCU^%B#$5NXrUXji!b;xd@t6-&%;Da!7AnyeB&Y!OIAp99cLY%r0}_MM zaj)QI^2NPBoT2X(85PGf_kasCVTYgr)!KZE9D56k!(Vu^_j)dO6h4Dj136ptl~8i6mkP;$2)+!O13Qu#~WB$=pBFk9Nf= z1zcp`AJ!+=K*eLAnRLIYi)W^^EbDt-yU~Ld*|Lm)Uz}i+ZIPySTd4D{E57@312hc) zEVHR;=}X6|11)=9lyjzZY;+>OZf?awQ9J8 z%Y>W(R@3p z^aaQHlJTF3<}vPIwrv8CI*fT-0XY{yl?OgCdB9H{YK^8+U}ptN2{=_8bKm$@2hNt$ zH`)k#=Jud&50Ro@*_XoMDJc?xtuNE4Ts5MWlh*ae1VqJH&}ZAfZTS0;^L30@;)&U` z0Lun%dCa7ThyL&%B7G9;ePKQO71Z;Ky5|;Rg1GZrVzF{To3c~blUzuMTemFweN0?D zE`ma%4@{z$G^TjAdt9Vm@F|~F@cw&0mpZMFN@c8u=NX?P(m%qxuXGu`RM*|`hA;-UUD8^V`G5y*1 zVFPVOjNze2p^Lrb;P)3L4UM28$A%k40RV)?DWps zQ-B2YT}z7GDf{@Kon$ftl+uBv=-tQNqH*13Kwv{tenXZMb$ao39nc0d1*D$Y)d7K5{Xtb7!q$6?#qx>AI|Vlz)t}H5(eJo$=a^uxRm=# z_31A{6&-E;^Aj^!@OBxBfzQP5chR~IQ7bM=7~l^*&9v?F0oNXeU6!qY=xC)3RQmVU zPBVGMmQc|8f)RLJGn~+4$)wV2D%*Y9HK5PuvSisZmt8L4o5MZA#+3R$G z-hx0So(7M_-EF(F^Gi@#4@nw;35sfCb8+h?#`yiE;-p>zF8Gz`W!oQUR4bfEi)TH~ zENyur!HD8ZXbCzRMvpw-Uy2}Pooy*?2Sl*V(f(=@eTpmkhlZnL^;un3$E?&m^pK%`;Xw3EHCskb2LrZA-)mZUYf zXTIuNNfK)cW+{?qzrRq+N$mUQsU}or-(}s#2R~&udHJd&zV0C>nX+m9RpUnt^Ao6l zl%+iQufySHKVNXW@~6hq9oI|+h@F+b?e}tA#;<%iei?7y6F~z8@z3>l3_|Cc6B`1o z360x{U#x-6?(K_Zdle!=$?8w}Y?@VR&q3m|z))1u0hndRk_S#S0?u329a~=uYK3z7 zff92{4DlQ2?{BsrAVSvc=Nka$wr^qv^dGsdmnv||?wwHl~3{H8_b#%xWLs9veQfhu^?C4(TS*G8d4IFo+`X_ZspVw>q zDG3Kz>GsCXY0zn;J)-~SB<$01+c*q__`Vs50Rtl_6_yq+am* zQDOohrthpqug7j)WM(-4R;rKoFyQ=FCeiSZNk)KwXG>4@V@r>g65Wsix)~*ZvfMRa zKcm(y9XgYM4c_KR+UVf=+UZdVzkVIkP)D0rH-UW6rIZC;?;@grcihWS?KcSrbJhk; zBLnI4soggRraX{6BNfTT-KX}b^Q2RAq|CvsctttQ8!-47G;s-|!P7G$A}?aw4{YuP zt>b<(@O@o_LF=M4Y9TNUQ zjO~Zve}|`0ht!c*a=xRvt}jn8(%hx5&o4Eg5M3N+HP@L^FW;ZK4W8#mj2-O<%ts;> zYQ_IOqj~%9;l2o>%T`^Fv*X^}^Z>L&LOhU!%$AY-!$C5?q;>p5*AN!HgN(g(TDqm| zhBrAMdM)WxR}oQFU2YL~E9zyEBYk80><~OTrXR93Wq#)Zg_o>txj=;73}&@MtM%+$ z_mPi%4r62+`ZS1w55cjKq4%S>38a6rL8ro8rXm}81qIF>NG;6~?ku0B6`kOxg7A1e z7$VQBMVlP(#&g8e}!mEr!78N-b#n~MT%98RCFl>>3(kXxDFP4h1`N35H zHoB-6exUW1v4Nt+(jx{IdrW>pxRfW^w~aC7HuW0QuXB(3z9f|dh2;#?u_lpET*DNT zE7t`2w_n)sH#19;Mm+_f0;a;^#QlYi(3Do~N}4$7eura&3!eM@)25|){<7Sd zOD&rg)PlXMOprF#tnOd`9;N%$Q^G zrfoP|9sK^XE7G>EOU zS0GrM1o$xepqT?G2C`Veq=5QfkNV_(MK@3aLgoX9pV+H;ntdelV|xnoi5RF*>1#Tq z(1<5iW511>2ErTvBBgxMlT_A(GA<3xBTCE>)H^@O>>^ZA=}jW_b~PyTy|^ZuHMR10 z>;w&kHhz9d|@x#r5J?mO()r zd2_VD=T`}^Z1riEEeCn&fweYYhkaM=N^90x0(L?_#`PNpiM5X({{Zu%XfM?jFs%m| zR)Rdd#O26wB)In=3-Ztp#}mx_d_!F~Iva?)6mE|wP1~;!c$+o@as{o$k{kJ2@tQphe-kTJ+K=E8B^V?N7VPdet$eqv?hqUhuuszUMb>dQak|N~-jAOp!v-S7 z_bQ9L_KB!2t~O3qrgeAED3n*|=e-?Ln{5Z_Q(_r;yq~t>I}h#FRMqgHgBQ)qpsuQy zhJ1{#2I)iwAMbhe_8o$j-dS>JSWSFTY-#Bx%$PZc(0dgWfTI9F>2^vnZ2{Nu+vZ=( z{9;#8VjYl|hXapK4quL9%LLDwXViT^!04{wR|d}mm6u=zU3`r>S6%OO!dZPRLX_-!(#+*2m33^WBL|{~iLQv%Ue&4ZzieK+TfKrEUP)^+7 z4ya1@kYC=~d?z)I#XdQMI$kDEM;`MJpm9sogsimgiz12H;5fGQ2(5e|9Mb0ip4x^n zg)1D-g4MA!3a!X|2gd9g7`MtS+N>A+Wxkrl{SOl9ZI3~oS#}?3-ie3Bz9ow8GP3b4 z40f!xH6^NTL0;gw(Q&9*#(;wF z-VA6|5`b|WiYYY8THs1ynU^OI@mYigy-hB-X%)5CWn?m#O4|g8p99U`Df~L(^eJ<6 zzrtf~5dij)Jg$Y=d)&H-CFBby6kq_1TF3RIpGVI2$sGRW_EBP|%H-ttp^d0;F<#}O6pT19g zYxkiv#V4u>HwjKTBM|_y8bGCH5bZG{mp67#C#W?k)OKxoe#hA%YmFZ_tH2EYQO4cM zi;F?f@CV?F<`*>24=!I=*1O7F153u>pqKo+w(r6o6vOl`hep2n>)E)t9s$`yTk=yL zz|_Ot8vBgoz!1#vSn6IcfE6%&5Fa%r;h`+mJLexZXzy^+vhiGI%J0aB(-Era2$z8d z{AYIGHYj7Y*c|NUjwdU?FNsGTFjg=}Z5edZ`l&h;4G*ME6pCrRv`T6X9W8^UaP{_$ zv&TU1Egd~NUCRo6&RDVo083MRdC}#fW{t=k^2;cRs5K8Ls-d`&0()-KOvC8|BG$4h z$xNdpf(4I33r+LG-zwUvVXRaF7bG?tVPg=r_TiZMqmxI8mmPu=#roXla#a4edr{ED z;J36B2LMu*wT_5yz;to!*>1#H+R^l~p-lxzvC7id)dGr*&KhN_#L^^$??KBI81hPEZ) zWO|0njpBe`;&dPYG6k@$m}RxR$7waI@dKPv?Fh~{(T-H{u_Dxp7jV9&qEzUv?kGH& zU%32?(1tY90qyn<;p*Owk%`=>WMgD37odA~Dv_U0GYT0rli)00<#M8Z-)5F2fo zo6*~&cp@Q|Y;9BCXUOSj#nan17=lP?mQel#%Wy1P16CM0l_pIu?1O~-!3;~HNIXGI zD=0%OIuOMLS(NPxOHaH`i-B)A6{I$OTpwCwZipWQH+VTNQ(uGo9p<(L+>Rk^!=&)z zn7d1Zyu~Z8lnnHn((8ym$`l-Jba>yb=OIPX!W}8qMf$#~?0b z%4lh@ph`hKDvx`wO`vC&8}1k8feh3x05Nyl zi=a&NChs_QBA+_K01YG&j|VO@8OmwN_ux}NVeQ--oeN(~DF)WxvZEh9wBrMD2*{r_ zk2#zyzVc^)c>iJUv^YpmHf_6$d-^z$wgCIBHGwMzD=tGMS*l*0XUb#0$D!h|2<2F?jHvGMxdeN{bK2E21qqAqf&P3B;N$GX9<61HQ5~-Qt(z z2oQ83Q7Ea0XBeHv$EccRI<-p`v8IHmC=4bM0h6lg|>Om*$rSyBMqu_g)vuFtkoawKCbNsiI)o zsTJi^HOD%c?9yTrdGdlSeo>|)+W=EUrHhqA>@3y@`qbt0) z0=1O(jiM*9ZVDBWuCrw?><`qra4Bzhob)@OJ z*X5f{sC~I?BT`8Mr{6J<%!0Hw_>MUD{4nB|xXjL4ynA3<;kCOM*gyJ^*whbSR2-1L z%1nSs=>3-Yq_c_8o{}W`=5z$0zOtIwPvH_zv(7{&Jn<%ZP18f>zr$Xe3^hY7^V9|z zy4in_?1d#G0K5n4;q~a=egpjQw$GB@*j;=|+6#$Mp=sRU&WVQk2><&+ z(77={i$ie7f{l)}HS$B}x>ixs!4&>C*1U$~tB0iDM0k+-RzXqQ;0dcs>O@{f(Z726oB2W`Wz-`Rs3tH4GRbWk}fr7GmH?rDGBxHW$GAeLQ_bldD~D8nK6E2V-?7UJ;Rs4dkkF?J>rpaQzKwbqOK$4%U90ta&88m>wOokoo;%0J;p*ZXK0GVJLbO!ro zmta?lw38v85Hr*-H5D4QkNJN1y3jnQvsnHb@FNSBR!?~&Mtr}&(c~|x z=a1>NX1RzV6KGZ)qm2^og(U

$kDNg|7XNDOiR<(Fah!I0%zULCB?3VCZ;#*uV$VLb z{QJG@Cj0bS2i7DO6j^HHFPpp5YWtP5>E-v=H*@bW3XU`{VDCywc-d=k=<)2+b(J*P zvq6&MeLgFPfu4WoXVk-*)988!fu-PigdW}?VY`lf_l2Af%wx+r;_Lop@HG3|l&}Xu zorYQSwDA+#`P~DWOVpT*sfTZIRHGWQXq;Dr`-?R=J)I%4-W$@IRhR@g&11Pk(IN0T z?cX6rox7CLs$AjFB;LF9pAFUtue)V$ES|l6Uc%{t!Wc}315jO0!F@v;GcN3M2%6g? zx6qw>?*RqHwLWA4E?}^0q%uZ*yZe$WQF}5YRuKazY7M$C&hQEs^9YDvCQQ?v$q-~0 zUk)goK%Ag!k=yo+>J6oMhB7e{lR!=uQ~!nDLlgPLCya(sz@4ri=bjJ-dKuSdoK=p8`$afEU=ChCm(M9rO*?I-$Y6x{{lRhe+NIMK`T)m>OzU|x z=zt*How|85hg-nhTNZ+xnm{&X93;QdWPSW4eP=1yuOJKBssog37$ZW=wOM6W2%}N4 zDpq7kl8lh(iv+a2WSrfW=!VXU-{B`X-`hk0xz%YnHD@K_X&1u~3DzhTB4tu!jVGjQ zPI`BJCg`J8Ut$`tQcVsj1En`W=Sb4L^NhojT#2cEwtTO{9pj_SqjRVvB{^8-6tzvnh0g68!Tj?qTdi?JknyrL zj5=2a6_T}crNdtw#<9j*qdrvDFqg<1sj>{a9ueITM=?Og*XDD`@r9}{inhkUS{j;% z4&3Xg5GKxqidDUYnTd}+7d;IS#!DWTl(;0D6K}dm%HmlIoH?XLY6MixrZO~c{k@}w zxCS(0Piz%>A%^AfBI+1GyP8=xI#{#=p#bvt&8)JleVEuUo_G_Y>lR@!p6Iu6fEdN? zl?L8OJ+4RLvPwYz`g4FjYvVkS=z=KvRfG|60i-(-q-Sj#7h{%L zL-4Om*1&#%ZpSMimfT>T-1NL;1uy%+k4Ww|?a(I<BJb^Ou`wOvB1~?+ zf*G`$ShjZu+9A@y1{e2CKbyB~(qLzbli96CPb|A?$~nA-T;kc7wsXi8?n_uq~W zCl76NW8|VCM=^>?t*q&%I0hp9IZn(5FPgxeIN*GchH)A(LV8t}Uq@^XtL>Yb(mzA> zwzm&odOrED_bdv52BQA*jE$ zObcID26lwTVnYXaridx!#GOHv%yyy@a3|&OA#%C0Cna>EvjqO_-MFCoIBXDL@Fw^s z72DaYDEgN3x)dgtA05oOZ~x#^1jM#+8y8HDe+Dh=qX2Ni+B}B9}@dX03 zpaj4NrF{DV7*(1ex(1tIq$QSRa0oV8xI5N(ZutB zhymniE55?#@*&VK1{SzjR1(dim}bCQr1mu896ND2Zf_&q`gK#v1*H~}2Dwj`AM4MC z;Sk}8je5$LBn`bdGW2qu4%5hB(aQL5lOXn2(c6tFd-qT;aJ+ z)@rk$JeiXCM=v!DMil&lk>PkYABkh7*fvUW1TVT6hAA1L6Kv0^D)M$Jp<%@Nx3&vN z&2umkIrPA0spfBTv*>M4^7Fcnr_iL7KZJ6g>kq1RJkJIU1H`hVcsK;&<@l{yaNd$#Lq$x=#@r1P~?@>e^;{G6S?$`yB=mvga zw4leo+!#FP>X}InfutX&MRhmzLfq@EHHPCQ691(>xNkd=x%vmZN&v@x_w2bCjGBZ@ zqreT7-Omu$N;sYK}JhbI@GJ-4>$7wOQ+ZLWCyT!)0#5igOktSo6OeR1fHt_ z;ZDrroqk)aaG}&wBVtxoa8EBHh>y(h9qm|h)#29Tsf6yfDIMhF64JskPbII}_nHtP zB!?9c15&T9#Y1xgYi-|)z5p7pNrX*rVQ5Rs<3XCz7~*v3T6TkIedc)hl>PRH%wva zsc;{ms^SQ5 z7m3iOJLM0pW1QdAW+(Afi5|rnW8?&Ziw&R!`{)>QI7DN@B(dlL4)R2Yq7+RWoN?2p zw27m!7wXb2z1a3$<-jorqDE+#`A}QWB^z#k(LR+Q_)`qjJBsk=;7Or>8iipVZ~eR) z;56MOSSNCBdnP>xY~-u&7#CFL&XI2};FAyn&=ki3|8aC4+pWT25Pl#Q^tLp;_r9Z= z4yMD?UvgK;IV3ice$9MCkpNnqTQa-zL5>6>S}D3%%8S))Oe8(&RRm0eq_m`J;qgv^ z<4}eD{CbrJCDmAmJIX57>=qLIj_EjjpiXKfRI+5k7chZ>f#_VaG$soinBK9CXIdRR zafW^p4QFu&Vc)A@}#$T)R-Vcr5Y$8r0)(CO(L@d8Zdeg z{31lMq@I36(00U|d7$$A)kxLNi#jFti(l)=GeH7v_d3Ya_!r)@j!kS>7C!j8%6NWw z(R2GO*D<`R2Dw85(EPz4N+U!Jh3!JL?!Zrc`-I6G!T}N5usI+=mLFq;D-8WC1>&* zjuFq|CaqAoYnxhzEh!E1N=2vfU|+C1XvtZ9DALP){*y0DTf@XESsYn+0|n|D8bk01 zH>33A)xIOo`x_}`W%d2eR89t>w4Xd~sx~;8cdgJ>+rc!*2y0Pt5C8zEL>1lxa@{OU zdJk=ry{7I^VyZTyhD;#eubE-|b%f#;v*7bR#_Y`_p}7J2hU)gR=z0M*NkdMf0aigb zgfKi?KX^no6Syff#&DCPUHQv~7N*nCedp_^TF9?+WQbT2dum{!aAOSn$*z8fVLRN2 z1;fh7#!CB_Qpg!6U=M3aK6jhu2mnyQtuE4LO-jkkq(jzQm)P@SZ8)?coc$F8UyRhbjVfwmq+F*4Zn>Y6 z6>$z@m_%zNr|3PORioo$h@EGRNuOA?;swZ)}g@fiN9klL7bt`qewfH zzg)}6`=$z*0pg$@%O`S(fu>PoJBbJ=tW1XP;GlK1HCWnOmLw7B)?Htf5Q-&71wgHI zL=!R)07F2$zu8j>Q4J8r{CZ(H8c7F-g8dc7zj|g%-u~P2)LqMW-pk8wp(gXd>8V1h zzUI*f{N)k|TZ1@?sFS&3;Lim)g(y1PkN>Zf==xrnwD2c31n;h9dqww7E|P-DFLp4xCPgpMLUSO8}z4`jJhKGw>vZ3+6Eyn7g zz{ws$QH`2an2;9~6K5^v?`&E8oSLsvjB1{<0NP7EeD5k6D5Ma=Vgq>5aP;Ukm0Ef& z7~m!qZz97fpz7rfy-5#-5B8>}sC{05iQJdkl4Fm4hd)3C9Ev~H?-0Y~4-|k+sKK*-Cp39X$-{h{$&@X7>75RljGV{%} ze#I#@6Es0E#kQm{-ST_>{ariDO{-7CKN=7o(9%l6+vSF+WF_CV!N@Q9H7Oh7& z%d4sVICQZNX1w~XIbTX@9y*kRtIOX#p}g(c4I^XpcwS1!LrmrKOy1eg;Zb;!A(3=xYZl2=fJQkyZGR_@ctaOH$9^j~WLAn=JeB&cby+925j6 z-ZHjD?KaDP%qu1_md&W;XupvSlH7C#FV5Y&H_IasKKvML;Nu5N4@UX`sg29pw2oW^i0RTXR-XugKPwP3rctuA%(i??qew$!9 zn$a4?Aia50i_&%u@r!Muo6f3FrkjF3r-x=rJq)0cdg5d!Q`@SkQ#~xU8q{g>w_2_T zyfvZ;b4-oi^^?N5+LPcy^xMpyP%F(`N{hf?1q|fI+L!VSIcFAw{;m;@-q+C|-W!`)j=N;gz&T`h=>7DO&-;b%OgCe}MEWPn%w3{E5cZFu zh`*E4^_Wi)+U@0T1jTv-Bhgy=LMS~D6EQnrx@RRMC9Z#{C3duz+p0O>sw7~e#!_q( z$HAwS!Xm6iiHpb&|HNf|uUe>!#TFBc6V5*x2OR*v^x(rv2k<CxF5A1%7$9i*PlZETGm!dXaZZMi70V7P>bQT#>blj z7OPo;LBFND5SDwD^ER_VhYsnpdcN8go>^a*B4rYcm^oUtc`y#LAD43XqqQ5T<}zn` zi|#U?EFAg*G5}gIx}n31y~m&@F;fmHL$baa`yiWKSKX1LArVk?7orafmEH1u@=ER2 zkh`k50qD^0$1ro&mMS;8KA!LUnfx8U+ypE6Ql8)l-yO zyCb0<3^XLa5{$py%x*IFEILbaILh|zFXbf9y!%j*sq8O?9mEl-5(eR0`OdguL;G&w z@S!oRVgK#F;>Q}=JvF5?9xOfHCNvcw^ae?k-2TS%1Z%trT;6=(6Es=HieP4LhyeS8 ztq)FE@*>!KsITL1!f(|rlls)imjTu_6*xJ#ox92hB&Al0R1ZThh!U^tmnFssDb z-SX848}qZotfu5876^t{vo}E+*60O^>ggwD>Y0UZ&drsKoE$QCbBfwt+Z|@YO!Bjn z4>=-~K$xjnY|7uWOz>YolmLUG*Bgv>OC{jSHj5q^{^MM zD}z@RN(d|6dNqb3WY;y+n^T_f7g3M6wiio1se27l5T^t@KR|d7(t$`8%d5gM+wHdo zD5VN^&be^F44q9~12#8N^$_87UH7MD+Pc|pPJlQm;D#XaE@5oymTpH8=$4!LkvD4o zt=Gf7skkDM9o|kHGLfctTs+R?3t#|;MUhSKGbY%Yf*`S;>M(gyR*~r99=%}N5&$xE$(JVcJ%949=6PXj3)~g7#(OY=RP{`qssv4jE z3TR5x7I=;}0Rg7&Q5v)IiJ~fAT5T4^l?SZl`ZUVQ0h~FTh#XDuvb>{*NE_XESj(o2 zD~Kds-(9GemEgV6X3S`eY=jxza(o(1t~p50)*R71g^g5Di=I%GfQp!3gz&l=adma9 zI;2Fo6cShbj_pdl;ne$lp|&hKTl`(?R$Siad7=2c%g$!53qyjYf3Uwr+AKsgKgr;) zk<86$m3i;TBrGah$vanT40K?Lv_h^e(#-poKy2}}Fh(c9em`Uh3zg+U@}&hc%*R$Z z@m|{^>??=+_|27f07!I=e=ttUZ|x*JVfCsmdr0?!bAH1k`o(Aj7McxY`dCxw^U-~V zOQ=jsn0*`-*XN0@#3|gVp5Q*In2Dq^0wq3v^K5ry6@lXq+o~oe!0zvnC-i%5m3JDm zp~eu^EN$Jd)rtRLYK^V=JBu4@rWHk8O?mjNay@X@O@itwW|wx-aS>Cl3;mrY23x>- zEwTz?=X;R{H-fD6#KV}7hrjfh%9eN(sasqQbaYKfET6~?o1jr|=pR$f(D!6uQr&+Y z{G;WrmE(*bcec(?kSoWh2+L!R(GQ99NCu3Yu-SCntNTu361nARN^eU_+aF|>ar@=v z;i+~EOVci;U&&-U!R!4$hL}%eVn^?F3H55_0ikksnZ_To<$gt9okV2my$!k`we@iH z(sMd0y&3Tvo$0!XujvzNSss=Te1^5 zZ^*2F=gZU^2=>F0ah!Ab#}BaEff$?&N~D;*mT7~C=7{W_J2GaBsr4OMT8|=-+*$`Y zTt+k1%MPAgs0WKjnj%M}J{*y#sMN9d8H@bektJs-of&oGu8h2CEX;k`x|q_v=NnvN zG%We_0j{X9WF=uFeu>Pq=k|?sart4e?DLjkAqHa_ucrttA(fZDYB30-k_dhdO7eA! zQYVPF=g2!#efStqYv|lizW|V>ePT}bwH@DZGCqpQ^GX1pXqaz_(LW?0zgj5oXi_{p z_`2>WM~MO-3Kqk4Mt*fvFL{f<2i0zp12&9bKt|&S9Cy>_r#B)N>aTB(eA;r9p*7*p?gZsBK1l)y2t) zXyj(t9mBQ}AnNbs1T}bYT(N31M5+J<(*@QAzt8a;Zt}deH{|Dya~4Y{oRIujP*U(* z@iB|PP#74C++SDDB(aK9s_j}&$E8=(qvFCz*y26uTCCdh+EYI~xJUzgdzC+0`rIxt zGs=(lbAH~=oqnVmBl$?2&@K6HTaU-rTlDkqaZ*9N0cy@ttHd#G=%JWG)ku8UQ6Q3X zkik5Nj9o40t2tIME__!kXsC=~gra;#Z9lWUpv%)QJ$f8_6H4qrv2veB;k1U*iMGda zK7x0vBk=lg0;~W#1eT(G5KC(HJ0_?a4*)7iB8?V4F#=*xd7%A*?d)Tup;d%F0pI?I6+4sAVy zj^xoh=%ng}X)Paa!M-u=m1Y&PN5G~V=UXq#d&rR&Yg$^fG2{Ev&h#s#^Ak5@XPB1h z9TYR{SRiuW@j5CRSCW9*X2iar4fXuBUrsjddrJ~%Cm~rx1jZ~Jp5i#mC_)*al^QvL zC(J@c`u{r`#?bqk6X_$mzh zf{LXdU)Qa{H&={Ia3Cb7ivX6sMU8S}0Byj2#)9w(hQTL833zpG?0EVnH8gs$nBFdE zNuDg+>+9uYl={v4X-3i0Dl0W#n`DsRl0lAGY>kbHN-(?t=iHi% zfw6*$MfYRu+q7QF0DQX+`MV(Re08f4g&6N4U_*n{VA0VnyMk=|Nt?zwd22EBpwPt5 zpRV{p##Rto9YBz&eyA~93gR+djOr@IZ$=Q1{u!oR^F+lA$=IhrU>UZQk6q{FZuvl|K4rv{qbxLsgNvf8QNlmGm)?n4!=lMY?q`B^kM=Hp4+7)mRp_+5_vdc<`dIKmBi%p3|f`c446HJ zb*i4apK1IeHxi14Bx+CES)}y?YF5v^GQT6kp!53^Z0!J$ zc*}yPGQ5&GVhG&^?nRKHqjwwXG`oGPn&*vJ3Ce9_2(agq1Lie?pxSS8{0!v)hF75^bx;P*l8zn*hAP1Z*iDW#SZ|>BwMS zbG(5;4P8|@<7H)w3-f2-TCaQ-d=_=&Gc=joT<}9=>{z>DfMJ$Du4B)J0tOvr454BBSJGryDu`ejbiQ! z%@9>`#o6guoWs~Cep``3wVa?T26`d)5h!5N z%bqwLeaXs>3jJFh2)R&LB}(rcLNgep!MC5MW01i%7;F_M7M490Ys2lcJ~BA~A(lzp zGG;0eN7L00*7^*J#inTTfoTeHpcxlbk{*}Mkt+M+ndb>+**TqGyr3p+IjC}Y5@@Df z(tW-Ju!)K~OI{pr&gf+HI3)Bj`)>%SLFz=aK7Mw33M{mqI!{9I<-*Ss;HXxIH3ncF2X?FMRqgGsM6HBwc*8m`ezJ}e{R;vO@!ETVwx8=yCMVB25F_JhA%?i(M}I1d$y)QHAZCCMX_%5q78wF^2_Sxo79#hZmpAn!5cx*_=tWqtj@zFQ0?#U z^xVHw17Nt}f%KThIayT0nxbbY5Xm^;2v!Y!2v0OU;`2clZft#e8 zOZx0OB0ozgU15XZ+8pZ@+`A6NMX07k>tjoXk!&xSPrd1AXH-&J7^9rOSa1WU=JGqu zaYTQR6Tp73?3RLq1drpiwjf5S-?bcR*PtQr)6W(Uryl+&+mGqrPcl`Ez)fQHpYEc- z`5T69Ab&pW=i~Yg6KLm3%Uz!V97{fU43k%fTTFFT*RCqzsh+XqQHkyqKdt z*`PJ&Jn~+8<%=y-J$LlJP=k`**qqF*=q;|%rVSb1P{oP-opc%xQ#BkL9DNZWx0e9e z&f5lPm>ahO<*jw3n-y_};*q|3x#X*rg(d{N4cbrOZCiL1HQ;_(4%&a!VW8rbvVF!! z6SyU!(Z_y94e>3lsZRd(vI6us@0q)5M7*{nevtm&;BNX7NHAp;S(EkF{M~)@*{jSg za23l>YBvjR7EuljUE;FY#w{(mO@O&CZF&%ZV^Zlx2Y6**_wsI_jd~Q4?%Tr?GdPE? zf{ryflcdFed9y*Q%Ba3nRv_OuG>5PmL6LHES~PoG(RkrD+nX$4_jY4?78K%EZX{*R zBiRMRV^rc*)YsiO3 z-&Bj`I0<50gu>sg&J**|YDloDEn~RG)`k6~B^q|ar zRjl4BpPKS@0!{AiB8d1rT-)N}_szp@auERY+5;qt1Zr=)6fo3QmP~J1Yycvy3naq} zFCz-b!F;tW5^=uZOLQXXh(BS z9R6CxPo@sP>qC7ck*vNl4giuvuZXG{GI(aoMb)K8X1sX8iCW@Z z`U+hw0DnIJ*F2*l6<1Lagh~3>s=$)8jDu0x4|g1xC`xJ&<0bqn+y4kzJ(jFvpt56=I6 zXUz8&3#c&r5pL&0XXw#C_|7r$4p7@RwmPcF zL{7x@fiWYw-x^gnd%cS0@<4H~$$+0D zfQr3H8-s>xEX;2Z{ZLpjp7^?1Rd^Z*SYGN9eYZRnT$)Vm=&2zPgs-_t4wLVh#Oyxa zZt|SZ#N;{f4*VRSC@Hu~Xst#C%;h>D)P3-wij~}FL76bbjTJp8Tu+Ul3F!hz$h4oU z8z_Edg!jXv!$S6Q({hv>+Z&CLq6{uLV5ta+6Omtsn4iEYT$vAhM+Y}(mMg4{a0IDW zL=24mfUJe`w?39B<~_I#b+Af=>{t!f?}og8>9kxi{F|!k^SE53eqIhOPvd3z^(9EE zJtH6a^!#MruIVbjrOj-WR7#?C4AawF<1)6N`_#S}&e%AQ0r!19ZozU31S^a3f7fXr z3;p|yHylq%m{q`xnVpJ1?WyE15^>XFZNGH#QWth(IJVVF0tqc!)oEoH1jW$Q7f#h8Q=V|LWCQgFu%`T%mPV8&sn~$H9xt+} z1A<^k{RB*8BiAY_J6BXKMDU7mbCJ^D<&mCKQOfhqwFk)!iDFbO00E<@oNEr>iS9UX9-cXdpi~OEb@*ru6j9 zqV^hk*DO&cUk_OX2RUWs(KI2oCsl*8I*5$Exn=suLzwbwKXC3e{?AM`>V;K&hhRHN z4n)a@lxkR%R+8sJs^cW*#b7qYm+UT)(0aY29mDDju3NWc{vJNxA>;n;ruMg!cK1Ez zL2Oo|=9FOT+~ACNJf>@UMr$jK_h1c6?>G)yR|dQ+fB`nwmj~N`Fe&a8{s@N(A0-TRClrfN~{C?*p-=7c(0`YS)=Pr023+_R2s`rel%>U3iyB8un%dj`G4y$A&bBsfY;wY*hL;Y} zp8}`kc*6tWPIf&6Xj1S%0uJQ*Ws%mCFI75q&RR(ddzF>mHS#{*OuCpDp&#CK3T_E-=$0}X=H**hQ#7U^HTX?_-OzknNXUMw=`Xqi-)Z4FAFw4chM8y+jyjuC;g7n=>AZCWAbTeQBqKRE$WO0 zGyxID{j-1|rg{%lKc&D6=3x^EUG2W~02;#3q}z{CeUX`PN&ImAidEvINc!GJTyCny;pzgx^#Y*jkKD_eq7&Jz3!fMfHIBsFd6B-! z=k}`v#!rjJ)5GmUpr;G4R)BI501+s+>+-G^2Xg5{LO&3&7e(-18+PAZ@ztXAvz8hp z7IXMfhzI%P(!A1UhWQ8&;3Ou~SmB0k;~Yl(0i>$Jz4eRJrCKdkj?5^(;r`IP!^i^H z<4yJX+iBC)o^|m$J1X?jA&*e~e6G7ff&d2Jw&Y+Oh?cX85!idz+g5KyQcj0pr)%k8v z2e~4}_9f?gqht9s7r>G$DLWbD{!-z$9G=Z_+w|0k#>kzpa|-J;iQpa| zw#9J?>x#~^kn$4FW3Vq71akN>%~Iol7vY?}Eh>h#thWHk_5`5y!U*S$j?R-}&pk@$ zN3|Xb1mM4gVp)k_sYoxT(YQe54M%!vTh%cnqFTBbu8}_xVKp_fwvXOZ5AtyIdtT6X z_#p`56vxn9@8*Yc@J5jX#&HKxi$NY(V;>9YMEOVC1njsnAX}x}GVSq6$o-h=9?0qr z%8@w|K>8HM#ZzkQ@`|cNzQUu-bDG`|X*1^6zL|I#;c`@y#6~H2LgA0ePoc z^gR)e<7**K-$XWc7W)HnOGnKZ6#sJSHz-0lN%OXRxx3jbq_!j}<2S2)P+>4`5}*#u zrnLajEf>zSJJ4e&u_P@6%5TEcW#CGx(i09qI2yIfBzDwCOu(>=gbDmyR?jEDpT;|R znusM80O@2SVn}Lyh8S#F8!SjcA1ZOq`9uccd1*O{q8v1a%O?f3m)LSVd;i$@SUmMG zLWkNWD3R4b*vWIT*52b#uzK7eLB%-60Hh0UpSA zdne4piZcSZcFC%#vfZ|Ns2Z83p4AAzzlTfavsr#fMASR_TFSA-i2Dk(GHx{|_{*b& z(Y^L9f{)|pTbKnLV%9jeJ~e77z5@^n1K{T^Kj6dqW5Ov4R2z-3wkslWPJhv8fgnBo z`Q{2_IzV$vQdEK_(hd<9qix@1Wz6Ase7t3_r4r5vk@i`qTp&8CnO>s_QbMNyTYsc>cP`87zirt!!=S zvHgy7pbnWef0Rkuyl6A0-QB-wf^yL;ln(IND2iDqTnq-?+J=OGSQ<@l6B2^$iba<8 zRMhD7cU}d?P_xI#6Z%AB!Ze(LnrMeF)dMJwlDAqN8;V+)QS^J>GnrOR^D)+hXfiB4 zJ!NMt<05o1I}lb1wcqU|=uo!$t}!-G>y)nq?8Nouk#bTdNnf^S2n^58MUYr*^ZgcCz(p57&bCAVR-x&$)DxM^M1!Q9eD{UTVZP8r}{pC0E}Tl&@6I!Kb(wzx9F(H)HWP3)Chc zQP-I{?AyM+SoeAWShzkTh1b@+R%`Qyjwq~o-B`gCCUxsZ&QEEiqMqVa4p0m4I1W16 z{Kybv*&+=Qzr&@WFlEjNC_QBLdZrUvt@kA*Y6`5Y&%jJ@EQxqZ{0@CulB~%T9_l2~ z6CW(;Z@tDRw|9tKCIb2X^3Mbd4lPy^jU;SuQ|uw$PGoC}rT+IV5C)&8A-=|1qJxr9 zrD)y@ipuU2yh-W0K>5l1w}OBkwyc(%y>@*=;kPGlB}?6=Aa zo}JzK`&FT3m;}Q`=b>-@d`w;4eIKwhe)(nvT$4CN?f|JaSYF5(mdJO2NfRGc{~2A8 zAkpV6mWD(yEA#kCbIUrkZa(Z~b5wNo69Va22u;yS#m=%6T1bCeaW}@-h^p?RO9I6} zSb}1>XSMew37Bg|c2Akm_1Z=n8YYrQ(vO!DVh@hyY)*LePbp*S*3n970uz)x+Sr%; z4=z5_$5b^4JPW{xA`9bS;>lGx{zVbD>aue`2+@S?O_zvyl21OKb4Gm;zKT(o)b2s} zsHCf%dFr!HuW!}3*GVq1+p2!DA9AnJ-&>c@;>)%I;YL|oVo|DI0>HoSQv_09B5nF8 zB~FW?8&j%L3aW0L{IzlMUNz8`_?D=F@e`O9FnoBttw!b<#!K4BNz&w%?S;SHracFTBadUcQO@r1R-4#@o85 z?r?gPG$K{m?5(46Ii6Q9t8ytP>N_?89SRl~V*%*DTzgK;=W#D?{NSv97RAoAzdqmk ztx)WNF=>(!*tGb1jneKr^f+6hBOHUZd%cVso6q_1=VxGsVlM|eF3ooAYfc~(3NcSk z0fU+Po))n<_=1#wKkd-?S&+5gkJ04qWOPTUO8A>5li|G;{_B_7V1qe(W@yn>ukIBR7;n5rvv?GLmzqP~S4N>HP};KR_Jr9> z!;FjoMem!``$%wnfi;}+ZClv4Ixy`Rc127cqRpZi@Wc*3Yo`a3r}jPR!;oIU*9~3f zSB|zl!2}4u>~7ji>7b?Hx6zxiigg2?f?;N;1Iq`3fmJ%eHysBgM;EHibT>3syfk=D zT=WCP=RB5=yU_%!;(ZY$;fV=YiCNs&kWa-|;&!*Y#_x#59QzArV0ydt)Ot!+bL2XD zv}jp`)z+$n5V)G)Okn%{^?#5POgNQmsO369m=(H|S@~qgo`m|p!0vtJn_^C;ROB)g@8+_X z$5g!hb{Hg(j+~+F93CPxaLgzSxd{DWV?7H^AF{LXI=xr5;fiFQ4>J;WySP&iAuS7n z#y-rA17zpRoA4sn?HjfcRB_)@nXR1!Sjuah_V(FIi0JTQpCOi3_7OTWS3TV?xUpR3 z)paWmA~}LV`|A(s+jucPqq?GKLUj%4r=A`zg1{xJ;Q+5<6XR7ik6UM8?2g~K-C>cq z;Y$-=wzqY6GZkut9TG3Ay0Zs^<^y^UZmsBm+Y_Jx__qwPT+r>GG;gNGP1JB$hWw0? zIg>BmFc|!BELi$p-jKqA!5jbyK=!|$IJh@CRw`;SbYjP@ccsjvKo>bGTNw?MwQ)bl zQ8;Q@UDi_)HJQYtbbQ^YOUZ?yB<9k#<*HCJ@?k*J7~-(%gQ=@;gl*#=B0a79`QQ;> zv_(O`2Ora#-5H(a=ikSiQZ*;j@5JiQ)vjLl3pqvTBdwExOs%=z=a*3N`5|r&8Pb5+ zx8P!#QpH;2%i!?>$8e=u43}G+ER^x+De+Q^fBuR>mf8JQ(PGVu(2*-06Ovt`9j>6P_R7x0z|ejw@AT~%MB5E7~UOsIDcqwKwyejCxg>fNjg>y z3v7Mbto`YwZ$tEUpNZ_KSF}Y!v|mY1!ZE=Q&9YKd#vX)Wt8Q z!~h|Y18W(Ubm>Vx!?Y`JjQ9naG;Bc=6eUL!aIXoy{9-Q9#^GForC!=q$os}cd+QC| zLv^rwH9Ex^H)2Zt<6~UpwKA;ymV18QHF^vbjS52A|b1FDQl}5QGl1<#uO;A;1@f%C3v#RThtmNLNHGRG(h-4u)CO~FfI4pwrM1o<}7JN3{Gi!^_IQm zvnWr!gG@Ddfq}8hJHL(PSXdd#>baLi`v>>A)6{*aKj3fhzCh%LNw~{>ipoK6Z=0X% zzq!3wq!Fm86&w}sjt|e8_6JjjpK1MlV(7J25vO_b?c=5x9t7H(h;pIW(-!pQRu}aa zer#s3W4Ka*J_viGbW*FEgz0ey%|z(9T4`{UBK?q5Athlu+o_;KbvqaTsEc5Bg5$tM~@*_Gp-Yp>y2A`W0I`@Bo+PFIzwp^o)*u_7C|3f*@ z&v-L&F~Yul&1lt0QKAdGL4{d^drzkHaL+q8^T6CF$u_F!7{d`Oo#qD!SSS!VgL^VV zn!*o|n$Mu6&$YXTBItda;K&hNJ=_~uiJ6f9!g#-Nh2)t5xtJ%Y4Hh6LgD%S;D5LWg zE4`z0rziIQcTwMXdokgeXmtU;;lZLXy^6%cd0hRGb$xtd*LB)d_{I|vQV90-Z4JAD zqP6NIVnGJ`Oc-uUpEv&}m7}6m!a`^H8G`(G?LWk@HNjs>EHL)(n`T*|O4Vd8h#j_7 z;0AklQ$k&vL#x~3+QW`+^PAJ_QJa%Z(v_YC^dq+hEXxl)Ip}xHpwXA47=IvyQcYV8 zKvUv1LY1gEkDrXo5vNF$;L*!F_jf}8?}~TdJX#e+z!8UYV}~L&sR7{jq2Ee_-ARL= zVw&L`zpCCwkN0>L4Dc22=DXLp+uIQ%*>?d;AoUH#p5wf%Me3Ts<%>|HC+Ko3A1_b_ zPH06K2N!l%;LE!e<~_1sKcC+@q*{+qycLnneq)GFYWD|yz9IU%K<1(7yavT`gw#X) zXuFRU$dc7zXZYRncUc(%0e_|ef*v7AXVXbyE<{nj{m44P%BZL+jB zleaGvQTD%j15YT&M3eGK0QuT9Zkc5b(uPvaHi_Cb1@rSbc3G2P$SUF0&6fkGfNrSW zcB2i0q3B;2SDQT@>oU8(m7rzq=Wj3dr$epz`n@932gVWTJ&V+jo0Ct2-kJHm#v85n zN{A2l=vaC47SXSC9@!L(1zizCGxKTp>uvc~O%MOO!4$$LJ_m5XOFrpv?5js!JvZB* zC2aj)0ly*UF&+#0VR0`;Z-$DTjUyyqYBt{rwH{ewhPjj@ke=c+iHB2p{pr++IQ0~{!L;~BS`9~i|av6GxbFtrEF8G27 zI6U;*B_RJ9hy-$v=u3Cbfbfl=Fkfb==C*bo5ml4JqbN$EXxZj?ug4X%Skk(lGvvdq zu-N#gd+gKt?8T6PkuJ@ej4{`bWW_ckD*Pf#qBduq0g#WT*um+nI=_q1d;U<~c?l|T zV-D}d2StHz#mpUi6TF({3-%N7UlUsaZFfyRJj{4QA5?n(o{ieq8iviFfMFk$juV=< zoy=$>^)6w7<$c1(GHZEMD+E5p&xK3BNi0PgVl!BIa(&e(Qu7~pN-yz{y%}cPZpu0X zISDf1*mi4qeWH@a-ff_yR~|z)aU~ESOo>{DMdr>t&)YwKr)A3E>uOhM=!Sio@$vy% z6baLx$w3Hr&Rd?Z!#W)RVHSOD#IJwpq0*n*`g>mtot}(*C$Ts5zSZ9_Pqr`nusn4z ztxCoy^;XJW=NUVj?GR-5VXns%Z43Ef+VXZ}oK!@gG*M_N)1QQFu(+mdN7vj?-_y$= z7^;SDT&d%b^L=xBjW2XNNh9m)2zK#~~nF`os*9(yr)t8#xL~WY%HjU%|<@3sXzk+ICIt@49iJJAB*X=}kthHU4Q)72bO zfcm(?>F<%_W?IP6 zhRNq6u0eva{YtL(qpB#fD4_R7-fbZ7!TzsJ=v?suu!b_m>%#(mRtB*XBoY|YcAwym zU65E02RFKtI3YU})8)ONbAm3!q!KG{3lzQxc093}V^(h-&Y!g=`3iwCa55@Wp*lIK zv5k*hmAE`YXWrO_dr1coI9rv;XH0Fo04GBK8uGX`L)j&O%wnW*P#1usGJ4p6;y|H08p~Y*}~rZIY=B}4?TnzgKa$bW3z3;x<8i- z`3hfwtj*e&U=as8(G{-Vy!Cs_^&@-;6zxmwpgLQeTZQ6vD=|Z;Y!7C}OA3Hf@`ASh z{fd;LP-22Lgv)Q^+oVh2Nme(uC`DkleqqgSF7>nFI1_TBqiu01r1yr=x z*f3eBTt$k)o>mSqqGxWUiYZf;au9Jw;!Do1SAsq4zi`i5bXJ<1YPpL}Rs$5ZIxV3&hGo!72rn!*VaqjB|0SdH| zQq^a1`@7>6{;|K)bTRMqEwi7GWM4_f>)FZ(I&n}3{h24Tm8IwbO_V2b=C@>eHiVo} z>P-ideNULt^C!Ob)IlqYG0ngW&RF%WGTeZL082o$zg?`m{R^V+CWHZiB(R}IdS4ZUl zqyoxh2iQ>oey?&ZvQ)4v_{G5fq#gvoA@Dmc>^l(;gJi0nSd1XGB1o%tQyGzV=SrD2 z>ke~|^{GvTWZ$mL6ZR7p`wEz{sqf0z!|?6yWreZ~m=){KREV#RY=)S zg*(P*+&Y@{eI?sVi;dw)z_C|6U;JvUF@wt4%A47ni)Z^Dt?`-ZUT!&va8T!LCK zFL<) zR!^nepX^Aq5)=bN8(-`-s4H%b=ORtxxa8{Wzdr?MPcB{@BbX~_c}JGfOW|EH)f*h+ z;L>6!>i(!2C=NT@0?g{XgpTqg+nYVn1&>ge{&uPJ8~=Mzm}BA1LCxfxm`ju`Iv*W0 z;BGxZ`V7f71oCdv_m_$EEy(O??r&d=aRsVfjKJZ>#38A3(0lwiYiuTdGbnL5@atn* z3GJ{HcdM7YV%Z^Z+T7**$jmVMPS;F7rCI92HHqKNpfzd|Eq-TZch4&5QF-(IdZs1k zh3<)TVe~1TjyCjnQ+t#$-3)0ih)me-s6_hAaf2U&(oabX$F$oPEiO>9@8Z&i<8lG@}*n zQbs6%aH8K7m63YCTwu}3BnKl%M-}uV-pC7GhHzdI`YuUir}F4X9YK+6G;>Y((kQDZ zL;6T`*txK;69vcy0v5d4*0%R-_Mc_Fb)`D%63|gRkDv?=)SM4}BU->z4Y^0K_qQQ= zgYpLBtCbP;ZGSdb^cZ0!`Fk37|24pwDj&#?n({;VO)0cCu{Z$r?%z43D&)WANlvsG z8$3jP;j;qK9-SHd-4W_<72R~r;e4KRJ2i9BQ=EJmILqO)=XAp*hNvqxkidsI7SdGu zN_QN0d**A4tjq6zCoh(8BQ(oL^P3v^MsM(7xQ$ykR;m-iX$VX;;U6@L?V+CK7f`f7 z{QH_mJ;$O-^(CMwaWi71lpDAjE6xr>!=C-{-M?~E&t8H>_}feyP_NBFpcOqZ_9Y@$ z*OD9&?OxKIkCQsm&u6dfWz3qvzHNVK zOTL+uzWNavtOXzKR2^?oHJYJsWT7zwRz1_vx12eOZI?&%lEqDb)ifjtg5Xj zd$6pXu_E5GwYSP{t$VhSyv}CFTj;%a>Srx>2k1@J&$Iq?rg#tS?#z|db@#i~cizao ze6kRw^@n<8ufG^o415$HCfHS1BmT+g$}r49GF9yF3s8qSMtNwC5`$Cy>)kJJ;Uj8W zjOU?4xyndVgT(-e6uIS3LDqOs@aCm*vJfIP-FAf#hG+& zKdh=UuuSxO)}FxpSb%@lR!ojFfj={J<<{lcf(W^b9+w+(f6a=$^;b``|KN||d@l}? z#psQ1!TAEwfSbvWi`UIJbYTzVT#n0%GAJ`lrD)^%G4*uvuL-5dgR7}nj{$l01HOE= z(jbIdB%nf+U~r2ivx8c~H|JJP6uiW40!iz#e91^1R zAGwg^+mN7p+Z=S&0p%OJjo@=>2W*zfhScwdrXq`kS^%9FaanB*BP)pparpigXwP%1 zU`8H^v5;Wa^P}IihjJMkgAyRrw5`kGGL=IjVzH0>> zzS0%8l;~Vi#r$31J(My)9>+fHa+qG=o2QGRIodZgcXu7zvi>y&&Al?qb~aEq0i=cH zuGoLKusd?G^A@WRnN=DX|L^Is;u`tD~hyZM`i12&vvF(?=Q{nJjw~x@}9X z)*zTLQ?$W?PDGFs6z{*lPJR|j9pdwoLn=>SCHRcp_-g+7177CfC;RZhf;g^T$78)Y zIHP#_3Ze%;g}Afsbk^~q*DLJ$Zfv%H$t`(`*Yl7QQbVaIev(mOgRV%;q*ugj%{!7# zliU3LZR>6w5xLf}SqrTb^6)KkC~*p$208}b@C&<01_kXg`%b^THEQ_&n?L;Y&SS7h zkHJ*;8_LM%tAvZWW{=x>LoW5twVgtjwou&Gb10LI9pa1L~HV5bc z&iWd~wvR#S4qIEZ@nl_7%sMXI9rg*XYN8ZM*rHlk>7vHe2JNcnwfzAhpx`6o)ToqZ zqJ1UQ7&mCMe(5+>3hypX01)iqby~9?i>cuSK6X6O5Ss)=VYuM z8=05OiBb|sE-5%{A_s)PbqkFgbZ*^!9k2TmgM~HAIeSAyPAi|0oRm9|`@O>7(BGqH z#?A*Z^6=^Vwqu&ZPA(|o8Oe+Y-yP};s>p>=5|8G@0>_`9OK0Zs8A7+dq2sOU9HA$9 zeA*61P;$E?5sB#P9cERUE-pcI3&Lklr z=94$OtlzWr{S$)2w(3f7(4k^f=K!6FX`2Y2&0*#G$lo-OSJAG(s4XCP@=nByz*y3& zSPWbbxj!b?4f=Qe{Tj<-NCq-rSlP3T*oc=aV7fu7j{lfv$stcUxfL&n+>+E^go`TJ z)=wJK`b6aTd*%po_SS{0Uc&&wF8SzK5nyuwcCCMTo0EQ;EoeXJE@+)Ioe=j5E;b6)6+%_tnyWsL^0<-!LgPALJ(mg!MJs7`vVWJs zhp^sFjbzJ1fY{@CuFKE}_jO6WZoj`XTaTLN3Hd6BHWLKa3u3ST(MuC&rOSC}I-0u$ zEO{V_!KE4#UI)JxfNcJ_aJjyfV(;<#vw3gdd)7^4arxx7JXjjLbZ_6OKT3q%3SspI z7oC2$$f$!m4kCXC`50F+_C%1k=(v|DS(pdl1ZUf!IwgxD#)_@`S*=#w9lnNTmc>Ou zAOcy?7+dPmt6^ALD5JHHQeHxUAiRAK54bOaHpAZGO^YlZ4@mBa6-#>+UPr#?M(b|< z*S*Yp^mCv`Pb%vXt{E-&tQCGM2ylt^9W+Z}G?7Q~fbZV{u>Yd(XNU2ON7M3vb#`zw z=#UI{3|SdOXLL(H1SgLL_6)06G+&VI{pkJxVt@_eNLA{t#Y(B$^ zcUUfCLin;ZjMunyacys5-g={B_~NQ~eb-lBZpWH~Q5vD)?}LJx^!5&@7A~hZ@ohCi zk2@P1xHP!>Qmz-s4DMJxBb3>8i|750rE-fhw+*TgeS^p1>=UIQyr+mEf(fz(PeC)* zgZxAd)v(nXdLw$#06|8#C)dfG!OnZ^u+(V4y+awObKC#8JoG9<)Tr|f-S@ziGZKR6 z3gzE7Ij_IR(*fR!{gBBJ<&`Sa1c8%=o#pGnxqhvu@pa(?sejma97$`{I!$A7ztwZPT~k&aUte0D{O?ul21Xv}ECf`&+BOZ|WI>Ep)4} zu`GM*4D)H@1+-A>xFDT#?Mmxht9SgUQ-l><%%`pyNtpcx*BqfNq~agYI~{7q|A3a zj39ZwdnhG`3{<#(a6xSCqXHP*^UY@5$GT8yOSX7HosY;a z1pDmoxeu@D(r^P=Ogoy0>c+XJxWL9|8k>Qzu*PeR!n~%;KFeV5?fITP=N38Pw;y<* z8_IO>mcnRR`uADuj{*)4*JFAv-g@2ZwsBGi-0Mwk&fv((4PM0V!k`xHBg@!E$>fOe z2Y;CF2hY_lW%sh0G$zD|^gS@pYvusH^X-Kt=$2{?x6^a!YLQSinlyO?T|-oWX5~kt zrnfwb0)WP@Muk-)kJ5|K-R(XIl{>s40~pB&kE~eYe$}`Y%CdZ?0e&uupBqbDB|X#0w2A2ro3prY z05^VQxe^Sx1xynnit04sOnPaXTKZkM}eg#~+!cC!{{J#o_1wz&5c znp9F}qC_WO2|?{i8ziyN5PdR*GnkvmZW}nuh9~w8=zGZhhTMaP2zs&G&&iPop;6H1 zo6gYsBUpCpv_Fs7V57c?{n~7qN%#39*439itL^fann7Kf^E~>msw&%sh+oBBv&jR_ zyRbxoI76X5U0`2PVcbPUVCQSJ!>;~*eXa?A9MzM%h5P#&V(+{MRhMJ8TAy`orj}?g z5|suxg-okHBaN-UFLQ}T;`TFp{+%0|jhy-2s`^f)f=0{WOl?_kZ*roK^26KdM*$w% zsdpAVmG6j;3=K=)dgMa%?fOKMv&}-awTPL=OUFj0MzBtGNHV9N~F%QODQK*pKb0khc4# z{5_N~iK<*4$`jV){b9-ZEU;IE(5*7Nkx$v~u8H4){FDql@wlQ|_XbzEx$7JGaDg~> zpCZLsN%WNDCEHobtcVR}4V{_Vy)>j3pk;D@zob)_By2};cbgasJQRwVg^|XA*M53V zL;k?ws@%lTy+p@_NL!E3a(G3%-i|BfZ9`qxqf~(O6%64A59~>OQ3=prjyAw|($hhv zU|5X{yqAK-dSI7)6F}Y+xG^hmdVZ#{3PF(>LFk#8`HRhicYzVmH^@!d3>ScJnRE)9 zeK8;DfL6;F_cd+)Ue%stb<+#kD{S%J$~W#vXI5_ag5`^5z0;ZtONkofFrmh-8jt>( zcjNCicjmS2=4QE=77Dx)haU`+T#}3pwJ=>L-R~^XvhA&t;Y{w>aPIF?Wu@Ute2Y0D z1*RJ1uJF&X!6vz+?K#jxt&tGea30XT-=M^oPB)V9cLSBI&z<-y(*SQgA9z<6>l&*A zV5_~5=5VMt-8C)>(D+k_av;-Pl`=+}tG*@>_TkUr)@%EC$9&_ohfCc zEq(=d2c9BK9bO67hcp&jue&gOB*W!PwMXmb*TfpA%RVE7h|$n*T~4a^lj3Ww6eo~> z6MtdnT4RFRsk>zlVH`gTwe^rIgxP^f!cpRq{y;=p!Dg1PmZ3(`|LZP`q_yT5>Rc?0EWCRIvpMe7$m zGc9_z-fayvpUbZ?g3k;Yduhy$-+F~Qm3Cn&UQ7o30tk88aTC+4Y9G|iPbfU^mwnSmH#Y1bJ_PbC@aS*5& zJ`FL5x7{$L-sXdig+N3&H+6PTeq>p{0TjrNF zPU-IvT_aAK{YLE0{QzRclp@@N9vosYcGyCSvBtiyX6TeMI^yE`* zo=;K+g~%A zhg#>KzC`7{vc+6sT>VVoaO0yijKb^#!TgyUOGi>#1LL&A4Zfk_N_;TNte>9k0}K$nI{^Agv~{ggeqC5EuOvX z1<6TxW9hLHN)arbxZC^{^ir6hsp1%Z^1%CAH%z13acL$ShDs(VsV@)EiGV8~!pQT* zN-5n{8iZ$jg@c@x`9Qx`?_;kB!qSM@LtRjq&2Z`r!rYMygz#G%M)Ke&#bQxmSAPIQ z^UbpLKfpo3JU189PwB{&IMVWUvEaHK{xvGHVtlX*=-(EB%DfPY z5DCT)53{b=Wo6;ceLxYHJ`-p$4_ zIwHU*1KW9}GIQv}t%-{{D#T@Cnj4x-QPfM&J!kng=8zuV1m67+-QY+L#P$nV0|lsJ zK0J>NO3)JGbU&?Z#|Ar;CTuV6LBNt^;VN}jOK)H(C|^r?H%A7^4V}ES7)3dMmaF^j z->2bf`$#+)egGhzJaYjT>B$s9^k7i!O*vwxFQqdr#(33MGq@dc+(qHog$`=C$1lC# zwe6G{dw!)~o*UTWLYxj!CZYzL%mDdYkDY1KHc-`3mpAI#RZlyk&c0=J7&C*I+@ak_ zSgP`ZuiZI#lyGuKAX%ALJWF%NV>4u(q8Wa7MiCLa*#Iy<-6Q&YPvS(w2R;~NK-Q~H z4fR%vFQe$+VhGtGqaQndRVaqj!}!6qgiU6*AO@(BRt&M>_T2XGiWT)92pZ7b+DC-yC3~P_s9`pJ}^+k6#R>VnAP1{LO0kygDTW zzlYqsw%I;oV}-_1aGNBMfs~RwSr5vR-(xQW<6IkkH9E{Fu{bK~H!3>xWD-$TmNZPD zh#iw(B1_3E?Mg5I#*$pP~F zV65==a^(bZoKBR2im)Hmv;*QZ9B%H;Ax&gi^a*d6bEQdV4X;@-WG92t#7frvHWc$5xL-b(V;hKT&~YMh8vw^_h?WC8nvw` zSUyM}(n{Hq)lcPno)U|aA>y%Dj(aXgiKmc$+9`H-w>SOy#dpQ_fBJG`+J~c5uzClr z>B)E{9HwHtxwKUpxK<{Hs09#;zbqfM{Gx&UA};d_X!xN63O!#B%|d1O`_Z#~rRN+P z3d{gHfg2AUfy`c!TX}}|J1Qi~w>xzvQjVR)6F~$gt<saE4nw;O0ToOId4+TD+JwENtN-H2%cDwGZ>>nItmC-v?k?Rfxmu+9 z3Q7IFYNe-oLw*S8!eS#jl$Pzyi-m!ldnpp=` zTUA2bcoH04l|E+?0hcPh!UcBeGUP|*?0;|s2wUklKsMCVW?{7}!`^AX)A?tL?@t!w zi=t@l-&E}H(8#ru`6*l|N+H|AZ@j!7w^~@Kpue`~E3R+j#CL(>5Wo|X$LxOC#o5FB z&Hbg5UJ_j(#-^UXxDi#FzN#bw&c@Zsl!{g9k3s2p7$h+>6#@LYIGP6Zj%o1Ne!&CJ zif${@c3E5eSA?G_QAd`GJ1sLBO=M8?cY>pc35QE6zQj_ynHd6*<=^kmU8j&oIFQldN+x@ebYxqa z!CQx>xqW&rW*ZLE2{|P`YQR1YN|)ug#ITmA=BmVhCL6p~1(0+K?&k=p5wFp0J^fvL zG4X{0;dB%}28Mj^NL#p8afv%t&w2`lmsO+ z%X>)zsUuk-idbEak2)6$EE$8~Qup`FWvRuW&C7XqR;W?cu4*m&;OpSPvjPUR(++H~bM!)V0 zCh~6iQh-+0rs}qVQA6$^2cH7u^+R?9iJOYgicu@ob>Gx@a2xGNtCJ$5Yc{!(Ro29+2{;9#w=9K*Vr@ zw(~Fh3R8{C>ePOJR|j2YifOz`y`myfRzY^08s@8)wo+zb?gvIM{@E1XL&TU@rM8+5 z)l1dcyK-gBXt7K=<0WAvfgXwS#3=dJ>OTcH2b7m)Y{}E)hdZ-Fu~+>M$S2N z^_zcIRjXUupFSH8+l=@=0R{uO-FF6+rO<0Vqj?J-TB7^leh}r;hx~9@!O}&^pzy&+ z$iWOG5d*AFrO7PpI5}1zYIH&m;8`IN^5IiUm}cwBPj`N~B8d+#sj?S>*mx2@vu@3C z11dvBcc@CxU!MAQj(aOd#U0;(uZ@=L;6FFG%v*JUj$Ph2Sj=57H!ATn%_!B*INGO; zkgrX(&E~GStZwFuotY?_2Cj8t##^W3jTalA@5Eu^lH9`sHk*>N^wIme{M1)3iWvjb zHHFHGVEm%k2ZgcCi%}c};fka2NQ11xD0fJ7o^?f5pM^-n3p;AQKKzx-Tsr^QX78BP zEUF@ImbWi+1)p}H;c9+SyjU5qN@bxTa0T4pViqFrTPr8jgXSnj#Y`)XWQpFn-tlCn=7 z!(!Lg``2;QVE<>GYDukzCanhY`$AXlAEO;{VW311vpYO9q_RdRx2!>I^HsDxmA%RG z@Q<`+RlzGE#hA!c|2k@Yu*B8ViHl^2aI?%D>fYLiXz|BbTl|FafQ2LH5w%_qLXRU_ zh1C5V!}Ul7=Ejf5`+(@W66{+HoUPvV@NED(|VYzl$N_90qf38#J|?+ z@XBEgpZifvtmH&!_aEG&DyI*_+DSyMbL3JvuR2)bJ-d7D&-|3}?s+qx3D`{dD3Q|= zk?Ojn%AMB54h>R0C+}Zw0NbFdF4{fhaNx*TUch*zUmRY7NltwE2kfYdB=wy!*)!l1bSnLU<;>vlRe_<^Y-_j&O8b>s|Ouv<{VW0gUCo!ryH2 z#3Lq=FVK$B)ip;2*5Q`nB2(h2%Sn*$^*+u*9iI#_PEmtfH?Qjr5A-sBw@gYbNhz%i zgN%|GcQ0ieljwuqvjycW?8{fXQ-axG5y-~@!_Dd_fG1Dn3leD&WIoF4##5fMeP3%{ZR(Os ztGS%Z2J4*i0NF3S>XH;C1%f5t1bEmhVUj@-3+7-or47Wh0%D0ge}=lF5*!pLmQCaa z@Sc9w3mlYdz@?26|0ZE++v&C*^V4Vkr4bX)DG=M%Ev+p}VAf0Ad(t{5O8cXvM`k%x zg};(N8`}&MhjKW-#XT$x_{e`OPHp87OEJ0maa;QK0DqIw6zr!AL3tQsVvDHWt^9A3#)mQ@gQ8 ziH1d#t&fn*sXA6lJO?VZ%5WbNg9mIzn@p|h6-nfP4$X+E%r4fOlhZT*Maxr!8#w`Lq zgB@hSFj8j0w_Dghx4OQz^ASXRkg8Ey^d4U%TCdT0zG#jz&^tmyUh6=(TVZU(zVCPy zuFhl|c`91lQGye8{GY|d#z{?IZsta&&J;YYvsqZF;dj5v1CkAV2CKLY{wz|pnc~`n zRTk;+3&()%cJxOk7U60>f4t*om}Qh}Pn;#sX-ZNC`9!aV{@I=!f-;|8@0cn3i_c7v zyW34xt zCp9%**H1%Y3=H_^V`!gvH_oCf5p%2O^u_x$fmy?@kFx6WJpKu+Q@~*=>Ue-o89v)r zen-Fbj{DSjS-?(G3Pw0Y)qw}ggKU0#;uVUwVbDM0GETTW@5s^isI*_f9J}c4vck|| z`R|cGXBM90Zf{^#__pd(y#xa*3uj=Tm0Io4^&XG1|K*35+mWG?USri~F8Z~&9P>94I1RQ2iyTR6Y(DoG`RoLAuMPp^HVTXr~%na zy>N2Ar3&*1Mk_{- zx>omB0Q}b6t5m9N++7`2VdANYQzx=}khV#Aa@F}IZ+GH}v?IL<`!nV1TfW2?tyh$` zT+*wNIkbL_9OgE+g~a|j#_jA32=D3^#wiA?)ckfJB@F`(FaiY{7+0u_b^AWwC%v~6 z6J_8D|8%deNFrTKrpnlLFlC<`UWBA>p2um(B45m1weN;~*$0|UnjN|O>w=wa2}I}N z0`7$r_UF9%Sbq(f%*o)3Rg_nJo$wxrT2&OpY+As2@%Uni`LSiau-agHjdBzH%q=6m@%OH8VxWlA29Pzvm(P{TGwoA z_Zmj}XnE^nsMoV?9i$7$raYuub|K(}Uj>dm5XTc^WTjyrq?Q8V5H*^EWENS*Y%}6c z>1j`eTle196>>L^E&|P`)_38Hh-!5|m4HobWODC!%YmV%DctTq@uQWUlSM@>DJ?2l z_f;V*M^5M-2O1mSe&>r^vK5uKjBqED<1S{PQ z)fQ|otw|A<9Aw(3dfIe#bMxgd3IA*&S$VadA)VSNlT+W0Yu)ZLbW_+tCh9vUSSV5` z;=mD_q*M-4lauhO|5-OHf})435lBBeEVan`on#&&1Pzmg>lRqoQ9C^!ku=w7um-Tm#R%RE_BveVt(I3zqP@LSC-V z$(fwAN;kfBjyGb$xi#0D9{3J?ttt02 z3#v+F7{VsbR@m?Tdi`ijExxM1v@oVq@%3xgf5R3XjgeFA!ZRZtW+mC6x(|kr;$0Em zOSib@tEhhgGt8XKXVJf%*0QLD5AFV}G;L(Tt?q}TkBJU$delk5CyZ1{@q~I{v!HzN zn1F9BhPwWR^l;@n@20ue>a=%>=#!`8H6n7K8aFUdgtR}$Bf=?_;`VLK`&yAw*o&?D zMM;WVnKU$lLH&$h?p%uiDuBEo0!*pZIvX1Xa@{D<&KB@K zFJl6f%3LrfSYirAE*P6m+S&(9@Qirt zeZ7rFPh<2dIuGDB1BA^Xsl^Xm3cbq)?k<%zW>Y379O61+S_=)keL^ZB7@mRvEz)a> z7tB72pGtcJ!369J&3OQ6;YM8(N#@MsFM|5Q)et6A7O~{$bw{?0l1BMEjFR@I<%#O< zU|2nw1${iAu+!r>MTZluhVs$-^?n^(jhx#I#Ix; zLYiQAq#483$qI%WeJpe4V%Y9G*3jk+Z}4#OyC!EbW{vI}uu0bql$Z_{;B@PQ#54cr zq{KwiZ#Z6CLlT@46-~~IoJ0Ua4DYLYLBME0ngEdIoa$+UHBQB!@*SKbvF&jV{^Ecsd!E1c3yv}friXUx(=s>Y_5yCZ&Ku~l|`9zDjrk$-6*#8Hk` zhyX|*xg&5d=%wgrb(bm#P|MF1c`-@g->{=NN0 zA&{2#7%GskBN54nlFyx+CGfi?!G|FM%d4l34ExVjzD3X3?OSsl++c>hfRdd-Dihz}RFHMY_bIpaC6$*vxyL0G zf+HUu7bhyBbfLcJHdNEOf(Cn)RLrmsj?yIAxX37nP>?Ocz|-rEke2E-E93Dd22>%q z9c&D;X`;ogwHo1G6Fg&WDrRN2)38p@@jIq;YXDef?(kSGHoZ@vXM~^OZWp3Gv>T_K z2cbM%pDL<@hziYB#Y8R-I+Wvn_wJcVf9nwF} z3HWAjfwMYKNo~RjfW#LD!}|sSM~klDQZ8WogHHz}iBDSgRV4@-QK~Rdke8|%InTyt z_V8%)>$TO|#~N%Z5=!AW(@*XurIh+D7;Kf~E-rj~4Gec?gV>l?WUT+~PvAbYqk2IF z?qR8)@+9$vxS`1eX^uFdv;z&DDJw;&$z^ywRJjI3#I#Vz4W(CLlspRWrPqo`IRaEP zvTLb_pS>Zp5%s6VVK`!~A2>NYW9Dg|HI6Q>Kun664An*CHOaK2!O{oVZ$d;{QLJ^z9Z(Qd<^N=70qctsWv(}jh>fRIqCONxD z7|MHPRJ1J4X1v$D2feNdA zWEMq0I!IV?ouQavKzGv`9+fLZQ=_Ygf2yQP+F%V9TEXh9t8+>!#1KZWGN6c-am9#T zMnZiBe)ywBWJ5wVE?-_Se<&5VB{?UY5tAIiXU1mi)AA}i4{3*Kl58=rvr7c82Zev} zl$NqVV93uY0-`qNv8({ieuRL6Rfr(x?~_QGG=7hcX`)XLEADdap`E}>KnHLpsI+UV zp>!+qWO&0)Z!QZnz?8?RN^Z#dXGVHT3oqEWYT@GcLFzZi?7;MPMDQWFL5GdS0?6?q zxx6A4F$No~u~YYM2%skhVZ)otVZnxHMe0dCJujR6=;WcBi({JujLfb4&L}!;OK=>M z=%4^dION>`!OA05boz7HXvnUl_q|mbSih{PCjBj==#rh&Da3E03nz>o*M#iTfKBDt zjD>89bE1w)30|!Jkr|DVO(Mb8Kxj%X7L>1IT+7m;H*Iqti2E|ZWb5NL_;6)>RWH0r zo-r;q9hI-^ljb1nb8sXCV9~{ur^W8&NBfPe*@N9=Vf|oSa?eAOm#U{cpC3;~D2+Z8 zRuSShJi>u;qh8TM z0;aTJM0L8jY;cOswO+!Gnlj)@TWNJzgkHyoDVh}1heu}&dNi00YVBlANH=dX7GWLe zlbI>^SP27q78hl}vCBk<^94#5&|&SkpHB}ic?lboAt}1aZtW$%Lk|;BvHm0$h!H+H ze9jLcLL%7)l36s90)qslt0)pe@Mr$y-%tVwWJ>FNYV=$AGiP&dGUONz`4u7fF~8Q! zs99yC>9nU@_tg}yauGw6L!04XuIHiXIg{{X6jERmpvmqE$%aKDvc9t6jsid(vLB>D z>ZuQsh6McDD{w<4A}f+{JCao<37&BSVufffxVo*@%If((I(ZD~>Ga5e*@T=MT+F>T ztjMh3!c-`j?lP~y*JUFjt^8>hDen@2;9>jL=;xcmJQ!Q8OH)*jZ+RI_^IEfV*b=YFMyU1mTZyWkEBs|u`*h&~7rA@h=P z2Z!o!c`vi>=VzPJhzN$)6WToWMh%Ia78*9fhwhk|l@jq6p5WjD%|I+AL)W0a#o`@= zxA_C->CgP!3T$EV%>!x#_|ILq;T?a8I$DkGkZkHH@P!6*{0&p8Ohfd9b1U%{JgJc6 z?r$>#tw{UL_Z<#DEz-_l#rVMM-NPgVq6NXCFx(b+yqdhL5&qH1pY@0{P&gJ<(*X|X zQ$C2&fOqwlL9>cG zW%OPP+!E=z{j;9MhPqO-&{nPH#3Vv!9yeUUnFI}vCJ~FEMX)F&Ck@$s@E?ygMM~-E zM(3=tqwPqHGyNfJ19kUFf(!vuqEZA~6xa3vq^-(^@H7MJ26v4X@i#L&*ZhSPxG&pWK|Dwva}YuR-=# zp55$2KZ;A-;+0804|di3MSF=p*xrKUa%vGbF2LT%z@7cHIc83Z+s`dKC+F+maYqm4CjnPU_bb{As$T> zh8{s16;lZyJ^zayIgt)yo-urGe<_3Ua2KJsAm6@eMT4cJ18%ic3Y;E#bv)DAXKc`$ zIxRM3V6#Ux!+?Re`H>O;cT5U!K6Nf)%pNw-2Ve!bf9;SzmgqT*fo1-LTYJbDr$4O5 zkV6H=m$W9gFyzgf>8Qcf!_WzVfHi(Mz}qhyNNhE{`_qxvxpoZXkjm7oet6#>(j;jZ z!wF&Tk;m?ps)Ph9o9KS?`G>qF`*lvabS3fb;}&+Rx#V(ezT_$8kw!!YAyyB6zxBmWX<(8EXWki*4#k@dL0NZ*kp^g&>GZ4T0> z-(k3a@fiYM8r;sV6_3sjnKW~{NjV5*R(H^ksC=9SBct+`BUtLOz7Y14&IU?)bw=Xp zvG%t3hAK_QR&@mQgr+bo4-xTNKrI<5r#BhOnhl@LSOtPN3*?%XjutB9o#NUgd{e#z z=)Cm#qgWIj)$@#vTCF*wyUrX4to(}*%32yCp`9CWS5A>G72Fe&f7d~dWsoFjGQ>y# zf8#dH8a?A|q&}~bLCBD1z{|8qma1d`*&$Gyu{hYfJMR8wL^F&P&l zJPlttiqK*1)Vk&*2M#|8;Qm~2H>83u8o%W$(f(+QuuPq*sv=7k7(ot}^ z)wzCJF>6jEb<0%Ih#5kb6!g_mJU_+t%dcnnMhoO(3c8F`nQUHQ=D5x@{JnuVEyztY2zf_DqwWap)I= z4vyJfSX6kL7zfKAdJzLVB{Y7sEaX++qfr`PC-qA;fO%$6t~0`%#1rb(TXbheP%==z zkwe3s;sQqzDG6BpG2ncV4s47u^k%ZPD~-YY^^mc_Tss4*AM&VFJqL!B*>5r~EdYLf z9#19{_M+$Ff1zU+S&{JvXR~l2H*1k%saHpViq6nJFgaGjf`_WY8Qcnonk4*pQ^X&z zUHS2_hDw}0&b7k6)@}!`Ws)z?Y59J_%D{z zc9uO-1kLq_8?s#@_WOLrbFu525Pim>KH+y1jnob|^f#l0qqIoc61a`2=rs`a#da0= zh|~?W%3JuxDX&kTmL1vM_lw9}*IuRt9IlTMeU{P5be5ms!K@Iw?fAS5&d(U5%Xu_> zD55{I_>MzGGda{VRv`PY`4lt+eTmpS;g_k9(F6Dznd^IWk~)H0uQ4`Hhrii79(|A- zeo>)+Eb@fep7$~oY7=1#T?GfJ$(N@H3wI7kd*@7Q*gJTaV-SYO2Q#y8w=PSlK*XIW7 zHD?9V32Ez4WoLFjfKBHGyVsgSt?ZGOB`F5viBQ6}c@)quWS4e4o1K3y6BB%Ljaq)& zl!r<&NR4xjuJ#7vbXoibcFqm8}%J4Bi;JBNGT0Y~201h>bVCRE-1bEwp_8$g>s$JZbC zTUN8L*MCwDK5*e%^(iUfuY|TGZS+t1bvY?mVZv|lFHVYPvm{F@DZI$iNf~~gHOW}$ zOT2Lv$n!&{5~@sPM;IT(_ZX0eViu*{0b#ey(Fsi-OdQ@@t!lFgdg(32Q47&AP$lHDO8-f#JX{qKEu zlYU=lfNApl%K1t6(wav<^}ExVPRa%G4ph5}%VQ)SM%W+5hdQM~K$Gq|#^s4(v7uz^Zws%hkl;FZ4|!=RLC#~5t4ymK%}K{u=emaHFan;Wa#aIec#{`R8uRWa z@JW0KIr7hpi9UE%lECkJsS4KF;K(~{+5}?^ZX@duD%?m&T&tx5R1hvWa&UV@2YphU z#CWt6ZSj~3kDi;Tc1;$Qv*`*#7u&1j%f0Z{zf4MPuJrnFV)cYo)QnC|pQ3VZpu5`! zuoH)@%Vp$&_y@Abh-{4UI6i+edAQ`~6)5AD&;7lOHO?GX=CP>lo*n{)gQvaWs$}`7 zP>O_s%X088s_te+{h4fO;fDpnS+;b= z>`7sS|B}|PDD^t-C~JuZleaUwW(SrGff8S9U7EKf0|6FNUAe!#DM3pJe1oDM$ck^_ z#DOuNI}b%!wDaRVnkDBQ;_*edMwt)o=kuRsjQ%cT;C<~myZK{Tha-tG=5R|Ur-NOQ zbY_2j){#uWI#?98Q}*MVmer}Xv$dV97D`iOd@t&U{HGlUG1~sdvX?+@s`fB8j~E`= zTl!Fik8pT>RCmV)UUZ)=vP#N^bN{i;q~%XPYGelRILmFzN#bITYAPXc_)_I z@8K?Ts{_J-8`u;R!9Dp0cF=k(=0IbdsdAG0=7wVK*CF9ddYE3zQzngaGsBcs2n-p8 zoh*wNc)wh6xN-&<6!ORYoQ+MvB$ULYP6DrM+eb77r?NXNk<)+f#<0EiL}HelDYGc%*- z5IZkPqaL08We=20E+1;t{5tRrmstLQ@p}4D=U1HKGXEeQDAFho_7K!d&^ToS9GlJ+ zwSej3rhK|M-Knacy5tP@RbDwL0WFJUzCxj?gkwuD2`=JEc>`jf{Qj>z?N zu()3$``QNpjGz=F=vQwFh+nnjRz)XEd~$9bZmv^mgd67XFV!UkNn=bXK3<5H4SH{k za_!N!wQHd-y6wOpm(#?b8}?MKey}vfbe%I^X8B2E7#@ngW&ujdj^_UaB_BVQw2Hjn z$p-Iqa=H2(;E5Fdn z@jiyQzImIp#RhynEnRS+AT6d5?|P>5ww0w4+7f!*7rqQxH2fd1(gk=BD)@^)um#%; zr75~A$9k5>dU`!}OIbjCq~P&+_f!Gk27$u^rGI}u%R8h}42!kwe7cmCP|Tl)?Rq~; z!MRYD|Mk~D?tlFS6MupK@$X>yAOD`^#rhxro_6(Q#9Q@`I{VjOf8N08U;pv%)1Q<# zLHj52|Kk7l=jk6RP5=U{KRf@|U;EPi z&;RkC8UC-o{!!Fj_piT(amfGr$2i4lz5OZcU;kLQWo+|*{q;YJzaRgd@XxLu@-&|Q z^;fcQ+y9l?jP>xZzxsO1m;asq_q(osU;gzM^1oC6|M~p$tg}C5dlR-L9@b)9`gdRP zw$#`Eg#QhC|KNZ7Q_J`NfBm1$^nUWT3iV&lH2Dt|`mbl`ZH&Kb_s?bT-iqW$K8#uR z*FTOteG&Vgc~QI@|5f$>>Y2a)*Q5N8|L6Y$P)i30AhgwrhVTFY+du&TP)h>@6aWYa z2mmcO3rhe10000000000000dD0032VX>4h9X=QURb9QI6``41}K$av3{z^*D%e0`g z9B}a7${GRZ9B_~~aLzftesQz2s;g&vWo1Qr;!3!|5#~nJ&e5Y9f%~uj*VT7_Ir3$# z$KmgPh5iNn>tFIA9kY5U|Nd9c<^M+f_5b>}e_fCAFK3-?)!+a6#r}mPaJ29L`j;xN z%WC__E&Tf>|J*w2{G`Y0?|%jV0{#U8zwbBn*T1}T4C~+jT5a3(-#(x7Jpbi{|7Bdt z&ld#2&pY@(yZpDStB3Y~)e#~|^7D_M{`KGfwfsv_cirFrI*dd9*T1aWGPe2O|C)4h z+W!07zx{Ky@8o~_{%zU2w@ZHH!XUNHZng8$xte|i4byF2o98<)T3Me$zzb0MF9 z``1tTZ~vO*#rkjm`e!fZpGoR>mOpRc|2*s8zW?=a-#-(A|Iw1k|M`FXWAy*>?`ZuW;6J|px$OS|%D)i*+c5n8*YE#?AxZpK9R1zG)nKZd`-@2>v_p?}Vz?&C855BeqXzy4)f@-<(MoLZ+BVmsdI z@!$9L&%wzz#a>>1k$T%dMEc*VB`^N|*DT)R|MrgoKhseDzmj;(Uoh(*ZP+KM2<1q< zU%KN}oL9bAh4sFOAVY<3%c{@@D1SOI0WJA~_Fm!K`(j*_@Ka7Cd9O=~>p1IYBZF~~ z8GLzHu>dJ4*nQb}Co_X;DG*$j{w4#VH!fMcBe+COIxD(gpvbNTzUQ!V?o zqQZg2m1P;xdG;yb3qbmaAPqCm*2lez2S&fodg3^7O$71aZqvsYMr!)h=5Y;Bt*xBCab-ppDqW0zSPwec7=D%MWfUFo9V zHt|YFCfK=GUOY{J^VX~lK&G7f(W){l%%cxtpQD^|`-TLvS zZB+_Zo{V+c(|E?&Mt>EqFWj|%j1FXEfmF42DZ6a^LJYTTlwdiUs{r;^4HRo-%5Ahi z8I!v)cI(&QUbz*E`#5}#Pv@rNVjR5QzUw`m9Za2y`5~p#($mMc6!?536J0876+|9) zQ06_=&NOV!ExuPO@V?^d6Mt4!@EE*4CiA=u6lrM0?0XJbwiOzw1vGP7WB}4BcG*UWKV_r(uJ&a5^FbVs{Q<;T zAKGw)70p#tFZZ{63f~<2g6bQu z5w2ja4)&tRim6gjEg%@qzKAi8aGJfhk|l9R8?_X@{{A}v1?eWN#AR+ zX5btx*CN<1xB2ZkfJmAHPF|{K9adDJy*?%@(5afMPZtiT>(A2o6@||)l*Fu>A@Gea zxg6C2xI5eI5JhJs3rdF&2|S)xBwjeqEnR_YS^}WZWr=94$g40X z>2NX@e8(t3A3Op`JFqabO_a8=ALL5MPB>Vt*;g~bpfYaR=^`To!L&@*emw!uiR%i@oQvdb z=~a$F6BnM9H4d+Q4?o<}pOhhfq5<<2_UY>w;vuQVEM3&-K7!GPnqP-5sq4<`zLXDd z5OOmuwt}MPs6?4s0Nc^J z+Hz`N5r~GB8o_?<)5-ObQQSO!P-zY@)Xr`mQ$1?#1s*WS5R`XNyS736+$bMaD$vq) z5EoIUz|^1Wx2&+^V)1TW>J09*Fo>|fi+WSsvu{qA=aU0}?EBGo!;&XLqXpiB51?_! ze$~3U1IG?Nq*p;7ARZYK0Ys$}o4K&UGGf=e1Zl)cME|4V)2#gHKgzjIs z4;oVISE6lDKPPlcL>*YC?rM}vRlyl7eZZ5^pN-~!FmJMUPwTQoQuXN{- zwCu@50lofC=fFNU$^1gtHG^ma+&qi9<448sXQ&f-3FZPXw zYd$(Zmb^Nn{%pY2Udp*2*|KoeWoMe2G&AeJ!}IxtLO&i-tV7xL>? z9g%t(i@6`tQC@8H#oN>k-I4;?9p*4jQibIXG(}|UAV*j6E`ov0)U;TmrfN6qtH6fw ziOm_CF8ncoBqmupy6^5ygwTL}dw4+C0+|$m zwW~T@M)b?uWt&*bJ>qs1jYNu%%i9&mqD&78Z=4?Bm$HnXAhcegEGh2XQ8Z;GqZaca z($MFJq-%k7Y=CgG;Fk|Td@X!nxynu`!mrLnoURAionO0f4SSKrr(;+lNqri$;o*y4 zU-do>K;e%ntT24^Z-2XhXr9zpj`#-Tt3lK)uWqt>pkes5p03Ylk6Zck!ESmY2_Gq( z^Z>4)1zCInXA1cggVcxpn_xQ)b84**<~gf9EP6)hjSFrMuzYh6@G-9u3?f!)T?4np zj$u#$=G}D~!sOM5`KjowWarby7&L?KtiMAfM0$<*6$9$L2f6_VUIvUhN<>$xD{j5< zG<8a)vDHI@W0WXZ3lHcD23(wY^*9g;-V0{2`o@DyQ&DNy=9{Zs^Msh#Id=b+wa&(X zvc_+{EnDQFcywb|P7eRzf$@mysIOp| znROHniNZwm{Zbm7$gyd{Mwo7xZHg-{D&7yDO1xWauxYMshFF;lOpgj7_pYTNE?5;s zA>8(BI$W&rioFgZ#}gS#?ioa)>%aDZ_*rW-43vJnFb6euh&PQ@5Z0h=HDS=y z*{KCEZ>_7iv|J`ppZNbkmBgF=(!`V;<5{6lH;LX ziy#fdGH`Tw@E@X`r|%fUY_+VC2D%0sb%#$t)cuPPsU7FvYUXZ#(&zUWU}!bIU660s;^R1twIJso)p#@=)qBxL(t_LUQ-DCkt*K1M z5^_2aF@>-io8p3nD?fDoZFocN9N&`kHZCOVW!9}o_RxqP>Trnc+=h?JMcoz@n>%`8$Bp?pwl3-!EnLP97a5hr~G_%U$I~aA@eCz zxmEpgVmJ~+jKjtOuYQ)c&MlPH{Yh9!Trx+JpK!03zdMMSK5*v$WX%cla*h4 zX}~6m%NuasOM_co4FX}nELg?LpHM&_qos#G^~VT4P{`&-&{J8I)@BD)K<2sV}gOk!eE~6`R2k|N0*l5Qmfag@&oID zWtWcqIh<%Lwpd)si2MU^5!^lt$35Kj?GPeIQrL9hY^LC_RP;A7Qa7)i+aN)zgN5W= zWV(@VK~{=d_Y3qEg!rdQ1>5VqLzLGCKAE~VkOJ{PdZlDBs6NEKpVV>uFu_=x^HCm9 zAfY>|y4Om#zkA%{p#*keB4d68brNTS`VW^U99NzQqj%QotQn={@0t<5#?P~Bn+@ap zWqFS^$0C00;bCkc(xB3|4jdABYr|JZL^27&qfyDJa=iT1jAB}r3h}$><-W}Hn;j?| zq?A9JPxFEG+O^= zgANYgRkl=PuE~9E`X6(!qy;_DtY{5=M?v}lOS%};WS7w0(k)fQF+2{FfPh#Vofl}5Hyx+XJv1F|UQIFD|y-oF7uyC#z&fCpOt%fo$^h#3 zTkPVu+PwNzY@QYz31W>ZQNhmW(?~V~^j!YxuPv_ZFo*HkCaS@ncYjLF%(nPpkwS-_ zUiFM?7Lsap7O}`n+`hN-GWcqGg=|*s$M#Rg!I+PB`q6z=HX9(Z{DwbplcsdJyF@#? zB>qbBzpp=}$-=LuiY+S)1^o-3&8xWuqO7Jr+*T9ZL++wK5z{Kc8ue+9aF@fcLL$kP z@7$}CMs=upk9$|PR#dKaYl`#gp;rt7yaF?N+?<}kg>RBm{+uEuf%?*&P^j}MJMp!a zTWTA4n}krGB!?%eU-Z%K39Rx#ZW;51*=48CrFzrx#cm{^F>!p_ny3Pw0M&MU2sQL7 zRbpJ4A0mmb5P|#b;9oc_v43N@!hDXi^R_IBUbax_)Vs0T@%7b}Q}z?V(lNaD2-4!- zQa;OXjOG1pA<|KVw;|$ocT)%!C32=fiB;;i?|uPs2Cuz&7;9-AjAp$49KF6S!Xcmc zVCeWF$XYQ?C3Rt{cy?3VUBRn?7I7b~*($enU~6S6hJ{Csea^E+zfJUNz`X}M6pE+b z8Z5nr+<8nKBu#E87N1XvG8RC1qng<^zSQ85ucNC=@PvJ805HF5)o_Z4hn^mb5wjXP z>!5}flE?!38jMw2nwxWW5_Peb+fhKFO=ur)s}yYYur<3J?Jea*rCd;X;oXats&JC2 zlvV4tS98#HFE22q7m<<9$+rGSumwAi_DwT=7!uxRD};pULSNI z_I?Pz<4oaM)hIP!V6d`0uA?fS( zI^_1R0h~y`CCvCSDA4yIt-d0q#QdVyV-9+X>+H0F#a9wJHdT~-**WvvHVzoGu^xxd z=4+^fL>^qb63dUl%Y>{Bhm_MVf*D9HiiJH)6ghpdAph>!Er`f2&w00;H>gOK;=s-ttCNX|Ty+Ab^9>!$R2#lAVme6*lL_buBRDv1Sm=)4%SM(4N~ zQ~>n2A+vo+bIm^|+p9ugcpZc>3QD|z`)f5HupBlz(ce1v8&Kb~wp)cpj4IkNc%SIAo2z zh}kO%k5|Nmsp81{Ixl<|D?jOhBc3Puw&RE4xmsKWMUaW=C}ztu9)u)p)&~zxzhBig zab|N(BF5|l2!V-h_OC(!Xx4s-j{aPr6)!`P)8)Jd6x)!_G}xx>~S9l(dhvuXbJkDs>;~S>w6ZK47^Bq1HNGJS!$eHwESa~^s;+s5fC~e+SrzkjJp+3Nf2!iOH->v-^9+rg- zv3v#q!$D`!CkuJ{+urJx?r{jMmQ@{>m7S=3am|b>UQ(4t>*cN*B8Kz>OP6_^^M~E! z#SSrv!!5h(grd4wuK&SKAIbDzECV+{PdM=X| zmZhXYK6WnKsh0mlnpmZVFw<~cePhAwoZl+0-QwlHorbCfw797}3YYTc6#s~tODrd( zob0b98ik<~OuFFje5%7#i+rBz+}?7v95)iB^OzF7mbH!|3jO2}YRrLzsIOtw(K)jj z1PncrZO99;n%=G+KZ!r$Y7pM(k`qBVe`@!2OrD{c#hQ5frwl@rm%fs7{?;mcQvcI2 zau0)FhMEpQM2p}p?@!W{Q=0tPh>Eh^@yDA|?7VSWqpOHvdBuR6-=P1K(LlaIt@;6D zYkZB&$^BS@rDGp*qo9tgCW>6q6h8<&OX@*?yG$+vpykxZtu2Zzz2emE*(EtZi`qeE z)tZcAFf@j0bg9AsRuQ!+o0!1?0<6WWsD@fqkCINO(Mx?-N1e^l!JAij)e585w}92N ziA@B){J2(Ej-RWUyt*ihgI5uAZLpgo@ndL&5$rnOi-8&NC$6a8)%n5wplu#yIl}Lj z+0w5r%x@n07J)gr$MGy*y%!Uf9GfIg$>D2HP%$1l9-41`bbJd!l89uccRdcTaB2w# zJx{llw&#STsolz>=WD%;*WU59-ZE`)JS0#%4pZXkA*ypd6F|Vpl~0C~_GS1X*t41> zWFkT(Pdyj5LBwItL0oFs_6D+P8!YsY%41h!gbnvIdmVTDWn}8rdFPab<#v;!XDgHx zST!w+x*)iU>wKPBE*ggU4c){p&eOitR0ML+cd8r~O$G@Cj@u{176p<_rj|d$ zkEJ+Ax=}Qu6(nsg__m$G^OT=%4TGMo+rdjuJ6#KfI$x)m*O(SAJgZ}}XAhPm=)M0A zc1k#7?B}>>xp5T1{vjj`*N1|W#aHu9B|#t0bWEJM<%Fz~W(Ol%`Gt}IEa zGbXG{?dozI_q4WwCZoRlw1JQu%aHTyj<-|≺{JUWft@xZ0&JFruAeOVxYbCU zg4E=XrZ{)}@oSaFd>hy3)fwmI-!kdhU=-%kmFo)m56-eS%Qi}uc*S-G7z%z~xU;l+ zr>DbP_xEuQ^fCZjcHh$&g(Qp7k=LpapZ%(jqN1XhfTCHcUMbabVXuO;@)cFCS2N0P z89D#4sEsK<1*VY2s>6zVbHJLM_GS_L_teQpTzZ+3&cX;gqLV!sNpwDnh27q&hQLrP z(@32fzT570_Xlti3vU*{lalxvv7LW*98=)?LmOo*M;M7Nkz;d(JJTftC17$9LB+-1 zA8I&PNJ$a%bmXV`3Bt8jVteO5n^evDHV#v2&#VZymz8(q+k~oz)24uuVV&l=(3;)+ z-K))<3I~-QWC0AvkT6I70JG+F6VW{!I@C!3_|Ep>u1L=zR-x{M3vc z%f40V7=y?vs$y#bx*E)GAbve^8|522qq_95t|}VZ8c3h+WjY9>mOjlZNqf-LmqwFE z!&>hW78As&XO&&_kODe!7ML?^GMYB%9>3O&9S+_5UaKS~Fc!Zv?>&&^-I4L-f*o{< z#oJS7V^qj`{qx?itMt)7Pdo^CN(L0gVwrTX04>OZNUq!(n+~VK&mg>FdAuX-B`rQi z3(wuFKtUChEmO5QF%-UBI*OYIV_ZeKql*b~9*yhQWgp9u--e$T#O(KoMbI9uZYpH#T> zHLpHg({`hDbjOg(9|9Tem+}XdQz8uAUsd|#-!Kfm7W&9_>EvUNa++_Tip=ejrvYPvdu z^f;V-C}pSKtom^I_m<#F9MGh=$5EkJitzG5ssq`;jKWGLC&x`z2cg&9ufuUe>hsS1 zMYylMmxMMK5|B1dWYk!5wHE%_Qo7>vav+!C*jb+PN$%kRn;HA&z3?OL=4fDmAH@0e zVnya9AsuNZWBKctu#AtnMUm0xbGv!GD;MAyQWbTLs5=r(?2a6ZWRd5ZAXOOkrIn(5`OF0z^~cudu3`$ zZVb;%(9mq68=p5XqT4G%Lz8JR_Z8=`h^e3L)ZvfPMkEDN0DZ-DjHBpGf%5(*l3>VV0grt-y^9_gR$~y z@E1aEki)Xu!oX<$^Nr@0B6Zp+;>ZS};jT6j@EdynJdbAS*OzrUgg|23KHoa4zeHM_ z9hNvwFDmq^c~w3oAE#z*8pE_U4gI;oa30D|QwWkU(;whsNgv9a6h*(jC-lZ}o39or z!AtYlz}|Uq zXPiXqd%;|Kap)muw#tXrq+QLz)f@E@T{tF-ZTE9r!VoN4_9O4l^`U?AS;e$`o?ZHu zj=1jPb5s_)4m-fT{IPe&mce;7Zryqa^iDB@*1E=g+lTeJbpgW?8TYI2!Xa8&&qWRx zl0$n>QPu!Kig;_S>q4`QA;Tg}e0<^u2>uV2ahNF=yWzSbGF{vVLXRm9WB*G^-?6m~ug}krO9j|8eowbhBEMJX5EE2am35asvf}kR|eIk%_ ztN2zc&M)6D0ITz1Gi{E0sZ>;$sLweGSY2D$d7~A|%|_E#^{W1>+r4y{y|fyC8`&}y zmWUN45fB3brkk8(gXk^<2sGV0nE)~iEWzsMT8jxX+1|c`u^`9!F~2ip#+Y)y`mj=K zJv@`vLB~8l7;UuGjv`=hE<79g4%^Kt3=0wOnyG5HUS8sWv;t}i%;Pj2GUE{;pohaB zDM`oVmk$W`pY2VzK}>0XI}uF7Q^mUX1#qUAF6rJd+*Y60IiL6mtK5EOedGI!^}Vld z6-qh7(dtj#)?TDs-bxrk4$*{nQ&*~RR|&{b`J;zo7VB2_u&L97Sx&F@7V z7A;XWez_W!=v~0YFd>!&3d_hul}hZ#mbAYtgXI)xURhy(Nfu~;>oR|oyfVR zbN@jWnvx%CA4He8Um21}%;%TmZ=BLa^&x@mD%oj%7zg+q6=B-h5kU@doz1x3n*$J-zPc4n5H?wX_9)JR_N6qSmSQP(O{ZM;mm9O*AC1 zVg{L6k*xH+y_h1yatFr>rWl76h6dXQ#1MPfHnz%TL?q0wd}e&}rjhF#u$X}OdZGPi zSw$Wn9GovwRDV*|U6Jv`OzT4wfpcQQG)Xc;8%m2jlFfly9sl4ETuMwv36IEzAAOjy z@8Jm?CL)L#6exNUpq8i&VdY2S(b}uz`Z&c3v3@c3ZcgqNLUR&;WZORbe2I(v8Nwn2 zF9ZR;**-wF3Pf9;Nz*gFW|jEKWboV?RC|c6y{8_vw`($aMD2lkeabSu9JdewiH+?% z`Q8z9-aniGrXp`g5MYhHsArC!i>f?R!78XMw;V2Bg+d0CDdV88P<+i$csVu%+^78p zEk~*<_$B=fvs35!Nmv*?Q$A}Z=bV*;Dv%bQ7MNN$eM`gGU8?d#fuy0qJ>EZvI%`DD z@4U9>FR}OxdcV;k@%A=#%X|bP$gavEm0|49ZoTeR)7UYL-khG!%vQ2~lIf+Dfz6`d zV9*%q%#@=-rs|QDS^T|>t%hJi2kmBXGl}Tt%&uNL>!NYn--$X)`Z;tl+IQnnw|nCK zp8hmn&v1NdZ!Ctd&fmBR3zzX5CW9@SZ-8}ePOxK$r75v!l~7e0Qb!e5frBlzEC>%9 zq?&wa@1rbFjQc99l@z-+BGMB42w8VA+Vi;SF5RH>ohON211c@$DWPyOTD$ z<|semT&%%9Syk9C=Qeul0)z)-Qdf%Rrn(>90ooBWz*<7uo)trfKw0yPH1^pxWW^r1 zQTFWNn>%=1t=*(^oq5{7*Ig|b2{zPdUSF1Iv~%YPfj%PL#)?%Ioc_8wKwau4(tYU3 zD)(osJ)p=jZ(zq|qgif#=zQ@5i=r&?&-3xpY&#sF+bZ6%^N zIZuo5kRdobBj2l?jvmns`eEm=hsQt!!nQukDzg#H@8&XMTmIe28A-AgUjPrSn`Nv>r~O zTP8J5WQB^c3Bs3f*xxuwuqJOL2<7=Q3=31s5teP!QiVE?%wA-{pA~VgxzsH}rdI0G zc)~cjetW#o_X1YWz22mfJO~MEnetChVI)N1q&z;`1M1<2U#EDVUzFyVqFFK z&5DoL>ofd`CI~8Of&9!)A}OQQguMp+BL@6D9i+{5iHmM-WLmrXHzBZv3Wt2L=Jl8_*tzc3G&2X=IF|?v!!j&=Mx7^^SlAn`-{}1 z?$v!hGhrCU+Ty5OR(r77wu8a7!GTPWBJ*2ssNVqV5Ap%%<;}M`s$1`@c5(+Br`73H5!pDidoph=6DJIr#qUaae zuY>Sc_p&$4ZVK*&=|Ylwe)iK{wl?|xHh0s$x^*yCz&Mcmvz#@P*!nk;DFp8!2ajWr ze`z_;N1;jxPx78uM{(9sR%VR|Ao$rE;V^LICtpB@97D<5V_`F@zGwI*^;jV;Taj0+ zw{sZLke^?oJp6;#C_xy%{Kq>GZb1id{FJN94%VXq7l(MJ=A8w*_G`Y-DQG71%xknU z1s#2fd@GIzmWtbWV6pdi@}c@n-BR3(nGH5mn7t#4V1e>P!6Bg{W*68Gk50S!>eZzo za2l7eoQYI_moLVQUXxUNa*T=U5J2p362Ai1M00nK`@+Z9F2s_FyJka}{qk{nAd zUJ!tjKYJS=PnEXn;VHQ{{wRzWJ2hE%{ks z3V98P9MDF3JVB*5K@u&w|_$mi!=a=lJNx~27D1~$A{tb5q!5Qy;GN{rnEo5P# zhN9mn4$=M*w}%wBt7z`u{-pZnClt(c8PNCea;md&p%SoQe)ZyP44i_6Dt9Ow@;g4s zL*}1^(wJ4GF~y9Lw~o`_SF_u2##!8uT8Ye5JWQ)Y+I!Zaq3Hgaunz!ur8r!d1jVc3 z7oJ>G~{{w>J$X9fzn-XKFUbMZ2=VD^}@byMQ#44EUIYIiFL=?Mr|Y(LqC60Nfje zBw~mi1MjNfEoL+YkUK3bI^>_&mGO?$1fX7eQ43)d%U2Pt_=j%F>1{ou17b2!@+7J2 zflNza8wEQAgp>E-=0!HplCe4)6Q}P-ouYgQsSY)N>V+hLapg15kx;wzJ%I z7{jF?MEj63-<~UI8wWi*<|T~HsI8$a4u{e=@uhvxRHMb`l@Kyj%o%`5VG<61o=v_n zzb&_qDTF7#b8LXjqEOjr6=CWafOssYLIS>wRns&QS`oO%boC%^xCWO=CW~B-{yxa; zg`_Z6IBpe+D)P%larthB3`X|9IZOXRz4R+#F zyv)-kGMH|AZFS*WV1QceZ+u5c%;>zK{f$KBRTyLKL5`-nQlCkoypwG+j9gYV!DbbqwEzRU50-@4YR)S9bkvS1xq6H>M3-5F~> zng(`#q8cyy+3N0SVsc?Dl4YOOFZNMvc$x>wtNEKAL;KJFK^|cyo5Q1^Z(TL4!7c}D z$B05yIe2T@OS#PqFl8N&%Zay1fe9TVgOlB@&`ro1F^@TYB`*OjOa6}kcx-(o>Qw%2 zK3#^W_O)w>n=~`|B4ACj_*$@o(&buqOTblJNm#GdT5z}3 zyJn=d(mtx~>R?jFHttR%8QQq}*FWaIV3Jw0x`C=XXKw~+gPj0ibo18B(4P&^ z{*CeY6^!`P4XM(UpVNA_cT^n`+^L^;vA~;ec>E3lFPw5 zyiQC0(sDh_q`OEE2QeZn;XKXHOA|T%kjRUMt2=>;$+6xD;yUstJf))agJZPy2SFSD z5bUX~6S|>ug@Ky}o4L3sdl&gl0Q6J5Hdr2v;^bo(#NRJNOzEcUn4h>OE4I0l?)H!` z(hI*l8ey`V{;v1x^G{PT5mDRMBw#eZ)OIW`yqg=xmNW%jy(vQgY!z2-wpFn- zZ%g6ag>ITs#2pQ)zsGVzvKjYUn{#$kbKyy*I3zEc3W96w4Axx{3yg(_BWtYaDph4K zM2(}<242em(~N^Y58uBfyOu$3m1reJT(o}O^qooVn|t!QDO{?GUTw^_(muVe*D;YI zSFAs6>%PYuaG+W@nhlM+jP;O1E45FY`>t#9%kW05$lUA?K_go~!!TRMI z(Vn9nbNQGLs2Z_&qo2UkzQ=kj)1BekNd$ZIa$!2sBJ5wXZ;$H~!8#p_1Yd_~?6rhL zt(eHwe4QJLQp4xkEstT)>OH@>C&TI9gy2%Cyr4!d;c&Fb^}BSuTYs8xh`V}kjPWy+ z-%39bpbf5ZG95#yM2FLbSbiZW;Vh@{03aGA;#ROhj__2W{|0NYuHG_Nz;kpEd7b6~ zh}zN3nwQvF;-*}G7-Mp4ML6e&DZk^-a>aph?BA9%L#?QR({?|!Y6HM}qePDQTMc{O zy!hnLPYx^oX;^9!yup^A2Ou$=0YtPgEzfd+%+}df2hrc&I@aB?jDgKI_HFJ?Peq~U zhCxx0@*8G~{H`dIL|uVFL|rK(F>H-u(Nd-0QY5fWOh@Sx8KM{be`OG@(}-)?MW4e7 zMdY$pP1b@=*SV5>KsK14mCV_W3%H!gKj~E2g?rKqH>yNq!ITyP!}FsgCpVI7^>8^w z9*Ui{yZoX1LCRigF2Z-$U(IjhQ5bvG*o(wTNhwZLoop!`tSGxfb( zM<^44Z*8hzDMl6&*u8JoE&r*CtQ!fwFf=+oV9pkz^MHQR?^_iV!z3NKZah};xzVl> zG?o}9T~MLdcY~ub1hf;biOnoa`ki*zl3N#IoEBlEPvCGKb0u=*Pp^u8UzsgdK#ml) z6PnLmiPJ{TF918aP>*-~zkN*gTR2{x-F z7MZZqTbSiSx@ z@<8;O00HA{FE|47o`%PFn1ssE*`n%=YNl%v$D0wDV!g74%~B`Ug}%(x#;1=u1mwTz zr$2H9Ls&XAbRu?vI4RqA>8~VWI6g0Gf~DS)mi(iKY2dfqzE-udvvhpbd#zQGS^DdppcYaUSpp+9x?`1w}Ug z;3zcL!Rs=Yxi{~2D0|mPW{0vokVjPN3_fTNY`qeJC)bqAWI876bp9JTOx}O(qv`H` z>_vVi7OjJv0Dk&dzw6MqGk*PdeMLlPZ#KOdkR~FNnf3@LwZT2A{9x{ZLtRbZ(54;8VLsVZ+DACCB#F70b;4 zGeFG0rI~l%@m8Qcs5F_QJi}99zE-IB_{T8x@IOx;;s#-kc9N{5UmvKj-np5J7*WVT zWy#;iWN)3kJdJ>kEqobrF-<~N2|^6l zXsI&M!n1f_Jh87jha%%$FjH#P#s^85mLrH00SXXqMd|o;94C_Q?#(t zK#OAwS~ATdct8G^e;7Sdzp&|hMmv1u31a(*5ZzDC&Wcefl2roQH%$&{Ofa9f3Q>Vg zCwe4!V$`JU_#MYb|unyK#AAFe?^GpFw7G!gZuR|av*h5Vx<2nYj?r|4EZ|5~9?-@M zd1?g~snNk!IwGJze!ABGecpbeof2`{IFVR_%&s7jV(CK1DCwZbIx9FV*b)?*EiiPo z%QKwU#FguXh;SqPyS0>9Of4ewzrgIT`Qcr~=2DCPOtL@B_t`u0O zNpp^0JJJ_tf$k!*punpLN4;D4`rTPGy<%TNAJ|I*qgbkv8x-+O?Hyi%odhlIBIiR)b|T;22HK0MSYUK<$C~bxVC?84525F%X2&LPkko8t6_?QE z(U3Wota);ArMm|y*=}K)Z_$qhRiCoPkk@mPwb26sa;O=`Jcn}FJ*7M~+Om1$n;~3x z*OC1GO*gg8Rr5taRQlF<{G}5-ORz7Uj|ufy?0ID2(TnpIV0!)BN5jc5=j*C|aLSv6`~fWF5udiZ z^<~2HB98DI{!%TnEK*$GnhpBjCi_W@=*hR(z*zDt%|2(|KM9(!e}7fcPHTSQsOavZ z6S8)oeQboPpZI%^BahC!^Fsw}^dyHKaMv{2(qi|f=@D+y!v3>{-vZUVeaZ40cVVG` zUK?Bx_(%QP7%&&Z8f$}2T@Tu=vRdq*62~=6qZPP59~MW$;+0uXFE3o^+cTFBUyFT@ z)`V6RLlDe{9E<2aSQE-hJcr&s_S+kYXEC& zrmFn9>z-~rhhgF9Zz&k_6PgLKwK=?&-f8OVO_XOearApRqKa%NKW zxHv!xenl}f;5?tNf;!29GRQt7pg7EOLK=8l|=y8{s>aBts_3iT>7A0I_rDeo$^s*m> zu8W?8a$Byf#NEBi!FV4HQ%BI8yaCq8j8_(VCc>FI3bi#)^Y5DA9OKIdVY zNynm}+#VDTl9huUL`jXzS+R4_1qR6pf?SkG;a`^@FJ}MLeCxHtI;qtk&Nyd-!BG23?fou<~(ryAIA!!h5 z685bG!S^%m*2mcC*>26I^q_?ChL-jlVXmn`=FFUKUiBGh`&Q1CL|JT=@Wl-A(#Mt( z#^V|G7Gy@Gvh$lEp0AkYTh zbA+yK+|kwG@6pjp=tpH4|DB^79n$`7h)#h=wYD#InjaM5wM53ZXUOdTgcPcEp1 zm9KAD-fd#4-eS3+X;jporYBs9{yFxUL$;OeL?Ek`SX>k!PehW)gQEspo^p-hg{iuH zYNw`#aE_baSY`Q_dto$QCEYUIrD!w*e-u@dEb(k}YhN=W^N3fO895Y)#^kU_(c;7VlsHyOUECgXF^U_t zqEQKgUzS%=aC0z}_)Xu9Fh-oq^`6c|s0Ftlc1SrJ;Do#Am7(l;n*)(ke|0yK!~Qsf zVYYz`z;@K)?4-5lbXh6k1~b$#gT-hAF*W$ch%oc~k+KjI0mBmC;)OtjtQs(g%6+X8 z`s=PAgrhd|q87?)6|GKl2aiomK_IO^h7KXsfh}lp=^62h*AF7_VL(edKeCAqSWx{C3BUVY~r z>OkdCC6<(=qUm&2dKcrr`Ah58?OQxmLXgna;lasa>_ti9?%t)h1#Pz8q@p$L;YC$~ z-*Hkp5OR43O&-gMG>dLkYeC&y$%AU1n0!(v`t$+ z+ERVKxpI1GmI=afSkmbGd`HnQ)GiNAg{cno^^(nAnzO-Va-JF|umg+gW!@ zP+n^X*E(8(&ocFEYwNbxlID*V{i*!QCy=r^qVF_P@>&#{0|ymuFfPm2Htf*5 z^;v$+KvQM~-7ZhvwT_Mj+(WP@#F0m!NF5n1_mmH1bi|mDTP%Ye-@67+s!WrJ^5)Zw zwL*Cqr|^f!^AshlgC>`zEK6UmaIw(niQ_yzPuViGjn>C!8j;b1g5$NQrO1>_rQ%3Y zPp(wl?=lK!6TxOg49e~D>GF<$0uCr>ESdS`DhmF384npBB(hK)nkK+cXzi=DX%DCG z8nlQ~3!93J5cM|J2T}y4?@1(C zx+If9K`=b$VOA>Ep`r8>oJeCbrroij?6-01gR-cJ1#FBCX;qY*kvWBzN2DkFWcIhu8TelXo($=Us@$ zvkQ{eJL8EpGxJI&tOP^A@8u9vCQ7lX+p`8oQFZz+RKBYm2r&2WxMk|KWdw=j-*w5X zFuzIWZt|(Ib-tuR{@P8Avcsm`cGK<&BPAfL4L0@CYHW2C*cYw?D*UFkg_f(@D{c&p z!}9fd4U>UuiV}a;-TwIaJ(fR=-bCwfF{LyA#xH$!_Wq+o!86M)1{%d3L56|oPNw5l zbHbJ~pZte@TW{2<-pe5KkbVap*MQ-Hs;7jbs!mAM#S(#Y;5dL+Ygrm(e77L47r8;N z>o*XU?^BH%lUeN&y&_7dm{ctp*I|Pafi>zq|M`37T(Ttq{A+5pXdBD7dw}j*s3=*F zxgRTWy8!rp!U4OZ3c#(sb%5Yzaxy1D^yshIia+HIxg+v0l{`qs%4iRTaj%{d4t9af z(BKQOt83t^DEKL_a;tJ zGSIpxL^2GpLYkya-*xy!|8~(Y&jE$jG3ao#6(mq3 z`$%!a7Cmjq0KU|f&?);v@(ivj#jqpTI5=3C^!+=kHMr!$b8I7&1vr~#*K2)Ht1G{T zDHbuDHjfRU&gzKbXQ^KIDuS}w$!!>s41FB$_e8*YFNgcvbHI30X{UiDiFdc88CZ2! zDm7SIjCdF7k(_k9ff|O8|jn+;tVOGh*;Y}Dnx0j)lLzxm-G$Lf($O2RWet$w6`af z6h`6ao$x-3WFP2z8EoS|^6Rs~$Cl0Z16jxp1FBxmtCQErevdZ%{f;Bpbo8xQwdv6^ zE<#ds9dcom1$&3Sg4vE-ml}G+fd`+D`dRBx`r|s#!J!@R2 zw&hF7;M~_+mA+`OMDtpZyS|p^#qMD1md2epmn?6Z4j&-lVUqOdG&9Dp1u*iIFP%pT z#irA0wKPt|oGd>H11OlZ?>@PFOk?(w3C^Ofm!^tR{K!*CR=+R<%)jR+?>Z`Gr@i*S z;YP?@;@(+Deq$1KWPVu2&|wc02Mn}B8}J2|i4)+cFZEt=v^~xXirLY4%rxVX&8Q{%yYGrwqM)D14bu;3r}NYMAr2b56w)?p~`FzF7y!#8pf`5K zYVYTFMkw-N^Q+Y$8?VNeOIy@m-wsysD$^QW;qe$??l}?HN?!i)72Gg~}GKPkU2o%$OX?DyXi@dTy(?_~@7(<7&8iZn?`0%rw z(6JM1Xn%0Yy!({F6KdG>W_p$C&~QBa(L4twO*1v}_MlI=WrcReGHx=CEaGa|(DOm+ z)i~JG#ca!rh+lILJ(nCB}+5?S$srH;_&0}ZpHR}rS!L_MJ-=w-nu z7>L{&M`B4cLj~h(DO4cG%M|X-+ipYRB6y|XZ-yWpGz2cTA9ik2W=iT}jUNgn(0WeR z=OqhO44`7`&I7`>$@5qb-Jt0am$-O{lb!>2PLP$vP) z9vxbPBSbPq(w}LUH8v>rHq9?l6+mvM`~E^Uualxpq<^ z2!7y40M56#p|2n_44A4{xwhZM5!{|~ZCvWxXHo~Fc(oM}4A-t;Y>FjqvtDS>Fwvub zx$RKK1NnsV`PNtKL8!FPL5n4!tEMdxaPgs65_8Zeqt}(8cl20x_*;vD5YL@#GIo;lX=@Uxf0dQt=w5Bklmm%&uGu_28h!VT)Sg4Fs z!Jgf-@9!VS-t#ZP=nH0s15Olub#r?L_Hsj-Lx-E2sR1H*EJMZP1o|*E6kr4}oKkGO z8jL}P*L@^=bmev}fJ{RX&YjwuNw)bc>}q0Yzydjw+M-N1@Ypv&YuDWA0x*!OvObrd789G66#T=6B##q4S2ySMzuP@K>( zRRVyExy;+IJ!+f-+NIlgviB9)IB$l8Ob+dtYixY#Aa*K>b$V&GFw(oo~I;9IIZHm-;-2 z#U4KDl`N?CeE#FzzE_R{1n8QX>S*}8mr`Zt$?hOJKN&;zE7^t6Pa7eqoTnt9%n6hc zY2jnajXvtee~YQV3yu%0i<6O#Hia|E=>|hn*e*PhkHz43_YDM!W^A~+HDJo?xSr{& zPbtGJ=9n^~uvQ&aE)hR5S|yh zBnR38daCs*d$vj7Nm7LXji`F{fS^LgiQrwA3*FEp0>t%-gWVNAA;3Y)=n1-J9HiFw z^!Jny;XIJ9%04$(&u5(Fm85pQH2$5_D#0+qn+ix+kGRiWxpeL_TWtyVkhlNtlvke7 zkYIW*Nj-UcVa0V>;ER6LrxDi9r5`4dyQ!#?p~)a`64a?B_`FS_$37~@)S?P6J-|aq zN7NTfUmYiV$AlI;}llsyI@eWK0U47F4z5XkQ&Cl6E zD&PIS|GW@~+C8OQ0J8Dvuy9*O(i-I!5*KPdst7KFTPGPGbDK9%(teR*xe;Q(*93NrrC3p};3SLovR=f|O|Oz?&s{e=4h z%q3W6-ndB$Q+!$^t;(53pD3f{d6GZ%_`)`l4)oD;2$&y#mZb%md0Llhy{#8~h@_ZEB~w_hR92p<94k^v!zv>uK9M z?mz;`8c96DMy;CT5lGL>ZgrXBWNHunA+++Z=gkDHg9vvqg?KNjbb;j3QY zW5=`GT|?EFmTiAL-`EC6=RB}Y3T&Exoo1y=|M!fiN`Z(HVf1%sD*+(R_IMT??$(lP zkeC3BOxrmLPmhaii-jtOP^7=nAww_5j*>9Yw_K<)T%(ipysp^wJt=+ibU3Il_2A?S zk~$~}r**C#Gn7J}m+*(itrRKi^jlA{Wle?ilfu~yBTrP8?>DdOHzL1C&qX_1dP8Rx z8Zugo!8;8Yy4gjEP?)LnadN&c*(5};Y7VIIK(JB+^qe@y}Bz(!M`KPg_Mw9hC z3~)nxZrd65BIP66hN%wzK{6KyCyAHJY&_TP0f%Q~8;A`hf|6g_siWtsOIwx;(4(Dz zccHPAqsQJ^LPCEez~WfmqSE%djn2deyEcgUKw-oLaFUQFYDZ1BbRa&_o(tl8g3SM( zNFBp{ne8~*Zfb%`S)&7I0n@+c;}{=`h+qaq(dUe=lbj+2_>zNC{oU6saq#B)+`MF* zsM~J?6;lJoti!4T3I4*ItRi{HOAPX>auW1kJJGH%8{YcP#?MVq$q5E&guXyKzdMq$ z25CvIa14Lv?BdUZ!&+>_)|+*Js%C%xTv{x0^!Gt9Q#x{Vm=V8xo_F?EVQhCi>H(%z zHLL-)((qN1xR5v}ej*K(T{KS!)3-xsY9>(?prb|tEd+VTa8)r}KY_xuF5a&e(Mun= zwRpwfgC2cV46cc>zRvC&{p30l-#>d|#O;&d7$D4d=P(_x+Fy*3ma*|e&25!4Vkxw~{7z|BqlwKO{+F z=vsir_mvdP7Vqr0~&}rdbkW{hq&>PR6k4?2DYxQojKDhmT6s z5uc$M3nc_8t^jDAiH7EI08v)H+?6U2fZ;R6tMb$>{m4=&I+ zFxj5e1M;VUS!!My1qMZSMdn2aciwp;q2O@!oi$S{d+BoZJeLD`9ehhq_u=y1K1ID$_j|+${2G*KP=BoK$(%gg z69W;TLsBi2bQl1;$XkMvqy~%1eh44lEe%;7hCq%jqVgPg_g`Wd)L23lYg5!BV2$xFNF;A~pFr#Fod#c2Jonsui6BO1r-o=AWj!jptw zc)vV(kV}|e^B?o;`o7UvZ!;h2;mcp&{HD-LpFs@BjWGpFc9a<0)IF*g=|0Aq_2t&5 zD#_dWDhV`0^1GgQrfhb|zV=uU>GGqmgmQdtWhbxnjX$9{Np92dLQpTv6h}XMZ_oG`6ocE@>WeKWsU1Sb zrz841Q1r`w6oe{olm4(V-(b>*y+LZW(J8U41%6t`jp`?&q2vu5i>7Y06a*p7m+%$* zn}@CN=3a2ItVXBNrdHCRy?H`6mp8o{`p{Vni*EMTmy5F#J0{C3CNaYVexG#1LP=Pt z9J%wFMCd_oUIFWqaOF^nsw0Z-ms2@v_#2)1Fjfb;*Po8HjYrH3S-k>Y7!2q$DR!U1 zL(L8@>Z|Gp0sr0)7&mKgfp}5*$AOLmi>=La1bC8j8i5nxV?Je;0IGovww`LG*+lj* zw;OxSwBA+cm`x`oFBZg>5^7oPHVnh&U~~5C+E!V;x)H1=D?9v$N-AOyTlj)D$Suhi z+fZ!0m*ck(7559Q0i_+~dV-;df>rCYUgEZP)U6)AT5(B@M(StYUS9$ z+#;Ob1Td5%T;I5GUYH8&d5!(Jbod6B&*DFN#;@^EYG`c5shv|}Xeij@*A***R zE=j`n)Fd~7{Y_N>*V_)I)3_{lVID!hB{+NnDSIc;4l}V-;%QEjHzaUb*0%+SzqEft z7?EBJakN%H_`AKaB7p45^BG_Y7dk?<=0u0fFAeaSXY{WNeu1;Xh2rALi-=8;o<9-x z8k(ik9}m@T-Pyvg5m;W64mVveFJ#u3Vm`9;<0ZWR)*vByR_paBK$u6WN6m6NLyO-? zCF-IgzGnFhvb$wJvT2zU(oj&+Use_vLc2sycF!kvDuxi>H7j)!Vui;q&PpRkKr0Rb z6O*Ki3V$G~d98u$rw7o1gRINNs29ZAnL6-`;51zjP~jEfxde%&@lhai;y|Asl@F{( zB*ZO4+ivI2ffi47|opWs>7F?5jZ+GfnvMm z_Ws@pyjZOvkB-@zzHM%=3-$4G0U<;ks&mUn#sXlj*)90I`Q{+t)GSrhmm|;NmW1z( zJbe6zcFR^T0<**5rhCCifjE}=C|!4V8a{gFCp8hmVlN;Ct?UZFWcCGR>5At{^-OuoAyhX`$!38MY*lXt#d@Htgu%T z)7poeA7fN>krh&r)=-c0TnEo_*De#jz!+^pZ>_2ATXqe%ph>fusNxO_Y@M9)$|cc69wwyDOgDe_Ccy~3 zry*?xufJaZfIexoeQ)1@sSl(DNi!xlFxn{Tqyt+BgJ<59exgPR2W@V0Ck%HO%@ zs*3bQ`8>kzF>lPu0m2?BW)@&h^As49>J6>PFCa1ucP90&DJz$F(b9s$g23Wi$+8I{Samy{hw?HyS&$JONW(=Ng?zTtjV#x0nV z3>#Yi6oHf3XsSkqa3ij(^}mn-HSI{feLWe+dP%$IH(yv^*-S_I7f6ge=MN`C*h?^7Q8p(#NT@aC^^MJjP}81lXVfFMDha-&h|F`=Fn znjgdF5XsfnEF+;(Z0T`Q5`0$Qe8jbybIF;cv?wNZrI=(PSV9J3LoV z-$#)xqyOTODC)|u$#>dsZ`~F4>DHCdri#{`vxNAbCXpMVTwyR{O zu6S}0={yOFi0>8MA-+OYpixm(Y&)G@IHRMsc9gN$?g2bL0u31KPAG@dY@a}YAO`d- zw>2c=;f{v3h{~o{J~!cUkiq8fjz+dV0Lbn`&L<&d^dQoGgQdAQJ@zWr4{8~!i)Y?M z@EGg^Gk0(qlQDW?B^)>l$VQI#0NCF=G&WQOR57IQ_A-NoG} z2x%NHslMp-HumH7cb=!8w-4wLZxZ*k2*z>x?Cz1LyGn{ynq6t?_n|t9+$YG1GY<^m zk_NhuBY=M=lX5Q+&Ugp&a_p#&n>#31G5i@rgkRm%G#m`ysAwudAtE;~?@{)iX9m>C z9j~%QDcco9SVJ!UaEnd?FQ*0%tMbnwA}V|$SqH_&cZMt`P~IwPBS>KsS~exC#ut_n zrQKUh@?clzHicv|lqrbbG>E-P_w3k{hJ3GZs(;OyBacp5>WMxWkM(6BNQO);7wrSkQW{woN z&c*txjy8k`eJ80y=Tv@74Ow#`Qvc&nd>c)uT3@B-KGnI@|7=? zf5pVwR@=+TOdl*^QS|!yy#;6g2qifF)*&RyBa9^0Wz8R+1jGU>Dn;}D4@su-PwY4J64i>SF#*z3Pq#{C>7~zW5 zg;ZM@Jy&u;5PBKQ&F@xtb1~-x5k?me&kvp)?&Z+8T$xo&7lhwDnBX?%l-ZxTZ;XKr z#N(}vizQn}o3-fV5hJHv>iK;1O$%U%!eYr|G_tcXb5vRye@mHuvmfY-T>O4<1P2q- z{ou$_3~$x>IMdn01yFWk{OmgXCGjWwm^3*5@C!o^JxwI&W~)Hv`~ZiqwbtAO_Uk)y zp=zgRW7YDZTA0MiX>;yW6^kRNa)_3GXY5G70r5h943LEpF3`3z*YgS`rklo!KqGEd z<7w0K{TPPQ02ysXZBEsTiL(Wdzc&UcBI2fIl?O3UGXP{nd2dD?1)%-PC;js4XSHA6 zzOn`Gy&UVm4f_G|Fwht4{Y5P#9vb_OXTr@-vO7i*VB$LCuP#BFs8cy)ODz3_WiR}O zK36ypL0oy`D8PyYr3}8yE6GLUnwDUqIA9=!>F|svSWA`VC$_RlAu-37Pmh+&rI=k} zg0}DZ$~(=5`*Xg`<)}Ns^ZNYSsk`#&tX-{)`Uvj_B_%kn$+JL!r#7|9tCnV()^=ea zdW=DY0hS?;((X@XAGXJBd3nGfc5J-|ecAzwe8A4RevlJ=F%=vbId~VhjD>O$fLZn( zqA&g;*(jb1y6$tfF7vv>%Jf@&*Yg+%Fd6Q#H+A2!x_cp%T^9YI&3rzrj5;o$>tcX+x$iZ^VM1K&18i zxg;0bAtRc}nLy2lt#!*+>5q7ruyIOe_>STzw+{C`t#q*Zm42P5he+|)l-$wc>prjM zZ&0)TKb%-k&vJ8q29OzC&!^MtLUd!)nEHg^`gg;200$;V58oB>9c_!Z?<)C+SS*VW zAN9v{x1{uzc6zj}<1NE=W^t#iV}#Dc$B-6m6JZFY-5w}7Bwin9Khgsm4?N&LA8&xb8HS9e+X z>wBZ=LK&iELNfPRC1tEB-CHd~?hr6+c?-X&&k5y%35==b#0Yo%Bp4!E&$x8TEnZj_?NQH_YEJ6nk17cLc)jKE`MH%sJ;a-j68 zc?51=!R<%&BUfuLlb%b?^ch9EN2H#J5WFfvUsPdW)T3RJ&2Faf-&d_EWwE~Fq*mnX z?{944g40DKOVe)9o8k^;$XZ9n51dDv``fPJXzo8JHZ2wO1nzLjZc$NaM z>GC0ht<(v12H6|aeBz6>%aAY1z z*^JXtk|>X0pgdqVoGwdU?vaF|{chHwziA`RCn!+WU#R)KFX&AGkIvtl6U5#X^8OW%lbCg@u zo&9HQEWUwOZCX@%re6NrNirSAP!Dh@PY;lk5S*_``*)NJug^@f1+{n;U|Dfn&sm*Q z(AGt7-l`hK~ufLq;rD;z;f;4+pggkvF(S z1?vJYJ&*z$SF8Gg!Ribe1SXFLCV=|ov!n(IBKJmMX_jf6yO) z%!a5SAPCgT+}S z<*)>3>%bSe%s_6*Xey&rlXR4q-&#$-PS1(NUmY}rCXE-utnC(n1vd(X>L5=l-Hh1g zMCFgk%$dRt?Awe}sL;E`tz5Dd^%8iX%-CMd{#NS%yl&xnYGtv9=VX0!NXrYgoelu^ zj2hVOK7qaFP1CX-6yOP>U9jc1Io*R5$vdfl{RW1ltEcoj0ELH)OVbMn6qqNOBV) z;{L5DfYn1h@%&u?Yc!H32lHL^1`?u9`42nr>5|eQZwvgl+{rQHo-6%HPxyTby>6Gm z-KQ(EL1S=0u0MRz+8|ANfm^c4S?NAkPIrI(H!$ilRVg1kEKz`^V4>UZjQ+C2fGDb^ z#koy265MGbXRmM^I4(>w2Q4gM0{7D@8t0B?bIyX1!f4g5hhbXy9;v?%m_9Bso5M^5 ze$1nSY?_{+ z&ccR+EODaBEdrh z%rjdxfm82#y)e@h-q`NEqs`aPZEYEp6ESJ5dN|&stgC& z=2C%jbY~-*AB=Wudw~G}S>e-phM2o9H2YZ6M;!So-o)&~%dg0K$yB{KvR@lSo?QS- zgZ;ApCx(bkWBm?{?l}v946ZV-57KloF(_(~Ki!kCZvqqrx#|_3og@J4fO~5lJj?=P ze||NiL~b$MqwsvyOtt`=A@=wS+gs@#7|eQSV-$LgBUB zxpDKrmxVQU8#oHF3As&0YvGg732n{DVL9jRI1^SPWOyrCE%r#T>Ub~#iVHfQ|Ngbym4rb7lwXpy{YnPyPC z-F5AP$v~P`N3)+>`A#?_!Q+Lby!!htcc6?qWXxF8U$pR$5$*UYPhmRKIL8wZxi{PD zRkr{kj+fH&%UU935MbC#%aA!FQrOI!eP>2}IPsoEuAg#T+Dl?l^W@5=u+fP>t7lmz z$&RVfmUq5y?(sGA*K->J4pG#Lx3EY7hRR1{<_I70>Sz{4K2ydCy7L?B41GekF0EoG z&2BGnO;QK>$KD%H;tiT0)TpLKb3CKek7)3nEZ>N-y#EH_B6$lq4iuQBpKD=U>|y1C ztQc;Sv7muJVjo^Q%blyVLl}|uDLMn7v~kwp!uDwueTgFcdyXeH$F#@^kM!V0FmiK$ zeA*c0A!(v?X_-_)N@{3JuCZf`Xpvce%eD~$tep*^l3e6H*v${bg6IxkUP&8O=PnOs zysnroz+8_e&Nn?4Ka}L%l#lj$`>y&qDLE|psYn)mY;<02YjH#0kU-OlMu5WZF@QvW znP>zaBZn63>|oUXvSI085m%cq_@W=c^MR3m?C;Wv#nX7T=LwymK~W4Y)!o1$xk z!qP)&u8#&oJe6Jn-6>!D~=cN%QK{|1s(JkyO#;S0}aINYrU)m`no;7 zwjwGz3L|Q5>m|ws{mQAQE^P-nFmZ%Tp_$GN$ZpVf-_|lMQ&;>=P*_q@!i;y;F8rn{ z10swVZauyn(l7cX7W!hljqMUDpBgzrq`sXv`N=GQt%*1;38*|mstpg47I{ZXc=QZG z99lJtH>16jtgeycv%j*grYQVI&1cL)hb|ispv@>AI4FEH%0ZCqho~e04ne4hoOGBm zMyF!n@Y{v*;Vn|+_OyHi81>Mf+`!QLM8Ug`nrl8HFoUP$ zL9WLYr9w_9rQNT}@Dg@keWigS*9qGGYFYT>n+M`sZ14+if+_HK6Ais1d@7*FQl@QkSlg0olqDB z=$_}A>)`pb3Eg5*5r7IMyD%Q+Muqi;bPNOn56%*zINlU+5%rRe0ZPuTt$v@@wi)n2hNsD@!7 zy{vVGt(woW2R^0!u$7D+iG-%7!*1UaBBRMUPRZ|GAVU*4-+~8N(UL3C%JSRzcd4b> z5FFrst@{@MQb4W0!O_02dNdNq>>7wODRCHU=g2z_UQ_SSq9@kwFbrOlRvC!1U4gN=?{h)JOEn) zX2^O)!`eb?N_{{&`{pzf)g4IdHmJhmh7Ayu2Cn>|QSi%mlp?R7;06S!*as~q*PhR> zZhP^W*&b+vw}!1To!crtVo&_@E0Xon=6Ol)Q05xS20UnB%HFyASgQ@%p6!FGN zoR`9KR#A?}xfZDSpE`m{ncbIKtcz7wc&eRv=WCi%)EDMJ0fjTInhm~-n<~Fs;qI?E zu)JLtZZ`utanZ<^K}0SYrSScWpHD*UBP4MhAa$X?MfI1ex$ozV^A2;pj;q7~xWCS) z`^ejTp|=mcI~@B_yQI`1#vnLXEVe>$;2Upl;Y3cnpj1Akh9=|BuLyIh+**82^XJoW->~~T=H(;4?1zs$ zl%IVnx+_<8ahiH-!JhDT62P#C5_QShMp1k3edolnvCofna80-17*d78Bm-Q5ip}mT zWQB&|E3VuxG|{_>3A%|h0r`1o(_v&nh#+5hZNt7srO6HS)?k^PX%fH!_#8{{ueW`= zSerQ+3-{Yow-?5~WC)nO_eF z#~e_-wgU0I*40GHCKTR9Tfl`8VoG(F@{2Z9;&2cotdSy|h`|UcKDgWg0#UO>8=9Bd z$I!5S3#|P^zW`tb`Q!u@4R^Qq<#(;RMKbzpNIF?#xCXCqaS(_GAZ8 zE)6E}6>Ghk-ui;vEUmQIfLVMmU_$o5tP%lqS6As`ah0(A*l<|);s@_^j@&y8sQSZU z{iid%1Wzxh^<*1+JQ$&fhSTw9hxz^v#VD8c-?bn)LlA#`I+Oq}yH`4%TAxo>%}REs zOLZ^2G+Fo8HJT=g43L@ufmI|wlZY9BJqg44&~oyyU=}5a@l9S<6n!tdPSB5zgU0QK z!0~UY!|pGE$-j4kirQsjKQEk$00u+>pW z*NDVJ66DlDvojKT>OvEvx{b#eoguGhezUv#f!J}l0t+8Yx9(MuXm&^weSlW$NTP~_ zPoMoQx$ZF@Ws)_&TOqtlu0XG~W?}Nsm>J6;74eMQ7f#gmC0-*G93mepp@YatR1-pV zMBxJ%13_Nxu@~8JgVU*|^b|E9`n0Wii;LwK){<%3>dcYST;#7WBAfZtla2JOvWh?c zxu^C==TpL!MhJQzP&vsD`R$3E0&s$UD?+F-Se1M^hWi4JrxaU(RP?S?PLrC#@E~d` z?Y8!ur=-GD-q1RN2j)Zsq&+^vhZTp?`_Agbv|EO>~LL2G~+;Lx=0S7 z7(ah+;mpaQ!Rz+5=lg6Dn#)^3a!(VLQUeE5AL$g0(QQum@!f_n&hW z1@e#c#3r#uS zXcRsFbWuI7@^kWMny{0|ehp21b2XJ9?}cZ&kM>*&h_ckQpYqznZduxvdl!k$hx%d> zG=Bky#sU=|!XnwkPvDp^32Mj)?W4alXjCj&7H)gltfZTc&3?5F_ha^C@R+5K z4+gelCjCBTJP|uJmPD2=<_!aG9>W=H7q<;2;H!RQmo#*iXM6voc$nY}9) z+M-x90V$TGsIP2|bwI7o4+&g|rT-S@w3QA@El&En!RtUg<&FK{B-SoxBRd_}m|1j( zF6em;Y*gKrRR%~L?br8qn3(3LWGK|K&^rQ3^_3>0?^3tAP;Gg>Hz~H0g=tSA#7-Sq zzV#;mP{X0FW?&{E2B7=k34WfEa`7sC51eX-e);%9*^3&M(-eK%#V6@zCxR1)ZxnjA z=#8;Dw`kY(a9#o5y6sel8#y&MlBjh3Bja1MFp%jjOW6CfVmlm?dLF2?l>oNP1-oW* z1K*9wa1IRN_y>ssy0ikFHv0tRXY>sN#DwrtBqTk29+l{Yne5Uv&?AG_-+XA!)zpdQ zOgD0e8mjc51U*TUhOZ>xyvtp-7Y4V9XmIsIXwV33?xRMyWG|?yzkcY`{D@v{H9RWR z>JByl!Fx5oxHfRr&yYnEhmlB6D(_Fj6=SM`H*P=d=i_)b<8xaI!Pwu8@0t*K=QH!!h@mPBTtX5L zSB(yam9EG)t@@ayAintuH|Mka#0_8cw|~IV8dgbYMQM)mU>bP?TjaACS{w$G((so_ zJ+@JEEghgdxf+J~L6o9i=IXj`S~UxM$H)!({5+o^KSp=bdY0J)b%e0Eka^}{vh))d zjJ5_gjM}L=vzq)nMcv0w7yKIAWpDUtNvSkr=uCclHDd6|@DtC0Ypxk1b;m4zFJ0HV z^}ZJdeUhkT?_Dh_UvG1E0g={5!boBlnv((u%0W$2vNjiYGpR=Hylz<=`cl7(epzl- z*jtMJ4mbWZ5vaATaKn@$Lo#cv$&&{Qj%P2PTIPd^@cYJ+X`RI5`mK zHH*OS1fVZAcxAipPM2-C7P4SmKql6?sa?>%Ce~$1{-tp7Bu$XvYfY>dcRVlh;&ZEf zyboMG%)So9=`l=5W7yW0_TWv*(F*{hMNR(i2+m zvT4hd9OtQ3In&*W5V)0h>&Q072~}V(Qe@?Bb|QzKfjrglnVBpto}u=;7pWBsC}8K{ zn;R!o+KIc*QI(P6a{|aS{T{e~ZM1FR;31<&gp1Z-$rf!y|nov$64)f^Ltgb#Bq3@ z#b0NHSPYsB_AAZ&VNv#3r@mZlI9tqDlUuOB_#w9Zb!b-;VOX@jxuT6Ir?O$zA4%#1 zdk+=ux67c?OzFuyiI4r*4cGduw5QCZ;c9akW}@ag4hwYjYUPbi?h1HzdpNJC+!;Y4^D)? zWA(#E0g1^w=tN0iAU3be!H#jjnJ!}KO{%~r5lEM+PM-Xky%gN{)X6Jw>%!|dL%+&? zfM4SEGUh!m{=nTjM(X2am|pSf2Vn`8v*PyVagDBLiRY#tt*da$dTaFHT!UK4=;P`U z+CdSIz`fv>0%5fxsX0@W>RP1BdEPJWmFqV$8D-#kvffDCJzpjchc@M8I`H%O;<=yc zy<9$}_EGgi2mLa%H)K3H(|&%lvEn))*O+(RdhF?L-!A+*DAjUqqKt^dPxi^+zju12 z1D^_`LX?qE3AwfdPK~97Y8~n4x4p|PY)hz-&neJIFZ@u{Ii2_t@UOj@e$&e61~`F_ zW%U)e<^E-~jzs?Y^(z6;e9_^=!dOzEHvt?;-vo@BFfZhw)m^@=Xp}K!b{>~WB)r6h zub5c*&0#u?Co$3iGu|rnk`iM6-B66WZKwiE9A`fpk2|Q| zyC$q1g&aM?P-i(KxRDu;JF`6!T({B6xYdwTS^F{$roK+r!8QDXKQ5F79u$;sEHdg) z+tNI)&2^h#wGEp{miF-rtFxYX+u}iK>OTb$by24JR8%X>UWv=o$^0_bqOFk$iHsaG zxX7xxc+9zf2T3XjS#A<6W+;R5)2Ti*aRS&!^EUVMUB7|*_lO4;X}g28&z^n*K73iB zyxOxgaK*2{BwFvGJDEP#k6+`tZKB+!j~i2OwQi?}oh!0@TXR`L@mTljdZC5}n7NC6 z@EB6M?ZBeB;XrCYtJiP0cBg*e=m!`;WrMF?t7dnUy&<+)$SwOau-Su-opw>ssL(3I z4%^fos+NT^l4WqZRU4eYF~7kSHM81XEcWi2tN>wMmFEhs$qLlejEpbyefQ4(ov9<) zc>3k+wO2+>0ZS^em$S9EeY-B(%Rah)+rKm0|6V6ed~lL3ocRy6`c7qow3230+At%QG6b{C7V?3#r!e2^#~2l)WJ zl~&YhIX~8({Hv$OxVAgqXZk9y8fOv+b0sIk3j3b&Zks1y4gxut1_${b1kvYSLN!CN z1;r=HhA|(dPh%y=o9+FVUS)3Pm$oCuT3GS?OFJo|Cl?xDgx+=^ueiSu>b=I8I$v{F zu`wZemJ(nt#FmOCYAv+B=<{7INEaWLxrbb0eZOC!%xYWPuHAs|1Uuqkeg#G_|j z$o9`XY#=wO&OIw0KxCh@h_pwx^^+W*wht%N(zwWA-fd!& zrG08FJfzT&n4M5iuT}+Fc7^={o9BL-Zb%CZzfoDP?gfOntgqw9haAbuqL(_Rgh%_9 zVBBf^wyi)+1er4#G`|9i8S0JsFHHp6{2A#KBuu9Nf@w?=bUN|$l%YScS-+T@l`$b_ z@jA@-_Yi0=YKbi>1~grFxZeaZq>UWJcXskg-6jdHf-GHfNNJuQEhLiV(e*r=ABAwQ{PT?0*OUfEIHXAQk{EXu{=wJOPm+OgMbdnE;M zVs)q{vp>f;BvL@_sTrE>yBkL2OqfjE~E+I$BMtc&Tb!bX8GZ^-xwBGZ%>%cp}l=HeNXql^-&Dv-MK&TyKHGqmU!^s#i~`9Bf$c zZ18I9I8`nh!~v{4ItKU~R4zeW0qs6NJsg~Ur>Q9LAL2z-&y%~%OMh)=O)9nq*x-?&s(Xvao7at$x(?peP z$6}lFnuLwTR2Qk-8rG_PSpVpIsnr5M)+R-qqS~kq@OyU?bRZF&9Y#jEiNOQhbL~Lf zMyUedUIW*3uZ9dz#2T>2I$Or;`oU|@#ZoLmwn~eL9jaoW?E2RvZa{IlkNMk=*nSNx zuw3|>OH}c2pwm@J(Kw6-;677llK`}w6~$BjA#ooV)5u1?^1Z}2j?le>L4FBa^BUCg zr=dQ3+(@t}ZF!nka}3er=JCmtCMV&fqks_1RIud}C|X02Rm9=n)OPspYc0xCULY7A z;$JC;-f;8ohjL;|gd1pQabfsPuGuvK-Yu(^l^S7HLmkH=>j-+p7-Cu84#{>}VT^A6 z>NlTrtCoTk%94M*mVh@nbYN)#eiePW|JItiYF#AAWKwQO`-~$nq8*kOz{7?Hx0Ghz z++!A%Wb#AQ_2VLTrWP*u4du{x4BxwjN5~RxQgF|fgN3CkP4GkCFb|MicwPf&xi+aw zIC4!p=7R^n);Kxo4A~5X>o^NbNIMi`|MH?4@MPTY20<0@E)YVfp!i+M{NKCcZS@P} zsyy+N>I1#nk@VQcd_+$Jdb!oq76vw47od{0=f9X^Q9*2&KtL|f;XgKUKiiZYG9}ua zRm?v^&W&fF$p;fClItz|=@E$4fWK!QDexN{)uD1e9VTyS%iiZ)BdXEHLDSBQqdMTz zG}%GwB%A5V;%Dr>-e4Q5up5Hnj)SY~7ki=){ds-K0?ofF84Ug#;1*OW{_P{{Aop*n zvo=xjU$azyb;mD37z9dtX~+hO;NIQO`#2;z$@Qr-Y9~9OjaOcmpNak=Idi8Hw%65R zB)Ssz5I?RrxF<7@gy1;atUbL^kcI*r)@fFT!bS@%{Xx`^l0sUk@3?4wl3&;slCt)H zcO_LOBniY_H5Ggwx&2UEIvv^79=(7txA6T8MI|F5k9r+9QRsa2Kpein=@qV6=0gj(+9t_xjJUB(Zf>{96okLU%uIi0UF0kA4gjmU>qj=5ev<#XY9-T~ux@v*J32+E`+$H;kzR%bD&h!aNn;(ao1@ z)_JxMrE(NC{ba}UirZTeV4Uvop7ZgK(U?4Dem)lOz`%N?)q#8{0)4o4=#r9l@GnFy zu>9+rd>ux)h+@#SjG~}+93A?!TV5ia6F2Tz9VG~ zb}4;xJPzUBL}kr=5Nz&c(V>SZ3kZ$IJL&e>e4p@z$Ib5RY|0Q6?(5fnQd%ZkO@X#! z3{K5@xRjU--Ymc>B&8fE1OM0`;(SO`({mO4YinDS6AgjI&(-0;4Az#n(8qjs<%n|i zuLIxJp)PXEyFXF&{VVG-y(ww)DaIk5m$gvBG$yt#MN$(ZPTdCFcN=PY89CHDIbCx; zN~D3_rvRMnQPeKnhukV3z_GSBmgv=6)nsYJ%nbtY(E)3WP-z}|2kM5}CzY=kirY~; zu7)k_ItY+f?bk!IpGXx@?#G$O-eu%-&g@d5T_a`7SOS3*F29HC3TcuPYssQvdX=%3 z+nW*{Pezkiin3DnmoI1Pcw7V8#UWCECJB--pO*!v@Hb>vGw`@k{jN8#rHL<~F)5&1 zn6zIWM6V1frb_6OxJNqz(fbH#XFN?clnYVHbOUWvHU8rqBtYU7qyGQxF+8oRb zAfe1EsF90+vcisRzvW_lfktV{PlNlC)5(3dY7qSG2UPUn!i!^a!BvPl@R*K%R09(K zo`vruMH(;hl)kT5+1Zk(R+)|)xhB!Sb@LX)0%z`_#1@X!5Fon(x_CtN4zJ^Dz-7l} z+4R>DIJ>iKJzm2i)a6gaDsL|*oN7~O2s>>m_ut={qwoSR&59(nbrO45`r4M9BkL0D z2mRWb=duy8eEPHRHJyy9<`=Zi4>ci*UOUi6h(5c9T7@cx6IcH|zigy^uF^s()aunj zVd5;oOcNfW&|ZgB#sczKw$*M)NBNNAQ5>RjUe$+uD)gJ-KaBLuW@qHQ8U}Is5Z`t# zW(%9euWLXQ_4@#0w8{yw4~rH6WTtuRr|0^~r0bURWT2rh+OcQhmf_AZSMQzmcP-6b zEHuQ)lW_pWqckW-W|SExQ!|7?WDZpdbKl~Nr|8oY(#$r&?&f=de}Y9~$+NYP-Cg2U z6dcLeDlB#?{4nR(_&X279V7%)Q?`c0@Q7i3iM4ULMK{<<4(b3!-}=Ew z#tl-c9|m443kC9LuO5x|=T0K&1QeZN{e2Kxa+NlpKgIepEZZFTOVZ9*8aa_ z6GpO|q2o&4p_|Z+aBPao)Vx!Z;JXqHe=FJG%f;GoUBlf6_T=1m%@3v?p0^cx?d;WBv1k>Vt8;t=bE`pSclO+&@BGnnZB!uMTdl6vJDMUrHM=+| zwh{zZ^slj(eP7G$m&JmxjJZQh(u&;R^BtoZ0>8X@IHoyayJ+We$fe^4& zz!gdg;VVKh1r(yQi1h#>AyMD1f$3H3?&EEi1K|b70&e>PS1|wmwm&;cALxS{!b}hw zuU8dRoQCrGDnUdGBdC~PcO$0Xqtc}V)&Y;E7d5w-Hq^9nqQ}$p77v%I|#rxMHl0t-2ss;uYBuw3i&?9UaJ((K)<-ZtvYKEvRba&q+jWz4c&AK<} zkiG7?86nT5fK9{`<5*C3ki9j(HB`GA2)J>64W~kcgaAfbeztU$8Qr@^69Mwwbx%#= z_Ru<1Epl$#Tl{s#HC4i(gt&rX#dA^PcX-SWrqX2s&u-c_AbInoM%epW00E(+6<9Qp zxPj)C_*A4e@F}Rj-_ia~gRys2w;DG3q#D)MX5J}fIKGd#cA*Z1`wUkZD)5+9Pk!^z z&QR;>(?-p6gB-Y99n0+%)fm^lv?nLp<30Wz*=RqY=ex;F0eGhk3Hl{S@0w(Wg-e;Wf(|+DRMzgarb7D&zC?TwNDJD1-_JYUzv!;^i3W)y*6mr!k2DD;17GE<~mhS zy`R!Fq~~XRbVx$p@Q5;aETN15*OWQer$Pb76?LMItwH?EpL#uS$SN=(_BQ|*%{yFJ z+!E(iC<=)JDwj5t19+ww$Mxj3*kINk)Wb69YYNmzYg_Hc>;53DYV=C zuBI{m?mcsNX`{hkVWNxg8$kMp%!Mefvr7Lh4`2))@?#jaN?7xMMw5Fp?o|-9 zTyYmFX1IqirgNpMvu%bL+@ z7x?f?!JOo*VlF1uhFcZ-Ylu(8@jz%E3)jjEO`Qee_FI4fBxQv(+7}<+tZqoQz0Ud8 z#W#6E;kjkx`2=RLPcX7Hd2OjoyRfv*DrilyqMKc{(xgeazmj`Cw;{r;YME~u1nbQP zOoi1hY@lx{RmfuqMyWvP*%J?8KI=jli;1{ozKG}~gh_koCZ0zm0pzj!4BqJ}b`eWB zu?S$PCqcSMN9}_-#OH5+px8BAYEZw>#0u0*5&*ht~Y(BFun>Xe=2 z;fl6A=p>o2>CI{TD19-0(N(&5Y7>Ze!#-yyB_55UwqXc%jWfn?N4IiJ6?T_uyT*5j z-y&Nz96-y0$oe2zvp$^)$~$W6+{JAlnE%{|g8Nrll|=rvD+Ral`ns~EqJg8yJN?(@ zlDn}4rK=Hy=ONJ!@E84PvyR*TF+7ry#ne;*HlBqQL3s<#;$&3*Ah{nC@7qxpYF(qa zMSy>*2zb-AAj)^yV3D`j8$J&DH2%7X--5ovrG8E-4WRrm2b^1NHX`s+khaZ26DAMS zzP3EqiVI*LK^v*d;YOFj$<9b{=gVb zqTfIXFu(K@t$rv1v>vnvov9We6>h?C;xClV$V0O|&|;JZ74klAb4N74^Lx!Xo)eCi z=F{5kY)ZGgBH59mA)<;*Bb`5={!JpNwJ=eBzNm`vUn!VHE7)8ga8Z#siE^7_oW$NF zE@tc2tXV@Vt+v`_yxTihJ1%l+6;S=ix?qwhb-D`koYX}LtW^qd;}7D5|znNtFz znPl!h86NZ%ji`P^SZ-zHLt8>4_Q04bcUw>S@hNImYxbN?3}VEY}EGr}HgjJW5aPRrt0<`fvMJ$d2l z8+&URRKF09UiiG7xO-%f(aV$!DbxE$p@)61Mm$2s6W@vE=E1{9)CiZy5DzZ(kT>ra zrm7k43d&^UwJ}@oTyoJiHwPToZBR{&NMfp+h!y%Fn66v-T@j#%BX}-dI_2rHJv4M~v zhMjb{TO$<6)unvak3ru_6)88e&Oe~}J3lMPxcjCTZBj5+0=# zfdE8t<(!#V68$uOt>K5lMv7FwRX`K8PL$^zp~)NE?aDUq$UQ;+j!M9*gY?-aJu-jl z-`Gf_rMSgDJKPIA?j*OK<%`OqaYc0y3`lZ=7E{?;%?QSkwX+g z3H4VTI2CBix2UR+Mc4cUvw7`aJUL+$PU?~P?UFuDxw(5I+Fa<@U{%@AEfcA*?ZevY={2dzget=;5Mxw(b?hkOwJr5;|Le&wk7{p9ea^|t<77_ zMgtz{5WfTK!etv0*4P%m@zJ&=I3BBmkxM5Bh_{L9ji$K9BX&F+c0s0TP(A<_5^p36 z5%Ri~-q({@R#>VGkskbx$O{vo9?An;8IUYh4yM7E*9;qlK9a6ZL%M%vdVMX6@1F}o z9OF%fDd+|u5j}z#K?UHpL&dfbpA1|3d7{mtit!PuX=4cc*WrQkGxG>V79lu#z0Z%) zgPXtJZ&+Z}OUO-smeK>gD!nF?IN%H5-`b$@A=JxP^?TurK0(f45FZWN8_&L#R>cRMSjg42qL= zmCbp*&ZF4^WQ428FUFTI>zxS}FhqUc`Z_xsiQ<0NNC?T73Bq7KH#G zc8{kU)*4>*5MpC8a-}zno;LH%2ele8g;byTntNtVS{VSO-T>B8meX}I+GaAUmN^}H zFw6VsuwX!koX9d{F8=mRGpcS^FA34*L2LPP@uEaAv$xEt$lQNGc%I)i_u3l-X0i}2 zFlM${)-Jn^tm|%5k^k-WBrM8GE2M~HXf%OWG=NGFOt&l!0Oaki;ABhweVi)%V)?A- zKMIfkP7-kII+H&|Gh#SilC04p#m|j*`G^o4Hu|TTbBj1z%T(<3&F93b|BWN9=|t$! zr4>)Y%UW9+fZL%{fktm@L*H}dK_m-jx6q>tq>9nc$N(W+@dnK8&cvwpc?YKsxTN8@{8%VFh;lH#_Rdsm&JIn0CbOHA`=Edh=v)DI54 zOn!GHCY4pTpIfQwS9?`Ej)?-a*u^{7Qv)YbZzhQmeJ0;kWM z_{HW!q@EwdLw0V9(51F0dNAaRy}?1TV89>{l9oD}?rvHomT6nY?AV3udjvkXms&TN zZ*2gC-RQeCRmL3&RXjzfPW>!*HV8~rWin&>Us+HH>~2HHXP0+@+9xf>_tGpl4Cn}} zKBmIBli|M)2HV3zb?*9c!556muID9d`^G0j?E`K0e`|Qvc|XwG@)`+?{qrd_cSSY4 zug+4XenMz9jH+OH8=9UiiYH(&zs;xon({8ZRgI*H--30>PgKs$uG#+UO}J24`ObLF z(sswL#cPg=&XHL{MJrAww{9;{; zNK4j^c&(?y^#*W*FuW|fXWn{Eqj=x!UR31_|2r&PPM~RVS&7nW8Gd${44OBbc6O4V zrUjCqEa0Wo+;ZU?cu@?rFQ*~xE1VYrn;kfMI#a2c350b5KmO&Q+vSyA#y{LxAfCV; zO-c#0IpMP<;|6ml>A(FZ$HD@@`fq&(M(Dq)=Y8PSEP|M+hX}9}A4R*XKLbk&KtGZU zFocDv(5waH0=z?ZB94$4rAFcutv{ou*Sl&Ec?wMWv8imwfS$rjl_d@a0}26_qQh*^6X_t5G~JGxi;j9NhKAc zpv!!D-G|tKGp(>9*-=Ni<{wXT>eGI48P>MyPB#p{T{;_vZtszOqQag6`^DR3-y!h> z>S%MlOu6Z@2KeP&FSBr4lfU@wT|K38M0iGPEbVPN_vXx$4OKwdY^wTRhVs}C zvqYLJF%WbP_EF|SrJe~qJ;yk)@ zfgbM*`vZnYG=i;&H8^NjyB@WEm_=J>g~5@0l{2&`3Xo;5ZQHhO+qSKDZQHhO+qP}n zHs;SnolMtSm7J)8y-%&yv!-$Y0Eg<=ss}F)lpJ8(M~pSQHpi?4$rlgw`M8w;26=`R zL|w^gYq*^=%(4dDisZpu(?@`g_!} z>+D$}Bz){Ia`1EM*q(_M(q-l6v)zTg=Qci!f=5WOm(7I-IC$shs!(euRgW?az*d+s z99g)P5UlLL`doxBARh=c-n2`;w)t(lqk=aQn4}hofo1$eZnn8a5PI4@T$IR>M03_#(#9TZ^2|+PmAg<+ zfXzX>)}uc!)B@s`-F9qK-lSIp`<1T9Qbv6rio!i-H1vC@z?G?Q8$HeVO;ySGk|!jw z4bqYOuzQsc2>5mA_}z-qdFA>+_;^BcQFh90h%qT!5tyW1-eo}0g5B)mRx?gJ_8Y(V z?S2O{y_K{l7UFei!^~Mt6gNDip`6b!VeyHoV9qUDXJ<_*(W{q#+#*TFDXUDYM?Rak zFlM{TZ?`C2Z>*;u^>89=ekNPvB{tKCrK4^-j{6jD$R~1z!#XAwXi6zj`T~*g)9#J- zD+rkguVhfw%g^}X_}#${!r)^8*f^irn)ZyM%Rb;8x+jj&__f9-f8= zN!vAf8^gv&q{?MWYLr$h8p^E5b%Mhz&dvZcnG7_9j-#eeCNML_m5Z7}to3WOarP^; z%wRvC77gA277*OLoCGo8ge&=DQ(zWtrC5|4)hMKBoyP<+Kfj?HOFE8nIwasN3GugJ zz-suMkSGwoh9fF__z${t2#L*CF1qeoWsV0>_GXCZEnS6Oba1+e;w}5}-<` z>~%l%18~GE`F-CuhlZg0U3czYcjw?@lkAv0g`jB09U)Qyb20i>rjtAPmpUqWlIsrP z4~%Pn9);3W>Z9mmk+nGiFGoF1dn>eRNwFr%_=2l@g7^58!OQ9fUurZcggV?7OjJu! zQ3e4#J${kah;HeEKsv!GFHZ0@%qdEaOCJ^bm^J7If=>|z0f5(26P+Euy~Q4K=m^J1 zKdj=oBhO6bD$4VmKVwVRtFQpk6^mp;T$Sd-Jv?lK)lw=2G9bM~p2`}c(#dD( zkL}Zg?;nlIpw%*3HvNIJOPSs*5=E%Gfc<L# zG-bAPed^R4TMedcCHAG=Z;%RJnbKYnhHI-;Bpg^vLuC67 z=F9FmUdeO;e}-U0j!400X<)o>V5^_gw){sCmIcmDVF}Fely_y=IoCoHRiypqV6ry@ zlXT43x^qOa*=qJ92zU1r+*Q6CurzADkhLb!o>Y#&xkNZu{t2L5GK<;Wf*bo?K)|yy zzb_PT>NWCqXTep+L-<{jZ5@G>RsA(7*qlTc@~blmei~?&d^d*a7$}*QO|XBy8h{b$ zW`5|UA@22%U=x`x^<2=lykFBA*Ccwl02EN$DoczD1H)IjLeuheOZ>cV!hX=M?}kLl z3iGLjI0CFbSH4M~PpD=ZhwiFoTzz`gp@nG%-Gu~*>ZMcv$nZ%(B^!Xavsf@Hr_KyB zR`ecH(+`mo(G-&=6W{R+j`-_-H^0J<5ev50o)yBgZcoBS5`sKkddA6s9u4B zE?wtho#D7LM{q4~c26fQXUY7gR5U@1p=#Ok?Pq~nExcC0yZsD$Y@Y3iMS2%mo>75d z&9KAMQL@g31!FC#5L85`F@KJZ$hCE02B>SutUSuWmzO{AQrK_AlU7ar#_V0j4*;jgDWW&x^qmR~6Rp0~tgF~uAhS{2Y#f%~S*()X z)S!d=4X3w;TPNs!YL;&!br2hT*bA(o&E|#PN;NHbvzZU4V9I8I->{CRvO)NiMNs!) zyPf#&JBtZUIEEhe@OrEpb_A0|`?k1N-j(h$@?G=w^Y*C5GFFw|YgN1fz zAEJO2KAZyVwVFtuqDILwC9hu~NC^4MSb@AY^Vh&js?9iD4G5SNi{4Ii8NTfmk)moI z=Mo3Uh2(iHvPV~H`x}``+*y@M?(TU)fe9k#qUw564b%*n`dIH#^m#19&sAR;{{4R5 z*IT*GlaYoS4mq6C_$QPdFzn}mS*1eWVr$>A9s6vgk47dEvqQ#(7#lz++=-?y0k=qC=zrxuhUr~z3jQ#Cq4U>VIr<>yq zQc<+3W=qh}t#P{t2%#V8Nm7SihwPD|^8gAN3$4lTZ0LYofKjt6a~@gpT?*7+PmdN1 zEwdfLpB3pAJ?8-e5WNK}JwHrt(uF(3HJDY;m~;TFyd9+PSuN$H32sel1I3}|3S40_ zYKTi|$Bp&b$~!$>#tkO_clc4ol_da_7jiF^D&)D1KF)@g1%DIgwc1)7kjy@~YU~ZQ znfn4YLHR{ox0qT=whp_`4HP)+Fe;kGXQ!{Lkwz1vja0bX5`QbKg0&vT8-#(%1fV}! zXyz?kCzx!2w9+>UVuVZ|p5s%&46<_k8zB<+N`OL2&8cYLCeE#TX0G=;V6+Yny|G=KK=)s@ zm0&@b`g={vcKg~rG~6D?nSPhJp8u*vu`=5ttc3AYp4p$X;8JvO03Zb}EAIFJd+ikFaVZ05nhCO6N!887D)_63q36iXh0HI* z!&eToAMUU@fN{xb_^MA^*Gg$t_b4)bFo$bX8iXNq>pgr`E&^O|^RKq4%QO#Gip2q(ses#eJD_>$Gdeo~mLx+BWheD1{aiI;r3MnR*DwS`!FAFJP(V#G3=vU1!-S;V6E0jDmP>=_M zfJN`U5I@q{q9`PH$X79KYX(4ed~JcmD)LV5M*a7`;vwtW@{}Yki5hcyU>ss{L{)6N z8w}e-@MG|ctIe&nW)`#!Yq8ob5X$ns@N*aTh2Gkmb%h#{ep+5 zlF!L3oPghq6)tH(s=+xEUp0&pa$|sg-TG#i!A;@iRUFYmG778x`yZDektJ~3?s{Yj;n(xYo1vPD^R4;V(nYMoh7%H zP;k)KBqz-KUYdG()&-7FsFwEB1m4xywdir2kO{j7prp8+gVJmPF&tH;tkbi{6VmE$ z_io%h^I7U6c1O+);j3AM2JQ?n(v)VV%mQQ;gUv3^N`_fb-ZiT_USIX5|1KGaiQcse zm4N;jKtnH#fQs2&uHHe{TjuL!`%(YH!;xdy^8PY!ck-+^(I8~-Z_OXm{&edJ4mQsW za`@WQR96E1JoHS~(>B}8(xY(ss=FV@$7^r5vZ0POOy8GgBZ=2qtoGC?d&mGUK+wOK z<#~gzeF#%HW7F{anI?LdDKcaiZ3ml(+<616r7uJ@D_px3mqqqfSW_jx|5J$5M+xQmUb;-)uW zMN8W9pRu#ea~y*-w5{zLW!)UBDB72M)q$TqV#SFo>D)hAd8;EsnOnosKRcEYnIWYL zyl^vt+#Vnar>+Z0&E0Ppul%PCdSIw{puo??(;KzWuNT(nDn-cj3<{1zY~^m2}hz}ZRH&G#;f zbDtOG^b>BSpYwpOy^h{P=fR3NcS*-SS&#|)T3()@4Vr(FeQ!_yx}uczUSmqf*m2uE zWB|%^f=!@+{$#_2(wC=KtRsGW2lfzI(eZzF34{{Q;eq*|u=+TKV~A1HZ5f$n96mu3 zPmnBAJ_+fQoN0<$0T5!Z$+F);;wmu}x~L;JSeorx`BSg?%bW$JG;Gmpny?K4PCCAw z(^ngMMAIfJw+-$fvbq+3%(C1&JVl(Oy4XQQ^`TM-j4q%QAKTJ8VLA@=CVPn9x)Fp4 zR2*E-N=}T50K!q+VDj9+#&NDRAY;H`Nv6I@Fn<1VT9F_eIRRH{Y3GKNta7rtUZV)n z2Us?*kxvZEw`|xmn-8_xkfZrlhrxnbj)SJnZEJUH)5hf2$pR8gNuvhkKwgi|lp#JO zy3j6{TxQzOK2${zRDe7h5She^;(HsK8)(byJTqY9=k$1g6x2eE*bg)mTD~LN^PG_2 z;og|GJhB_Mcy4*t_;c&Ai?4d9bsA@>-iiIrA0#|KP`bdyUg9p0WcG-FYki@FEev^%D7t){jSynIZC{jj?Vo37$5>}sHi?v$jz`c(@}(Q{wJcWF z1jK+ZI$p*Lh+134{3AXZbX+!3-3NqCvJH(b3erG$JpEc5W<*=D+nyO$>Nq82}<2G20+=4SfQo6U;wL!|MnFiNJHjT(X zeI_*TfvdQpy%rSD#qvb0rWU4Nks6353_X6?T8t;M=6*-aQeLW+QUiJf!Z<9^mZB8? zjH~jGs4|6QhD)qUy77xd=?`jQXE_J+P(42dhrCAlN4+mAdhjuV_0;<6_MG1OAn6)7Q`7 z$&yT@i`6lwzvQ080sUqSWKWGaq2zypim|q9zM~8P8e@3ad+VMK_a{@ee*7Na4;)q1 z`AfYxQIk1n{^4{>9`aXB+zo(?D9rlTwJB7g+`q&rY)>Ddd7R9-(qx=^Zj8}qFOWoT zVGISWlYG{ej|boXa59}<@>meL;Dk%41?tcoa%>8Pw_c7ah-!D%B7v8^vMi;eDhwTl zN#=3v7#pkBlYQa-P=~xeU%@R+)1N@t0D4xL#pfFjJN}TldZ^8vX{6RLiogI z-@kOPUSD(NeiaWz#lboo)|oHu&{M=0%O7L-jPz$zYM85@0w`_WznA3$CQK{i1*5&C z!|8xpPt`=&F|g}3zke)59T})KpSZF{Jll;jpNpI;81LqxZ35G0!Nl|E6%*8!jfhQ@sgByyal!CN5o;!Bedr5TiV<@)-`coa%Li zZvh7(jdl1l#^Nk&1~jfr9&Pha$*Rtc(xcm2Kf#l`MK%y-&<=!Zwc0%X)1l{&swTvUhc!WqFk)AbOqg`qYs8&rmvc>db ziufdZg6^&R-~-(SE6G0cnyKgmg9!Y)wiMC|KduOroLw zohe3h!J}XkPpvFMN}YHjpfU}C5$0mc`Z_$h5PA8n1=|*BEgwqD3Puqw_mT7HDWC2O zCe>Bjg(=pQRBxJqt-z)w>TeWfeYO(5Z)!M>(J}})aKlP{oA)PuRG-zlCIyiY8kR4= zkm+itO*P}kHn%?~0WKu}>K1_fNosKK-F2kV$=#=l{e*9=su>(kVcW<{GHS#^Rf(>t zhad$jC#^o5`-C66AyU(CneOKbk~7&nr<@%b zLkW?Hi;5vZq@SPAq8s^QbeK8hg|FHSu3|X$?T@-(``*(__9Wd?-IX9IZT#!AtyvxL z9W4N@ns2y$+GQ|`fE&BY1*<+zZN3$Z0mEC6$gz}SZY0~eR+hyLJ0W3=AdyK@A*@q} z-!^FV+gCTFvNQkQKmUmY>5F(%vO9f`^xL*foSc65u^9na;NIs13SkBSR%F_B%ncYg zMcH(}S*LwUj_L|t-mvL^oJ7$0nqC_~%Eqh{?ZiaMKZPIT0Cvi`pK~Wc;~85_@EaF8 zHY9{|Qd3teN56Psi(S!%vM2W*y{`m1k=fguMP?OTU0Omq99IbTb3r|IxD8^q?W401 z9v3V1)?z%xXWHQ}jR;m(VrNW0X>A8z_hIBm<`%I};U#;yQnp-YdsxIsXFXW^#h>wx z0r?=RVa?w{id0|J-biC)#WL0XOAi zMXA<1Rnl zh!&5Iga!LxLO$I1MKv3nYQTqeES*+L2>28Pz`OOl5R2S(xn(dT>eO*#q z5Fm$oaDHuTg%aQQKIR8JLTdt;-Gw=oZ@BD9tuE+qg%N(QLWPHs%<`A+<1uY*KUzHt zk0V0YuUS1tZ{36a;VFs0> zIQk?=#A_7dzi-CeBzA*a&h~zlMy3#a=1v)9+cCLl+nvi2kFzZJM%M1s*7UC6dbWJb z)&0=RcC9!VLDGMJumEh?g6NFW@gXsb#V-nD)yS#^X8QH<Ht8GdnGFuC-x^2I3tFWh;`~~X`On@{Py&r4GF&SMIyT;V)XONvYVG#j_ z73#k;$LVJrAn`cckI&DLD=C9KZE{&KfORPByjVpJww-OEb#i51v< zGwz^~e$+;&dKI(gkO4N$cWw3@jn{a~;{&T}dfk$a_BC7;FgGxHhmM3}F-+D!Y&Exh z95aWAj1O6X+QwYYylrzk8i zqOgG^ghS?=LUnqegC+Bm8AmQVw9%Zn@XnZl4`A6yqh^U7s)Pv0H{evlUtTX3tTQDz zchyI5NJcZVl{;v2&=wvdG5FjB@ky$~LCK(_M)hjoTek`a3(`ZjN^~S9IT%iIKaMJo z!`Yh(g;=XICUH2qvDv{c6K{gSokrQ&_;-kF3xTz=tm#SnyJ%Yw&V%Db@yYgW72Xv3 z<=%W%(9T!svt-tA3UPx~DN*P(Bo%@ytPv9@BBBzqXTksvo*j^+_tamm-XeO{(GcT} z?<`{s%{Xx}zbAbCOoX%q7YTFtNL3HU@CMoRdElEaWXv&(+-dO~B146@*G|QIJO|F1ZEjT$V0%5cq zQp~WK8dKf0Paf-uv9d?p+&Pj>RCk+gYu<+N`cr2AG5DAIs>@SPyp?+IOr0fG-{$_6 zA&SJI3-AiRKJ{Kunh8ij{1Ro$hyK}ytC!Rl5sG|61$vOZ}na)xph86{&h z4dYX;+6)!)(cX@|26MAZ_vXS;hdIokq-O}4C3{A3Uy-MIf1{?l}4t)71@D<$=Vt}r^;vd4x ze91sJuKqZ9Tdin+M=hxiz!4mV(mxA}Do=*xab>xeK4Hf3JRAIQ?dEW=+32KkA~Nm6!X_L_qvEv|XXKFIL1C$KvHDja${kPNNn!$o4Er>hR8&A;!+ZOvkz z+3F`q#amOkBI2~6zN8fF-p`Q=ntxLE-d_MM^TkKBqzwamk%G)P&W(ZoV66(BJsxv$ zfnM{jWNX7=^X>Bp|LSC+w&&$MEiLel$^F6XF}wsiJS=}KV8+YBr3c9m@3Ifyz8o+F zu)c#b9YMfihr*?k+(j>ZcD5yz_96uLaTlS6IlQUbPwZ9xC&CjEoI4)RT0D41g%aAB{~SU5G1RadG; z$Uzi309n2ReI@Ky@L($8Ow$9ouEsv>0OJx?vtxML>f@%yGZjZZ<&If4O$V)jKlbqq z50!~=6FQX{^2U|&%k#Au5>5iR{~*)X{Nxjr{}8fp?qS-0=adEtP~^aHY}hJuAL2ia zqUd=!*X9MB+u4x(+vzSsXYJ)P_}4v$lFv86ruM1jV%7S$5(->kV4J4 zp+HoqB!mki(-@wxi?ee)aiEH=3021l(moGx3vwWq!*W%N^z%s!%PjQOwqcfHiuxGn zSJg%EkphP)Mr`vswPN&Dz_%$2XL`6~<#~cK1=bZY!DAM?JOp13N;MrFppFV>62mCW z$vhBE?0TY=RV?OD5Iem%e$ zsN6Qed%fVjx)eJ+#ViUXkPOHay#JCcv1b=Xb4nIUw8eg#&}LcbJLtJ0r*4Rhq{F31 zrKaHuX)i8EyVc@vBfyAZBsDv7mP z6?%Qj3p|^;N0`kSXDK@LE69emKxs) z5VQbSbBvAZ@_K~+bhIXZKS^1-62Kt7Y<;VKm3XK*B!XMj-js~;elIGNc!=O1rB3%F zQ&SenS|RSIMsvLhEWK!?wIOUw9l7oKDEAFP14wMVtiv`$34TT$>F!XyBihEH*vi-r zk2zFh{!c{5hEOb_ph!dOwm68!5Fy-B$9BEuirhUWLC1S0NjBCO15G*e0MsNJg+aLs zf$XB7*gy(2?Uj+i$#!}D0?LPCTyitTyK9eKKzq>fEq9FhI_ zMrs1>cl=#ZjHb2%3XvzWv>yqm?Xf7UML`s*dJd-Wky$oa)`rh~abmOuDG`FE+l#K!xfj}q4j@zj+?FYfzmW?o3 z#{6^0Fc5vs5^Hfzt;aa=FWBwZbGK1yJYcTV@b1T&o5UJ3lqq)jwdkuf7+GEN`rtOs z`gqes11F{y?@|F!GVK)`$)42&Dk663sb+zPhc(&Qe3d2BWInOaVoR zvK3l4En1pXur~ge$P9gMpO0YNr6$vlMMnL8BSQuAL4q{i(jwCFfjM@D1-beV!qX5Nyce?^| ztOd+Ss_1-$Gk!=cVdznqqDc7F?Y}&Lmr7*WxQ%v2_V}CW7;%-y9UgY3cNDLQJaFG# zTT)c642gxx-0PuIgR;Y~OM!}Jqu1hI$djbwisj|c&u+x3-_y5ZNN-9 zN=cMqk+27niF`ZKAG zH}}C%cS^beVk~OfTHEXm_CA6Tsg7e8l-xNLVbo!kK zDhOUMHxpXQ*_ZKKEUBR?$T-?EVn|Ie2`+DvBI9J2z}f;!H>e~o9i;84DsJD+-~G>L zM!O8DcMyeBl!Aj-JNIUZPvhD=fsK*%t-G|1nOYPelBWUy&ZKtZl52Gd~h)Q0$&19~>mggDkE!NKOLU^^I62s&;yYa1U{Z^YQ%D=?0v}}zuj0DF8Od2ZA z5!syQ;SgL`T7A2(=qq9WS9TPm&zGiiW#4sXnKm`7fo+Vlm@8}017ST|d~GmYuwEy{ zi!9_v*`V4@xOsI03NpNh(Y?V(|4h=3Y6vrr-<(jA4WuG}7h{uQ4gpX#>>Y@k3``{h z9LbSSU}+Pw+`6CO@Y(!K%SZA`2tvf+@CG{C=C{DMggha4sCombc1)}^Bi^CXa4jui z_~wX7RcU0aUAC!~xJ-+H!t_SjS7|`V3tNyC0kH$_loK?!UT{+~49-FLK))s)BC^P* zH{Vt|SGb%_cyDqc@afTc2|XBoN}n(zJlG+miw@`=yJro#A(YaN5KbS|Nv^>YUTE}p z1W6az0hg3F4sjM=)^<$Y*Mds!0Nr`eJQieV9Cz4zvxdW&T0xEWV0vOQqREHZ-J`Rj z+m)e$OHQ1IR8Rv8HMFJmlg|Vx-MCAi*4flQ7ZCK>;XnfY6>Po8tviG3OE=Ybs`Fga zps{cVqErS6P{T9`a}^=HgNi8Vy{$)zCd5D;w)??{#M&rv3J-->wTRw%M_*J5Ybc$A(1>MlUfw4zP=^=E z*r|fk5}HV9_h6K&j;$s|<_O5N`3Q~Nf)Nqr8?8+NPEUO=hhWUaQqxt^y;W(G(0!yioCy z1ue*&`_8Ri4El54IYk-|m)={x;-~qoM2}ALVwjn9KN&eH$ zbVYkU0v4g(7Z=upp$c093Bu4m#mC<0g{a7YI}<$Z9rCclA)lX|$j10=yf)M6t2C5F znPHl^a%+=t#@P=OQ5aW&5CayvTQ`oVbLcv3o8sgiV+LTcK8hiT$4R4f>21Tnd9?_U z{1n}(m>(a3Tu59f*iQ8MV-1?tlyo7zfe*)A(W$d>#zENqT`;c@?1?zhOjTV})$fAM z#l%HOpn(V)Ob2>8hrQF2=#hjB+B^}}ih@*F0sxV?;j|e}Ks`>uVFCEYLdr~gLP-6e zKmro!i?+#U`C@kxwau_62zLETkhsyZ*%e)KCFbpYTClRz3SOj*@`50#A_J1cnuD?OINc32|AG1e!A){_}65z|lPPlss`q9)XEc>CB5!>~%8 z(1s3(&430Q4Duj>4h0X<3T(l4Q%W zFr7OK9T3Tc5=o}U13s5&%srEVE#9#S28cyuUTpeD4T!Z9a=6ny_yfka`p(@@(wZif zWJ^ED^f^G?cGj#PZfdOD9-JU@s?{N#Bf^z6PJ(m1ysN;nhZ}K(%mtT;jqC z_kp{CCJsGPc#rZp8jd8BczSIRmmOXwC=(g`UNVZ03f4%1Le97_lL3d`5=_>USaPGy zX`h>Jw`duHW5snVmxKgkWdTKU+LJS+o`f;Hgy*di>S~ep-6ktEJ56SuF)MgfOBPns zIkg`Rn-iP+iVe@ zUJk*ZYrHwhlq-_%X#}O@2e~X$(bq9HILyaWb#P85Wy|!gLh#y{+0PPo1UL8|0j_cT zB><*|0;!Rd3Ibn^JUR&Oi2BjV^|A4O99_=A2_;nV8+5$Jy05`R`QRr`Q6WeLCHX2b z`)#6=t#A!pR+zw8yDC;EvDDv6MHSI@pz!R`tNp4t<1F?Xku1#u7=+Q%Hq)Zzfp$PX4wQU7KY*+6KIV`^iOJp2wtC z$S1Y6p1%s+K-s2bPMdT6`UeYkVs8qi>_;kcxfgQb_4mzQ7hDqL5sFiyx(-}C*+&%p zg$Cn?zg08jpdDj2g{`YrPAKVQ zq(OQNFxEWjL7LFsfKX8e-R4qeWR%nrj6J@vnEicozqg2D!%8}RJFOlcu%aBR0*?4s|t+D z;3i5U1IHo16@&6T_b|^=LsFpNkv@OtA#vH}U`$8StyU*6H=YJq8;meNxtM{BJ={1X z^sN9ex#jR-(VJ#~8L(ZvI%U)_P|tbD3)h>U?XEX;GjEcPmS4@KvRU&eQBJVxF8hS9 zgYo~mU$(CpJIQd+of_GHI_}vI9yV?>?AAK)P227YYD6sn=e3_wfK9o#%)vUHTzy*Rk=OxH&0cGkFn%GjnyQS*&n8~O0Z0J=j~ z_-~lo2o)O`S~kfuXYo(#cY!3wqC;m69xij>JS<9O+76IlzO;QE+tP)l4}#g~{2&7O zKM=6+H+UCf%5NE!%CRBMTn9o-`|>zPJNkzNZ_z=T+zAv)@u0zjl;op8PmUf6)Mf81 zh-5zW(5y}e3ka=a6qtVurCP;UAY3{jlkxD=>T=S}K-`P3wBvVUnBIcKyKClXzq**B zD$Pd3da#5Uvi5XJ+l6l!J(SnYr!{I?j7|650FLGgfkL*)Hnnu;s*a33Px_9)lIf8abj>e%ed#D?>Y3-B40RUZju7I$Zyco=kds_XwtdoCb`Qf%zbI`;=4M^C!>eC; zEu|&ufvzS@em*+q9TYI2yYi4}JTa^n1F3lppLyOSqk%Fx$rbmf9@XN-rgdDR>By@i zUXhblWSMzHz*(6CgifW$+x=AG)mVAr_tqM#TazB*%%dIFf4Dxm*EF@uBiSD&-s1EI zIzacCbbD}u&`iYDQUf;5aB=q_VIbj4S;e0cH`u>ARdh;D5K3`?OixU02r?dR_?+7} zbn8F?@q8w%?yQUg_r@lHI||KT&mMK1iz8!v)-N@(p66ojK;E8quX9cPe*XQuK$H0f z`28VQ|NffmCGYk9Ww^|kkXrwUC;h!#oq==&K>>h(fB>N3fR+aMA4B}#x>?xUm$NFfj;-Iyqa~{uj_Wxtg!2&ctpqAoRXb(l~9TjN=oM2uiA57KBAgQQLk21aJ(D zL{u0Jms_xd#u zeJ7LNva1bVLe``rxpufBeDpfnQeN;q=|<`v7gC5BkAtITvW-Yn zt|^aQbk5#-XGKk7cGO-8T=JQ88aHd|LOmaHxIXJ{BNma!#RB z8*BO0;jK2Lt}{RoYA@awa)1c(HIA=Q+WFZ!3d()+bAoc5)`wgqLW`}fa;Zzcxx{(x zUwI3jRMnb)a^B8zfdF7B9m{GvDweg+mgIMV+n*2WPl;2MR^}6p?DdN^QQV$jByUNh z_vrdI(rQZ3(I}oi-Pxj|7a3XdDFX8tHeE!-=?}c-%#Zc;JoQ9P-sATP8_X-|PD?0P^pYEI z;eR3GJW#go#$?KBTR^r}gIY$c53-$u_0n>DK{-sI@jj(i_9BU&bjgL^Kif726(IEw zOk6C&uPA}z(7N>7f_Dl`;5uu z3RG+qH!49HjpfOhkC@3_F?MaDaB4cLMODetJ3)x`$npFsXP{|;d8XDl@8&Mb(T zS|k{vw&P!m3i~YvM!XC5=`NKfg>1E;dq4DSk!27BlR+p9Fa#qTB;eq7e=SuUAhzv!WgkSjDl%8q8}C7aU^Eh~|)W)JVt5)fzqbA#;x}o(JS|S~VhL z>WI}j+wWQFt7xvW3Gnhtr$E;H)GCg>UiVS}c*q>2?Udx48k|!r;5LtUY6`SUl?(7> z`LyTkT;$FG?x`|TU#b&D1EW+V8+wX)f%J*%2r^~^8$tF4abf^Ps(?aAi&H>&dwN@0 z^D3pdyxD>TwL{slJf9XAj+#7KmZ>|IC_#?rk^R`qki~h&$}F}ip_H_1R!_;17sUb% zkv-u{Q>N+ZWxlKYid+Pz&+1tlwNf^yb0~uk8=JB;=>z};;T6m1JqBW109VhK&|@5g zSm0dnCFpt3Z-0QdErYy@zR~QfT0Tg&zx3hVJ`vl;yxN;`hn|mKs(~fWoS~}83-H{^ z^+*hwY27e5W?;b zZBIy5G$E(qT?r$+r4!a3YMW-+PjOrPR#T-gOG76NdDD>TltRJjKO+yesarpQP!|u& ztr**35Jj=r+h)C9!{!p!TU=0$c4uF8{>+D*fz29+iP@oK2EBHMTJ?KTdd!?)-TDi8 z-(&Bnw#>J{@ZuhEz!v`OK;xlUwCzciYQwWtR%$K*mqyk=xKruX?Q0)7uLBVVbnzR9O^GW$Tf1v?g_w_TdUt1Qy zD}EYXk9peYxQ31%u_$$4<(wW#7N|q^{kcnJ;eUr<`FuhDUxOy35Tl;{GiVC-e=`X8 ze;OofZ(?dgFKuaO`rjY0H2#0~Gw=y{kj9(l6zcc&=3~`tO49V#0v!o%g(b zzf93oEMIQu(V(42h}<)!Pg~FOo-t=k_x;v2S^I4?c~pe{w&@@A3H1FYzD&fc`8;gZ z*~@=3zg+!&Zt17>yq}aWwtU~H2meA#DVVJNd`f4iigx^#NqeQ>UOW80Qa?jKL&FU5 z-|72#jGm|M`O>bre7hm=#2(Ruf2JAI34jC=++Td-w|#$YsQEnU??5cE!2bU3=>NU0 z9j0|#ZSDEqgzM&lj@jf5_}%_Ib+^pXZsfiQXZ}8wmi5s@ zjPCjBmeOW6{W% z|Giwk(rAW#%xUKGlmDedytnlQj_mzrnteRB_5D_ld}0=RihX?e|6Y~*iTysCA7dgE z{%!Ex={KK!;@>#^{Ps-odwRBX|NHTB zFvP+ZY^YK6LttLksx*8;SpH`@6IHHQ)Wcn@6<2 z`qT#ySFhRlp1bPvv#Kidn1B4kbbashulalPd1n^kX+l>;N8RB6_a5l8S+OUWWTFg?I6siF&8m~4@S|aqk|>!k-IKp#IVT8$0Ceu9K#rUyxkPuqO?4D6^+;MF z1%%MM+6~@xDWq_DM;eLNF-+(}cIQHZMuF~aDh_HtpzaKb; zkyb&?zCJ7f`k|ii)D^q$*b4dVcHX?$|*WqKa`io+$jeu7HvN zXcZ|g+lF`=1V2s|1dhJ=fcZjS*kry1Lt`|SrR`UU!ZjbG_IbP^kp)S2<*W1bec`@r zBYn$70SsbHQe^&_s*|zbYzF` zzKA73L@+P5u2}?|UCHt$?=TgWr4(yo5WpC50w^R3J)dNeS31iphWZ9)do2*Hr0lV= z7-LLT#wOzVl)sgOMd{ByE5|Rc$qe#TD+g70`0kL^uyKe-_V!_f?gcS;oCwFg!(>%H|LH84-tb;!(8g0F`0J`2n=$-=}*kycB^o)n8{pz`fUFOZP3{0kW z*W#MIF9{W{H9%Bc(qqO!MMzI#=UUq9%H9`A^X(HCs_0(>NV?mpY zCR=g&w5ds(hLpmxV8P`#mF@K9UK;WaubllV7N^(6uF}vqKGf{Ztx7mQ;juw7oSFu6S`O@1V4>MLs2x!{EM|X##|?gG`2(U$TuT0Zs=V zh09~qkreg-5@R!QKyGtMZJRq|ghIMdaWL1DPx|upOi){#($&DY0y*u%Ox3D5=2$91 zjU&{yY&I;44k%durACBf4|kr05wMT@+|Dx942NZZg|}9A1~~E9B+To2o5j`ug^(1$ z!&$Lj$GuT`7`6gZa^H+CB=d}yUju$=BES;QJOriyY(|tKIB_@XHP&?v9&z60>ZcR9N!xcPZIEA4F z`NIiz&TuR?G-)NX4VTwfibt#4NBNuHF;WBd5AhzQ86cJ+k1b%d;lw|V5=<5hMfYCW z#5h9u{YJVH2lCH5*vY9XVLCOvhxl*6cJK}ZhVa>PR4lTBCs{$U8kR8=H!EcnH=*?# zFhu%RgYQzy^KAGdLu3h}E2BzA3`A=IT_QS_Ec3S4=jg)}Kq=e4Z(f=mv|!-nJFbay z5hFk<8Kf~Q`M&R;ec}rDVG=$n-grhdkthJo`!q1H&iQk`@TjdV#<;&bBDZx+FK;X+ z`n8vzwXYahS|lvXV@&SYJ@{#E?OYn%^9ii%1!hWw=5VQ@x)Z6^cPIr7z}MFd29!WV zmB1hMH{8ElsswG3TNFcrz;Z+(xv!kD1ZvHJ;-OKf$%CX>V@FN}gFSp25KU~^9C!zl zAe$lk+7(S4gG$fLj04(gwAgMsJdq6CzOmJln;D^*7$0|YB;!;YbOur8TH`x6>EZ2g z^b8Cpc7Qb7AymXH0xFJim#IJe$HpQko!SMK&Ie5UV<3sI6YgfU#{qHx75~@umPcF~xwy zG(!Rq8pDF{dc+MbCmQ|W22kyD&@I8rFmjdkLPd2B;O}=##Rb?4hV(wE%zi{ebE8{9cYtdbf<;S* zk>s(tvTdJbjJRMxel~l)t;RX|%Zlo@n^j)22@j4iD53TEJ3y+Pf>bTNk&+F!gi_vQ z&$=9yHN&VF`EZt~Jg>8oA``HReJe4ubsXcf=}XcAKR z`yM=CT=;?oK2o(h+n4wvs_gJ8=%vA&nQsTidq2~x9AF>qWXkaqXp-*Ga?3!VR~D`R zoSWhCSgTkxdD69(191!iMO~XF-Q$NP%d5o~85y7WK~LBvqj6^-=1h+uKBiWDBfGm} z6q^Q+je4{YVl=g&*!Py>Hy8EXr;^JTA#zy<4Yq92kunatWWi0bT5*E+wcpJ7f|(rW z($V5hH`he(%-SUpjk-g&mz1%BXqw}3Gbc%|N$8QB6rpVMN3AT%;>i`11{Tc^2Tb=b zBAaz~?ul<}54g%^d}EVmVI@k(XO~+ad;drUoKZR@Q!!88CjU9FAlQEUXqIgS&>Q*BaHBoZvcikjOEH37?yVCiAs1GH# zA(#}^4pPi3Uh6sBBN_paF0mpoPIwu;D~k*_jmn6em2YZ-R)tRv7OYF2P%IGF+*IR@ zLS{MXlyt4STljk=#Qvy$vw@!!9*D${_G}_rzagnV) zK%^Rn>2lsua~XH58X>fH4ed- zBdQi`H`NyqMR?vi9(xbwqfx)@eY-dS;qGHXhya`;%^~4I$Wt2Wq$I<{RQAR$JGKYR zQ#>~vn4&A<+CGJ^Ybin8Ng09Oq%GU&?{1#$~!?L{htpYZI9{v0bkjVsDqwj;Pb@$NUmTJFmhTR#10K3itU4;X^0?cHgw-m&ErD9x z4AZ*$U>x$?KEQ@0gk@qknkR9x61vZP9w2sa0L(#S$WW|E)bk{OJz#YDu(I*CGY|BN zVprg(sAbhe_EqGB_~92-@Qy<0*9X|=)c)!gr96iEmNEeQww8J63RzEVZ>(V3S=|x` zAnNl9khk;+PTzz!tjJw+>_EJGF7Z_En)`}q`ksGu=K3`a*CEG6zs`yNZXYIfGg}Lb zcMQV7_UI-n1G@Q1Q!k-Idjuby5Q1z_RK1N}(6mz($QPH~VVUnx`WwcQxV$n6sh2JQ(agf*AItDK-jGG7&+X z)!U3Zcv~WaT@n=H^9>JK`v`X+LJ<)24zf*l#bcj=`BJgcWs%2UlJR=#tbRXvSgmzy zFumJ<_7q=fYlD|K1PRc5^b7mo5Nf^#u_eJ>>?q*%D>dXt(Z}Kgj zV*mh9v&=-Ae1hQDdH?-IY)@#Fq;9ossqH(~%Z zK+C@gC5Q7^^K3c9N47mUYO?p8Rx=hwJVU=e)-`!bcR3)FG_nu~Y~5c=_MrRQs>+i= zbIt8uk3X8vk#Gk_nntMR@{(>&`~YRU)gybB)~G;8R2GZ#`4$InmV?~;ngF+^g*`h)0Do=78>gx zvu~~@rS8oG+6%t8IXDxWTF{Wz-!Faz?=*fw;GsAMKCab6L0IVrzp?HlX0{#N))-ql z%VY=CM1}}R`iRXM$^;;#_oCymCzt2t`)(!qM^CN1#}tdaF@Ym7RAqg1(G4~s5nXx1qAZ}Q_YEh;urw_EhkoYKfYM_A?<3Pg$ zEU_ms$@B2y_C%orvV{m+ICQoSjU}=^@;t1H=kWMj@-@%xE=x2_s5A-^*|dyB4$_A= zZ#3xfz=L$g_UJI6>qC*mKng9!!8nNwKs@%qT&b?gPk+mLr+ou8D>6^BEh}-aO@76V z*Y9Sya^odJC@5@_cfoLjyzj`jiUHh&8us$90p7-JWbjSU6x`gSycRJ&eI=YF4C)K; z=1!gl{#0lL&_4tTsW8GHD5DYJfO)uOea{_C%Vn@SLPx^$+$@L!A5!ii`LxiXp?Q|V z<2awDRHsHhs+)Aw%159o%lO{fCVLB_5*)3th)^tq+7mnDvpJn2FI1h3L9dxwk9Zht z&EL5*l|*9?IxvqE+_l!i-V~L~VLv)@jR&|(zUYZP9y+4t(Vv(OQuF(znh$iP#1x&L zn?zqSUQu@+^waCXOvubOHEDuK&%*5DYcT;PVut{EH0fhe0gR3fm1^I)ZMjdVy!s>2 zIr~;vk%}q-H#c`l;ecVlLO+ulca__7kxFV}X$$B95FD`XxvRJ0HZ{>_+CVyWXed^Tt0Gn#$bdrWW?e zz*j;VRr4=;!Sjk z>Ut!Dy_jX6e0^oyj|bpo@Zob&o^gpH5dAaE$!x|K-{F(Nb}xwU`=Y>EDIt-GwJlCO zFkb23=#`Y?l!XwrycmhcZLj})8R6x(a(!3*!9BG&*R@NLw$u0C(+Vj_9yY|#n`i0z zh?w@1<=o>DR4d0+BTbjLJI{Sag7XBEWS>IZT>4p>xT`pG10)lI7uE?VOvX*%zcSFcKKL%)@7y7t)EW9a(SG*5V zF`4uVc9r+gEoE>53tL?2FBN@ER=(f&^1AastVYw)<8f=hMjj6bE>597&UT z<$)SevIWqrfx^cgarXj78M}0en15vU$JGv_QY zG*_wXc_>?xzLdqaAS1(D`!>u5|uNWuMUW49F<{9t702j_=`QEeE z%z8QkZwmNQh~<&S4&F0Bs7-(kX1=9yIi+<8l5j8OAo9u~=&I%T1J()w*SJ`0N93`+z3OgC7 z%)aXo9MGqsy(0qk1l-R>=C}7zL8KwhYmhCwe%;fnkoP2uBwOk4hNAO|q`@mX77i|@ zUG)T#Kb!%G;jC5?06Sg@KpAxA5Skd0;0^5$xgnhwIM>G24oO)`M4fLEPdqxe)9Z%8}A)M`5cx{gCGN=Pg07^=mVZ? zwSkwH2fmZ6xe-B^hEa~w(0{z3tKkF7J>@`ij(K{GwlqgjsPbh8jxE^ut8Mhf-90*? z=~z}DH$;6XC)vRQ$!KcMzg-;7qO_-op2&T@_n_EwWKEJOMBscO&B4(<;_NwUFqGD=>6KdFFQgR#d*OjDH?gw1^TiI@cX93r*`x- z?a|_EoKWHs*=}R0Sd>YMz1^?5u}-i@kI5v?R>9%Dw75(1q4!KwI7%?0t+6=vRkv`# zAWAY(1)*@QWm!);8cRo2IcLc0i@MZ8j~8I%IZDw_A7KTfijT)riKL7VKJj4#Vt6>`UR~en$nW|+b8y3t;}cX%JV=%`ixpUx=N%XH zoHqn@pC|bkS3ftfRM>;+I#Y`{)`uaJ=Jk0EAX*BQsH@#j;@L0;HllKr;$BES(D94K zRn&=D5Em2&7cd+;<(rHe>cu^BTCytLlY_gioiO_tp1k@bqR0#jQb#pz=IDAsraOq6 zfj)`%f)9d^(i_nO1ZMd5mZ5&U(s|!2HJ5_jf_42JA9bkSUHYowBJp}jfB~X>z5O&q z@#RQi%DClv%Q8AKS$$i`1A&bf<~!=X>6$Q^uMVhUYWylh3+OuYDCY)OE&x{#NEhZ_ zqw1#L-{tE?4M-B%HPmfz+KguU*$c-%&%mawY;UTp#9%_Ff#g7P%T36DST6j`*2A_K zB+J)w#Gwk~HJf8eFh8Ql!ZU%T#ac^Z8aP|$Ou}WXV|3=79rkc8D|L>q-2@YoS7>B( z$(iB%)!{}-AfiQg&>V6pQwrMQS-?R8z~q!*aAObzcl-!X>tMl*##_I)-o~0* zDJi>xN1mfx?%g@8-?j}K{@HEw%q%=lrww;asjR=*T6$Sjb+5yCbByy?SxwCYZV8xI zaEW}QIxhsO9BcG-OJuMW9;|}NSVM+y7Nd-WA~;DFElkL4aTrE5-1u&V zc{l!&#ds3*16v4hr9JOFhNMRi!&~JiNsLBZAG|6Tp#UO)6YUF~q0lB7M)6duVcF@L z)o3IWar?~-GE__2E{nZRMxeItw^QgIu zj#+W;I?%98$br!MEz_R5`I3PJ47io-@4x%wkJvL28b92#I~T8yyKZF3x1^Q$ z%*hZYusk=b_b#lJYZ7e~pf91)xIrl^aFkTTTJ;fbNikIA9*4nEysPyu>^OQ=Fh30@C5`l9g zd~)2!lW~lw4Y55=R`Bj9x0eqIj;;p8+jgGBOZ0hW^|{wSd)rJtHt!#MThK3{z2sV8 z%B&)0rFV_D8-2aaH%4F9TH0(bnV49SgkC$jAtg(?}i`ys!Uf-_%mqC(T_ zr8vjI%yU=ng`J-i|8Ubsd1`fMo$Kz?L=QkL(80P8;phy}$M1TG=AMe9953?jVFgh6 zs`9xuTh`>y_yO+SkH6Gl8$BJg53a+Kg?!)}aI9bw``%~;BSm{q&`a=dfCLL1&22c# z%SZ3_d%A143Ah*zQ{AJ;ns+U6+X_9Rw>qe1U+kqZ(_%ep-L$tBqlZd+9BLHlzNxp@ zNHpQO(jYlm^JkX1_u%F4_JwBZ<)e>;OAN?-L%J(p z&srawa{4t6Xd?tivdl1>(NX|NQmueg?PiASwgZv8Zm(q3{M``klAQ$yZu3i~aiZ-T62p!ZqFyWs8<{aZI=xOG0?e~o z*WMOzh$)K8itUGzP=%Hi3}yD6Aun5Z9p-bSZJu1wDRik)Mc;HYL}r{hMjqFraeBm< zbcbWCyzuCX*_p<%)6FQoN;AFS*XdD>v4n`70ngvuH&XP(l1HNj zhbW(?VQ>#pyUNthfoxmJ=xVF94X`9F3xnl61=b7h*Iwn_-D6N1zW)H&+>BWHNXH6Aknx$ zK5O6AzJbAJA5Rx9y|QwqtQV=}yIimsaQ{S76t%)nOv_0Mo{>ZlQdvJAM5bfT=yB zj3$&f5`R9|V`W!(F*9P#o4w_g?RMRk))9t6NbHi7dg$p-EBd%XLaF<~6T;X>(;Pv@ z*4H3({1NR?*#8DwTmJk`Z_WKmV=xe)-p+1nhJSvmj(T02AsUEBeX?E2)r%$s55P8M zwfYIoKr;+$e3pC#Cg8`9wQVYvq^^V_Sh>5#e@|3>qe#_gNzgR3X?#hyvNfNoB_7;Pid4lms^k$Iz~o3E8eZIgNhW)EJzx zUL13TKOkBWGW`YPDX4i2BtewEC`Wvxk6gYtx_@Sn5(_rPP}(g^LJ3$78Rpeb-wiB_ zHKQ`T1&xk>ocRdpAR;yyOmP{AJ|MME?~GGj^~~Pi<C~S>n=bTn$3_J>QI{e^ATyi`v$$*yDG6br_eW{ zsp(JZC^7#f2MbI`B8N~idZ9=5l6S`k8lzLH?h=W(VC)mIddCH;YFi1wU;-HA7Y8&u zz)XO29zU!GKq#Xl>yakv`KlM=GE@QK8dfM5ibw-@%Ui%6^)gh0iikm3h=$L}BMDRk z&Jecx#LZei;T^nODpYwi*vQk9jJQsYaXVktOQ_?R=efe0LUh5oxxAgj3SWa9HlhUZx$$>z+^QqP)03TcFdbA6Ra+Y7=IcsP$`bAZ&y-h0CqVYODl@x!%Y&2j z!<;9qUBJ#|xCrhQ=PrO)*ql@&$5X>gM(+E)7%)tcL`I3O!cpce!+IXZyJKV=6Nb`9 z_3mWX=xpsqj(XQvIbly4+fbD$bAmte_Z$N-LF};~wkvA*&4wA{LD!s(d+qyv;7S*R zf(qJc%^!GUBxbS(2ag|nbnNz&ix!AD5MHg^leK%%>~7`Or=2i)`G{w{dBk*{iAv3Lu3R%@A zzyQ4#kfW^>Z_a1y@5c`~z}X?5bP&1uNsJ7PZ;H%gqwz761wREK1tqk%l^o@IV3OHd zk+mTRwSxTWh z6BKG2<5qsg6CD!{1##XRb4U^J#Q%7c!d1K_oW601tcR0s>a9tQSCkn$p4OdCKJEj1uWUh3dYHjv ze0*sjH}j2!z}=+o2`I*X2Y!DZal^68_X$?wj_u0!;>-d5i))P^zz#K2Q&Z(`*Op&A zCRWC^LCp3n-@8Io6-lxvvsK>1een4dqmhQ+vQF~Gr2`$lh_%@! zW~XUJAcGMD;y2w}FulHm%KQRrFzh>td}T^T6@@$QJjw@ySPHIfroAH zXgFia?3?L_Ro>ueb))juS6y_c{B$>hk)Ha{Yp=1|v(m94-py*Z=~0+3t$l2p??3)} zW$x$|u+;B9x0iiBKj=H5rOX^^v-*5q%2u)+El`7b*iD}4B!t-NI%_-q#D6}*dvivjxk z0vMR_vl)H#)A8~HfWe0f!w3;kI6#2EbCYHtml#QRxiP$Te5Ov0^R#W(5;NS>>n!B$ z#||f3Ni6Z^=vQp!F`ggtiAZ4}f0PCtzj#BbMlS918~CsV2<=%Ph`es4WbKOrK{!E> zlA5+S5xvr9k%m(#Q$y$)1ev`6M2kALhZQgvi(r3+sEmOXcC1J3A!!$QWE;AWdX3e6sPmgpP`Qi+_p-|n%>SPuel%F7PvXcG%}Tmc{HI>e`8ObVW@6lTmA*NmXbkmR9CkHU)6Rp!EXG$rWNT-Bi|b}r=2D{uTAK(nAn&xnCADwfyvSN+L4mhtwt z;|5!tj)A$l@A2+y(dweef3~usk2(Y;RwNsqHYz~HDA6)UTA*cg@$@py*F5pAcLnX# zl|@m{(BJM>7T`$LS1r-`rDgmUHp)mNwA3OmunSpcGy(ft#TR^AnVxy>kiM-ay|Vd{ zaaP*^F5gsanRn%#Ki;ayP%#O#o~ukzu%r(!7{r{ z(q4sr=EC5WH&%~vF8gp^&iiaVXF(duQ*c)OOEAPQ&p_o^RUYb!NXeqTc#5Qz2CpkR zr>ia6xL7dK=BUyp=4)tv#eS$=#-%OZ5!4JkW@nkr{KbZ!1&_G(c3k>_3yZ9f^IY0WKqR1`d_ z7RUn-h9y2e=7;3KNytD#$3;tV)?FBLRgLR~D6wtBCvbn{NCbbbKq9f5S=!7;@`Lhx zdK42gZUOJ>O#Eq18nl{Xns7&$7^l4!G~NX-?9$#i^7V$J5MssO!bP`6^$5P7o?2bU zq_wlMTExuIDC>Y~jbDU>&7u_gBFv$-CDSSU-9f(id(C(rGEnd zQwJizjeuZ&td(einrSo2RduJ6ngmy-`n4q<^M;IN@!(@9Q=&@_1n%RcpydxehOt7D z+EDxbU?rWiP`xfXAW1)E{lOTyh|b{#9oqlC;+<}6D>-h$eSg3=KdT9doI?*nWbgJ$ z{yvTMW4#jbZWHVHNvae=+R#DCNgo|??zClhGip}uzz;t!yzXC6$_?5#M$8iEh4VFc z4X&Vej~eq$I>7!qGWrT$xW0-Y-rD&96!}zzxY2^=j-j3$N@oA1EwAo8tM{`2JI>=d z+baJ=M|2WRH(gwJc-52N9v%J$TL(xhCj-Lh)srC5X_zlvt*h<>b#eq*rJUiEwg3W6 z1oGNM)M+wzIy-_B3&T%BJu6i|ulp2c2UMou@+U@MStrmZt(D;pFj%TH9{>CjG2y-g zeq_uXaJwK0j_B=O(4!8;^$M>cOnnG9RkkIPDy2ua?_oq3!%uPei3(t#LFjd?mQd?J zC`FuxNiqBZ=hn3P*Y@am9_rgiExTFFU_G|1XB!|xr+je(C#)2Ph!H5`2pdiXtwrt* z@EO1RCb8Owq1vxI>13c_&3eMm25BDf=8N@iajGP*0R%?mopA5Hc{P4skU9R2Ie+*J zcc9$>6*-&lZdJVOZCQ>~{6K{_Z7vH**;s)7qmic@j#UYvJa*tM8ZBi! z63cPK)+ZjZXz|T+2sY5AL?M8v<~sKqT;1>`&9T&pS#QD zNjM;qwF3GkZ`!l}Q9J^6a{U|R{D%dT;;X|JEwKV+keZvm+y>IixaK;~+kd+Yfd>wgp@b*SwTK{~7`A6rLNp-=I2SgMcuHb zMjcAaM9E`M|I@&fa4bs;Q9pCI%#rATS|~I9&1$*PNR=^ewtqFEY5 zHCRfPEP4o6upzQIzqq{7-)Fh0`MaTYlDESF>Hw}eQ9HOubh>tY?d4bH!g`x}clhAA z|CXmBV^6HzS*{ll@YJ6Wh4!s8gvI;lzLL%W(KOd zeiEXpweG>{nVe}rPN1)#-P8D;K|8!>W46yGda#5iJM_^Mec?DXF^w?WV``8Ud%35p z;#N+@WYpI#T#yyPyZDX@9M!2-Xe6%Z5sjL2(-c(#1BOK6LIXr^<|3k=FhUc!ID3V% z%zgNM0tpxB2?S7gWF^Pu8~U~yHUBqB=dmRx5=7AtVu5$d!WAA04?Dc~p06KTv(=IM z(3uhO?!}~@vo5nCiKZYESgZJcMg$#l)aP+g=tkv7+rpSs;9AigPi1;g89qS=>%DST z#J()FK(rlAl$_1FS&~C%+jT+&Ja>b|vW0C`*uK}2N}=?lF&_Qz`_W;82E_{^*WoS(3iR$M%-nCl2u=YO|b;#jtCC} zRpLL{bhZg<+Zd>hc~d_RjUI38X73P4yZmj|UB#993$~e-TASq*S+)3xU>^#$eY2Xu zME8+BIse+m*7kck3q6PaMh|-`@^PDaPc7?9&L$<`c{1Xn$LH^esbiirmnLLnP|&fK za|ol1K(JZB!l#kCDuxIfyORF6AXf}bwf}V6`8gTN5bKJrsnI9Af+(w&55;!5^+r9T#%*LOI~G+orsto=w(ATW&)&hOt*gdxzw1n`>;(4`9WiO_|=cW zqY=R-j2zBg+J5liusALwe)!kC`XwyFjeu)Er{VfCf9awk-tXvex6YD29h8eO=*Mde z#uHMxdz|&jE>LFhMS1Y0&(h2lw;#-Q=fJkx-GL_h1Mp9!1>N6$u{y-AGdkD{VwsN2 z0l2YQ?*u+1?6A#{)ZP-{HbXQ9KMs0^mOs`P-+55Sw8_-UWOmxvO;n4a!nXwW=tD8e zSkE45vryqzd5kA0uI^ke#h(ePP#{?iEgfF-!3Fb8fp#r zDLbtIo~*(j+#!@%6dqt6m+gFh#}#W|)|H52BQy2g8`t4154&E4g29OBi$nKT^!>$x zbI%Dqji*&8{=Vx+OKo<*`OX%Ni)AG^o8HFp-=LFqey`MZb5AK_bPxi;Cu+}4^>d%VVjwd1cx^}x7Tg!k$5il>l5 z0>7CI!$0<8IpCHrDSiXLm!2Nz0`M`+_8w~vFzF{wW`sMq{cmmm%wwR=Y?+)u(20>Y zyYN_{CHI5fD++GN+QF19{+*`ghxJL*}%u5#OYZedbCN#e~e_1J3vAuaoB1obfor^b_I|es2gsjp2v%Cg&17Af7 zGXAZ}ajL&z|8^Q)i8x5|rz{c-C9eo`f}@zDyQ?Wi*6N~x7&Z=$mQun(BSrLhKSgc) zybGE|15yxveq;O~Qql)i>x86W%Vk&OF@9F0ev*$Jh_Y@rX5bTOJ8Xg#;25#_md4sh z&f8OfaJ^DiL(~08{>Kt;;ewEp|5)H;jc9z^1V<9uo!MJssg1w4$J+jI)igFlc6C?4 z655a)gY^?2{HFIW9ZLWadeuX}-+J5?D>)!hFn+-(p`-^BuGKy}A+2}EmvjUw!Oeq0 z{A;qCb0n>UJe^2g9M;IrBFv;e7Bl>c%gA^!=h#`i;h3*--(~8oOF(Xbhi0N zOo~ef(Wizwo_pZaYMZuAiRZ`d&X5zwN__(zSg|tM4OZII0zq#eL{U-O#3pdw06y&J ze6Q^YJP&u?CdHQKg7)srDWZF*gu?e2W8C%pW2KMTDFCOEkt&XS?@ zE6V_jjIVdqqM${+`CONy)s@}(?gb{bbK=PUyz)W;!ZW9-zg4bv@MjqL&9OCye+PnV zDX5J$?Wl}&jdtkfDQT6V37@#d{!u?JyfQ((@yM%DryP6|BObA$aO$d3Df1uz1A)t! z5*Exe6F8qFbQ>mTCl38Hhg&@4qf5crQZ~@qh=QDB_XJbroR{Alkr~Z%hs{xM>pb&! zOByg-?;URYskou^CLt>S?C-ve< zt*Th&M-S8#*-nFoEdr>QT(0uG+8=`ms zKH%JC+>FobJP{z{#<~5)o#jaO$(?Q)HC77RL$FpQ7YF!-G3Y^-_5B9rR^#|vHqlow z?H3TOnKg;2)Ie0S6xtSdOYINrunPGGH37tKuc;f-MGV0(r$mV|y@>EccY{7OOj;)F z<%iX4nMvP ztTu-7$Ae=!-95itGgo1stjCsZF^{Riun`Vxgd@F)r8<=u`f+tB+{6QCHfIR+Xz9uW z;ny z(Djlg-p#)ru%La%ThL^{yR?G}fTIaFE&?zez)=W5V~QEU1~zXAREjm5X1A#XS}6MJ z{CHdy{EcXN#yz!D%e3RkQ}=&IWoecjg-@`+d~h5`@j&@TK3UT~*vlJBuEoo86GW`|73vEbEs$EtOJbzE z(d_o%>f(q|>Gb)o5g{9Y2Uux#gtcyuIie6yjC`iV^!LWNe`90#h+Gv>O;81sH(jb# zfBWV60(0aZd3dv>Ay^;k=TG@2W|=4{>yo=x>JE;{qpo)V@HF(%qCd!%Ek+u)Wm3m4d%SR( z#f_jLUa1GFu!2T?1#e669T1O9C*~pwqTIQcF^ZIOy;4;95H!H2OxS-`DU+xoNU^L=@BI`77up3aCxM*~d`wqJH z_P(0|xYLWoA}8V+n15j2U#Pk3)NE&CLG1YFWLWW4v9x>j9|(<6=-1h~5wY^+!qIu^ z%}e!TG8DeliI%g_TJ4$lth^{|M;r0BG7!UXnD_Il58-4%{_#1}Nd()vkJwVdyh^|2 z08HrY%%#&8yB7m2D$q9eV>0tZiJa2AQtmO{&VrzN|0uK6*PgX?>C=jBAVNJvMR zLI;88Q-_{B;y%|JRPuE@{A)uQ*{vS$_qd=PhP?NNZcs}ps!T5HIlC`m)V-2gov$l= z`kB@XC}EXc86fW`?&oi|$i3MrpXNHU(_&2aAToneJ4ay4ysCipT{!M8N+=;-jZxlj zU@ty+2nQ93FT0dBWWVtxh26v)Y2;G_Y(F`8E3>?~YeQNv(#qHM4bN`F%LDFv4l>g#QWomYlWcXR1>TA z4oGGJv8(}quR*yh&gNDDL05Q`wzjx3S0ts(REgqK4OyCaXZIA1_0Lhapr4allH6@A z6o8cP*DY@a@!kf6d-s>i0l-i7Pal>N@0vzPF&(eBC*I-9aQr{fj;uJThEs{F=+l5l zbo69eW-OZ!^ThW#D?}x+dfs{WFc1z zFdB8;CoCBoaMt4iHJg?m#Q0>MTzRZ-)&#EaPzYVg7DG+xAD~BP9aBy51aHDzY;y$! zbavdsV?hUIZhf1b$^J~tx@^>Z^~x%Si~Z<7XIdyHx@IF2r#Mi~w9@>aq4$iC70=ZQ!&HCz07T8}a`(8Qg%+1INdP>d z@8P2=^ePZ~zn8)}zkj@j3idjBkaZk?hyERmf1HdcL}~~*C*s>vuBzYh*No1#khlO1 zwqDK6l>(k)+Lqh@J)F+&Jhy1BoFR`?HnH@=GA+pD_C%40xf=9{gK_WydesRQ5TAMK zJ$QNBqE-ivvi@$xA?|f2QiO+Gb3Q%pTB6(Q3O=8Y^kH6M7hH^o<(k#(7qrxvaFD0s z-%N{|*9+mn$J%Vf;egfU^MmAC>DJJ|4VF5N>|mb4>rS2xGu!6edcGHurjH-xGk{8X zwD6Wg{&2q7mg%&h7NHinB=Uj9mf?otMcC=#&5RSX?JTjuR$?iChEVA9I;w~~J)o*w z$*td)HkOD<$5sMEx%ib*~qhoOYvzS!`eH~pvhnSPPS1_jo*$VJWAe} z!F3^bdZ}XEIe8oG@WJ^$vR@7St#P5aF(^CX)A{lAyBz!{vWA@{Za>a2AnTEGC{m#D z6K8*VD>7fWOpcDw!wFr}W(YJVeG5++#c^VMf36ODjT==&p7u*6&2Xp_B=RT%+uRWW zd8uWbToVppsg-hAkm~NHxV&B%gZv{pSZ0Lbk}^-mB5S9)A6aTV(+2A<>H`xuFTbcE z%`*#Y#m`$iChcLm$m(XaG+CJ`-kIOrDsb8|mr}VQ@fj8GKij3`=a* zA>uf8ZZC4fg<$%=^$kz}P`z}}FVK;fj>QI)!}3m1(K-yUL1s-9=8;gTs%8pHW5o5Y z%8lS=y?uzETL(2k+Cmq2u`t#PWG>t;6VG@uML^TH{aCOayBFm_R@Jw8@ z@5_`M-RE^tTV6xR^JxN@=E-)UFn_y$>RT^bBRc~=d^??H*B)<>7fsuX9p-6Qii4X} z(4~Vl^{xRTsj*8@DNlzJ7cH^>dyBfw8J$g?_RKdvwE|)KJTCj#UgzDnBwSrFkBVfZ z9SCO=`BraNXqB=w!py;ICTQE*;s`9!k%EJZOc@#_Y(jA`6eq9~(*T{++ya~R1PSvx zr^*$Oc$o3SgqFnh?x92*#L6X=Wgwg)9ssQx$08;Q=725Q3nTeim8HmM#Bd&Om!)Pk z1Os$*&(EED7~(E>UubP|#QFz>L{|;qYTw(=eap(YfMR5WvGMnn*h&i!Hu})zp{ALR zPSIL(icpdkCdc4;&&#RwZ?Wz_R7GIv0iL0C`LC8epk1+oAL03~;Dj`9q=Lzf3~Le+ zSg!E0_#@xCpj)u^UHeOPiNzXG|IK~XYaO>jkT73Z$1xceU|!YAxM`d8yy^*C>1A49 z`v!ujF{yk{p1R=|gPdSSz@*RaZ~i2pGB65L`J!=A)dA(ST?0JPSR(YX6-?6?^d9Dp&3l~W4kD8T4{mIoi7}mznAEbK?>IVT zt;{{#Du3(Eeoijq^y85Uar47dTx4AvKJmqK4ahvmviFGoMftYwF&)75KY zpIk_v*8KZ~x3$vFwy2SygZVX{Ih%gxOuuQ@VenvD zuy+|$>_C;svAGIP#D=T2$JFB7ji!vXQxA^r+j#~1I~?CNC8(f+)u?$#chWo7L5LZ6 z3dk_etWn$AG*G%`G^`;Z1M0lm}Os2~@0^&{eGz@Q(#SZjwZ+z^6nCz{v1 zNU`DpuWHX?D7f#hj!w0&i8$w2_|@TvybOZn>p_-$I?eR=6rbbll<4K~Q%BA=F%!Pt zAQ~+~oPo%h=j9uD)Ek)feT#l*EI|dYULvFLB;M`t;Htw4V5_4#{??^ow=||j55ae< z?bw;v8i78-xY0l7_M^bZ5f;PYL0LA4H=(prje3`5AGxQA0`<@JF%6CT?q(5v%RTlk zRE3ti^D%nHSRLaOt|sDRrZG6L7Lv9CG@Q%Y{q29nC`-zUBn2mOms^aHpw9y&mi7xn zf-P2#;(0=Ra4{fietnR+yuhckzyhD*$8`Us=-SsNA`S<&ZSOKag0JF zUs4_JIg_ss!Ka*^v*t)#^or3JErP!nf5XG*O(Vj+Xg|Biq-Xx6`w3j9YX+PT_VL8y zrQh!L1~v(mgMKXzdEi6}CwI^s)MDUv>tnrj4|(mlCeuB0+_eJwCS%3CtkN_!R^6^M z^yKGczW(z5dn$GBwD?YTU*7y4IJ@Jxc&Bpo;HKE4&(HC}-N3O*`o!d)2D~H(?M>Xv|wE+87*G;Vd2#JSZ z=4BeNP7;NHL?5R|AZxsXZ04a{$;a=P#W=p{>0S<(5kfeukXmXB3>x2D{Hwst??dZ7 zk^bU~MxB)nME+5Jvl@Z>Adm9_;4y zJ3c-HHYv_mmN83)Mr+#pn5MlvQZ1ArFf@~}8`*_82j=x%73Sju{tI|C8^P`!O)U=S zj%?r{Eq+R!wic@&&(rjp>{Sn!LgKV|lvmue9t!~_Q`uelDC+aMpji4P_A2k+ z!QrjZ^OZz8p`J5RaiJsNYgm`BUULeR5hOF$8=9)hBD{2v4ujN>%4W*q3cn$W>~Npc z%EB>~z(tGv^IXqgo@)zv8}lYGiO}ulxcV4x&sMtw-t9@(jf7IPxGAl}j-OcNp}Fqi zJWz_(sFs#$K3j9obQo1A86oQLIaMjAu-Rn2a5I0FK`YpdopNx$nWd$s2y81iV8UkP zm#;0VMG}VaD@17MG#$mPeOoWw7s_=jD{MXP+1U{UE>En8(0(ld4^Gk>F~^I*lom1C zCImiH@PvGxSoS@j%luS-X=4rdw>Ye<$Z-a%Ui0dxB8cjzIWxzks>vhQPv<4#MUJ@=Sv-A za322sicA`xwNrlp4juNQ^&_Q)-CFsg$V_$=ENLzNsc|hQ3Sh#3|KFDr2P?hE^XNZ| zPY_KwluK{a-uKno5lF02S{4JBO7ESZ#(GJ6%-L?>a}HAU37=)@&c}v(54=9k(VX0Z zo~DH+DVy9`l_N$+iVN!IS207}U641v)2~CmDuZS!UO6j^5s>moc6Q|pLw?WKl;~gR zV}8nmn0!V7^npKJ#|-YxD4(?YRi=$aKWVoC4+B;yz!O<<2RluZN8Sr_0ecmdihN|+3@%zs=wIyY69MzLd8uAJT*1XSXuS4+R|wC+McR! zCN?Shq{Eb%-Sw_H6|r+Bp!7n1w6A(}bDHW8a(Z7rT;kR7edpdaZZnyD3m)3^vT2`{?|L|d30dZ`Wr^&lsevk_o4J# zM=rTf_lXmST(7;H$Ro@i!}(yPRl_E3atvJTND^dW5`yioB2^byi(AfRFfOMzf<`wog#>hQW!Iip#ECdBURvWOl-&>zk z*%R37Li;cm^Y$4T9De@09Fz;Ez3o;c^K#X5N~)i5MMaqF2_r}f9be1NgP)!rzqBmn zzstdrwJ2YpmnceVMQm8>yh*nDbbT!$#&aBYTr5iZLfst6C4@2Nh^u{WNYVnC&!#^# z&YNl1@HAxMVV{g1%U52T0+zAMJSe;6so!Jr)+7H)n#odPt;kmwW(eJ`G{0qch1(-ug7Y$w8>)yUod`cYSSk|*0O z(&d25*~!?ld6SJSsa~}^uGo6BZT6io5%0!Pa@heRM_f_pIs{0op5ulpgkNFgROAD= zLY~Bq&n#!(!7k_C7+(7vv{U~gN+z)2SD6?54_ zh(>!Dlda_MnJ8(9zWm12RATd&A27hGcThN2-;cUO2)~|N6D6}-sRYuXkvEw{FuaZk zr(^Z~GKc6!#p1vOX^J90p3XeOQc>-`y#0l)$nQv?7p+#e_$JKZT zc5Bp3nak3;_6V4C-~IFY_Zg+A)()x`Lwqx8mOPOe-h`HWhtAtMKZMu;$Hd9o<|Mai!pmE!rTW^h8F)K4;)Q~_9DB!(=jT96fRM{ThhCQ82>k{>+`dxH? zy1f>EBtxMpR1gyH&YL_7io|$q@Nbt^ z7@pU&#R;J)oMX&oulhn|Zq`>*5(A1ic$D8hl+Y$I$~1LyWBbpYV5G?Tq7! z2Hf1s6wo#xxvEpA`JzSmvO2Xg?J4|HQzIDyCIDr^=7!aE=#hCwANpMX00;lTy08JqF(6v0M3u`Ci};7-fgA62?NWnW}QxPu=36Ni>V^*Nqq>MRS+;Mv5~X zmu%=INKX%fJRx0y_H!eo3_uW}%5szeDg~C7?wiQ{smbl{wop($A6{cs^3#TsW6oi- zIajAE@QBZ*L8|>^5nb0SFm6t!Pl_!-o7rKfKUra9k-Y4TWIt&{)6rlUK@~1*3u(_d zfa3=Mc!VYiU(?8;x<c`cU z9w}xmQd^+v=Z!px&6o}tOBl*RA)KDPDAMN?-_DS)B;I0n`B4@P4VQkAf~W^Y#9QvoRjn0_i>C-wB5-&uZhX3qh~N_c2Z|D7t}5v^KM z_!_svu6Ih#D8r)V>%G@PKG(*iK#E8`2Y)>Z7i-!>C`H<4IT@(c&qZd5gq*)iHodJEx0!^@uR43bjWlPGG_A*R{~E*tqLr= zbQcWV_@P{dGDZmv90=Z|KRx$vdWQ{E9JxK^5jrXbSeO2Nv`o=_K;abQP7-;9BwIxI z(%XQ2O(d{QG91bNz*?w}7B@Zwfc?80!5TS!>f41HOezW!}5PzNru;Mh<~ ze!=FMxFW!Kh$cR}*x-4fBOn*UNk@6?g(NIBLJqy<%;?>BKhb;GPb2F9)9rE&(K{^l z<=%8}{F2u|(v_E2gQV*0cv6Q~penvXQj$3h$FM<$Jqv(14LGj)lv_udhV}P}W2c$c zvx<2db0X}&TmQU^j7V06g}BnW-8(hNo*O<7uDS3@b;8jVI+e^#^%g zzxzdB!Z9LTVhm6b)Yr*3KQ2tVfQl`aNY8pGk$iG+$o6iD?G5NY?=aW$cL7yh>Trg(DjZx`6(_SjSz&u8xej}Qp57o>>a`CKdV|{L3iD}WlCL0&R@>|0-e?{>!hWL=Xu2Dwba0hor+#BwCqR zk~l7@P@>3V`fcunds@*IFpjcFt&+Lp%^|yE$wal>@6-BzpXG0>mH4}bH?#HZ8k81V z?f@7bcv?0;Db>G72qDAF7lXblxf1>+N4O&m&LRWI_Fmam7{ihKR;ljCh0>@9XdWngTuj zJj}UYh69+Fd^~im5m$%>qDKopjNA`r-3(Y#(xDILfk(Z4T5`Br?(cq0^F~CzgZ|B@KYryI-X(78Rwq$UX3K?*_>V|`Y)Om&(sCwXL%^n zEQ!;xQfs&NZ$~xz*|fZ6_WR?2t_B^$p@zH(tYB9b=e>7LM-T>a_T2|W*glg|n#ZcbMqbjTl6 zl7dxKZx-PUi4y@{RkW^q#i-nWrq~k(UB0afF!X|ng(lNO1u;SZQxX&i)p8&;OE^SK zzWmB_?eNZ?NBfejn8NH-xpKQkX2%gmTL<;a{gkP!1)P?>k*gPYrP|o386QSc7yhl>hTC}f_C9M0z*O&`ZQRROd32tpq;A>Z56qtVQPz)IbZk2~ zĿ>3fkM5g_|eMY6_tjBme1d(JMW`Pqh}FWhXE7rH8Nw|L-yY7h*R)0fUgr^C6V zqUopwL!-2vzYZ!OTh{~e_KnZ@gfqNuD`)>i$58PZOdEP$?K%)K&2RiWN09&}Id%FL zD|zv`5cN|bX>Y_2MUWmODh-Yf(@nI^bv}Vda@q(P9)m;0o|ibdyKHo8VPmV~F&fZA z##;)bcYG_*=kL>K=t`M-rsrA2F~Lp7z0J(tgQX_rXJ;ZGoLpD&b@c*S6Guc>2;3Q< zr-gZsUL0HUp(|_Me4@4I%&|93-w%4y<@mK7F%gE` zy{6S>stu$95-EU^wxZKxj|seDsQC;ug?z^5esF#JzFo%;?I(NG;Rq4Hwk(LuHxh4D*?HgYyKp-)La-Q_}4MsF*KkR3(@R~1= zsq>(tAuyQfw3ijgbvj@i>O>O}kZOQoKp8T7yjpC5Z1_Bbc z?+RFr*ZWp@^~-N8hbVzLPtJC+t{Y#yxqMLD1fQ>r5_>d{EO{J!zzxF-?|2FDzd4t{-MrgR8#nqV_Z zAV@!mT9?O;C*=ifnC~RQEM^4XN*AulRPHUm=!d$34ltTQ}i3^!QaJr8l&yt=6XQ&4f@8&1)f z!!v?qjiO0|I3tX$_x=&9Vhk?@9Sw1=qo`AgyK?O?!0K;qydALEz$ z!SN(OEvhzzUT{C#$4@RwcAK6_fY~TMT%zZShRAjlery$sn*cNFRnBsJsG$(2VWMI> z@XL8~XbjSEl8iyf^-gfl`ZlhrU}AYg3~4v{alfpSR%bvxXN6GFn?B+<_!SbxcLL&( z5YTj(a2cl!gY}IABg_0K()&0Zh}ba22TmAUC#Jny@~WRfznj=oI{t|S)QLYQn)gCE zaS_2adp&{h6)C1TZCtUVGd13TRk^^Me;?e)W`7IV`7Q|JSv%K-zy5((7X{|b(bHoM zRX?qS;=eNop(*B^K2U%Cp~r`DLMg3L*^_ISb|B*lpq>wTaT;3N%Mt>y%W9(DHn^-V z!;d#|**tCEr0@;Po06q}=aYu~!W`<$Npy<=lhitzHbHIRO!Rhb4GE#maRUtJ{rH1C z87HSjHFYVxFu^Qu+C#439s>)cHZ=sm_YWp|R*$kh)bVexE0{;Y5`Pf#c z*$!q@K4lAyMq9Z-`4#jFwL@G@oW3m0=<_MJHrnSCSa3eQimeO*VDu9x=ZF5q#}|A| znbXc>k1H*2P`nKV^OVXnDhxIud7Bbs@?fES7`q0x81`}Z^NuWRTHJ25$xJZZW5v~&TRa39ishG@`BMPe2JGCfGWoiA z>v?_$K(a3?^IWMx2~b4D{Q2m`GCKIqED)Rp!3P5wfojf15S?^NTSUQx`uBG5w-ocM zeQP}V`fmagNvvfljLXgUolPsct!p{GMAZG1?LU&vTia133ZfrGfOnw);k_3b-h0p2 zKkmG2f?2w#`<$v>s7+3F=>btP?v@uW4|5xGdQpFlPuT$dv43Pmd#M1SI$4?v~;tnq2dcn)chm9+X#>cD%K~} zJQK70Mf%6o&b(kElP?N4#7b5C5dDJr!ejTkx?2dq#c!CH-u|AO@GM2@0P2!8Ce&K2 z0{R9g{z(Qao_tf#wG2~aGpWzlc|qd3gEWJ`Fg(sHk3xAQ=Hc7y3%?wwE*&L7@_O?7 z;BvpZ@+`ghjD8H^o8HeE&5~OFok@XQrULsC^2m7{S_{s~_$;8(5N-2>=OC5s@ZP;1 zOt#u{lr7L3DQD|$*tO=K!0-briH1i(!;bPHw9&tHn%ygSeY-AIq{9gNQmTO!=5l|h z{8jGclFN7YX%Or7M0`etdY=shm-;OijEE2Ij(N?1CEj4L&o1V#+F=W%JAOf_AcYyp zk7HcO5aI52n|+5Efg&+@zXnY&1c*3)Jttzy(d5xwKi@6GkUXQg@|~ohhKa$mj#ku; z)|~@&N=l%W1NhM2hlm8|?G37cUsh>R$UlOY``~uVJxQ#(fE7(z8^;zk`@f&B2$bw47{Rwd1%fcuqXASMDvUywgeW{{pYsOl*Lcu8IH z^$6^8;EZk+$;b|IiLu~~Q}bycNxg(NN9Bw_zjfqQ#5GQ@RY;6MeFZ{2#-ff|V-#MC zb3kFsQ|`(sOl>sa8-}7~d7BQB#(C?!1|BtfJ_eU7V%QG$7#mdJry zVoue|;szaqLhKuWCSDOw9tutr7ikRFm8QYT$p%M8hffA(aXRXN@o?J^Mu2k8OZXXw z_k&Usk6R>jFlDEJ%u`8|IEji~6W-s=5Y~_ia}qk0oZ9Q=kmCjoFkAjE`hp!`>Ecm} zniDTPJ?i^#MUsL3Ny(311654(H?dw#efm@SMeDc`ck|}?1Uho*&PXl6CwKOaDCx(f zag3s_Q}mbZ;M09E5(!3f)tWZjeXY+hg3752_UO(NYH4kzeL9_0Dt3wi5j2jsjGG>! zYYy1@I?avPF3o+5`@)-7zZmQ9kfz5!;c6A1yFE@FxbhQ%M3KuaC2FcL1MAf*o)q+U zK_eN321M2t(VC&U3z0s*pw1b5!SVE)1z@>nD-D1k^nIcA?|Na9d?|5kpv&N$eD zo+blRt*2|4zt&_2v3&L{=j(HibH43`?0(QTQ!t(KCq_K4_4RL}=>9CYG8Qp;$&*}y z&u(a24073TrLBr&Ruhc)_Y@3I7CL82BBn8Xi#LqIfF$KjzaJr3It@GJsrmI`D)m5p z1ycqA3JnA3&neDlZf53w%m5<_YxYqAd|1gPIH_p{`YcA5``7PEihGx2HbVgB4mR+o z>lm#V`FI{@zZ5iLo>j(;lNJlp5Q^ZT*rkaZ9+A-jN{VE3+CWStn^ zT(!<&@h(L~aWFc^A(9(^2LEno;V_n%cb{5Fz|Z0V=~bZn(RR_H>EhlrC}_Tg@xyx# zW{TR}O;YAT$~veA9H#kanMV${f0s%Z6*?=XjjolMTR{@_@B?1z=erMu(YoD}C_Vk5 zxY}FH9uw0M-vH*fC*^u4gfe+{_iC)0UcHhzmn;0n)?l()E33xVt374?Kw7_k96Q6Y zmW@XZJGJkD7Ii+*=)0-|6Im@BDjoThv~OPGq6zXMj0n#uY~B7iEYnCy(N^)#Vq@%) z+%c95{R+3!r-(d&TmwSIe>)EOp9RSW*Nbajc z?3|m9J>}ni_~M`+QyASNSiw;lxujM#XlYvQ9_U@B$>^+sTq=abtGFy>+-tEuh^F!ZeT4_| zdJ-m1-A5lF)Q*(bqhbBdxtbuiweM|RgYxvT^nG}GBg&voHCOh2_6MR|jZdUAIx!Nz z8I<>dG4GB$5;yHN3OP`7A2*bYdKenvv1TsoVQ314lGO?9Z+Uk@+;u3U z5w)Dc(EI5F){c#^-uf>sILMTruP4LA$HU2f$n49*5rsHDkBt+nX;U+#7B&mG1|;5} zuL-eng-&@pcFY*tpbUY^Z)<6dK>V<`e}I-bJ{hv%dIJI!QazTKjyvLKx4h77K(LX^ zE0<32qEKI`<8?sOzhQ$5ua5-d8z!>Yo5KRWJZHqJJu+L!J@um;2ZNrz5B7t=`7{6yZKs$Ag7D@_{-XlathfvS1(;TP0{RU3B zm5y;IG-Sllln9QRT7`&zQIOT(9K>bqrbc{#)Z*lO``Uc;^j|~}}?uho7H`;0t==_liaC!_V9`QB+V4!g5w^Jj1z+2r3K?Pg!)5mFBcLINqYY?2jZs zj>F-}zuLlZDmoQ!faaG`IGP{eEI?6vP4Y@IFXUlc=O3Wy-TP)Isz_}pOZ#5crUDnm z?h!gF_T#^E$zHgrGPU_u{zL^!F-Qd7-Q)-(uM$pCoRY(@Ne^3L5aEkk-6uJsH}|nM zPP5nd(9a>XGQq`*N%F9h^-&IWRk##UISuh>fG%ygfGubSStRlvSgefCj5PmabS+eF z?-JI(ceg9c5zW6XMFaYfNA>~?=)Wb|t)-87U$cI{XbPao#8K1KU%cXiK%rP8&ina% zogbWyFl95TX!HS(`!>R`+ebwpvppzLXs5npdeWbbWGhLIn;7$)tp4!C zp%b|(lNWAx$j;ky$iB|M-*WQOup!62y8O$(-Ko{*5=^AL`@J-`SRc{?XdEfw>H5)-V~NIsego z@BxWV71L!#QB=ulz(oO&@kuq}te1?R*A8wST)bxn-Z`JC$5zL^Jnh^h%@<1bFBc~= zx;Q!U{%t_>!2P2$%U9!ao{vzEx9!sDC0+b+oDF~@rrKmeshv;IWs)F2wX*DY{0~KUpHxYDYx#6hn%b>I?`QHI9e8ce!_G3pJH=3Jg{ZsYlHCq8de#@L z>cUtw1dvUU{OR7M*J0iq(I+jjeWnm*z(i4;j5;?EEo?l$Zo0Me$u>Bo3N%~=IzznJ zf8Q(;TzC$3G00gp zPhPm?6SFgkNQmw{r4mTCH1ZDakPrYN@Ytp6Uvnn9Ic0Y@*4%H4h^`RtZ#e$>qu&`> zJ-T2xhK9&uk|e){oGsQ?3$qk(gBKe!Z9Fd@(-8D&bJ4qPI$Jr{xXU_5`5|e8# zvnFd%aNG*@YDOK3^_|mqTzhd@_tadS&~tf_t7UVMfC+s6yfi(8v?va9WUiY!0??Wl z8VMHHxH5SfKMO_&(jwJz)aZ-yKUU;MTl5&n>5DxBe+WlUjFqX9eK&PnvhAS~l7pKR*yPy)%Ztku=gQ7NS6C^X3m~x2&WI(K|ik5F_U_ zuXg@aIiuIwg7(q{D7?T&cIQPA-$h2^G=t5UdQo1=Xr%tzyE4^5X{)x-xV%xWCsT=1 zDLP25uYWQoNV6wc6@S8$yulXE2tc249S}cK0g_9S4{iUOVOZFoPC5nmiNo*T+rnTl zfE?p*V=vLZW0?C11L$`IyqTr|lP$7qd4VHuGf=uump^H$2~AUfoOxw1k8Fiw?QSgi zs&^OXX_egVRky;O&2qEasV*eyIw$vLqhl(5HQX=55Xo&#^&rBOKk@|dTxLjPKf=)^ zq}|ZqaC%^nlA)b{#wJi{o8x9-mi+K=@6kov*hh6=cKr^=wX~y|LD}Ia`7L}}6oP1H z=4bR-FjY#QrJ_nZx85|ZUa$KM95O0J&f^Ghs_5u?X~joVbf|_y{L1S^Muc^>sC4pd zH9E;Ghq;10dwpjnXdcw*cO=v)<#v_V1Z({(=>Uv&;K1JPJt?~UvUG`0%~0l_ADWH2 zS<_4oa|7IRF6t8b-!22)?E4T5ugpX(G{OZluB!ZEmV4%Y_N*?srXP7d^{CVd)&4`z zI>`XR$mZXH8aAG~a!M0n*l9lWv~`qVx32r+eBmA;^oBs556Z)-tx6Wg^Fm_DaBij_ z>%nz!L^d7S-CmG9(e&B0&dAJEz@>*C^79V%uwc_`Q9m)iv^;&s6Ar`Ku>oSNGiIk6 z?*?*O{WW_dg2G(D#8a0t(wjhwvOgZzTlbK` zj89l1Pje(Cj$(57@4Yp%s?aMzNic6uq3vLt)~+xxI`5yVDQ!_fW;Pc$D&M~C@ZfeO z_UI1d1Gdo~PCgf2AB9L2-5coh7$_!+fr1A;@pcc-hv33mFq==7K1-;B~K z?YE2E0z;^HU`mnGzT)akQ1?*$IP93(V?s7uEGU0-ko6D#3@T!%_x&MJt-1=JIC9G9 z2y28XjH(@^M(RQlC}y!>)R`>um@8yca^|)7!eK7z=*SuKL@4i}k#B zQR1q`UTUrYlA+xaD<^I48K30S=3L7GQ(lPvMP}2F_5vA9eg}f?IQHwV@d~ zM`L!f1xWC3`3zBNxyAIk3gn&wrWFy{;2#wKa$lU*tt&-y5eD*1d@2Xkl~Cb6*QleL zrwG$g`i%Pg+?}gsVcM@mrK#Ryx-d_2b0$08)T zc)ZmM+!5FN?)(K0TG53p3l6D{Y{R8A{m?TEj=vkq4F2f)jFjeT_UIHXWV6n}F>tLF zp2m=elH#Lb;TMIE4aB_RI27Qjv_(f6uKl8r1ad`OgZFb5{}-6=;ij z*7Eh{ocxMEle3nV>(C>Jofo)z{uw*|Ms6W7-_-TTd)(lBKn4${WBel9APt@!FYhZ9T`sLM=~5}!%|z8`UKO4{e)Cpu%EI2;fSs`gpQqwx9Li-l{O9rH1~s@DoZ+e8;7w}?&f z-^l+43~T%{QLzP*Bl{ZHGtfgJb~=N-5qS6#;3|0kJtRT5Fd4MS6#pcs zL_osa9_-raEfVzdw0=>Xt0-6kdxkVOJzH8Sz!;n*aKBkzpL2_C?HYg?NZ^`=n{EOD z(@@m~W(m==U8ycz_{zVdIP`p2GAxm88Q5DG5oPZ?j1e=!2QOXRSsXh7nDNOkgav>z zLGphMV@fduIR(S^a|bx#Rd~Cb52HE%Qn~!u1_Xp7;*#LgK4z4LPr``OVAhe}_u|}* ze|uz?ww0%@939P`kds%5g^_NGN&h(JOe75#js802Ci9^c`QzP86EL)q?ew8R#_ z8l%9u;UMFwS_k7#%UZQ|2kTU!@uayHpbI@`l~3W)Zj{0BZnPF~kH*y6EL!qI5BHzJ zLg`Ernmc=d9|8p{G{Kg9z)FF0?vI+CB`1P@i&@NCGL0;v>@%4z5qq@G)>|Z`aN_^m zYwK~hg~Mv}adhVfTorL_`amFELrWr2U}0KLRzoLzV#1rM(V}Ky%MWl-gX@7wcPVgR z-{$f+c8XMOg4}6)ve;Q3H&WH6wD9z;-~+N(q7eDiSg3lP+MM>lAgW!qN~lCu3IL%o z-Q*~tiwAflrb+(+vW&a$hs&sl95A&K7=%j|FM)n^S>$=-6%5I&LE(0;Cv_uFvy}hc zcQB_-qG@C*qo6x3ZWg&w#h{!_Dv8Khf1Xz{W*`Cr!}<`T#r{Tdyh%LOOvI3ID^4Z* z><=F5NK;ghStSH+E0{j~Rvw1<{!&X-8%wRPn5|~gHs-UhoBAlXrIgAN*k7ZUG)$rg=A>>2mSl6Z*%!84x{>oE-idz&c_JR6n#+rCNrZYq0A;` z2NQk(_#t}zjJCY~PE;Chv2YCW&Lt>k@avHeK0)D)pIIcF-m*{7%SBtO(SG9woP=QQ zcRWo>7R1KBWi3a5;wi30Hkk6=s9^xqnes_-ghMddh4fE}2mD9%d7b%A>mCg?Uo&10r4a91 z@&*~aG@KJN-G!*zva05JGbQD@4c&1c+%O%n%Cz9KI7ek;PNqy+h_H@ZF9-vC#fSD6 zVNpACnHMsv$7{ElpJzT;N(+Nr};p5oK487`JBHaKR!6! zm$s>fN<$Eg=viu;3)4?o@GT#13V35tmLm^g&o0yNxr>05_^a2`%js@QxLBN}>#*GW zo3`46ell#-VB(y8+)`YI1@Po~i}szYr)QUEiDIkvFyvmWuU#r=H`^G)s<})-2CLWf zNewa~7bBO&(y!sG7GcLvPg3M2FriTS3|wjLWNi{GgBq2lu;S%vO9YI95=q0ime5o1 zkCxfhH4+`qj{KjbQAZ*Cg;({woC0r5M+fQbn~itO-TP2JYzO(XKLjUl+ccz6HA zp!)zQ{v7D(H5NDxsQT#Ji$NE{f+!^*k|iY1a`a(ms}r+`aPu5-AB;8H=j=?&+AACF zp4I{Pt-s4dwXtQ+ugW8~a*rlyO@`FNcx0)m>_)@vlq{swnfdFYQ|wPdaIFB5#9J-5 zFu~Y_h>oCMZW#K3qhK5cRYz`feL|M@4cdPaSVz|3e%bT_1D-TVU5W9UhwHwZmt@~5 zZfp?yq-QPjcS!%?N|4+z4){wo5{8zX%bG1c0{yNO|AzLc>f!3_0|9XXD`ycqJ5 z&jtUe0HZvzA`2S%Ue(&D*9?j@^jLFk&Bq3qjv-*l={mOLCDR6oBJddXtVT`~1{O!zQA z*kNb8_|Zs6B5SaXEpcddAN}6kMjbqa`cjfAWVT)@)zgxN;DPixuHdi) zcD<2MO+`=851$^V6dqx@8+T`75R-3FObfZBGmFp8__z6Ru?Djc!?MvpgX&+Fv$q^U z=%@j}G50XT%tzGLnImu&I;YN!5>_1X!udlj5GEeMY?@uve{mL%WOvd(pAY-_IG)Y; zBG5F{7oEZAr}E4KrF-ecBan)HJa5*Zy68d6rNDZ$#2*{RRdjk@^G)PYOG!TT+C`;`DRVP3K88>6NPtSIem)IYwCq-1DU znGDIH$9s6(H7bo9S_t-(=RMG5tF$`(t)9x{7Ru7{9YYI%Bv1Q(rSBr?`6jN~=YEQk z{0NtZcy^JJ$`ku~hA)UpDaiR_1Ea5#(BB8Dk*a4RhvQzhazbR6nkx!n870CpSpyQt zV5p1rNg(AC7q=W22};^bjx$t*kgDnlGfIN*PN4jLx>;F+=Mn%r@S4r60ddW<3f9>f zAI6eA)|0f2XN2n5Mnzt{YA0v46^|GQ4yg+`UH@wg;que5SW@! z?UA{nxubF+d|Io}?WHl>p!*x2`{4c#rnwbeMz#1*)8poP2p`&SVC~}-yc{-2M?;G3jY`iC8b5@6#lyn}!vPm7 z5v3J7CLiS_Y#H5+{rfTq>YfF6cgSp;W1HHhbm192X=yW;qQTpgxF0R7HzLc z6CdlbDcGMM0nMoFph-C_HqK_m(#Eknr-ZN?I>hpy>IJ>&M!U&xC`ll$U&3+rL_BX+ zbY%;%ZK7GlWkBxQFvco)V|$mb=n#ZAkj_(kv?+U>1J$wWIplD{V2r#l1(P&D}D zdLv~dy=T1pJI|B+$&L6bAO!FsWovFedn5OKuWh+>p_`SkS!G|ke}2}v0%KU4EMuxQ z3aE~^%L_#WK=?4%{-Vro6Tup?m}k}bu@Nn(;9C1)yI%k9PAd9vR0AX(`Mo7+kU=;X z-be=fFv&E}sXwPxTm1+^;-zH!Nqe~X%ru*8gT+;eFZ-({?n|P*&6-l6J*NKoRTG7p zpIG?y5fOQ&iv=*YI@#PbQ`YYYKs@kPl?C?6OI7 zy7`baE%Q5yDPLYloXh`ru=k07m4Gv2pvy7 zqWt$3vtyD5p+_p#O|Q-!hi3r(=F_C zXQg@$l%IH!oZ3*81{AFElN@OaqE_hD83TUt(T@u8vq`C*&P)?wPWRY)_1(mJxBBCb zUEh$Yy)v%8;c{lY07@KCUih|ZWV3+J+yWHxo8Xns@qI<$x@xpgV1J_eXj+@BCl$Ha zJ4^+w*8cMDK%j9z#f#~RTj;Q>_Vqd&PZ2M{TL{D*t$nWE$V`MgOBX`_N4k%@clnuH6v|BEW99 z*a#ycMS*dl+^k0Nbmebng}5xi{Dv*4W(fQBOzM7hVTF@r!Mak!CalEzrH*A!+XqBl zRQLfbv_&9ybeVE7Z&JWE{_`qy89N~H{kW@X@N|NJpyj(q+61|<5vFur7hEvjFpBZePIp*Td8NqV*lyf`j3`Q3yH0?lH(EipUc{rlA*T#k4t#f!*8OT?h z4}{znVBV2dXeq-Y-K>q!Wfq^gP*{nU&r~#h33-L9K$!5&Wsely8ELsso4IFIO73iB zlRCLnpgyW_cnBBI;}EKoCk25Vc0M<%)ywneE((ld-Fj=ICgnDzj9bYU~6-si#2BYn1n9K_?ohcCJCd*_H@GsB@ATr`(XI< zm?2r(vX8x`kS#axjvk%52e88}U|Q?YA>=nIhXvNFBMytYi!hrE%D?CC2@)Y&19j@` zQe*2UZ&kFKzia&tiCA~&>_E>j)?5{;di=@dRFR~~S$Zu_(HZtwfW=lcN@ z{lqEvSM=s`AY*S)P}o@{bX0MdVrU-!XsigFF9cZdM5POTD-m(biqiK#N~dCDLnYu<)*Ni6nY z^lRpT!8I$=S#i8vS@6XHL2LsnoQ;DAkWZDedKsX&~5t~b}B zk5lUV{347BH@&2Ohdaw~KJhxVm21&01l7g%5)-H0_$aMaWvYv_!!?KE-&vfu8~XzW zKkvXdZ({?VYr3gJJ5es)n6d3suz)*8w8t|?pVUl8#Iu0;D^FAEJ$VW`J_BG+7kq>^ z7WRGG**%qyrj3rN3VCv7vX2XVznQ0*%C|2w2A2f4q)( zit{~SR1Yl9aI+|^hxI!kE5Q>HmFBLoIV*wHD9AlW;N)VxExa5XROR|l=&whp8!ySx z#RLtySXU!O!!#Gp@tepecGsk?lR&X@Q=c=4T(M~YX@2Ar_n_l8DdO9L?7$oDD#_<1 z!&v*f9zB6qPpd8hZYNAqTH0n#+u93->hz)(f;2Q3I?Lrih<)0ukfGBBgwo=hx%D3E zT*2j`$pV8Uy2Z5)m(a-a87K82Z)ffMyn%o~sQwJ3A{^KB2jp76tlN{V& z9SWJny+Oz2A~3Qm*GYMK=lbtm@P|HS!X61lF8tFC<@8iy&zOjD2_G@eka$$GO(kdwVZ9Cg!~ocH(hQSgfG__9eaHNE~r z1#5s&qq!#Iv4J8a=SnfbAi%Uk%i*a7C31z4wN5MeGOl~qnt|LxtF9KxY!6I6oN94= z?ID~5oaE~u@e7y8vTz{$MinOz46bbt3I4{7@wXS8b>)87zC<*;^i1}ej}AsfMUP~L zv^+zX;9b!V>yqz?bU&!yMae9?)?0k|)tLN)4ePSBwYtRy~X^`h-A-aN=il$++U5JD5PKX^xVKQV zb#@8R+{n6}kr@&o3Yzz*7}2Arisq){p1w6B6;3%Y5@B@Hvf_hpk4oV@AzfKJp)Btd zPZCL(VC+s8^{j#Vo8|%OnM|Dg^W*vIb`l?9%b*5lmuleys;<6=o$5+Xi5zY{WHO=o z99$ls`z#HKU!Tt56nVAZL)418WwmEEWe~sXtfbzQ+n+ZxYcccUj3<`*WQkJ|AN4rX z_e8=dumEwDwiHxWDP1HGPWW%rjrvQ%9yq&q>Xh?NrIHK9c!m{ypZKUU&~ATUpmhXII37Xe069R$zvBx7CW841i09>494$TUZ}O{3 zi*KM=Iqn(^NR5T5!_p6XA3Yl)7aKNpQ-CmVoF5Mz&R27bVZ}dz)}X;5sV@SjXjADEh0xqievHwWJ!GTXmbPxS>N1L1=5)$4M_n z=sxhbr}fEhwrqv~7YW}KP2DF&NXCNby<=c%^*UDFmjIvMOl6j4*|}q_nuA)og1vcR zoamc62?IoWqmbpegMd!XF`y9qcJzLSrrEJ39olR15O>=;??J8dI|xJ#CHFAqL{c59 zL3dq`{cV!N<)u{|rATg!`W`95{~gt;ys#Lkpld;tj~dND@nU27R4avslW$`Jo16OaIC&vp)p`$8S{*z^;kkYk6UvI?Bdjv z;^C(tuJxs|%M%J@#Tdi@OHk)$M7^}S0iTdgbi`Uf`@Gi7TJsmB0{lza`7hL(Y?dr# z!=aeYryW=)4(7Ro3D?Z94LS{WF~P`O=5-2wa^Kkn(nk>ple!;aEG+6YvqMiXjcQ;- zeB+t`rI_00?(8yp4%kTZf37jYmCLd&1{JEJ)GXev`jC9#&_O<02vl(3T!f!)cWDt4+qbT zihb~7-o2>~$X+(T?!9~fK?t_b7lmAE*t&W;DSjg)N(Dfp#|m!Kf$l6 z>Fw}~qa~@0{vmpiX%Ho(u4xc7H`I+Si^WWTtJ^B&asq9!6EfPVu6>ZK6B4ERbgKiB zy4jYR&X^dFbrS%>_{$e%U#6R9rm3*3pNE%^8D(V5D47{>X0eNdK`9;n4v&sCv~E&L zI>nIBTQAf%q$*OVnsou;M+&VZ+@k{Y9)&#s;)RM036^PJ66jgGW(&RIdnxG5`G{C* zJ*T%9F>B`6|A+z3pRgYsY{kU4Jk9f#=|gPfVG5C5oN$4Bck%}O!o$@skgK+A=P|ET)qc2t zd92n2nKRJ-bHm(6w$U@f=-0Gr3gje1fVXFu^dGoWrF+9a>&zHZ<|IvJtb>O|OWIxh zUTK~e%f0~YYgV({_bmd{5c7akdBRT>Z*ImSDK7}{C%s&1DS!xBAv`z=8u5ZzW;dSilXGF>sY4-F5RH@OkPiF!jI5;8 z44zaqp5Z^-q59&6rZT90LT~lf%_L6_iR1e6R$i;#YQ?b%^tpI?AAlW=cvyApP(xR= zzbLb|=vXF2^Rdn3wphX+J#UF$x0`$V;}HS$?|s9bmh5TkFt3&~euKhNkOQKE^&*C; z3BD3v#y=#e3eh$`0TB0Zkg%$+lH!|~mt^UhpjZT04+F4U$5vIySV{)I0xY#DZK&%j z)d-C4@N&j%*aeS@7}EO7TO>M+=5<{$a^$sZ>Ah-}>%Bej3gOXF1B~mG4z-6@VM{Iz3H7q1od`+URleIBi;H8_cn8(p6&WrX~70G0+dIRV2Bm4drR7 zoU0I~z!1dfJXd}5*Whq_fwEURzSk~VCiG~2i>hOxj=JIiKO7dnp=f-Ux8(ib%q{5f zWgbV-M|e^fR@tGnhs6k5QZ`RDp3zuv=qVUPn@a>snhFRVS+ywT3HA76Q?dx(joht6a`Zt9)2b6Xtt54B@lMePi{8BXN z!$i=vQ~LBEjvUSBsx2&JUIolSK&j&U5k@i;4A$EdHPDbQGp-=e`<*XRM!WDZ#|14u z60O_rDf^X9VT7PBjQs9p_Y+!f75bA}=J}g>&A4?K(j0cnxCf8rd|XNQm}x|;2df7I zv<7*d^PQYSo>yLPrJunKshl&VkMRq=L8)f9Bn(`n@o61P`Qnsp(R<#Q*%ub99vkKy zz^PbF<2mD~1AYBGw&_xaH%6rZCjC2)6B>lLf&dBCjeF*p3<#Aeiy>ZX(9Uf4J>*Cq zcv&YU}9hI5cOixV1&=h1MNQs|J6+6#4@yhaq5Y(2hSv+Ttxe% zu9e5TufVyyp!G95QN{jUX?zLY<7}Mx09~Rq?p`eFUmI~z{^|sw;-E71+?TtyWVhpy z5*4W`wQi&)YuAMq=)1(3!gWTQ`D|M9TqWW+J*nMQPL8ADt~jOQ9BUNjKkiP_2QKln zCb{BR8LSjMR3s_)qigRCZsoVJ_wd_}aLN}v1!iWU3FHx#}7_jET$nFT6$r0l=} zH)nPdOa(=MX(vj*h6p%r6u@5p>L!vTg222^g(?-p3QN;xPRHzX3X#1G znzm90+zPAu!=}6nD$UKS8yJD+2P@gWR%0qqNPm{*i{EV5RBKAVc=^2m1j$fnZzK#2 zSHb9M?SO?+ugP$EQ%qW}!MYH0SBrN@+Jh5+NO%!Ua0_B2k+Km~c-)rMGGj15Wz2+Q z40J5PsJ;w%^RSLj%)UNlHU23x9(HpuC@^ftb^k0>Sf`uPLT|55Zu)}g9hjX=FyBd+ za_dlcgmE*vSXI7xZ z-QH`io;8aq?C@3^a(#%*L!M;MIaQ;Kxod{#6qf*b=YoHqA_MNccR%Y91xJLH2O4W}%zSI_7-3ac05P*#m8Qj!fw-fyx4tN`5*deN21m`mTV% zR2)jfynQzft+t>^8b}1jwR{$EQY|*^UNUL-1NcJS1CxQ}Hs<{1cExW;yVmDGMYCl3 zPyS{%dIEpnvc@-GKF?4#AM!XMB~>70zb~8GQEX1ZXZT4v_*7i5?1MC(DT<-4M^dr$ zkd&2+gf)yXHm;oor0j01M)KWd$o+zBXK1E!{G|T0N>tdmu!YJR=gH4kdz`~}a$;w^t$-6)4hq9+le;L=grdQ;9dABWuV%&Iu4Yb@`D*+E2t8&VJ$Xm` z4lhJH@iNa~hLbL!a-3g+yEiI2z{*2E%LuDcEhnEp_9t#=K~MGiV+ z6rEOlUm3JfV5oAn*AM1Ga3zn2MALuyi{m))%(W9CBtfJv^#Wlpc17u=dx^Za=UxTO z00V;jn5M`%Ep_$lD(BKOe$lW8s8Rb%rH-sG8V?Z)xDMI{@waooRrK+^cPvIW9_ghX zi21E>D(?0(4ORS>3y?Bz_;Z|%;&*@m&=6@`rN+rLS0E}y$!GIDoK z{!2z6F#xcZ>QI%Mxo}4Y_8|LFgfaqti&-k|-n30ahC~kkzO`A*Ffv@=28`1&uGek~ zIRnUe*B(FEEFA(=I${O70Azy6l==!gkA=mbR5U7HW94ha*kVQE!~t#@^~Iu=1Af85Sh`};r)jrg{ zt=OEx5&it_d}6Eb^X3rhfA8FhA341ly>s5Dk}j%PJ<`oFT{-rvbyN0&1Z$%oQ251C zFtA2Xu17ya`qA?cAc&y54zDR{nG+g-@b>}}`Q^exLUaEmw~}qiwGSsV!3PNH?a1l` zdOo}d-iKjdhZ9bbxv0b4gD!Y+igz&f;uNEnkDET^P}4&w=z&!4+JG?qEkDLb4Zkrx zRK1}%A|2hq6jmgKubhAvQ?P? zC~i1}SGTIOjLx20&wM~=3xqhEVPxjz5MJ;;ieJn^0!)pJnHuOxBP2V|k`pnZ&AofC zWWR?V(8Yj3`H*~(h{Q&cnZ)eMf+;M(oDI#t$D;`D_F~yo`{yyY7OtuY)HjEHDjY}j zOWIAG1e>ffJi=d1moyKpu7%k6LL@hBh!-nTL$fEF0oIYCrG27Ui&x$rUGY&DTe9db9rO=?n=bX)_SMh3Qz7Foo ziDHbfDVOuJC2SVcKXTBF9q+Xo^ z3pusuF4XRpY|2m)E#-mg59A8Fe2KuMIf(txv}Fa&`lSW#3;I3_3a^49qq^L+bw!rH zdTj-&>&L*!ZilR5Xh!j_8_2v9&kE;+d#s#G%TG#l-gZOg3ucCw0Uy7CIr20@8HESx zN9uK+XTL`Yvyp~8OyiGTnKQ!tf_HcmnI>4qht3P{k(0$HXDIrbc_Z`Hiq~fSW@8k; zgR7ITC#o>v3Yuah9vT6)jNY1OqTOX2a4aWS^?jHx!ToQTe zCX4cYjmI`e$AlO$l8viGf#5RP-I(v=a+yH$Ym3wigZkeN-&N(ZxC2t0wBd8W1qG*o z=N#Jl8)HBRwSdA?;YJFw)G;)v1QauK{f$wE0)eOU09&nR#b6?PZ03b2`#ISh;ngZ& zLx68jc#!6)=BL#OyZ=-Z*viL`&q#)?sJJ4&5tgKQdEB@2cZdu3={Jt7;}0HHP%BiY z6irln{ZIoJ==KFM$oR`nP`yz5hV6Aa^bI@IK1@1Owjw{(_>#-W(EaYi9Pcr@DNFw$hjG?W_YjZ2!uhnkSk0!C4hnd5b*Q}>t9^ukN zKe!(|b*_7&r}-VR_|9Lz9VVJ8Q>)7hV?!a)atl@;1&P_PO6w(o?JL{zaZWc#0!RX^7-B*TyCS-ijK} zUDe^qIs6zJYIde~iO{S63Nj7t?tX5UJKp<(DWFuICQXLh^FKw*r$M%rC$d_Z}O)>#gL{90102U&nF$t$&N^i36)6DHZ{E zoMT1fZ9ZKxg?{1C%p_U7jk(d>v_{cusCt4stHsZv$r3cb!(rhMw2Je9#Tuj5C}6#B z)?Ar3p7;|Fh41atO82|3ZcnCu`TI_AZ79kiUL=_H*KP}$8KT1J-tj&U`^A1|%vOF( z4W+gF8f|XNY19JVWOJwX(y4Y$>s#5lu~0H>EmfEGcbVk7nWP2jT~`!lB1 zg+=7uU~w>`xvk#6)o|!V@AI`IKKtMK&R-ShX%_CLIYVVJ&^L+1q^aE+2%C3iI_Rkw z6S8uOBJPWQN??abhGqg&zF(#>dwREoaGwhy`UbOKeP-6^up-XZJ^ptZ{mbrYf=Udr z<1OxM4Xg<|!4UEg#Yr;?eYmm__iI?9X4?zb8p*m0% z*$*S1+B-b=0Fw&lERES4HhV@$HK5fVcfSQSweOUiYD=*(dtqp!@&pozZfi2krX_Wq zh)m(+gMu!*zSiHOe2PZ##*M$WIL0CzrvSj$4KB3gl-tTR`EXdng=FU~6nDoWS<3LF zpP%~atWvYL8^&D!WmmZojC_#K3DhPCnl?L)I z%Fqg)nRJdtX6!?L02dqlY*$tEM3d}8{jNHA%EhodJ-(Fz6_^!00)6h+(p1iqk$Y@ zz9}vcUAWI-L7CISSySlPf_e^=L`+?DD3CBG1brLI{*Ff3Ph!kPQn`iqu+A|mVKGrJ z@wc&^J+!VleQQ;J@RFO9VKI?S# zy_19w&=0qP0_3IjdZ!`&432hME!0Ootp-ZiF@UNfYUMTTwb3S z&pn(R3%^}vHFOt0P+j1dhS4SMcmUh((YVUr<|saFR4G-L<^yJrgXBhnOVtz4y(8Pm zXa{JuGdxl!!_MT|KgTg(A>DvTaXbT$<=6EQXk=l?d`0VT30xwU<*k60KGRf}QkL}$ zkv9l{bTYg-IF}SN(boe5{AUmHT`K@0uP6FNNyPOZZTUirQLGn75xa-yVg;N8jK)E! zhH04Pq}tT%!fWT#Hv0!|&8wHgat`7Sg;woB-B+G5S*lid1o2|%=zb>>tSRhom+)Qj z_{K+J0Xc@OyA{7zk(5rmt1@3t51wh3hx2f{3$1^TtOcU5aXb)A?|Kx|;HF`2%Ov}O zw5YUQNjc*OC^FA8kWbw)(Q_IFy`5KSajuA%gAX6$uhr=$px$_ncSFez!jV447c+y| zD@zJgtA{9QlC3>EAF*1Nd&z6JT0jZ+bhEB}R11LRFi%-X=a4k3c3a<4LPN)|t-~pn zW{YZ%rMdbjuKX?rZ}iATT^iN5+-2iMo8c*b7b^r9AX3S~+17}4pG-ut2fOMZMI7guk1OPTk8PG_oKUb*H4FoB|i{;WYxNDSGo4B?KelXkb3 zx*%)#B2iVyC)C11zg?kP(H z$sLTK#^5K1cD1&6IryNkyPJz;zNnqRF^qwtL{qsbKleI1##c%@@f$zTS4CG=CT}zj zwRI_(uPlA52WzUC#v#do(bk!%9_$A33U@BmS`q7Cwncg}ZMo4V^_VkT;(VGY$G;ZK z>^v8@&E?m{^s><-V1+yZfk9q3X0Whzb!9$AgmM_eL$@os9*&cdWt{5S$DVkk!FkO@ zRgv@g2>$A%AYSB}$kSCQkOUTImgxl@c)<=GFJ|Y@g$Y{iI45$HL$p*Q*uppNl>S zTKepfg2nb+ck_0j<>`*z+x-=cZXA-*w-eLt^}M}vai>L(k4Edq1GGTp?p4T!gITAJ zu^i4x_*#f9g6b|hpsX~LD~xvWdLWo&6xq=Qr4?}it~@A20huG11r6rCa;wuW!1?Z6 zsUq~Tdw$KnJrj1y7?%0Wc#2{LfPSa7AfiRGoY`t@NSbLnMP>++QLY#1D=e5KwS% z%7wQ?Vyg+mJ5$U`!P+3lIl@T@5pN0)3g0vQHKz22o;TR9ya6gV4MUPktO4J z)QT;gwJupJ1>dZC$VLrihS25}etAV23lUdqf-_a1`a4#4$nFN3)3`8(Q&Gu&1cU4E z@Uai;Rfa37niKu3d6Badas<+hV8`JoyL;t8&cb09tJ`q7->zaL2ZHG=6?aAxS#Dxq zVWh>P$YAw%JdqxNpelQo|ENQ(G|uE&nk0G@FmbJaKu_f5-AIDgG3%)f!iZl1ZUw_{ zd)Z8+1(d5oaPKF3@Ek6Y)wEzemijvl+r(BRIWD{^dp+a1Qk1ICSQ7nP={zXHiVg^W z%O_67T<~8m%4W+L&~N+ZB(F1Q307y}03{7_bqp1$zU0J!l4G4$S9=rE@plq~oE{c1 z$ZK{YA9}ua{4T$aURXm+6z|mejL`iJ@NtwGp+biapqis2*M56i-t(uJ(HexwX8hT^ z&}lL)t3U;tULfl~1^-+X33rz5Ag2@a6pvF~QT9LtWxw`AhPuGwU50Jq_*`w4qWwsG z4DFd<;#q$w&gzq}2xG1do#U+%%kojN1qg@Qy;46g!6MP}0ds1|iw`DK_x?Te$*^jN zv2fglVi#9pm@joddGMMH_1m;CWnQZbY_pr_QlZy)D&(>=NmDmk$-N+w03C4c#`XxNDIp5 zFcJWrIZ^<3Na8oYARzMZVbGxQ=iUxwg;)bwfT5B*Ep+;)nXa8XisZu|z7@B6092)b z@(3Rzm7Jotc87A8rr%t@TRY39;<=Y^=~-rbHIh8MGnz+F->C)pXFBm`)}86G6rMz{ zuby_hHz~%)nK?~!J$WT{gNgVj2^up#@3GARtA4Ya6V-Q&L8Tx_(uTb_5#o-THX4YO z5fp&vmDDistQ9qYdR`|{aO-0vnIyX&%z?a<)q$ z{_i5lWF@Y+%}f%!=wt3EWM~bLgQ;lU##%TSC7j`bSc(ZWbDgT#Sa}C-y#8`eY_WS` zdK#AKTk> zKLs>Qo5sFK8dY-QDGx&h8c=V;+pGe9+dsi7!;@tR@U7+mDWC;=q+)nqn-)(ew81z`Dk)*I-PDDd+2KEJJn;U7N9 zf0oQc&k79m=X*o@4=4*O69;SF3G$^B#&99jjNU>si*ig3nR?uP;B%C^D*V_#Y7zeI zlD5X}>6I~nOUN)^x9ls!%C#6C!fkn}RaWoVDMd)CV&$Ehm9}S8*`TeO+7Q5~IGS3z z_BE__DvzLFE-Jh~Z%nQvdJofzVb9Uub!86}bf_Y*$OE8aCiXE7QdeOC41bRUPOu`A zuTw_2b)z|89w>lv5uL^fo~AiP)=+(nZm5V~Y{bBEVAmps|BiD^SBPO`@r8RtluxRh zeH?tEE$|_ALa~L+JE2NWw2JgG^}Tci2nr~^9s(9VZ%NNq=M7Hd#tBN&)SIwh)l^V1 zM}c}UGHpsWHc81qIQU}FUhn|g<|q3{N@c+>1x7}bwq5}sSE zv3nf1DxokK{oss7X!1c{6(uKzV^6Cj*tc{}j{&TTGziva%u`0AxP_i^H05t-S-JGX zUQafQVz)`Ww6vXe5A1ifpP2ru*7lD>eJF~4$X%!0NdT`VDrK4 zSBqlNU2)mg2?r$r^F(Q2jj5?u}9ZPVCcyrWVGPCuLQLR2x?nyZInsi#llJf1_9|lmXeS~GYT3_NZFscBDj4#uN zMfnO(5iGAq<`<%!-Yza=?(Sw*m}#e-v3rYLU%PHg&X0hq2n z1t>-*IbGltKVXw@!%8G~}L6iVm;u_*1P4V_e!5EokLWn9-a5zApT{sK%BE$yj zGydBQD42RAmTuuBjPVDWBC+_w^Ys*Dovbek9KQ?z$Fni4`G%YMvA*ws8Gi!g(mRMa z5jA1VaS&?^+|&k_Xk-@FK0NtIGTgNv?)|s%X)0*l#|B7X!O{pX>lL2yqNPpC+3^`{ zy4$CE$}KP?VNFUHVTM{1%7WkA@YJ>CSdHqq_LjQeP+M(fX2N;Cb1{X;NUgx0P?4B( zB!dKagMi7QG9+gGk<3hkN5zQ#@)LZCQzvwe<*VH00Hkgz7X!6REF+s5XB-vb<%cXR6o?X(>?>rMxaIV0wiIa3S zXQ1to*7iH?xB#soSWQ{%r63VFOPM=qUje z##18(Q@h*z_NpWn?qN@#{w!J?_&`PO*0%Z?5Xg|A%z|8L_9>I|i}<-8#R)D2P1vvN zvq6(lMrD9uGh%+L(?8GFSg>+(Qb{^)U|TZv?3RaxGc?5?tUa@8dN0_#^^!Uo_Q$Kw z0J{Q+13OMKxo@>}hXf~3T5tWjZ|9&h2$D_EE)Uu=!5a+KH_*(T6-i6Q>%{g&e-yr- zJZ$RY@2KrBlmBvftXN#So19xH_2pC?G|(e z_WV)cO00rc6EO>I@+9_prYabLqz4A02v;KXVO&-ZUS%7|fKoA0=~5)<*f|990fRmu zc6Gh5S!It0Ik(t`WYN5?an`wL?GSt5NN#YPMXUQ>9oQn z(s)7xBj%2zOiB{}w#DssE{9~NU+$wV*F9hVhmZiKiI2gNT4gl5=pGOsI^5GZz19SD!Gc2nK|Uq@PJh@qNeA*vvG|iYw^Ad+GvCQVbWfO_eZ00D9e-9?31p9 zO~auwa2Uj1%w3r`*xMty9%xS6c<;58nsKBy9C`X>2Tj;Gj10fD@KYRI`6WpEKStLGbeJz)l z`xyN(>nZx>=ONN)Je zAx@-1=99=YG+xdv9@QDNP`5eZx8cN{VLA2!`vawZKxY#m#mg@9}g9Lnx=H+F4$S0ZXu7SG%(XB5$w{ItyX>)HMQVomltlC#28K_yo!9W;%{C~o z`K))H`eL#o1~*O-@gaxr;!>?QQCbN=8&QyV?o*$pvFR`vhaWnZ;m7Ph@P3?kVA)}1 zL!J0h@Bw09U?o0P4?j1~zuhkr@#^t{$DripSKAPgm4xt%!tRF@(Zl)FV6Y|yIUhJv$>UYA({njx!Oqd`Nd zw14(NI?Gicz;v`o$}2&f%$HHm{(i?Ko{7Wa&d0g@Q^3_D6s)0{)ZWsSOrU0tj4yl{ z%}Nd@;n~<~|1FdTVxCJLfo*@V6xAJ80hV^^^h~;EFKUq_bG08v>NXH`*?8)EEKc0A z4qv`%3`!`4PamovjhF;+WM=Q{V8fyGqv0C1fFHO{i#b94hMZC`uiPSE@7`{zvZ@sS zr};Vq=wxRi2l$g7sk;XAgbyIUHUOl{%9Vw1*c`3HADbbu7fpb)rEhlKz;{i-?ey4V z2`~LQ<--&WOYUJ&(rm^0iCD`$9~yAfx%P1p$VfkocyGq~GxStd>h6A>@F^2a1aiUq z0fsNgpy<;}v+YtbIg);EEI?9!%c-FNn_xJlG;QU}aZdmehZ)_20#h&vWA4g0Xr$5 z9$?%GkS~&d?xQ*@$5Oo?31_BfpPD1RPrpk^L@coQ8@I6ia_S+*?#dAf-P07uDftD( z&(yD_33k|prcxeG*%;%vEFG|jG1og2v>*EE>j)PVJaSjwAFQ58f65Dvj3KL5J%d!j zE%&x)q-J^HZc4KnN@l)Z+HO7Qj&j-%h&2+@K8p}|`wj(*t_~Ae=hQo^G!k)s;E3-< zDVGUu^uguLjWapI2I_mcsYz}s8{RwZEX|Y+?Yzv9MA!K@P}sge0zy+xJ+OFIt zyO3hr{>#NpUAJ{!uU!eW7$S;WS=bXNWQ$iGIt%DuAw@0v{Cx9#SRV?E@g1dlGf7X( zUhMiiy}nqs=beV;jQRlKGMaFIHOja}9qO8>)2hf$it=Pgd6HM_C*qKxXT6?My_`YMl zAXTfu45GLaZ-+K{6gcRRKsC^rblQQr^!6_RG(4Qf2PYl0kKBiGA;$Pd*e}!QbmiYw z5Wj*p4tp z=t+I_+OP5lN#r`){2=i4(8l3?J_tWEVIvA(ZTWJxUNhWG^I<^4#=*(|#Ct#rDyeqsb&I!_$|* z4Zn3?ZUx@1?_JtbiogVV20pdI(TT+oxs=>WiPoy15S zWxyXT3aF^zpLFRF?kP)4_WXcP=4Dn}CgZ{mZO>9SP+Y@SNC7et#BWT%&s6OVJnt!f zausb0k&eF!?WED_VC*PZcVXcHP@fSi56>AyC9&4q9-x_QS$Maj($p0M7d{92(H`VP zj|+Y)m&Uk_tYxIfMHmLg-vMV+s@|MED)$V;Br$aAXqnYLPZP!LuVi^3RHvBv6al6C z8rF2p(w#GTb5g5qY=W014%7Rz9_I+A$4CEVM{+Yqj~(b6rT2-12)1kGBeGVwb0p|S z=ksEpg|=&0f*o7;DKFeKDiJkh@ZjW?Zm;(d3XsMs4%{rG?lcUI;~a0SF(z)(mO*q* z4kkfD@EM0!vbEemqM{TYmd;<(Gy0k^&6kRODEPm8;1`k~hnW|TDX z{^<^_MGrc^vZnmMy};#llc~P@z;O36FfKyX_gD!d^M&hyt{VWU16ww^u`l0|S#+!< zW~ldh?I`-#kxVtgg1 z2(tiTO|vG<>#aK~5CJ3$A=fdiXx2n4wlm1obCb+_)r-6F;bVER1{nPto(p8CMJZxq-UTO z?m>Uj@>zdjZkzc;-U&#jy!SmmZwrBC1Eh1@14||h+y-1+>X-M?n(|O>7<&$PG8Fib zxbpQ(F(C@`J{!xs(2) z{;;+xs9dlmww}^K3zK~C@zGDnvvKv1AKlJvU`1trfXIoar^tN9AMcS z$&tc&KR6_w8Q@o1E`^F3oCj;8Ew>9AuN~H%_b3;qXx_k>8}modH^{^G5AFou-3PA* zUh67lR=nU2Oq}pc4nSI{FDj>Jhe9JA`Dg8#z?Q}q7C?{1Y$%2_84bkGeA;_x4O~Vb0bC3*K$6l`0QZ6`h@GTqlpL9Alkl~>#*AKs{(D|1$}XUi5A^^o{8g_N&Q3S62$@aS?}UtFAb z&(G`oBK`fkbkn+2-@t*4N8e6yCtr&$lKREDiCr|RxCNy@&$yt@NMpn?Ms`Z#4gW0x z6vCEF%^v+TJlOr_enW2k$Sn?>tH%@$hMSv_G9+yQI)vRYt5c9!DvwpVbPG4qG!l^S zI4+TO-7J@a;5zUzPE%s64V=s*F!)e&p6NnVSHEL7HYpb2~YK86s zyf`&IRpT4mRY1sFJhwfy0}St5#T|pw7cTOhoa)2{IVnI=sMD{{{Y?qq+fc7C50ISc z9|b<@752IoGpqaX6rR!u;@SmB%Jiq4eE&!NKY!&&UQ7zmT7x=HN_v&?)+qXRL z`%`SabyFqIZgP^&-V!-yOu8dyu*vZ0o9C@MrRwfw*=Ehsgj3h1)f-5!+OSn%&%?rgssABxN?!a2 zx!Kn+Y^ABds6UDw+8w85kHF$+jX#J=cTm{&iE|cXYlxY&EKzYodfu`?#|97n$mgho z&O(FstLsR&qEhyESV(bbvRiFf@%RA9-8ksh(OCipTqTFp7SL6fK$vA)Uk(#!#8q&l zf3iJA^4$h;(nbB^YQTWw3;#K0nVl5Yj8R>q%O4d5J|aCb-fq`xxo4$LKZB}^*WAI= z;u(;S(;_N={JdS01+6y+UTI`rc-gPQC_>`bSafLG)ukAAihJ{ax*QIO-~q2NWG1|u z6P;RB+0755Y4X_sE!WQ~YMGLuNgUxM8t^h2YNE2|h@=2e6zd~ijtgL*>Ytf5H%Ws8 zd?U>*UlWvDK?F>EZ7<acrG&kTs~RgR6#1bK%Oc;*|l_PqpeTF?wKs_ zlWJKp6=148wjDOSxM<+L6(}-925E$Pa3}(_;#gy}V<%ro0pJ`cvkm*G)sL?fN>9V5 z+V=$zV3h8S!|x*(Dyyj}GwkJuGqQ|UN)XL}t1@7KC)Q_%WziClOo`qJyJB$zrZHU!Gt zjs1&O-t1AR&ecGI=bt!$RF%-B>kpO|C^-x&_4Jo$;0m-*!l%?xkl^-_z zlqmnx{ovrb;a-L&K1l-*a@tR;FyJ^v*pPGNNZcIuB+MfCq+1-M^zPZR>4{IEKe&;e zG{AmoY_u*}l6Tn7UXevb`b~!LB9qYyPLv3XVAv>BB6QPfN!IiH7L2oB&!u+J;PH_UR6Yqj3O(Jz zRQ^ysM4vb7YP6dCq@g#M!ixzov>pFo^RGh|WCcRQ@+vz;p_h=?x$tuCXXGsGS3XJB z<)Xi4hHmp?M;i;dpkFmX(`W0D$Wc&`xAQ)j9P%N7>aak()_cC@P_#p26h5=#F43Cj z{fwr9kT?UR`BEok9gQ(-sp+(qC_!b+ChUi{CXhpDDD>COgVINlaPW;qvQm^wOb;e7 zaY1jIFAipe$xjg4$+uTn=Il3FThdYiI(n%3oBT z_soR~!i4ADm!(YtU`3+cirPk}q!nm7Ie+g*k1+Xyv}>a>2%=T84%_sl&y*4H3(3Zp z^SmibMGnxTr4(2mtty#(4Zt8i+*jg&;z-Q~?z5EQ(niPw1T8z*G*2q_gH5Sll%#08 zhX`bBAE5dXXyl&=2F=f4P}Cc=DRd{<>{`tce}>r)sNDw5bHJTedgBz|(ZmUE;E|y6 zP?Rr~b_%7+;mf^nQ6=;pd015;c~0`#x&YTFz+ih)E%Ku#3j1t~JX`1mI8bg7Q5qh+ zlO8uB0SUNmRpFuq64y64k*iP&*mYgu$qMon<=VG-wq$O_dQ+JYGY{?eP9NG$6JVAe zRshnUdT$4~8Xg|tueUk|amGMTFnsp&lFE6AcBF7!*L2KGS7;x~2%6@)h=KqkKEMc7 z=k(dpSel8clCH5%>>wmXl+d)6f!W25yI-El1jGJntm0K4l4LsckFS6Bi}P`7U56RH z;k(Yg9lT%>yf*C)W?}XrmElPnoWz5l8v0orgoade`!Q0V{o1E%%**swj;JqH3&PYo z%3ff=N=G@x@^K)K^tnt9zp#vzj|xGe^*S{+)ojQN6W>2#^=QW$@-@doqQc<(+oe65 zl?(}}(a`gi`vva$j5lE|Vq21$G zjhCkSg=@c7?|_Kbfi&li(rEIe9Mo2Mo|;6s_X05+TVJw=6sVTjupxS0o@fFAcY#6M z5|d-v0Kx&d(W3M!CVBhBve$y6-DyY+6sH0(`DI_&#~Jwn+x@psQGozTK()V{m+p}_ zLmDB!DlG2RH;)w0pbgNrQf-S5{@_DAD?sw0CX-V?$eT!A>I&{Mu)c}{EOcfX{*^j^Ks}Z z(KL8J#S&iEHO4PY8!`D^$74M(2KHaln0f2RkK}T@?!K+Fv#$dQl*|W+L72ummRchNNG;fuN(S00+Wy zK%Tj^%MeUOkeZ=-4gUfE$RD!QlsNGdW8b#Ne$O1;6z>=(5F>qyxSriY||vu6=a$uw`{) zPWt|+t1c+x3?@<-t3(R=Tu7hnP&H>j?+{3j`H(Ldp6UvGL3sRZgFLPJ zS@WkvLi+ksvhI(jt#x+%^l(AZ0&=Q0BV{(^vP1D!UG1 zWP8Gd6&%;Nd1ye~Q1}*J2QjfX&4fIe&C;@bL9vH{M}@`dUV3kpw*wHTOg&~qS+)Lg zY}VW1c{{3sEwo3e7R?MqEl^DG-b5ZS6#NH3T>Fd)5kO8!7943poKf|PA#Kr^fY(XCk(U)QaYo}C6~|;2GqS#x z`CUo=EH`a_g`kP+it!Eu3A({#fbBUf0>-Fw$=USnkN$C|siS`mNl*%oNhAn*s)(b{ zfZwZ&Rj<*H;wvf$;^Y}W>QLB7>hVKF6xPolkT+URV|+XK^L*R{TK3&e%6$Y@z zV}l|sLn~zuxCwC7ceJU=13;)*Iy>*9(VU)5>e0k-!Yz7CiTAmu6=@32u=p~nOE+Cu zBg(!!?V|;76f0hj_)s2E0?SHRA-z@&O)t2h0;9X#&$Jz2A^%HH5EY7Lm6yUpdAtH^ zFT>*V8G)Rxj2W^ckzZEpLt*M?DpHPwD04cRW4&c`!XE>>Gv4WHct@f3Rg#+`%vC^X z)zR)5{pKVn{9LD2Qi*T zGC-QfFXGL5_m#Y{Wb-R?Snjg!497&mjZe}{PGJh9Naq7`9#CvHX_{g z6i!>rVDLh<*Lz3$c{uz@gyM#t@$x6;L=AK%|8njH2DH#6IX+x=m}XDH4Z@^$k$84i9W!w!5^1$HiaFoLs_G zdt9&ZRxvh(DlF&sNrvgW5yd`~@b@q|Q4Z0?mTrl$KJiF{dLg6-PungTE`dT0y-Ts6 zibNUQQy0)j}Y*gRzpgRxv+GZ$5hY@<}y-%(6W?K%hsw z?)Ecq#+zt>U$JM^Z$@33ihJNq4>9IPXum#!yrY+@*o@j1joFfXK%$&Hk%L#-7`8@s zS@-#Pv56=6_gj_mNsnZ-xYE7|f*FQcaDG&@pLTposPzlQaV5XBdqK#Qd)&>AUHnSr z1n9no@m*GjG`Q~*V3GQnuSHTJ9t5oUis2i>fs^`BJW9iX#IqRl_jx4SO;qR0E@|&! zDWum8U+sCm+sSd!P{zsLLxwfA@8cTjetSy8qS4?M!@(K?-UO}GYSJ#cL7-6*Ch#sTq z-j1PF6@8b1=|n(@LNt7a$4GWaT(zrh%V+(vp+-udb5X-mP4zcr-5)dw=`28Jb8 zLdfp1ZGi2pkLxjnfBbApsc;HHp67RPbX5?5Wk&$W36l8T-efRtrCxWM-iSDv%fw4G^Hm>X+ERYC1r|?lE?a)#`?XbZhR$uGI4@p6a`&X$- zPL0(Z)gM}}PsBsBxMG^eO#5%b{kcA?L`qSHM<+l6QX4Mt+MJgCaI|_5fr@>=r~ZIn zeofWJzfYyA5GB}x6RmytHLSa`2qPo?9p#1q+)p5@c#D@OplJXy9D$O`lf9T`a5*(9}(LS@-ug!}TK2+ z)LnH+HmR{LT0~(>+fQwlpw0dk4sr~UilUWOtN@I{^JYp^BdZ>eE_cm*?#_DPf?&5g ztJr#zX1Yvp$VLZy52&Zcg)Ciy4Xcu z!T0UophNGlA!oL(eUOLjLFNG(_)UjnGiMzMZfAMdYo-1udk|KG5ORx7qqpcet2dqykF)J4-$Z}cxlPXjr#^{fDEc=kP)=YwUf7Ynf zk1YIi{@#!&LDmCN0~@!wQv9EKKF?0d*p?^ctsSizr=F9URga@dL+LR*h#D`i?3>X= z_ZgY`y0dBj#8{8h`@(63tE)93S-2yT8xDh`KMKFH$IlZRDF}OqqnBpb?y4tfZ78OD zHo3+Hjb}O_()+Xq%R`TRoA(|#HTFTu;fWH&uA;&Sb6{J5?gR56EZ2Y}-e8z5wz>ZNzfwZLBGoe<~SHey&fGgDz zD@G>^_k1k5*lmt~ovC4rh3#fTM~YWmUl`o&FJ+A-NljDwG6(qQ(z_W*t@|B(wbH#$ zn_(RLhckAkbzs$wFR&)IujsRQL>(cbAhlH%CHmARh477AN{LR53RT-qH~>T15D;Q1 z-P0&w2R-}plK_HmaZ^=Z>}Lp2iCLGy@9+ORHg~&v*h^WHl1}1O?60HT0r%SarjF2M z5JtndfQaqSAjrX50->i&y z^baqxgKvI)i1i9!P$_yAA=#9`wNLXo0;r6R)F7>-ouWZYkS0a4!$=0plX_v2 zms284zK~@+fa4tCV>Eanc?LS?D+1~uxb1EoMNNx<)Q~P-xIn0J?>^lr-Rg)X2eV8c z1#R-7W02qoQ#|ns7}2j_M$loWPjUS6Q%RF(W_mV46JY7a&w2-tsExtJwR1Pb2=BRa zElXeX7wtvO;2Ek~O;Y@1Rjm2ZhZ07H#G{eC==Jx#s-pQEs`DRk~X8v4C zfarDLel&lo7NTYV@Eh;8m2UzaEIb1FrMXY)Aq@qxQAyMM$z6HTQ))re)!8ALcXUq| zSs3Y(gdAKC_0~4Ys}n_NRM^>m>bfBJ2$_Az?JSEZyN-h^vTxAkk$LJkGbU%ZX8F}Z(@eJ3#`KU ztOKjhgyX7{SRj(3om7_<=c_PBko4b-yCrTQzpO7PvMj?&E$5oXIur=X;dz2<)!k%m z=Aao35Je?*I~}N?Oj!TK7D(ypo0NC#6%GuU;W0W;;K({`Kr>z)0sq)#u!J!AnE*M8 zt5#c;&L-xUXZUip5>q~r@Jk86^UPqHirYL=9h0|XNojfbMD|N)pKoZp?S^k4{nKx6 zBw~PtX-2~vc5HHtqZ3bk_gYszXxv;<76i9HpGfUJ^t_UYwlDP6;k4*~+zEGHH~acB zmcbCvWneWOh_|s$$RCsL+Pi~7hWb41=tx9wbi$X}$cG`JQlFZmpwnFw1B#B&!jfAs ze%Fr3*6}vc)UuvfkN6}gq*WULGGl+FN}cot^a*BAs8HH(>?sxt%vLe#8ssj|g7}5S zit)!0Hu8Rh^MZYlJHyOI6Kp%tgbbO51G%ZN4bl*|FeAyVP=_)3W4Vc{x75LFw6?%b z&w|!OM4#9lU<7Y&c4J^c%JxI)_w_RhP0Zr>N;=pcexTCxry>7pk_aMv2z@acoZ!ig zCxz^kF8Im!?~tlWEXp1};X=umqv3QoHDH2PN#M9B&3?+C3)A_r+#N{L%ESaeh$!R$ zBQ^X~yJzz9=qH*Nhz1}RQbcxHvtIxrXfO2}?&c93K%n#!=9&n?e@F7zPOmP!G=u)R z30hrMf*BS5k(NIlu)?-;O92f`kFy+AzlcA_T7VQ1#BVv8<{^@(C-*kMIDfv`EI&p3 zfEXB&xi7KQ*{{)*$=cip-$YX-uTVfN1jtSm5U)4Q?wDgBYraPD&Coyqe`d1I7@j*X zPvmWf(Ny88QN+U;n!A7QNs)IQ@Ox!}KI)yXqQFDFaE;W5rynw{FT1it5ssH_`kaGp zp&z??p>=sAdvZ}GBf-2S=*patuat5RC%bUD*DJGrG$02JX0v_fYx<|@8K>z$tJDc6 zwf;D2Sdl+BD3VPyh+yiNmal2y^s0DOmBrEb_1kBtc;~UfDp1_`JaUw#BmIj?Za%M_ zm{aRTFr5N14AY(7$7KV?oM2;EqCR|!Zc`-JcNu7H$Gv7Tb_EgTw5M$3rnxLhjE{`- zcO|IV1K|gs%FD`Y{v=%r%(!68`|qnkX&qW@sLdu6Yx1#?u0Bdt*q zES{{RYlNHfP=M=6zdF1ua~L$M9U+6A9P{FyJ?X?gE7@=(-25g+6vkP~1f_!w4hM zg2`mCuc`Kix?~6&`vA!V{${K@NJa&c)Kj7*jBKO>H=plDI6ckOu|s*ah|Ql|sU5Ht z)Rq7RbzZVIxD6Pq3*q84#c}HS!`dwq_if`)wf2!uM;BRPK1Hq2cyakfGLa4!Kw7K6 z7f1pDuRPx)Fs&9qLj{n5hXIm@L3QjSHgXPa!$OLEE!wAbgj>(aaD5l+6MItF8_knW zvz&g}7_`mN=A{v8@39PwK3~Zq6Oa74J z?+l@u@k&Su;u)yrlqZw+LjfWx^TvheVMD}^XMvvr)1I$kkD3wn*>FE`1&>f@w3nbr zvi#1}U##d+)5n-Eccp-toxDP`-*-j^edD{DdpkiG^)S5m&|pPMnU6T$p? z7M5*hc1Q0#902x*H(pne(mbCnP#Ir3CQE6wgm8}sNeT-kqYi(91ZP1bG_*B)RH4cE z)Xro9ENn+g_wO)`xq`>RNW~m%Xc~TK<`y>Ugd#pIQ+feH2@*#~p>tBWU1PC&-OeyQ zHG5`26SHsY(Xc)#1x2hnWO199DkS1rIL%eHAP*Groy%%e*7E0p#^CDmnfu{>1QnjG zrq8daOcW=G2;02L6IFU!l_^LAbVxyelJ~~GbnC(eq|Y$=zsIEAR4BjgEy0mj z0H0|*Fr)0HVv{T7k~iPwFGr_#XDEIH{B>qYWt)x8N>r}S#hQQNAud)gM^xYmw>4uf&IBJwCX`Zg~Yl>Uovdss?7_Upt`i; z?O(G__z^eG^bYL%p7VqAA+W4?rj@Qj*>1USIUGlM84O-X!Ick1AFv(cbv0Bb5A zfxmNNm2EJHTLCpW%o{rCkkbT}75 zUERiR?RA9RKYQ^rH;jWO4S0^AhO-SBb$z%bv5efT_LN4e+o9H)C4xeP4)l3s6c zN9L()G1)=;ruloF;*i3d^!~m6c;*#;03LMb7nM}5J9L(xqN4L+=sxSnykqv9-Ao)v z?}IA)pd8IBjv3?(+3y;x;wab*%9Uq2ITyQj(1!Vu@qD%XF6|ZV;3Fm>_{~vMJPL^E zwNA)DhQ$bc2eiL+nu_!SFsI=?dV_2XU+Rj*4;rwypI||SQu*bl#Sob*KGga(5~{n6 z(HnEBgN)I|8@ot|TqVD^Res69bNnW|@lLK4E;TevNrRGFQ zJ`xy(Jss>C9Zqj@@h8@PmNsImw$FG*a60(L@OE=8HVZ3Iqm1Ui^K1SLwTM(h$&)m} z2~C=neMlrHx^{Z&Qc3ZrM$~Fnkd^xMN=0_XyJlj?0^B3fTuTs~)?rjz5PCLLIB!?A zw+TCetj9SmlYVt)j^D*cnS|0h`g`#+1aTL1l@`OtptbZh?67XSL|&o40g*T4Vs`={k?F#d`B-}rz0 zdHIJ9L)8Cg`tR3&=zo9a|D68&Gtb}4`LEf(lmByh^*{bJ{qxTP{`J?s4FCPV{m+H| zkH7v=wZrhQzoxec|N6)LP4jkp*BAclAM3Wvefh7y{u}i7&wn-ib7-eBPrv{AE8Dm2 z|JB;f?ewp|#&#>0|K0xgZ$taOy`AvCTmS#d`RCadf7b17*p_r!t9cpUd8OOZUjH5b z59ocs|M6!l-{=4MKfCJv%b$)R|Lg62{zHfU>kWE4000000000002}}S0C#9_Y-K`kWO+?*WMynGN?~JfVrgM+b1rjsXSDiP5A#5h zC5Zl&LhZ{A*wyrIwrdvjMijm1-srve{PmY#wV9r|v$(jxtOO}ZDw&ZP8FAtqN&oVH zUw!wNBVX2f9RB`S_@AM_{v{vMF{_92?|=Qd;@_yh{@?%YU)H1i%UNez_4mIb^gp8n zMfUw)|5D|3S#AHrrK8SIcD(-nSLiR$Utk#i^ZM&wUK_*u_rF%#HvLx+JkRr=PxPP1 zr34WOg1~q1f9vvJudW{2|5ZnrrfKjWpZ@i~{Y&|mqVBrC|8*FL{I7pmw`FYezyCGq z;|M$Q4@wU|0{|WyS z^gjRb{$E~Wf2{l^`}<$N@A+S}*MtAw{BfuT{d)ub<@sN)?#R<^T>h39#e48?69NC* zzkua``OWgWVDg`k*CL8w|Ixz8Yx2(r|8amo|Nps>`Y->#6Z$_w_kTu@WZ$;`1$OlHmM{Nt z{U2vt{WdRP{(pNO{$C*1|MOP-4T150`WsCB*^j!9%ltpE`1Sr@|1vH4nlDGrtkdgb zJKpN?-xv1pqyOpl!u0E_xBY{w|Fv53;_rXW;w}EK{}>XShVuVP;x#9*f2uv!uuteC zl_T>$bmvzIzw$jQtoKcZI3|2sUV}H_^QQwBu!3Z-;9fqyw8ax?{UcponU!3 zHW(M3k!5Qq1K{JjVGf6Zmp54|N|~0T4Y7d2ih}TUn0eImW&E%;!+Na1GNQ}btk&W7 z?xoG4qTOC)@Azi=qgsIV6ivRivK*gSjn~l2LZz)G8NX1tY2>G^@xRu+!C~KyQ zvXfq=sas2+OyV!&^FQ?%8DYy9yK}xD_D-fa`cS2Z>m)UC02lUJ#EvZrG5n|b*Kq^! z?aYX{ABo6rwS;DX0o>xo0nCxXCwV@at%OueWyO_Fa=ZnFwNxpO(qmvHLaO#WUz1Ug zJ>ByWPsYe`3&kv@tUDo2Ls;250ZzO$bbgJ6wldQQs@3{OAU8_adTm&G2WMB|&z%0u zKU6fnT{#bD5yZPN#3>Fhf>c6Z7P=XA?DRkK zEtj1WFDzD1SuMJ6Kh4n>?lKZ*is$>=P~v5mf7YE!Y8k$Ea7K0nr4BQd1#( zi1&kfjMS$g@fRz{beCuT;Uj5GStH7`^J|3X9tN8iPMjjAOiOzL6_AQtS2T^4^qI`! z33Ca-NP-iq71XSwt)fec+ae_kBOG_%(D4bugka&am=lpQgR;m8@V6<%v?bpR{!c9&VVg-pT$fhNyU*sp-<0c@1r}Klch~87ctB-(r?* zG&RL{MC0cye5aX~4L4WJP@2b78r{rdLz~66Ur8~uUNRJ&*!2jj793;%{xD}!9;q9( z%g)CDUFP#Y=IF5;^4?X~-sx1I28f+5TbvKBTOkp&+;gGXbD-Sc?Te>Tn z{7pzOPBOH|mNb)mc!O(~n&rDL{P26>W#zJf_HQG2+|L179^6mAQXYD$x`%)5%#l_s z`Jq2f9|d{jqn{R{LldeJ_M`$9MAygs9*OInBllgjoTrgvBk-kN(lXbY z9$bIT;B65AOO3TV35*E^y<#!S@)d&%8kZqdpO0h6CwF|aEI_8jN?K3@E z42`tbC!S;?Pho&{sC^LNwW*R-F;4rH{)pk3js7d+o+w&*-7KlZke7Ir1 zwRX`kO7Ld>7<0o3H_?gqPP4-yTm_s?{xsmyEJVRBILgU; zhW?tRIOcY04JRr@r-rL4pYb2tXHFA^G|h3MAZW^nDxb#8ATT95P#aeMyJE6&o`S>D z3T=Ht*<$b!Ee$2>J~+rWR`KK~<)|-mLqCCuZ59k9ErChjD@TLWCaisGuZTtg>=faQ zD3O&Vj!s5gbg#9k*j;Dx_TjV5!3sF})lVb+xKr0TOu)O7$>h_qSSSvdbO=iGEL*W; zHscgkBXW@Jv{tjbLt}$W^=rTwCNaIi3BxG#Z{_(K`d86cIni22l269@z;(pbTN{Ka zx1PX&t7KBTVa`h@nG{v8ixgx+vD32*l;AD)RoMl$FqsT$c%a4uF;2WrN9%3nl00c}|^32(1fZycmdNktBX!FgDat-}fenX?Su#&zSKl ztq03n*_gz|t|BQ)Umr zzOL(cYr_*2fYNC~w@bBAgJED@*N_o0R^>yZ;?NE%>Z z_Vq@`b&VJjV`ngcXq9>ikHtfsK%z6#_qXl4H;=}P24)g4Tiv}eQuJM&Z=A&^g)FqumK+i9_k9}LsVmCk;&dIfhB`##jyi=M7V|taw^f|QK4z6>oB>n@^&GP$* zos7^S_@L~~-er-8w0VA{;jYCgOJxY|_@1u?bigb~ZbM7bn8%>_oyOT7_tv!-hRIH0 zvqHi``Y3kwDai!Qv5zQXaajNsy$u#W)-u^%Zh|R;s$;$=V6)13sIjSHZWo;htPN`v z2*YWYSy67}6G%oq??A~pu|~afIy!)?B*z)d1+QO00-6V7&-WzkGgaZIDoZqYK$zL1 z1pJ`mL|s2b;xXVue_&cSS*ZE_*>lp$h!YD74(f4>L~o^05^GbF;&-N2mD?Gx0rW84 z7C_pRXn@U&@jvjJZz3Sug$gU$3d<(U5OHAE(wr3^(K1zEsGy{Mt4{BC-OIpIpLLA` zd2*IGr`5s~&Hh+Dy){6l57?Tet%-vOz(trJy&B|TzP2fUV#=cdCqmQ(8iy}%BmsC} z+IRHsI10xz!XhHHkpile0HM)=uclm>9sn^4Am-crs6PC2w7pjqykdt~w$D7ZUu zy~=cZDCMnNxnZh&2W~0+={6M3htCP`>DH?93=>}PD%!3p zVk3PFjwjazxb-i~nXpcy-iYTmi!R)GLoIVlMDb?ra0+$|48gMib%748@YO=<6&mbP zdZS{H=vF4zG1tbMi;pn!S5aTV_tKuR(5q=LK2t}zfjiMwOyh$a3ZF>#MC~Q9>W>fe z%xl{A_*Q##2(AfB3+}Z<@stSy4Gk}Pk(7SXyhKCQqgyQ<7){vlN9pOcqBEKs zL1)fkaoY1F5_5a^Ih~9S4oDb z*nrauq~ak5J2%FojX{fl)t7zF4VCF4uR*Mam*efpORMi`9fYCB7%!=%fFJr*T8d}X zEmAzj9w@}%P@(2O4kX{WqhbMI?fXr%;`O;4J?0QCAZOda1}xyGcYgTPvpXZqsX$0x zIe#3af=Y0CRg^s8YKPUac8Hr9~ z7}YRUxu%3Eug^Y!4s4mqYBNr`(vqaJRx4vo>84eNOWs3e)1tLhu)cA^hg~)+E2x8k z@7sOxW=x$liVQNq`MH$~eRf@25MwK2p~>r(bARQFKuVEUmC__)@k8q~%Nm{@4^ise zhEqDpq!kP`M;qVr8s!O$b8$(1M_NiObl?1oDIkrcukyVylTLpHKSlY}r(}Y7*p;>c z37Y5Qn&HB$AQ66kz>hC|Qa6Z+IPicbm85`%%0b+$OF3fo^#gdRha$5GKx(!qy>SeY z6sv1=rv1K-^>HKPB+6$I-b^fQW25fX)@dYGvrTPBz*SC=1+P!r*WwezTyD#SJ~0PN z5ExkoI?cVzq$g2woLtG0HE^ZXZg{l2Z* zGX#7Vmq3o@eZSp%219j@o6O#MyxMBDf?3Ay?F1Usx%eX#XA*J!SEt^}!9j;w+2;vs z!P@Vh!#QuGj!;>vZjQ|Rm5Va#pD^_UDzvr_Xo`2mNNYyNGyL5PEjk*6rcGMS#+NtN z-)`(DIB-7FD=P84hM>E|mt&Q_=EQw65R>KFA`4$aejIepsXhi7SZ`!NXgYz!qWqYF z&pBcKlIWF9Z=hrqoMFywTK0i=fNB_8`_%#vL9r2jvKx7K>rZ4#+KYB~SOGa@NE_q< zin7zUx&r`)h>Ri)nh$?4O8*fKXU*QPUQR~^z@U9;AmC^Yr*eQ0mJXsTy+H{GompMw z+(JoYyo$yV7_jD0)0M{n={MuugI`aA2TDqo`TI0@`qYy`T*t10T7It*`C&l^b@aEA z5dLiO);@zlRdZUz1$|x|<_|eGdsfi`A79Z$Y?M#Svj63TU>1_{hmrou)E4*ZS}uNl zf6v?>oogh;tK>x*<0hG667y7ppFib6jwT#gI;K;CzmMw@RzZM#L$Tb3(()oY-d#nH z$M7j%mbmbOo)WO?;ObK)1fFFkQNAid4!d7Vf0=c*)(Wa5Ws<(4Uf{A)Z)7^`luiH& zK=r?)3}-(b1iB#Cd^g+3>QZngajupFR>xmo9L=wH{q~y;qX)7>>f5~B#EBn_wS%iK7mSH#ztlvBtM zPZPqzL&2_hbV01-4+r^}T3~++gw5o%EIAPpqt+#-ThlM{yvFPT=2He_KJZF2jpPvv zvYGw4ANq43FXqbtTpk}nI&aYOMBi-VyPb>PnX@EmKKdwR->Ppi*o1@efIb@LMvkAQ zhTtI2^|D6R4!>A;>X$~y-K`e9)H=S2;6HSL^Sm9VT~Mn_EFm|~E0&#Fk#GU?IYs2t z->VnmVr+~8odeZ{q#TD}oPXp!j2H*=S%HwwgyZmt(Kwn@wT?W`ONQdd?*Sru0%T-& z7%vobV2rbE5S3J4jKj*b_=G&q0IbWPt7Xi?L5UhmT(Er{1&HHg^p23y?1uo)eBc(p>x$ z(<1EH(h|;=z9hg%U{3)w$daA3U=_}g;B#PxSm?F#EUQ!@A{PzUkO+zkB`w3W&m#R+DaMhIN zs_OMHeBCkmc%cYGPbI_huc!6h@Y2NNi;5?~x%xy5#Yq$h9k^Ry3Bvn(VRe`-DG(FT z)(Rgm1-LjbQ#spHR5x~1Jv;k{ni6*+6QM?tjlhzE=-Dr+)w}&Gf%4t5$7+EHW;qu9 z^POWi*4btOZ++iQjR{Z`k_M7l9&vXyd>S%-ylGyxRJ~W!UrQidI;qy`(lj><+v?3l ztO8ts#vTnFUOsL#NKji_A7fgKs+?h4O@{}}Bq$2xtQTjDA-{E2K!^#I@so3#8i$pq zG``{|U9XpGT?Bi`j5j${(1yjj2c zUsClHq@z8390R>iG|g#gv*fZ*N8ie?3ctP&0J2z}%EM3d_mk3=h#tnF4DqVWgI9zm=~)scX_ zLC41-Nj+Gl4JzS{Prg1SJJS|5(6v25j5}=QdZ#qB?|mc3Tcl>Vj~HH7Dg0uyd?o53 zrywqo^Oo;1h9F81==-<*ZF<#*1%y_B{fbQHEn8VPt zMnWTA(}YV?|Kef-O%(;h^00^nB(Kgzcpw4lm!GA8uwuDldrV<##KO{bp`=C0;XP#T zXvi=43tS>?g6;tk%P(5Fwj!|V`Vb!s;U3Wwx~zDzNa9q)TjJnaWeZQY*Ij6VeMTp{r+-}wtSpQhs2M&#yIy<<+Ey<0@=AA zQP$@^LMw^Cu<1Df3Sz=#0ma5qiZa^!NwGENp@>uWr#ZnR_*!AS>R(!B(OtpdsPEm|L7g(8-i% zS~U=OUHwX(P`#dbd0R%f@xA6fRK@J1!%IU8>`!n?w9R(~9z*PghT0sPtk$aSPE_B~ zFr~7J^vdMh*k=p(B1 z&}{4S(6FL2MwLVMSV`%WSAXv62z8aQLH_47L}2f;twlB{kISG7UaqPVfh&2ktW7oW&2}tcs=tnQ2{D>?!5}pGSK_ILNbBh{Z|aNbNf6j$g=!R``W^ zsKEjcpt6C!HXN8_NYlvHgOJ?c;id)OeJh^+#=4{5(qckR&JT(i-;lb!HHz^gP;4fV zw4Ef>DWPSY+YH=uDaPH_UwJ2}UvEYGc&DKT;W5AP#Wh}#n@9qZSPjjvA4ee3h7WKya=)0VL+aTJM%jM65jK+Zm=(DC*Z**$Zqcr(BNUt!8E$?cCg_vGt4#3CNyR&4k+LvyFaSLb(ow@i%+MBi0WAxJyu>x>fkG*R~M z^y;xtE5eadrgK)m^?pXOM~F{AMFd|vmAbCi`;qyGEBt zVK*54dW^L>4F&Y?LT`*MY^atV)~>PpCUsWuXdzgVorJ6Krev7ju8)X@<%{GqrcE9D zA)4wwsLNEHAeo`|u-Sgg7k9TLTzb07N~;8dDN9q4LFSdA zW<@SJb5j-)oLPDLm6iE^+j<>27&?%BQy3PMtjd7gZ^*ofijcYJf5{WtDNxb-og>Xv z{MF@zBpT|+gnl>8EstMxH;+UJNO|$B>&A zIE7_zp3!bDoek5_LkAE8h??J5(r?6O_>yi-h1y50f9f^cz#Uuy)1;-=Y>vCF?T|Al z%PPglPE`pNMff#>0ec$2JMcrk@9Opse30+K!y_5~S~vxMF~yYaMr^G@q;wp$D@h|Z zQ)%P8!N6~maV`dYE6leIY|gUW@|B{w;#L5W;XT*3YBe{>ypwH6%;E>@r@aCnkr`?c z?ofyu3Nf(tO-KCIc1P(ZojXt~O-ip(AM8$4&pl>~yGfOTg)fKm+^{%BdR zd`2+=Y98Gkv#{U2)4t;s9+BEYbMdEi;+)0M;=^gXP$_cAp^L$?uwppxi8f>O@wPA4Xfrw@#w?q>vpV&8CZ$45zYG3sY+M%>I0QZ$&N^`RM*xw z8GSjOc$VR0nHEqUh(thcKSn3|eOc(rz}~`+(u)dT9C;_QHyJ5Knvn8xt&n$W?dsDT z(k7#)a)rJ^2{$Pd%MT8>e4fs(U{YVICd4fYtTb<j`8l`NKrlDpn+n8u zSd7oRYG5A$q>jrUfsFB+4v(WETLqnx{Hy2)hUD+v;B}h%1$_piyHZ~w4c%V9j? zSIdEN9`|Q#ayzT{oCpjTL6Eraq0y2*c}9|`hGGJ0&Q}i1;AW;=I-H-4B(y-GC@v8>EiTRE%xH9fOKJbLpu$X$H@q;QU)s;Aa1drg`a|T2 zHa^v^u z2n_I3^l$ksEsQqU!G5~0qWo-ycSN)5KWx=n4(-lVkSOqM0b%^xi>?ao9m4}s4LyLh13 z;TQN$&jl!cL;A>?T8L^!uV+g>i8kipWsJvmtPfLrWuOALiu{5R8HCl1t*|eyILwrb zEbY=qeDo(=G{Nc(pkntSf12NN%kU*$A5tJ<{h&z6TYzTDUCA4Lr5i^XJ7oVOQw^gV zLR-^n&>GQ?$pmzw^`(CZ4bZ?pKLBi_IXbje@DUxSu@AxE?PW71+tF>IHu>w{*i+OI zOwU7q-DTJIVL7A}EUhYedk);u?IRRbtHoMT>{96`4CZOF!TIB^VDY-gx7i27pg^~K z3($?Foc{dr^%Vj|0OBJB_LL&J_91P;^~J!V6tFt(LZ4vF7t~|KE=n2*@qXDv-g}jb zJ$(X>6%PDZhIDI|tSa^3!|p-w(^3MwYdO#RkkQ|CK@ z+-#fYoQH(f@}kFUK=f4!6r=O}fjxTH_*%jhicdt$jL}N?*0B3`<u{3hIndh50Ft3{g#(h`4|CH1#Wjfd%oLW~opi7u?;l>n+CnSrl~<4yR*YToQgemDJuh4q zNH>m<#24dV$_hYcadqL>h2F$ErzNT>O7@o=wBKO{+}`)g;NI5A%4zGDSR;5HOn6DN7PPFUMS}Iqryp87 z_b;5_A_~)#@NwzTob?$(Q&~P9L&D>o^M3bB7)lHrwq}y}e1n|uVtvqiuC z;@UYq657$|p0pDrwKflZTXPTFofIFOB>_Cl7>$)zf7VfDhBG*)sb6=1mC8+}EyRuj z)T|H+w}CcTg8~_Ostw#LM`Tb(qv8ZRdx{ce&O>Q4TFpnNf|%g7OFG>HXkIiV?)Y#R zxI*o+A(B>NG^k=N3Xjpl6D^dQW9N9!B~oTbsn@T}?2dc{fh5T}FxmXxKOIT{W5P3| zikx&D>v#J_rGJ}y_0B!+HGC|q!sPKbxzlNdvNB7YO|;<|%e0T_iYXRT_Z05s|1WU;hmWB z(5&Fkgt1R~H%>E-o@>3WTU~LYnA`;XSl^e|oI^=BO1cL5&~-s~5h!8r?I(&Sl?cg% zFrF*XV27UzdWwBtCdzeaMQw)m&YSAv;}k;uYkH;oIt)^iL|JDY1A~&7IEp5jCmKW{ z0zt1rrAia>Bnt6J^@yug)ZZ|2MJ0X;<@vF`zxFr$F&;bLBIJH0;4gNxN2L!R`!>&n zA*j@dS=&99<09p-@9`Mz)a3%#9BC#$k#}$ncm@?2$tL^59I=66q1tEiF9ezV4H;L~ zCv%G6$VGqmu&bSsJVq$=FIfvAoCZo{(4)R>!&y8Pf}ahorTm^5J3M2g6drP1r<)I- zapKKu3lTT;BSo>3lcbGSNTpcP_*-p#dKI89q97g!_*O!pS;(v@NQj9Ap{{q`Xr~xt z<H~B1*NDaSH=NMV&Zfe{F(0xvLYE62C>P)ot`hcTyvFcgnxb zz+E2-knl38{m(v!k06gXnIM^&Yqw3<7g*PP`YX8dC?YrUYR1PGTyn_P^b)!$pnIr&KVC-uA(PcC;Jhv z($9$&P$j>f!@I7xXczdlaAZHXIXvZlVMf=+Jiz<+Lb`P_*Mq||xr=OJZN|PFpweqS2|6Xzt;HKmtp3?jhJ4`OR?P#O4IjINKzJQZ-l9(OM5bjH-YV&~ za7mUAT=-~+?Tm)sxy@^(US9K^k(^NBq=6M%AXT+ZT7HTxUlial3MFrK`QYELQ<|Ml z0jMkiHqmH_Vcv1X5`ShZhdj>RhT8&-UCd{U#9ha zv+|*IrJk(cuy!dy6%QP1`N7v4G;%FkoMzyId(j2ZOI_-hFMOtJNBz_b*~p_!d5NA=_zfctcJxE_g`Yt4=f-&X-tV`wk>u1@p#>-3`c3X4cbkSKyf6%0bB%+pPiX$&jQjILgtC${ zC_G~We{+MXIx7Z%%HXx}Rod#4#>PN*=wjD9s3p)Ix5=d&l^#Kv=)i3ZSoye<1}8i# zgZ97gDn4^`!mK|{)F5TP{EU`JtN^b@;zJYqicY!BcJhen#%HNfZsD)Pi_Vui!f$0# zieDN9S<9sefSGc|ixEaUI_VuU%AR!RRgF}d9Dol;uj=xi6%#<4D&1}j`=C85fvA^A zvBlzeDA0R-dN^aU`)~5wkoLP3i} zL4QJUW3(72y<#rF!A995rKY}PQ(k4Z5y)Rm6a$JPe;+UHTEc2*CGX>Bj-_4GQe}pK zH8AeFBB<(TWAiF6lrXPT5yrVL65ua^M+RYEK#7*%ywy8&i8;PxRUE$x%>IPlB_gz8 zK3eAil}7=rTiqloXHog;qRx>ujsnb(h<aloGc=-K{k!Ya+ zI>-Lr>RM^@RQP*QUUWMA;xmFvoM$jz1c_tm4~BVp`38?0>gi>ILna5GK4ng?mz~>g z(fI|r6fEOOLcX$sx~>Q@{RNCy=LYr%+(TPdVkG{2*CE`1tlIkHv-VpiR$TFcfGF)U zQr;ZO!3lcfDh3#Sii|>2NpXg;FC7iJUwpG#DcagvurdG`5y9I@(jyXEzpJ=ztk$At z#<-%6%9^KdC#NV~g@3+mxzjQNP#LbRFq8ru0LSoJkN6#|@3#H?wN7yIYQoZLGFkzG zI}r(2vbW&5T;uZZyPO$pHZO>z^HS}CXM%&~TZyclp)X-~L{f^iWH^n|5xaaE7S*(u zyaXR0X4G_}Xcbu2#>PYy1Y_YO=L111(!}6P%?M21D1!PvOG_*nymuC1g*Z(UF4>kq zlBNd%gpp4XMt%E}DR}~6Ev-C{z9K7u>zeRo1O|@X;62-WNW2+&N2Mn#A21E^bS@~| zkA5EGRrN@J8mA_3n8Y}a2+x<-yZkvOsqz*|uGk|FR6?nSd5|19SPgqjdCYmsW|U42 zOuq{0enMqMUJhR4+6XSm7K9{XGwFhG+*d@!n5&oK>0=E2y}{T@v$J0e&JoPXwdAmI zg!9(8D!8{H997mk4*Sjn;~10{ReD1WYQqd>KY((HTwq9IGhwcy%~YxP0Rtb7 zeTO(!VaU4UqB}rvWzfG6dTyJO+ki9sS=}j9zqH!vMB#$pt4mBZF8qiPEoWLvw1hV--0BiBri}^by$k6=zw@w&m9@{g8tt!V_$Ij}hy`{^;jpKPIS8Wz@$t2R zIx4U(`0aCG4L6eQK&@5p5zx5-#p$}rYIUcFK z`5esEP02A4x+2#>+A1$V$xoDX%DFA@1Ycm>GbgXamJO7$5lg|Rz^>6`_<4X3Cs9blX5mR+EeD+?Mx zeOh-XF!(Vxm3@_V`c)SE262&kNcDXezCO(Tx{)~iP=$l;Ix3PfQK8 z>I2(ySAk}XyhBRY1()mXwrc7#^XsSTm%=zZva(ummU6s-Kvpm)uWPSqpZ(A^aS4UP zbr#3LZemNZn|g(6O)YQrjPH3_RiCKZ`X@W z-l0JvLwSokK{IgRdG=PzGA7UPLPI;>%0L__1U&ZzmJ>nr+6Dl^YHRX*4TVzpZRKT3 zjqsJ?7Yj#|l(hc=l0zJ$$CqW$4=DHnb6%O*J0a)!kF# zg9F;?iFeq&)8Wx)gFxv1fY5LMAYMr%SShvfQ$qb#>re9KazGN{A5B*BdNpvII{gn0 zDzt+|MquOtBPN&{)raOPTA30+za1YRq9iLTx~+B4tTl<66MP08Jx4OgN~|>&l)I*+gR1)}!Y7hPK_2Ta+GM(PH!HR37g8_qAhmL*j;Qd8=gH+9^w z(T`+(sKlGc<%&Fkuw1(I#_4rXT{fcR7U95We#lh6#U>F{t-<);i?hCD>igR6SBS3~ zbFgnz)ZG08VWJjo1}>moVz+uBebp!p?4$$fxK>=N=Ru}kJZTOu;8SzA*wX-?p=6V0 zl)A)XrKdavwXYN9Zpk+j<1IU#3X*GKx_E`5wE_Hl4kNp?6s0d^dSUaU@YtNd0{YB` z5q@-sLD9(;fferL$!p8sXPzaW7wa+t;lZa>teSk_mti;R)9FD@iQCs;tv<2XV2wQ>0LX? zUBv_czQnu!;tk3XF=P!wo=dl*?{_*tSP3>X2bWydmNI^fPImFAEWOc;pokq8`S9k0aZ^G%S88m*#2)^yX7sV$?aGR?HI`<3n1 zMIDyOSel=W;7YEc6BPH}bpnL03G%pd(?xCia)5GyCX3W{_Xll33Q-wfI|s1w*%Sjg zs*i^0`gr_~x~tvN?H734GnC2khOENo{HQwYo>qUcQs~;4Uyoz^eluI>)>c zh+*p?!D>$Fb$JqlTCoQ56u$9Cb0!OypYrEN;oEjdTHZZI`J#{#^1YX+_r=uLgh9mF zF?N~o-;V$T*%&zGka#n}^eHog-3wwpXNUpqz$Ro#HJ*U3ALYI0NGurd4EszcJQs)3 zjrPZ(x{P8Wl_ITc$#4h9eCyOEiS4OehLb3HY2r4*I|<=t12gUOnFej&UoTHlU(HvU z!pitkqC5R@Y}JmpIPW9)eG|deJIUx}b64l!0an7Z4Fw3N44whVIg5lkNR7hHS)va{ z%LPb7)4Wid)SH3_xKfsF^?X=CQtNi_%D(Nv3UU7RjtJD#1%iEW?oC##h-LDwi;D z3ooJGG_$wSpN6sbpl-l1F_rh?^(bi-@7zt)F%W_?af3NMgrn0st*ojnwdtg_Px>9) zwe=p0Jcb%#mCSeXv^AV12{#^44|r~`ErC)P6GX`V2pam>Z%{XbUMPN}nR6C-wriB4 zI>ADmnjoIvR&9-D<1nVDghK<^#gPIw&Px!cNqqK%nJprDMMbDth;3XA;>ks zP&G`zIltHVK`ZO1!J8S)<@g0 z=zFxg?X(#$w%9VZzOJHMEI4!~hjC#+YbjCsHp97G1T^LQyYKfz@4#%uBf0fT+gQBO zZjSIi2Lyi z3-Kg?aaV`Q<#E1Hhoa(~?)V-ni|y-7ZzNoEIt+B&$%ozY=HvcIIt z>~HI(`#oOu1E#N{$(<1L%E#e!o%p(C-ziU=`2D$0kjYwFOb)eBQ{ljX($2gVapK`r zV=Ts$v9LP$TzpUKd1|R?kp?}@@kyDG>4-I*odS2;=SA@hw!Y_Qx>Zx1A6gNXexxXV zxu~5cvxL@cn+a)3V(VR0z4x`!zQSyM#WQ8lUOiV2V@u7|e?2-aS}cra{Y}TU36eP` zj(99!!BmgY6~B3%<0li3E<0EY&_Y;hGH`}{E_80ZM>cWHNJ$N`bP>qxO}^*%)$g+8 z(6{WRm&Nub^%ch&Za-Q zMwB#J+6W;Sx*k8{q0AJ$h+Jh6>32octndktYx$ ztem@*V}+i0DnAo2mX)_@40X{wL+V856XY`6=~-aqC6qb@{fg@n{?HcX0!sk6bK?j> zxk+=WnC_wB`@F?ccXVWwP8vZ~r7V{sLh@RnD46|}uANgYBQcaUd&0B*-^Wz(vQxbJ(Y)kjKy9qYLEKv#M$&k@(1^H4_1I^yQ+ z{!nHipU(NCr64`B{1-ZM%0-mhF*H(%bp6}fm&Xpd?jcpeosNi)yTx-QzCe zpt8`jK$rfs0$d_AiDnOu@=S~qRx3iCn9plD{`LU~>iKHen?Zx``BS;^Lia!+(?|_N z^EIY}LpZ6$0a5q8fh7Ubn6*5xroq#PNfN^dHX)*~oL(^*(c~buAL{U?0I*gJsWrSN zquQ=U09u1#RA%1!aF0R1p$0VGNFMB+k9d_QRyg{($q$oCnZR@WucjC%%RDn~xyS|m z39x_pYBKrIPUSkOfm$f={9?2a_TNG66x2{WRRNLVQjBF2%&yNRIOkkmyJ=lrhWP16 zy!1?h<|plyrQKz(4*w*JIqjGMqWI3ET#{5x44R1QVycx!MX>L>dC#!LTXD=p4N9M#B)322WR=AAGXPcocX=Xyq57g$wFP?b`L~{wJ7ME7}p-s z7CP81&L#DWpr$}Bn|#Iu7(enY161B*<_jjM*U4A^;mI>j2vyHQ0Uz|jXq3*O9-st- zZ(_7OVl*anF1`j3`2K-qGQY}f^|UZh$~t_?IFDhnp(v97Zu`muP<}1J0mw`$%hmH6 zgK5sXip6-!jGVyCZFuW{)M~>ShF(Kgt+R*7P7Uv9I0Pen%v>m@-2g8OT(HRUz?2qM zgV4-V>)TG;sitHsp(-^6iP5`tlg!Hy&Y< zen$x;EtRWR3dCoAdMgE9hbp?c(+)7-^rovXd*JWFcCN32MKkZwX$;%ekNkZc?Dx0l z(|sMH@a!6HbY<@od@!4C)TwuePJ9-K{e(^akGBzrn!kKl-j?&$ua}*@g-ze z0>O}~mXndQ9S9ACgF0|vEq;nB;Rud@soP4z)tf;^?OXqEgV-n{dLnQqU&F+YHKI^x zIbYo1y^N^E?4WeGZ%ugvze=Ezj#F73YZ5X|Dh!B%K|oIWYI2O8gygk3R}`UmChlPI zu?;$xFRo&MnV*9gZLjkkd2-fIsrX_-o2*6>32t-&ejPPqm@nwGec07&x-UZF40t9Y z_)`l~Fn{FP-BMBFq}F(G5Z*u~Ae^_Oa`a$?+Q=mjPMwXTg`I$YX9px+@W`L`ranoFDsWTW;TuJj=tUY? zpuOc@Q0pui)dSnSw2Q8Ki}$QhJ-SrvH)~|&3f!XuNl*w!eLP+4l4(_HAVX~YO?)$E zCeZC4jcWavTl=B$<;jFs%BM|`So|}Esb2)Q%2SsVKJf9Owgp3d+}H)7A9e{_28G;dQuqcmAs^FLK!&fYsZi%RKj&*F(_&XY*)u!TFsCqLI^$F?J5`|X(8f3- z-JdFZ9r+GJ2b{6^eAx+|&)v7(?eA;-2g)Z0d;&7&%QZrR%59gF#+cAkBB(8Wy**** z9-erIUCnln3(NvRxJE1ji^wVrtugR(k1nL0bVZAX)e(lY!;2AQtEYAlMXh(CBu1@i zn?&B#2+XBUxeu7$7_lp%Qrt-$#<*)?3#$}VJ>Xa!4LW*t$u#b_x@SJWdbB?NY87vh za8DsX*3(Wm@k4dIb?mI{zgy^9!d*$IXOj4w$JMV0eB$Ot!}2NtJGJZl-#yA166c|u zf-ldQqnSZ)%H^#IN!`A^OtP-OEy+}s8E*U#K3D5{-m>4cIq*`{n-^aMeCC$~a0g@U zo?j*&L-$3BG4r)*9PKfG5kW45J-ag3i#3Y%<3vb5>rvIenZFa3JS&Vy@D`)}JSE>; zToxR`uAi->3v4_y2dREh!MGC;koFXvv(}Z>-PN`IWpo$?x9?MiPb$tHheepR#bJ~A zCTL^+hHc2%7ORL>A81giDc;-;3h_%%NrV_O(I zU}_J3lL+4{sZp-4=E%y^M8Hr2E?V6OYN9L@rPm3BQ~f?uC`3j2z@&9l zRJTR@t#q$_-TM2CfJ`^_G z)41vYooY?h1LJQwkAM`D>GL{iHcke(pC6F6UriPsxjapOJNH%nRaQRDn76U=wbJuX z5{Dtzy7%8@JWm%3S<5!z zy7W$R5e`}sNzM)OwwW_CWC{pw2qhRqrIAQ+vi2_$fM7PfUmxD9m@+J>3d2!yo-E^( z1;jiLvh{Y~+Qtd~EWha3NAcXMUo*T%nH(d(xbrQ=pJve*1=1DyRz1H?;DeDDYkIcO zs_`P6w$uG4nKcBsc|$@no$96|71{1ir6OUK{Vm}?D@KP<$eD%qMhg#dJi}h8(YE>1 z{OXQIL{|TODhOMS?*{U=U!BjDqYi_ZBS|XQl?t+Z!5_gC{Ev zjL&qaMC8f5ePh4-9Dz1aX(4_Pa*m2%qd}`NlYRj32ZxzXp+7TFITIpFE5%Qr9LY<4AI!>3~lsGc$UyW?;{w-vMOu9f% zd-$2wR1eAT)mwUGS{y?>|5zNSoPRmWru;TPLbRRLydiA!Emw{s1wTRXN}Le z9nBr;)Vl6celLo;${@m|ZM-7vw%6CQVQHif{%hUz!aE#dyj6ihlnmh=G659T9VW4= z#p^u){Lm+S(9DQ|98!HB#r_a(E*?#WqYwWe7_SbeK-i~e9L}}wl&~QntnP=vHgrO#Mp(zax0hf#o2qu6w$|gw zea_k0Jac`vG8zK|bJO#Mq(ym&HrF+@5(g4NhAx(u&^vJ-^ajLFCUaL2&4?K)i@g?8 zDS+a@;BO(q;*r>QLbR@+RG#-_@wpZfdb+RCUE5M8Ebu8Ou8`v zsiLFMah!T~s%U~rNOQ5aVtSTx0OXsKa&@OF$fOcv+r_bIN(MyC7Cp%;_EZmfPmqb= z+!{Y}eMj1mq8sy7LuC9b!uny+gSPS?z+iG0$WK&{!4ZBXN2Ksuf3?wK*bQKm6F8}1 zY7Bv8cjBdho%qq^igSm-rsYz8z{7}+VjNro>_w@$8Gs9&yz zk%=uyI*4?{->I0yN35r`5oP?|wxe0p32b;^^p4f(blx6J<)ZwaNe|vT7X-y;vIPt? z#v8|9EKw+fKPjy4*x=5r9lwz}ek0y5$Gc{BO2=ZG9%m!Dpy#zZ3dv zr~Ha?wlNFrh}+G7d!BMYk1cw%<(mdR9A733_V8+^ zRRE6BWo1u^tVwCQ3sS>Ej(~<^T^UpPR@8z~E!B@=<_{TWfI{te>{CsVZC{TQ$3Go1 zu!Po?m3xo>tDYkUn-U%(3|D6OI0*aASgZru9zs4Igo2z?IEKD_E|^zQ%W5=t3hYVz zYCmr&m}O(7(B%l+Bn0d8x3<*j{xVuyw%p%MgQL#PBcqOnZlgfSAsjjfq{2#Smzg}! z0{cDgERcr{GMg%Q#2gkYjhTI^PF~}B?<$0Uj9o8&e!I7T_mPWOV<08 zzs)vVChvnyr?W`|NeuOB5>FQH(LC}BYX#VF+C~EC+|p#x6~0irqeGD%&p>YIe*QcH zy<-L$s@S8SeGVo+aiZ*EuBd?C?5xhkC%ji|A80M48aRDPZ0gvR{8K ze%m?VmEn}^3j7A8GbpyHx)a#3+0;Y*^Co}<_?QKIECDctlO=xPk8`Yazy$rsi+8*! zOz)sheD9s(MU)Cg>+%~nAf=~06C1K04qOId`V;0Dcr>@o2irW-gZoQ$7tS;ju?n*m zA{)0Dtm*Q>1b(6ZwykZ){ck&ZRGMu5D<_yH&LIv|t{1s;iyKvukf#!!xeO zy*^s;GCoDSv&BR2=p@tU7`{oepsd=#>cmnEMN0SO5$T8;MJTR?_!Z=d{{)V2DZiXC z4oxV&d_MJ%xJO**=?3hcQE0I5KV1AGT({aO`!yH|T6 zwYV6z3sDxz@OemM_(0cYwOHksN|S)vr@M?rx#ZQ-*=khe;tYvXL85!Y)$P7gzpzN$ zZVJU=?x19UDHTG8Wp&D8xF2Wry45fyZ!xBp4?_43uIQzzo|Cn*V1NEbDr8!YP`ku6 zxk`n0{BR!jhyay~i3&$6+YZl)Yd*hUOD4RN8eZ%pTn z0%f&>OQat@~m{oF>65t_>FD?l`Sk+#wDs+X+`OMU=l=Z0+ zQi2zB6tCo&h&d?NXQ(4+pH25?iN^(g@{S@?b}RNOTAepA!t^R_Je)@*cgBU*kXhU{ zwiu)Ldl)`fcpf>#JRJX4ZoCPZ=kYbzFetxBf)G_~z>%J3sW-rVf*`3!{z8txvgvVd zyuS}~KEkJ!rTzz9Nvw+bN8Ei!P~J34xm3v}24j6c94x$rYS|1W8bkb=$*&^Mot)v{ zLCE6ghcaZ)uBUI&0$VKN-dc)Qq%i4#umL68PI2T7FCn}w28e;#LIfiaptIOq2Fv^gh?+;(z+e<*QCYVr~=Qu}zg?i+tvz736sk@S44`3=2cDkKYE zdD^GdxRXb~6vTTOvqn<>Y?50{`=tC!8{^HRhHdyD`KT zhAV-MF5!=1zi(`Iy1KbeQ2XmGbEIkGi_E~SLS9fy&-#6Y4U#&?-U-_;xx=qqr-FYa zQ2Fs2eLZwbW@7R7)T`Iac5^0boxIB{jNl)gm?UpYe|cGPv;EFa0OY~1H12Zh>HPqU zD{?k&aV<*9#n4(`*E|be9zrKxUKL%qQ@dS0+#y*6mr#mN;6nXFGrnfgctX^q*p;O> z0{ogV<+dLecwcy~Gy@Eor^z~KY0Cf!K=!|66Y0flj8#Kqj*VCtCyKP(!sr#?>i14C zH4G*4>(4JnYqgf$>6$V-h)OHq7kNl;-__}F3Jt7RbfCCLSDm`?&XriV_88%|KWy)z z>GkPn2S@}3*%*8`X;{B0wV@~Qxj>s-pm}hqa0edcb<$s%rZ#A5atGj+V&;70>N0Ab z$I{ao%^?u0&?7Scq$3+C^tjyuh0G|0tOxPnp&)Se`A$HD_pkPB$rhr?f!SN|Q7xv#h}`Y3Y@!Rj&57)Z|#f20vqJ!_an%N zv+rm11>KNuR%cew%Qt>8#Us(jx~vd&oV(CzwDlO)?BRzpyT{mn@0cQ^Fy1Kw83h{P z%O#TZA>xT!9qyDjcD>_T&~oj!#7r#KdA|%{rHZ&Rbxgu;>JUM}A-EPr{S-9)y6}1k zprHWd8Mg2#C%QXwVlIB7HX_VH>&s^5xv%!}#_Sl%zw`Jq(7&<*jMha$18j;an$j+rW1pY412}7(1ftGy(5J}E;Tydo9*Aa%c|LmFWE;s z$lnFu7d3@_zEyvH;^5qt@^y)-{3LY?-O+qpU1I1rGzQ;kShNP1jeM(UC!5pHAe!+v zTQ%AF*~w{UC5_MsI9wRB1?bY*(tsbFPhgKdp{pt4LaZStJClq)VqZS7dji;-yYRh` z-@(Mh$7x7R!zLeHH70a=lhnuWJs+QzpuH$jiU#lIR=F0P6tEv$%5G#DGDT)M%g$Y- zkXQU8-#Z+QNSEIgXPe2|+=I-1Wok6ftF9!jd}Ee}DZ<)9I!KON{2F0$WJ8L835_52 z7k)BdbABv$thh;C>82-AL8%jZZ7<_ZbHKd}>f5araWQC*&_?kOZcOxZ(Mw$U;ON`P-iWY2WG8MN z#RjkTPx+(xn=6~(F~B2BW9z(nhsXVN)aa(aO_~&{%Pn!2{COvI=mO$LY3rXZ^2qA! zoM;koqmjO;Uuo51{#s&kT_}sAB&M`AEXL;Y@3*z}U6xBLxhr$c^7ZT|Nr7)V4!G&a z9+IdIkA;Q~+0nw$%_Gkat)L#&+)v%iZctQdiUE2uBo=Wl_e#G2cgZH?rh0Oo;|TUR zwL!2wroTZA4;>_KJYt`6p`MHm*1Tb9Yb)TCPRefpuqbUGBN#p?5uPrNKBLKEpO}cI z`e}kvf?UKa0rb!s>U)tN>&)3t4`AbCWPKD+d=;J*`uO_b9h9d^!))lv8wzPIB3?|H z7e(4%o1SHTx2Ec#f4_6wmnI;+f7T5_kF$6e)}Wh%pn zfyYIYeU64HUOsk>vK?bf+D>zg7}7XiQ}i@kRb=T49?_H{~SCCbqc#&Yk|W7)@L=@Ub>CKpg}Z+UX3ahk}unh2IrF-EyV zTM^zFH!FP}tP7lcE!vv36qFlN2t+c8ErO<{c_SZXkqdsenN`45zSy z?AlQ{RzYrTfeS7T_f~8RZNF0s`F6CPP|&&Liyg&a4RaMSieYz(`uoslHf&!EhfRy= zMm?vf;tLYrE5kR`a9OZ6Qoj_7(^DgIwkA!j4RGNOPXl4K5j%Wb!)a=*H7t!rMj(L@dJ{-=QvDg04&Me%R1bb*?ns+c!zDcLsE5iuq_aT%ASy4F+ezF=ZMfU>xT zy!`aRsr-7B_VNGcJCqy{p;t)Mu&$s2fsBy+Yi^9vXhM2$e3X@VJ?xn`J95vAXSM^Y z`QT=Eg<5N0k;Dvxp;>S9BfkUBVdBYAxCBbvKFL*eX=l4ox~7u0{#%d5?$`lmUlW+M z&pVfVn4nfZak!@eLZk%<$JF>H%7<>N4D}10I$AaC$qdi$19rjD#7!#j(@G~eb*Q#W zNDuD;A*7dx;h$f%yLTyctxSXWBW@Y7K(ac1y7=>3#7VJDz{w7h5tiO|D;FPl%bevO zL~28ETM;fy)^B5P>yc%?RBvWfdTkv9z$EGG>5#gr~U8V z(r?6g+I}1`EfxSNSPHRR(y=6YjFxX%6MX+GM2aLRjQ{kLx&r7bmTqW4AxRkJN5aAz z_nYT;G`;%MG>3ws-f05_*nSij0+li%Zh+t%I3|L=jiO#aym2r`s|(R(3)&(s2WHg| zbo_ifi;~MAULrWMAg!VGwGddOK@FofFk5g!3DD-^2wwIs8UG1RnC48dyc6S-s^<2@uz zNjEjq9yH)JLxLCZ*d)_FQ2iJ-l%4vy5T8BruSfwk!W*~_7mxU2PtG_TZ?#DSDq_VM zEri}=pa)O0^W;`H*J_7_T>+NF*bIi7g4xMK{qjvvLA!xD3 zEa`*0kDQ-dpo8iyrRyX?8Rh`^SAxtGh1U->Hq}eVB|k+(etdV^N#=G7Xs);;r<{#n zNk)`})I_6Qw`mL28y$0!@Rvt+DQ5psJa1xhLR&!~|Cw~1>1UV}e&*~os0=K~5*0)a zp6+hkru?l_=fY`~k_X1gg*f9!{d~7!)_^84Nc}zL+jnIbzxCDyl$Oc^1>JU!5>f_= zqFcjDLLPMZJyNsE!A1y zG*K`Mv$tdcpMoOt*x+rzr>)+@Ug$H!u&SLznKO;^w>;GBhgUJkPa0hqfk4>@QwPN0 z`y`_tuq|=328Y_9y-k=_j_)YI^MD+ zlB1c~(@UQp{gnNq8`DZnY$!}akgK~;j<0@`2g3A(HK{ggkdyFfY~Km{ijm?%cBbsk zWmN=32+cFnv4{5}`ONg!561Dz)+e*Z&3e5LN)m&@`^5H@q!u2KJ79(3IGkAt!k_{o zofbn(y`6LkcQE!?16$%&zvB==&te`cX6fJ!X#2;E@#TJi^7F|7lIDjUNDgXgrem8A zdSiaV=$7bkzc^itCwFBlZs7}!7%hME{x8d# zYyBC@9vJo*6F_H-(R1;)Lyn+Z=kgV1ZZ5%)^y4v+w*Ni?n)*WbC;|W8MiW5*`=r{G z5G{ru#6szX`5~QvVA%{J^P6-Kv; zK>YLCrgnNr0DId>ExmoyQ$gsRM3mj#@}D0n>KBLj$U?q{5kCg?m5I<6(BKv?VdIm( z4U$gge$g~jGmhF}ZQW8Jlf7H4tcS9;rBux`Gcs?eNGb_CR0E) zW!^*rppSN-_he6vaGyaDzQQBL_*Ka_AuGm9iH4z!o4^>#BbkO8 z<1Wu+**S&@7dYiNar#9xF|BO!?7`=7Rb6<*OtJKvpvG*pA=Nft1Szqvh)igjTiGwk znGmIZw`d~hqrQRo;GL?^P&x3wHDhs=mKpcIhZ!o$c1SUB_PR-3LD^u%4bZ8w$7li=qQUPB3qLJyy2ygyHd{PgoB z=gV1zi!)ZKk8M(|&(~B+xesC9A(}QHW(uzm+&8~jNKdE((3AF3kF8J05DC*uhPl4y z?L}2w0$;Mqx5w5$b7ZUj{fPrE*IX%^%+j@M|6)2gtSYbna?B9gmBeZa15Zjm8XI{1v5d%c5!xhW^+7MI4~pYTaCZGoX&N=@NtV~{;*_7WO-p)BN#T@N z>4<;+X(j&Wf@Jg8@xO6*PdVQNO`1Sjy# zvz^*y;UhqAM`}|LGe0~6xji8@#)srpQ~*S0O2N5dmP@OmPYUD_c%+OC^M4NjGeFG0 zqR`$j9wK`HnRjd^L47=EyVY@q=H$G1k$r^U$O@rmEGMuMTPwc%diu0Y%Whoi4spB@ zE1#Wo{cAdv8g$N5nA*V)d&GIKMUOYDKyjXw1z=T;s%+I_L*-?N0;qEU{(D7KlQZkD=JgtC)~gu($r@XYD#>K;v9#x3KnFXTR~4=|3a z4ai>9MjNl2cTi~_0w(7JpJnAHPvh)XX_?C6W6wT4qSj;K^FE8h)_y~gZR`wO(W;CC z<(xqJP_`wcU{q0uJ&S~TN%aDn3Xy{-Sho%u2^6WPE$CxzG}w^ZB@}& zSuI80w+p&L-5q#VQg+ee1KK3_oc2ml*0TjgIurYHl-68WLpsG1xZ{NPB1s1k_}iV4 z|0cuCHn*LNNpvxdrFYFTvMsZL%g980^`HE5q8CGC zi#!+toc+t#jv6IkrY<2OBs2 zUp|L~k1}F{-BCz~nvRu*F%j9g;z=Hi&L#&8=#4KZgGXMf8xX4r{7TsU23|P;#?zy0 z$VJ4xOh)IyDmw8%My_d8Z+2fo5y*ei$-LqI{%YOStOz}b^G`NZN^Qem(Ob38{v59t zGR3roN+|~;#%KcXemL*Ma%hH$TeV-eGw&N*2h!q2fH6Q&s*)`v?O&hT06I=XyB!>| z%n0TBYn1N+%qV0sJ->E{ksn^veNTqWQXqg*$%<;(GxB#yiapWr)@q?pAgNwvP-zg7EfR`1lW9AzV(4XD>pVXe)0OV(d;VUnF%K4~6Q_dOA5q!A zMTcg$FZvO4_DoNvTkN*Tfdr}2MA&gJa2KWaQd9d+CO`vhJpU3kk?#8x=I&_`Czt zoE@mJ^U#3LZd(`pw)lnl0Eg*D-;&!AM#e@bWt-BW_{aC)z(gmpODz4YV}j*gm%{ip zyb+XXP2c)OPDZfy19_}HV*jF>sfnV%mZrGEK2M(^`f9{QE7=p5t_v9q z{9<4>yd^i`Lxk?y^Z2P!fTRKjNb)MZ#pwtZTs73<*4I?7NwZ`ucit@za>_NS-?VM* zga*C7LQ+yVbA;c|XUt-aA$QLMCfx$VI8RgeLre}@Now}y14bRwGp=j*s^j|R8}81( z{^IcP*6z6FE);D9csL`#yFIkad>tsI!cdW=g;kLok-Iey5hvD|g%b9~Q8{za1q<*r zW=tAPeA`9J1{6ay)wu0 z@MsnzsYE`eE1bT)(D0OHpN7TX{U0L~&;XyPdE~j(X;{;MnALaR;ew|_7m=GcfEDYP z>YYgnuma1286N8JcX(vqUiDhv1!u9$e2Qx+x(`$|?@I3%usS^2H!Y=yEbrDr0~;$4 zoCLiO(EAK-cM560tB3fz8$?x8LmePF*k}?e{ypm92l|FPxk!3cZ}p;z@yfNxw}xj` zG1~Y7+vm^rY>_sh8R~IyI-#+tpvX=j;0rT$BvItx@~!rva)eVtr^}01!D72r_<4vr z0?mcO@p%y4hIH?e>n&Rf9xjmGkTqn7&L_s}*kKcBchITyANVts&RF>jwz!z4U-L^< z5W8r)xZm*0@}TO99L`k&bl0QfA^QvajypFOH@m@;QQ= zk%(Y^vE4WcGvJ|Cw{~0$DxBQR4}dx#;LyyPV3AnM9!4WWYarE-BUMjqxryVpnumC< z;6Dfgf?$eu-nnxXRQN<)awH~lbZ0OPYKL(q4t>{=Zh%y_~5gX4aZF zy}nCMwMDz-kX!qAl?USHfn3i4f18R4?)MNrao~PB+2wIAr!A46g9R4^qoH<}&nJ9b zq83o`6>JGlBNCufnk4*I#4P#G^qhCJ`iTbP1^;U}>xs86I`i~l>Uk1BiiF(R_ua3n z%yLCA2gqdU@LV)mE5V7Q*3R*94bE-CASlJ;_8dCLtc~@ci zax~6OV-?K?CEL-HodRwZne&kSO|xuQATR@DH81GEwaC7%{l^c<1DD`EpkSw z(Smjy9WQ|#9+Q^`$QgR^F>{cTw;p>njWgT!4!(^8)3^rwQQQs_c-;h;G;;2n^>68OB<{AE}gQV}(F>*UCF zn^llJ|Ftu1+p-U^BsCTNkK8z2;lj0lEDk@$<9b2Aiy7Tp_?Y+MzO$V`d#R>-NO)wz zL)jb$$Mq2uTx{(=@5pBdQ&io$v!NuTtEATO&vEaY9Q7vokTjqpPvjj-Xx7~eqsi)$ zBn(DR5w6enD;6zQ{@(8E7Gn~MSh*#P^ul7jz{#(~H9iaiUa-}gxjv&j#hBWc%CsGo zd!zh=HIvCA>gd9@1)>R(7izT6}rgkuACbQcLmdP(6^y1z8> z)7vF`QIXi@9r{9niGV)QYU1O}86~Yh%1|gs)<)AyPe-0tCF+>$fQS1L9S(l58xe%D zyEklX5&i^A-&9T1{+nZQ@g08mD^E~Ot0z>BdOKyKZny8UE}oO#ybs$5GfYuTl4U#Y zVu)u5Hv0UUG2<d@l=~K;Vov1zcaEzip!`QPLL<~w^JNHfuV}7laIV-$)?6FhA@c8> z+#i0MZZ}Uu*+bzZCBP4yrL1dvSHUC-a`(o%dKI--#81S8YEa3S3BMGWrVK&rI$Ois zGAGg_>NdAZHiP`KY;i?4%I9M#NdKFtzaJ!>Z;dI@7C0OU1cxSB_rlppVi(VnU<6=p zE5vs=Rbc!1e&OGr9(OceHd=1TGbeUTTy3LeY}l~v5U_#tu2U1B2R6L$7ignde76YL zRXnigmzLm#Y{M1WR4*}>ToJo1aeko6QMKGWH7x?-Mqv0@@%=OwNa3CH-C=Ld%L4C< zS-qu5H{Ft9LK}^O_;aV?gVe>Yz{5XL&uu1V9xeKqvcBPsd>Lt-Pg0VpM*%NGsXiNW(1^EY;n_bZIHxO`gZc!SQQnEb^A00 zo8wZk3*r5=w`&kl`WuBaV`2%6OqyHJMN;i$xczM7}*fr=bA`)hzOp*-pogCjk1rJ-D zo^5Ehx3ZU*V2eh_u0-Md5QvJkw=4$wGxf1Y5eJ zT1+mLz8hY9kj8)Z(4jVmng<0Q9u!o3i`?6RPIMEJnsIMFo7k1Re)o&?Ws=u@!BBID zAsl`Sl=~(G^+$5=m{y#KM-`wlnb;lol$CsZ_nGVg{qOEKrPvWy*ZOk zHrMM~QJ6HkKk*1WgGKr<_yw3wz#A>*iBN~d+n&fJAaNf*w>@cMg$$c7JqSz~WKMy+ z&S7<0gZ}th+)@~X?})EcASyNZx#LoMIGpSXE_IKUqUqa->*YbER~4?Oz?g!$!%g&l zVAm1XGB2HEmL4~HloK?Q>S$1`KU?Ow+mB{8s;%6IJI}2%@QSJmMVAlf_79iKu@aA& zVbWr_BK&U=F|gf#MIQbf`54@Jv9YPYu>0aw@@B!?Z-~H!h-va@x4qDh`t3k7>DR*% zTMTT>?XgSr_|pgpm^Qz+mHy#;tRPawAb}{=;ZUNl#UHKX+Vk&*r(BuGi#%B9^xRCR zPu7=nm}KvYO*qujFGJ`+pl{0O$1gLe$lYms@i4{u>U5Zq{fE)D#AjGE{sK;1$?~t) zj!$gGR742@Q)RAbJoMj%CZKfwXtywdjU@sf~KQyEZ?FGs+QPB(R17Q z8*aa@hSsd7N%~iOs-_2U)X*B@+4n&QRh8F*xwrxH_ zL+i40kJ*Z26pgLzR-w0rz5N?s*VITD);470#v%H4Q~^kFx8_GK6A~$#ypVkB_KopO z`xG(qqZ&8nRMSRzUK$9xH;TdjyQ{Ka;;I{8CWN#m!ZyR5Awja&DHr$Ji!eJ9F#QZb z4KHH)D0lE>4Wn>4DbKn8gs-N&!Y#BI_%*env|Au$ zC2zjxz-d!ZT0En6Q)E^I14l z$nW7}d5P8qjaB5)f;g*(7J|4;;PU2M?$KGx{tUt7r{+>Bj75 zY4NG~ZdPnTgXc#*O6A7z9qc2fflqxGk!3lAP8&$dde}mMVxQ&HF`>_Kbb@~T099Pk zIgVw8l*m`kK+Im6zl%i6--~wdR1DL$>Xx^BQPJ_v1?@>$!R2DW-~iE z@nS&B4BK+HO|k%PT1a<*4c|%9Rd*5?%wI^rY&L`Vqd7Dz zu`jYh9S4lQTULgEr=heXh2!15|8NG2r#>e`=#H5leP7Sti&&slO!hi^Hkfm9P#be| ziJ?T9SRBBFf}d6__Gh97zty&U-p_glY<9xUXld2SnF6ieu_`wtLo;&v4v}P%duE}* zF|ZbN_U?F`p!uezShXo^t3F}Qdu4uJzZK^g6H7yfdkWfD+PQMqZ=s(?`5X-N z8BBpd6gN+WxD{)L23UmO?e87MjF*(*OR99Ovk`6TQrA|K$WVor6X)MS3ijm95~j!~ zPqQ(r=tHve{#5dA$sDkx;aB5>+TVn$B`axd1hoDoKluiVUXDx3&DX%FO2^gSc#ilC zy_OXhW>6eI4EfeEG*9LObNWJq=hE*=2{$2FsQs(!~w%@oS(4Ue#SuSF7oe z6OXcPm^`;bWejgI^bB!}Tti%|#F$T91XmhMSmp2qdq&d*9*^D)OWZPWWuoa6RyiblP_=11 zwB{k4EB-)hssCB1r#!-9w9{TVn%al}OPl^hV!I`+M}LagPJU1H8^owuOH&=a<#+8- z*W(3-+YB8D!QrM&~7JWW(|aw%doZQc|jsC+48IE@$mh3Ofrcdmv2jyYsy3>~?u_Dq~9W zE*uH#KNdw?kAlha17!6GQ#iXrF?`7wc#Gc#9Wpgu@_A(z?c^y2gK(!A-Unv9!~ zg#D1?ya=U$LEK&~NU~E-(a4JZL9tRHU+6M)>p)Ehx=;<|A_n8#;_vp%=Uy|KDd?Ye2z5o`TGz^yv%wOn=6r|t!Lbh{36DdLb=&RJWY^ZgsM`UppAOTWH_~N$Vup<3 zQ4f2XoSsxnDa3p=#+USxR)f=!J&)xsctG?R%fk{mk8v^%{g7)W-Cf`8{+>Tic85A@fjawuiXIns&1QE@I{U7w>Z!vBVCKT9Wx)^zNRR>B{694 zM0!ZJ%4$SdIt@~g0j+-0&hE|t9h$Zl9vfD*b`UfgMLvQ=?l8cqf#hYdP!v4$S}?zR_U zgfYFL4H*MG(~5?AGQ`ui!iCyf^2ATTp`Q~$QcGVZSCcI+)ZT9UZZ}>`F#HtY@G^z@ zevGQtM2*>*SL5jgh(}&5v9)1?o&S~|bXWrS?(q8?ko@a?Hn_i?-D&8I632MZJG%6V@p!fJkJ|!avvHBqbo;x zXJfBK)Ks=DLL0+ygqTE^y?SNx#j}0meTfgBeYXG`X6}vqIUI=8oizMy-Jm0r;?Pr1 zGk`*sW&R}2S&l*1XN0M_b;Q#h`*ry*xj<=_D*uy_%GllV0nzIVZH?A>0qX^-Gs^ubXA){OQI$x!oJ# zJRG-_xhvx#f6;e@Wm+4ini2yW@oDbc-XUZv8nOw{W~~SWuW+vQ6Im5b7MxqOvTi^N z0balQeYE0Z*AtnepW-&gSM9X{+?9Tt529wUcYV>I5`&hG4%Y{>rVwAFsrFWz_Mra! zC6!KWOi`ln)3qrj5l@^-YXKn22GMgK$__2=d%6})$}Ki7;V;|!1OT0z$gx%sJ5PvAmk64zPB<>d{ry8EyuiXEPaol z310)Xp`4fkE+K@FK~e`>t7_XdfFsfC+pJ;7W`hiXc~UvA;JY)DJ1H7k&8T(LxPo-P zw`xPg3MLcJ-`jxcbUJ#WgsKF7MP%r041r_gjd%p!Yp~~2fa@Bfqg)7UcN-RiuBIv` z*@{n2m9rtDV`u=cLM(gfcC!6chidK?kkVQ=-~6#a5d7{@(sU=Z^T|LVZfZQg>Fv(9 zj))tT@JTL3L6#s=$RS!5QgmC~u|gI(%E8RqBV@>|E?&F^Eb_bUvyIb&VRQHdUQ(%{ z1pmxM`Su_JTVo?6Y%L$)+l6dPPGH-}GF21J5Qh6E*Ta2&9ow~zVEupmR0?p0 z3E|QkCi!5#wUiSWOiwW;r@(n$z+AKAM9P&Je#Ay)_ca$ax%U3d3E9!c=3e1_CKoRbPv0uh#JDD?+f8IZwz(|` zMY7Kl7$Iu400b#54qxUv$jiOed8D9U8pKIvU}z)R%5P%$Ja1`}D-_GVvv02(!y&QV z5uYmRJIB58TUe#lK7lDE@dee^{&xWXQg+a~>+j869Ci5V4ZNBCcYXqvm{^^E1q(u^ z;5}q8EN6KX;the}UXHKd6-!7Y^7eyhI6|s^0W)9S zb|>KK#AV@!9xIhk>J1>xkgttd9Tq{vPZ<)qCZ5I8RWIKGoWMbMQLI~)koW?BaaqH8 z4%UCdgph%mh+#p)F5dq3{YP)%z!p#{Ux(C}?y?5tR@~VVwy?>I$rGz~DJhwrx zIraXsQ)ul&!J<1N^Y03!VhEwdd?HJU>UV*BR8hRm+YEGoux~V9uXLGuF@$5QkU7H? zhx4c9v{Ej&NX|a}ON0+0kvjS2_g}4u+|YCT(Y!?q_R4w2pAu&yON<$1>f-F8-~W?u z9Hxh-9M}wxx=$^VMG$stA9}zyJ09iLF9)L{EicDhomACRijac3rMAi>m4(Av4s8VYiN2=L37{VCE6}N`U zcvt+7qru9D;s*?p-=Wwt8UZzhEkWbb+`r3wVe^&Z;dz^7+@P|WL*ka=N9jOx>+mhU zg3kQfT7KSi*(5_8_T8s-fVy~V=i^pPpPzxdUo=Z2^}gUtK`kp3^5|B3-booz4vHJu z4SLV}IWFcP7%$2ZV=$r>*Km3J$tNuFi-fj zKrg~~@&OGx|2sAnWqHJj9oP5Kc8Uc$)Vy|GDPEacj4r4q8_#l1_nd5R_AG2QtC0~= z6>XYOHW*pj7D4nqjaD3`sv0~f5&InRA0t&ZN5IUStVfj}5(Kw8J{JlMup{JTh~n|f zw@KFC9VJID#+S?}KfJW;0w|jxypABleHybb{yEM={WzI>yJz$Q{g-=f?^66B;hc%Y z$&wp@y&W$cE?iE7?zI1KlSDO~Y*+W!w8U4AP0MN5sxywv*tG%eNB?UTQer;-S)xDi z!heOc_Jr070F!zb^=P^yC{LdbJfz?lA?te~*(P1VdFgzw%J~tfpZ)@v($1f@DjYdV=Cz{lY|by$sC-HZP4|z||MvKU zUHFxLY6=_g`JMoP16(;URoJ=QwXSV|T_dGP)KiOxIkx?;t0gOs0;e&T`(6rX;qEZ~ z?EmNdEWQ!fr0i!`6|*o@ky(z-ayzI`W)0E1U~QLpl`qor5;$^MR>G(`tKJ{+!na&+ zVTZnlHrIDtg7-B+@H?3FNIQM!J@g`#ePuO)4?1vsI3`%3DMDjrm*#S0z-pa31iHVh zC0b&5)9pDH6p&d{FI7Jcd&TMPEtyIzGym&R+tHXmf47e3b9L4OXwpFDj6)fQma_%f zED*dG&zy7Pi}er?fWHur3A6=x1M;yvZ{=oWHs*F38>aXRs$Sj|3dLubsJa&30l}6- zWN?oL^-y>jr3Rj~3uMQ!>Fr)>8c*v~o46CU>?Zylf1~ir5&&vuY9jO>nW#`D5s(=A z6;s=L#|j(E`GrEl`huZV0iS>*LVchYyjGE3zZ2oK(glw&-~@-^B=FV2mbP(_3MVBK)TID5rST2PR{;QNTrmbk&f)=s85c z;y#}pT0i~Q*El%>y}feC=XQVk#@KD=cq#8QN9c_J#95II&4S_T61?l%!jiL?E0p$k zY{3@p#I^9yTfTmd472s!ih3$Iwteix7^Mxhv0&~%FEldTJSwX7(EPI+e_X%( zas4G9c0`8vg3%KW%O7{yNRy*#?zYI7>5~pE`mQ)b!gFW=;-ewh(|~rgi>7&MLn}|v z1z-ZHk>wxJ``!}s_l(1a6c9ao(nrWc<8k@b1B<30YH~u(gLHOFU_|02R5JM5eYuAH zWwMHsg&9a{YQ0VRD{E+mzEie+!_qPmt!d2~xAgw)%481%_KxciMY<6(p$_mCp3D8b z4MKZwR6v42w`DOv7`;(XQyy&ZWU7BFk~_muYq(m?vdI?PGXdsbJO_MH9|r@(aU(axE>!5WI04s$IN2V}u$Jx$Wu?rd2aT64rH5Ul*!(1qQ?YCDM>Mf`9w zx87#61&h2$N#!Ty{Ps>)37sQP3IVc^2*J^Nf5$-MI^_xRcfOJa*I4Z>gT^yGX8Edo zIvEf__;p>u5Zaz^_C-JG#P9u?>lrzQDX6~;I2Q9DVaKS^X0;_oOYXW-I|5%;I2AZR zNew`d<*9N0X5Vlj^{ijs=uA=hJBK#IAG8En6{ns-S*UfcsH) zcfhOt2K$fQZnz!Ckk|}2#WsKLyt!_ znH|N3H=}d4gCY)d(wQFUhIoA$CF7v%JM_Ujl9^g`aTrW@Ii`dx=&7+3kQBl>-PO9v z-P(i}=pGe6WDFMzx_*N1!(CE`PCo+~&_~39GvLH!I4NJRecHM#WbMi*<`Lx%Q+7iw zUke%eEF>}g&fihmr|;6sy1tzO&9n>OwXU~|oIy62Y~?*s#@_KgqwiiZQ_u>n#1O=A zWhu=7#21%7`WSwXcmo|&>O@C)Wuc{_uDj4KG^%Aq$28xx*U@*A`d2ni~0geM)qjE=-*&kv<1h8w{}@#{UR-ezph4*>6zXF z;W&qEx|jkwtNwS*d!AqWyBq{3l|q$IMs9am4x(d)a5=kt+kF%HgpnfmB4cdu`nuGq zu_B=lyL}L6W(36|ep#Un&2DTcDy%jZT3gk$dzj7mr~p zb(rPy4>7__Y>K&WK(7YT7wVb<^ntb84v6SD)K*sH%;mWW8`A^3vG!=Cm5_^DyVXlU1@d)4h0?l# z{GGrrWCxYd%bJ_H)%#^U)y~54Ny6eIsSV{yA+ahUeY;U z1nYx;!}A!hf`uU28X%-6@Qp0;JiCf$ki@3PlR_;KJLp;*3Ay@bPaLyX(7fkgMYpaS z))WWUTZy_5dU6i4tu`+v?EvKXCY_EDtMLOm%$*gIb-e8)NpD#Ux~tc|f7hAHl=%>9 zcQfMpBecLSM$<9Egt2afSVY)|AIbb^hPUUzNgoCY(agpgs0A#YD@{E1IM>ZN+C#|p z?^?(n&mYOq$oWKBF z9&h#SEy~`)Ur7m|z=r8U#B^?;fVVxetLJApsIiGk0 zx3EZyTn7>*{5R`V)Ym@B{P}^D8?8PJ(USa{9 z&Sn*TnjW_RxCvzF_HAc>?Gx6q$pj#j8>fOdavYUEc>Z^;rmD2*2XmZsjtiRf|QI1ZaIr<;gyAnx}y6w})&g1*(+h z(_kB;t}2wmqXIVvy)-Di0P`Z#g_~spvodWq26V0B`YmQC(XDyr#S*35(f|QFZLz#C zE}iH2LEr@ZyIm1wba(UI(o79>t}H{vHI``x8~WuKK1ZXn$qEsGGY*8YWiPM2I(?0w z>fl33y94~XS;$lU-4I?W3Vu-aYHw4yx{^Gx11XV)=nxHwR*=4WDsRJ$d>o!0ID$?8 z$YCJS=G9vHty|N(o3-bk2pi&m&jZ4VSM4n2(h7ik`0b);zt#p_-pLwR2>=N|_P=*v zBJWZV+%H3m%)a?zNx$5kECO9O5LjL!E_v~|FN0?9u3oPu%loNn)*Yg1hn8J1zh1w? zN@c8lhHnQd50YQu_P9|azyh#FK?lF9>1*?&qK#`tItwGEKDK{r+^^?D^~B)sTt>K1 zUmT~Rv9lIIw%L#O;k2wIe$4Y-7pbV-@5@EQJ(X>vI5BcLXe2k=wZEptjm?*IU2He# zZcNq&Wp(#A3}5I;;J|#6+92*V;P(0Hc}co}bU4>@v|r4ah^c0Y{ORF@;_?bIUxgyK+Qfw3*0l=)?#&MK z!voDcv5Bh);|dbPZMVUT@@j){d6GPLG}G|t20?Z6RVZh&v10U}Lr7@sci#%qevL%v zxyCN=xm~l`C1faxVHc~F&k`u4jxXQI4u5dLn+uE|sjn}prIDwJCiRCrX%&tK=`Gzv zKR_tIFO^|kp@W|Sp*dQ?fVW#*M?iJ)@r;POCT9d{Z}gO#!r^l;c9r%2rbOy`_ujuo%_-;H`a_chK4n3of5?^%`*igYc0x!yu3W)4S!2hmH>joshK1V8z zN@yD=M0rGnCBiHS#!+A!f^gV)#^{0k&Z0F=(if$byktR5tuDDDE`>?9%`_H!d&9S< z8B_dX<|Ma{Bu%1Db2IR$Tr+y2SY}A|RjwPX?P2-mpdFU^#0nUvv#4_R@{Zh;*6u%Zs%B#XTYb-5co2Op9Ifg2 zH>EcjoKX{Gxq{fTX^&C$tTNdQ#CnYd5+vAye1Wn6odlTy#Hn^W0r48wP z((xDo4FrNLgz$IGi@4xyAHI+TQ?YELyEtFZg?ROMoSp^@(x|ATipu(a51PI6Y|=f0 z+6zzgcPTrNuv(91ae;*+jd_Cva8@XbmTiFy zl782oP13aEeJ0YonIJ>_z4`hm^LLMck`zzjdA*z6GdC>Th+3VP5zO{Yvrzwl2?0I4 zy?ASQ{bT7omK;^KDEdJR@NOu)@CeTg@4e^iFV*i2I-;sNLK3Ny`>ch@w6w}gs5?lu z)`Wv^io_c>Xp+b$yJ_KjQ%Tc0EXx(u^5&c(Yzl?Sfmh#leB&r}N>?hmzRocnuIX;p zV0}M-%c`muy62wYqh`<&O+Kmtc@EF;%KR3=sQDN;_Ql2ncE4P&Crw0abyA z2JLr(N8VaRdN}P)ii`X9RCzvvJ#j}o~NdGQX>p4 zzYmrcfm$^eM;0j(R>plc+{cq_tLA^zJ)hqWBjYpUY3uoI821s8(F3*u&QE(VI6_Jm zRZ!`dk<1&r4RLtE^lO6rS<;M+etoXq3%2D&Lo`ybb{3%OMH-mx$H{mXXVB0&Bu28i z&T<6t!sCE?+B=Dfnni}T9(1}$O$v@HGW_CzcbE(y4_!VHEovWv4-qX z43Qs9Z@8GwI&J!+;>cUUHnGu#y*`lPt7!iEwaYTb@CF{RqCP!5crfJTMhZCg+HOZ( z&7=mPXRvz2qJ6vmG$ z(w(%Bl)I>oT3~9EoC%^w7jS5P96Cen$8>aO7L|ykFWW|aNO}KrAD2SyBJCmbD1mF( z4`6RWiz?7HI_|cXuLB{7$9c8LC^HDkha~u%unf>?+yZaTMT^Rt%ABZ`_j_New#fs~U)tBweh0S;>-$+F zhX6J~xs(X`=}Z&U#75@Gws`wI5XboTWN=KF5TU}K?B$z#e!0oSD-}N?3^4~(^`D(4 zma!V-yI3mL{e89>h4dO-A!3n7xo;dh)-MZ62mg++?%~?hT?jN21sR zm`R|BD`J?13VvHS)`<}+OIk0Xxzh(ch(he#y223%VA2Z#u*8B>Ba$CxSdtqu9`VLg zeQ&-!iDQ==(<~1AoxS!AK-$a{)R~&`w@8#qO!?jg>l|yxj9c5V3yh z8>T#CwHR6iMkJW0z<0Pl+82r8%(+1_(zJo)=ffDnZErK1vtC1kfeP)P_@H6Lw@2To zRe_wmE`6n7jHBWOOuabnT*OKM^2*}x(cdgvRj74D>P}Ta^j|%DVj0-;|W6wnSRV9<8W#l)=-@Xr#l;h z&4vnq^AM(iK=)NH32i>LLHFTH08rEIMPVzrO6>ylN2DJ!_Dx3(W_ElrpyjeQJ(*!RAHMwCpn59s-BZDxHd`3*-yR!A$rpF1SaWIe?}}Tq zju;2!AmulLS%-0cE6%=hcQ?mxIS~{}jPUqPOXyhgA|ed1%7Gwy!Kq zKf?K^F_V$%ZDCddag_h*6 z4>y>($x#1+-R;fq$BTauoqrHI=uw7bvOD&g;8?*RnZ9YE@kTw)OVoh?9q=22Qqki~ zpWo5(hH;>wqP4b}Pf-8%ZYv&(9D4b6FUVo|{7VOf+x!`lZ| z;xH#5z&EPC&|n zIWJ_r1ogcp<*ui4WnO;BGGfxJ)p?EX#*x?h#LXeQR|*4t2^1KqhFs8B zc7E0?3A5D1GG;ek@F_nszOEQZ5766L6rGxWN6od9iBw~RQ6ToB!9w^cnSuca)V4%O z`?SU#@VsLJ6i_F9i51!;R=0D|@%vTi4xvd$T5TyjCoKk!kvYwIJ1oIaf#N!^`YxV! zu5G|YOTQ^57m^%MX5B^V1B~9fS%UueAa(5Canh7w1>WcgM{v)bNPS~Ui^bz7O98>~ z@eG2&B<}CZz%zJ1i&1R3fX(C_&ChSy0J~NlJFI|<&eBKD3C3fILoEMPH_MdiM+4H}$@ z=Non213FiJEmd+(7qFPxn9@7Ovb4G8+fV@L_X%V48l4GAQTl72Ygr$A?Wm9OWV&*h zgwB^Z_=3II-qeq*ckCMbf!kQB4eYP4a6we8@ZZ8M3Rjv?DnArnV??I>8hCI!*7dV} zH5SV?rOv4(h|I~obVv-|^Y$u9KPkJ4M5UJ@;-fp|cQELFDM2lyHga&oBz@tR>d%25 z1rjJH;})fTJF&~JSlF)c3Qms{&ORRN;FgG6VgK54Q=23O1Ge7W24y-XySK+@a_p=7XE~dqLN`9d!2d`_PypMZZ4IzUp_le>NiVNoJbkX13 zz94$s#A6>sdNB_xQI78MJk{ez-3q z5V<{Y#N4u`Kqyh)eW(JCF^wXJrpqOO)1X82;407cPAH9UyJXlglJ(?$Q- zp~LK?_LTvOj6xg%I(L>nU!*C5T%vtYs`!9&h~?IaLnkV=djgW`Sbmk26gUxQR?d>TLkZ6z=heDc^G zad`MCF<(QePo*j7WxxV#7vKlKiFg)c0I(nxA{{vLb_Rm?f|br@B8McKCsrxHYcPjr&9pFz2bO6|AYhkorZNRd4h}# zr{SU+p$~@@`!Hh}atY4$%xLjs^OxuXO(FD6)eJ~(lC4rcLAH*CC%t4HK4q2L)g5@cQ+%0_-VCEfV!P*g-$cBDg?e zg|mxj317*vbvZBj$inH#1TKSCnQu1q0~cWBba0)kfMFg0_wv|dUysgNHYxlu>~yam z$g)14?}w3pyx=;Bg>!qEY*1#v*0(fo<8>G(E~E`AW*t^+iN zgUi-oBGw1x$ZwFx*anDs2g^&dS+HTa;|olbeI1~lJY?@X5R2ga&dW+Z&$nC&wD&NePB+hO<`&Rg+7_*y zZcmC+moo@!t1ufQud8R|MCbww>T}6B5UZ$Ics*#A53@I*DVi{zcJI4C>F&8IM<3th zx2Ss)!^_ZG8C+fdf*lXwB)r1v&2RdAb%S>> z6j9~64rv^6M&M*v^=~FOI;Tj+mpbSCZ#Q90;D6#}yl&`G_l$pRR!r!Sg2nsyvJ|L* zDj~Pm&StswbN}vz%{iV-4tn`z50rnMU?S$i4(O4?5L7B_GTDY`D@|js2ezzVr(GS5 zpg^U?4Xk*5*O9sqQVb^r`Z{cyjafUh#`X2(_mll%pf53d@HB*Fx-|ant?qoI{`ui~ zIJu_IwhM#GU(}8B`ZkabY}#CWHFOOdpnDu22dvIZ7IcjNax@G>Bja$FouB7Ci`-qC zl<_gs)`K6UQExX|r3E$b^h3Wb@PfE&CJN{)-BVKPQE{(+?_9If#GG zc?&p@4tXOWCiHn(M^P`NuZ9+mep+;%)3*^68eU=@b}3VI!hG@59zVjLm}kVSX5=-r%?$cg~{CQNX2CLPH1X~uxr0z~q!#^9GJjCGNq z88O^k*;>i_2KI?ST zf+P1^I!~@RWp!IWIfpeyI`2eXKI@y}rot+fHwong< zNF>FjeT_qU2LgERPYuW4yd#}NXcWzjcZY*(`;mH6D4%#dj>c4QP`3qLQnz@$%kbsN zUC6AH3Kddi*sEdA6CD${?SlSX`p)%lKb%WR&+ z;rzRHWxw$8`ORh^Q%d5X59>e+$7=6XR9GG|_6KPva=4M+C<-q_dN**tMM|i8-nd9F z+!N(ZB;GNEh_~G3bvAYUp87s@seIK_|D`*zF~w61C@x2O+R@V6izABeA>RR396rqX zcgCOqD>@reXx{x0_DHz&yh;T^Nb5K`(jQ2naK9ngDTn>_`Ii^*JpVBaz$UDzX zUcM+1`&V~&z$h?YUmd|R}Kt&5l$0_`*y}Z`(JJ4M1;mcB14?;!;dR8+I=o~`GBD7Z~d_9+2;l#MB&R7$v{11aFc!QcEDH*-94CHV3HG` zyeTt24luOgeG7YcJ5alTHY4fFo#1E&l`>6U;iKzE{zwsN&b+j#)k)h4?LSdhy6A^i3@JGDds2;vQC<5?6{0yrn zMrge~|LS7v+V53God(`238jB)&i=+V#)wNJe1V*Yhe(_dPI2@E)#e+elEK?WE)d!9 z_D|&u!_|}XqsTmE;&L*4xkH9^ppxASbUQA?f0$HyfPYqpBj=#m?!V2u`=4SN$2gu4 z&&_X;uGK>?#NT>~f9J7QNrtrsTZpar&Ep{6ZZQuMzV>>ef7wix7Z2v+)6uaM^w&28 zaXp&X{jdH3(CFzCyU8o>J6Kfx=hTMmb--y?55ktARdrzE6S)qWk(lAt(gd{QOB>Q? z8L2s6#;)(FlUFJTtI#5PD|LMZjli^2p(>ZpqvSP1+1Nm`=0fut$wzX%n|gkyt1|%{lzk%Mz_S*>Pl$@N}}Q%E8~Ul zMm{z{r}idN6Qb;#GySd4gm1dM_yS@JCD}_=*&jt!b)>lds6%lY7qFES@QR|BX*g++ zua*_auFk14Ib8XZ4;w+#h<>$*ptNN^GkwaGZeHo&?MdNbC``L!XEXLAN(wPrQVa&Lc>O(|OX7x;FIbVOCUc3_zL@>A#O2~^CjbBBM!5?6!fc>)&wX+K|x z;zu_^;cCH99XO4s-5!LOdMnXC{3e!1tXDad)bkk78)4#yD_l3#!5^S&T!#+_79=r9 zH0fU@(%|M88%fSQy2Q~n-9h{+JJNsJbyqbq*}dCA_Z{b@>e!Is0B9NJ!b87I(&ZaS(kG#maCPT9{7r5~q`V(A-Za#=C-wX> zFC(#CRt*F_alA#1q7G1#S8cQ~sfq_tKJ#BBP7ThU5HJ`z8ben9+O%YuB=$p9dHz&~ z8L^$Iuv)=Ie|smBE<*z3*d~1we@;JDp4a9b)<)g3DK}B$7Zhs+tI1R}F>xe0xL14g zet=BRZgOy+X9OWfr(_2dJ}7+w$KkogOZYh7d2Vd;)y&@6t@=u@7PmcnOZ;tLYjd$N z)j~v_EMwNw5>2baS8toJB|5PCE`v)~0^4Yfh%)$SL^>K$g_~9?efDSQlI{!PRdN_&xG; zXyz)F1P$u@)6fRpi_5&9abdzSql#B9F*8gALW^<^`eHh4TQ@E2AKn!J1Dax(Sa!BE zUJ}e8h%wFyrQRy!gc0$o?IgDUopbA7605U%U2>d(jONFNp)QyfE$D@HxOjM6-P=e= zY3FS_rb8=O=p;3!^R@`s=W){g%KjTA!7vL~R#CJX@E@f#ai-ur=ZqixJ&d6TPZ*y< zck4NKyYMK)$Ua=x@*TO*D;$X7%bE}{!N)RM|NnWtXN$=Mi}NW($`;6cnK%s}kS(vl9b*7*nXaRjpjMV!r+F`UhMOQ6ZpJ0FdBu%tRX5dN}Mp$){7 zFhGqsbhPhJn3yd|dI(PEByD8-q=*H4gPQgJ{^TW3=$=~Fzfhv7$?ah7p&!nVlwaZ# z(#(xqrO?)cU@VvOCb(f#R4$OMCFv^ZGq-A5H`RE!HkZ>s6NGH(TH7r73jN585-X5PK#u6%w5ih4xHBKXDVhcQ`hiBV$@XuJUz5$Oqf+X)6ArQJkUju$TRSA>CGdk58d(*U=n;ET)6nqSAAxaRMuE;mtz zFZIo>rBJq>n6(_0iOpU}Cl-k)8g^Wh0EoDl_fNEy=Zf*}HLsmG7 zOVMX~HRp<`bcAYqQ)jbHUWz~qdf~*hRYg8Ky{&wDgWdqM5&}L0XTraQ%s?TqY5PMX z1+%MZSHt<-#a;G6LVBS^=s4Dr-Wlw+HRtPSBD#)mR*)OxzLx*V6#U}}f6x5fg$&9P z;1(txDRhr{$rpc6nRooBRyWYv7ng5n$eLEFBDRoKa#1HdY0sZQnPzAj=4Qjjx7f}| z%M*+ETkYie@qTY@FIyJSuG7?gleju-7GUMW-|~zLo~HTQA?&yzCZrU(Nck5SLB&yO z?v2jy7f>Ayi+Gzq%uD+QPUncdh22Q!3Q&|PRdpUJfDxxBP+A1#Vtl{3hQFVpr}XxT z%N%bQ=*WX#9r?##rNi}WS%TS84Q49fm`I2l4T_ASw@{Wq-l#(t`bW$7YlU&^I2b{G zOJJ{M%~@iiGS4hEXqESfqF>A78rI|x^9gy6d&ZJ-NJN~}_21XKk8VATFDH8~%``W$ z+IfHB3n@28b>KV;1uOYwmye!;^23POKL6a$%#haV*8(2#ikl`m-&yfh1@!k>uwnTQvcSfjG(NA-sZQx*a^Vf4cexl zh3N+P0Jq(DWEmxJC-)2Ekd$uyQJ-^!BMiPxg}Y&eg=S-~%#i?=iIeRb1UPGZ*w`Fu zh95D6GPn9C^H=#8&Z!1RgLv+~k_}NPOeb8A3kO{CL@cthUz7dYi{PX0&GNU|%lGj0 zU~&lhZkp|z>Y4X`0s7%?@lFl)RcG3W*z)&!2P=NcIXXP5AFj*}ip@NX$;t$)T!l^A55U1nmR~--!Mau-gfbhRR^}DJOkE#NRmUSkfuaESNHh~t8d*~OmLlPc+QQuDsPC~8e0HA~J zrxv^l`{W0gXk~_^WL_SJNS$#Q!Zt`ho$ut<+RHznYWJdf`#iM~QXanGa(EgjZLQYR zVt%IEjFw8a^W_N!FpG9eVP8K1BYFhGI#S+9uuj>SF~O%8U?x<#>Mp>XssL)KndL-% zI*-?~eJxF*pqTAmPTb9^Z6ZeE!N0YGRS9iA5!JG;n9*Oj$2I47WFb@gaRCIf9Z6Em z{(8a$R4H4hK*9-Ih;==|u%K|vuF;b5nfFkZX&}2pF7>o6Yd&k;a-GLp5bdI+QL%`$ zIYIvYRw<0hjmks5N;R%H0QxS{hZMBSmbc24N|^;CzWIG+XDeyvMh`&2 zzb*Qqol%HJoM_pWyqx-P zZ?fR)*uR&V@g*W9AA!&QbR0|M)I<&?)#xq57$nmOr7r@6m1GX;jix*!Jw2BcD#M3} zo~HP8QulZ~6oldE&o-w0NuOO+>pZ&X3C=uE4pH|Y$eHX%6*zJvH^psMaMQ3DYyZAq z+Y2vVE1K#qP!~)@xKb2U_ri6ewFyL@i0C<)4}dNPmmmPIczs(heP)#ND7f6uvAXI^ z0bo!ct9<&!u(Uy2faT-cN6p)dR<*?Fxf)Rkgv}z*;mU2>X3q0%!{B0c6Akdcr)>tm zzHuR_v@cu-c>JboX!>n{gH3xOySO_LEWat%Zy2EFN-Vssgr%2;r7OLKTS6?_sjvjM zq%a?SptnYP)GxNQNqn`GW#rsbCXd@m3vitu!ss43=15BHIdz=x(Hwst4-LuwLdD|j zxg9@VwGOxi)D`ag>8t^hRDyg0@@2zx96$mTq!bjM2ht>MKTKjeA>vKgzmuB#lVlZQ zVLMY;Zz%<-Ya<{vn|Bfa7??b-=2<=%h_b3t>gPu)SmX-O7g576*unlGtkCRTAogOz zR#9f+=T8=TJ`+(dCg5ihPGsVDmjeaY;`H_SAvsCa%X=^+*=#$SBCibw!PsmikiKSR z{Vl4mMA1({R5{hSZGXjWd13d$ybLsZu1I@Zy9i*PmV;FSS>Bml3LQln6ZY%D$=CFe z4_nnwQv{86%8*I7v!wyR(zj^IFkcz-M&Rdu$yPQ24X--bs2?tz6Ofzy8pH@iIulPG zo=AT!-cl*d7{vQ-$^a4`_$(%vI?QAThugxb<=dJNb;U)aU{N36bhp?P?_KZ)5y;)k zxsM@umV;PLf=eChQ}4XVMKixN8{=X)396Of*Xx~e2_WoB?AaR>6Is=UGK7sJat17L zF)akdChyP>JCl6UQ-pyX09Gp`PC&;Sq<0Ut;4aiS2t+`v6*{YLW*R>L5bdS6S zyDOt7^mqRGnk+eW4&iCN=?8n}=%4ER90>X2_zxF{aaT3IC4JP#E0YR;3%@*Pci=P)99?-VpJSL273q16N?WnmjaSSK zCa>sxW#9>})*TaZw0v99o0lD6lXdK0PDI}#={xk5rQ>Iq*(>3U<(O0#W9 z$9^4hgMNlY64Rm1`06=(SrVC#Idp@A8e{LXa{N+xl^NoAzoy+(d zBmp&-OPB>F!-wKt9aRu+A7ty zm%4nd-uG&eTh=Z#0-)?oq*=^dY{H_*{WDhvIe{r7G;mWS;Ee)*upVBi`($e}2aNea zf!6tozXT{g%>$9f(Q!t-Wo;jU4FL19m^#&`Ya5PIp;d=_h9Dhx(R%Cd4oRbb-uli+ zOhMf?k?5MGK?>*Xd-S&9jL_E+tGbeKmC^@L*0QwE9kll)bJy9idLk#{+Jz3q=_XPdI4mnIdv|To5?zf$#K3Eha{LuvbLiz%uooHn)_^C8N!KjGLg6nUUNP1Wg z<^5{F!(g=j*WHB^gP?jQ+TKl13XCSnQW$1vSnkvF+X5z7k{Xc3@+axZYP)))nuhMP z*IT-OFT*@6yCu^DQbEJ|d#-V``XE!nD<&7L*xzQkz#!%1MiXUo0B-mAdxo10N+(Gt zQ!mV)$EW5_TFz)7@SK9LjKpGn!L&?ejS2;M79+PP&^Xj;tQf;vjNuHOmkolZNxx&g zU3*$n4kP(lrtM4wlFbS77NgR9Ed&I+PkL}dyQN^7rj>EZG&Q10*1rL`5j4CN%qLrA z<_JBIy9A-`$WRi;x%%dZ^N4zNjAhZQ$+M;@;ww`Xer(U}=vTf8z4IU?mqv*?&Tyic zuSxpEeV09B6_5bSjs@?us5hWHM3o{>n(15fW`UF*umxKy+xxfgyj0|R&A&ruZyU1e!}c`)+CS#uzBdyPjE=I z*UUMOG^RZy8Jm{=_BvYDj8Hq1dFkIO)h%k@b+bYN%ERFvW&R%72e^8qo&Z8Yipw6P z(#(V>)K;~rT-1I|JEliXN*$}hg9%1k^_E;0|BV^v2^r$f^?~r&lq2LVBpo3=I%poy zkb~Zv5Y$y)`K1yxvYQ$QBT`X(mqk)%p9IoNZ^+<0s|_%-=B9Lp%*Np1X0R<8lzr*^ zxs{QfFC9k*KgsuI2f_ZsmC{H2B%@V$@W+AaMtz#UyJ_C8DYC%Z78vzMm2Z$xn(RHr zQ*I(bOW)4`htc0fON@ND6FzdNNZUP6aq@xusLcy$lt~pEpKz>!fooMvR>-z_z-h@V z1+*iv5kua4_haG0%+C?(rPDI?jqJn3FqE81||A# z4Kg6L`*o8xrR1e)MR{-NhEu;F>KoteNuaI6t(W+9S$xnSoJS>j9;X1o1?>Y4SuFf$ zY`R?9Pvj167f3{k8EiIgJ&?041t#y%zLw9wV7GNIx~E*q4;;DwA~Jaig<-(o&7%f} zas_n{0C}0x_pAQsmc@v1+*bo2a$owO)BS-T`r1urmj}Y^%(UqV)!S|~%o8odFZg$+ zEKu!$aPt>1zoD`&=BlmD-3@?|77(b%T%)tR-JW$Lx%i4}Yhi5IJ=2F-C#I?ILYZ%@ zpe85&>|kE^h4e;S(s1n)Eq3FJ+7p=cSs#1u5I&mrH;BWN$L47s4-zy?(Qj(f3Cji0 zCP-qZ^m=jd>N<6}WFV9ePdxb5gIxsn`@&fpNOJ zn|rk|rE~CxG#|!CCw@Rv`cW`doHU7V|0N9QLx??@mY^#fyALWE>qe^Wq)S_fp++spDn50zyx5Vxe=ZGehrh=8ET^13I;DS zf9Rgd+oPn%A2s>{Y=NB4KAB?q-$-`YSn(@$=beCF;39#cUPBIP8U$ApnRJt7QB*^G zc}MsaXY}>k?6k>ppI9wC|M+z<;gW`ni50r; zQb($jU^BsoNMMxn_?pCW!1(zxna==JODOlH(DV(>dSDI~MgUO@_xNyGW)rSc7!sUt zTRA2TdnF~i`?(AtOPU+35)pK=vG5DPbR38`ZY&M&Ovm;M%Vva%qwgL$d7uSK^5PMW z3Bxj`%wEz(n;C#r{XWb^Tl&dCQ4y$2#xl5Y@k&j}w4?mv2T)@>vDag1X~ka{X~*VR zZ*>9aTio2QKZXV_*1sLS>?`)0k@O^)$QU8brbiFDJt~kMBHhsXd_Lue?|93zj$?;U z)YXgwU4o@5uteS9s@{$5&ofDrbl&Oqa8ybTS1b&@Ney3#4nF6s^lXu&KS@P~E9Zd3 z|Jfq^sR^58-Y~NFQ_oXuZ;f0KscDK)QTLd_In-ZcArFd>m$xDCdAtGowquD#@6^C^ zF=ME0B3K?P)HJMs(;bnG#&Yo9^xg(w`kR{Rv*!|KHgH8o-UfGz5YDit>QRowarMJR zK#C8aOZbNU08>PeOQ*CS)H-_kaLMn?4U}AR`?01bH@79y;B~?V;Fo*)p&H5-^IJ3I zXmj0{o(-NeW5gZ`p=+Q4IPio6e-Zt{eEZm76P(AL&9!$O8kbLkdFjaJ|QOpXu{MQw}7x5E zQ*aSTeEXSg=~2i$Yf1?#fB$6}fk;-?;}E*S-8SmMo{-v6hx2OtbXD@tvIjCd2q3MO z0_1-6UR1aR=7FN4O?z{19J*?v645GL2dfC&`?|Xv{wbflcZEZO55e9AQkwm==Scp| zd-A4w34NO(w|rV&WJQQj*NmL;W=i;j3-6Oa&8Vxd?xgdRjGDMe?W0yxt!!Lkqtk6+cR{`M)R|gLC69vOJRI~f z9(ELZ5J52-n{9tPo>^Q-+|RsqM-MeDm8ETN^t593+(^^Tg5dkM+#XO)e!{RT#Bw9b z57riGWJ1V~42gj;i}ZrtWD5sdG|Z2(w#==4uB0qEFYstCVG6l9$bFsxEoO)3Sznwi zHmZW9-_68D8Ahf#Y!tsIxe;(wxswCxeFsi6S)bBLbOmnPL;I7ww+boCXLEp!$&wTU z&pC3MXen$8+9;C+B_9Ws%EwZ=R|?BQhdzD?hkbH*#~79XAAm2wd+7E7a+D=7ppwCP z!Sl{$UQVs7%3a_XUK6b;Gv2I#hdu6D$r+%N49w_;CH8^5@mPki_{|3IPZvI}v=jrg zH2oOG*b_zgTLYTTY%U20Ddbr$)Lej^RJ|)^VpL%}0JAuY{c2vmZ5xp*Ja(Nyn0VPo z_6i-~t|qsOgZpx`%W9JBh5;ltEA6-6TA=vS!&-}p z&alPbeh2;VP4;r$j7{(4^iEgxagp=X8>t|XK}0j!g=z zpU-tBAhaIK=SpX-``c&xRp;F7C$rHtAyYwuw9K(IDa@#uSRTLHZ-1HvA^TtcqHj2w z6JM9dwvIizzRsJe=rL$m$UW@VojZz9^yl%s)tDH1O!x3_6{Z|OOo#GuMJ161rp#b! z=o9NkrTzfXJJ)_qLM9XJ1$qtwDpwT+?BV5m0RGTzaUgB?TO&HR?o{>XpM6*1-3113 zUB5U0Dq092mu-bgu-Zx0V6k$;zpbEKD9+bj_(*fh1_E}s=sW=ckn)^)Y`9p;q!bcN z^2y5<$L#%`T-|xuQb5d4FxyZtEJ3~s2@NOq4zFhbt?bsEh|20I7Q|2&J^PSLJm{Zq z|AMGU#90XWJ71jlxrsXIQ1u0BE8uu0`)YbESBU}q9FP~T8L>WXhDk^c4D=d>Fb}y5pUrLhwbrkiwk zrBQ^6Hj~(pT{vM5^LNj|*KC;I3vY@$Zv#X?j$ctrZ=Ul?5jX0Jv85zpomLU zxG{QrWsd6a3TwA#XHmCd zS1eUjj?}5eI6x&<0+H(o`vEkINLdnNQvKky`m&^9&eXlO6v6~dt8?IDUwj8CGyqWK z06i)wPE_rd@w?5#*FpKYDsWL*y-a}bQ`E6UMTf>ivx9mDF#`Hc{}DqfFU2jSAIzph z;s@cNVWqeA3BTfSzrO9B>GPyQkFaH4e)>XcGQG^(+^MEv_UkE|A=Z;U&%dc;wjB@u zP$Yvve!uMdXG;w65;mB-q&~Kb9|C|tu3jiZBQ{AQW5tr9eA%6{y~5g#*!#q>s}vla z6dpsFh!3F5bo>%|Xr?U>Pvli8-Wbbp7*^x%js2cTNkJ`@+$hF|s|$iwviYI;*X$*x zE5RR&gSPn<0W;(M<_%MzYUM~r7);PmA}zeWJANgfB-ZjU1w&Ja4!#iT<~LvA2}BOC1~1#w_CRHr-3(if(2IHB1@3`ZYi4k8fT;7d!Fv zOC)kD?oq@>OuX%bIE7cL>6!UG5CpF-PLSogEc>Q!9tm$$H0`Bnvm1p2tXgf@D=C5h}2J4+mbpfuN>S-5<|!KB&nVI)xpd3YpuY!UXi^i z%_!m#}b5;Y_Qr&eN2vv1;#Bt;YRxfUV|sbL6|ZU$|C>mdRI z(g-2$;u04qqCT|cq>Hmgo@QN+zH_OYS*g0SPif(l;VkJ!qDmw@3P?pL&VWK5TYBj* z1O!}281YAuJ>?~>B}_OWQ3!+(B);*8Tj=B!KF*>9ufs=2^uslx2eJKN?=MPuX8$C$ z4tFX*yfbN+-WJH239t8r2{2s$H9&ZCDyfOGt& zS7Xg67f{y!X`lXuYcDBB{o6Y-Amv>Al|nSd4hZDvO#;UA)&B^cPIt$5fS=NpcqUdt zjQj7^Yt+JOH{4tIsJ|Vx&s&U2LNRmM7KY#00BV$zl^;|r2jq$LM~GrMC?hH2GHOpVdebQ7ME7RcW6XB z&Gd=YJd$*%Yb}yA7yX`gn^8!bsEYM9X6q%!1Cg1lFC>*6fTuHqPdExN-PIP?@`gXg zy+H6`UoQKK88deRs|zqs`se+C+_@79`+Kcax6ht>EmyFC!_24-aUnCE-r$2te``Rf z$@H)rc&S4_&~m@-)nd9I-Bj;<5rcG+jga% z_z4D{^rIz-7>*88($Oq_zpqZ~zW%FpRf-}3U;Fs=Br8NiwjPe$*Qe(E&Tn#GgtLQ* zh_cL#g$ZTjPtbzyba~F*mI$H=x$|N19`Iv6o{dRZ@jg%VqVuag0Y0}gcKOdQGlUdLN&dLDUI5K_Zb%o zyM-1g&sd}wFzfGT{*ekrKVz!{!LK?jL6n1svweXoj_x{)ey1Ll;f#ex8_3kNQ@~z+ znLO`AH!xqz?xsOt5BCi~@893gZZx#fL74bZzuEF5lOZ>?YtcCRn0sE(xR;q5QUpoZ zPw~QoC^foq2m3`QapW&VaDm~+h$RF1*FOBXFS%Gg-0MbPi-lxc(9M%)qcV6i&(QAJ zAaLo1lJ|uHWi;bSBY=_ieB*D-XVPyl4`F=M-Rmx*TZicnPhHgDfH>jAFY`hp z4Pe(XrXly^z0cq0+K7mFzU`W2_GSY!$7?DtGrw{WK3`LmIi!yF{Y<|AxXO02#1GjY zP@Kz(&~Sv#x8~8{cbnatF?hgwd;(-EAe)YNCy_->WZn>8wJ=n$zq+mjQsG-|Vq8dD zRTN&qCVA01b1HR=-liXw%@x)Fh;(#b&CPR|Z~&KQ`&sVa&Jx5>AW58-xj6apalMGjMGIs|Z3RC4@~V-JsKFtGHu9N&R;s$<5)bVY`3`C&Txsm?es zn-}4$NE*m5R=lFK-cf?YDwPaTWE233m3uTuNoA+GF&%!GkF8-Ai11?XSW3or?vVh| zeQBdv5fEAGMkl9=s-b@8G-^=UzSmm?_ZuUlsMke;Ft^|x1F zNWa-K+%#d{w&JOy=Cm|Fa{}{CayRATJ?*h5G7XQgat<>VKRAs;f4+;j z6Mvk13JaE!iF>yk!AZkW@D{-aB|un|a9J)HM!aJ&fV8FZZ%g-=TLiDR91jgGO@JI* zCm6?6Z@+K~QXMfgiJchpD|_6~(F60L@zq_mC}Ij`nmQeQbFi-`)`u#cC%V*Sr``$; z5j!&gL#T85iOEL6tb73Kzx`m1Kp-ZnS%8w|QB9b68s)H@m8h@QvgPzk0{yNl^jjT0 zb2GgBT8OY1m#glrU$vd{>}MXDobsbj^jp0UaJHbRZbcp~-9s*A=3Z>E{haHlk@AL! z$_JDAO;yv<`M60lnOM?%mo9f0oJ0NcuQRu>snHnZGL z-LK^8jK8BA!Smkv(B#nJ%>*vDS#W#Q(SUDrmRUAX8T?LQB2wPCA0p4#|JUlv_5;PR z`Tbj4>g$>&5#%>W15iv_X8c>j9|j|(CjSKpiD1l`L$U9$(C+O{eS~3$+@=`nB6jYc zR4i{VBW*f4FFsC=_949(+TbE+?yNb|k|}LB95a7`cRvAV;Saq|=p70|x?I;Ey%!z- zAl`TYV6a@B4Mf2y@8*N|-J1GKn+H5vpkK^CHMyn43^(fvkJ!DssDt&XE?}0Q1`;O8 zGy0aA*nSMo>k-bcs-Ct2aCd?=YT=1J^_|?QDG^+nWj!j#?my?-57>?r%v;1f$=64U zO4~K%3g5d|zHa9C$*$N_-Z2X=ru5mDlixZ32G_dbC38%QF657d!W~s#3R_Hs;2!>| zl4-!+bcZlq3v)A%LZB0>&3IzR5dZ`RAD3d8l}LcwQmIkG!7NTLT+BxU`=!AYHRHp9 zDJn%-=_?=%Xma>pzK!q)18!o^1gywBCMT~9ksY3m@%ur&BgGFb-3ot93=l5UTWlz_ zEhr(^P4XfBq;QOyldL|l8eU{Vtty0LOvV>uB*l46U$~Y4#g_za{)G1Ftp=8aL|wGXlHz{45H7-gQH0j0{x61EU#B;jOH^kbhOPXzSn zfU-FuTH)Dc=R(>=&XGgaHlrWP18(A~3;+Pj>+eOh#q?@)Go7so?aQ2enwjs69Fy6m&^r zS2N+~ilM^N0th`X-Scy!Z}ADDLsA6`uLr;+u76~Go02kS23KUj zUaiIPYjh~ipb{k}5gyOaejh9!qCFv$J6=ksP~9SuXG)hyvu3z+;Nk$h5wh zXRYUr!YZU*dFL9Zss{mofq|pG-Xc@Qv#7-k<9XkL&g^mP-P|xSEdckO0b_-Q@;S4d zko!%nv>zoavxs(^0Su2nr6Z-H>F6@=;kLwcgU1M}!@fKX@+73kl{6?#@W};Pb8p{0QjDO|JbP zb%1IXU%?#l1%Wni+m4?sG^7*#Q98O6RdNjap_u5s1AiCeUME?PJR8D<{mp%DklW{r zA5^ivUQ`xNBO#>aK0>_!Tbr(vr9z3MNXvc^uL(b_HxV{rDh7|_bU^2AA&-mGF8N7t)nn*j z4`!#SD+Aja`o<}ygK(%&x@ztpHF?QJYPR-v!II0k_G3uwq3iG>U=**=GiyiW?|Jde!BR*?E<4YC^~E|H*N`+3I(z#-`t+4z)N;_ zNe*AUN(Y5IEOA^snd(ngIZrC#+7mcMHJ-2YwM$*jC7dE|AO;U;DS+qsvN$#LDTT=! zi$pwM=9QrWH)s=7^^4YD!aIDxJ;>3ZComHJJRh>9$s_doAY(%VM|x6cy|g8>L#*#h zG{ET2hPn%Y&}1#6HdCFZo20V)^zD#wae3h5I$k(4=y0@((`<{z2ZSqx9MGv6Ov8Y_$3`2I zq<921O}*!DTc~NXXMGcJ_@F_SnXA$B0J>*J4I@b;cJ3OW&+9*xo|Uch`3A&K!=j;N z)oF`kw*<%}@R)NCIV0Ky?Mf3~K*xZeRjogu>+C^2&utuAKU%4BRHNew1;U0>-;c|p z%EZ3opo~qNO_v}8Yj2yw*^i3HC%+WV`OyPXYeiY2zrd>CGm-qVkW)c~Uq3cS_6)&K zaH#?#rr!cwW=pCXHz4Sr`{!_p=~Msq5{Ht&eXa6X*z8jTTlQdh z%iw#$L*v$%1`B-9G&b;%5cP~J{W`wc(b%eh@J%aheBG7ie*w6A13Z;_zNV^T>!~8b zvEEiuw#v4@l*Qg(DXq0Fk&!n@^v{={-g%NwePPe=&V4I1LjkCDB;Io<4btix_+cdr z=a*Y`%v$n%m)tJKp|~Ny=9wicLShzl0nbgF^6&HdQ2t^kkO?hgG!u5wGZ0U2aSQ#9 zg7iq~$qZCo^NQi`vZN5GzeF-2t}qjS&FURXVC)cs z4H&v5y{N*fxLPck0kw_BZTod@Zh`cnOkIUEvmc;+aSjj4uTrR(k-A?|9StY9Yx-mX z2-S3;#A_Nk<4SL@64Y78pGbRd33)iBuG2D&eup? z=NEMBi6Nr#YO5)2aVm=WcjkiH?Zq8yG#ph?!Bu(d z>(3Kf8o@zPL7K%;xgX$W7yWi6BCo-$`;Z3RB4dZPkT*)8sKk*rgxMzm zTl$Ab6|f8_kV#daQlX3PEzmg)f-PE_yt${=ZRHJ71-d_VL@)`(GsBeY?uACD|0Yvw z1dm`pQ6c;~UktCI5SEKWPMeea?m9f;0FP?nDN#VqHmDk&s8^~yuBTS<@iK5x_{(V} zflpq#$GF|3h5D_4K2TX~ukX#MOlFUCGe7I8_LA3EDV_Wx5p7pPLlR8S_XHENmGo^! z-Ix~gE4)HkMTAZ+ONfMmUwCRo@6YwCksvO;53(_RHDN#}wWX=NQBWe3A^CK@bvP~l z6CLRJ)HbCGIhmfP{?h`2!~lM^W}*CGrMM_`-AZl{9iS1P_a~gQR6B`kvv}kuP1GC~ zM}6=5MsJG}3B{&<-}niWz-dS&`E(SZc&Pd%4vi&vhRo3_h06u1X2x$EP6lXF;!Wx# z-MG$TTU&!$L*e(4euW|S2Dh4!RF_eMSX+Gj4tPuOy^`EY=nPk(vgU&2;TXaOE=nt| z=HC)h8P?o6KW$RI@mz)eTIO?e!wvA=hYekemN}YEWKR7FFatW?-H>KX<$8n@c#6=w7fbQ@;p( zsb&}kV`zY@nnhlhSqdR#WQCcFsgGUO8Mre77KrLnB?#^}yqsBd9>Q?(>)qg-DI0pc z;Z|cu*}!W6*@QDy$~`Q2$Z{!87nn?;a+adCv6I0HH{@r8-h9w5SB7fEhdkf}kI-YX zRxZ*2IeRl}@~A-h)rY2G(_X!o&sIO%Wq-X~KH<$vma^eBFZeue+7Dk!2kA)9#y9aTVPlUaV(F0Q4yB+FP@CU7rFy- z!0{2KpEXU~r81yRZH}N>>=O8xVAeDs|IVk)dlLhk11YZ8EPxPB#-oxyPbg0>!c4i*{TIVnetsW7!BTXS8csNYjD2#v|T0iUq0G+~R2yQRlvGfWH zJOXy9&1UdL^59EXnS(IT_A+jj3r7;f7uB{KI^4t3($m93w}0mei5$a8)2Z;Pi?m!< zKV)){Y(|w@a89T>Np-b+^oE`vtm=VUjikT#4hRza4)IEiwEKo!W#V6^V*NfQ&y*F7 z^B0+-kDKa5O+PL&+Z1^Y6e6T3$p%j-fZWb4H}}XYXQPsAf(Ifh>h(TGN-Z!o#4YRP z^Hd*5hE%<)jo;U3+FiE*`;BwP=GYZR83A=1+WIMT%3|pngEnx$r#h5DGWn~?#}__( z;Ox`PN}>OeDK%b!@cE8Q@3v;V68`f&hku__HT=C83&NnjdKx16GRRpg2&@Mf0+!0( zB_fh!lJL+QXQ|NGrnN*>o9Ie+w{5zE{&w0sQrNG}%dDCs;`^(qDt&qbH3Yf?UF#C&oc(a5PKnqnYm08g7Epv zV#tlIpmG#$>>CQ4yQr)#o{2!H&Rt zQXujhI^C%qjNJ`|9T$JRfm;0|d5JY($mw5s4Rj0;`-#iHfR>u+!8{;Vu!U8dmTlIi zbmk|&O26iepWntq7U|McGZMrsC)fw{~(5G6x4ChmJYa6|L{{sw(uh%(& zyevUnudxH@dbK!fuFoqKV^T=C0DQ~JH+D@v0h~(*#l~TbH(;ZgUZ5+pr(KbQ-@z4+ zdm^_5`BmshxQ;_X?&V{D%!a&fL8BO0rgpfCXhBh4IPNr@~qe2R!R24GF z#zGe&_gn7QE&<$1ZCif*voqvdzQh=kKx&i}3o93YUi_4((76@2?U3>9M@PgBXUAT- zt}KKgSy7r8wo54*;X^dGVf9J^(KCcQ(%=3HQ52guj;DIYgNg3m1{bg^K#$QY6Pmg4 z^~plpLcrAV#HT9IcZ|&;S~c@UT44)?c3Jw0cA}-rl-eta35iAlRd+4fC?s#eam+|m zOEJyzVchX|odU$LwyR#x=YoKT{O~os*YbxoC1`c>iduNueA$|qAc9|}q%^&AwX>>~ zMg044iIKYq*{&b}*Kxi-#--|haH3I!>eeR-W zJu3a)v=~W;j3_R@6Qf}+{aa5w@De>x1|xvTYq8nWK1Dh1Lz+Rmdf>?M!RG7loEb)< z-vnn=smV{EO%uv zn+6RRI868YvwlWWT5@ur7bw``nS?SKyC(l`q?FDH%JkN@9e<$&)~BYfsi08SMwbyteho} ze$bMe9HZM_iB3Pu3uafTp;zPeY`5&?o?hn82!dl&dKEqoFK83d1G0MX`6rx=zfH_q zk??HpEUWI0Qufxm1U%9j;g7T&*!^}NA7>~Kp^?q(ro4uc9Z+^I>tME$|wU@NLoc%D~-}Nz zq-D7mI7Ai}G#5zYI=q(n8Vr3jv@!QU2YuE);%B2dpd|ak3L|3gbl2{+t$bpCoM^ZV zj5|WDN}g{v#)vq|1V7v_>N}|k8$}`iz!V}fj$u*l@PV?JK6E0f>hJmBZXfX5lo?|m z{OB#2S0Mh9167}y2|CNS%F5LA?2D0THeEF#(d*UN@;BhdtN(fmV;c8<3$I;YgS@l= zpD&3$zW@j~BK-Nv&nM~P_FH|u$?qQg>D9<3L+E)Gya5Np=1v9~uBINpAbL@UR5~jb zwSX(#na9kMECKpOlEQL4Kk5z5@P2jAw~e!|FWG$cKJ;7RiE=cF?aUJ+lk>IP?C~ zUbnWRg|+*(n-DZdz0SAIgO#UTa&q+=a8bTeG{c4BAZf5RUg~#-lm`+9 zba^9%xJz~is~LsgZi|>eKk1F6CX3lLIo&%7ap9VsHz^vq2?w}viYyE5AiGHieG1WZ z0IyD_5t|dgi03yKeaeZ=e9VwtLgXDDf2PzI+-YN61$^%s{8bPhqS>*0HLKxBH-IP8 z0d=qO%Fqi+-YB~!mFWQfYw|vt_@@aAoI;%E zOK-h9r`o_>u`)aJZx@6&hzx;03fmAUy=lilA#chp|BRcM_=_DI)D238tAyVHY_`S2 z(lEMh__2T7;!^C0+v3tO&d;rX$L64B&i&fm*qROqN$7RxuV|Qo_~if)rHN-d4;qV( z@I&-VKIJ$Vdf`eBCru(2wtPvhhC>xN0kx@q*V;;n`5;}gRxfE^gm|f%MrCa}_R1U){q8$G_}b3m=xL5ynI|Th;N84e`Bf^6h?We|>A!GT)YM ze2JQUX!@^M*f-2CO}@i%hr{UK`Y8+6#}&AoJIJ*HTG`Q#BTwoNt=9eg2`T{?ellK4 z&SmWvXzJ6cW`Z75j+PHTNk4`Z5wv1&b+Lhb8R_(v1{fJ2Ivy+!JLGT7Qt6r+qtDrldja|hV8HQ7)thPt z)mjhKF{PlGxn_@%8Sz>F7kSnYgZIG~gXvxaQ4ii<5j2Dcb>rf6o_dB9++WqHrqq?2nn9NRde3@NaK zdr~1ui$g=*sNdpWpG>*m++BFF>_{g=Opo&1sKc#5 z%LEH@d=ROFylw21SSdEB)%7~!aGD&AUfD1|VO&qALZ4}R9l#<-hVN`8`PU;rBT2jY z*uUA2W+h7lrF1b*{3RcwvPe!^3ZtDL2otvUgDCuHUX#c$3;KGjKPZlj&wy1-eDZyZ zm5_J1AVSBlcHVH!=%NTpOewLF)>zd(fcR-N`^jl8nkG{UVZ{jfpY9Ffv6%%1czFvf z3ucf{gq*ndLU#uY26Q84aqH<-Y+v6mIfu;sRf`$lEBWj&9)&cS+P+o2CwDyegbbo% z`2*Bz`zRUc3p7R2DFd;H$1?sDNJPomLfGz>>)iH5hh{oeiY+qQ3l62s{9L(I>WaFgIvAUu83^)2c)YCm@J$SU)*_#jjk;6VIzi4Bdg=c&;l01HKwkL?y ziV)^)tr!>A>pB~Ik7G+T}PO{Qa2 zMu)|Sn$h#%qrG2$K;Pg5)@@N83JB!Ou!7y)X8>ELpWBc^vKe4Jt~m(VKB)|ShIQRWi;Laxj~1BJ{}-D}YO`(&vk`>N264%}}DhNB>&2ssHr6WE_c z@d!{UhPYH-9PH=za)BLcnBL5KEtLo(=L6nTIk0s_)b|kp zi}>qjOK`|xDP%kcnz=FD>(UYZMPxQ<21?rSqsU|UQa~Axsh>s=d0TRyL~{>wvZ-)! zOEgYmIAkkAZ;+vN!eg+o{I`4-%Nu>r|2r#H`jl|^L5vw+x=pg7slM-`(O&YoIO%VmF>&y0_^5Ty<~5H9x+D&Fa1WJg}G+je|ex zdRg=`$={VOdyMo*+1>Wxf=Yf)B1Kx-->?$g_x0yJzTWnVvp0?o-_$|<9Hz`@9Tp6B z!z<5m7*B&>JcTRVUzms^m0U~L#nZt7Ylp=V&r47Y4K^V3yAlR#K7KtB`nP*`#OGZN zM*7M;=L)kjk@r2!#qsyn?f6Cxd1h{A7o%Cd$R-v;J38c{S{Gi}VZHH9>N!xiIl%yHx_Oy}Jekv5?FWZh;*iog z`hYIIU5FJEja-T3$q)l$NZ&)rzN)AE!eNe26-H_cSa~mN<#rAl6>^HS(!0BRDf8-n zH7TO}@}1K(t9_bDm@`B}`$3UN*o>4*y@GszV^@`kAeC8!9U4ih(>t26O-Wy?Sp9l? z@!3$nglcSLYn3L$V^et}B3f6;^LA7tK1@fgwl6qUQrBpM4 z)poTJXpFdmW(vjJuwG%BJJN^0n$kFxRxGo4c>Ni0v935GF_B-5TBeG>_^+ix`X}7y zq5>MFfy)H*mBMvj+V_|&V+t>+mxhgv8t8`SaqBsV-Uk|&69By=GjizA3RyP?|0MDr zNOM1TtE{^-KL2|^u91O_T3cy2b1yax%UnEjpy$4W(W<+#?0!2c% z`vCxk80tD;C12{{7h)V9ZC_+cYoTO_R8e`tmso}TwV`j;B`}Xt%aYDNOuPBbmU0^@ z5OTz|D+S7je4~uy2OMekbK&X#&iyYVhPum8ffIlr)5n`nBG&z+@3{^jaiWln@z#N; zO>WDWJ~`*>G*=Hwf_EyLrZ}6HOH?42JG^5OH49|wpAjYxl0&8AxmGDGJ6UN;et#!Y zCtld-o$O|C4o|e23Xe)RvMI~kFrCZC$KDY?!U{L_-uS!9FSF3OSuO^}yQ#1C5~Di4 z)c868ar#2hbe6tPYp!JtpN)!redENab}LQYU0tBdI&?voC~rT1SJ8l3=wOlich*B6 z29k|}X(*i~*~Py*%|;;~nfi5)jR;^@c|ow&%>gem4&32j05KR3=Vk@Ditj| zYmPlw)Y{^PY(}Plp@QpuCv=p*SVfs~-&#FhLqDSY60mYyW&8g5$&k3}y&U9F*QgYx zeGGY-Ewp&_gqQQApwuyp!q$`0Og1NEy4W+H@~#K>xji-D-*sTh(>!JvV`-^8KI|1I zTVNu5ygx)JYn2&(RH%D^I&eDX_w(*SRObzWvP2PAL%Xvat_7)q zMgC2BNP%k2PNL)!hx9w&6%}HYDsh3_XCQaz<;44BR6ERzX&pKoK-y3B+Bvyk`4I~$ zF>#0w6zZU|F(z45UJZ>h@ny`Ald7rMyMPQW`ccQd$so{j9&&UA31aVXCW_xd>~D}+ zbUsImV60tr6@~Ha4(Ov1J@-NM4OWRN=MvSiFN}pxRk7J0h?A3M1#*&YDZRUw@aDBt zq+LE{OKu^SWr=e$+CJ&hWUkd@RNK2+biv~Tu7$Cm{HK=LfRivdcn}d58^qnY^O$gGs2#hz6`c1G5(Y=_sy5m-UA+h%gqU%0` zs?>f@et_{cK30YiL?k31D%LIj&VT8QS+6}o$@i<*u<@NpUx z$bKb_nJp?jq&${|h2a~!&x-L&az+WM*3_!#Lv7aYBD$2fid+67IBJ~-4XDLupq*m) z+n*Rw<%h`WlrQE7Z#yEd(4i%RbRsjI9pDo_JmpTo!tePa;}@?9WfH6opew_Itv-RL zQt)_`-?UY7oO{|7$=MsB>Z0)|$iO5y9dkmPAz#%T4fb42c3Zmk5qKvoZkhm@dJKc7 z!PKBKry|Fep)fh&8fyE72Xo9h#(pn~`{|(hMtYBttArnVQfK*;W~b(9WgusdIN5Ce zXhYmi=*JsV*tml+gLVs&gYxeOa#5Q&o)015`KMEUd;sT={S<^U8_VNyAuEg`VtvXAW3o!t*|~Bc%~Q*f?30t6S2%E)jA0AnJ9XVU(6`2Y`y- zPRSYpsjnpUel4Cw^gomQ61F*(VaNuRIs}(6`p%nE_>TzQFd+|Zfkixd6cMe}1#Sd4 zPlWrg_#)A-d?3Xex4Ve#8|2qVuJxJ>KW(n>rTHB%woYi?LETEbklm7sWvuyyIU>~I z1Ie9UcSey+*MBi>dN;!Fp9_nFP=UyKYYL;Z;=j8_>hw2-Wda?cF~OLTT_m(zz{nC+ z%tcy}QS@8?7|wiWfFg4jhDjMOI#kVH;NJO+b$|( zsi~*o*U}2baO@Uu7$h-*qvtkTwnA2%-8yS(PRc?;h*v^a_;t-t(KkzWe7GayHlIg7 ztBOLbakyV*pk@R<{v+uuwxd;|F#13Ya2p~GH10OTY25AUFZpkVSt}i?ICZ|gX`qbk zb>Vy)T>!>eUiHlyf6#B^IG;DN8;HQs`t=**+}&pM1rlr$`cpp7EP1~mpagNS56iZ> z5ISjAwF8&5g-=M!ef)s2Oi{)Z+02GcxC_STk_niv_Gg|u`3kP zi^gB+(yb&oe1b{Nc`Pgl_$%^yw+BN^3n}5X8#JN%avGj9kq9dVrs^ba6FUg-WuLIp z^7y-QhyoL_5MuK04HBn`a`+G)W9fX3mBH6p41A;CM#azFOJ2iLY77r|Ri057bfoBd z$}|=dO$>tsRWK8bz9*hC4GUm)Vj%o&1f?Yg36*3rks2c=7?rI*%13pmcrv97+;bd} z4ar!j$+{nl;+Zj@k9D3n-6{t52u>=8c_0Zfpiet@2PuX7wNjr=6PR>}%WpjGX)?%j z)R#3`nRsb%;@W3^tnGZL?Zwe`Igyy6k^>F&UtIxaQ=cH3%%RJco^QcHz!(AGXTl@n zOH}~QIpbW#B2_YYC<=YPLuia{yTu{+OBQYb7L!5PQ|D8g3a$M!6k0%{+&Kc>}y9Y6jfhBf2 zzC(uP@oDnH-5(`gj{6pl_ffuIfQy}=*DD!%tjxH15!e8oVhU zU-SxH)c*RoK$`-tEjCAKoKEoT(4m)8vsL*r<^=$C|7C0|4y4bn-{T0#G zIT=I@eD_@)b_kQ)NJeGahhg*F;E&j7tws4U&*!P-zj~Bo?+T0USwNIPk|>x^RN~Qi z#)KwQNYGNn@s~AXUl%%<(#FA~YnLaaRqfQvAyulsD({P*lteSudKnmW@Hg$Y=qTZje$%^6}@(H#F?faE_b@z!ru3(qDDgL z*>FL_gp{ZyP~$f8grGi1GVh;|*EdFY#C|OK3-Tl^Hi1|%qaxXW6v838SJ3_{yJY={ zaScj`{i`FSERaBG=4>&yMqBjf(}+w#MlshOK$eR^@^|sJE(IcGM*Xx(4=xqr#WkJ) z7fJ$lTS!TGB208+wo(O=;hWN^*Ft`lHjw!Bk8gjqa4}7K@Fo{dKDpFYKLKsR08=%A z7MuFu)XLS`0Q>0jzH(y&bCcv3HG#GGU6O`iI%OHqpsI}%V3#wW>k%;2Q zftwFdNQu`D! zvKbdZxe*qK)Q504X~*~!y&&dR>Ww_mT&GbGhLU%t_czb(h|*pT%_+!_=(MGxa-mY? zjJt*gj>A@4y|q;xK~UcaASxMT;_3^a5vUbY+fFBvhB77FDxIF|K75<-bf4Z18u*zO zToyRvgfukP(ZTQ$v=|K2_gzyc72E1fiimLbhm2dz+F5C|h*hGaOBK(bd_3Ng0?=jQ zI#i4Ro25ha@6BGj!WSQU0}X$F5IQKD^CcMTL~}ODvY8j|M9TES0;#3#OY|b%Dwpn! z)17c5*YU)U{sVoG55>52d?6YB1hGYjtXP>3@9_uO;Ph-Xr(Ii=j=zX}&SpB^sXN_R zL@~fA!$#Qg#P?Liu}oI&qM1u>wAAS^q-i^Phdn8;_f~c`Gy`Ex9nFub-vXFVB-*e~ zs^OA6SIBt<`w?Ele#08Bn0b;l7z6^>6T+RuSxsG5{7W1>A;p}E9%|T=ajp*M6A4f8 z+F~Wm(3LeVR)&_Rn^+O^CQc&}w6(-ycAU0cy44MPqMUjQ$Mg4M9gbSA@G_*Y>D+r! z@a8@UD)DCPpWl1F(c$ZkTBx|E#;e7gs2wNDnmVQ?ZB)H%qD*+Ovp~m0)pSEqKH-$^ z!gS6rXX7vQ`MOPciABj1XnyRHG43^`aWH8TX6%yV^C`p)w`0U>TOov}e5HVEG% zYkudqf)FMH($U1#h1d)osXY)6m9E5MFH@iMEZ5nno6 z67Cd#OxPj|q1I|Yc?x!-_czs`NHvU`Bgmo?Tg7eEt4o%KOAqtY9I|@UXiPIS*U|V7&5J2)SIiiRA{AyyY zN5=+w43PNFZI|)56Yi z(cQ>BQZqgc0B|^nf7CPGvr_MIX}RPqH`ioaKIA>X87;GLlk&Pt5AAAsVm4N61{voa zzjoEvp{G!MJ6IeDlwW}%pMDFN(587~Bb@D-Q{2dO&d>^+MtgwL zps*|%7r5bvwe>+Mr>bG-(qf@bQEKS#JF?`-AsQt{(O`^+g29hFpsZJGcbuo1#oNT` zez+m4WE}j-8^zhCm*9dhA0wrgJ-<`ewbaXCI8U^J(UZ+W`dvwD4zpsQtmADi+dB&v zz@YbDmyp4P9$875LAtZJ9Gf+z+eTCqdQ!X;@@xq-9d%p-mA5IuLSzTGsF80b_|nRr z^VDar(Xs1_ty=&gM85^*0ssoqu?iC#PcVn%mE(!*h|b2 zKklN`WnuB>%BKqLK1$AJ=#ym)65rbdgQLdC_`Z{VV5xxt$)u+ib!l~Uv-?+oReY|W z$e8WkPqKp@&ZB)7%U1g6C$LlCSO0!GF?`D@$KQfhW5aGCoOzapm#Bxu%i%?sT6+@! z)E30CTiO38Jc+!kfVVnEw25{eckaYNa`j zUbq`g9ZAQ9n`)Z#R%5P&pCl6w%N1Tz2{gYgG1V2f#r{C)`dkf>K(4QWZe~RABc|Yu z%|3;o%8Sl4tM2-*S(?yZs4Xcqs56dqlph{8TiEt|BBvUhhrVp7oH>N?m3bR%NRi(# z*o@Wz6+(KNo#^D^-`pu10w^hrAzvcT-UhE20N6imdDq+J{+^rU)d}tjv+oo0fJD~< z)L{r#gn%SA02U0O7eJDjiF~?Y*lV-ixKi6n8iiJZS%w;)>4Ni1((Pv*JDv5!gWKYA z3k;^YM*)V5r;JAB=Mz>_!VvAV)31Z^*iPU8!{1HtLC1nS(P2NR1B@??__QhfF;(WU zf)8z}R3md@+m$c2!DmAIi3S_q_~8hm4_i_Ah*mLyQ|PD5F_LcCK`U^ z2ja?j&(Thu&N-^`BZYC*(xlnO0qjdV8!#6aiBmcBWFFhFy&FV%UK@`!Y*oXd@Qcl9 zkVl`vK>8tF6s^=Xs94|@)>;Vp=jv(1ZVaQ${`dg|N>pfadZzg9b9sr@ch0Xn^5Q6_ z;zG%-r_+9wnbiOj9|RsTRs=%NTu-Ht_R{$}7>%7~g?t9KqQcEOZuCy7(oyBAVSkJTZ;YqU61dh!c89 zqRbi!hg7n(yDoByk1h(zZDAZeJY~LeYYvihc!mtR70LE_qeY*x?+LQTzh^*%VcVvt zz7f;6APX$*uEGfiB~68^^+Qt1^2L_D6WK?X=5w)WPz|t{^sL=I1bkX%xc-95?QM)}d9m9!*v>gN8;dM(!BL!xzdI zgj;5B=_VCI&Z)rmY2RWWQbKmZr9LqhGalnCRCF|H{mYHi!gS{I=wEwe3iAZ$W?}p#gb&QZl0;9~V$t_c43iPSC532)i$Vx0nyVNEdH#(R` z7elir>$yMMvE{_*)y#u5+ z*be~^CNT(l4yKsDABQ%`L;C6#{s8^_MjSdX`$BAmf5id~PW7+5HC)bcDo0(a6whTf zI^s?BwnJ7sOqFi(cqt)f;)AY>2JP_0c9(kxQwInfQSom)o*>imk^Q`69ekzFopd9h zws#I4l2soeixXU7v^bET5Hp%CL6l%MRWHwM_!XS-(kJW{cz^p=&Rpkog}~t4hm^ZE z)wY~gCH7+#H8ik8(TekrryEj(;Dk3ppq6V3Rax#AV!xb!7n_I>CC#`sPSGY@1AdE_ zUzu9i;OKDd_n<|dF}1^?E{d92BYnyOuR(kxTgreIut)~k%o{M-aBcN8RRySu z@&%q2B)LIW#Q`|=!gk%Z4=$hD7z3CC#}5gyV_5M=*4mMzkcLA4070@v;XuS(cr^1uzdt-iODluRpQq{H zKu&UUp$*lTnoeCm%dZ|Lt%^#viUA%(c<8w*6ez+E80L3gTaT}og9B*y``g>W8uyDy z^y&5!CxX$h1Rg1O&oHn(0*JRayqmGbmN);1Lak`QiV=U;dvcRnc)$Hr8csha)61d2 z$;UhGrmw5zKyCGH*RqG;?d{)$XKZV|UBvz zq^Ztf+o%9Y>X6)!6BI|S|KyneAk7%Z`PX6Hi^(Djw&CFR{p|?IvZpP3rMq4)T z$Kml=wog0o+82&-0rPUoi=PE+;`XZ*9t zvA5H&-?Cinn($ZDA*B(aU~Lj%PAe=>O<>{Q*!i*WNZgsQV!(vZ?w9w7#Ma5F3|YTm zD^PIgL9UK56NH6ozi8x&Y)zFrt$Lj;tsGmh5l&k8FB{==k=JG>it$hyAifDHD4U#_ zMT-ZHDvN+KN!Mj(4bdJ65j^D~ib-vhy-dNHw1AfIlqWmNSKZZ)h^JTAAE+YED9rV<(ptD2(13>)0{_=7sfEj+t*X^Ic*wt-U z0CzAyphl^tz4C)?6 zz^&2A_0C!p0?ff`aYY(EY+0-cl6JjwjZU7DJzrtJoLQPnpZ2BP3@@{%XQGUnK@iUy z33s)$FfiV3d@jBXNj5M;TZ)(oWM|3{2tRtD~ZEE_+e~y%f1I{Gqzq5pnK?d!QT_)7jT$d z_cM!B*JWQh7VoJUSuYJ_hkX9-13S@F+A5Piu<6*qK5{+)*E1Hym1Ep-QY^xdNt#$O zP9_ZVHB2}rgbkeBMDS$SkPRGyeGr1we^e%RtlwhnS@gGOXu1Q=&tcXzjAV7U%O0@x zbtqOKx|H=nn+Ev>Xn}Y=;};cT?6j0OSK&FOc=>}OFik{E3orI_L|f+Q8v}5jQhyB} zuo`(tf@?!*z;bTW5YO;A`bw*p+*aONQE-!nO8WAw2Uy1_&UEf-u9j=Xrmx$!QjSZg zHlCSVQ1*!F&}A3hcFH2=3DMz+e-Fe-9Z8P|(sdq2E7uZ+o%^wz_3z0@p$HVNe+gRU z_X*VOya&IvZca}54pxy7jZZMjt4+|};)(nWVBe^F9z*fg^p}g@LYrATTym59tsXd7 z39CkT_=_la;!!(!DgYY>}Yz>E`9YDMzBz-D0-4}qM zi?o_0v=ptl@2ps!_@&Y`8jBh<9S@c9h~7fZPu8pk7 z)<+V;oIOv_N(y#UdK*f-DHj2J)VGp)MVAT(mYkg;Z1DCV?EGSZ5=(BynpO zi7r~i00bm24VGN|x+fu!eG6D`c$xI=z@N(>Lz+OSLw=(&>6(>P4_Hb@`9_97!+CA7 zj3g+3T!kc@)tAn+Tt1BjY`>Z%nF==YqB*{e)I>ihYy(8#Q~XrOWs;~jBwoY*_X7G8 z05Cn@=jU*!m>47MYY>mB zX9Aa<+YTeg2K~_|^Aj6GMj?!OOTBHNxUlihh`gLQVjsMtHvT;+5A`iWhwiZ+0PSMD z`f%~wbE5&RKMSC?5ee!vSHBUduistqVKQ+=R4b>QNWU+%ur^ z@A?TL-i=BwKr8#e^O6H-938Cucnb7HI!Y-43kTF4WXadZXAa|ZlFKO}1rm@g4*JG> zK-|FB$b=YRoyMph@cfupj$ZN-&|Ap|VEmL!aE#mcgZssaZZ`SodqN}lmV~4DD~LJ3 zeY9nNS##s?zzK84KNYi?EkubP3c}Sk4b9Ajr?5VqyvL730Yn#e5XV@D{qoFXBa_?3XjY_yhL}z zZ;agrDj@hV4a^pfbiDIR(SR_42hSgLR82$&AOj&8*WhnynR}b4)drF>1j*46?C;E1 zVSqBdMxG8*GBrjrA>$F5`q=^C!#CI)oHZXB<>r<2rgM^XmPrT;aD!lqI^0n}w$9yr z)unnXpV3z!=A&0G-5*_P-~fRiGvKJu=s1*Kr@OYU9d6=qy#ioV!Don65Th9`VOJYv zsFh;*;F~%UxJ<9Tmd{~P{(|)nZlMvh??M5R7mg(;*8U{aW&!p^kmb8&YzlT=b+9F{ zFWDEkLcG94nF*T*eUmQTX;2d?lV~>tF726Y(7XKb*^E44roh`;Yzek5$YK%0Tz>Ag zJH4|1Oo#Y-Av1;tKbtN}le}TJaaYTZtdrysNGDtlndu4BZ=3|;#AO@@amL8z{qi@! zDV=^VUXMz?gAyN)LaFr$7*4!t#bw}q4aQ{{`4%5hr#=C|9K{S#B4M-e=t(qU-Ku?#qHM!nMd0e(66CH7L@!`2%O2YX1!}>vWAp7NURA{!i6W2sBo{cApa{Gp}(? z0E|)}N^k_VPmylk#=n4jznLA?6u#Wzp?Ahqc;Bd$!}E1) zDv@L_`50hjQM{OgETL`?1)DYAyG?BMaE)Rqwo{moAtg!9AfdkzYhd0!ny~jSqmqwK z>Q3@z9H#20miLUvH&jHXwO;j?spo8NW`UjqAJ*8bm^mNyVgxwhDcEZZ4vmFHW3o^O z7B?HA6(uknhFw_?#o$i{x^l9B86|J@M;u03gD4B==gc!~*Oy;%Y~{Ca1D}ZKy&o9E zeG6blSg9di(vI^$9{L`^TJ75iv*O}9JqEDv(cqQPf$~l2=c_=Dye-b#=d9w32Y83; zD^rx+h)_Gr`+3-%uuI?E;mRGlJNy*GnAsR$-`;Qi{tgWT{P|~&bSq?ueL=io|fmGB0zj%WEERU%=vs_b)!l-k)8xvX3lF^W?GnIYILkh~1 zG4RS29NwO;)_5jMUx+YH9mIy2SKS$|n4#<*@eAJClV!9;d(@2JQ$OejK8=)t1({N% zk`6>60DgEBv({7%CtkvafkfZ>uZc&);u)THIL|;PY}Am_I!Z3D9@ZIp=6lAryO->dq~7jr#|$G%76*PR#RkP4__e6w{Psn=Y|`C zD1N&mT;i>I%uM2WSiaIM^P@Bk;{=BCqe$}n_BK1CWVT~+8Tj0@mLPeYgR61<7F0>v z}&K?dZ!L|!cIcguY36LP-$DhcxPUS zIpByLKBXt&>1uoS;{fTrm@t)XVtG1GZkLTf+d6f&!zsy2ZqcDNzQ1aF4MSW%*o*^V2Ndfd?+f6TmBe;_C9u6A zp4|e5*g%GVJKw+?%SqqgE)DmL`|;Q$^CWg$>xzP?;XnEy2eqnf)$~+f?6IwARqIsU zut^0ti1JZ5lne;n>*2Id0kq|3GRRm~Wz!l0&3L;s3&}32jzY?8Ixee z{~YLJ;;Q6d0sh_aS8xuX7~pU}OfKtQ4+~G0Cf;+iTFbYBY7k4Dg0{-9IyuBDL35e3 zI_l<7*;%Rj3x%6_fSdgg01qwzsC}J+)#ro=6dfm$3n@SYi{;;M>%Tb;gq0vIjR0?H zCfGOY;$m5E6SiLP{b0cExv{46e>>45r|E+XNHHZAJQSPKAANjR_5N0N!2y>T-Jhm2 z>n8Pr6c5BS>cIuo;m@b#Ne+)+hqLfqa1egV>ZYW{}san%iM8`LnuFkP3|1NCRSqty71?lr~6_^bCaW7TtPb5cOAlK z^hkn56HyTGk9ksC(Q0L0;te6D@|#?NYWf$tdT{D(c?s3-Y9eb-c!4`;}$D-8Rc8@S8WC$O$uRRiI zKz+E7=HSl&)PGOky%^57{VwR}c!Q;2Lt)fD>f9})ve{Xe%Mfju?%l1&^LktKLkRAW zFP!4&9wp>U%K|Pb{E(PF6lQ3yvex#pt^N zefP$grckg(u8YuTD{C)S6tId4J&65tRSDe)bn*!uIJmxN#PRj^tuwmMTL>Y15B%~a zroOtdGfiVwd5kGKi)rbLN>1|~F5|(Dj^fLdax8pBq^lr=Lmlm%m%CH?GPv0lgYbdn zz;EE78>9vwS4Gr8LAIE@6{Ro_T~YiAwsFwr(z=p7vJQdH_z%q!3Pq_SC7?EekbwA&jkGyC z^C?Wpu4fVn#SQkC)&0dsJ7LRL4V?UzA3Tt&j2WiAqUqCzRn-vKi_`ZyQ0U{F>7qpA%s>(#%iP!-{!Y7ttOxHSU2IeiYEhAb*13DIcyCqx4U z_~rfGTtp?$3jN%r5;x^iNIXpUM8BZbf+kFw+|9&c%C0k1i+`T(e)Q`6r1T*?>!e13 znO+Wf&d_bS@u4jNn%vs{>juH4e|_wagT-FhiI}Efez_n3Pe8E0Y2RvhYPTZDXWlZ} zJfHO81NrJ3@c7%0G~s}FX@@G;Ln)E#d7|BEPuFaTA|v0i{=`^n6*ZLV?YB{B6Q_63 zDuN%evvYki?B3gmvf2~>`l1Se(p-#DH0HQ&5x;+)_ zx=9Q6u!Kgiv=WBjC=RMz*q#0qNCUd%aI$wSR&kv^f^Too2^9H(6b>`!Q-wgj%FLZs zB7GQWK6WnV9B8&W`kxE$au;;HcCU@_`mhqvP+Jt0V~_A}D#3oqfT~vF%V_8lXy+w7 zs*+n<)MVh#uFEx9U;Gc{xWuqa@ktXS^*-Pi1D!wwsQ168!t+}lT|%IKLll#%cD5J+1h7+O3!wNL zI(inlJgQY$y2!9yBuP&H&Z(Ij6bIUzqCGO}$l*MxpZ2RGXGubM*Z}*<)ei*KdacGK z=AQIqYF=(>_z@zyZgF%7p!4BU4}MNmAl=FlvC!0 z-;(q;b8ri&Q6Hz2jQHBjKbXxWyjd=p{-YGia&{dpwS1Gg)LK5t^wzz74UaPr*zz*$aKhBT{f)Xqho%x9SbqUmelQVQ2P>g<~z6uq@I?o+-n zL7fdPEY`hFx_(8wvaGS!fzN=TRu3pMmC}_$ccFxn!b$GW^yWc@oKs|I`Ds#t5RC*Y zL|uBc8p6YTMNRpJcJ8JCT@^>|{YeY;u)m?7;Sim0+ro9aJoN7HT{mmaRs{n}8l=VL z)IgC3La{w)`eI+m|9!%}67dDjB`JE2$qXI4e`=jqf2MT%KD0>rsy$RSe9NG>FypeL zN={<`xtkDG`_iebtcs^AP_Xqodm!ZhO5L^afJU`9H5HT+#*0c!kQ_J)|JyC1m)k9z zvMC_uS78k#CJng`q-zCaj0?e1DY2?AtmhOK7hm-yw94xN&68eS{_X0Aty0);icGX{ z5%33Ckv*ltjNY{f=tHV%XjdlBn%P9{OLfa_N`LTXSa!0A13tOM?58jRI;4AKAZD|V zh@-&~Gquj#U6U#!E7>Dd2V;Z=mQvA4be(+Mw@+~AFV|Pi(b`jQWp-Nc_I7F+7hD{B zZT1}^&3(a3Q`0AmRpUtPwbyMLkXP_K#Td>Xm0Gsrp}lS6O(ufktuM%-Wh9P@vJ?;J=l34M94ak;fId*PcLF38xBCIi|D^I0sH1358Y+niJ# z=LzzFC%cDjKr^##A%IUKm%v!|7Cpvxj$JQNieOG=V2tNV+meNk0pB52e#o1-g))|G zBVymD|DqSa#b%`yP(I9(Gy&|(MxUKEf1>Wf;EfvW-_2;oNw(1Y0no*kJXMq9>NSXK zDG+V4{pNQTl6SqF8oluw5ZifIt4xhgWXRG(lU(VcNxlq5!JF} z!^0_V5j%h*7w~17sA||E#}iJJ-)0R)+zSL3buA0)NE-Pi0LpU#k`6M}E~5=&Fq@8% zzo#naIMHGnSblZ8tA&;c^&&mzbXE5A3d*;IRu&xOVNJ}y4EH@v=58yfTt`Z%bVcJ0 z0MLHr^Y?Ns@&YH`u&KRb*LVp;^CD5ePu?3{4=p?*IPK?V;CPEJjFW_S^*sz=ABFrO znvcra(D!W{50kA3F}WV{DqtG#r4@yq<9~lC+sa7m8k$!TLhv2V8U2Pq89q6cmaZHb z(9;YJZD5*;HY8u?gYe8EdYR}2^Ft2I_D4XoAM0a$nKSo%LEs$p&fT56JOhIKi%g^(qJHZmEr#(m7Um5i9bOwE*S+j!o!d^i>q_MtqH~C!^wTn1 zLX+ZASV`P|wE6nMB*1i?yT>3g9<3s6x2|8)bdguEuC$+mgz)F#0s6^2aix$SIc;N5F7emB z>iFdNfw2oZ?&FpCHBDM%UY6VJG?|{UTJ5*uSB+Kx<|GK3A|n}q6I?4j6G^7x62GR8 z@4gSp+Yr75qwI>4KOT&>(V!zy963hKzsfWYcNV^Q(YwXKZBnQ`zQcDViX>Zc_=bHL zLVW8(8wd&UKzW#8z^$(GonkMll>t-bYD3VKnCe9A!gc-nsBnS5%$Jin^nd(WQq8ao zv!~tU`MVIqbK|LW!^s1gpMVh5fdixGb|j!u$C9%yNI3D+nNZvnkZgxsw;&=24?Iv{I1TTl>Y6|U#^mf37-Q!!$fGFD_o$=lYd831`36Z<5RJQ2?8F|;>6K+Bzz?o%WM9pDk1U;#8Twq0jg4B z@kRgM7j)Y68Gagp(9ox=iY4?{{9TGFr2t-xfA9MoGK2%ak|jKKt2KwRXX8aL@uiB5 zbNiKtD-&%bFhawfbN-?_|Gmo>_6XeY`N^l{4UQHRv$MeZ=0f%$83n$p2HC-~j8!mpoCj}o-Kq^I4Jx3HDkobQ|bLt#7IZPEGwlCR=(PX^qC;4CoVM06pW zsSN?FQ{O{f-gtVcrmdt)Z6Tt6`;cweT9L~@Aed-E8i@I6V|eXc5E+x)osn#G3g@I* zdyhr(^P=PS1B(xCY`wN5h!HAwlbrMXxW2#F-!rM9wHpVQy%6GcmHrCI-*(IBOI@ZMkUUc(AVvy!v>;NV?G(7C0Z~&N?LJU!(GozLNQiK1#zh9@g_*EUoFYNAIi*SuFmJ#nzN@`P{O!Mynik5|=ZgGF5PlbQpUv&;oOd~e zP)Y-vgSXoLw!A&u7Wu6_&!0?c z_Mcyqj3dpE&uJ$v-tN9+e*{bi*)A#Uss79u8sRR-DC3Lo5=#5#ewzd{7Tz3MqwwYh zOr*3t?ktds&f(b6B-(I+uwR8`3+^FrtWJTprOr)dY%BV7KzuTSD)c2i&&$VfH?0td z17aXZ&SYT-L@63CnfO<`*uT%(co(A4Z)=^~$Bi+*Atu@@1M zuYpVrJbBO_0bVm9ir#;D)Nq09s4=19`d%w53=*!jx>9LJTm2d3co=k{TLId-|#{fzb-~3}^17koMG)3u$P95V)REPMoLL*v9wS z#T>cTEIkPLkzQ*55zd>&e$pzLQ=gpH0lqQ2J=AaBdKZ_}SP9&KHkMT?%1@yi9YQSa z%=zjF{o3cP9cG=}{y?g8*QTka9H$eue0%bM^o~D3Hrzt<`+prsJ1Z3QnX)$!d}TF& zm)Ed1%53UnozEDL!jhlLZQq|yxaV)9#)z18Le%g!y?@Q=w-orv+8>bv^UolRQ(F`z zbL1$lFT-7e{>~kxABTx3!nbPJj-sN1hG5%5k1-|Q#5V+cz-{%UE%0x=|Hcmlib3S6 z2Yp}lc>L?T+w=-u4;}*wdb(Ncy7kF^Xe+wD)BGa3;h_=Ob{%h_oNi-jcy}gzNT~?}~+4&yi^}HMrZk ztIGuS3s5UWl$rhY$_8M!6CX)6{JUsF-)AP&E3q>~x=PLowO}=6Xm5$%?f8=7=S;12s47~59NEZ)LAlhHtHZ* z)jAYl4K4cb23l1d8w~SRcNh&55m>3-Q(%d)1xKS&hyoaSyaB z98QzV_Q20deu3#eZ5K+1pYv&RHbJE5_sS$}vmQPMx4CGT&j*M+efymA;Z2c>Z|V_N`QoM)o#6_1tL#VOanJG78JYQ;vjw$K^>8)9q`q!h z&tz!snIz5L(lyyHocHS{+)`42erjUS(%){R0=paA>9)3#Q*!P1;zyHH12m8Amzp9@ zRt4Sa33ws*aO0-6py8VhmSPfK#f7b*@wZpVZ$}vlN2h@>q#YD$kMwmNyd2?d$LY`+=%_I#{EkPaUd6m((i*vk2vv!XC;?1O^t{VrG(H6>( zv2{8%TZ@xjRxIz*_qrkeZdP`RL7&oXIyXuTM643A6;NamIN`M|=< z?lJ+}Q0_U4)%Zep;_{?81>xzefS2%vsYYH!MqnK|w?wg9mT#k*8?2R(lqU7VdZ7{k zb3_M(X9j*krYeNG+ZU9Ge9c`fB;O{TG|&q;+=DPgb#9XQ$tqk6+)yj5-y>dJ zZw}Fk(n26+AxF?1JH!{HNQ9o8Psj?N&};H|)gIg1fBUE5Dms=Jh=}!Hlo>=qGHH)B zF4t?nl*Gu9TL9&&&BeDHrfig{z08}gHy!NpIKUwXu(EbT4HyPbdXKbC)0IpO!tOD# zgQ^Ftzhjfh*;6&JN>L0oT4;CYe$Q307>@6+^OKG5U4Np#71pPXE}!bR3|eI<*+;es zjo?{iDSiOY&s}X`0)ky~EZd9MmN5+0dJydSud=eG@AEMw4SQCC9TS8_D_J9?-`12F z5Yw;2v$>CAHBUchzuPTQAe(%Urg8nWY{W0lv;An9z@FspjY1z7>_x9$zc_rfUfyGc ztM5q8E6I+{Uh?XlQ&ORNbdC+}YKI}!4c*pQNY0sdvC^N>Dcy~>e___gUk)MMmNsxF zBni}l^x=ylZ5NMVf+}O}4g!RAXmWfdWOnv9$zJyPaPn))g{24 z)k~KB%EI^J1+$`j#wUv4q{rBD@0n9K z^|F1biK^wL8_jLJB>Wxndpu^_7_FqeD}i8sQ}aaZFZt0gOxqMl6P1jcvw(q5PD`y) z+A5wbt5pM8(yy@3dh=zlO16Y|!&zP&;h*jhG8Yt{79`&z1iIil$12 zZYV~0Af#SR5Q5ZSD?aOy!@5yV^h}SZeh4Jd%lk`?xq|FxfwJ&Gx&MhfX$!TlaWZaIRH}zAeGi54g<<=F773LUGz*N;{W~e3PmQ0O z32kPBV`Uzuv<0)29@_?5jJJEla!juci1NC&0`9a`iGtM zRrZQ{yA?!pQlUBf-k6@XT8hrE%^--&asQzMfJZv(4^%UK{h_s+xJG1*Bmeu05En< z%o|2I++6u0GSeZQP53nbVBHp8fBl266Xv)!tAj zda@eHn!90VY#0Ei7rTHP==?qk9h|%`yBgW&0N^omqIS&TBxXX6D_x0v#veiV{DJ&p%j{K2#4v3GJ-fPiKR(p*oxD!&iF zA2GcM+Q z2=7byAWj|(Wtc1&5q618Ke~+eo}-`n{SO#uQ3%RRN1+f{7&2H1$aDKBV@4Vz^@|rI zOfv$6`mcTK%uYO6+gnq8QhwcPxn!f+K^*W|{1VKyy|?xm*yzj{oS}G@Mk4ucSOxe;sSd~u6=i>c!}SYk<9U)( zQP`GxN`-hiDR2Z7#WxAjeh%h|RXhm0s^GO_Z#D*k9)RsW+8T&%`uOE0G}>+xis)|* zYoPcRnk(M7Ip{y9u2wyp*7y{ZvZMJJ)Z*5nCl|M=ClWknd6LuK*7CD|@5}UBeKnk| zIy!J$k#D&cBaNtdsl>!bwO6#e>Bz`_1+PGxpck545973f2()lY$eGsqSuCiqUGxMc z)CslH+1rIkUOvsVB;XMtT-1h8fO#7?`ID4CpL`wHCtN3+q`W4?rs@}3Yq5F!!sDzr z3gWJ)lN+Ajkakn+vo9hJw+))~eA{_mL`#Ae@rNn|}y1YE>Mgo&qQ}2Gr z!yh=I-I%51=jGfuc=Bd}KZ6jBrD^)wx7_oH41;S{!{-qQ|i` z0$Gv#W6qoi@HPe<0Zk~hI*}&w30L7nWzE3n_dWM5nq`v8-M&*P$3-fA5;YaG;%@;D#jHJ}9OH@y6eJ;o_VDXzBF_uotw+1ZY^jK8$gEOrry!os{2ivU{@XX$&KcL{!SMY6V)h9mL&pk%O)IxvG7Z`_rvf8{kN#e>N^yVSZZ@u74)DuDu!-7hv`HYNbns z8qa8?7}jC}z-^ARJ~-9tN(~`9Njg zkp2C6BLbBB54eJxn}Rhs9AS|aB2$Zp7-6zrhEHdHj9UE3O${-CK?c#d^A#}45;cKG zhn&*dU_Xq{X6hFDk`H4{v;k`vupcPk5=rQtWjN*7-2S2+Y923ZoJ>CrlD+BqphS?N zknRbCccFIngOQ0(w!FZI$jzz1&EJIP0Le?eQrgCTyS6Shon`;N28Z%*e~!~zDq;rx zSFej zH_Iq+ODmSkdEijyr4_m*3!_+r#6Gls25V!ujPm=7#-EWW21LF+P^+j=OYs0z63{NwlllzK? zUy9cyA@zW)77zjrdVh;f`a%Zn^;GsyX#Ti&hBQg z_^;&A8js{p7bqWuQJkQ;JmZ8YCU`J`HmM=~0_RsgQvqFJ8fq#k;3_)vne+PDK2!!w zxPfYurddz{!FXXhi*Yd5 z-uN-rf~FrX4kT5by|{%3nqe6dc`jh%Zz7cgLm-S3`%~T&>>W1RD?{J#E4ws(aw*zC z-?qCX-paTyi3vIjiLC_LY;vCr+os&lR^-z3S)>`5hdCm5NyXrv3(q zH{Zo@M)CWKv2S}1sRI6DekV_kJer=x^HO@)5_$1ipqg^;X9|uwpWe#wwAc->dm`%LxD=}!{k*>qjoS#%yuvk(s;IRn}Op1U)Oe6Li zPVA-oyE9&rLYN;9lEWO`=PR&zjf)$L87A-jGFDiw$_Qj5yfwp=FJQ%()+(9%1lqW| zy=hoq~N$Z;n45L zeP{jlOn=N{Xg?T_e0IUa%=z?7UM1%P>?g3KVb>5iW(B@DAwb?}7P(-UNqO4^${u!GhBNgBke!+zKZ>w`rWV{uDZq3X0m^>uHL@>^ z*2CuXctap@7w z$ToGzaus?Zb8Ns1N+6DI3~=u(P*6-ho@^IDPz_SXODlaf>`YxyyuM&OVru24T>?+? zhn4V8u8Z4Nuy4urg*6&=c-}14tBTieImm+g2^=Cyk!1G=!{7LEqB8XNZ@ttyY^Y%> zh5Hp4xHsq)sXWMlOTBLsl-gwqq$$>_dP^>p6?X1cz>wVq@gSSXg|2yU6h4z3tI6=t zuKBsxsr0Gu8i3aDSqi%cpCqiN6@+H^TadB@rp9hti6CsY`62QWTUj%7>0l1u3rO>mJF zLqq)=4{z`7w^S1Wz^%U`YV@WiHPK#EP9?)W8D;tLAqD-ascf}FgxWJqL@kV|m_{G! zst3B2V+=(KSLoRL+IOpSk?dAn4C>I4pDmtnM|tI$CzLBY3Q?Ku|?!*wpx)K>4kdUX4CV zN+(SmF~x(Xp)b@nfKpdbqU}%Q5Bvx|p*%S_ErFL>e866tl9FEz^c^{X*L^|v|Brw`ZKKx2*)3nlS78G4yFtKNZQF4=4hd{RgnA+mykSfG7y5t`u#qL zC;Up^?l4yzH_SGQ(IGS^g&Zk^O~mI{LP7@LxZk{*j!g5TgFC!#QLiD@v(zBb%ErwZ zl!luZ0z&zNk2$A-^@hXp#uBp1Zyv>W8V9@fD898#x&eH%_ecOghh1y>TXc7H!|~T{ zN>{2dwhzyTOw$!V7DSO-nLku(mDZSM!UPb9cWI(wmXVP+IQ_9EDx+@3)frhQ)}kt|B?QomCs4~f#5VSGsy9-Ra=-1}&NW_iZ;%b|ZA_GMQ?VQEDqa`Rh{ zoSan{d_EofTQ})PSDLi~?AE7G{xt=hIDLx!$vnO%@Z;xJtu|D}Lb(Ufq;duZXjU`C z%l^@8-Ly<2;eH^#T!0qRzo&EJZ%-2{@4MDdEp3{nk2$uOvpdK9i}gMCsM5A6E##1| zw~1mj71$9k?%!qf>inzEk@R{Y0zCMeV?{W8 zT`Sgl5AWz#9F$AiQ3pUKhu6(BAZlb9y<%Xu4=i(ACSHQzg*ZBR^*Of9T9!@VoV(A1PekII%01U51x&C}rtQ0~Xq%JCULLFd_U zKYjSxobL{qHEF+iRX889w*-N0;)(Dj;K8=^DB5qDW5}(L!7`;zleFYZ z`(~6n%R3DRCgM)f9XmxU0=@vI6M}K%&o6V6B&$RMXEIA)2~e;w*Bu$sde@oPFAK0{ z5lYaUt#P35d60VRt*V17cP`=ky;@b->ga@5FHNL4uWRNtcvr4*4Ox>$x<<+}(toOq zQ`4glCzc6VYJn>@X8*oj#hxp1;AR>xnqA4P?h=592YVxSmAW+RC_bdKyTZ6Up2t19 ziqVEOuYk|o!=rjC%`0AcToj(RSJ_|`+K^MR?vyLdp?n&bMhrF``UHC@Xqak;b*0r% zHryGe?#w-oU(n}IZrs#D&@|v$$ZUFrRulT{UU6&|_%dzz@V>`hDL4C}V{Vdt$}&i& zXVVac#<--{PZk+6d@51;lsl8FP(i3T18XLIoGC$83PD0FhNO&~t7k&UQwyoJw5WS2 zv+kGz4}P@utL~$fR?ww^`90&&tr$q*`NxPLlvL03C+>BLz((8J6LTp2yUn;?iXC;O zTb5{C5dhilKHK!@l5KpH=C-*bsLjX+EPlkOT6eP5wiKFR^jwHZI##z_0S!F2AALz| z(2zSV1H*##4xCZrjnr!Q+-zIWGaJ}Ry4*lYy8=h-$I8A&3i`%L^TR{t@3e6B!;_1p(^If$Cr!Po7dx*6*OH+z4p?HP;t| zAebYZ-w?Hw>lRR(Dw2V3ji*j9hxD8hh_74z`wYh*pC3T7H74XC;P&6J(kmY1YGRH3 zv9ucO**VH{dX*qiU1@8ECR*{i7ue#Gw2WYv7Z)FT$c+(QaIi5z{KZ9?R9h+DRA(iD z=wrWVj59m=A-H{rq$ zO3DkkH9UmyZh}{m3QDe45izFf_~r;Sx}??oDmbc#!8}+y@l;_F!ahub_x<6k^l$zJ zS^k2F=@oR#ousU5vQ)@uqNgM~PZ^E9NaYrh-Kr!?@T=Gj*~vxZmo6TXk^<8#EuA_l z4MHIiMX45jyWR|?AR49!JeV<7Swh6@gvSTDLH35?kV#dN1v69iM2aKYYcg@KToPs{ z;7ai=bV{$i6;6Sop3*0`$gI>_88re$qT9(+kGNI)kYY--8+ySz7NJ3o9B(m5Y>raw zUDm!2nEB!`O2gpA9E^>OAJVeR5()TsI zw6!E{5h7W>SwIPPozWQ#H+HP}^3d>n0s^3O}QE2j(n`aD%VqD8|!V z)JTUPB&?@gEbz(8EGbS`gY_q)KBHHt;Rz#letoICDCd6u? za98?4Kh$V3I>hl1QT?eQ0hgcRUWNU^lPAGH=q2rtO?LW24av>>{aH@DL2-L}zNKw< zFwv(F{Z_wU?G*XrQnoPMoIPU9cQid@$&-KH`{5A!Dw!218mKzrT&b`=R{3tCSUJg9 zg2o$VD>?bgk2Ub2==Sf}Jgf{=6EAb#C{LC9J0`?BNw-qo?9064)Hi){jyVzKnY486 z`BCmC;~M%jmZPByVzrpn6n^>hkt>rd{V#}uc8uYF-6tGN^BVqmsXRlXAR9cmC5N}Y zzUiggY&+NN)0oO8fa~$W9#r-aC18GIXSbwc>FR*Hc#_Pcf)F`T3TC-fDK7VP3?EcP7Dm4XWj+3F5-A1FZFGUO>pSXRZS)u0b7W-?@>K!ToCU2EXgClw(W{4!1 zcvnad;3Ah}K0iol(5EuKPTd;9Sbg(?BW}#M?-rE@Y4~yo1;?!OGt%lZjkab-S9bEy zMY3e4j*G{#)uTuX6XE3VJA_m6#Azp%{Gw4%;WW=8fcn)AY4q)NM+V3{&f{Jx!9yE~ zB+If;s8Ss!Og1u%zsTfUcZka`S3Gk$S%8>)6-7i=`SYDMppA zBQGD3rb1N)DBHQ!Zi`Hs#zt*eQ}(O&f##(zfk@HGL=0G0f7dRk9<&tqF7vM_WX^hL z+O7DEmB&zADZ~nwhgY%zt~H(xOsOP)nuS6D(pXW2mh(w1e3qWCzqj3xjjw&T)wJ5`9)G$Ga#!a_R=nYux;QBHFVZ)O@|7k+Y;k&Yw zF{uOf35ahnrt?Cs0wV8nxZtFkGF0%5kiG6PT55%|&fsf5>zv^jmUJlVdtNFBg#xwR zb}Fw4Slg8Ep&(bC$1g*mA|o#&5+;h46iU3_oEOeKaksB#Bo1>;ab7#X{acvB_Q+UE zLZOZ+rIcXG`HWeQJyV+^JLWeMoG2kb*`Wa>xq>wbD)f>1`IT1wwIcq;c2Tm(?e%Sw zH>oer-SRHx5E9i=AMy1WtCb9ug<)0ESCJRgWJr%qSH;Zfm3q?|9UzZ2oZ7Qz6Ud0b z4tp^2kP)XGx%bovbRCTj^dR7!WVD2H*zfD92b3g{vN%r(pQ>7F={BHfkQDBu(D*yG zxoeQqUCv0mTStw??n#+&ORjKNK2}?b`>cpdo(_sBNQ>nsSSiCC)`8mjhH_xiOuYsB z972gS8wj-AqfmZ7aIw{)8n?Z`wG<1&2iUZA&kW_&1=Qko&5QC({$or0vyv#P%lLd5 zK@;PjnI(5hpnfGq8dMJGUv4F~H_2cu2Cwz#+Qp#4$R3}|7k@Q<_!S^`VEK4cAKu?i z@j-FrC(L@)FQKJD=Y|VEIgtlf0BSGrcGOR{yuYJ4jODMkr}dY@#zpCVgxkdoG3RIh()v?XN2k>bk()7vXQz=9w+JT|$<5LguhxgoSV^URDB zKXNE6>yOwO0}Kq?_!PpL-=;FqU(22|GNx8PvA^HyMi#U#!&RvS_m{{7DxR5?3t>%9 zff#O|s?;Pj?OzKIBI4M=o>nWjyHsNQn^tTBddD3sE1n98R+Sbi{K zn+Sx_bcQr78M1Ft@V^-Bf8cKm5s1RWKFjhC->mVPjBatgwM|0k`D+<$F4yzS$u0F# zn?qf1>GpJJiPaN5OoAei`|9#xpb4jZD)+<55OTi$qQczq<>IGT-q8RSq92b=H1IM0 zI@X>`I`(VDCd993gM}3PDO&0fi+^mfOR3phZuRgi&{~R9w5fbya-!X(QETisK|KaX zw+^)IuTI@#G(e8>oHy1`Mc-~$0t}PIk=96_4WW0B zp|M~C!^I_zfBv)pgOnTgQg93ZnCllAFezSgD5q&fw$A=Ht4kizzmf|j+uKtGJFBJ4 zbC`gRdYbO>J9~U(F&}3J&s&%Qn=;h~#VLk9NX;Ey4We9O!_xj#Ch}6ZJ>)cm)em^f zf4%O+1L7_aXy3R$ig(9TU%)U~9|`fIc2DJ$4n-^3hA}jA+yIp;;l00qng<}(r7N1 zhZW5Gzd2^;Ih!HPBMb5uDP~3_0BqgAGhhZZlZ0d*Y<*uN@B<2(cAfDQ6jSyzjsfvnzvoa|-m}Jel>dgTX06KneTih& zEaRJj98I%zKPZ3W`r()^NQfZn_MG?gZse1A2>cJ}UQmaf?HXj=I0(V#HX)wZJT0s8 zMv%|BWpGqXBuB{%+EalhPga;z{H5wu(_Co_OX3Q9ER8z3nU_-2lfnY{=y6lyK^hiK z7QvEme9?XjKhE?T(DB~b7IS^dtb`9W2)<0PJUl^4dD+RyD@-)`eX$Dayi9%v=3$oc&%zIjoT0_2;1 zb9AR;C*axc{)@wpXXYQr{Qf=P4HIPGtF4i;0syQ3yDl&z^rG82yESm!KmT$6`#%xr zpWuJ|53u@=|B)Bv`XB!z>zmn3w)!7U{_p?%djg~X{Ez=J|1EhJX#a-%-}rz3`|}SK zhN%C~-o>Oe;@wO^;Q4)Tl8;#EBN<+?o0n)|I7be>3{p@ zKgy=>|NWoiG#3B-$22Edv%T$w|M`z~Tc)n~_kaEu=wCnox!~XWW-PK~{`Y^T`?meR zmbOzf{`)_NW-FHez5HL#`sTfRJK=vX{r|7$-_9ogYumeETas}tr)7BGE7_Lj`mgYR zhu&ZKzyEFJd;4$yXIH)d^4Brsf8M>ff2h!Z-a&7N{A&yUZQ1*GV~SVkr#%1XKaL{X zrsdy?m&CK}e{KH%+C%@ktw;4A|JVNmP)i302S22_j9~!)Ce{G}P)h>@6aWYa2mmZN z3rhe10000000000000{R004JrZ){~kZ)AB*Z)9a`FGP86VQpz+b1rjsXSDiPuk%2H zB?$hNM9#}JSXuP0x3UKG6uozE^hWev{PoK(yR*7_wik;9dUSCW6cq|{BH|d``)~i( zJ@kJ$%XMp~@$Y|y{}uY{U&=9`igv93{#V}<|3>}w|N8fT+s^tgS6l4O-~Wox|B4b6 zIShaOOH;OWv;R-G&bGYR>Hhm)p}#$?8+LjQGI zYY>4T2z(p=?^XWm-M8cSe^n8tX&U^;yMO)nf2;pewSE8hzmC&b{`D{0zE0or?|;qu zH2?nd<=_7MXy4BN)cxCf^lz2&EXS!R{-e^{UYV!!-~YNTN4l2()BSF0UqG_=BmFo!+noMs^uP7{pT{uGY2NO?fAsgy@%-n}{p~+0y!h^GI&Rgp4uAjaknU@H|DW)` zK=02#p8w0+*`HqiQvCg|`uqAX+Kb>ni$8#B&_4_4FVFvac4wLI)B3lvs@{wLJ`nKV z{|&7F{ojhR+W!6D{>;Vt(@FdG^5+HmpL_iq@-Kfw-VP!9Kg##_FWP(mpXGc1`A3ug zZ0WuHZ%zMCKpkuUfBql;X#c>X!mmc zkNf|4)wgf)66XIW^6>wHx&FT|#otik-6}BsXFb{>t;_%5;urnD{$*avtz6HN+2$8x zC*9lWpA-9M>wl`fH2q@rmVbElzcy=G{r#^+x~Kp3A5DVuSpUDWbSqyt+kiEl3sR+e zV%~@0`ib(zdR#9I;;PHT-D&U_W^5bB2JFx8$?lK{u`1<}ND^>ARfOEF z*>X{YBL7M#FR{=xkVy_GObV|I4P4dI-2%;wZsW?r+mt)ly+GDoZTJd;&1ciRTKbuU z-d5VpR_g`iFi*Jz`tx<0K;US>RhVf~(B8M5DS!`%E8EFjv1N~$wEf1Icp`mqmY0S* zpYK=kS*vGif)Zy2j^quS!uwYy&WyqKXXPQgsFCbibGMs9fWvrTP>i+9{bGAl>!phMY2+qjYLJ zlkBMbqW!F+)^y4A4pQf`@Sqg*?MLPU#-rV#ZN_%8nUYOE4MgP<(K~w4{Q_FqchE_) z%g_XK+Y(yCVKsvcj5RTZo~akma{0i*O+bAs>ox|jjkz}>8?~_;6^+Q3@$_33nXuc~ zSV2bOx>_NI{c@=g(k@i%Ig7*2p{F<+^7iQu*1@##JAvd3>2V7cVcJwO%_%bF9Tpjw zG5P^jc*cm3crp;JUDk0ZKDtIR5?ws%us!qcUwi+4!^o`9No6^d4JDdlFpW%Wnn7i8 zkA2I);sRdC1L4{W{}4A%Hn~faL;Nsqp?#0yM)SO?LUmS+ED`4)W=yU(hexKX}^$l6g{^$|d*i zDK@K()3gp^0@4V+R0y5WrWoUC6gj)YAWVRQUSY2tSX_^K@z%tbJcy|d-Vdt+oJ|fU zr|>0|%uw<IK4#wG&b3%ZU4yG7>^p5=8s-WU;I$iI&hpIaT8=Xiy zRlI|w`RmeQU;)KPf3!UgN9oRyO>My9o69UJt;04qd2Q%Cj@Ep{y13b&yfAo=8F5Wr zY0HPmzHUD!S}4x<7GNK7n~Kn`GUu^kYhKxIfoGEKjM&;IX|VV-w13@}f~vYEVSvMV zI4rd#&7UKVT)e5&LEO4Z?guNWSYA6($!rW@@?*7vY-OA!lq>gF%A_Cuy!9OdtxQrtNDtjEa# z)&Y@Us&etqmX5qjVNAlBj9nl}#6l-nX~BpkJcCStKiU0niuq|4F;f^}P%cKAh1T80o+~3SSEHQqCj)JEze~?Bf_E{M55Ag6yX=iRyU1!|7fZeYm@T-PtYxjKK2rev6+TSfe`O1$ zGZ`hx%(h}ZSy}$3%j>R=NY4`P3WOSEx@6&^kWyZ2t~2Z2M$EI8tw+kH zONT}hGo|EdFqcZH>Cx6k&N6?D1<;rNXyDJD)UEMM`Dj`mqyZ$L09jvO-k3@1Soh}; z2ZB7V53!?+UePu~o%6eGj=e@PY};$x3Hh`wF7Cs<^JP*DKtDp(p?RAEKWV)xNLtzX z02&zMBTI0ZH?c=Bjnb#K%SG3 z5jj7ryy2fNGbl96#^TvXd58f$Y&c>E3-&!rkI0TE`-UMp0I0xO{b#L8JO2P3oDeVX z3;I8_Th*qI3@(VP053usV7%vW-U!HrkHpi>wL8<=waENZ2k9|N`J2w7#*XD3ll!AS zSZWd?vMD}qAhDR68VTIe4dE=3F+=#1UQhL73(7yZqJDLcQhW|1Rlj2Ck_C0;%atGw zaTF)rz0=?qL_DQU^>BN4XpM>$@K-oPlw64>Npu zp+-hlXb~)PNKbgRcRh^3I#ydDhu5*c9;tXe(wSbvp4ZkV0TQjWUW`F`9N|ZLmv}hk zi^yxd%zG$8?@yT6auixkX3Uyqu1yDK6lPl5Ki0S7$XxDoW6Q0giN>}F7QwfOs^PvmT3P;hgLgUINu)z)LOkxK zye0OkvY-g`BudtM2%5{5kgWXu5cFsiI}h=D?}M2_+j)}4!Ie!Pn(#1z0Ldei`MCtsI&T6)4gGFtnv(F@l_LEJS;2^^g~3b z0SP;M7dCixz*vB~mT~I9$^v-hx&k&lePt_;^?8uB=f`?bED@527n3~kXrTu8bG%8L zc&d6R-1yU~Szhtd0G^sJ7smERnx}5Cflf$PtN+1K$*_z>CMof(^ZRrbZZ24*o7>f1 zD$GD&mA9}*%2HSE7Z&_*xO6#K$4V_3LXoa?5Alem;Bf1&nnj4j>uEbHBxhaf2r@h- z)rvZOOZt{U7%s>+2e{lRWzqBG<%s9q#lEX-7vq7a72s&Qd-g>6u?X)J9(nR+NSOjH zb&Oqk{VfW+Z4>8_W;_=htIw)|G!BOpsL?t`|9ZYk)BTsOq3qp{LmhworJq-dxbVLW zNr6_X%r_b9=+%Oyi|oC{^(Ig{+QY&8wc_fBL#YTLtOrYYn_>ha+b+8b2E@>@Tmb9{8LvlG0`2+JBE^X7yCpuJ~4I=e)= z1jBbM3ur&_&EvyW-DnQ>j$0O~n}cWPe!nv*u!WRRaAtO*VUDa(7MxJZMEO!J)X&b1 z&l=E2xEnEA-)fy9_1)OwTvhv#h-z$E3M9N#VNK&{kzL74IXWlA8@h?{wGq21+MxH@ zMa*!M-EQUqkj99n$yohT<3VT>^nqBDU+eYsZ9-0=OS+(ti>Rj9fZvLst+LZ}yXbf>rDuvRuYXaUF}Jhm}b5vR}Z%K}sEocTbN529U)ZJ66U4ZkLh2C`A(%7gpqaxi4)WzW&%UKf(m*Jb!7;vOi zYs_m%$BNIMDJ^inYct{BB-fuI5l+%uDY}l`fh|)VGJ=xpf6s1lh$~0sAPYX|sUu(0iRxXv9SG&gUTup% zUrA`W?^hq;D4I#4_%f?$5SOt7!wB*lq@>|%Ly(<9JTU{n2kOl#KXBHzQ2X@9QnT?D zU=~pArnZUjQ9|kUId+tP-NK0+nr0PLHs5sH)HphsuG}+Ouv^1vghP=KP#uC(V!s9m z`ilH3n&bflB_V>qhQc5RbUzIG9iq^&IC1h?ciIuN4(NW7VCoM55&A&hmSW+poiY5Y>@cW^(9NcD6gy^A+=PU!;@L2%5GaVGJ0@&F9vDicv_ z6J=`f(0c&SN3gR|u7ymHKE?$Q{etWRJ082pcPT9oo;R*($^m}Yk@n~#P^>`4&OIOa zfZf+}MEolk_nWKB;XBIDd!o|UsRYWybwsWSW<85QpCURBWWR|uiy+l*t6fNy3l|HExzJ4kE5pzo-#AkAD z1GU8du<9i;M9>(k5PhysFY*RIcsFWw(DeM^WseJ90D`ph+}%@aHKe)YPp0g-OWpV* z^sJDsn6ZGyujamnTY6zxX4rZfAkoQj3xwhvt}{v3o0T)7dj!E>?`qRPa*F- zHsmmPijYY=So2`D8Y>R=H9biuy1&OuD0vlxYAq5j<>ePc&_gb~QQ|S|Vci)G$KhuM z0B2jfh@pJDrVWyi;$rfxZmU z93%!wj0{@w=TZ;%-V0a@3EBIdgAG>Jc2Vwqz%p~b<6%SsqJo?<70mQuo{X3$3@q#f z@mA|oOMn9JJopxyyhF$msfP6vzQO^=CWjgh0Y#VW&C{nqwXUIO;c>kRxoW=Rf_sAB zHB7;2PjN>es0#@6KpL!TumL*+epJr9<&TVUbQr&Rc=qNu%G1|05M|8BKuQYlILH%T z0iC3Oo;8xGGHO5#M8!-1*;#lghtM8yfGN^j@6EGPr!jgx0LQdIoJz;#3wMcQx-?Gf z+%eiYa&}U$JnBA}8E=dV1&C=Wk1IM#R-|njCu@Yy!6*%LRhQ zi607V1)s`{f*&7(#Zx09n}R?V{@Oa!G~+|u)qcu`+Bo^BZMDaL^j*i5XqKC`CD%8( z%=bRdpM+=D<0n%=qfE^8q&9g0NKVE%X|oBSFJ$4r87|Yt>0v4&-LCo3YRGf?wMWm? z^X}+sLTZd(lAM(g7TRPiG)tK<25Ok!;4aZGh0{**EL>_L=(MhLC}b>V3^aOL_*X{F z8dr0-=Invb5uSlCAW!rch___ZNNOqYMXwk`#SX;(`uppn4A|2>2ggt4#~;~L0OlPL z;Ft!4A`!(`Tdvwj?;UZLucph=fS($SJU)?4bBB)Pa0H?64zjEATvuBv4aW$tY$(r| z>*vkWRq=bZRL>%%IFK0F{8Pl!NhT%;gnm)?Q;7bRuurNSF$ZHn7UgYYQo5^GZ1_eSBAZ325ZN>oB)^ zT1WS>yvO-KWsTaQAPqBv=EGZ5&PD?eEl)gTOYTD5vNcYd1^TWU{FL$x&M?UOHg^zH!L_@>Q$iaG4E06f2o=myqGpDcop zmaxDV6}O!wRs8e-&IoOfqKu$Qzae%Z22{dr9%bhCGZO1XHRWY*J|0T?Z&VhJHqeb8 zxi138!R#DIG(UhUv9?kd0tvwsrZ`OeR~5#OwkGjD4&6P3B}06xGhJv-g3VBI&jl(m z$`t)p)C_;Bb%PJAZ(nJKLfvJ}Yt>U9j=9Q8J`2R(lnhnIhsuzA*QSVe1){@B&`QzJ zxHjQSM2nY64deZ!lc^rgpL)UnNL@2Z*F?qQ!EdT42G~|SJtoCk(T4ebTKJb(F}unX z>e1g}FB$VtQ13AgvEPbojb31tEYfFND3}FO(!!MZ%=y}eTHK5eD$RVTN5`!W-KPvV zau&#R>62=H)7EQRifl1!zZYG2(}Huk&*l)UPkOPXs`XhE$qtem2&_)GzbRdv?fVh{ zw8QnEY~#+1Y2m_fFuv&NRrZ%$S7A8(##0>5=%Io?j1jZO1?!A}y$`E{ub`2a$HM^U zsx#wFMczAAkJ&7Y%!Q9~_UPWguS6NG-^xp9zX71B6guS-b>w*YrY}0DiS6K<%HpjK z$L$Ycq9#mp7jJ5fhE|^@Jm94uf2Wdz35MLt8bymqmp^BLsoejHp0TGqEr=w#f=6US zo{@_W#1!ie96adeCpL2GJOqOHB?htLq^p0ZrpcTihW911*{!Ubnm^9S0NR@tl#al?0;>ECgE%? z5Yl4QFQB{E03O_yo8wMg+?y~qJ(72a(vY-ChNtlw!;LNvR5VW8*QUq&{*HeU&k@A9 zyM*s0SXCD>@lvWgDXG*8@Mf-=KFe}O-uPVnf{swdFNf-BbVuk^$FTLr=X*QwvTsI* zUcZ(42~%WL=oy^@9hwm%dyW=IpE^(Rde!zfOaS>S)6=|_60*Vl9+b_GT3!}tuN{`s zt_V=O9ZUav9P^NrYLvlu=7nW!ayft>X`p7al3$q8|FSF03695p>wCDJzjh&qqB8w1-nWpRQ>U*BK6u+6v`0$@Zo)=l~GtSI3~%B{S(E1=((6p~IRgq*rt4fXsVy0H*;U)yP-ezbnnL|NcBo%6Pt9HU)yj*&-POw~bhA}T29=DJWfeE%pZC}={n0nzNI#hUWlm!YB>vO+qFVrR zJoPmpL$fwI0v@k#4V0ObF$&C{`~0~J1x$r9<0Q6aO`D_0Pf`{O0@)Cj=ez@$D%dVD=3qqBX#_}p;LP)oUU}7PXzf?hUoyc0kV9Zjk zs~`X;B{=XuUz)(GFsFnVIpOdlujh%SeV|X6+#E&v$4i6e^k zjN2=|rFY#%X^umm)g@xk3L;JH*KHWXH-ke~iAYLB792%*DM6YDC^W>fmqZXm9tc;6 z`|EmGhM+xuqYd?{rdIijZY7j8D!uOT@l5UUo3&V0TO_0zhj=U!v;2i3nA|4bPE9_4 zW#&N;GG#KC$yeZ23D=;w(BRqVhhv=__jlwX8(Y9X|6KE2DY~%D=I{IlaO+^c0kfPh zqqdU(o-GSw)NY@?6dlo)s2wD#asGp3twU%#?m_p&l^s3FG;*i)EY+&{y1m@>k9FYG}lbULplOI+z8NfIVB6 zd_ENajtWKJ zfU=>n$QcG$J6eEe$7=7UNxAxUcf=-aZ@LgmFZ^(m9p*M!g>KN+`tcekG-3&YdBq%2 zYH~eFYsx=X#@Q=ElM6i%&*uR0L3HwJm33IW)6Bb^>%M}^zz|4(XLIjeX?;YQOm)B< z+iXZ`^#PwM?jfB>0{wH>5w%I9mV4SP%E?Z?>!ZrA+yZjQIONu!InAM&l}xj8?PwM8 zC57`ZCuH&KCk>H|KjZ7orQ@)xHb2vtBC-bt4KpM4LiuuItm8*83hm>69~s)2&Oc&` z`s4`kpj%3U+ZJzQ0GjUZ$m~=QOV`OIj`%7ue%P~&cb(X&p_51OH95&iLhl)D}7>{@=eLO2T3^?T}z(M&}@&_ewAFB0~gpTkrcYQV((^j``> zY=^jOoL1(0FV`Q9wJf4$aJM`%az&OE1;*=t_$G{hOFa2zML}PoP&C{Ka}wX89v;eT zKHP@8lDiDGMVoyhPLY#^c}l_8s3(Y*>bxC@>z^_#0AGTujl!oz(XT4~h-~R@b;eDW zU^T4ERIxHfswJq(ai`vk`3~bSJg!wTJ3E~{E_Y&B+90nKwH;ATS;c&#zr7epA@XCl z4hK!L<-+X!LP7a#I=4}C5&JT1&S5)@C4ZvK&AbVzbf(=fmn>k{vo<`V;Q?@q5;c?5CF%4$ARPLHHt;Hk|_FD4WP?5Hz z&T)u)c3dy|;Xd3E=Au(O(v=&#%$Pv}v>XX!Hhw;HCBG)fO&kb7D-^5d?gO&bbAPCx z2Nj2ZmK=~V-fl8KH{TE==wf8qO-h8m0}bsfhOHa9fmq5MOO_``?z=p`zo~Yx#VS%k zP$b)?kBT#xe)k%u*j!60YZjG3Xcg`wVBYp6owJ-GEx?P*QGmo zPA2;iQKa4!Zgg;RctluPaE$Ezs<2*J%0i{~@iG0*ow{k_WvglQz07*@rNL@+WT~&@ zw^`^1sqZnmdXh#3ZQSsch(iKe`3tQvmLziL&eTuxj#15ktmr33m+3RR$!`r>r*3op zeRJ}aPujM=(pnvkk)SxoNFAl4%GinS88^|zm3}i{s}~XxsOhGOnOps1;l6nZQmDxp z;tQTSG*2*Y%dfHow$e0n@f~^y+xso>%1tWcMViA(+;LExPe=1h!M^ygeiq!%bPoVk zWaX7%;{vC|o$dEky-X=ech3N=O&p_%eHNYpBoFG*rs`v*kj3RUWN!K9s$x!M*095q zX?Cu}^Y_Hs!_?u!xYTK83#=22uSWWZfzpmlvw_*~Ubjl7)G z1@A3sxshs?Ajl}^_B$EJA~($8)-A%XWkYuf~*qT(Vbw7Mje3!{Y|Jp zg{A#do$>cMj>9FB+vw5XNq%xyKk;Qr;Z_9Uhzy)Jyw4Ue0ooo)X5f989Y zB3%_N+Jfh{UecvC`Y;cWgzyp0zB#m|C$oguB>fh9b-ll4poo_2_Gyw04(2_Az(@Hlcg&obGMW;G(Jc@ zlD&R_)%mE6V|I}=-^VCiP<)fm#SO3JI zdH?>d?1Csj`aJDtfVzuV|>N#HUF5oq&$L&cIga3Zn+lBcieCxsmPpM+FcojwgCsCd=R zSrnl|`$2GzxBvWuNOZ?M=zVqih-@?oXPHY3t0hp)ColqHRk+#AqB$l8On2IcRN7}O z`|C~;h$b@I<%+u>r_5(oAN*BN*S_QJp`}`On1Bfn&J;f7#^}=2$ zHU)(nQ!qK1^Zo0y=SIGDGA%Yq{WdpSb8@Zwho{~MDmAkLjiDW2>k7+(@uh@SB*Lll za*j~E;CJW}CLjzFaMEhQ3|tk+L62|F@9Z1qH>STpiKgp;HUUs2HJ9Do;iJWff=`P6~ELwof4#7bCQTT9Z-JlH0(vV`g_nY}b@m$|? ze@Qi~i7^n`_&Xc7$QETAe(4a56hx0Z0nBj;r>e+(xJO!$LNXEa?d|k-X4ILIpXvb1 zt%Bpf5Ou_zx&HB|a&ZuwY-9%c`hWj}Tn~CEzuLcbovjc@Q=n8b-)xCuA~YD|EmXR; zq8hu8A;v+u#SdCU_asD@P5CLWpwUu$rptk!wQIc2NU3^^Af_FgXs;~|HGN~R2H`uB zpH+|>!AN|;#dyy3P|x^1G+*poqpa-1zJ}LeQ?Q9pUeBG-(`P|w=M`hPg#gK%Nex6h z@mg{)2YjQKVLw)pVS%z1>LVvWuupNxpkC=Y_gJe0U9o)BjxL2B0El9(^}cH=&Eu=t z-Ix9wZ|}?+6D+?z^cPJo+GH5|0FOIlz$%C5kz*{L_IKv~!ylFfvC3(vk0Bk;d0S>> zVAJaf7ha-Kh8f%{wM8AGWyoJ-^)jG7wzS?Mq_u7!6%^f=5v1#jw#^j~_zI)uT2BeT z@%dK2t~^gCM5QH&?q{ZOW^<MnW{U~-W~TI(N86EOmi&By z_ylsr=VfP>-as%n70aX;fiPz+bg3pY@2=FS3Wk68O9n-nt-)xtxqZ7Q^LkP%7+-M; z>8+;RRj{sg2&cO)m4$BMbb-AR3^>{K3}@nqvbksCKH04N5%Z|la(mA2w3#g6>hJZbDeZ>~ zIwjl9Y(i65LM55Z838NQ#bWGPjZ`u~RwOqlzirlf4`KS6e)=qhV`MBHt3J171yF)o zi)tm2we)H6Wi3o;`m%Rre>&_Yjl6UsV+(Jym&xF%iKwX?ECl*lD*6Eyw!1vphBudhn$ZbO8 z;^!6vdD=fbQZMZAT(W~U`(@o5iLC;`Tlje6L*T!9QfC*8$-#SUXmn_ExtRIg7}y9x zhq`ayaO5h>{-AIGjcZCEUOTBb2b0DC@u^!xrcImmb3p3`L1fZE0dacq-AU!TubFAA zjLlTk%RBWxiqCS7JIq!dh75Z4WI$kAB8%!6e~_`Fq7RuG1tlj(l7)-{QD-a(cSlQ( z*E~spkML&^nMKm@{X(79=dGHc4U0$s+D~A(Jwd3ln|L4GioT2Oe_eAtF+>h>e2Pd0?J{ zxrE+DNd|mv)wX9`E?NGb<7#|uh3dfqZJ%2c9;z6-C^3Bw*bf*meh-a>!HT}euf zEkD|qGI$pCJDlYH{5fkOwanAtF@^%yVIWqc*<-z+8fM^-ymdIjCGT>%up9Rm@SblbZTRH zazjt$UY9L3nD34IouSvrL?607+;Xi}v$s#-gt%mWEdU8X_P;AmFVl~5P=}P)#ge}I zWD)KM_a>`wH$6u-vw`goUd1ecgQfTTs+jSWyWE7#xGFkkgx4Y#_)!}$LA&lsdT;ew zU$6RWSsj4jFaU>Q2xYa%z;m;Y(ck9OW4R04DiK|nh8^2~XX+_-xUP1~6Ql4DUWZ`Y z(&${d`KWq|0fuw7OXv+}e&?a@HrEzIKz^ZBj0MF>M28d&|K9bo(`*tF)RR zK#BLEl4As|xLcG{HUk1>u-6P`)3z=J@SWKu&*0nY8axLj0le!te{g={wbEG2Tvg2&IykC1jM*AA-*454a$ers@FZHOu4g_X2ruF7v6$u03k zbYk&U;FXqeNOtxmypThU3htiQo3c?grXXH4dy0G7Jn~rzRyDF5(*K*Lv)Fo;S%c^W zF~Dtz6WoH$aDuyC{m=WIb;d~uEl*YLq`O%)C7JvEgITz&wEf4|Se06HYq}7MLJAYR zLkq>o1C=3%$M5Vk9&WGsa?lHrD!v3tbQVP%bW=m|nL!6St{Qe9SVvG)6Rw4{l>&@x zL|*&DGZ>Es+iB#o2WOOA7@<7#wG!=wt4qSMlmtG!oqfnLHxe98zO?186%VW*=Cv<{ z<$SXyk1CK1AkHqA*?-9%d`KrlDzemKVbo6AEhXn@c%!{0x&S=A{3r z$I|3+9n4v6)>NB_e8O^j$}5eqKD{RgsH8;38ucL@We*f=#o;**7vv%cv@p;pEo{?T zS}50ekAgMCaAx69++zW)%cKQF;QctO{*W_0M;}0L26WZ$dlgxga0G4)T(ZJe_gZnA z>lipT;0sNEQwEfG7Ibv^!YoBqpfIU6NFFRsbmGfj(&gN;aZQ?2v>!b|l@@F2TwYhO z^W0TUIx@4|4L)Hj6?(Fp?ukaK2Ye(v%l(c{)Q1datGLw67ul&~g`@lthOcx^S!l=-q{D-PsA-UhfF8ED zjd!bCp><%%@g^q|mBR`*F@TblKzm^U)D$V(BcbGZu)w}Km%O~gKEQ2l z)0MXfG7rY|!~77yO6Et+wMt;Ae_ ztycY7SS&==6PUv>AWUn$QYfdka&j4=O&8L_Bekhj?rzqM) zv324rI4sRUdF5=TD<&&`1=X4SAs3Sk@7D$;8si=B6qQJkte@<9o()lxXKa$1TiSDRL3 z=dtt#Qr3ueqy4(D$+>m0aC9uU`VMDKFgFh$`h9W83fK<-0UKDVABeCJ_o!ffW@cXI ze^XbF!_lRuf%>~F&6Md&aoU~}% z0?cR;BEmZTY;V$hmDVtNydX$LfpDt>RTodoQH@OtjrHIrY>z&9YMvK1$XCKX5e8(W?V^h&Cg=!cpg>kF6_1JDM!v>bo|+F=br zNG0>VTfED>qfc#lg~Jt69vH!IG!C#bh$3#@+^^O?S~*QGxJb^iT|Ee36%--4)^T77 zt$TT#W&sq;B1SuOotjT^q4gwqT?Tqi9HT=W)gzUvB$OH^Tz79>LH4MHb0>v+tEB_Q zzOZ&7-&Q)@#9y(~e?0~CKDh?@K*{Ftz<6}>#(+NzutkqTIB!1#|N2=UzWLx>BaM0k zluP9`golY?VMu-%WWH{Ts1IW{f124mxcqmt!b&#S%T@9I-X4#jzp2NKzxknxQC179 zZGO2e)tjb}S#Lb`JYcbv)yeG$s_A)q=}Jk&_vi18U|pu=W6_Hp{lT>T1`08a!^PLC zL?#lsVSjMh@0<(JGko9M;mRKe8?T36sL_T|0kUST=fS`-uQYQJmU@Mc3?j(YKqfH5 zFFGi*!I$cuQw3cTJbj2tiUVr2+0&$*FTUc)Bxro28mb^st^Dz!Rj22aK@B({S^?Cr z1O03kXzov<#090DPH9QaLZxTdlA@f_hYzA39OTD2?;>hA9^wS*6*GXK^ZmcgvcQ?1 z2?CJv0MWE^%ti$NZ6wY~urHOGFCe`>gRDFfYKy=g-5U+%yx(W?GdzXVJr}58 zSRspw*(2L0+;Ce};uFh1?$f}KBEPKjG8PYDq6N&qB`bo@k1-43X+Fw9rWoKLXhQ9Wf zX?3Hx01j>Q#5w2gE?_!_`eM;0$@H*?&b4x(ZJqUyz#0A8rZ)a~2J#sb2UVqh0N@qS z5r_$d-$9=`7!D*n8Wc*mY?wD4Szt1wWut>&p;B$GGNu~hxXJV2V{qxS93JpdGB7-X z@u;ipZ_PMxNB~y+HUJBX!UuX_al2AAMUsXe#wT%D>_8muhpa?D6d;7M#J}0_gZ%lo z*%M^iY*I~*+ybT$ewet=;=C~(T)tCa^VC3b(!)cYC_E=|qO>L-hD|<$Y28ib?!*%< zYoBa`9VjbPim5T$h{8v_az_(-aaa->a=Ia`DQ*Di zJ1VbtoGj%6i)0D&J^V3x(L+`|IV zLHblkk4Ad}4Uu;A_4vMK>ds-3eQ9$H9)JJ+_AyXwS%M$o7{H^>YWyNP=w5{-Tx@wk z2hn=fWC3KVj{IP!yt(do1ashHccSpB%L`H4X^`QaNyzip;bg1q>U^-347^3|eGdd{ z>xC{Q7L8139|@RHTPp5@kl^pp?70-)N0%x;;y%rCb+u)>B@SJXF-YA+I2|8?Pq&qb z#o@Dt1@w}mDw#g_D%d0ypz-!k0D>u)|48ulUi0JP9mLfjFkWTzcG-h{r(hpPy)@RM zK*r#LNxA_P61ju!dlE%Xe?Lu4Ce`4mk&I91NC z^6U#glKRqgQ@CD+@%#8-BYkgI=jE`zKf?AWr!VY$Ps~ve(0SuKsbT_hpb-EJ<9S$0 zT~y5yi*u`?RXTfSP$@niHc8>p<_9aU%f`WIAZHv^@;5#T|N0?Bo+b2{d)bLSX9%@6 z9Dv9JOv@+$z1C00SRYX&3kvsli~=wPR*!=God7^dDV5J5NnC9l5dIei-yz@16Di*A zBskq$vfAIu)z8w2$jBdA(zq;V6v$xK@hAe>4C8mNss88RlU4J5HISY!(d~<%_gN_? z#K%8ul^4dMrSO{GOD)hHO&r${Zg6HW8)66r&2M97Ft(MOJubN>P#-;D8PJv^``1Q+ z;Fn;}VQ+LE-)xp(`6dV-)2ML@+1>7-L*@APwn9IN@>s$W%|b*W>&h&Y-#I}RMlp^uAw_H8Hjj+*mbKz-BW@p5Qheaq=w`!`-NlZk=#&8Hl z?qg+OSp6&I_Iheb<$Xu&9$fs(z%JDEXu65ZWB*K7ulCufQjslV6y$KFG8P zjdj8Y6RMD2TG|tXFI|Ih;R&})U@CyE409YO7-GgNwIkfwn=xhPt4#b-0)z&bA9Q@6 zWq>f8FiCaP^f$JK@MlY(zdiWr@w}i;8TqaS{Yj}SwWYJaIN9-xDw7gsrPcOe<4rA_ zTh9*|43jBiqgDVcYXj*B-;Hz8xBhI)c_kBzhJ3zko{q%=#tmsYN78BOQK&gnFIrX* zJ;dY;%0xKyfiZ5+_wCAH=wOOM>lXk;nmH=yZNLu=yELG<`Vs)`H}}0}PH)nfa*6ma zJDW5OgWpKnA6pg*JJUXgVxTCwAfFC=Fzfu=Zv>8)zwP_^n&6`Q?elkrQF)ZiF51He zm7f2S@T(pDZl%fLxx1-WD{1m7Ms8DxpA)5!DdR6#pXNo=+Pe+es=b$#4O zZ~FqLq`?_sm%m{Cn$fG4b8bH8#2fiZ+x_MHgilTS_yAWxsK47Vq^GC?#{uzrbZBXB zck%G}q@MsD^U)|^&@QMW)pnZx zHC4qhABI&NLHs&>tN$95nRUOWQ2CRu5U>f%#x^5usuBO`&~~eG8>YWz+`&V575lP} zstjPDmmKPsZ=EP1QyHHFifV-nKd4;8L#V0Sm-aZp;(`ooZ4j2PT#d(H4X~N<*)@GUHczXZ zLUvVs2MX$bK7~`Wp`RlepPiUU%?@0S=A9DlTBUh?`>76M!`TOvqa=x|p^5`0wEY{U z&0MVLGUDn`B{($k;u|t7TtdF__oKjkZ<(mpV%c2A-b*5=j9hkidiEG&00hNdg&hq5 zbfvv{mMUzHtG@2gRBiC4Q-aP+II$NTePWzWXU%iH=v%Va0ZW}2n*QD=FsQD?gm_zq*7DaXsn05o_!8gU9;6&Bzmjod{9?6{kQXl3n-GE;Ib<_Mm}@<(v`Yn!h4yC z=U3Ovd}jrN%3L+;K5=TmXS+A9vu~q8g(!05J~1?Yhdbdtahi7 z5fs(VEKQG1TZH!*o_(ZKw7o)_RC2kdZae30L#{*ke$OQRd4K=z<+6SmXv0M=+Pfg? zmJE!phKdfawbIN50Q^Y-`q&9Z+U}IeG~LArKa&hOZU`k?rdEnpLd<3-e4^O+n?5A zYf#P&auaXG?^=_UF=xgPjakhjN4YO?OgD@h0dcK&xScWBei`(+daaoJRI6^KU%koC zgMrUn`W5}+I?7rrg=eLX9Dm~Ek-~9Hi7zDWdn^Q6X!03-N$@c=^%Wi(lU+aZ3D50! zpPOBZj=8d#f{%$>v2uU0S%7cOK%_N!(MA8G5l}{TttcOTL1FkyKGWiecUW+>bCXhP ze4TO=*CAcc23OKOECuRI!69x~iiE@8Fh8IjWp^_>v|Z)^?E@@Lr45JWwC6A@AEH6B zG-(T5d|)~c=3yNtt4+;>Ak4>EJ0si%>yi{;Q`TQhcZGNLS=#p&vv_%+*&IRcT8GWs z)dy(7=92vjS$7ye$DpwFsD936u@;>}%$l!PGFa);=bYm$!!-7gokS>7;~3tn!Q2*t@mzCCu30(LaWE zK)toHXTo+=`sbD=yZ5>gNUv7PR2)1upb=bk^)l(?zx=$$z3l+u02qi-U%-T?my`?; zXrkhT+hl%lpg6ZK5kUA-4k%Wh-oTXz5S;**j-fP&Zh6gxf?-%^%mp(@?W3tG<#+wP z6kj*j)NJ_xEj_tg>GK;`_#7Pjg4w?jJPjK4qwH@2Lhh}JT z3MOr_DOh?=-75|7kA`q}xBL6{(wC#H0R17)1v{-OQ{@f?pr&u=&4czSqE0!un0ug} zBsVbuKEU#pK;4;C_&e`mGdCtmk`BsiubGlQl!cELaOjBCLiDbr`q)mG?xSssIte1dzgL9aKpDH}F)E+-C_iATr8U(#r4#;|7MjKrF)Sv@U zEJBksU3|~RaU>qa-?l7~fT(?oA1SKzY~=s$OzClFR(Uz@&5$|1%?{&5=zm(G3~mS6 zLlF+v-$Fbr^K))~pXEJ`wLM5M{aa$_3>-OrXT}ElikDDix!Km1oh~UXNbnuHcPjd< z%6qaeSmkV_I6ieV)}8&h#a1ax671R}peoU&W@J-;w%-9Fk-|RTJWPc8%1c}W!geO< zf&@X~&peaKqn)ViWbj~OLws+4e;t5*KHezDfX zbiGy#2rAZ$NJHKU%3*RmHY2wJ*^nA18XHXHN=u~z&Z>mNk>skE)ioH)aPKU9H35PT z3*hOSb--}Bd#^5zUH@3HPOUd#YH-uu!L6~y1%2J$iWNLnf4{4yB8@fITI{Irr-(hM zi5Ve2)Kf)njq6=&E_<h189x_UKFG7u?Ko!jj`2C7wtFf*m z<8F_cpgmj};f(XJXSFvb6gQD+{z|bazOJj7SqTNxt0NX8)L07#1epT^ISMPo@y+(i z)RqDck&F8DJyZ&vC;4nb?sNbQ27``E0OSFseqRz~dH4&arD#8Ub!0dL(1}#lG4vbC z+~aBCUgKJ|#q62N&7^KHd9ye20J;eRoZwzb{${#Rh&8j|H--%j0tqZw9TYb}dY*Gq zE(Jd#Se&e|6=?GX<|UGjFm(|#p7Bqj*7EKa;wGuM6JA?k6r{Qychj!keB50e^F6=^ zYxh=bNKy$Wd&V#52;${Z37M$6)ai5m8V=oNacWOP!V=+AH##Jm8*$Nh1dbaQXa1GArZEqNGs?6Z0rg1;3x(Rb z5_odj!CHqh&&je&LP9p@ zB?6gSk0~nRL)b!XdYF@~6x_dcxTXB@WsM*RjoR~979nj&VS>Ed2&DlZc zswZ&NCc8e_>KKTu%4!n$jRi!MnJ2l03b&Wf{J&a4nyAWE{Ak zNMc;wX~+G2z2U-e_>um6m_3nNIhf_Q3Cgkytq)o)Raxs!Pt&n0(&Le%vWm(@)n^N5 z8h3vwVZG^1=gJbW*@uJA z!RwgR=EQB81yqpYJwW&ryq- zPIJ$YLUJ%uf!FAp3f2?fY-D{cvFM$jZSzxS8m5u&uo2!q>EsV}$U~eMy!{m!%f--UVI|?7Ix^F60Si`*5$a`F;pP71=(` zGfopzZwzh+E)nFyuDeMTg`X#`>Qy3AynSi}zP)?Tlv%6@L zG0f*F8$Bj8#pSJBE}|jjlOBc+a&(d{^&#pLojE({Y7Bz#k;cVh*<%|ZEI{JLEF5Iy z&S|b2tFiaWf=k4kn)H_0JbYA@HGAtV8>6_Ro@=*_7%5u7RGm87fnbnS2YC-EU0jRHRxe?C^+o7R7213 zbetLRpycevNj$dYmHi-pSJV1Um&bLK$aF}|4ythq5T}KjrR+x z*)=TsCQ@(m?7;H;B39~S_&(fRn9ZA@-Od?gC6CmpehB@sStkBuMw5jS&2+P-f0sb% zAY_XDYP_j1sja5h?rr4Ah(EqqKsTiM9SNK6S|b5J$n6-dVRoD?ABcENi=YSAAH-&4 zxG)I>36T6o2o(FxdX?N&&B`1MS#W!C<#Cqkk^Zfm4zM{6fhYRRV9Y%k}}C?1#oJ zw9$N~%i4#vw5Q)hn$|BnD4%WIwR6y5@xY8cxFd^u%l^c{Fx5-hiX z1qfB*6Idc$`P?>D8QoSoFZdZdO*6qi7AoxHO68f#!*~&?i+S1C)dYI(UUT_)`$yT# zc3`ic*nN!4^*&l0lYx^m3aOUBx?7)OMGn{gigerSI{WgMRRp*!G` zk*2HgVT?}bhSA>7-MuO3F^4)}zpt!7r|3?9**v=`9BQELjd2XTWNEj5mEwAMpK0S7A7zhmfcK=eI~1=AVf3_^I8&)NGh`BjE$o^K#9^%pmBSG&+cO{HM#m` zJXfor&HC7>V_vgCKQ`Q0iTjm1T^5%40zs71#~*Jd!sEMm7ZG*(HC~bt@HdF~qh*b# zrR1iyd>f4D0jZXUhHY4R?uWJ8hRylaW%u=xG((7V>V)Hs=achhiud6>6`I*G4a{VHSqRO_b`*am91RVs zd(R2f9*9E*l9b=&>k7yR171+IMJh11Hkux#Ynoll;UTgozbd}#_Czbq#X zjHd#oz2M>(4B-cEJMfr={%pI6<=8il%!;*Lcdu*#x92rDA>^|g-G)M(c;^Y_4VEJ? zGzQdPW8~1q=D*mngNL5R(fVmN`o+P(9W?^%*OdD%RM1$1VsD_TagM&g%hV-0HwAF1 zB^iPXclqhF$?V(ouEDV#&aISXDeW}S*n%!*m-x)OyHBfqev3!)nz(^jWu2H!TCY<9 z#WTx*jVkg`>_{9Ig3??F4mB||k6<)1@AGLS_oo+GF?nYRSd(Ub-6Ec#y_)dX?1&{PaIxv6B*OX6bFBpK_k`=iusG7Oj zBoxVRZlUy`JO|H@+PQ!zztg1xg-x-br8~AA zrIZjP-!z*N(9+yCQ%+Vb0HsEJ_n=JMksiU3GLhJoSJ zlgM7~p*i`t9?VQ*G}=-~+o^%&~jWT?G$fqCH>{DeRG2;6bPX--m73_wqvQW&f7Jv3g z$PE(fwF$h?ko!&yvLgI@o4nO4lo(ho;N#fwF*RmIuE0|8WK$F>Vgr_@V4UB9YCp_T z+G~WMsNm4v`Lm-3Z^o#M{z^6N=XCfDO^@<30GNoFOc#W#GK;3|jD4t*T+{1>A?#4! zbewvuh``;sodihL!*j1EPfu~+qCZ$^yMdpdH#!%#NLyQ#VyjE8$VM1LpwoZ<+53hy zgO36H%9XWb7!k^%9L(1gZCqW(J>I?W?KiZZJ?nuBB+i+cXD-OU<=n3fKpb{#z0;Y( zDh*poa0t)_3~8dH+|5~^FM43JGx|8cXw@8&Bln{LuI8(AH5_t-0QwAT~LfPpII9)OY1nA}%QAb$z`#MxCF|#e&AgJRYFk)E7y28iWwDV;2OKUQZLfRzqu`&WD0+j zVpHVwTbeg<%=rL=LTRCusdcOEHbi)yhba7#!G9S1u%~KU#;t?4FaSlqg5mDA@|G%N zw7h~6D6a9bd@P@#I5QjF{Jutja7P7XqOYk{i@;C!OOlJ>;E)RBZPe1-N5u*gkNjD^OLj~K z^-3jfzC`nVJ+;6yLOwss)yNR%pDoD{3T4qqRt!`sTMrgOOOnFJXP4y;lxz$nInpea z#@)@$6)`9$GAnSx7l0-v4`pCrw_1Yh7_VnqzU~d)ohtaZQ<2b0vSdp1P5fLsxZ-|nk5J20Yg~$;imTH zUdQSjxh|PMkt>@AyFYeaCQ6V<*iO{tPFP=ivpJVr*n79=I2U%ty_rw0ODVK%d>P=i zn0(zJK4F2PBRX6<{&;63_s2f z*pK&W1csFr)sIdI_R4zy{7KoAmNlYPVR-ob?p{LvpxvIy2D(BUwPN4Ih_wnrx%34U zqmA*iG2}2CEsdhXS9#Gjd&Kh;T}+`HHyb!g26QbPps7OFVj?-VA61`fAlClC-#yDrxNVy4CO z7X!HvVp|+Gk}`fiISAw4db?DS=&N zD_%MeKSoykJJcY^+oo`z3SkyW+a0N)l%^3ewr@27@$VGVC>?S*teoM2FryI7jBWq^ zt3R|G0KuF0%rMp@SeX|hZ7J*M4iOYR5*?!e0SRRwY5pR4n8ZjoP-D#9(Ps$dOSB!^ z`eOUZ6-5}aB}h82-@zi-6h|;x&iPA&4Wtkx?tM^p%BOO0T91Ct-0o$6q6KCG`5-m1 zA{R+S^6?w*#zX`dMmufMj)&<#1sYppvy zM<5kU^tcVs7g!PsMi4z}?hj`bkD0-}TM>KATjhFrPXUs-mk4htxJiIEX)}5a9!9@5 zh_zY-f&_N!O!YQvSgp1Z%af2^j$HO=LTU02!)wE7d^eQ5pPSq-aAbk<8goc9AJ|{` zaX8?N5iklFnIFP^GV0cOdGZ=1?%NCbtFhF<}CotWkt4yPI z)19!_!$|{+=9q~xouw(11I&O93y>!1Ns3Vz^K;Iicxl>eD0+~mKZ)*pb%r>J3pP2 zWuh|Vqw$%dL)-{dKeH3lJ&;rHJd0(}QOtD94{@duWO-gxWB_*O>i>~=dF}c2{jQ-4p= zgl79!X>|31kCPB_A<97J>l174eq|NluXPLBZ}iP$Zn25)m;^yJsf5@6Jw8@qa2%rW zo%2JbQYmf7?6F+>zMajMN87p2Lb1qgw2^4-y%=6Kc5>3FETV^UFk0CSX`FMvCp+%y zzFb+^(FR{s!<9nYj?Lugg8Gea(W$T&PYwykNc$kRqj@OqR-pd~QC z@z&j-U2~;s7KP>$zeYzNLCrnr0zumfQj3X%9am6(O6fYj;!6~t)#tf}a3c6fhDd#p z%;$)udjg=;OJIzM!0#yGUsqn($*p$bkC6fVgdg|N*RQt$pMe~ieqr~0_i(uU2Enby zw=9X&Edb^cK3}-`G&xyrXncrPNk&@wGG7Ka)`pZCNgbuO())w>9>UMrN!K6t?=S_4 z*K7teH~Q5VL5w;|71DTmX=N%db?~-8((-q_LxeIJ5XvR9(Z)0zCZg9RX&Lzc?boP} zu}t?n>)PbT0q3i;FvcdR1kQP$soGCwz~jD~i71|hqLSU>WvRmUN9O+4Uw~H2p%U;L zvkg{!>}tz+*UKnj7r!LO6?gOiQj{E@1mf@KrAyWaE7N)>e_0vZ8qruEBDamO_zqPA zv!6&P#Acq)x4kUJl%?Mu)?vvz$oJs`$ZwnhVM(V$O2vP~ishu7xhotn8olj|l{(FM zS<3HO=n@mTz&RGh*0er)v%?{_{Iq>cV5l&iHnS5k02ZxD!tg4*0c9mFpXPX=;>>b^ zOtcsXz7keQ0+te19?7K8W;%A&7JW;Kc=WweR-&ooE80gQLk0 z2{_MjK_m?yGg2?Vxzqrey8IwJ$V!bEBHlihgW3PidiXtHywg_xMwGf%p{ea@fAzh7 z4P^T=NkBr%79Mng%a#`U+Y6+pcPD``owOA176kzqoAp9Hoad01J1V>b*RXHK;-*!I zD5mf^E!Hw0$`I`h1uG!m|>)bdRhUyE+qDOG&FZ8aMQY{`hbe zlfQFcd{>wN72F2Wl&a%bAzlJZa6lXr?yu&61s65UbZSzc#k27|hI9_oS4sW>c#;!4 zh{zYpKoS$AAOY)mU8a_{V7+3GMe{q4YSza4zz)J&uV%dw&3gKmMRTb+6b!EB^UcFT zLM6zyT=^A+ry^2G*k*mJ^IlXJQted_lHXeQI0{^;G)O$2IY?lsT#SnZ9ir`X^LNYV zBRw@+j|SXG%O?hPuP+a^I`Z0)5M4)b3LmsU_L<}_u96{D@r4B)*2nxi=Lh*gTQ7oYR0gNXKM?Xx`+~R9mDD9*_|Z-s*M5C*XddG{w2$xycsh}iAxCVAUdwF`$fc<`- zUDuYvx;5?q6N~UR3V7M<-DF z(m%iAhW0LD2u#tj`5taqY|d+0@vt_z?T5znuS5^GAk$x+j*6)iPbB(>gTh6OXE-O7 z$rf*u+QG|1TDT)9J%it!s?v}INphVuI_@p1hzvqdoH%6d2enS$X$deeSH7PW`cO4N zAj{?l+n(Zfp)WvMorX;T4=FpEM#AgYz@QuAotZ-WIqqSQr-3`Yb{EL65E`b5w=$fj zHbpkp^!*l)S?K3(0q9!C5&3!iEcP%>baMMU5fO+I|4jhmTHJ|uZXzF1!rQF0b9WC_ zQ4XPXU^GwseEcw_6m1~y!1@4(n*~8i!!-88pWuxNl0UoQng0UJOVeDIIlRvM5P7zY zD%7;ju*BR^a$Dfgr6BKFaq@upZVMPuF)s$h;XDqz`FKr?AtdtD6=Hmwk7IdT$INVd z)K$L*c7ha|Ho4YcFWo2YzkS&#JBAOHrHR-vzk>@N8fq)w4le;H-ax!prp@DgTe*GkB&O(2Zo+;V57?>R zbo-y}zf8VdrnWiYKw9C-8U!}*ztP#47-0)l2~Qvait}Zo>qqh#KdPC1WqDvpOFIA} z-b0c|gZy}ucfcR7+ccPp*?-qW;njib7d-ZJoI@sPLX{i5yU%jaM?z_%cw_KhX7MWf zyK;=n-rum7zcCj?L%TvAEAP>Ez1fl#$U^$E@cLEi;b?$T_P+d{@vO_GHKLY2(OZ>= zF;cZm`WJIdfHQ|*8siwF2ZhLzL(K$u7{;E%E=#%&ag0X#@SLD0113sb6%}OWPL6BZ zxr~_l>A&w6&UU_Dkdkkuu~MtrWts84ocsc{ad@#Y^(lcl!m({->(uFnp&AkLt|8je z=IxD@xU9F|^@;PAcP@p%*{XDD8M#DxKon=RcxR2`Pd{qtc;tBPCRoY)W^Cvr+kGyf zWsHrp`Oco-&VIH9rsl{c{}PE9fmr#TlE+@A#g=PRG9qw!=koDxfU&6`B!s2!?wz)> zfjrnTv!DezM#sn)#PqV+6KiP<@{);a^=rQX;f)yxw8OwX(l_38%*%_l(*CyM{wC7j z3hrG^z!puPTek+OHQgB7gS}eLBb0Q2e<@LtV;c0!kV6}sHg?3bTnuSc3*%B3eubNn z^b>5^{Xn9DHIF%(bGu(;jbI_jFx7d_FDPnsRQ@|}LbpIE;eIF)2m6dQa%o47xmr0{ zkccP`f-|{qHX|PvYRR#Q?^iDw7~%Io18=1LJyT72@A}#pc<;C`VO1cU3hZ!yNz|nRD z<(#G=HLDD|wNp;Mnb8Ce&%mgIk+y4*+177y7YpYApT=n5I<=g zUP&WUn?<$IHV18F`s!t#d8B77StQqSLs>3B0bSvKNU{iHy2`uiYK%Gq(*{31N>E>y|93avEDfS!xWWZANmk+)W?Tw-{2ktDy;|-bO-Y*S7Dg= z%;O9TcQgeW3fh>-envQ50}xq3G)h|FKCWj2uxgQ%)-B##^ug<$q7BTJNMNtx>YJXT z3b5Q0Z4*3(dv$b2M_5At6S;CXCtj@Q#d}eDtv2Vdb}VqZgHOb@?(roV+y>?QC>jz_ z?{R-ai21yZvO@dB>%Ug=A#fORPWq5x9vXV51o|Ai&oli>&Mqa^dX2-XCq0BLJ$=J~ z&@Sff(D~GczsP7CLW4d8U76E*Q#c1YH^~d?V^Q}6df+oMlVb|w6g!?>u(7rwH9*>;F_#_>*F0SdhG5#L38k$sXM z<|&81nqO~l)Y-uOth|IMdiAE3Dd`6B~LqQJ`bF7RBi% z{6blL6D!cEub$HG1M^|K7fmkY!tzU^Iw9iNwFgTY(y|A35x~b#H$bJo)jC0~i3kI6 zCa?Xl@z#Jar!2$|rNGw310UpN8nlne25Q2uCs=I*-G}p@P`U`LBd;%(?y$b4(Aw4 zfcy$nVA`A+e{gw%MM-!YqT9(OsT^`dTVd$a=hFhU|9!4J8_TcSyua_ZMNQ5(SOb>a zJ`HQ=iRRrZteDq*?@J;MvpvAN7<|UWUSZ3_2rZfhzsHh~JIJ*B>k^jdIqyEnP6)%n zGOY)9x8}m(#sd55QHwy0?Z1^sSyMi`jx?1s~Xjc{oR{>1q}=Xpaaln{pDCF_tTc_kHkZYkb&jf1(7&}TVcb&`SgAr z1`x;wk0&DQ5|rE1+GQk1OrI&ij|+^4R2-IwDA3btM!M8yCmON@A0p#Dw9Wn<<>6S+ zNfs|Uhr$d{N0um>Aq*OE^?ozZL+~iEUwExn8F(!t{)i#xjS;U-nSD=+rQL5@XY^Y( zLc2c$_OB=>?S?l@>~Adh{o_3Hv_{~?p5i5Y@!mOD-?N9asBNka{mcCO%rge z98;i-2acB}7+aaN=I0cA7U$aQ*G2gfbEL^`Ic%Kx@#n^%6gagv-(%5M8c zqVLNJU;Ry)d2j0x4)wu5z^m=F~^uy>^ied05eRo^HrHdbqrh>O0OF5 zcok&6KG<|c^rKN3`pKyC5W<2%xMPxD5J%tPq#4BRmM&d8uhKBwd_dKWUx7=q$5@;;nMAo1lG1bbtjC|8mFqPE z{HY1701rU$zm)C7u)g~uB!#ed!cCx&hhqwh{?2X~L_lFd4S@=t;sIi-&G;whVF`M8 z#6iK33Ky!xDMDVvEBiYLEkKVA;FA|GeeFp=pTM+bs9T)O7qzuDZ0Y0p^Wax$50^wj zhde8D78s@!%aV5oZD>>j#48ka*DdD-`vA4y%J|U3@JcFL9#*1Idurn{LE`QAD7j*@ z>00VuxAl-1>6YXqvzCKk6Hc%~s2hP0M`~1DyUfOr()EMLc&Qx4up7==ex;QvALZjd z57clCt~LalSISP-_`}44{N@x?^8qk&MV6!5ye$cK&OTH~So?O0g?*h{xH=kYs?E`* z`1i=2rc|#{78F8!KLB1{!HI{w__>QR*2UmW-fg@Z6lS3lj3x-(v^W8%G?kh&hf@*u zn6F_IH3HyTA`yU^+?8;>ixDgmU6*d6D+mAWOpm<@v>Oc9!K$Ez%zRaAB03$_!IU>u z&Cu<`UgR!(k4Md*)R}B3aZ*&%2-W!n9J#yI7?9e=7e)k^3C}qvoV#tsB<$}?(p{wu zb4@mg(9cUNy4xA$dc!WiVdP}4+`4d}Unwu(kzhOc>;$pNgy3PphLkc3;WI!cabE43 z$MgLx;6n=Kb6%c6fzQAT{b>_tdKHW^K1WIXU@m%vgQwaRka4jPweE~Ry z#Epvrf2+3KvP$9`S=389c%KviJ~GrpymmHlbLA;nXDLhyrlt~JpW{4bdL}Ux;jq;X zbS#KMMHOkJ`181~qM*4Yj>ALz9z#zp4J`Wrk`!*IA3G(y*Rn~;@!oc{nYlx72ya)c zQj2$7O`;g09M1)YY7=v@a=s^*0#z)nJx)0?iLy7gb)iHW%%0=xY~}cvS)U%cmWq$+qM=(nDiPizndgGt8#>q|<|bozIQ^;|d|a?!`vIH}*hjyw#eZBe`SsdM zS*jd$mdgE=Rbcrn#hIp2kLk*&$9zff`8iB9Da^%i`m?|GD8lcY1~!%~0iqxw-vQ07 zn9|FFbl++O^PPm_c`2qWzhXQHSJ3lWoi}-n_o*ZFu{Qx#jMao>QL`m4u;Qng*iW>V zsvQNQ7=-1>)_rHx*+<(!=TgZc5}LPwy2xKb4E2jS;JQi9!{Bia_TO`AQ~RRi#T0tB zAy0k02*>|rzUt73yJG}8G2wwm9DwHj>$H9?W*MsQBK*8(Cj%KGmv3b9;qHS0k$y1i zO=sHHv>|S0eKh8h8)2r5#*Y|bTmxGV;p~X=?QaRcllpUvFKXb(N-a?Sp}sQVe*HBT z`(ED zM@pZ_p+awUl|PuzSPJlpTfD!`{=F+L5x?7o;s8z!q_=B)@Km}!?hiacoQ=#5Hm2;3 z6(iKGr^35j4E6GNeHcQ&4|2VNkH%}@H%}Lcny}ZDM5^r7kPB*bN00A#iy<5ekZo@n z-L%t-XCFiC8Xs%0I>Cq&Mv?^r1k&hxtr5Vh+IZA^@!D=npgie9r^vmwVWElV2Ol&Faiv z6&EdRmRub-TG>Rf-61$XvFsNm9Zhs0Lg3n*N?iU!{H`(3XU|tKp<0jNAE4MT8YzO4 zD)yIM<8f~d-Bpu2-|<72VJ%ML7S~EUX{9U6f{}dVg#u7}SGoJPpK6e7pZh&e!JLTi5 zp3V~iEO9n8SQuxTaKG7(*q@~fg~>ZjBfthL>R0bVN`u>kqCf;g+6 zS@<4(nkfYI>+!mqS}83p-Tmrd!X!#9qkZp(AFLWa*7^BV=V#{eu+`Q9G}neqrx*Oc zxolpjxKhWUT)O1(zbIR7m-g%m@n*lbMv0kwwC3=40L@>veaFlN@O6K3UQ&TWlDJX0! zycd3A&(mK2E2|zQk#u>k&NHx5gw_bBH|9ZU@2V0x%gzoJ$LD3@Ne<1-8c~@%gB>DT;jG8V$V9C+5H5OYwU1T=l*~pk}#zNDlS<@K>CZm zk^OMG?>DyoX4;}(&uTBTj!q!K$b2fge)rdpZEu%o)`hZ7Nl95F0cDCMro;R2+uU|a9> zL^SL7qi^ot{Xyr`bUGz{;km0Zvc3KJwTr(SC!*$NXDu;AJuhGH^DV%LpemZJHMIXl zq4t*KrAOg3G;c~JU>iB6&P2#uLhqPEiPvX<4t?i!X=4uvS&u3?;yRnlG%BjGKYOS% zyI!d3FEh$6K7tfFa@DL$T<;qcJer=1@ppDp-fPo?6D@a1v=9I25!KUdd}*Mpyy{5? zt}HRVMYYe%{2fzDJ9k=4aV%L*(`3*Z6s=qW>-Z3ac`H!1ii3eejfWCK%=zupa~Fo>152`SbxS1(FeUrYUyc+*M5<0`L+zb z;_ff5=;&|X#4pOV8_DEz88C3}Ma7%?HFrlFJqe7-=H#NXjT`(*uq<^|X}KThh(^3- z-O$Hhw6RrFj?*80aR@)`4~Dbfo%ZhLn6XUH{XP>?k!R6t^{1n)W|P;Q?DI%JWV$-B zBDnj0>0Ajl>yu7=7i1bg=W}cHT@5ZsDL^ZG%G6ROM=2|4p;B-YLX5HU(Z#G|lp#~B z5tVT1jbg?tVLW0BlG_i#;Kg7Xx*WYvjiD%oS4RN?cbyE)?<4^v7umkNOnySTPyBOy zmejAJ1;$wT+iO@%^Ksyr^M|0hA)Qs2cs(9gFbV?f=cigw1+KVqa?*xw4dZcxg2ilv zRJ!VD%9PA42d=W}!-?B^{yS%D(EEQiFNQh3A`FsteP~d{KP@hnW!|}+MO&FqI{y4j zUGwI~z_NMEx5IuOzu?4Ro@eJRrLxJ&4O|>cAJF%qg2No);!dmO@#oOr96YH^Zwzi(9KTB$Khh5^9{PuGw(ll%AfC2}#92yOXWZ8s|!lTQTwg&1<3SO5d3~~_Jv2@6tRu`?hA2zoKYG~L%mpY5|x&L%?LpHcK)2i zyyd>`z*xR9wDvf7lLwHpxo$rSkQlEJn^C~|1g*KXf8l#oeXmtW0SciSk; zHxb>ia2W5-`31<7%(*z6>J*7dcD1zV#f0c`u51!*>AbzbtWx-hI%EYT2M7bJOF{C< zc#{;8coqAz*LC)z_wR)I{BS~h z6p?r8f(G#485nK#xo-{c9e-hV)x@2W}sOs zR7GJv-98>ps)SD`Af#}iWS>v0+irpXOWWh6>*;%eCG+$}e#W%iuOFF{MLVaO@~AKh7xS93Q~zNOg#SQQ_ZjMA z@l3#Zace^0wv^-|4!nMTW6}fP77==6XDFwbSs(qW?wSbSMt*V5Lw>&V*$z-XHc5cG z058hcxdPvzLWHrmd1_-r0`qE zFsg}deWpiBC6Q#H(v7l?Xph?S_l!ois!u|MsY7TL&@cAqaR_2pI?2+H9O&Cf_*M4VHjjkC~P0@BPCySA=U* zQk2k!VODL4>b^TRavkf09H((yIF%qju$HL5w2g;fb8Uv9Q%9vJ6K5~LcuVS=T(Uje zg2K=&S5v|u5DjD#%?~=MvJ8)fU@Xwvbne`?U&r8o@S!z?y_$R&l8x4a;Pu7ploEk; zo5h`HN>mrsav2xT{}s)Tb7Yz%>AxEvX`>baCef9l73FvloB(1-+iMSzpg7|+kmVX7 z`v||_XoKI5_evp9Q2-VdRg@rP@7kW=cf(RJhLseksf7^>1YR4eFQQg@UJd{@EI`kC z%Ap$>*8)h^UTy`x_`Rp;HYFE~QVW3r@fY7ZR{^szF~IyHI3+Y#(RKitXNyPm~1XmUI*oNRAu>_gI6E-?AY0g79#1M zphbmxo#WdRueQTub@igO$uNvs(J$U(30XIzp~|VgwyXc)-jcN`g(tb5(OI^{s~ypj z2U6SKLzf5$TTy+cRF``v+C4}OUlAS>9hyJn9Et@t)EZHKv}_l^f_?>m!}1IS>@NTs z;H%$@B+MLAX{rR$Km^dpx4$s;7NVj*`QyB~~Pp33)l@9!t8xZ%C`3#sVDve^*oSmNTUTM*6 zDX`*|V^p}UVUgF`$zz6xom%pY&(t{+#{fA%#=j6Ca8?J>boWfX0efZVga(98iw<-p zw7M$5%?bOWhQxNcHRRhA+VV=`yj1X6^~nI=5Bq}2Q@UXh41h7U53hgEFo+c5?@}Ly zVj&8iAN8{-6KEMlILSgek|;A(Urj<#e)af`0EX<;@T|N4_)v=18OmMj4u%*nuFohQ zy9G$q(JC7Wi7raw0xbpBCe`7wG7QHsj%TyJhE_;Dg1Q}To;$hSHO;X+YSu(gvHnxjir`ir>C)KTo9vd&ogt7PU0!`q5sNV8&johJ@|Bp+7I@tMJ@#8emkA4iTVM zw&)yxn!qVgSgF4fM}0bVdjr)6;huhPF#v@-A#Ff3zwa6VVTMl02Y3q*|3t5=f2m?$ zx|BMRvZ!*9!pmLxd5(ia-;!U$r5=i{>)N+heU8wVp#Gv;?o^AKiDtOm-^&RRRvpT6 zFLOg}j=y!V`K|)Ri913_-Xtc{QrR{>N_>cT)12KnM0bNAwBOP2xkW>hPErRp3~`^)&e)s*e5TAl1w${2bRccY6=i0+SxP_Hx{ zfam!zuHJTvGJgNoe~WOJ2;5J@OSSj#Ml6&0(C-UFF44(-b!+2mUF~?zkr=AR+5_4R z8b$&*Vs>&(D19dLTd9I~lm~5C!-Sf6oxGDvY`A1@;*qXfwe!EnDB6#-<(>}Ed{ z@$>|O{$1ayPyB_lgy28#JP~`9mE~4|;sC!rMbiW>QTahMZ;{Wrag(yeGwHPyZ?4|E zNq(8>>{1ZpEMj|-W|7>jWEjMdggE_r{P}WS`wRTvL@d3ws4uNNdC8|KiW#{_t)S>~tK7ZG4$mPOC7$+Zu{L4I~ z#C!*-Cs1R|Zb_q9%r*fA0r3cYD*MXboIRuZ{(V4D;|=MDiTIQzWQ+D7L2l~(eHyL2 zbQfZ#rJ9KO=4Fa5`AZ-s4qFHH6NjJGj1Yrve=CVx9bvfLOFxFY=lX9q%n8?t;I}SR zl1Mc5y=MO^u1)%tpL4txNu0ht8Ab3SLV$LIQLQGf?yLPYri&;p=Ga@CT4Sc=x`prg z1Ml{wEEsQ^PSt_Nzc8r5XMP#P$qtt)JtGm4)cq948xKvoFoFSJE_BJtQ&~&26V`DS zzQk9)<@L4a25KJHBY#L9dbLjIOcN4Tqfkw`d$iSByANWeY_%H-mbaF)$y>{pQGog) zt>Pwe50zU$HkJpi0=iR{6)ZHm}JrL$lYJr%x4GJ$lrKGg?}1vH_ZR*k8AE_8J0nse>_MQP^=`S9wfv32yr7t*ad` z-_f&AYoD$R0tbcDVTezs3Pn!aSTy*HllAxl)rXw06vJAa-RlOc4XxgCea@=^TfG7d_VS*=L0@_!CbUb)SR*yJ?=}IBaS(Fw$tGOJwj`IdstPn-Rj=58{ z{kTh%x&8F>*B}$?(jY_n+o50iP={LXWmNn)3m)$9Xi^!s{cX4}bQGpeu>l&1lWg(0 z=R$*UG2CyMYlUGKlC3zy+Sx87-^nx9vBMAnWz%2SY6u|&IT?5If?az;9B)~!j*T4q z@wy!*Fp{hOS|dWk96rXvBCd!C(fXDU2j`|FEomvJw>bf5@kt=KK|teulq{|0l!2uF zO&F8f#};S=5drkLIoc!NU$fneBk6b1uUb0NE<+rEsl0%8$Gxemc8q4QcXzIRv|0Fqxti3Qi{<$q%0dgMO>|G2(Avbuoy+UxNZ1y*5|EpXr<5X zGGrxGC&XGD;V3Fp_J8mmwHa(0%+vt`_r zLL1+hzDUT2`g%Cx^|jTLn27cGd4%5qd7xkf)M#MZ_1UHhMvh1oxsjB+NbNnOYc^ca ze!Pe1tQ%1P6+>+j36IC&P|Z)gfCyWA3=CC3eju5O3PX5xsmRNvrldu7nt=5;vik@S zad>etgfFQ1)-DMWoXcvm*K8```>zhDtHkHuZKO2B0zxyAf+70jIqmL55A%cBDWFvn zO4wC!eVC7YNLi`+G>4Pr;yR$$jMBZ&Lc}mNMWR&dj?DWRG29A7Zec=^6)=7g7)0*)_OQz8 z$T6(xcww*}cJb{KXtsp5-%xc`43v3O^G`BJ#r(W+?@QKa?#O07Hb3)uk_fcu80_Q0 z{ANFLR`^G(3wjb9KL9%ZrTRVG>WlPW`=2cA{TPVwM*^DR05|&dq0<7P2~Z@VRO}(Q zrQ_B7;QY1IYK1zcY?L^$r1>$CzpeY3#WNm?1XJ5+FC6i$r$+mBVb%pnxdmIDRVCs` z%kNu9aEDH;%fsfl65JUsMR|?`ns&giCrKPLUvI!hivr0XtqdnOKBLtNze4kKQ})t~ zWIlh_Yn35h`*A68P``Iu6fi);FVp}pb%k+DHoY0c*Hiqs@y*ch;h;!V7fBjf^w^}I zJN`yS-5TT(LFU1`JRv*@ZUAot@EmHjNA)!>@Pc>huu->s6*3od*w=+o0`9RLU`^|& zo<>UXhJe;gAr(YZ?fz;X4v|o6534!PY|+^z)l-AmyS~X$-_5HR<>}_~{Obm#kDU*t zu4NH#joEq3X}KB#UlZzD7O6a^hEy@rei4`S0=)MNBL5z z3JEVq#O}X5adg-81f^Xj4k9-rwL;3!>yoWIwGEn18l)zB46w$lJz`=ay-bYHT#nA%;&)pV7b%b?c9uuT*(ywZ zK6HMxS|dpG|h>p1=?#dmBSOMnWLNQZ*g#> zmIAkXMYXEOzHXnyr!`z7cbP<=LpRAzB?+a6=$xj8H#3$tWsjOl+||q9D@sJ?noh|@ zJ?m#*mhbok=|`Z(?+K_qklLTEtqF<%^0ynoEdU)V)h_2N6^pDApYYW#Ir?36LMxMIgxVB8 zn{9Sg@#w+%L!?~Xeh7UkuErg4!v6^|i>S`^(OL*^9eAaM%$PD6PAnap({^Rs54BAy z0xL6(%m#ncSr1!(s|t;=fzb}BJ$?qa-oiK(YQ4K7K&jvcZ}_r@d5o4$f`kBKA#gff zNpfA&lWk#Uaz$%z;?W$cqnZ5Xq90*&g`|uU*2`XRhqbB?ZPm%u9o+S502^cOR@2lR zPsSTY8zo?;JBW4Q_ow1U7lIh$Hd(G+ka3x_a78W0)~NvQe`}C#vu=(Rn&b|QO4$LV z`Vj4qxr~;OY#PMH@S!}Ieyuabgy1!N&22gF(pA7sc@AGixSE;|Jm74Tep#8QK5z^p z6ks)Ua{|2byTOK#dlOqWGt3(F>xEdQ4Zk-$HPJ)}m)8KU&vU@nEfvc1S0A?&(`w)v zZ79nIXxIen?nPmH(25pkCamU8&oMX`^0+}o+dBDJ(5DB=K>%53$iPcB$cccRgmk@g z!%?&MSpl~d>F-TLk!_M|8cIMgDe(Oe(Tm?|}1ixj;%q(YdKRHYDx#32?#y7Lu^7iB&Q>jbB{T% z^}OQKorKMKy;VFhl5k!;-nStWfLI*F1=mMO11(tl4~Z;TEjIYUENlkpn^SFpzdcee`S|AS{iV11PF(3Y z90@L_!4VctQpW&5A}TO)LC`1kF6ep^PQ>*=xAp3`LdlB#N_$<1av*K5Lq)U}G^&p- zB3Bxb1!gS`N?S9(E}C1hA%mHWCLI8NP`aw1`yKg}9b}GO(Q6JiWr?+Yi>YLY;&oIZi#lWG`@^RjzZlfrk#w+I7B2C5woDiy-kJU!q&IZQA<%vYTcD>tRU1jClI;qqEW>1{xi#GuV;#m8# zdx*4K7{Ke#wdwe=F@?3{fZy@WhP${pm2A&sjp`iZIOwz;{vK$Ju3X5%Tj76={j0Eg zs_GQ*@%t{kzp+ykiInFxr{Y%V>zeVuKbFkHCXcR2zQ~iO2m)LPlAC&k(krU9wSKB_ zJW9{EgLS2l1@@xfla^o~7-o7To`C8mn&-d#$mtp7@coEaLbG)mfa>@VAx{ovMey6r z{4p!gkn`Pm#%0;WY<>d-Ljm(syDE~3id5yz9(xfd+O%%OsIo%TA|S+&E&iOqe3k9G7hg*jkZA%?U) z%2t3$pDyn!N`UF!GFS$1`NWZcN~mOowuJ!^lnh4~78uk047@rBdVO|OCyZ^2BO4>G z?52*cR)}0ZitgE=Jb!`r*q|Sd7o`jP0vE|Fhl)yei7Ets#BBx_*^6>q!UXC05t@Ue7OP=(X)$OT9|nQLJS}XKAzz`AKo=$Ze!Wp8FA!3e4U1DZc=}e%8ZcB zfnVVh)b0Z&`j{mq8m+0g@7Jo0^lT5mXjc&R%R~Yz5^BPR#g60N+5}Jfdw!%@=Dp0R zF!M6pqxxF@Mx-j$A&TmN7ggiD@!adoX`K0iG)mBN?9iE*1tqBaE}%oEX`Pi(j=$;x z$?rh|BTPY?s>vQ^b5`yKzNplhJ=l)!xXWxvIijM^81+FOz8TacjZMmYS(jthZ$G3K ziScIVW|Ij)EfiKqY>zzj<1odvW+XRTVI@J*0~`969{BJ}W{<;bS0QS=_$v`5I~jG~ zNliT?Mu6=&fvV?fqe?Nu{E5hKS>Kq}FMhuUrT9EHo_xip6H(``MI3>-b+c-+)l*)4 zDrXyf>(WLT;~t3Cz-lQ#GR9B9B<_{0Kmb3%^BBvr9xJZU57L~9&^`R0*gGE|w!^+K z?Ha*_!tZY`A18o+Gh2c4uVh5|5B5D6VgH^hoFU3a6F~$1zRrg`)i1X$XPOwwXs=1; zesJ~{?K!#jZv)ui`1&~N{ceB9qIEp<&KUBS3G?RB$bk>wJ{G0Fbzi30Hqjf5$cEJX znr1HT^pmU)Q}+y0?@QrXO`wGm?{W048F0F_S*2#jtK%!Qk)@w+ws8u*MC0ldYXMQh zJb5!O4+Y06Y1=N@h5MZCt5G{bCtn)nqRKtM+y~FNQ_t&VEd73#C%gF?jXFno7_r`# zE?=?-3WQ&N5#CfT8x&c+eVJgGru1M|S{!Wz91)q{5P6CP!;byZE>JxP9+a&-_ZCyR zXuvUVgA62ZlP)GpJlKq0Daf6G4ow)%B@K{&-(lvj#FNz?%g-cOBDnI#uUVk|R}V1K z$)JO>iccOcHqf{-2&wd|6QA(WoW*KlZhtUG&Bgexp zf(d%4>bCC>VgM75Kmd4R=LA5-C!IyrwZ`v+y@gLB`qrlf!aHrAV1hj<9zg)ZUdixV zDsR(50(KeCpup+1F5hqeQXR=|931$+q&a5DlD0Hh!m}Cm9~}qhVI0f&ZE7{k7R%LX z(5rHSO+puS0|iN|;K`_6w#Dx>->~!_NoTR;xDG|p5AwiF!j@F zgRDxdt9$l#BsqlEAR9L$A?9VY1K>=%b$s8F+nZQaq6=%kDV^gOL)jaxUVDoyX_Z_C zq@^)3BiR{+MX0FbFPVnr3j!u1tdmR9w$89sic&wtv2~e4;C6=IIj0Wj z{3HQ_lWh}7Kkr^^mi^l7JOeI?ekH{t{=N)-b6B!6r%@eOhdU1`*8}-bNT6@qQX=61 zkqGXH#7vuef4axmvav+glYIqF1SK||ceCUU`-^6pdV-Uu$Y2pt0z@HYB;@QIjVBbZ z$!-=0`0YWn>9M6n%PufHZ|wTKNGlOG>X6$^9h42xsF z(R+7*^QisV+x@oWh)$PUdeecACvZ)jD+SP5_qQfyR^i$c8E=kO{qO0CI+x-%Rp?~Up)N0!zP;j$P(+!q1Bg=a0fO0qfl6VD*W@^=_}!;z z&x(V$;OJL;C_LBxabkk{EQX=E}-C&0cd_P`%B&eCilfE}du7S01IdHQ<1dQ(_pa0z# zS5_&cjXaaOEx07vyw~AnjnWA~>pHB74;pNFBWBX@yyW&-Q1IV#LP$wMh5iCAI#IH) zsVvmv`#>DOW9{_U-pnRO+lYRhML}MmnF=Sz>f1PBavA(&(5CbI;Alo5Ok%ppH)(*$ z88B3Q1Rf)Oc}c8%%}1e+>_JwvLiODsL1t-qqvq%-N?5p07BWZN`h|o z`8(SJv=tiaf4l*M8^@Cse5{%qzP|$X;a_TZ!>5N^ zLVS(^sLFRnGRiN7_DF`8{s>M3$!b04flcn`wSOfz_>g80eOl_ZQJQLPe5^eQ!Yz#f ztf(QRO58Z>9x}i%!Ek#C5Uz?#$WndUFTa z-`Es)1WfC`zg!%xmPmRh(=$r*nR1`V*8sR|7`8%3oINgqmxwiwHDL`+djSVScEb6N*rUYykH~ zhnUwP{l^|7@pKTO==Jg{DIvRR7U(7vCP4jA&P9Ef%L?bRrm!ZwOb!&=iMW{V_+r={ z7hM1LsEragawy&~+Ob@WSX8qcyJn$q#fwKRUF`AS_1{5E$`af|w@a~WyTSw$*PF~>X=)+83dVfADUl{@{kzdgwZCi^ zRy#~ zoqE(u_s+NVOSS2W)-4a|6XFI<^q^X1eoD@T1D*n_3)Wazx}p)w%X2XzV()_t-=pTI zp-9H_CDQOd0tl{^AikJ$G2X(J>Ge<kI{GGvI3AaU(U*9rv{;XpuDZBvqGy0?hSfTrQ%Gw2If=w-p}?l0O}JWZ(>*!VgPU4dF!fr2 zyW^SCKAE5X%~GW+n56<%I)coV(D*R8_&yQ5z7#lm&qhp1C=!(&a^wRH2=`*Q{6q7- z=fXd}-eQYc7L|b#j}C|(OyKw0PT)9y{e>k=T=VlBk9|$3N->VymvOVPE@}uG`|a%+ z!;{v0Wp*z7ynihq{Ts9vlq6>Dtl;>KhDSr_U9vi7{%cQ z-;b2L;oW98c=FmlZE6SO9z{DeH76BYj zz*_^)7X);Z-`dCq3<)#nQHfqG$=a`=%yVphH}C{p>#m%OUIG;>L`cQn94GcTSVN&k zDCW^%oYh!zLAEz666^l{ZXqr5(`X584#!X|=Q&Xb0d9wOMgySwM%GcB?L%7{DW!E} z%SGEX;TK?oOo*U4RcvAu?;w4e(`u7*DiI-&w`&>xaEn@thcl&2V~@+&;Wis08FI(^N_dm3pVrs)_TO45a2JmI>_ zBO++E=x8sdy}wRi{AQ2o@4yF&Z7isE%5JLz*v*-+hHLf4~}V%LrT@+52-WcdEea;i6xQf$mYIHUsT`^en&UH zBlA>R-4SBLHFrZ#k19oF1(7UsgE?i*tj9>=d#LAAw@}F79h|c!!|JGtJ~+W0JT0=g zz^DD72PSJhlw)Pw-U?+v#N{&DjLm%{-wSKvZTCS$v?zCd{92<9oH!Cl&sOD0L7w>q z1!#?LxuQomnZ^~Jy89XYC>M@A^%K+~zXgjd0Qa z$h3%(vBm1evds>VM(-pC<@cT7rCNpA4&?34hPR*TSeq6>_!G6HRDRZvsl%1AntZ*P zrnT}<1`w!)q(nkKO(f15c6Od|Bzk54TyK^=%wczcmtSktv^BmL%evW#<~$AB zbWfE$>@s6eaPpY3+l;o!ywoMJ1FCLaDCfk#D*TPX8yU@@(r&xESraLco%o)~CMmC& z-{$yOH{IIx^JAk*nd0gBPTt|TZgz>O_d6zbV(b`c0YGx7buQYyS}Kq&Gy9>P@Io|} z*fD*EWk1!qDn{?02n7il&W<*4Ca7$NGEI1f9_u<+eB?s6n*}$e$FA@CRKs~QnBIc; zv&c4?H#-Q^d4YEn+f(d`{}x#p>V%Z&qe=O}1IEoIK+ZJO_Sy8cb?k10kgE5hSV!xiNlBhyC>7H3M~ zH6WLrwrO#H8P1a@{`d6Y3`2Y8nC=Ius=D35X@u=B_dEYxHRT0*zOzA4bCabRQE;J&Hvw8jpWP6yYx zI*T#G^Zm><(9O~n?~_(yECA9({i!Z76P@zlLEVs}S@50AIm?07;^*Tjf#zoY z;mDI*bsce4^`qjYL}iqv2|}(c{FXNsedC0T>Yq^VdEJwd3+JLmD{`7LHUAbAb;Zq7 zOSVI*=dU7_Dm=t+zq`!j8QpD`A)SUZI!whC!CCrM^6;d?q9x#%DlpWg_?0wXy~#(v z`Y7X~=tiX4pv$b0-H#M-fW>tgh8w)Nq}WlPu>79`uyu*%UqN4LZB>MX36ZR{e8j;G z{#)@cKiyJgwZOL=0d2qY+|Wn6f1(QE^uML7F={MSe{vho5+N25;Rk1#_wp;}D=YwS z@{CLf1kH7Eovrm%FxYP=!{~htRQ|RlYaUKQQOa5a>Kmso(mx2&qZrN?7RGH=#Z^Rf zOo1klq!c~30f5pJ?p~uu)T_YS&Cmou<=5?p{n%~pzm{@tog#Gv(lrvh z9>vL9F()OTGmQI~xc|B6{?kD-H*gK3vyGV@L* z{3_yzU~m5`*VF5%_=IVSTfUZBzCyp$=SjoiXLH{?A#B^+_wwZjl-&L{0mt90 zDy(=LXJwZRBm z$tM~ZXle-45EblIPn!EHZWP0kyt!i{d58l`DO4X3*aI2DTlZ^edK17?p?dlZg-W5Lj0J>wiOM2#DhvS|R`W7ah6wJrvxyD|Kw_l{W z^5vbg@F+)N6PSbf%l(1=#TrIKq{hZw906^7K4H$J5P=o8#0q{S6m%FouOZj0Q3;B; zA8vNz*}R|2>Xz>R?*#+_!pz^x58pT=)a9wMP*=P5xA7w=OMC-tYiVV?k%Ug|>fan& z{L2~nrfT%3psK1^ZAg0g0LPFoi(m2rcm*@FsrrMwl)N45 zCfwg1BxRsXQtX)!pL<4?14MPa^$J*kK9UnPOT>#LGD}rKKVJ1yK8B*dzO>Vo4sf)d z$WgkWKNxfF+`#hWRGr|PtdTow)~4L6)8y5IS}0{+7x)&jq#M^TOm$^L54CqDiwf)2 z8LyrpSX!*Fqu2}ys#7-3blm6Hn5O}S>zETq92YrUE4{9oTGk4^Y_W zTw_5x{fp6!!0l$xTr{4DuRX<{9Tu1lz82yv5Oz;%KQs1s_UUG%%6(j2^(o0af-(fav>uBx5Khb}33MwZ zb{w1wSt2FjzN_&C~-sRp&t7EZ#HO(sEB-G z12S6yGnYwSz|wctb+n0wtg z-PA{w<=cn!p%;rzIKeX5gQwK!=!}pF)Gm}tMUl1~U`Vs*ry=qsCxtwN!Pa|V07qcd z&%u|6gkHis<=$wX`%rH`&KN%9phM$>XHkBmoZZSRL;^!>AbpxFq)a{emF#?A!WWeB zC%5mb6fTw*TpB|;C@sPUZbvPuF?I29j|hp#vWtKl7(sn%5jrlRtOrDtiRwfBwn7-< z=eKVz7&jWOj?bA}+FM#KnUfFnlCDds&uI;2Am<#+kN^rm^}lSgW!v)3ZASRRbqVlS zZWLmIdnW#Am@;*NLPznttR?M+1-0I^30g(FgJF$0gX_qKmlaLn1`K~RnKG;9w|Y^j zpDJ9}L-${jT?URL!ivzg1LE_|bQOADb}5P^xtQ7>_!l()zvX z6h@=knQ&wi50uIYfO?K-A#-CKa?z8-Vwl%+mQ(4x{>`X{B$wHsfOYudX`06KY z(fcYOa0jPz`G*}mulVJNXD*e!jOU=qY#b6-nCo`|!*7k|BUlpC(V1mGZx^n$1z8M5 zqFyqgI*dF6EUOxW!js4kY z82Rt8+>CewB5UYYH>IuCjX;ILA!K}acNA|%={CMTax*`?mFT2;PrzPm>QJZtZ|UzU zQJtQAJynOTS|p3Yy1w_YdQu;VhEBj7^TJhS_B)O5V``d6Xg49xHCKH~Wv zZ!AA&1??-?Bx8|dG2cl%+$<)jx9eSm*OX-X{%HmJK=uwL`%a>ZYjpwTI5zW8)bS$| zz-LeG+daG=-n>fNJ@*Qt&GDsW+rjLaDI|>*HAiOavh{|ndR+w~@L01jL9~02-;`A! zqAt>^-Hf87FjDQqhdat;hhcb6rV|wIut$p@&n@l8*1j3>VQXLc)`i4h>*UdbdeiDJ z9Oto(t>xozN=afBEYDMDcVnIdM;I>!$p?4-de66X{N6EfPk7b?En3VH(pGn8!%lEl z-%DYJ(YFtgO?u=$U(ynR-|t-gSyRtenubORFiEI;s6Na`J)&cy>dYI;;^F{iZ`9rf zvezmZK?$E=RPf;?+*_v{#!ArRuyP#H)S7Uv5v|$pGgXbe!)^R(#-w&nl(9d)Hg{4I znu*!`C)Du}z$|)mg}!eVQK#pfF;zkl2Jp+znNv_Jh?1N} z0!MBsI$XckGnHc4yL3D&kaQP})N9I$_J*|=Jx1XdX3)@LXR4UlLxc~zQv*e`WsO?7 zY4VcAMe-}I8>HY}j!;)cGixY!M>RF^dyo?Y3ZoB!xX5-0SZ!e@^VBv^|n)9oy-;!S8lBbFtLESTt6KzLCB%6Fc_}701yZX ztpRL}(F%p;FuZ-^^$t*mgIMVfmt|j^p?p>)!RnL+5xM4Yi_AJClknwR2LK9u%cD0q zgkFD|>l=@vB2CSTE#CCmG9_@swT+84mJ~dI)SktcYY~%SX)~ZQ+d`+9OSx+HL!I!# zh2;q~t#3KK(`Spz(eLZoa)Yk0{JCI3y600UP>mkdrv``4G|AgY{0w$K)$x_6+~~Av z35PEGjbz?m`yO@}%*s}0&k_)X`(Xh>owl<|ZQ0kz7=|9TFNS?cN0yk6x7*mY7N*ha zP%Zq{7bV+QiGW0!c4&fh2iW{&&IKCh zU~-HDG`Vhlzjg+@Qi7do&2*m^7NV@rO7rMqd@ZQXvQuC2DN_m6AKD5j3>>J^isb`B zQh9-7nV(j+HmionPfRMa@9SI#lCEjnwSIJ{IX0}baX(bg$MibT80^!ue|C$AFYo2@jfX_2wTBh(uD7miSoN)cej@MdVyL?VztktL)|3bhkI6URJNRSDinZ zEryTMe_uR=Ibt~L+>gf*#zh09vcGk{&KBt$lwsv}`F+2@)#UI0Pox3UF#L(W1bJq6 zMN7LD8z+PMFESP>pvxw|aKSSSe44k4)rdYbTEct@xU}_tC6kt8>abO-fPtoT2<9!v z;k(vOgXv9pgZ3?7eSJc5ocKVM3W+wPMxD!A`=@R`Thc*oUT1>j)ok9_uM>TGr6;z} zH+IvD-OneTqs9Cf)Ddrg-v^TSw+1Ndw8wFJ;RmQBKVSO|;y&0CORv7g3BwT*=9vCg zuBD1}1PZkc0+Z&#dXEwvO@ZvcVN&eV)DUI~FMpK65_^;?-1FL$GKAoM94k5r%RpRT z`a{VgNL8>++`YXt>kB+V6_$8M={E3Zdv*(z+MDn!$r zgoKacGXzFzZD~CFDisJ}$8l7v{I?$$!+%}QYWGJGFCf3HZ0CXPr_New2cqC&#b8>b z5Pufqxrt`cqDpnOL%h9@pl^9@pe0f(CWf{ zSGWE%NMh1gCZhxaR3l;!%-n6djwX{R+N!JzNk>9xT7*kXxP|bgAyzQUA@aB3_5jUG_a`&bN=# zp`3hh6UA{QPMy^cp$*r}&Y=r3JE_twXT4CfO(z7A8h)g4nEQ|R4|D2FF(K5RiUxmL zRh8R|l|!|$__$W0qJ;wu^4y-Rp?2MgZ*N;577r^*g~wCLb@ys=L7c|RvjY!YgF!aP zz@Vwr89UTl21NzQ>fxd8{kOOTm!?4%t&-9(s(h6%cfi{V0|>oAs(A-@oLw>s%(-H} z>2E=N1I;)RcBBy05$l;NoF(X!8KO*~=(d-2qGm*EmT#Usr(<>ki;5%~NS8Pcq~RaG z+jVStpm+MgrIA-v!s{fOri$iItQ z*JqoB9%=Zd0?c)`@VJ#(!OZGkcqq497@|;u{{HAl}$kjW{OAHllyPv{0eRNb{8;`VG5ZfrD8?sYnGNC}N7@nzGBN^F$}j~CI9q)4SB0?kofCGLFEbXp@xQ-6eRuQ6H@qywA+W@^X8 z$;u-o`@IhFckbpZr(YVwhhDKUi`Y1Tex0?NFk)iu_V2T&O*4IH{;BO~!hoIn;)`6E zbEl0>?4wj2&l*P?TJ-A0~9UmFz$>9O`5-A|3EAe?z8T5lkDYC2xT z4z&BeUH{Z@VvhseL@k5cDPE3T`mnd(|C}=xspaX<`2LlOnHQ?UrgD%Dd{VM7Zg{SP z=qmu(!J^Qewh3Cz`;A^Sh?n^Xv`q0zPszvCTn+HTJ*`)jtr*O+&v7=-A}5_Y(Z?dv z9=L>eoF2a11)x%xqP#nNalWcqD{98{;?{=CDE= zqrGT-&@F|G+Ex?6tmcnIlUYsu-S`#~A<^=SmxnXlzX0EMPm|4NC|o>ZbVGjif6p;R z{?-+pgQWV7Tb?&d2q#QNRr=g|+Ecx>>Rjdg*rm^RP|e8)E7p0Wx+5^SZ1vdVVqcD$$H9pZ zVI)h6k~#Enp9gp-#Z-=pUXCx_0@o#bGQT66=&H=<^L z$Kt5V7Vr=aAQ|WH*t%KQQ`%BwYQ}@WG^a3Z^cpU>ZUOoxhbcKAvN%xD^RhFe2e@A| zqk?AK8OWLKIww4%9@vNT7H*>r-cej{}GIs6Y1wUkC=lcQ)H^*@p-QF{_;V*BOGVP z+-{CvVY#q%DSz3&&`{+$XZe$Nge`t4Bc&?q-N z$}~mDCtMVEbCZ7^tU|;u=Lqm)*ZKbR+lu3pS-Wql$ag#RJ~{bb5h=d`3GLD^WXYfI z<`8CIdMwE<8(x7tBl`-Trt!DM`6pn69tV{z8alTd_bi)) z_O4yHmVP^Yk6TGVaAh>Fah9CAu=^mXFm#Ld#8vZFR|;j} zE12f>TdL1b-4#G{-mFZ|^`r7QyLNLi`LIX{c;mFk693%;1JXm7!V$NnJ`v>#-2m;n zPO>KZ9reN80iYb}zfoS!kM{R$R3q6)LYMx&>q#}JjqI1R01mqp7 zm!lKfyNTWcFdaq`&ZeQ+`#6#b1+%{i?#^sNG^~B@!4;@Xm7ZlBgvDac$U3_9?a~%2 zGR&PV{3h&Ep$Fa8YXUqNGA_yJs_*Bow{`hbAi!Hl8bVT9j7qw)a06I-Qlgz`QoSim zi-!npfzyUiNq0HAFcHE*ua}XJh99xwRoqg2iEo(?3YAY{d{dliGF!LIopk^08X#!% z>;*HDx`N*&e}J#?t7y;OU55FMx7{f!W0D=}Q(4JCE^lZ!<&w=L@iQv}kC~A(uq9)L zk`ceHjw4ToNOytSJTi=UX7~&F37?B-{P6Xymr8`gyv$JV-Iz@+*rohQctPe8E0-0+=mOfZt-y<>OIlF4gpKbkgm+#SPz2QH@PA#iPMuS>E?!jGYXWi|E0A_&i20YoYS zOqJtFYzS^lKgae1;L&o;3{y?d>Zq|zv@cX~_}0Fu)990v0y*Y3N#QcD;J>p`BVK28 zQP-whBTHY0Wym`TPh$&3{#z$4hOLb&JKQI5{uWW*^6ycbTJfif2>aN-8DUEKpB=bL z`FJ~JdMscp9jM#``53P zH|K7otBhz*w_-|9s7V&GN59A;_mJ7Sb2kzG8#@(k9ZcRiFS!N?03T5TNEpnxyi0Yr zy)oH2r1pXr;Xb;ph{vle5{rf=57)RaN>Kx3`nS}b|%cQccNFul>JfjaKLy| zA(D+N1VIN}J}syDhPf2hVe!=*{_~9wwLE=CHZc)CO!)=@K+%|ej2H?p#8oUMAJKm{ z>NV?G$sOIMV=PeT>I6cmz6jaWQP<}uA1?(Oq|7~P(DS7Sefz#`X((vBwV|HczRUc`!&9wCDd%EAL5;ZP_+ z(euea?ay-RSxTq%E0S|Sb_ALEy94o?_T5@1jE}+uCMSYdaSFw#`1p0kgo`QnRNPS8 zTNwRp|28l2f9eV0SL_mitfG>Mejo}g&Ue__tj}}TcTXx@;-|iUEEIIz+5|ZJWR-0` zCU+h~DioYuuc8y&$>}LKd*paI=HlO>Sc?j6A#&{(TGM(>Aj{Y*qw6*rp&>vrbW?gy z>AK~lQdw6zcj*w|+{FfcymeW=OYEkYD=MYg-3i}D?f|`<7!|vSo5Rw+Ck$@=T^ovF zvv)kAgKnBq67*slM@i`bD$T3qN5fZR-8e|)^*2elYp8eMeZ+lTa1-v41GQxO=vXiBF0y)PZ?VmN@*VeVNS5vFSr;z zU(VOwaLgZ~xEUFmcIBh+X2w{Vt`>m$$lo4mZOeE;LR1kEqC48mXUm}Q@7ZE%7L120 zr)_Cbcpw>pn(*V42A6S|1Wqubj}cCbxcZ}@Ac?=`wLC1bon3=ik6|$L9{kLCE54Cy z7?bG0xd4Il4K3nUmQxg(?z#la^OH(0As9G8`bMmbJ~pYG0hP@`JXrd4M4LHyAg|A)9ZVq6qrthFW-+`QMOsqapL<5x6{j+ zi}aIY3G|t!4i*t(89*T6xmm^5{*BEDz6s+;^hx5=r1mzu(!mh~yBUlXt{~7oL(HDy z6IeuFIt&9@{BCkW+~y}ME67dJ<}Z$8K=#BgBLu7)rY}wzOF*uTmR#!_*&&dsVdMJYU^w%-@!;TKlt*mO6CO?}Pjg0wr_be`GWItHeR5;~qu z`fr0q$rrl`znVFzKDbRgwnVThwkotIpfHunzvsN5Nh6w4*#GTW){5m~57#7nJQOLq z3MEB)>z49bHoJ&%EX+@Z7T=NIzQ5nw3yi!b37ftfvHf? zx*2(7Vgmbb%-b4YoycezzXa7q%sOx{Hss<0pb}AE+RL5lk|Fb!kSWVBePu*LyNY!Oa^2J?n8J zvnPU*DT+kJz2j_W!5nxE&vyJ3I>?P6&V^hoRg|2SNz*`2?%4Qk9)mPok*1ttah8ex zZ7DOJ*0pld8-*u8n7<9K$?Hh+&IN`bst#2c?ZQF?!z}f*OIyB~QD&;r_+?F4WJ8KQ z{L-y+6KB{fK2POBF1g(n*Pp%{X*;=ig3n4?&Q5-j&tJG!+lTB}5z~re$wS2?*UsGX zgXyY4=jPJv1ihgg7?*lp8v*I>-UIW?#+&_|CXb3-BdmDDjjC<&+jisIKeZvq_i*uk~N%l@l zT2{yY4zsP-VF^|Z(2PpgK=&HV;U8n@M@c;v;1r@lM?w~5_!1@*4ez-@^Hw*+U0yE{*RnLEpTGehXpUG-N292ZHwWg1JWqKo{E2458G8ZcJR zAWJM~qkQ^NvO6B@qTP z1auv+!Lp*r(nhjf^tJ16Dc9ytWOv^KKyzy2`50*neTd5*_}_WsAmTlZV3YoWnw4mF zctm(e1>C{01WGJfRKtq=gpWj&^FKcTLN)@Lddp1THz4YG;LD#zv+*z$ zerJGv_oP5W+CTOyw91#^6x)h2 zv7HnTX$S;Dd;K`PDT2FBvFYCbxxKF`O6=E~!79wB{`-!ZZMj~#26Vkjd=I{8OgmW) z6=)F<@Qftt@I&e7AcoC4vJ546;w3_W7>XwK)~1^er&tcjY43MYoig@~B5DE3zx7DS z=7zwoAF6w4VZ?Ty-?X*`LAQ;SP%1H>V*B}>~;{>PQt48A=5{G?^XyfTB$ULvc2F1TT7 z*}*=36n#XV(jA}Cx7uvU_G7lhGP-pO?fNpDnjthA6p>8#E`44-bAZw- zGxKyRF_OF=!M9&3%~D6o@CeB6aZnH`X@~Y8H4Qcx2h$XDpywp`orFm)UKCWGlW|V1 z{t`om)k!U)AQF%{@OMRVQ3=8iuyH)>U`k_GZ|6tY#A)eR`RH;_HJkj~{;d&aqBv?f z6`$2a{w)_b^y@N#B<1?9V5p_IPfK6R`2Zhv6C*C$2!!2ZkNyGSdB9bRP*bUu-$A7@ z+X{~~fphXr3%{F}VZ^7IsyUJ4eiw(@ct!}iI^a^8Qjy^uDqt7}rilfVU!}gpp=bFF8jQe@Z+9OL zZV#jX9h&dV#vvQ6bV8P!*T{g~C=KpKJ&ht#o>VdUDKrb$x-^4W>57TPATvyh_E9(} zLOwlqgGz8j)pQzfW(aWzqcL);mmY$#n`h1A7}{7lhRna%gVP(fS+cAKlP9#UlpT-g zvl?M4V;K4Qo)d~c-NT{Gid$MGWF&FD)m}IXtrPf-;hPz!C5Ju9GiF1Weqi+?()6eb zC9No(V7vWvm1l{3D`sxl+>DdEHJs9?nku_*cOMc13a4_Vfl8t+Owq>3g8DSTgEhk} z5%(+Hz#PfCpS%P8YT}*U&KR%q_dG9uln`Z+tQy_L&1=nJ)0zyDcOs(o^{V){sRA^^t~)+=8{pI{I&)PF`{kJxXE~`7PjxzNGC-w_s1!i2%{ByW zsn^3*-{WPbtt25_$p@N;g?9-4e*OCgHuj=HUS(exL5W4+nNq8P$gUIHvb~*fWop#q z=F-`Ty$FpWkXqeJH_!e;L^y7(FtpTAGmXnPOUstkUc_v~nt$v5}YkB=1hVt!fS zBRH4ZKI*jJn?m)|qK1RsRisy1*mgaaqRij>?SOEloS*qnr|Z_0tJ6~8CIm(`cDtyc>4N3zt%`a1Vxv|Ed9O5=WNC&+Dx0&WUxxRe@zbpiIIM z71GtXeVb8XcqPP5PCdMw6CAr^FjP!pT|6fV@SV)~B$+7nwl0MbA^f6d1*LfaGjdrp z02DI`2PK@jmQN>PQ8Y0Qn%X6Z)KgI9qe~{Sd6jlRT)j*J$K<$AhtP4AqZ-8quW37s zKo&(5g&BF@o!-8LuIbh%7I&J9qQjG41i68h=^k=2jIQ8t{j@*BCkyf(`wpa0B^^9) zw3}KyCbvt+b)ljBL@iFI32~zQqM+&KI&`!5PYPylX5*mUL$|fsp;TIi?`M7IfXlj* zNk37*UqDNt38{);Cd)jW21D~v8N%m>s zzPU^H?#c&QgAo~`WNDk6`2p7TFcd8JCC~PhM(1t;WXB?|WL4BFH{V^mS7q z-@YauiaOP)&L7`Ej**4bHp0$CgA9fJ(1mPLfZITngWt|+O5OI6XS~{Zkd>BDNsKF{ zI(lNRAx38yCF{_TT$~Q}aAsU07KUT^>N|<@@Za-KwqW%%0pkldA>pbfitfpmM308C zr^1*&r1jU#KK-8e0`v7#VGUp8B7%1*;-%~S3GO`D!jF4$=Q3Z~=RraS?%BNJfkJw7XTZ4D)WqzByqtZAqqgF;(&6k&gZ|odB64Ht(Q}b|M9qgJDF@f~* zHbPAipbt_;K!DF*#EWOV;mj*-TjTrwxs)#NrBU9R4bg@W@K;H84Ko zoFdKJ6MbhsS-m&)theK{wL0dF0_5M?Tto6h|D-;AzA0h()R>q&@cX^}_H|#;)fRK^ zjU^N?dSS_dyWG^o17Q!_j<>=Aiu`)O6d8vMtK6+@)|>e%)%|QCOQRp>$5(kDH~?4g z-H(4?3*TRr)RMXx^RFcsI?^e_!sp1bY||tN95sLN4;A+b0Wc|NEluD$9FNarn~lpB zopmSTjEho6`|J;tAiv<~c(LE4-E8U*DRy?hGIGadManmy22{h!ArdqdF^WxY1=7cq zyq@upj4K>OF?vzifl{}*0eejR^XKWz=LOW&{_#eQ9Av~36~UJHqtM?QapZRfjt?lx ziVW!r_EK5dC`yASkqKlNl_X%N70Ei|$S@RUsgbUUXOwrtw#{Eq8)YU~7q%(##u^1? zzGpZzhc(Q3@cI$5jMdAMfAI}O@5Di|0t88}_=t`zc%#>_$oAPYHE9~767zkBq~Ebl zWd}{U^_jTm;zJhPrA^bHC#=1nBw4%V=)K`#^}L^?86xsrVIm;>-5cKwEeCvW6V0xv z9CYmpPcuReXL^=~8D>Pf!}eVn4dKD|d#O>RU#U&VcEFxYVC6d>96J3$Ir1Cgm;lMs zr5ew2P^4rVLRvA&0uPuvwo_p;ssy6|^fA3Xl3O~Pf#TrQ6#U>H3H=_W{V9SQQwi?3 z%s~WShn1L`Ok~ge$%IUY7ZzQx^@||gHXvDFCDFp%A~RSQf{H@?kq|l^q~xgvBDI!- zLD=6A*}J0xl3aUTyS83E+v4;ajZ_dQ!#Ga|LUrNMF|Rf8(uq#z^q!U}G&MW3hl7cp zdwD_K`I7pccIva3%)CfJe7gR$2bU`XpL*;l5^!C_{J`+FE}_T%H)Sj^kzDv9ZS$kU ztM^#}V4!!t4(rmf9@ATc#_a(Am_03R*fTC8MFDwZor^r2Q{D{xp;(2&01tKm;1`E7 z^0m0lRw1$*do^=W*NSxM8ks|Fj?B?(LwA;1B{T==h>$HnOd1HLr#y%<2b_>L8U*SF zA(ibj$2YNlDVNmlv;Am(h0=3c`r0wt9Ys=wlv>Sa(B-o;z~}E?U8ogW;NG&rFe4nt zj{K<|IwIF-C9GmzLw_>e^-$Jh)0+*Hi)147NUT+SBIOMZz@fILlpLrA@a6hSMN*-& zgNWsU>2EG`j~V?%Ed4POve?M>E_ZB&fpil5RIS19xxwt49E!SQZ;&U*XKd? z+$F(=m=|S6h05Y`ON$3QysCzW^JG zrr*rpVVOUgSY}Xk;A$t213f`_B({givE7iUu=*UJ`PGL5R7^J7j$5$QJ@;$Suy@T~ z)Kx#z;G{|%+y+XZrq=mXr_|F$A{w&5U!;az7fqK|`ubIz+gu&7Vxe6W4A0-HPmWDP zsGfNHDmtyQX#cLs{>WmcV;4;kDmW;32oUwUT*ymmL;;jyhnn0z$|PR|1Q#qIX*BFW!s-r1`3L;r&#*GQf%?$VFAGZz_g&cP2l-%tn@KY#&HA1Rs-E<~y(>Lj zx<|}uJw-Th9F5Jw;F3+(poT(VV7~4BNOowOC6?ZRN`J9!Gyqp)hbTunFk`}p6f{B1 z-jZX~CbGV{?ER$W?r&mdqN$+a`eORjFc%W8@Mw_HO6mq$3{F_s;o_>H;(V|JE1D?} z?EV8Z2N|+41DqT#MC?7Z7={{J`e+sZnhtyEnu_S`qhU3 z?d5$3n}54)o1ti3TW_kBD%c#!oZL1tF|uEm7WkGgv#o7~24EsN)=;z8dUOH_Tzol3 zMPpr7D3mg$M4<9szsI?=SF8xapKwQyXr2Q+Q>0>9tFKEyC=&ES;Dv?=^Rz6w7QuBE zGa~mIlE}bMHoyb^m%E9Zh@`}G*_&WT>J;doXIekCxXJs7>t)DNN49Eu*AMqBGw8`4 zM{rYRER3D!*qf0vQ>;(gE-|9DzzIx& z1v2Tt_?-0g33MJFp5JsxFai``J|Ni{VzE#r)fe7K_U%_tDl8QKXq5ufxpV1efh-*r zsC@`nCRlun0@Od%p-F?pB!s)w=T@Z&eEe#Rd|N@ACPvA2VlBihdEt^qA3*Uy(ElY# zr?tOm6cgjH8)8FwTZ~pYUdmF%HIBN2?&(8;vU@s1;VeEN@GVMT+&&}ahWJ*%TkB({ zhH9j9G}MjwndN*C2!_$7c*@y6VPTS~r0L}WoRW!JiOfM!Y{d60AL$QJLm9Q- z2WZvJz=PY5QwWVL!vhuUxB#kxE!=x#M`z!oZ1w z{2-hsxWmqqt{mclorC(zsq%c#0fx5|(qG?lg1*)z*l7H9aTM03BO*SHw*R;=oA1{` zL*V(q!^;%Z@p;N_U!_&V)?WZ}kiMRd{^)*U^kzc+GVHunjeimsbuLkT$!KYX9N!t0 zusaZjLwg)HTPQxT5rGB-l3sxE+?GJ3fm_y4n-Y0HV-Q2Y&Y2~xh?kcX2O*5(>up#3 zIvYcE<$NOrlOqlH7Qcw)*r>y!05pr7Zo5yd&tXp#3GpU`vY=D~=d~_F|}^@9QjuLx&Ic zOeX5Yj^;?KFYzcdR0kzSQ(PxQwHFvv=tI0fR{P~kL~Vt_1Sj{YsBpt_=w}}Tlhy!z z;MY$9UL()(JGmSF>;0;FISQFiAp)2h*iibSyoh&{k|7XaW)zR)PNYsI<{kRUu!>(L zibI3{EL!+ErK~!?FBq_!Ika_dbZ50h0~2Ma0_6inxfij@ONkF6QXD72SlgaA0OsCo>o zj(Db-C-)9&F;0K7={g~h=-uXTldD@h!t`xQ5P9*rbVmkEG5WUZjWsJ7#2TIHjvgW-!e8|pgI<8o|q_d9F(o5=wmXJ_dyYY>5J7J$kg!%LlPd1~++@0HOxXfEQ{I^qY0l%C z%#w9y6A3M?x!kw6W-L-PSM@@Ia6PL>WA3!0LSXH_A`p9kmocORW~Vv7QDUc zR zbzmBp$S-O;BAA(10;`;=WXOdZ<1QshQeTfN$Tay|;4PmpEOLTB)*yp1m=t|GaFz=S zzL4qffkus35#ahuwkev(+<1o)36XDw+DNWNhLD%KNM~n+2a-CaQa*fWFD-s3ilNLh zCW5+o1O|qo&xu=2=c8?Cn`2$94?pSIV zMZYJevYkek4`96g!I{I)-qoWelSGR?(=*g3zb~a=;dd_?)Mg5KEj24myv^8Bfe~32 zxr)(A!~}}7fHQPvP2j1RM)B$!%l18YlIHL_)HYjkR`}U4<~i#+w%F?w-})fsuH}36vt*{tb6*7l>X%{bB_=@;d6*&x&<3_7Qg6z+O}eMQ0e4qeWczsG(X6k8ibvclqt*-)>CC;HPi6tDLX zf}Ed4HdS&iKhVN3Ljjhndnu03TgY* zg%uPDDdR#Vl4p!bSwTacVuGV%zM35VNnSuA%9Trf9PK7cs~PsMbRC0dl5YjlYXO(#8~pT<|rpfl#v^=MT{;)M-gbwHAKf(evfxq&;OW zNlW2Zj1?nFlULP)i^F|onch`m@nGQdHCc=dlv##(GhV}U(CeUa3`+uDX8>?o*Y+1! zf2$=uf1Af7RK{sX{4q-gyzNSaEVGWod)P677$v5eoKk)Sn^7 zeAc(~zgQSdzw^FNEEIC4c+4X0vwXiR@>eEANm} zy|W3ko?<=QFU^ctjVC>4QQ>*&xLk)&N{IeNKs5kRmc9fwdrAF>-ofTw|TFdW4z`C+4l(RgZJRKBLk3paYH74sM<`)%?c<+ zlo3Gb7;M)?g47?w-wlfiu6h_GExJ^x@qZ`Lx>htAhw@vEw9_d1X>2w-DW5XoL1;dg zdu#W|xrqT5T5Ux(`Pm9bLMAv0P7PFklM!FG0|V_ND2`_4-_;`nt{;B{a#Q;!jj;>6 z0E3zRKSq6|rCro=j4(&n(E-0c`(5`jS+yaVb5s69J(tvUL`n!{7NJ~p>qq5tn!sNc z)!3N~t-8)cZD^nYODz&%=o8n0dpz0>c__&J|6R&)=j^bPF@{`QBQV0oZi%!$QTFCP z_GdXt{3SBU?lZZnZfagqhZ#DXc2l$ZaKFI0jOz8q;w7|b< z8pLoYgMn=q1)+$cN}9I2To-;vs2$88G}n4E~<8q}0yVna`_l1M+(ii95f_s4W3C zf9NsAS5fXSZ>XJcaY)6IzZ!s+FFfLE)u<34X}@Z^6Lkc(+VmrUU07?O9tkkt7vqeD zLr!Qg)kX2E>nayec9}GYXRU^+>7z{zhqHs8!M=Jq{*BQWvmj7lwfza+7>cP=R?;j? z2lqQp8rFGWSZxC?Z#c2M{qB;nQ_rs2jP&5zm#6bf>J}SqNsTuw@cpY!!AZ?ATlK)c z6C&@`bAS}1(mI}QUSE;~r|E=J`oRZ>MA6p4;Mt6C9U7T9!GQ6P|QH7?i0M#)>QL%XU(m4T!#kZ zJP}P{ANh$dr*rU~n+3#5?C%Ov5VhkowwKM6pmvAOuPNzA$=-B&8ecsDD8cKRCUi+L zz{@#IK|nLZATNwq5cz$oamXj;dpaxK(J!Ckfx=H!vVvYHu^jjoN7Boep!j=Qq?qwb zFt4eV4`w@<+fbNE<+3=;LDGvY#l%M;w~$4%os1k=Ef1N!LPNMQn7 z4ZUQVmiQsP%By_&)lh21vSzZl8PUAf3w_KcF&AYBm7p@s2d~w`tN^vqhPs@m*U1wZ zURhh}yIe?S&)_MC=Um&jZ$wXIFk8n|)W!1BS|Rq@NMJ)FLICu8iW&Ko>fu4kuLht+ zDOeJppx5;l4^7p5QE0w$KZqjPU5Gc>GkaNqq_hHGmNic{$!_TlBGNQDK{*C5)b=V>T^*W`HIso}LUs#vHU9zFQnYo;#+i5@&jacf@fFpEG8{cc#hL1OJ=SLG*c zl=0!K8_Hosefx!ieovH=pHJ-NA^SPEUWzv&DSnEp9m(hKL3a4X91RSge7iDyGynGA zMN<%uXmxMdiKL}8l!0fuj>ne_0~Mgq4-x4~;Impz&9$i{!DO*^XY5M)CB0{-r2@e; zx&a?qBaw*AYJzx~9PM72oPa;T3vlxDoY*>cGE16}P#ZwT(xCX}a`mQjiq5TuO?DJ* z>~IAfeMe4a0igHn`k;mz-EWXXMT>MWzAC*jn}#Q6Jiu1F7=qrPIPi70*|8SoC|7Z2 zCvo{B?+46}a=32aF`IbXiZGhcHM7+oTVHuo#MFB8x;55owmsP_ZeSkZ2(<&ZP>$k~ zo#<^W_@j7ekQ#ycEgk|#qw>bW{O{Vd3Lo%W)GfcVoL}_de>dAquzp=7v}svuXu}|v zbEg(9eiVUZ!ZUg)pHjUeW$T22bg6Xc7WScq{|QoT)A zCjuWXb`JamkfzBJRQ$Le(%&aVE2GFxGPa7OvGdGJOGaxS%uaeQjjs=lJRHPuOZ57W z=`*3S;Z$~xU~#m6n>kIIffETiBZ!-~vih4&GlFC9rq?seVh@+*EvUKBg%4!t2g+g8YhZGoqay2`jkIgN*UNhRE%WhOb^g*n9~LMypcCJ1cUufCcMU7 zQ@p}@cQ@UAGF!X5VVMtWaq=wipex|_Gk?98O~K_^z4--}o*xtk(feXBhcZ)`PXS;W z;Tj`BsGUG3Ck4}9(RTr_e$S_jv3fm3=s<1SoQiTA0Uh(w0v(qE6jL%aAnyy6 zUHDYEG8$Z(d&Dmn=D|ANEVTNnMpHP?e{f6tLb=7u-v6moDU-4=7!EJ6*mFAZoGnANQ z1R*2$bShQ0k6FepJJ@YXOxec5E*B!?q0JyjYqkfsNH+j+C#-bysz z#v|Z7@O;=~jBdf&F6y>z+qP}Zwr$&d+qP|Ewr$(C-96jpUTdEmBs=FDNhMX4C-w8n zeUDG)Ao|@EASYL*p$A2d49m23v(;_vFc^!~Yk?l&B%n>-gZ)(GWolsOdM*VH!(~KE zu}351l?)!O%U?GYN|1Ue(1jbBZeYbW@K7Q_+bQwcSo3O{A zaOWnfh7LXYgs|j1uNeGO#B_qPf58!hyJ|C-30^ojd{>9Z)B+T*$g`#c7cJ6`TA~~z zdlKP`Z|eV3zy;l*i7?`!YNJb(28J%)7RSwdCcx()km(|-H4Uf>6v+-N(sL-5LKq)N z22mlc7E`INSs;_=1pYZ}2RTqQrXpXqk3Q|>|B&}#8FCzHJSh~Pr&o^kJ*Y{hJ?W&s z{h7gU)qthvD$*lH44(@j)AA+H#V=5#1_!4;_i%8x6PXApkji%39^jNfqeaE;^(Zq4 z{tTG^sTl>xhA@io(2o*`&5J*D`6Y=3iz{C4xP7f{2`VGJIF6)wd78irAfg?Xa`%j| z5jHat#ht+@N*)ug*t6Zgipb%>mqQZ76-dBbC9eM&P)-c-Af}p+HVDiTr3Gwe2*J=;Du7trbsv&F#}=Gc4wIijDD?VngLj zOi6VLJ@9GA%ihsjdl&Xhh~iL-%g<4mzmB9oeC;Vn3Ouku4tp`yRizeuL4C5u zQBu!I2?49ek;Vh|m(qqX?cMbG0&fWj@g9iPs1`Z>NM{dcl>U<@gqN(~tTdcTk}27XrN0vaMTG;0 z=cL2COo7kG*BP0&Re&CEE`1{PtG>I)taN^r+0+Xlot+|zs=@Lts_}+VQ}FmH|GOr4 zOCe=&I=9;eY_Xm_yRa8(e|fau9GY$}Q#Y11hLf$ypkIwCmJpdU93hpIQcW>pdth-S zCwIwS4HXM4W>i^uE-&XfL{hI!PQ8P4n^NimmT`?=fmgUFY_#aK-@WC_CUkMOK)xt$ z#+0}vNa4ttzjbX-x6*>P$eIk&S^hk`0M+<9?}(Sga#Nq=-}OSPEM6DG(*T#Ao-Uny z3J;xR&LF%XNqPIi#(%}ymPF{JxeUYcIJLVdaY?M`O{8?Mz@c% zKmGwV4jV6%XW0lv;}1P8F)=dk>)o815G9b=^)C#l;^gEr^am|E~_5%5y3aq zw)4gW6J2mP2m!p!6*QLjGel!mF{ZO%cqfGq8qgS*9CS21DaxTtdLQO(S*;mJWX1&D zZt1+132&6?aKGo#&j-iWQ;lo!adI0hgt^4swoDBqh_%+y6~g3%tw&);i=Smy=8PaW8xRfnAbxdYxB^1Eq=ntN^a|x2|kcwK)Y{)(ZlYIdt3Z zydNA&3n>7KxKrCA0RmbXX@Yb;rwd7=QA=W4ZsO-b`Q35@FC5u6V^+d!A6Y^q6~4$4 zUvMBZCZjyw!ucI$W^e$5$@H;+h6H>7Lz=O=XIo$YL0cCHKJ0}C#Gzh__u2&Uy@QRl zDw=znAyv}itthg{r$}!zXN1Rrc8*3GbTjY4xt^y=9ar$O`jAgwVh5uzk_;IYNp)0qO<9tnjQo(Abi$h!l^zn@ZG-+ zmdM{n`&%Rg@*nz}9}ww8Z|bf^2=;3*%OdQbGEw?t02d3$aCwicgL;EG>82`*2+J`7 zMr)lbDXsuWi#?>_E`2yOnQvYBwHN8jCZW@V)SB5%nQ(B!{q34T{RBttw?zD1w1*dVlp+FKwyUK}$@C zjOao&)3(T?@2@Z33;6Xp8 z+}w;!o!yk+?f95xRkrFSqJQ+X2}Tfx+reuX@Dp7S{G9`Pbj9wA`x(NYxmwG>_e}(g z*$1187JX29EP=0GHiq5R-3*gEVROJic*5JV-8@~I31xkG*wg2?T@*1;id*e93To)$ zbvm^a%2D;VT;vMlzOHK&7zL$!*7z%*xD#N}1B;Yr+yf}`H>T9DD>dFAB+u$FxfVD2 zjl#^^wjW-1`*$B*l8ZW8kU#j=8kK#WkHVWPr{UE`m6!VaflNXA z6C;kq(;$zhFjc--g=GJ@uguz@yt(j^qhINxqtw|#14PD?wDSP@qM?((I@P0S#Ole; z_{du5ui$n;u_VMAX zM7-6{A^o28JVQy@K_LW`JfLr=W^Ih&C+J<;YE4zKgpXV$s`rM0`#b;&!i>pB86mZXnet8WHcw<}k4ZM9Z; zuXS%vE7Ga!)f3X2Hqxd{*vWI_897UJ4!deCvMW1zgZoAlr2GfHA^bUn-;4~CM6@zU z%Q+`ak>w0c3DNbJHWK#M+t{;cEq0 z_&%b9MXa_Nay#{vLw}qQ1S7VHsW7$2#L6O8tHYH5&M8EK0Wc<8_!0hXK>>Sips zK@8{@3{YCIA~z>Ccym;mKtb@hR_r;t&=|>=f7ls8LL6Tx{$3D2=cIqq%rpYi43L7T z?0AQQQuh-nPFg+cLIyqsc5_!E2}6AIAf6l2$^uWcT7FE#X-fo=bZ#`xg?6LI#oP$7 z)YJ!`?c$TllKj#zCc-XNdWx!VHsTbcGQ$jU< zHaI?qr??U9k(rTnKF%jo3X4nn=`!$!{?R*1vzP9EEQ!BSbIZZ=!Ukex*;TwsQ>Qg= z&noKr9tnC3+#roxMpPp_c$AvekmxJH3KJ7NaI=Q3$Mn?fq_?Ixu?JfhlL1hk$sOUb z+r(r9-EO|Lme0^BAg>02Zi9hJ(=hI19G@Sc)p8znn<#+GIP!5^EW4gFB5mrre)GeS%62HqL&6{C|eCYD#oB=%>-XOSLlg_1Mf$~A08{Ya4xQtHYJO{nNohnlyl zh8HQB&QDfpq`+tMX;B{-AI;XNG804_BfPDrd|8dy>?lgcGUj;Aa_#x4-PmOe)zIY6 z+-}%&9+LsUQfAX2gG>o}9oLPC$#WLl(#yu>b^C~SKt&MAoBP3IjM}m4Rpvld^EPLW zojqEx9gr2z;Pg92Fy++(;djO^BCbkBi*M<3xHCTRToLfEuUc9c6OuA)cPGarVaEQB zQ!A18^a;nEg8kG&!w*AK4?nif6wof9QrB3J_1GIJXu?;`wh<-aM0R3^&`v!M)4%gtqu zj)Hcb-H&%_MrM%yuLm{x(6d4ruC1q2Z(LCJL#oWmoFRMTqo+~y$xu;1up6f zyFBh1NY3|)Q{*R2gtZ_j#7ijMTX8U^vp>w+?{ne=cEr@g< z+}9=t&3c-s^p5&jK^Juc-N3j0$(y~{KO6C5q1?6HJH)Vf3)_LNOi4?X%FU&^#1T*> z%=r`u8J8lrKO+k%0wOHZcc5MC{%`;2{P+>0{!BhbPv=35_`&3vb!g~PA~}a)PB>P9 z>ZOYUBwwY-yeZw+Pv9v|hlqijj}+wHxkT?Gjc%ricrhlSR|T$do9#5kF_>czEu2QI zbETU7QI7`ZALj~Pjrncak7OnAZt5##TvpgSqX-L_AG&ptQKk*hJyYzP2Rt;x*e}l! z?JLnp8+e8O@H7AoUy;1>MzP;hjJMYSH$ce0!N=(?PTEWCDq)U#7<cPHZ%iv!d2GB+OL;!O*Vlg@Fjl;?U&cp6aDqyJNtLD~U;ff+FK z>xph%j1Aq_Qx&y1V;o;b%CpLS!~;QX=xbPY77gB)Gd9$s>TOcpk3YOd!d!u(_War2 z2}`mze?qHDU!BysST!Cs>NvgHnmx)MjaHfgAdOf7osKwZ*2+2(s7a4Ut?3wmNctRXi^p>zCsI8uBNO;$I}+v_&;0m+dsbKDSs zK?OQ#8X6PyXohQCTc-4}NpQ_y>(#`T=xQhjJ`?)PXkAc8k%>ri%F};3-4cw} zgWyv$!cif_1p27$m;0Pn4mk~UYx&Y-4T)mc3Fp+3t{Oy}&S~S^1XBHbkGfJ@Ys&GX zeQKhl`Dn@-0~JLmiPW=9DsD}mO-xM%+!eqm6MB9)PY-ioS&*4tAPp{qHUD99c~FiW zT{R*b9VYSQM1{vppjy|Sv=vJF9d)JPv&>D1h>|(J^tKv$JK9-|n)f5$I_2+RwSQGk zf)pF|&g+`xLhdCR(0!Zvqh5Znvtd#Br^HFQ^ftRaW~Jvt!Go5w@B^%*0kDu6m9XSl zYQFp&<}DTQH{t4jb~Vj-Hl0tGo`(gLp>tpk6U2lx-6d(sGEj+=d%bBOaQ%ogUmKAT zm={|~;a~#TL|a~$7%+qzEW3EQgS)fD+TC~{9OPaX5UC7lt#LAly-$9zsHA+JOyypVSj9_qcI30RzcuY|mAeCuR#NN&@Ehb)@dhz3 z_m&ho$*Ba>FXQm*Nw}|*EWvg;kQOu!g6n|T|M~syho)oU*An)b5AJgPEbBd6NSz8i z6e9uP_YqMV#2(a-Ub@if*Op}~ zR~j_J0fnY?Hzp6A``YeYY@_kP>b;_ab(eodHh4v4Bq3v+q$4pENUh(8p!$%ezW>;GKY-R@05|AL(FJ20A`xxd99?YJbBtmi~d!>*f8juGhWL zGo`SR+$Pwuxrfv4g=yPxC+i3^gXo4OU}Xq-hxUoH-&3tvr?~0q)ueAwxVK@mfbbo4g4w15A7zLE0190I%hx= z5HwbAXMBqlhx-Qk$#hPb@X)L+jKN>g^|AHAn!-2?<;&uj)ve7jc$rEzXDpzA-PVqxXU^Te)0$J+QKB;{aW`@$ zST}jjxDLc}j6Z}Z3%et$&dtW}=QP%A^*p;dOizjwJW}nf<~TE9svU&droV1mE@HNW?i9Ra*y^Pt<5P#_@%gk< zoQoHo-s?n7oFZ6)6P(5VrentdHjzM-90EvGZH&bC7+4>Zo`wEzLzqPRfH*<>mo_Pxr`fkA7Tkw<$z&>bUZAn$1hEcR-gRl~rz0vg~8 zrAncG|0PU_>u3xPcebNT@6HM|qN~H&=5s_*NA>*u`YzKJ%!V3shPK6)W9&tb^=9NR z>$k+ILsGN+a}aGkdkoBdx-D&eS2PV+3lN7em>vmTEIDRKS02BUMIRw0vmF>Ty=fSi zg&(%)czV(Y5Crf)CsIqxCb}Zlb&z zn~T}VlNVLAU^U&x5o8NeyABk;WVhCR5N>R+)kiJ?b$7J_Un2vyZGu9hSXI0oR3NL% zhCqG2svY{}K@rREglY^=a%+2(k>&-%^`EzYB+6%W9y$Zgq9&u7uX^9Pm)4;Agz(NR zN1-_<7CDp8!LNb|L2k7hv!bV9-YU3{-M-8Z8p-C#9)d?YcPlvs+4)%73OeR5)C9BiDC^H zkN3JogDvL;!hsN2*Qv}0Ivi7_IqZ*)zTj2u!RZxJ^gk~~f~aZtPOH>Yp*nTc{dK~MuVM-l<4#_LP+^J>NXNo|J z4r;hkYBDDFE$v889zV=GxK3EF-!3VE&0mW8H&zs$DJum1J!A$_{OBl7#+?`I!hFE_ zlZr{)Y3x13G*Sk{E(z?MsSZN1gnTg{i0-R@6H84QOnb%bYEIh^!~{TAv3N&Flxij2 z;$UWHE-hGITP!4)O;k4zk2&r`Ty5Jhbv0bB}8Q+4e_;P!GK#k0G_KDAd&+m2a=eJZcOAif5jIbAeg_jQ1z!6pg1AGRyL z+gXkWA@|Awi4eJ3xI>BzxW1irOJdBIk$aRak7p1tvS@#NC$YKXGUv!`HK2&B&Z)Q( z6zdKr-8{bAe$G;F>l5A!%yLo7*aEwV?-Z!h`Q~k2N)5@Dm1XORGZQaVs7r5+{M*I` zims2Q0Kv8whJ>a?c1+aEio)w*h5)hJHjDIIZsoXjVvULo;c`)XP*hudSX^Tz;9nE^ z>VCi)IVX6MBq#p+5v*;T$*D*JITrVRcrFygU2RJ9H)sCRBXg6PO{p4)x2$v@y12P> z`pQ)?dq{nL?+zO?1R|}{Xk&^JuuUI^v=|tJ#-gjPb?LW0=TM`eLUq%?1RmU{AqtYi zu|4^(>(TTbNv7a#6r1Ec+@Ujw1Hxu76KO`_C@5MZ{5?Cw2Q#n#mRla}dIlQuLSs*j z|Y}#1x(~F~~tGP4*C<9^7r++zrlPK6w-^Tc$DDUVq1X>7Otm(nMgfJqb$vFgcQ! zM2)s!g#I>;qauALM~bN=!xvgIpvBwGl@N`TGyJ0)ha|qm&9EJk%IGCRY8S0T3RO(I z2eLSty$J1OdCiVVheGZ@N?2zoE*eEW%$!~FfXPY0QG)t(`l-$TckKZ+*5a~94s2jpR_es z`AMGu|F!np-2tjjK}4`wW`cX_0&%)T4TXxHw&J<5owZRyJ~WmM&&Bt(*aeE+$V%bO zN-4rhv3NhA+=LqW2S@~evJpTqIB%FxA`1)6xJQ-S@4~bIs)#eY$}6Vjo(O+p@R`|l z&&&%h**8y1sbE}NjR{jLu2rpCunmYHH%tY1GQ0~49e%5iMiogDyFVFM=hy7RWBpuT zj8>CRUEMg{NzyswJk(N>yA#g1p`Ne;{rTp7ml5qQTctN{f_hM-3KBnd<<0RA%~8;U z2Rzc=%MaTK`Y10}c~FuDyAxSj-Q&@hgL%gkv3jHqDy7Lvz$wEH%ha6l*wv5U*MdI8 zkheOACU*S3XLx2@3yFrZMnbT)`4x?j0CmXbv42j7-gXL@eY4=6WJ+q6R@hk9Em|A{ zfvb*J632W#)3RqXm=3Ic(sevmPgPKSH4CWgsEQJEo3;cR<^Q226g)AYBOMGV-pO7B zL??vaK`jwX2+)RwdzoAqA1Y8H7D5D3Zb|$L=_L(OE==VF9(jJh0Ct#Osir;ZaBdDS z&_WV=dp6NEq3~aiT-^$-^y%Y^XXFz}<8`3Kjx&u@()C@N}lnG7#U* z#AaTkRX6n<2DoaO_&2Cf>IRe8&r;~LN681#RFVLTI@esO{$&KMes3hZHNoD>0u0QY`I+4^ys&@JvFn~rJR*BDu!bLsoMw=h#S(eap!;akL+ zBz;o^5=ZfkbT6H^p#)3{QQ9jG`7H@iIm;*Xtk8g6?_G4{K!48yeKnO(*-6SJn*Arw zbcnI$P50SdB$%G{a!a!C4f)FBE6Q);&^tJl0~l#Gn_!P=&V6`$yFdy_bTTO1GC-Or z{QqV46WSvtgv$@NTu?z@V=JrxS+r6y=4SgS)0iE|is0Ix`9 zbXfkF!bl;^G&K_gljl&5n9CZ3oqSP_YQNHxo)!Yp#ClNg+*o6&4>+FLFYbw&MWsQ5 zMD5Gu_{1jDuuQ3c=uVTD;9!A4d@L*NuH=_4{xN~A)l7~ELx%#4B0k~Mp>C964uTvTNwv^CuFw-0>Nh=P=8PX>DY$X3vLDS9tu%*p z#K@GrV~_%dSd4&x$d^5^~ z=aXNs0^Am`MWZnLVjvjQi7{>#OIZoTA*of5Q$_L_4zA-m+8h)?b+Mzb#PX%JCtO<>)9v6`ns%0@-!=&>qjtH9PP#H z>&8K+CT+bq6PbX1)^k4>qJ*0@8*ttz3o&Maq+_rD4*LFVvx;5cuydPEB-`-zEnonc zc`%6pHYR1neXqmywE!zrwXi?gR5IfO^lAVP6yVp2; zPw+DgH!?UU5u>**P?U=;)G5DBjacA~p^5 ztwo25Jb6Tlq%On@6q~gCfFa58byR>_U{b%Pc}WsvC1ZP z^!siP^XlU0j)1V2=|4rj9?|lO{-v6R&=ETw2g2lT@jNex9y~JlinfgTp!Bv|Lq5GXlHz_ADVv_*yjyqmSM#?t3vPvz*CE2*h#5&VBsA4fU=4 zxYPwcor#yB$?EnRdv{Idjf3{HfGiiXjG#O;U@$|CJCH4NkB&knr)>Qijgu6yz4s|) z#xDH#{WpA2?luk5uxh1S5!pna0z{VvcDU{fcAUKZhfc>}pIcky0Kv__{smp)`2N$oI<7xb$cyMkAUAIx4&6U=fGWz;+ z9QzkPJ)vgOPr2}YC{*f1I+UZY=FJ)Uyp*{qF%_5c4^v{N+II>NP*(eWAKE`@N>ARO zoEmvp^<@4c6_#NsMB(B?9kTHIPwe@hGi~Cqqd;J<86-*BlKCB#^$(o{pw9O= zN$tm3>{&I7EWgRaroq=Y=U90(%~47iL2DXVe3k#*$`uE zlMof8dDu6rY*aE|+69(KYTq(ZiRt0WZp`B{L9ZE=Q#aIZRteEBS%Gs1X3?{WAE2>g z)_odM&29T0AzBGQWB*iLy_vx0M7w{fN>?eujCN62WUG+RGY_DJA|x$}_t+5~F_nfK zGF)J}IiiZojtxDWf1o6mr8&c7o zNVO$F;^;V8jJ+7WENI1fak1!c!0t+A5Hu44xsx4Q-==j&RNjsev{%I%w|}Vfb`ZUp zeJ*Zgqo|f$lX`81oubPSCl?L+xv>JnCfAFgBMLHWoLIvgwrO$@VHd@_uMcl!Mg5IX zPRB-=p{?FTvqH*F*7FQPagd2oKqKQp-M;}T{RUyuT7=wwswW-3UcWEv)`$j%#QMpf zZ!|((0M&5Te1u)!V`Z2mv?sxm?#o#@6L?}pUZ+d4mA4PTEvjNXyb9|khD9t0x?M%1Us4F5cLDX7G>H4V{*W$=CqKLq^rF>0 ze%z7{L{`OD^tSHbY=s-&1>6X$uP`s7-3bC-H9mZp-&*~yp|qCBXxHI^LR{#B&>!w=s|F&5Drl8%p>;t?D{{B3I zNc{e+`OEvu?1Fp~j{nB~j^&s4v0)Yc2#);%eq=vixqr{@`{ulU^yd8ae)zxgpVj=o zsXxZ@VSe6UdtHCO`@ZL7e#iFwQ~PQ^&-RA6(ENYd<)vS?c3%ele_QOQ)-is+KKq1! z0bd#ef}MMcrV~$deM^2@KL({UZ@5429=}^rC;sWbpK7l@9=Akaw~N32{J&iO@A<7g z;9E&>Hrx!~K7UPh0Bio?zo6c~`@e5XQy!m$zh{a)w_n&;4}I>pFX<59YY5(u$9w!= zV~rjT7E#4mqkO-gb;aYYPVbURX}1Hvmp{K*h5im#O5az%AO1j!vXD?XY0uoN1i(ND z0O0?eLBY^~prD|D=(u2If&M=q>wlJqrGu@Rh=Zxu9|u!2TSi$cdow#DS1S`2MhORJ z4Z~|M!-`#ob~>Q_JCq0|{_jN0gGTCzK?vY+>jXD1at@00P_m4cz#L+Saul z&CeF#7rtyX1>J~oeZ9$1gpFV|dzT$tEZ27(jc1ox;iWbT(TWe+;H>r6Gjn8A(Eryw zbToaVdDq->Oyhx?L)Ur<3R2vtfO52n61orOx&qyfd+S^KpUIFg!eDRo*St_cQH{xw z^yKrAY2((vYy1}4#6J;7T&U|^dJpY$UhiM4B6#8pVski6R$ISp#4-5>Z@iHaa*)VG~Zw7Yy{uuM^-8o?RgrGpAhCO z&K5r$`Srz3jL?r9rJ#UF2sb*h_9t!_51hF0Di8I$4%a%&6H}+92Lh2F~+sx9MDMk z2OLjd9Gqi*1-5d2r?8X4j&k3FjNO*{*LXFsGTauZ*O*Y!e^Frpo@h5ex%>9){h&$~ zc>6b2+ioraT5jWK>c9W*&YSGhzRG$dvcNyY(Y$k^1fyB!J5U17w)p%JCbifA)kKX+!CJ@h%2S zs4pKCi1HgpsSV9kppc)uQ|W)tAA#%_rTwD>19JQG%3%ZKWQ!TqkNu+{u3YaTVmQyC zz3&N^8NajNe-4r4E*3e~@mn-|Z=nlJ@e}aWH-l?9->nU14=D0RKq0`=AQzZ+Rs9nK z8xXC%PDltu#xem}@(aJ}&tqFy>0B%0jYoi0wUqbtpAjD;%GVPB%uV0I7ou&{+~lvg za=yw}rHA&{P67Q7elV!svrf_QQO@m7`eWf6=Pz4(&o&}H@59jTsX)s>r9Y573Vk)p z$wnFTWsIZa{ax&47^a7DHP8M#W%n($J|nmBbClBk!Qp2VqMHoYad_|Ft3L1S8NfT? zf4x{&tGt;51p-pR1o|Jm;Qt@JP&Tu3a5eic7t;3bX3j2V|EC-$nmP`b691K>o`W$m zWTy7jn0FAb5>bt?LiM6qus<;LZFn7TOIIG?XR(UOB&|Yc2}+~H*Mxa{4cMDzx;~$> z&(y@t#dJyw3*k=DJnA#KNxG;HhK+veh7CS{as^649w6pOKETC<= zxH-e(orP?wV)|%@A6M~>bqnl`HHWj zkClSp2fLovTEJmrqREZNCp^bY_pyX$rK?f8rec^|Pb`oEE44Cg}n zFg|XUgSb$2676cXr`R+!z&kyT8k|90dccSvbL#_oINN`y#-|PlT%9c7xBnVP!@SDW z=e0v}M(}7cmr2Op}a0=>Y`>S0j zS5}dSIlVf4MRX48gJ+8;h4vCS`~#r!K5M^S>ZD`5>A5DQ_@dBC_txNe;@t8P{pFLD z^&y}?0^3Y}lRi^|9*KWOPpgxRenXcZw_Kw0CmWS~FiTnX+v~Q5HBmt_<9Rq0vtE+L=JNE^x8?bLDo$%y}eNe`9N&(EER7^{V>fVXw zJ6erVat*`t6h6H~30dsN_TT6;94u}*LrXy3v~-3XvFugr2L1FfGO_$Tqg}>Vamt;d zPzx%C3^TU$3<;qz`gDNyW0vk8 zn9hvndG^# zb`R_G&O~SaSNH+*n*QBh96;_ld#P|T-#sBc`mgK*nZQxqx$0rHWhVav`aw(+& z=f-*>#LoKBF&L`{dO&@U@OxRB^UlZ-eXrmT{9ke8EeGEq!GM5xaQ`Q9{^x}9|L=_U zjzh5olK-ti;P_OoDbpvkSgXRN=nAAp)$+@`nC-RWz&@z)=fj$ZxluzyF`6kQWK}WK z(5$!M>FZXm(f#q15h`vM(^N5AX4bH~9H|_}1&hq8%42??e-q#1lx@=O>ZpJ=M!bp& zSL=~f=SIe;3D#di*tayBPXVU}OU%$ugQcNmSGX~vJO`;cwt{G~{H%EKh91KB*Uz3F z3-_$QW6MrC%*}dg9fHG34^P_Sho3*1S~DA_b~Qy@d0Em~A!Uh}S|4cgGvQpCd>1;^ zICRWvdbB=qg);51$*vtWw8B0IBPwQ{s4bf9(Qd)4ucK zh<6~OE8Yq}mX5gbbJa9}UNN*1j;q*X9?pUXN(X&j{}CW(1?Q zB;+xBR8^aFcMG)XwNoul!)VYdRvE=uB;R{;XoXe#atvgCMe2#oL+;iu3D6%dB#!u* z+*k|mS4G)?!!uT??O;`yUBN5xTiloPu8f@hy07OJ3#6Z$Ubr;+g6I5E4bjr8y*Y#$ zUM@+GqdZ$Ka3Bs$KK{YRN@F?&X>gP{RPRkM*J~#ophaAZ5^oPGLQ~wHxOFB1w8@MG z_j7Z6F{JFRC?mB!cI`d!F5T3kN2dZ9!LQCe`~v_Mga;lXjGVa2_8g`A-tm>_Y_84% zg`oF87xtn8#%;t!(mq8S`m||ORt7MOi7#Ss!;j_Nl!Svmbpt+kOd}ccHq_)q`_{mv zJ9xJ%aeX?K3hZ|(ecM#BPLfZlbR+26Qnig}fFrt4jwLjR{Yr!jB_-ixtH6=m9I3iV zWrDou!_#AO2YXycB}KG@!uj*71HFPindCuj@NBBEPp>B=b75fazI#kI1Fgq%aP#wv zu0zQhtR%ajcA6~>Y(YV9AzoNWX2fK6glujOWE2WdMcts|AA#^fp&dJnQ=``44{OyX zx-}4B34b7nhU-+}opeWzA@58Cc=AlFsb_vK6lZ9K>hEAOObu#+? zGH({&V0mw?q*l1cuT~gsB7K@VWbErkZ!G{=+_Q}$S<6B^W**Q-CfvOn;+K>vpJ`~Mu zcwYg!JEKR;qI?^J^&r{0na$r_2=6xF9>jU?fc6wg@OZhe%c#(u01rqAzUj4#v#K_| zjhn(>9oX&AB|fS$`}c&o9_=*B;bnfB-29hNR;DLx|ManMeG0$B>k+c_lVE{ke(kC= zU$$kLGfDt+vx=ac+aB@FE7L#J8BjqIB>m}^Z*7*ArvXJ;%L|Esz}z=vXt47O0>`Ui zg|~D#B6Lui3HG~|MSd8#>v=@%`6VjHC00VOmqtzF-n!X$Ypve)l&6Y<(k%xv2={%- z5u~qev#7-Lv&lZY55^wZb1!H=>WI;9 z_4#@DufW__;({?8MG|MGimVckmr4g^F__doGV{(tf-V`SoBY-MEc^8f7q?@GAEg#_3$5N2Ye zH=N)T!w)8Z#6w%+(>5I?aDi+`NUyJBBs zu$j6+b&VnIbMAd$3=CNe9~K&sbe)9O?@LiF`}4xJZ!g=&{#2aJEF^)tW=F0=kj&}j zZBgvfYgaY?@SRS?D2Gg7_Cd~ARbBjt%CB24XvJiU4abCf)g{(AyC1D1S*usyBiWF@ z1BOF@;dc)r^!oWXeJo%M1(0-3uOZ#d%n_*Fy!*Nw=8IZ$c-ggE*K)SZQ=AQSr!Jn5 zYNTHxARk;6fk=2B(yt*XIB0H-+5B>!KQ93b)PO!H3cJV$?d|<;%iB@)FqmKjC1Wz` zDv&MlxS<_(;#(&FkiJP0#;+Qje`BS%m5G&8C{CFXjM3SpvfQ7n-=YV%?EOrjyhZZv zSl;&b=F)!?@x%8jpXku^3_B}*B!i*XXHU)yMc8!KzvNiv88gQ<#VxOlG71M9vcv^CIDM&F>6FYFa??_&ntNbhzn;ZomoTh`)1X<0Atd#Z57~)1{~``CBVy()TMd9IazLx zkZGRU+7t~OtAiQF(PwbvnObP#1kX`!41)u=ANa`*3V2qAqgI9`!f%vU%fNJ-o5tD{ z51659695WKXJgzmhu0rrl_>m!7)_KaN;O}N2k*!iI$l1=P16~6{8w@3Xxm@u{tb5< zF`g6Z_tgvZ=~5$@*^zOW|KvvLfacDqB-PsRzwa6Q^8+v2y+R!L$9~;r=Gi!TNd5fs z^nZ67h`Ts4s0hz(7Z19vH_2B8I^AAhw{Fi3eBZMD;3qE$-}k{y5>MnuKOQ?IQoOgp zpz~aDinztQ^tRKVi9Xc*I^6vj?~#{TbP2}#*$1ig0n4LnpJ-u8Zf#ZoyVhI&mTrc4 zc$mXH<5=fk461kLITu}G7rz-TY#oO4kmEi4F<5^#=!ib`|N7rQl(gBIC3gN(5Y_+3 zf=Ky4c_HTDD)Zl{ChzutiLn(|%!TB)S66?Yj!lhZz_hPEF7;Ti9ox7l)Ab2V#%xsv zZ5p6k_G{;F)MqsXu|&L+1x&t`Te6~h;OxuoR;7D?ykwMHluI{BHYXCzwJySY=ozIRY{F39MLr7K;b`f zm|9~r!~NYmz@GsUBMlK^-R5KV_V#n&?WlMdOml*hX^OdbWzqjbDT|%H6uCJ;XdMN1 zs>pclDesT=W@(O^FF?ytXnBeYJfq+(#)?$&{J$u7#~{nrZd*5P+qP9{+gWMbwry0} zwr!i0cBO6Gx>dFIzGr{uo>(XDzcFWwh!Hbpds=V3_jmlnO>7o<-I0a=x;fI@(Eo5h zNh8`a8CS(=kfl;@ym+OR;RnFf4Um;J7tp;6(Cz>XS~VO&^fJ1`y2r%7k=nV$m6Hda zw9K{K!Ftye!35L4+JJZ@16m;C;DH1R=22bV8`r0A&wMfqw5wR2SgI}!WrTOW*|vgM@1y?uD;jH{AliAQ}iRAWq$ zK&GhDSNwqJ7Wvz^C=hhL0OzgC1w0f8=(8G+d49(Vehr+jkk-by?|NoQJL=n&s~5Nw z+dCDLK;3(uo#@~*Jzw{F0B1@utZr=IkKn9}K1atQ{eJ29C{0u0ZS_4|_o`yP3$wTC zer_F!w4d+2%Dz}AI#c)cp3r%!04a|K42c_Ki25~HEVqyYpb{&)=o%hFi-FKVzXpBU zdarL))UDNR%eZBlecd#p+tV;p{N|F)gMFdg&vH#p+1U0=K;?@OcS5sj0Ia1 z__M+-h(+$7FLZ5xedh|cn*I^^9D@GY{G1uw;T65NOz;QykA%f$9VL9u))J>{J0b7_ z3Jt$J#Bz5G-1UqCA#ZMd4&A}V@-UG&eU6%q{pv<%JctW4XYkF6r)a6K~39*|At%h`my` zmGl(!5ve-&b1oir2Co4UwJfLu{uOM#rR$q#5bChD6fcSfVZQVa)@B=9-c2-rI2z@_ zRF$@F>NYYjM^+7SyMeaqJUEP2gvMe6(7-$pc5mDH^!%F6Vj-!n51Nl?Z}Fad_4zFh zNwAq&EL7fbpOH_ydp5D*jsiZXiDg*bd_Q`Ccwt2yV;Wsn)GlFYa5gqlAapfXuDxKrHT>uC^{N4!5`yX9tGnD87nax++VjlBFl4Z-Z}Q6_DhuhOeg# zP;l=A3f*}1d#8vc;d{zYnJws{8l*J0Ie2TY_&)Q|ydPkHF!a&Oc%=UwCbZ!H4MV1X z!BEK9#>v6f+(_T*FO0UGVWvCQU0uP;U%(DlJN!h#5I zfg=fo<;9+L#uhK!IyY=Csw`8KIg6wBBKurB4qQ^gcXyUWuTi2Ol({pCDG=4scJgW1 zMVl(e!0~oEXmq$!ix$bGYBw#F&tRIbVd=*X>eoO%pNVutT0dQJRXa_;N>KbpaNkMh z3DMKk)GO3DtamSuzE|%C$MQLICrtaesI&lXCn;+!NT?qmP8q6)Z*Va=Y|Hufgz8a2 zX^1{USI*)@+XUg~w$1x+9p5~!uzC@WkL^kTNoEYYvEr6AoWzs=&dsv7%E1T-LbU52 zseNHDW;SuLyp(8!W_TEYhhi7A>_AO7>q6$*##c6tZ%@8pXT!5OM@eO4&UM@hsaoPX z&MsYJAYl;mN4W_?8Z(BI%eh3ZnSD$kUqXQ@YBVj z26sQCP(wT)vrG(COvA5cYccODNI>9ZNrR~$N<|lKtm~{?lSCLNww6DES*xjZ?ks>a z2ti8^Mp_S#E!FQ%)IMIHnx5b-<+_@mMeT*OA5|#sYHxGCk#sU zjopEuwcf{qPB?)Suw><4fLrPD*-fVt>IMU!TR#F1pU1ZCFZg_iHvl~A;XNY*IB<>1 zEq`w(#rXX{4F@%ttg7nulUV8IY~i4iA+N#W>MHhmXuPK*`rZL$h8t(*(Hq14aP|SB z=AO%Gvc@X#eI9^#9@y|6?-z-{1W;hcwNYRd$q-ttUm{>=YFu!sa~^JVdGoeS8%qjj{{y zpMD9WvUDtvDN`j^_Bi1Exyca8fHQW{^vffBU*R#|66DrszWvItj3;Q116QY2IyXEX?*0ytzktC+XB^?o2=P7M*q5be2-P;HpLK^@yKhvG5>^wHJ?NV zI1#;#UsO3|=m*4%BG#0y)2vm&Q0a+fas^6zSkuoRL-}VQd*SY_Fy9{xQIqpkzjWgO zV#%K+SEV`R5{lYj4stCvKQJPU+2u}iCcQYbKaMA=fv>B^8EW$LCx8-zoztxNw&P&0 z4)2Ji$xIp10AGQO4Z%>F08@u2ehstg#MIc(9y-gX6Gilz17pgO@40cRhn1$w?rVG| zC6F-upqcql??N2zW@N4td*oL1$Y!noY{FEE0jY#?(CR)b>`CL}maavK`$MvW_*>)GzM>n5U_4!L>4C0`(adJy$s2_@G3wP|Z^r zUgVnLsMkmEdXn8f+w#}A=#vwuH;wP|=6LL^@vMe)jh0wcp%?&nICAax*1dnnN*^hN z-<+K=wx!DaCZsaKT-bq1|DkVI(!+e<~`gT zdj9?K6Sux+3{%Q3hiCpL*T_AJhw(E1Eyxz3y9?^AEPWSXzwlvwVM8isEvSxZo)3mc ziO?6qw;I-aZzlAy=`KW$_?!-DZ0Yc^>Cxaj$No2oeCh=LR*>)3`=*K;zkdV9&xZP> z5@l^&t^Vg0iTv?3k~*|C4JrPSCs82zxFr)56A7pT^;?p$+7Paq8`NQ2&5C{0HRtw9Gk)FN!-?7U_aMU>+kCVVz;Ts6_oO|29^l0 zEc)`^t0;Ucg}-5r+xz&cpOMOunE`Yt_!=GQo$&u?uGe37zNiE_#U0dZ0Uy0E@4KOy z(3&&r`wWEO4NYQ579o|51LR5sTx6PoQ|;KoQs>TO7EzQ}KDB^Uz}}2S3#0B|E zoHf${ehG%vo-9q6%Pq77Hb<{*LrLSjlZGocZ!n3VtcRZ5Gb!O}B(xX4t@n%`3tYLc zSI|Fhgd1;R#rV5vNW}d&H)8x3Hxe^;`r|}`=K6no2T@xGL*sw^NY&bQmmT5Lr>9@C z=UkFxIXo*RqIS+_8J=8L!~DvJA4>MrT6}r1)5`ZFDvKQR)(Tr&dw;ejBEy4A0?!nUH2(Y)qX<9rAZHx)d~zeIn1q zx&ts-1SHio)&Sd{vYeoCJ6#vz9AeSBgDlu?)=YWntJO#+Az14y$Bi0a*Yy*gp@rWhOFv49rI z7;$GsHk=ss&3kalo4!;BK!oL^ZR#)R?GJpi=7C4Z5C+Toy{KQAu>v)%w1v*MkMV7s zT=0FdX}PNP==>_CS{m9FHcuA3EpIqersD^|*X@^$4&TWx58OZj3gR@ZL9sGw$(>#f z(}s5aVh{#qF~m9+Wmwd3^R*7W1AG1KW|UlTeHh z6?Vh8oQ>M{`S}9T19%j^2A-XYH&5xZz>*;v>mNjZ2}>lmnZJhcODr3!*frvUEz$OO zh;erg%Mi-$hCCY3DF6@BeikY5l&A$KU6!ha59B@1?U8z@koiDJqn4rU`^m#tG$V^3 zolY67CC3+hP<1IRlKVT=b-;5l1(Tbq1)3PM)%skYnfDBhh={7Ke@ z{vbClxN2UH!cl3u>#rIfREPiJcd=H|+ggeRXa6U!OvM5v-dQR*-gi~L7*+Cqc)Wb<-FoV4`V>58S9?+?x~sj= zV3V5VqBB^k<50|D8yA|L{9ApI!%CXH3Aj5$-w`US44o24m}l&X;%cO2Uw>ZGK%9_Sii3PATp1w)n}Wn$pGjWryb+bEj}$-)Ru z+rp60iNoSj2zA8UI_oPZO$=>t8W6&bkp*egI$hdUi@AIF_QeAUYVT?AVvtboSYYjS z_F)PXB6hQb-O@!H-b~CERun3|Ve2IOf~(YZCXT9*D@RObnFbFAsE{g6ztrsjjG$Ty zIrnJ}qzp03L@HW0a3YLZ_HI+6m-go;r_68xbSd*YBcbDh*?$ynuQ_rOTrVy`Llo!d zx`*}jVaNasi2|gW31SJ%?Coq+tw^Kw>)FFdW`%vjQy+C>F}3HwE9+V>C&0-s^`DPA zh4;djfjM`PW`*|Gs9GN|C!M=v?s^~E+TkRAy=!F6S39@^E*fn$%5OT8 z9}@t;&*_(a3fIRk50pm*3R?Yb2%EjvR5Rq8yr+2SAuzeyqmVlhfyT&d)sXN+SU*?;zneaLyLKnq8<_5I~nZtxA!48ynRqMs0 zc`LT8KNGoMqvR-TB(Jf?`T+QIgK);LC_c58dsd8WB&fu+q739HvjXWBV5CTo6xq@) z1Z5l63poj91C110{q)jw+&1Ck_D$vmd#L(U2ilmo{GIj1?%-+5^u>D(2Iq?u<{64W zf`$4vmArzgAjPilB!>tElKYrVmUuxqLsLWsXCy=wcjprrTdRdvq?3yihRcb;C6KRS z_ea>TSc-P)!GVY*dVS#;-=XwtvKE;|^!1%=Sx9Bzi}}T-X?qm+#qgsG%6u2djQ5cm z+mArs);+nNzg1?se5Gu>t zW-uW5Y}M4Rr>H>b0mDgvDyHwM!Lz?@3Ou@|x#8<-sU%!-G2-m7XK7XseYG@xen-ppL zRZHRYp>8C@)z>lYkfRp>kscftj3E$EEOV`KHraLLtbOF-Ppy3N5`+Lx^hEdcCdo3L zf^*`<`*g0EIZR3=tW4S(2Rl-_D9L*VLSJF^z%8BCtrSsJQ_zgsdW~yqlpQ0B5K~hx z6R?)ECVhka22TkPMM_go}ZRf8%N9hAZwQ3uP@80)Ch zY<~HCZFLHJ;W~M)Uv(PY6zW3Q;4_2R_XOKt0tfG7k8~goontub~jq55R zevPbWCQ-wzTC^ie83=^o4#)15i}YOz*A9*rK>yKg4usWy8SoY~qt-Hymq&I7!wYaz zo?*+64}!r5;{F8Ub&}@i(Mmo2D@Fn}Bian7sny_X9OAf|gYmF}2at{)LI4_QgFKf0 zc_7Opyny)07J_Tr;_GQ=(bWSXjOVIF_ma?E=u@N0yrgHdX zN!ZqkMX|}a=vGk_Q}hN`gDKoJi=Ib5R81pn>kHSEN{@myikHc4q`g*IFlaGrlA%QFVcKX!IsZSdL!S90ed>@`v>_#(^cB!*BV$tv``2s-%y=I^oIWnz;P|~jYF#sCluebe!-B@<*6anmEj+*y` zI#)qie7Dnj=&Ot*U|hFT%Q7*w&@2|QM5&j?0D^1aWf!)Bb{-F=#o7ptS#uuUDyJ}I z*wv})Yf&nW2-oI00kYFx3O#(m1b8opI4Eo7JIA57veDfrRSsjFJKv6(c}ha|g9k1=vfcR4!Hb1$ z^N|W;v!?}H9GM5!w7YvvM|X>J|4KZ5J;_? z%Pi3U%KPn^o$KVI8_{gUX*_9y;Q>-qI@w~#IBN$#Mz<4W>&U#LLViTmBx{G_(OkHo zxX*0Tt&6ob;#tCrt0fQDbi=f1nn3_$)-Kv00+IhG>wu*ptE<3_bJmtf_nb2Vk|0p& zM#=gGXo}nt(r@dAUsud5`BvVFfSD}G6sb|Lh&+C+fO0Uu?ZKlC(9)K@2_>%2MYd?+ zEE(WYNyCb1<7*8)Nw>>~3eJ;UE6n~=;X0~?(rT9Yk^{VnQql$v&UV{zYKn{0uTvDg zzADj%X&puM?gKUpp>>@djNwOs3g#yiuZCY(U^t~ltPjcY%WKDlnt9@*nsQ%Z3F5x_ z_oI^tW$Wx!wigpZc0Dz6&XN26aCD8iXOiNFDnDT`>x)a zn#3gbeFNWV7hnrMHq`dL91Q9_M;|xnGrDj~NaHJFX4hgmmm%iMY-3KM#Df&7+i_qFtKV)M*3%Jn5yH)ZxZur6!5+Z&#hxZ&Sl(^sp02J!P;$oH+zddnv zAtbeIrnE?b$hl(Q`gp&45yyLk72_(`AQOoQKQj~-A(SFJMe+50-5q=;lv>q};#4_x zju{ca#g?VNR~~{5&zwmC5S`4wOF$Hm?8EnZ?B;IErD0Zv zqoK@jqVJ}@yQr=(S3ZfP5sum!8Nq4c;kfamxq@D7@=jpR#?I0fTKzXyJco^#{Mm&HyZIvz(7(iX?^Siv57 z^{H*k)_`P_;OlJPlb5R1D(rjs?!yXcwP?}4H1J!Vn>bFS!7k;U`Z)Kbn(|4OX57b! z{ZF=psWv>>-Eo2BwnhC)|=(3n#imv-D?id+u z&X_V)Bg!HI`A1L_Lr$#MUrUVK&oh=FzbUQCKYzw^C0;B(BwN*`-^M5qE z@~@i3`VY;j>pR%}la2L_{>cvi(V9MKYAw^%hVmHq`dQ;|57rkbcT216R_gLe*3A_{ z&Vf#b(D{qR6-%7rXgJ)~mSJijZ_YPM)ETZ~#F@;ZHI^y7f2@%kM&Q>M>Z+RM2CD^( zFE|CxR9QwQ2dPK_l1<+m(#IEnBOMrVNie`(p@@{<)&s#z=N*zFZ1)_;3hBe)Za7Ff zSZ%fzIG#Q588EwZ8=DQ^TUKzjPgW`|j4Wz3#}1IEcY708;5L2Pm9Ge?My1vbtifoF z{bs(Jzsw=PUH`KK<%v&~gB<)3pB9w;@ESsq5$n@bEm9*7PKr|%hX^<57rey+C)GEiZ2-MWWO5@F!NmA9QVBtBy;sXEcaf0h_l#AY!gM zfjPi?O|Yk1P)88^oM66fsfOr!pBLig&R1y1-Usmd9`HJ#8v16nI5Zzvt2S+~8{**& z++Bvk$8i1=VcVR}j_f+JXE5G}xIr^+O{*&VC!m}Exyo`3H*F_^9&knSoEM^B^jC7V zw=uSFmq3`(qCe331geAGwm=#6AuKhG}V z&0OJoptYD&e*(IsT-%+>9Vl^}%OnkmSZ{Zq2Oy-jlJvi&k@fwcxoL3b9VrnUa!w zSdZ_UFxoRC)T(wgXIwdKDhS-AMf)yBljJWs z?!gKobv{@zru~R0+PF0!>E~!w=XAWNUVL40nXt93HQ`(2j~WdC9BQ{B2EwIaGw}qo zlF-&YoKrG&=m)D^*q6u#VliNT)zLzW290DwI%LwJ$pXDko+J|~pKkZ0yh`Ez>D zQ%02eY=wJ=?s{C^3Js)eV}g5$WqG|L`PkdaC?M?-bXF?RTq zVE%i5@mukq-Mad1x*BDW61Bi(5J|;lIjJmFYw!?*kUB#BILKzcA5&A%HHJ}o){yZgWljSL1SB+%|yZ_h_D-~};Pp@E%Yv+qvkJ%tusi z^TWx6_H@PfR4~wuz`6l*pF?tg0*WKI_3vzn@q+BclYn(Az@YViqCD_Q)^?t8v zw^GhgX+Yg;TfQ>;k+L(!Mi0(>I%sTv7Yt1)^IM%^p*f#_XFn63{d4NT000+A|AsI6f8c9oYh`5Yz%Ri6 zUqLPUH=W*Bzw1$O6052MA%%Vs?|ryr(y9;t?`pIpQECX$p}SQV-e4rqXlA|$x>H9! zpf!~yjl_2@72*=a)>w^np2{j(sIiDy6#?S=^*EZk8|uD(4z(~RUD-#%^ugdTj#Th1 zZ%D(>!l3<9psAqnL+uLLiWoZ>@3s$LxHKK4CU|**rovjYAuIJ8Jt%h51zWaeH;35rr!@jF>T~o>RcFl z_2a(xO;^IzYaY5-QKa+6p|$sGx%({;%`VgyA`dcQ<(ob$c%R)_utNn*bo1DDd9vNs z{n+)Drl1O>$mfuMrO$OX_t!P_AMrE2kKVNYu3a_%8pu%oL;S`L4z>>ey*+dINBL%n zDMnzrM&n?n3~47qImgnbt3G~!m*7g$J-P9{YV2W7qERdtZ)K%ygrMM!85#most%vs97+M`-d!+2is9pd z$K=YPV>fJFl+{8>7#u^uMFZ0yG-2{na?^^{M3m*>(7J=wTC?63=e|$I_4$n&0c1e0 zg4~T6yBMQfJc6nFFawoH9A7Wp_vnyq# zTAr_(OkgzRXYqUmS>$e(IEv@T zy4KCZYpZPcSKhyw(tra}`xid=<10vJ6$to51GEBrR+fUmd=N&W05^tc)Vv zV;+QrW(?dck0h`z(;X<6KFq-r>N^!x0#s;J z^QcZ=lKgB`3w@2>pHNOuq1;l0c+AQ^5RTBGv;5$zL7qcaM>R{c*xwxZ9-Hc)ism7m zceNnTWx5htX1H!1LEs^{%+9Z19sobH08QDJyKv9hoX}?2tH*8f9r9cadyX2nqPp=Y zm9IoSc3cY#ukwz7?ENy9w$#yKS}lpYvH+aU9i6z;A?@u~;uT2{I#jCkH1pDy4w_P9 z?xZp76K_F&8S?6jkmL>sZ|T3invdq}1o`WPmk5^?h!+$-TAzN#cN66H#fwC$v!)m; zB3DnSm_ulcz9EhIwHo(Hs#Fr9QTd6Qay9OU$~s=+Ib8nATuN3lS`zi>u=i0Bx~I$R zSekg5w`AY49ES1k)3#pt__fsKvl?~ZfK}f@zEOhzkdJHt1}uqsGd#XKn8l`3nq8_p$r&R26gW-3wvyI_* za~qfc(}{S=Ur1_jGeUB7-*ZpEf3g}k%rbr9Qa<1fU^X#e1)gt3p615QxgDfG4wc7gh=_i5Mn8`WifHU1Q zrP}B((;>hJO78fx_=e1yO6Br+R%dw6Qk9d)aZl}TVvn02Z$6{u?>9Zp6C9ci-%<7Ooj4`F9k*D1DX@(0p#!qj= zFZMF1dh-G_+(J9D-&JjeN4>m!v5V=jAP3v}rJ*w*Xecf>vj-3Kn)esNnd)_c zX}_z@XMe$-Z`mOKl~hGZMWECAJUfbH3Xn@U z_qcNzx|W{+T#;)@ozqR6!f}VgE#F#jz7YMW!&AYhvTA)x3Ge;n(DsJBTsSVcyinIe>vIE;jcVt5r!cVnQ)A=K z_hMF@as8RBSD|lqxwBRFzLF(M~EkIV*`+r$})Sc?SI z4I1^hb;aGnR`WD!IM%$XTOeKHeh}fmAc}5xSs-=BI=G*(XG{)ny1CFggtk|o`Dq$D zw9&dbzaJGv2ww3DGk>t3GH@^>RhU7a-Yv8t0EBupC5b*T&n#7Mr zn#O)Er28Fkzzqv|@Vv)mA)cAivmAaq&V@bR)4|*giE&GLTTl+9hiBk?*-ap4!M9MD zOd`K4*=M0(A98+ol+&O~J-%@wNg#{4O|b)Ea+XZkP;#f`sO}m$v#&vN7D&%ycYd60 zRv6bgU_cAv#7FkuFfCj-ksgeWCv%Gd*~=_SHYefUX?uWAOrJ?=+%@ilR+4*-2~*`w z3b1W&daYf1F6*yX?Q7>%2ql{9J7LcsJi|jc>6MX?RgO8YcH@e5!(T*J6PsDkVT*%W zr38HYo%8YP{ixBKSsWG$rkUh6MkYK%+=(Tm+7Kl@QSKH#>?S;~65LN$ZWtnTdc6kj zn7kpMK8B^^Wc^KQkS&x}WvL$Q_j}5jJw0!QwpdKA(!I{~Z;r5@9VROtq$~(7w=!6@ zrWZn>IdL9Kd~%Cd^=!*wqbtHyn;5?G$n;WbM}6JM&*0xhaD884|G<=6Nm~o~8z!=U zg$e&ZVX_tdd-BrI_RqO+r+?Nhiz%wMzsr>0)*Ceh7zI+V#zMWqxWEr0IXVOG&Zn?T{>r$n)L1#2=gqkwHq*P8%C9G+^jQD0lnY5+_)v>`|D{2Mby7XQuU3C zVeOiuP2#PU{{pep|E97x4ihqiN;}4W3Fgnk`2&rx+J}x<)^*i45ynk=Ct12J)7UDH zmdL#Eu>)7AEzCrko6^^sdu`Ty1E81MO-V^&^bX-DZrjSy8dmzb>=rCjf}R5IhP<=@ zlHV%$DmQ#3k<5daw*@sTJl>K;g5SKKVVIa0H^v}cX)i8wG|;K9H?(qjjrZF)De&ao z?4T_uN_kUK{fqjFm5jf}+U8E<{>np=gWa90mTGZ3oa4Z_F(ST%%oNChc1O7}jBwZ} zp^K%jer(Du0r|;`XW5Jvi@h<~guf@%?Ixjn2bnH(hsY*neF3`X70}Asksdxyea&pe zoTa~O#4ltoJOAzJz73+#ZAkfj%boZTx00XHI_Il-w7H50e(cE<|zq&|ho|Fm`xl6JRq@6g4a+o*W)AN9&Ev~Wq_j7B>t zG(QzQmrss4Q4Wr();t)H1^5@B)#PH&7Wcqj5qwCfL(qmhBnx==7bl7V!D$~ur`mc@ zKf*9KPBc?xGc}32;Tg-UwR1Rf^dL4i8lfO-6f)UN&w8)Lnbsg!vd&twmBJgepay}o z(6Cog==ND7L{$x#?!3KC!;5=nM7SOsy6Z;4m|q)c70WA8FN3o!G$UafT^ zDo0i*L3Q_(Faznz;1i@q1k_{r0%FnvwUk8vKr1W(>B_3H8d0f71RHl$yO&UtFhZ3` ztm~8^QXWzLQ>{qZ_rgN(Ct$GnJN+rk8-Z0%*)ANeLB<2mAjLK1H@D2c;C)9J~p&u7!coM&NE%jc2h#0On|zL{)!0Jb@m=yGRe0oO_G}>@1YN z30@w`cYjU~1^D|Aa!_aTZH{u=nS4am2@Lz99w@=n&+%=#7KKeOo0B45_JL)|<`kj3 z(0keR9JVHw+s0kepU~Y#L`imM`L^4Cw)$+PvGD?lHAUG7@ek5Vmv8e$LW>I6k;$vuj=#n2W^Hw${ie9ij`X?V8*Jgjo@o<4JyY-tL`HLgPi>OgC)+Tf#$t=wb#@2dK8qUDLE7KOiRN@=AGP*Lv zj15Q9%l3JTC($OwD1=)RBdCu{cqxp?b*;>vDrb#A4U(Fo>IiL!IXV2|ek0Rm3H;-ah>eyIumKi?VZ0bvbl7FJx7n9Cpx*T z!O_X4ic!$uT=Tf()_~bp@cO@8@L`n7(x$d(4gzF*R! zc!}_mCY@W#WgPS}6pk@IJ(YRlHIXK;K9p&`$~AIhqIbWq<>dr{GV+7Qmeqh2jd2+y zeSdog11^^wNT3-5vZY$v{c_z=u2INga(E(yV=xo>7QVPc5X$b^H#Jc^^o6k{ZGZ;7 zLh9J0!PoQJ9}`yQP1O1r5#59g%A1~M361Op$lF`cCNK6fC#^3H%$*Ol-+x$L9=Pje zeeiJ=Y+z5BnyoD=M^m;Iv!e z;-_0Pq{2|$RJPUqkM06Y9awFkvLwv80H!u;V|rJ}3i%Ry-8(VusDg8VSsTdf^@r?f z@rr3+srO0TLQ09`r%we$@}FG{BW%#842)(^ni)%vt5KB1hg@(JVeSS77h*rNG-1sA z&WzdX(&W53O2#8CnKhp@Aik4Sf&kFq-eu~KsLOHE!jLm&pTnqTeVJ>!GCVm(>Ca%J zsSAw}@It-$uY$SHF(@?G73!^8N@~ch+t*_KeiG_pr`=j(lT5WoFb*zRo4f(11JURCMAtxCAy-nVak-diD*PE1KHw z!nj3=EXQo#i}ey^l4bHzPoXQ4w|uk60|tJ?I1h|^GQ^t z+M;ke2l^6ECP1gNFYX6MEWpXRS~|OnnIr#3U2^|5NlAJZuh4)otH3SttEik*xp4W% zKJv069?htOT1(9PBG6aSR)0Ys6B040JB=BHM^n*qR3agJedL}46EMjZJk>;1JjsK0 zLzgHQ2kaNiR8~y`}K8kqp<~z$gE$eoky&v;F{9N8v z;nL5@4;=}UN{YJt!3ZR3$=??*Fj~(*B&7lUd&Ce>Ty8OjGb><_-B730&d_c1r-`G< zzQyer_Pvcqa>=IUn*^%aaZQ0r?%=9gqgw7Q^J@gEc&D#cWw!z?g{ml}Ds$+Py4}^_ zC_l^Iv$bD&1n3J|nB8#R7ZD6gYJm-eZW|r%^cfyfRa+?FDnKi~TK_ zM~c-hFFVtSPbPb7x;3_&eZ+GXKb3X zAvA%|M4BMdn+PHgk&Zz+f&zj!3P=;AL{yaCq98?@bZJp|df)u-O>)6^|1X)zOlEd} zXE$YcXTNjK*G;Dtk3+f~SXTB&*|jz4xqG(Jo|}=(UmFNci%(phsMX`03Ly)(b$V}C zKTF%o>Sm(JmiqZ|Eny2+aqfj%Nu#|FT1VbTWP~{uBnqHHZMM=@WGEE$DrZ=3J zy^HQ~|Gw{6>rvHXcB@XRdQ$b7%fU%TmT*`!#X9SOVLwOpi!M{nmAT*JjDwicG}o96 zW&QFl!Al*prqR319GEC*X8yyoiCd##>gU7#MNAoOHIpW5m)0Y;AzU<5l?J zY11h%n8jNqL2gcZmoupsHnp~1XCMXo$tZvG(`|hjZ+=V2e& z6uS%ZJ+^8hu+k+kdA0>})ptYI7t0z_*0^EgK$Zr$ttIHM^~_*PF%B24;6^tZ_hmBg z(^FyEJ3S-veG@SdD247;AA_>|4l)a~>{*OQ`WomPRAy5tz#76g%U#w_Qzv8$m7oHEBB)I zF$>vq;|wlthc>gFq7b(0tDmWbpK{gGA(UMX2KVAyn%ky2jPQX>5gShud_@enOOd8S zk!v)2)iz_Fc+EXN_P(MSWfeE6MDLrvGJRJOjYaU<)u^O#vIS6tBrIjeXYySY@f?3c z&d8-&UbtG4B<3k6$&${~^B~1n5#j~s`*1SPq}*VQpDvx^Y%2|ef`Svd9iqA@y`jQn z*C>q(Q^RHUG8y4pknnQlb#w}i+Xy^@cbk0vd3Vyp339Y~r=8o#W#;AR z)JFloJ;Uc*a)7T^xnmdYw|fHzU(0n{@XA*FVY9Dw zICI0rbetu4>I*|E>xC983hdd8)xF`WgiCg?zL`rCC$M78QRp=sV4G@=d!9C!wfm_x zVoI?YCaxK@=*eb9zdY;3wtF#9iJE)k-l#yU zS-Q{mtYA(AtHAt0>`HXW;Z7&B(y#_faoSCh| z5j)>>9^dZ|EO!n*p==xQSbpP_16QzA!dL8Va*F{IhL^0JVF2ORZTu$(>`&Dgvfs`z zfL)E!?QY#FxDdCbCVu*X5@^^5X(FZ<4Z!E|rY0EXcI?}jj*^#7zrvAKK-8?|M^97$ z%cmsW4-{OKfnL4m7$_>K+BNWYP}s!CBiAbg0&Jy6At+fg>*7^@sR}MyL5L zCe59L%d|oHp)#~+puK4;uESc66&mChbiX1h(%E?#a4=fCA3cHCQK(H%-^{20Vx>dN z;Eo*Sx5KBho5%5`d$G4%7?UtHMymXF7jjOb{Hx>N4Pma~@dO#&=rrUY>(^q#~%d6n%{p;qO3*WBm zH6Vloz6sQCNod|aWB$D-aOfigONP|+@f>3t%mt2*ZRj_vZ^v>IMLd(A4RMc-kaKMo zUEZcE&o-hQ;)=?B*k_QtKtfDdaqo z(p+<`JoXy}7bQ;06w2)K@^A)7(=USiwJ9r&VIxzKW)lT4NTnRGcNppni!^SY#5CXi zXfHATahq*4wz$97jh``Z^I@CCndpat1FbDNq>c2`+zUHs_Q;E6 zCX$hRxY-%oX^}f;e7?%$G05^d-Awa&oCvG;PMx`YT*}5&Jk>mMEX&S4;jcM zY@MbQlPyZE-m+xmMBx`GX;|3~C{M>uI0UraC}WWS!sk7VIME&7|gS4FQ3Aj~oF3?86q0PQxwjVkeDYsKb}S5WYubr*7$K z#}8s??N3qgkIj5hUrpxdpr+|`hJzsz?5Cq0qw7+0Bv8NcHDkh60H(XMW7ie=hpXKUggFc9-wt-K^KVVP8*?#!#ZW68d#tQh?Ym7TjqYo?xl#w~ zEZ}5aPxB<&^dM_4R&`Sd!*BTHMvTY`n`M-x-i*xU6LuG6XG=tobTXWNX!unN=4_oN zqoHC2e_!;s(Vh5^*p7az=2`L<$rn`(F;n8N)vq4_<7AnXgp;@y0N2wu*FBStGd*}~ zSSMkntIDIN_qLyvbH7EhU+ASR)Jv4*!yLxhR=ExpX;S6D$quhB!3ta(8~&IDh?~@a z=BsUqS5|pJ7mE7apLMmz(Q#!D$=)~HGw0!&+qAV*9g4J;$ZZ7|tWZfFEc$SHWz z-Dp&B=|HvgDrt?c|(jiMi_U(>tuL|2U7Ft{#L$hGsVRQ?A! z4FT%lPU?G^2LCcoweyq}sQWqzPd&n$aVx<6eV-BZK(EgJ`f^6b znHq=Zt8P`bw=jtg6 z(P+#SnMTAva1*<^JkpXRcCv00+GSJ@8^YW}?$FrJ-noEb(s#*CK7ALKd9~-VLmBS5 zplj0ht!j>N8#^=-x4-rkmqAyiUgvHm_7t23my5Z-pq)RFP7za0GkFK(Ubo-NzNBPU zy2Pu(y_Iuk2)*VNy-7Ae;-J=u?hf;og@2WQ1!3%-%OJo5|kum{JasE zgozFd{R99Ah>-zki5M9J0&PEsym(byRxZi@EN+@s3}N%@4;LE=RG8vUdB zN0gV5!U+pVB#GeXjE{yN*+oQ(C#+MDBEnmk|5yB>ohGCTgyD8UB853C&_6C|Af*zf ziN%Ph4K}}`9u|`)WfMj|iGPRrcA)=9I+>J97|SF6(^xu!{%L%a6iS$BVk3e=oI$_H z_xIbQ${-xk=OSYC1cUyYM}`ze zIC4sS!WRt({n8RZN+P_1B>sdMqCkg^yBg{qqx`u9&yS}oH2`3m2Kw>t-%v{f1QY-O z00;mpI15W%OqciRA^-sTBme*w0001OWprU=VRT_HbZB*LVs2q+Y%XwaXYG1rQ(R5B z?cjsE1PC4^cnC1KO9+AB?jexikOU9z?k+)sy9al7_rZMzAAHWdb$`PBcIs5M)$ZL@ zd#z{n>fTjP*k=_5Tr5f~004mdK~Yv6(GUGsf#`^~Lboy-(P26&>bU>_czyp>q$GAc zDgb~E@Ih8e(=GEX%k#%;g{*_lc^KQO#~uB0yybA*7wXk`&i(~vWuT>F zntl9N1zC}eodrU(xNGC?(73z1AE0rEMjLl`cWInP8+RI)gS)%^%>Ab3 zpKoez-J4V@l~k=KYp=bMs-3($i~6I|GKyfA-TOWKqx8#Wo4C*Q!vjwJ(oK6qV?7XK zQ_3Gt(wB7-GS*tQ_?{d_j0{XhY3g-j^W6(Dc3`;@j+K_4=ER7r&`iojr577Oly_(lYJFw=BHkc~R=71BnyL+5+}?XYHQ?BU|d z0k+^qqHcFzI#51P5YK?OckxUMUZsNaJbI9QYdEbj1Rcm|B}C{y^ffSZq>1SvE69ok zH!|W>XF>D$e(TVOxtnf&XQv@4aujtC?~g~l0v0i+fkrcOvGa7lrY*z(MTL=(#ytQB zP-g#)u*;WP1tnbCzjWHa{XB^G)RgY!XQj1a?N!_i`+!Q|Y|1^TG^Tk}X3)tr3JYUm zEhEx^iW|h#vH~v#>ap^s_Fs-7+Yp#nNnVQFc5jTgcVMuaMA~0our!WqV#eeizdZdc z53_Y}wXVVjs8#ZpTJFit>lYMhf{+1j5a@zb`ih5~B*KqX%aRN(D)w7nFI%VDWAEC( z_u0Tp&IP}uU#7(}QQ*ooi0FcT;4LC{#9el-!g3K&1s9ez(R`jJv`BX^+NQsBV2z_# zePmNHe3z4|(fl#XUE7|mDg-^aA7^nHe6TxC0rzDd0RZ)yD?)%dCX{H3wrP6s09{B5 zfS%z-PaVFbo+3y{L0<92J~Rn_aAg=t13&Fy_a+=dos8mt;;f>$z1C@4)Fg!GZ~DoF z+J#968~8$nty=K|^b(LYDTC2ju8UJ=I+Gf5d$_xz-E2BcAdub+NRq?6E`Y90BgS5H zAlsBL&RN6|#gJ4Ce#N$%sXn!f{#swGO`q1<6<5SvNAcLnm05E)LVH#H`AioJx1)Vwq7 zb_8p+OMdZU&&hP%%zG37q@$p;*+i`mtTPJa|E~I$3)WOe3XUufiS0BnbZ8g(rge5% z3B?eiL)uNm>9l=z{WTuB+`{Y;r`TGaEm4AEO{A_wv;YmG2UQvp((aXGy!RmV7oZqJ zOZ42g?%gi7zN%X6(?hmu(jD+g(+r(LPeP~MT`HMN=P;D^5%c)RpyQS_nAwNkCgbWN zr|s*Dah-rPxblOQS`$|r&@ACIN$T7Ta5otTAY#Nx1?Z7E7PcAvsKiiY?I?O23?=G} zjlYJvav6EMZEW0s0ZJm9t@cjvPw9rFcu3vGY)P&Y@3o-L|dj35T$q^00idV4mq%FXK^$e7io$*^XX^iRkFJ+sIh+(T) zKbn4oxhH=Ie%o38J*T50IxE8Qs3D09)Ks{Pof6#pSV>yZdox?)EnDPPbHzA2_JnNQ znc#SI2k*y<1J!YddBh6$_k?zBw2Ym3!4=SYM=SIxWtz8!TQSi~=5KKlO=fg%JjQLT zk_u<5iU^3`9uZS&EJC+tq=u(eka7V1G8<%|lWMe+kRi~7vfBj%5O9OM=l)v~K-GbA ze|i)M8gnoi&lziq#j;%@OZgmGmtGO>qr^!8^l$aA(u^-7)#%<#%}zKijdLjq(Nm(d zLZfwEKA_C29aZ{`$+6jA@XVcgr+6ms*^RB6!|(tUiqf$>wHxq?`GzlQM=;EBl0N!p zxctlge38#5j&^4T2|sIb%B*fY=z~k5dF!S-G!uFmstGrBGCv7G#p~1QyicN0(E2h5 zH1@<$t$vB#+h+lRY}O(=83xxQX-67*o7xFBT@VeLhGaeBS2N!!a$_yC+%r^kugA^^9IG1^_0#x!nijnC`? zgOLIQ9BsIoGf}sf@cX#byaiS@9P1xNLC)Q)labdLZNq0ZMv*u*!dJ^xb}8lFVKQ9# zqozcna;xumdh9PBb!apmi99uQYq*-oioHtQms)&ZeIyIO!a{wvqmxMWYAFJ(4c4Gj z^GME@xcBgM=S)!RAZyI6@1@mpKuYOzYqmUj9h z_#h>E@l`)hzA_I&pR1T*1pnIvD1>&niWc_SNbN?h>8;~j-#eXQl%J1*C36$} zR>sq~;4yF~-#DX6tVq?fhgMuxUCunP*hg34Mmc?Nn8$F;EYe!1<;P0l%0P|c%&=^d ziRV)D^N__4|2Lj!>;|0a&DxU^QFIq zWK6XhP&WH!uPv4|RbEA*)6}sX^rU9`*IKj{f5}P6H1Oq~OmyFu=iq`3EHwF5o-YN$ z&Ta1^%#-)srZtM-`<|MBBVXN~kc|7(^p0S2&Lb=K>9VkUnqh4QVJ=_r%YOCtZXiBW z?l1TvZ>GLPmxhw-!?JH|eh*F*gKt+H9%EdK$3St@z-rX-O}ja>uyZ%uPnnZRKhOju zHTaKzP8#bW6fZi9hLE-my_z%P)u`DM#Q&59@Zs!wDOT?2VU+r$REU)rTQX_*HL!o` z8svez>;7CIo^a2NVV7jf$m5o8D*Z{S6Q5zcS6~BA895WIh|@k_tW`nfo>~%#om3Zted|3?4i>R{J>AYcOngZ1M;rzXx=1 zJfI-=@56^+-%zOcSGa!9vCxkTmI*687wsKq46^4fWRI#M*^>-J;XVm6vdN%sHX8R)jwAfrdPtWP&WoY&_fTR9LVCBdt?Z4;rPW8thTFyo zecdxrq;#O@(AQw2O|M;#az4$U`Eo%wYo0)awPmwBzesZ2L$WXFF@mx_`uslATJ)yV zSC}#FTW%*g4feG^;c$5v2sG~H*24}8+9?DC3Ofx zZ>gN+SA@MT7+DS*WYb^>h1!O>k`bZf2q9~^-Q=jHif{AJMf0V@-%5#|JaTmw_IoZ^ zqMliz=m_*VOb#J$oWCFO0JlO#%^T`u(5R_+c9Mp|a5YF{)|L9HJ#Ml)WC9Cd^(_%Gb9KO=E$~;Xb-al8x(lfJo&lJ`p!`XWm zt%R*PwsH-HHGSHM!f5c;@j$tNwMuMN;uPpk9B8Q78@PaeRl@S(T9!K&#A9CJCdYW( zsV?FOyNhMd>6Q1f=X2I=oLn^rotecGEIsGD05bBMwf=m^`zVncR$W9D^Q;=6TGFh^ z>p5kA5X}7hj2HHR$=Rl8)T(o>sl{}GJwgSmVe0cHMH?5@vEton z8CZJNVuDu+?9wl2n}YYEk5bd$CdYit4$+uR<+Ii_rFRji_6+azbuy0_;^nY*+)&UT zZ+ERP?~iiA<1h@SXb;47ZYXE9qx@NZ&;a*U#;EF|qQK4n_%XVV$Gx|H!>pe~^ngS% z2hvAYlj`*Pr+yCPLfEacM{yvO`QIMG9)Kb3pVua~N*!qPl8Vw}e&9q1^Q2ktRBkMo)elI_s< zBwg-HvzfIqn6uEu!1$cb(_<$<)a=~h$?L<+zXX1(C7jf*1R`Pge&tE?rs=s-zKyDA zlD>K!dVM7vEH%ZrmS0;>kt{GGf+ae=9JSY0)i>36x#pui8O2 zX~lG9)y`#|j`6<=k(94}6z6E?un;J&f%z4q0|H)N*H~U;QooV$9*AB-;IY{Y^;!Kf zPGI5Lw72?YY^LqE{V7s-ZZH_B)o@a;t3R!LFdgEhN_(>SEsbH`M0SDpJ!P`GMJu8O z_V!%VNMySct0H%L_|2x1m3}ted6CPNz>G!v9C}4&HL`7dv9J*Mbs;UH4+Md?%@KLG zU$qbuuJ33AcVw1LkbXUi$^&Y98AHSO24hulO^RPqxE6#D=B+UY)W>Bu`+a^I9> zpQ*^nv++Z6A%FX*49i_$-mwQ7zccV&oz&hPgdOe9M5Z-2r_m}Sz0^s15uwg$$awm) zxw`|-(m&N@EP!lc<%MbXPKV$)MIBmC=ZGCD_+sR#R*N zZ#cj)V3jT{XTVICqITM2T3h99z-OM`BmG_+H?u9DNsdMP% z^p4~*t-A8M>kN3ASSX@{U~!HGRW&Gu7Lw8@WXa1xk%?|a?%z+^gW5MbZ}ucRYG}m2 zKOKGdZJ(-dHMr*@=$Ymm30HxT{a#59?NJ0B)xgq z+)PB$_#Q;lk>qk}Wg)&nGr_1Wo@r_jG4^XN)o*<_+!Zhi!#YLvsXf{mk#s3`HsBFu z5vo>5>5FB){6T8AYHv}5;R8&}pPv*wf2i)}o9NYk^xBoCh1yV$)Q?89vVoBGnmqk% zR2N#zBk|rt7?oCELz>UIquT~^(Bq!sUkx3rrQ;m)yZL(?M0fTwKgP)}Vr>3yMJ!#A zCY6Nw*fK@db(-lp} zRDo9JrM;Vxd7M3kL8pn%6;{LA*X+i4Vfy8rH77?tl5dORxINN*p0>!;_#D06I)N$q zMUf4WG*oovl$^u zd8_X+=|fMhf)~jiS>2njdP5xrYJL3I-Ui*7`mzw8r2+f0MB!iyvxK3jBeUQL$hOlI z2c&+5d?S73-_k!7t&WREQ^MBYv~OB1xHDNo9qJUW~^Ru6E)y&43arc#) z&~WsaECHHa@x!cEa&jw#!Rp}H8z6s90<6RC^j>G7Zm$#`kvd9l<} ziR7yIX}PDbI!)Vc;k=gz-Do?*a+lN~#ey)~fH0yJ*v$Yn>McWGwRt$Jp{L~ncQ`@D z<5bDG3LJFkWboN;&MFQ7rZrp;IxOEC4F{7id3&zRHRbKE?LUJU2t;)mLlW-L}l zC+KPu7EOGXeWp%2zlxEYKwxA=&Bn6~aylnT` ziSS(FaNlNM%6a!VC7d6qujM6KrXUcA1?4XG$SR*d9jRZP1bog43|=X=xQFBWkz&#N z8zkFy$;?Q@!?}SX>;29(mcskL<0vdC%WrhIk!6I*m<6YW+|c%%%t`GC*}^x$GM6TAgw@T}Fl+Q|5?0 z;C8swLtgB zWF6#cQ*JAK-AP!mST{Ijn_dLW9%ry5PwbZjio0<#X6PRj2x^(eG)5!NMrrd8l53u7 z8=>A1hn4KH?if`Dr(Kr^B+5VWoIbx-Q!WZDp3Ws9OimsCp42o5z_3p$aM}A(bMEa- z?c`e3u68hZ?yWMYn|zFsyg6L!N*{8g4y_! zv4=%S%DpgFQl@4$&$Pmv6n2P$tHR*Sx5Ldh;W06GMqSVSw_MJ2Pyt;x4z7RSnc^Lmq}VS+ zKhkO`VcNwLtAp7orQl}tALa7RV{}>UzJz=M9LgP!)*!6FQ47u2g@Rxye~}VqHwiO{ zO_}~fI%?{Nhtxh~cCpidx-Hi$__?RfXJo3~0O#{0!4-<;W;W8o4o-}#G`JL6zH(){ z{wWPb74^{yRpBP#@1<^StWrOi78Bl%nY^WjUhbAN<~n(?vpQJER-x4XaStdvkT1tD||I9nrc zE#{vPxg*w8$@>^M?fZHcQLVQ@}sildq+qaABww3bg2+E7zBmP0D0yiBA#b3fPhlzainM_BC# zs^L;}q2&Rt)jz9Xe+=R1HI75S4YI7+(TCn@kUNuusr6!e7A*{!#0GmFwOJ5>X8S&aWOZ+W0;HumE3xf#xeUZR(WC(VK53 z!2CTD+eXYT4BUEl?)wOv$8>*kt11$x#+r`ETj30dJoySvE2pNyE|u;qc!f>Gco-mJ?h@IJ}Z|8;Be( zvLct#@SHMYe4RgaQ(M%dcedh}{V}qj0NenVz!uYgpAB;CNR80+5$Cp_(uqC=4PglO zzx?6F1g8mOJe+$TanOg&#>EZRDD&hlW8pb58uh7s35`Ko*#=vEEjExE>{Nd`%=r%1 zaEqt|;khdVnJh%q7&ZOGQhN7IP$Smh9pc$t z`V-MBmth_uGCnhg11!?zlUtkMQ~jeby+(O?Io3Wu^jGty0NFV`*z&Cei=fvGvM+8K zCAa?8k=nDeM=EkDLrl%hUn&xyTS^IsWhbjBpN|`ru6#X>D;+CzDUR#?e&`4VG%)Vg zv4@o)#+q1Z;c^NJ3T~`azX`1yrlE9Hbz-E9gXPm+W@O;6A=O~@RlSC8bqUO^%o=?Y z%A&|47ACHO;qM{w=g!y&jWTI08Gnr+k$E$Q-w4Z>;-Feoo?Kq{HFVup-vl-!aMIDy zHEwv9EueYj%~1DFA|DP-=IE4+y0#&1NJF0d5gC^6fUyBOLHr?53JwYJAm9`mMNGet zL8GZ9n8d>xA0Ll1==PNt7G4Vokn^$=P)3Pbs>&b4W)M5wzny;QhUS4M1 zo~nT+%Ql5syhWg@m75%g1S!L&-i0L)5fR@LjAO~yREZ}i)+Qa#=jG6=BkG?Zlv`Os zsN%5Oak&b(h%6fo=41Qxi$wNZF+osRD68dYZ#o@6sIKW z_cr^C9j4FlF+IV?=9m$JJ2po0*||WS6@kzCl5d;S!8HwpYDg)zUh&M&XILHPE1Tt>vtp7&xtm^+AuJ#VXzXIb_y@< zyt5Ef%jeMS1a>X&Fn`xnHffsV|Zr|CwNJk=j2f$mHq8k?m$T%f5*w zzN3Rrc#MQpeaf%n+xl{ZJ`zh{X7e*y>#7@6e#GdAX)1c5uI|HyK0Nf$#86AK9$NkUMsTv!-D$H*Yw+{3L^dQkP`)3@Gy zjkgR5wJ&muT_IrFYy(ttFmV{HMG4u8XIULH!C=_xy zxCr}WripHGaqI$0CNWj8W<8kbjB2KiHvTa*T zV)7Z?;=Wl`5TrYVi#CIa7s6cJ2M-UtVB|;wZ%AY^FfvLS>gsL5P^cq9mSBEOO5;5w z#;p_97G;BAI26a=85!iH+nh0CVyx%q1~=xY_$B}V$9=ahAmz2rzMu8z*BQ)N%+xxH zw}f@aOAHbof;S$L>t_L6+_b$;(;(|1hQs&Lmh`dY>pLu70f87b+9)*|5GER&mv1oX zg66kxik$51BxFB&cxu~6Z*nZVJK&$6Q?zcZqZH~a-O82`b_EGEpcAlQvfLIsit~>; z`E}ITSXr(6EteEpocN$+8GOYqK<8+$=Q)lE-Doa>E2s5p(L>|+a8w1AjMZf5 zaZOcKmC0C#3_!L$HXB2<_K7=Y*_g^C%+ayw=b0I0q6%1R2>$cO$8pByXW?p;qnjIG zKhoyz{s#I6_wUO*VOx1+_jIoTk=wn3Zrpi;&~Py$8%7v9M|0?Q0=b7)F`aJY4cw?Y zM~}z!ax}6(%XEjD)mmn)y^(;1G?G?=DwW6+l)U+f~g7IPm`w zDLQh&3rS*ezUIFzEv}+(L#I|O`|CuB!61qryr-pIN9N|RBPHAtA4|UT3kNSgAYc)@ zG^GPh^b-jvhWcGwr{vF{fvXk&m1`gz@bvVwP)$+v%>J40Sh*MJX z!^6kc{7$)g>)83ahBpJ+D=;y>!p9#*p^~MjvF%!3?G0>A(a3lrGAaE!Lnl|vZU!|{ z8m80g%~2e@rBS#A96V`Xe-I0I5THEI))qUfsz3t{#>OH=JG(0f9ibFoMzE(&EQSVS zEOre(#E&!wb|pP7mX4xE)eZ?Nr2HFo*1p2;JYVD^yHBpPh=u#GTYG@ zh-}c`zWZnuls^$dz1QpkW^yt*>JWTCt0cjK67tzO9#N6G{}U=CA$U+qSeQjgSZPh{ zk~N-QeDD0c+Em}Hi>HU$)&&rO2t7ew)AV7@uK1*k3x7QryCWJFfbty6??rSQgpgcTW{{%VZci0Yom`Q$E6aLfu zFHqLU?q47~_y0Fa3ww(-^#d{Uu~GgFmHpx6{}mI;003yx z!2!5`V|s%BTYmg!X8dO>y)Xi1+MxgdGWNezSN|aW)yfg;f5W%{jeut6whr$9&6Q)P zsBM-HqqL6;qyNp7Rwn>JN7TXoqa8p4RS!oq7rp-ms7c_-BK-iwegNSA2Eca#0RBqx z|C7@H?mfeYW-O5smZmoW8ZeUs{jWay%iaw5Z-I5Om9sK-Hgfh5advQbF>_{gc69l7 z)PIwo{nL$)oiPl||Mt<}#AyG?_|LoaAB?|(=|>0i|8>tQ%0hm01^@u}u}*yCMhQL4 H$I<@)u|y8l literal 0 HcmV?d00001 diff --git a/toolbox/WBToolboxLibrary_repository.mdl b/toolbox/WBToolboxLibrary_repository.mdl new file mode 100644 index 000000000..5bc9551fe --- /dev/null +++ b/toolbox/WBToolboxLibrary_repository.mdl @@ -0,0 +1,6100 @@ +Library { + Name "WBToolboxLibrary_repository" + Version 8.8 + SavedCharacterEncoding "US-ASCII" + LogicAnalyzerGraphicalSettings "" + LogicAnalyzerPlugin "on" + LogicAnalyzerSignalOrdering "" + DiagnosticSuppressor "on" + SuppressorTable "22 serialization::archive 11 0 3 0 0 0 11 0" + LibraryType "BlockLibrary" + ScopeRefreshTime 0.035000 + OverrideScopeRefreshTime on + DisableAllScopes off + FPTRunName "Run 1" + MaxMDLFileLineLength 120 + LastSavedArchitecture "glnxa64" + Object { + $PropName "BdWindowsInfo" + $ObjectID 1 + $ClassName "Simulink.BDWindowsInfo" + Object { + $PropName "WindowsInfo" + $ObjectID 2 + $ClassName "Simulink.WindowInfo" + IsActive [1] + Location [173.0, 232.0, 1280.0, 721.0] + Object { + $PropName "ModelBrowserInfo" + $ObjectID 3 + $ClassName "Simulink.ModelBrowserInfo" + Visible [0] + DockPosition "Left" + Width [50] + Height [50] + Filter [9] + } + Object { + $PropName "ExplorerBarInfo" + $ObjectID 4 + $ClassName "Simulink.ExplorerBarInfo" + Visible [1] + } + Object { + $PropName "EditorsInfo" + $ObjectID 5 + $ClassName "Simulink.EditorInfo" + IsActive [1] + ViewObjType "SimulinkSubsys" + LoadSaveID "192" + Extents [1226.0, 537.0] + ZoomFactor [1.66] + Offset [0.0, 0.0] + } + Object { + $PropName "DockComponentsInfo" + $ObjectID 6 + $ClassName "Simulink.DockComponentInfo" + Type "GLUE2:PropertyInspector" + ID "Property Inspector" + Visible [0] + CreateCallback "" + UserData "" + Floating [0] + DockPosition "Right" + Width [640] + Height [480] + } + WindowState "AAAA/wAAAAD9AAAAAgAAAAAAAAC9AAAB+PwCAAAAA/sAAAAWAEQAbwBjAGsAVwBpAGQAZwBlAHQAMwEAAAAxAAAB+AAAA" + "AAAAAAA+wAAABYARABvAGMAawBXAGkAZABnAGUAdAA0AAAAAAD/////AAAAAAAAAAD7AAAAUgBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0Ac" + "ABvAG4AZQBuAHQALwBHAEwAVQBFADIAIAB0AHIAZQBlACAAYwBvAG0AcABvAG4AZQBuAHQAAAAAAP////8AAABeAP///wAAAAEAAAAAAAAAAPwCA" + "AAAAfsAAABUAEcATABVAEUAMgA6AFAAcgBvAHAAZQByAHQAeQBJAG4AcwBwAGUAYwB0AG8AcgAvAFAAcgBvAHAAZQByAHQAeQAgAEkAbgBzAHAAZ" + "QBjAHQAbwByAAAAAAD/////AAAAKAD///8AAATsAAACUwAAAAEAAAACAAAAAQAAAAL8AAAAAQAAAAIAAAAP/////wAAAAAA/////wAAAAAAAAAA/" + "////wEAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" + "////wEAAACA/////wAAAAAAAAAA/////wEAAADo/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/" + "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA/////wEAAAE7/////wAAAAAAAAAA/" + "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA" + } + } + Created "Thu Feb 06 02:21:39 2014" + Creator "jorhabib" + UpdateHistory "UpdateHistoryNever" + ModifiedByFormat "%" + LastModifiedBy "icub" + ModifiedDateFormat "%" + LastModifiedDate "Fri Aug 11 06:58:36 2017" + RTWModifiedTimeStamp 424335513 + ModelVersionFormat "1.%" + ConfigurationManager "none" + SampleTimeColors off + SampleTimeAnnotations off + LibraryLinkDisplay "disabled" + WideLines off + ShowLineDimensions off + ShowPortDataTypes off + ShowEditTimeErrors on + ShowEditTimeWarnings on + ShowEditTimeAdvisorChecks off + ShowPortUnits off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder off + VariantCondition off + ExecutionContextIcon off + ShowLinearizationAnnotations on + ShowVisualizeInsertedRTB on + ShowMarkup on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks off + FunctionConnectors off + BrowserLookUnderMasks off + SimulationMode "normal" + PauseTimes "5" + NumberOfSteps 1 + SnapshotBufferSize 10 + SnapshotInterval 10 + NumberOfLastSnapshots 0 + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 7 + Version "1.16.5" + DisabledProps [] + Description "" + Array { + Type "Handle" + Dimension 10 + Simulink.SolverCC { + $ObjectID 8 + Version "1.16.5" + DisabledProps [] + Description "" + StartTime "0.0" + StopTime "10.0" + AbsTol "auto" + FixedStep "auto" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + EnableMultiTasking on + EnableConcurrentExecution off + ConcurrentTasks off + Solver "ode45" + SolverName "ode45" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverInfoToggleStatus off + IsAutoAppliedInSIP off + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + SampleTimeProperty [] + } + Simulink.DataIOCC { + $ObjectID 9 + Version "1.16.5" + DisabledProps [] + Description "" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints on + MaxDataPoints "1000" + LoadExternalInput off + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "Array" + SignalLoggingSaveFormat "ModelDataLogs" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + VisualizeSimOutput on + StreamToWorkspace off + StreamVariableName "streamout" + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + LoggingToFile off + LoggingFileName "out.mat" + LoggingIntervals "[-inf, inf]" + } + Simulink.OptimizationCC { + $ObjectID 10 + Version "1.16.5" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + Description "" + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + DefaultParameterBehavior "Tunable" + UseDivisionForNetSlopeComputation "off" + UseFloatMulNetSlope off + DefaultUnderspecifiedDataType "double" + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + CachingGlobalReferences off + GlobalBufferReuse on + StrengthReduction off + AdvancedOptControl "" + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + PassReuseOutputArgsThreshold 12 + ExpressionDepthLimit 2147483647 + LocalBlockOutputs on + RollThreshold 5 + StateBitsets off + DataBitsets off + ActiveStateOutputEnumStorageType "Native Integer" + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "off" + AccelVerboseBuild off + } + Simulink.DebuggingCC { + $ObjectID 11 + Version "1.16.5" + Array { + Type "Cell" + Dimension 1 + Cell "UseOnlyExistingSharedCode" + PropName "DisabledProps" + } + Description "" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "none" + SignalRangeChecking "none" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Classic" + MergeDetectMultiDrivingBlocksExec "none" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "warning" + InheritedTsInSrcMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "error" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "none" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "none" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "warning" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + UseOnlyExistingSharedCode "error" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "error" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + AllowSymbolicDim on + RowMajorDimensionSupport off + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "warning" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + SymbolicDimMinMaxWarning "warning" + LossOfSymbolicDimsSimulationWarning "warning" + LossOfSymbolicDimsCodeGenerationWarning "error" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "warning" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "warning" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnreachableExecutionPathDiag "warning" + SFUndirectedBroadcastEventsDiag "warning" + SFTransitionActionBeforeConditionDiag "warning" + SFOutputUsedAsStateInMooreChartDiag "error" + SFTemporalDelaySmallerThanSampleTimeDiag "warning" + SFSelfTransitionDiag "warning" + SFExecutionAtInitializationDiag "none" + SFMachineParentedDataDiag "warning" + IntegerSaturationMsg "warning" + AllowedUnitSystems "all" + UnitsInconsistencyMsg "warning" + AllowAutomaticUnitConversions on + } + Simulink.HardwareCC { + $ObjectID 12 + Version "1.16.5" + DisabledProps [] + Description "" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerLongLong 64 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 32 + ProdBitPerSizeT 32 + ProdBitPerPtrDiffT 32 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "None" + ProdIntDivRoundTo "Undefined" + ProdEndianess "Unspecified" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdLongLongMode off + ProdHWDeviceType "32-bit Generic" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerLongLong 64 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetBitPerSizeT 32 + TargetBitPerPtrDiffT 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetLongLongMode off + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + UseEmbeddedCoderFeatures on + UseSimulinkCoderFeatures on + } + Simulink.ModelReferenceCC { + $ObjectID 13 + Version "1.16.5" + DisabledProps [] + Description "" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + EnableRefExpFcnMdlSchedulingChecks on + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelDependencies "" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel off + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 14 + Version "1.16.5" + DisabledProps [] + Description "" + SimCustomSourceCode "" + SimCustomHeaderCode "" + SimCustomInitializer "" + SimCustomTerminator "" + SimReservedNameArray [] + SimUserSources "" + SimUserIncludeDirs "" + SimUserLibraries "" + SimUserDefines "" + SimCustomCompilerFlags "" + SimCustomLinkerFlags "" + SFSimEcho on + SimCtrlC on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + SimGenImportedTypeDefs off + ModelFunctionsGlobalVisibility "on" + CompileTimeRecursionLimit 50 + EnableRuntimeRecursion on + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 15 + Version "1.16.5" + Array { + Type "Cell" + Dimension 13 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "GenerateWebview" + Cell "GenerateCodeMetricsReport" + Cell "GenerateCodeReplacementReport" + Cell "PortableWordSizes" + Cell "GenerateMissedCodeReplacementReport" + Cell "GenerateErtSFunction" + Cell "CreateSILPILBlock" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + HardwareBoard "None" + TLCOptions "" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + PackageGeneratedCodeAndArtifacts off + PackageName "" + TemplateMakefile "grt_default_tmf" + PostCodeGenCommand "" + Description "" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + RTWBuildHooks [] + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + CustomSourceCode "" + CustomHeaderCode "" + CustomInclude "" + CustomSource "" + CustomLibrary "" + CustomDefine "" + CustomLAPACKCallback "" + CustomInitializer "" + CustomTerminator "" + Toolchain "Automatically locate an installed toolchain" + BuildConfiguration "Faster Builds" + CustomToolchainOptions [] + IncludeHyperlinkInReport off + LaunchReport off + PortableWordSizes off + CreateSILPILBlock "None" + CodeExecutionProfiling off + CodeExecutionProfileVariable "executionProfile" + CodeProfilingSaveOptions "SummaryOnly" + CodeProfilingInstrumentation off + SILDebugging off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateWebview off + GenerateCodeMetricsReport off + GenerateCodeReplacementReport off + GenerateMissedCodeReplacementReport off + RTWCompilerOptimization "off" + ObjectivePriorities [] + RTWCustomCompilerOptimizations "" + CheckMdlBeforeBuild "Off" + SharedConstantsCachingThreshold 1024 + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 16 + Version "1.16.5" + Array { + Type "Cell" + Dimension 25 + Cell "IgnoreCustomStorageClasses" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "ReqsInCode" + Cell "InternalIdentifier" + Cell "CustomSymbolStrModelFcn" + Cell "CustomSymbolStrUtil" + Cell "CustomUserTokenString" + PropName "DisabledProps" + } + Description "" + Comment "" + ForceParamTrailComments off + GenerateComments on + CommentStyle "Auto" + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + OperatorAnnotations off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M_T" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrModelFcn "$R$N" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + CustomSymbolStrUtil "$N$C" + CustomUserTokenString "" + CustomCommentsFcn "" + DefineNamingRule "None" + DefineNamingFcn "" + ParamNamingRule "None" + ParamNamingFcn "" + SignalNamingRule "None" + SignalNamingFcn "" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InternalIdentifierFile "" + InternalIdentifier "Shortened" + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + ReservedNameArray [] + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 17 + Version "1.16.5" + Array { + Type "Cell" + Dimension 18 + Cell "GeneratePreprocessorConditionals" + Cell "IncludeMdlTerminateFcn" + Cell "SupportNonInlinedSFcns" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "CPPClassGenCompliant" + Cell "PortableWordSizes" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + Cell "GenerateAllocFcn" + Cell "RemoveResetFunc" + Cell "ExistingSharedCode" + Cell "RemoveDisableFunc" + PropName "DisabledProps" + } + Description "" + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + GenFloatMathFcnCalls "NOT IN USE" + TargetLangStandard "C89/C90 (ANSI)" + CodeReplacementLibrary "None" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + InferredTypesCompatibility off + ExistingSharedCode "" + GenerateSampleERTMain off + GenerateTestInterfaces off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Disable all" + CombineOutputUpdateFcns off + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + CodeInterfacePackaging "Nonreusable function" + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + RemoveDisableFunc off + RemoveResetFunc off + SupportVariableSizeSignals off + ParenthesesLevel "Nominal" + CastingMode "Nominal" + MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant on + AutosarCompliant off + MDXCompliant off + GRTInterface on + GenerateAllocFcn off + UseToolchainInfoCompliant on + GenerateSharedConstants on + CoderGroups [] + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeMexArgs "" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + MultiInstanceErrorCode "Error" + } + PropName "Components" + } + } + SlCovCC.ConfigComp { + $ObjectID 18 + Version "1.16.5" + DisabledProps [] + Description "Simulink Coverage Configuration Component" + Name "Simulink Coverage" + CovEnable off + CovScope "EntireSystem" + CovIncludeTopModel on + RecordCoverage off + CovPath "/" + CovSaveName "covdata" + CovCompData "" + CovMetricSettings "dw" + CovFilter "" + CovHTMLOptions "" + CovNameIncrementing off + CovHtmlReporting on + CovForceBlockReductionOff on + CovEnableCumulative on + CovSaveCumulativeToWorkspaceVar on + CovSaveSingleToWorkspaceVar on + CovCumulativeVarName "covCumulativeData" + CovCumulativeReport off + CovSaveOutputData on + CovOutputDir "slcov_output/$ModelName$" + CovDataFileName "$ModelName$_cvdata" + CovShowResultsExplorer on + CovReportOnPause on + CovModelRefEnable "off" + CovModelRefExcluded "" + CovExternalEMLEnable off + CovSFcnEnable off + CovBoundaryAbsTol 1e-05 + CovBoundaryRelTol 0.01 + CovUseTimeInterval off + CovStartTime 0 + CovStopTime 0 + } + hdlcoderui.hdlcc { + $ObjectID 19 + Version "1.16.5" + DisabledProps [] + Description "HDL Coder custom configuration component" + Name "HDL Coder" + Array { + Type "Cell" + Dimension 1 + Cell " " + PropName "HDLConfigFile" + } + HDLCActiveTab "0" + } + PropName "Components" + } + Name "Configuration" + ExtraOptions "" + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 963, 135, 1843, 765 ] + } + PropName "ConfigurationSets" + } + ExplicitPartitioning off + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + MaskDefaults { + SelfModifiable "off" + IconFrame "on" + IconOpaque "opaque" + RunInitForIconRedraw "off" + IconRotate "none" + PortRotate "default" + IconUnits "autoscale" + } + MaskParameterDefaults { + Evaluate "on" + Tunable "on" + NeverSave "off" + Internal "off" + ReadOnly "off" + Enabled "on" + Visible "on" + ToolTip "on" + } + BlockParameterDefaults { + Block { + BlockType Clock + DisplayTime off + Decimation "10" + } + Block { + BlockType Constant + Value "1" + VectorParams1D on + SamplingMode "Sample based" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit from 'Constant value'" + LockScale off + SampleTime "inf" + FramePeriod "inf" + PreserveConstantTs off + } + Block { + BlockType Demux + Outputs "4" + DisplayOption "none" + BusSelectionMode off + } + Block { + BlockType Gain + Gain "1" + Multiplication "Element-wise(K.*u)" + ParamMin "[]" + ParamMax "[]" + ParamDataTypeStr "Inherit: Same as input" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Inport + Port "1" + OutputFunctionCall off + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + Unit "inherit" + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + LatchByDelayingOutsideSignal off + LatchInputForFeedbackSignals off + Interpolate on + } + Block { + BlockType Outport + Port "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + Unit "inherit" + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + EnsureOutportIsVirtual off + SourceOfInitialOutputValue "Dialog" + OutputWhenDisabled "held" + InitialOutput "[]" + } + Block { + BlockType Product + Inputs "2" + Multiplication "Element-wise(.*)" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Zero" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType S-Function + FunctionName "system" + SFunctionModules "''" + PortCounts "[]" + } + Block { + BlockType SubSystem + ShowPortLabels "FromPortIcon" + Permissions "ReadWrite" + PermitHierarchicalResolution "All" + TreatAsAtomicUnit off + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + SystemSampleTime "-1" + RTWSystemCode "Auto" + RTWFcnNameOpts "Auto" + RTWFileNameOpts "Auto" + FunctionInterfaceSpec "void_void" + FunctionWithSeparateData off + RTWMemSecFuncInitTerm "Inherit from model" + RTWMemSecFuncExecute "Inherit from model" + RTWMemSecDataConstants "Inherit from model" + RTWMemSecDataInternal "Inherit from model" + RTWMemSecDataParameters "Inherit from model" + SimViewingDevice off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + Opaque off + MaskHideContents off + SFBlockType "NONE" + GeneratePreprocessorConditionals off + PropagateVariantConditions off + TreatAsGroupedWhenPropagatingVariantConditions on + ContentPreviewEnabled off + IsWebBlock off + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Terminator + } + } + System { + Name "WBToolboxLibrary_repository" + Location [173, 232, 1453, 953] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "black" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "273" + ReportName "simulink-default.rpt" + SIDHighWatermark "1772" + Block { + BlockType SubSystem + Name "Utilities" + SID "192" + Ports [] + Position [364, 17, 462, 114] + ZOrder -1 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 20 + $ClassName "Simulink.Mask" + Display "image(imread('utilities.png'))" + } + System { + Name "Utilities" + Location [173, 232, 1453, 953] + Open on + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "166" + Block { + BlockType SubSystem + Name "DampPinv" + SID "104" + Ports [2, 1] + Position [435, 153, 505, 197] + ZOrder -1 + BackgroundColor "[0.848000, 0.128048, 0.320035]" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 21 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 22 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "tol" + Prompt "Tolerance" + Value "1e-4" + } + } + System { + Name "DampPinv" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "mat" + SID "105" + Position [50, 53, 80, 67] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "sigma" + SID "106" + Position [50, 93, 80, 107] + ZOrder -2 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Damped Pseudo Inverse" + SID "107" + Ports [2, 1] + Position [105, 39, 200, 121] + ZOrder -4 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + System { + Name "Damped Pseudo Inverse" + Location [12, 45, 1279, 3773] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "1619" + Block { + BlockType Inport + Name "mat" + SID "107::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "sigma" + SID "107::25" + Position [20, 136, 40, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "107::1618" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 98 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "107::1617" + Tag "Stateflow S-Function WBToolboxLibrary_repository 6" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 97 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Port { + PortNumber 2 + Name "DPinv" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "107::1619" + Position [460, 241, 480, 259] + ZOrder 99 + } + Block { + BlockType Outport + Name "DPinv" + SID "107::5" + Position [460, 101, 480, 119] + ZOrder -6 + IconDisplay "Port number" + } + Line { + ZOrder 61 + SrcBlock "mat" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 62 + SrcBlock "sigma" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "DPinv" + ZOrder 63 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "DPinv" + DstPort 1 + } + Line { + ZOrder 64 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 65 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "DPinv" + SID "108" + Position [225, 73, 255, 87] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "sigma" + SrcPort 1 + DstBlock "Damped Pseudo Inverse" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "Damped Pseudo Inverse" + SrcPort 1 + DstBlock "DPinv" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "mat" + SrcPort 1 + DstBlock "Damped Pseudo Inverse" + DstPort 1 + } + } + } + Block { + BlockType Reference + Name "DiscreteFilter" + SID "1772" + Ports [1, 1] + Position [440, 260, 500, 290] + ZOrder 83 + BackgroundColor "yellow" + LibraryVersion "1.386" + SourceBlock "WBToolboxLibrary/Utilities/DiscreteFilter" + SourceType "Discrete Filter" + filterType "Generic" + numCoeffs "[0]" + denCoeffs "[0]" + Fc "0" + Ts "0" + orderMedianFilter "0" + } + Block { + BlockType S-Function + Name "DoFs converter" + SID "1771" + Ports [1, 5] + Position [240, 241, 385, 309] + ZOrder 81 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend\n" + FunctionName "WBToolbox" + Parameters "'YARPWBIConverter',robotName,localName,wbiFile,wbiList,yarp2WBIOption" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 23 + $ClassName "Simulink.Mask" + Type "DoFs converter" + Description "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on" + " its configuration.\nThe DoFs configuration is automatically currently taken from the WBI list option.\nThe robot" + " name is taken from the environment variable YARP_ROBOT_NAME.\n\nParameters:\n\n- Conversion direction: specify i" + "f you want to convert from YARP to the current DoFs serialization or viceversa.\n\nWBI parameters:\n\n- Robot Por" + "t Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use t" + "he name specified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name" + " of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the con" + "figuration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole B" + "ody Interface\n" + Display "robotName = getenv('YARP_ROBOT_NAME');\n\ncurrentSelection = get_param(gcb,'yarp2WBIoption');\n\nif" + " strcmp(currentSelection,'From YARP to WBI')\n direction = 'YARP -> DoFs';\nelse\n direction = 'DoFs -> YAR" + "P';\nend\n\nfprintf('%s\\n\\n%s', robotName, direction);" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 24 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "From YARP to WBI" + Cell "From WBI to YARP" + PropName "TypeOptions" + } + Name "yarp2WBIOption" + Prompt "Conversion Direction" + Value "From YARP to WBI" + } + Object { + $ObjectID 25 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + } + Object { + $ObjectID 26 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + } + Object { + $ObjectID 27 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + } + Object { + $ObjectID 28 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 29 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 30 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 31 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 32 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 33 + Prompt "Block Parameters" + Object { + $PropName "DialogControls" + $ObjectID 34 + $ClassName "Simulink.dialog.parameter.Popup" + Name "yarp2WBIOption" + } + Name "Container4" + } + Object { + $ObjectID 35 + Prompt "WBI Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 36 + Name "robotName" + } + Object { + $ObjectID 37 + Name "localName" + } + Object { + $ObjectID 38 + Name "wbiFile" + } + Object { + $ObjectID 39 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container7" + } + PropName "DialogControls" + } + Name "Container3" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + } + Block { + BlockType S-Function + Name "Minimum Jerk Trajectory Generator" + SID "1747" + Ports [1, 3] + Position [335, 73, 490, 127] + ZOrder 78 + FunctionName "WBToolbox" + Parameters "'MinimumJerkTrajectoryGenerator',sampleTime, settlingTime, firstDerivatives, secondDerivatives, expl" + "icitInitialValue, externalSettlingTime,resetOnSettlingTime" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 40 + $ClassName "Simulink.Mask" + Type "Minimum Jerk Trajectory Generator" + Description "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk " + "Trajectory Generator is approximated using a \n3rd order LTI dynamical system \n(for more details see [1]). \nPos" + "ition, velocity and acceleration trajectories are computed.\n The main advantage with respect to the standard pol" + "ynomial \nform is that if the reference value yd changes \nthere is no need to recompute the filter coefficients." + "\n\n[1] Pattacini, U.; Nori, F.; Natale, L.; Metta, G.; Sandini, G., \"An experimental evaluation of a novel mini" + "mum-jerk cartesian controller for humanoid robots,\" in Intelligent Robots and Systems (IROS), 2010 IEEE/RSJ Inte" + "rnational Conference on , vol., no., pp.1668-1674, 18-22 Oct. 2010\ndoi: 10.1109/IROS.2010.5650851\nURL: http://i" + "eeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=5650851&isnumber=5648787" + Display "firstDer = get_param(gcb, 'firstDerivatives');\nsecondDer = get_param(gcb, 'secondDerivatives');\ni" + "nitialValues = get_param(gcb, 'explicitInitialValue');\nexternalSettlingTimeParam = get_param(gcb, 'externalSettl" + "ingTime');\n\n%Inputs\nportIndex = 2;\nport_label('input', 1, 'Reference')\nif(strcmp(initialValues, 'on'))\n " + "port_label('input', portIndex, 'Initial Value')\n portIndex = portIndex + 1;\nend\n\nif(strcmp(externalSettlin" + "gTimeParam, 'on'))\n port_label('input', portIndex, 'Settling Time')\n portIndex = portIndex + 1;\nend\n\n%" + "Outputs\nport_label('output', 1, 'Signal')\nsecondDerPortIndex = 2;\nif(strcmp(firstDer, 'on'))\n port_label('" + "output', 2, 'First Derivative')\n secondDerPortIndex = secondDerPortIndex + 1;\nend\nif(strcmp(secondDer, 'on'" + "))\n port_label('output', secondDerPortIndex, 'Second Derivative')\nend\n\n\n" + Array { + Type "Simulink.MaskParameter" + Dimension 7 + Object { + $ObjectID 41 + Type "checkbox" + Name "externalSettlingTime" + Prompt "External Settling Time" + Value "off" + Callback "externalSettlingTime = get_param(gcb, 'externalSettlingTime');\nvisibility = get_param(gcb, 'MaskVisibili" + "ties');\nif(strcmp(externalSettlingTime, 'on'))\n visibility{2} = 'off';\n visibility{4} = 'on';\nelse\n vi" + "sibility{2} = 'on';\n visibility{4} = 'off';\nend\nset_param(gcb, 'MaskVisibilities',visibility);\nclear external" + "SettlingTime" + } + Object { + $ObjectID 42 + Type "edit" + Name "settlingTime" + Prompt "Settling Time" + Value "3" + } + Object { + $ObjectID 43 + Type "edit" + Name "sampleTime" + Prompt "Sample Time" + Value "0.01" + } + Object { + $ObjectID 44 + Type "checkbox" + Name "resetOnSettlingTime" + Prompt "Reset on Settling Time Changes" + Value "off" + } + Object { + $ObjectID 45 + Type "checkbox" + Name "firstDerivatives" + Prompt "Output First Derivative" + Value "on" + } + Object { + $ObjectID 46 + Type "checkbox" + Name "secondDerivatives" + Prompt "Output Second Derivative" + Value "on" + } + Object { + $ObjectID 47 + Type "checkbox" + Name "explicitInitialValue" + Prompt "Explicit Initial Value" + Value "off" + Visible "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 48 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 49 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 50 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 51 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 52 + Prompt "Trajectory Parameters" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 4 + Object { + $ObjectID 53 + $ClassName "Simulink.dialog.parameter.CheckBox" + Name "externalSettlingTime" + } + Object { + $ObjectID 54 + $ClassName "Simulink.dialog.parameter.Edit" + Name "settlingTime" + } + Object { + $ObjectID 55 + $ClassName "Simulink.dialog.parameter.Edit" + Name "sampleTime" + } + Object { + $ObjectID 56 + $ClassName "Simulink.dialog.parameter.CheckBox" + Name "resetOnSettlingTime" + } + PropName "DialogControls" + } + Name "Tab1" + } + Object { + $ObjectID 57 + Prompt "Input/Output" + Array { + Type "Simulink.dialog.parameter.CheckBox" + Dimension 3 + Object { + $ObjectID 58 + Name "firstDerivatives" + } + Object { + $ObjectID 59 + Name "secondDerivatives" + } + Object { + $ObjectID 60 + Name "explicitInitialValue" + } + PropName "DialogControls" + } + Name "Tab2" + } + PropName "DialogControls" + } + Name "Container3" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + } + Block { + BlockType S-Function + Name "Real Time Synchronizer" + SID "1657" + Ports [] + Position [155, 14, 280, 51] + ZOrder 23 + ForegroundColor "white" + BackgroundColor "gray" + ShowName off + FunctionName "WBToolbox" + Parameters "'RealTimeSynchronizer',period" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 61 + $ClassName "Simulink.Mask" + Type "Real Time Synchronizer" + Description "This block slows down the simulation trying to match the period specified \nas parameter (in se" + "conds).\nThe bigger the period the more probable \nis that Simulink can remain synched with it.\n" + Display "disp('Real Time Synchronizer')" + Object { + $PropName "Parameters" + $ObjectID 62 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "period" + Prompt "Controller Period (in seconds)" + Value "0.01" + } + } + } + Block { + BlockType S-Function + Name "Simulator Synchronizer" + SID "1658" + Ports [] + Position [335, 14, 465, 51] + ZOrder 24 + ForegroundColor "[0.490196, 0.000000, 0.000000]" + ShowName off + FunctionName "WBToolbox" + Parameters "'SimulatorSynchronizer',period, serverPortName, clientPortName" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 63 + $ClassName "Simulink.Mask" + Type "Simulator Synchronizer" + Description "This block synchronizes with the external simulation on a simulator \n(only Gazebo is supported" + " at the moment).\n\n" + Display "disp('Simulator Synchronizer')" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 64 + Type "edit" + Name "period" + Prompt "Controller Period (in seconds)" + Value "0.01" + } + Object { + $ObjectID 65 + Type "edit" + Name "serverPortName" + Prompt "Server Port Name" + Value "'/clock/rpc'" + } + Object { + $ObjectID 66 + Type "edit" + Name "clientPortName" + Prompt "Client Port Name" + Value "'/WBT_synchronizer/rpc:o'" + } + PropName "Parameters" + } + } + } + Block { + BlockType SubSystem + Name "TruncPinv" + SID "109" + Ports [2, 1] + Position [335, 153, 405, 197] + ZOrder -3 + BackgroundColor "[0.534601, 0.470279, 1.000000]" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 67 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 68 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "tol" + Prompt "Tolerance" + Value "1e-4" + } + } + System { + Name "TruncPinv" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "S" + SID "110" + Position [50, 53, 80, 67] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tol" + SID "111" + Position [50, 93, 80, 107] + ZOrder -2 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "Truncated PseudoInverse" + SID "112" + Ports [2, 1] + Position [105, 39, 200, 121] + ZOrder -4 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + System { + Name "Truncated PseudoInverse" + Location [12, 45, 1279, 3773] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "1610" + Block { + BlockType Inport + Name "mat" + SID "112::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tol" + SID "112::25" + Position [20, 136, 40, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "112::1609" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 98 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "112::1608" + Tag "Stateflow S-Function WBToolboxLibrary_repository 7" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 97 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Port { + PortNumber 2 + Name "TPinv" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "112::1610" + Position [460, 241, 480, 259] + ZOrder 99 + } + Block { + BlockType Outport + Name "TPinv" + SID "112::5" + Position [460, 101, 480, 119] + ZOrder -6 + IconDisplay "Port number" + } + Line { + ZOrder 61 + SrcBlock "mat" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 62 + SrcBlock "tol" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "TPinv" + ZOrder 63 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "TPinv" + DstPort 1 + } + Line { + ZOrder 64 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 65 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "Tpinv" + SID "113" + Position [225, 73, 255, 87] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S" + SrcPort 1 + DstBlock "Truncated PseudoInverse" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Truncated PseudoInverse" + SrcPort 1 + DstBlock "Tpinv" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "tol" + SrcPort 1 + DstBlock "Truncated PseudoInverse" + DstPort 2 + } + } + } + Block { + BlockType S-Function + Name "Yarp Read" + SID "1632" + Ports [0, 2] + Position [105, 74, 165, 121] + ZOrder 22 + ForegroundColor "[0.490196, 0.000000, 0.000000]" + FunctionName "WBToolbox" + Parameters "'YarpRead',portName,signalSize,blocking,timestamp,autoconnect,errorOnConnection" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 69 + $ClassName "Simulink.Mask" + Type "YARP Read" + Description "This block behaves as the command 'yarp read'. \nBy default it has the option 'Autoconnect' act" + "ive, which means that the user \ncan only specify the name of the port ('Source Port Name') from which readings a" + "re desired,\nalong with the size of the expected data (e.g. 3 when reading the torso state).\nWhen the user unche" + "cks 'Autoconnect' 'Opened Port Name' field shows up \ncorresponding to the name of the port the block will create" + " \nbut won't connect to anything. \nAt this point the output will be always zero, until the user connects it\nto " + "some other port from command line by issuing 'yarp connect [from] [dest]'.\nIn this case an additional output, ca" + "lled 'signal' will be added which will output\n1 if the port has received at least one data, or 0 otherwise.\n" + SelfModifiable "on" + Display "port_label('output', 1, 'signal');\nportNumber = 1;\nif (timestamp)\n portNumber = portNumber + " + "1;\n port_label('output', portNumber, 'timestamp');\nend\n\nif (~autoconnect)\n portNumber = portNumber + 1" + ";\n port_label('output', portNumber, 'status');\nend\n\n" + Array { + Type "Simulink.MaskParameter" + Dimension 6 + Object { + $ObjectID 70 + Type "edit" + Name "portName" + Prompt "Source Port Name" + Value "'/portname'" + } + Object { + $ObjectID 71 + Type "edit" + Name "signalSize" + Prompt "Port Size" + Value "1" + } + Object { + $ObjectID 72 + Type "checkbox" + Name "blocking" + Prompt "Blocking Read" + Value "off" + } + Object { + $ObjectID 73 + Type "checkbox" + Name "timestamp" + Prompt "Read Timestamp" + Value "on" + } + Object { + $ObjectID 74 + Type "checkbox" + Name "autoconnect" + Prompt "Autoconnect" + Value "on" + Callback "autoconnect_val = get_param(gcb, 'Autoconnect');\nprompt_string = get_param(gcb, 'MaskPrompts');\nif(strc" + "mp(autoconnect_val, 'on'))\n prompt_string{1} = 'Source Port Name';\n set_param(gcb, 'MaskVisibilities',{'on';" + "'on';'on';'on';'on';'on'});\nelse\n prompt_string{1} = 'Opened Port Name';\n set_param(gcb, 'MaskVisibilities'" + ",{'on';'on';'on';'on';'on';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val promp" + "t_string" + } + Object { + $ObjectID 75 + Type "checkbox" + Name "errorOnConnection" + Prompt "Error on missing connection" + Value "on" + } + PropName "Parameters" + } + } + } + Block { + BlockType S-Function + Name "Yarp Write" + SID "1659" + Ports [1] + Position [230, 76, 290, 124] + ZOrder 27 + ForegroundColor "[0.490196, 0.000000, 0.000000]" + FunctionName "WBToolbox" + Parameters "'YarpWrite',portName,autoconnect,errorOnConnection" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 76 + $ClassName "Simulink.Mask" + Type "YARP Write" + Description "This block behaves as the command 'yarp write'. \n\nBy default this block opens a port names as" + " the \"Opened Port Name\" parameter\nand stream the input signal to that port.\nIf the option \"Autoconnect\" is " + "specified, the first parameter become the\nname of the target port to which the data will be stramed, \ne.g. like" + " \"yarp write ... /destinationPort\"\n" + SelfModifiable "on" + Display "disp('Yarp Write')" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 77 + Type "edit" + Name "portName" + Prompt "Opened Port Name" + Value "'/portname'" + } + Object { + $ObjectID 78 + Type "checkbox" + Name "autoconnect" + Prompt "Autoconnect" + Value "off" + Callback "autoconnect_val = get_param(gcb, 'Autoconnect');\nprompt_string = get_param(gcb, 'MaskPrompts');\nif(strc" + "mp(autoconnect_val, 'on'))\n prompt_string{1} = 'Destination Port Name';\n set_param(gcb, 'MaskVisibilities',{" + "'on';'on';'on'});\nelse\n prompt_string{1} = 'Opened Port Name';\n set_param(gcb, 'MaskVisibilities',{'on';'on" + "';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val prompt_string" + } + Object { + $ObjectID 79 + Type "checkbox" + Name "errorOnConnection" + Prompt "Error on missing connection" + Value "on" + Visible "off" + } + PropName "Parameters" + } + } + } + Block { + BlockType SubSystem + Name "errors" + SID "714" + Ports [2, 2] + Position [200, 153, 260, 197] + ZOrder -9 + BackgroundColor "[0.300000, 0.580000, 1.000000]" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 80 + $ClassName "Simulink.Mask" + Type "Errors" + Description "Computes two kinds of errors. The first is just the difference between x\nand y while the secon" + "d is the ratio (x-y)/y." + } + System { + Name "errors" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x" + SID "715" + Position [30, 28, 60, 42] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "y" + SID "716" + Position [25, 103, 55, 117] + ZOrder -2 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "717" + Ports [2, 1] + Position [95, 27, 125, 58] + ZOrder -3 + Inputs "+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Divide" + SID "718" + Ports [2, 1] + Position [165, 37, 195, 68] + ZOrder -4 + Inputs "*/" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "x-y" + SID "719" + Position [225, 13, 255, 27] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "(x-y)./y" + SID "720" + Position [220, 48, 250, 62] + ZOrder -6 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "Add" + SrcPort 1 + Points [10, 0] + Branch { + ZOrder 2 + DstBlock "Divide" + DstPort 1 + } + Branch { + ZOrder 3 + Points [0, -25] + DstBlock "x-y" + DstPort 1 + } + } + Line { + ZOrder 4 + SrcBlock "x" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "y" + SrcPort 1 + Points [15, 0] + Branch { + ZOrder 6 + Points [0, -60] + DstBlock "Add" + DstPort 2 + } + Branch { + ZOrder 7 + Points [60, 0; 0, -50] + DstBlock "Divide" + DstPort 2 + } + } + Line { + ZOrder 8 + SrcBlock "Divide" + SrcPort 1 + DstBlock "(x-y)./y" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "holder\n" + SID "1296" + Ports [1, 1] + Position [105, 152, 165, 198] + ZOrder 14 + BackgroundColor "[0.537255, 0.721569, 1.000000]" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 81 + $ClassName "Simulink.Mask" + Type "Holder" + Description "This block holds the first input value during the simulation." + } + System { + Name "holder\n" + Location [12, 45, 1340, 980] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "s" + SID "1297" + Position [145, 43, 175, 57] + ZOrder 13 + IconDisplay "Port number" + } + Block { + BlockType Clock + Name "Clock" + SID "1298" + Position [45, 65, 65, 85] + ZOrder 11 + } + Block { + BlockType Reference + Name "Compare\nTo Constant" + SID "1299" + Ports [1, 1] + Position [90, 60, 120, 90] + ZOrder 10 + LibraryVersion "1.388" + SourceBlock "simulink/Logic and Bit\nOperations/Compare\nTo Constant" + SourceType "Compare To Constant" + ContentPreviewEnabled off + relop "==" + const "0" + OutDataTypeStr "boolean" + ZeroCross on + } + Block { + BlockType SubSystem + Name "MATLAB Function" + SID "1300" + Ports [2, 1] + Position [235, 37, 305, 88] + ZOrder 15 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Variant off + System { + Name "MATLAB Function" + Location [12, 45, 1135, 3068] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "1610" + Block { + BlockType Inport + Name "s" + SID "1300::24" + Position [20, 101, 40, 119] + ZOrder 10 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "unused" + SID "1300::26" + Position [20, 136, 40, 154] + ZOrder 12 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "1300::1609" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 86 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "1300::1608" + Tag "Stateflow S-Function WBToolboxLibrary_repository 1" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 85 + FunctionName "sf_sfun" + PortCounts "[2 2]" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Port { + PortNumber 2 + Name "s0" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "1300::1610" + Position [460, 241, 480, 259] + ZOrder 87 + } + Block { + BlockType Outport + Name "s0" + SID "1300::25" + Position [460, 101, 480, 119] + ZOrder 11 + IconDisplay "Port number" + } + Line { + ZOrder 61 + SrcBlock "s" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 62 + SrcBlock "unused" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "s0" + ZOrder 63 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "s0" + DstPort 1 + } + Line { + ZOrder 64 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 65 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "s(0)" + SID "1301" + Position [330, 58, 360, 72] + ZOrder 14 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "Clock" + SrcPort 1 + DstBlock "Compare\nTo Constant" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "MATLAB Function" + SrcPort 1 + DstBlock "s(0)" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "s" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "Compare\nTo Constant" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 2 + } + } + } + } + } + Block { + BlockType SubSystem + Name "wholeBodyActuators" + SID "224" + Ports [] + Position [250, 16, 348, 113] + ZOrder -17 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 82 + $ClassName "Simulink.Mask" + Display "image(imread('wholeBodyActuators.png'),'center')" + } + System { + Name "wholeBodyActuators" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "667" + Block { + BlockType SubSystem + Name "Set LowLevel PIDs" + SID "1752" + Ports [] + Position [745, 230, 820, 280] + ZOrder 41 + BackgroundColor "[0.827500, 0.576500, 0.603900]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 83 + $ClassName "Simulink.Mask" + Type "Set Low Level PIDs" + Description "This block sets the low level PID values for the robot actuators.\n\nIf only one gain file is s" + "pecified, those gains are loaded at startup.\nOtherwise an additional port to this block is added which accept an" + " integer\nrepresenting the index in the list of gains to be loaded (also at runtime)\n\nAssuming DoFs is the numb" + "er of degrees of freedom of the robot,\nParameters:\n- PID Parameter: String specifying either a file containing " + "the PIDs for the\n low level control, or a list of files (in yarp Bottle format).\n\n- Robot Port" + " Name: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use th" + "e name specified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name " + "of the ports opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the conf" + "iguration of the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Bo" + "dy Interface\n" + Display "pidType = get_param(gcb,'pidType');\ndescription = sprintf('Set Low Level\\n%s PIDs', pidType);\ndi" + "sp(description);\n" + Array { + Type "Simulink.MaskParameter" + Dimension 6 + Object { + $ObjectID 84 + Type "edit" + Name "pidParameters" + Prompt "PID parameter" + Value "''" + Tunable "off" + } + Object { + $ObjectID 85 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Position" + Cell "Torque" + PropName "TypeOptions" + } + Name "pidType" + Prompt "PID Type" + Value "Torque" + Evaluate "off" + Callback "% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(gcb,'pidType'" + ");\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]');\nelseif s" + "trcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0]');\nelseif st" + "rcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\nelseif strcmp(mas" + "kStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear maskStr" + } + Object { + $ObjectID 86 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 87 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 88 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 89 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 90 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 91 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 92 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 93 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 94 + Prompt "Block parameters" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 2 + Object { + $ObjectID 95 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "pidParameters" + } + Object { + $ObjectID 96 + $ClassName "Simulink.dialog.parameter.Popup" + Name "pidType" + } + PropName "DialogControls" + } + Name "Container8" + } + Object { + $ObjectID 97 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 98 + Name "robotName" + } + Object { + $ObjectID 99 + Name "localName" + } + Object { + $ObjectID 100 + Name "wbiFile" + } + Object { + $ObjectID 101 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Set LowLevel PIDs" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "1000" + Block { + BlockType S-Function + Name "S-Function" + SID "1753" + Ports [] + Position [125, 39, 185, 71] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'SetLowLevelPID',robotName,localName,wbiFile,wbiList,pidParameters,pidType" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + } + } + Block { + BlockType SubSystem + Name "Set References" + SID "1767" + Ports [1] + Position [645, 230, 720, 280] + ZOrder 43 + BackgroundColor "[0.513700, 0.851000, 0.670600]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 102 + $ClassName "Simulink.Mask" + Type "Set References" + Description "This block sets the references for the robot actuators.\nThe type of control mode is specified " + "as a parameter in the block.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Refere" + "nces: Vector of size DoFs, representing the references to be sent \n to the robot controlled joint" + "s.\n\nParameters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name " + "of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name speci" + "fied in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports" + " opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of" + " the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface" + "\n" + Display "disp(get_param(gcb,'controlType'))\n%port_label('input',1,'References')" + Array { + Type "Simulink.MaskParameter" + Dimension 7 + Object { + $ObjectID 103 + Type "popup" + Array { + Type "Cell" + Dimension 5 + Cell "Position" + Cell "Position Direct" + Cell "Velocity" + Cell "Torque" + Cell "Open Loop" + PropName "TypeOptions" + } + Name "controlType" + Prompt "Control Mode" + Value "Position" + Evaluate "off" + Callback "% Get the mask parameter values. This is a cell\n% array of strings.\nmaskStr = get_param(gcb,'controlT" + "ype');\nif strcmp(maskStr, 'Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]');\nelse" + "if strcmp(maskStr, 'Position Direct')\n set_param(gcb,'BackgroundColor', '[0.3922, 0.7882, 0.3451, 1.0]');\nelsei" + "f strcmp(maskStr, 'Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]');\nelseif strcmp" + "(maskStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nelseif strcmp(maskStr, " + "'Open Loop')\n set_param(gcb,'BackgroundColor', '[0.98, 0.98, 0.98, 1.0]');\nend\nclear maskStr" + } + Object { + $ObjectID 104 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Full" + Cell "Sublist" + PropName "TypeOptions" + } + Name "fullOrSubControl" + Prompt "Control Type" + Value "Full" + Callback "subOrFull = get_param(gcb, 'fullOrSubControl');\nif(strcmp(subOrFull, 'Sublist'))\n set_param(gcb, 'Ma" + "skVisibilities',{'on';'on';'on';'on';'on';'on';'on'});\nelse\n set_param(gcb, 'MaskVisibilities',{'on';'on';'off'" + ";'on';'on';'on';'on'});\nend\nclear subOrFull " + } + Object { + $ObjectID 105 + Type "edit" + Name "controlledJoints" + Prompt "Controlled Joint List" + Value "''" + Visible "off" + } + Object { + $ObjectID 106 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 107 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 108 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 109 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 110 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 111 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 112 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 113 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 114 + Prompt "Block parameters" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 3 + Object { + $ObjectID 115 + $ClassName "Simulink.dialog.parameter.Popup" + Name "controlType" + } + Object { + $ObjectID 116 + $ClassName "Simulink.dialog.parameter.Popup" + Name "fullOrSubControl" + } + Object { + $ObjectID 117 + $ClassName "Simulink.dialog.parameter.Edit" + Name "controlledJoints" + } + PropName "DialogControls" + } + Name "Container8" + } + Object { + $ObjectID 118 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 119 + Name "robotName" + } + Object { + $ObjectID 120 + Name "localName" + } + Object { + $ObjectID 121 + Name "wbiFile" + } + Object { + $ObjectID 122 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Set References" + Location [535, 41, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "521" + Block { + BlockType Inport + Name "References" + SID "1768" + Position [55, 48, 85, 62] + ZOrder 24 + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1769" + Ports [1] + Position [125, 39, 185, 71] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'SetReferences',robotName,localName,wbiFile,wbiList,controlType,fullOrSubControl,controlledJo" + "ints" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Line { + ZOrder 1 + SrcBlock "References" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + } + } + } + } + Block { + BlockType SubSystem + Name "wholeBodyModel" + SID "209" + Ports [] + Position [133, 16, 231, 113] + ZOrder -3 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 123 + $ClassName "Simulink.Mask" + Display "image(imread('wholeBodyModel.png'),'center')" + } + System { + Name "wholeBodyModel" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "309" + Block { + BlockType SubSystem + Name "Dynamics" + SID "369" + Ports [] + Position [364, 21, 471, 128] + ZOrder -1 + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 124 + $ClassName "Simulink.Mask" + Display "image(imread('Dynamics.png'))" + } + System { + Name "Dynamics" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "219" + Block { + BlockType SubSystem + Name "Centroidal Momentum" + SID "1694" + Ports [4, 1] + Position [495, 101, 680, 164] + ZOrder 72 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 125 + $ClassName "Simulink.Mask" + Type "Centroidal Momentum" + Description "This block computed the 6 element centroidal momentum, as defined in:\n\"Centroidal dynamics of a huma" + "noid robot\" - DE Orin, A Goswami, SH Lee - \nAutonomous Robots 35 (2-3), 161-176\n\nAssuming DoFs is the number of " + "degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" + "\n the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the con" + "figuration \n of the joints.\n- Base velocity: Vector of size 6 representing the linear and an" + "gular velocity\n of the base frame.\n- Joints velocity: Vector of size DoFs, representing the veloci" + "ty \n of the joints.\n\nOutput:\n- Centroidal Momentum: 6-element vector containg the centroidal m" + "omentum \n (3 value for linear momentum and 3 for angular momentum)\n\nParameters:\n- Robot Port Name" + ": Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name s" + "pecified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the port" + "s opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of t" + "he Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Array { + Type "Simulink.MaskParameter" + Dimension 4 + Object { + $ObjectID 126 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 127 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 128 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 129 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + } + System { + Name "Centroidal Momentum" + Location [0, 23, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "248" + Block { + BlockType Inport + Name "Base Pose" + SID "1695" + Position [20, 18, 50, 32] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1696" + Position [20, 53, 50, 67] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Base velocity" + SID "1697" + Position [20, 88, 50, 102] + ZOrder 26 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joints velocity" + SID "1698" + Position [20, 123, 50, 137] + ZOrder 27 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1699" + Ports [4, 1] + Position [180, 11, 255, 144] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'CentroidalMomentum',robotName,localName,wbiFile,wbiList" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Centroidal Momentum" + SID "1700" + Position [315, 73, 345, 87] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Centroidal Momentum" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "Base velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + ZOrder 5 + SrcBlock "Joints velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 4 + } + } + } + Block { + BlockType SubSystem + Name "Get Bias Forces" + SID "1724" + Ports [4, 1] + Position [400, 202, 540, 303] + ZOrder 73 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 130 + $ClassName "Simulink.Mask" + Type "Get Generalized Bias Forces" + Description "This block retrieves the generalied bias forces of the robot.\n\nParameter:\n- Explicit Gravity. If Tr" + "ue, an additional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.81] is used." + "\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the " + "homogenous transformation between\n the base frame and the world frame.\n- Joint configuration: Vector of" + " size DoFs, representing the configuration \n of the joints.\n- Base velocity: Vector of size 6 r" + "epresenting the linear and angular velocity\n of the base frame.\n- Joints velocity: Vector of size " + "DoFs, representing the velocity of the joints.\n\nOutput:\n- Bias Forces: a Dofs + 6 vector representing the general" + "ized bias forces\n of the robot\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot." + " (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the unde" + "rlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interf" + "ace\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Initialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on', ...\n'Name'," + " 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb,'/S-Function']);\n" + " add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S-Function/7', 'autorouti" + "ng','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gravity/1','S-Function/7');\n " + " delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function']);\n end\nend\n" + SelfModifiable "on" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 131 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 132 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 133 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 134 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + Object { + $ObjectID 135 + Type "checkbox" + Name "explicitGravity" + Prompt "Explicit Gravity" + Value "off" + } + PropName "Parameters" + } + } + System { + Name "Get Bias Forces" + Location [354, 32, 1634, 747] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "255" + SIDHighWatermark "1748" + Block { + BlockType Inport + Name "Base Pose" + SID "1724:1725" + Position [10, 38, 40, 52] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1724:1726" + Position [10, 68, 40, 82] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Base velocity" + SID "1724:1727" + Position [10, 98, 40, 112] + ZOrder 26 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joints velocity" + SID "1724:1728" + Position [10, 128, 40, 142] + ZOrder 27 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Constant + Name "Constant" + SID "1724:1742" + Position [-5, 157, 50, 173] + ZOrder 30 + ShowName off + Value "zeros(6,1)" + } + Block { + BlockType Gain + Name "Gain" + SID "1724:1743" + Position [110, 180, 140, 210] + ZOrder 31 + ShowName off + Gain "0" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType S-Function + Name "S-Function" + SID "1724:1731" + Ports [6, 1] + Position [180, 24, 240, 216] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Bias Forces" + SID "1724:1732" + Position [300, 113, 330, 127] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Bias Forces" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "Base velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + ZOrder 5 + SrcBlock "Joints velocity" + SrcPort 1 + Points [44, 0] + Branch { + ZOrder 11 + Points [0, 60] + DstBlock "Gain" + DstPort 1 + } + Branch { + ZOrder 10 + DstBlock "S-Function" + DstPort 4 + } + } + Line { + ZOrder 8 + SrcBlock "Constant" + SrcPort 1 + DstBlock "S-Function" + DstPort 5 + } + Line { + ZOrder 9 + SrcBlock "Gain" + SrcPort 1 + DstBlock "S-Function" + DstPort 6 + } + } + } + Block { + BlockType SubSystem + Name "Get Gravity Forces" + SID "1733" + Ports [2, 1] + Position [605, 200, 745, 300] + ZOrder 74 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 136 + $ClassName "Simulink.Mask" + Type "Gravity bias" + Description "This block compute the generalized bias forces due to the gravity\n\nParameter:\n- Explicit Gravity. I" + "f True, an additional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.81] is u" + "sed.\n\nAssuming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representin" + "g the homogenous transformation between\n the base frame and the world frame.\n- Joint configuration: Ve" + "ctor of size DoFs, representing the configuration \n of the joints.\n\nOutput:\n- Gravity: a D" + "ofs + 6 vector representing the torques due to the gravity.\n\nParameters:\n- Robot Port Name: Name of the ports ope" + "ned by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underly" + "ing Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface" + "\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Initialization "gravityInput = find_system(gcb, ...\n'LookUnderMasks', 'on', ...\n'FollowLinks', 'on', ...\n'Name'," + " 'Gravity');\n\nif explicitGravity\n if isempty(gravityInput)\n Simulink.Block.eval([gcb,'/S-Function']);\n" + " add_block('built-in/Inport',[gcb,'/Gravity']);\n add_line(gcb','Gravity/1','S-Function/7', 'autorouti" + "ng','on');\n end\nelse\n if ~isempty(gravityInput)\n delete_line(gcb','Gravity/1','S-Function/7');\n " + " delete_block(gravityInput);\n Simulink.Block.eval([gcb,'/S-Function']);\n end\nend\n" + SelfModifiable "on" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 137 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 138 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 139 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 140 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + Object { + $ObjectID 141 + Type "checkbox" + Name "explicitGravity" + Prompt "Explicit Gravity" + Value "off" + } + PropName "Parameters" + } + } + System { + Name "Get Gravity Forces" + Location [354, 32, 1634, 747] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "255" + SIDHighWatermark "1748" + Block { + BlockType Inport + Name "Base Pose" + SID "1733:1734" + Position [10, 38, 40, 52] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1733:1735" + Position [10, 68, 40, 82] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Constant + Name "Constant" + SID "1733:1744" + Position [0, 97, 55, 113] + ZOrder 32 + ShowName off + Value "zeros(6,1)" + } + Block { + BlockType Gain + Name "Gain" + SID "1733:1745" + Position [100, 120, 130, 150] + ZOrder 33 + ShowName off + Gain "0" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType S-Function + Name "S-Function" + SID "1733:1740" + Ports [6, 1] + Position [180, 24, 240, 216] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Gravity Torques" + SID "1733:1741" + Position [300, 113, 330, 127] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Gravity Torques" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Joint configuration" + SrcPort 1 + Points [41, 0] + Branch { + ZOrder 12 + Points [0, 60] + DstBlock "Gain" + DstPort 1 + } + Branch { + ZOrder 11 + DstBlock "S-Function" + DstPort 2 + } + } + Line { + ZOrder 8 + SrcBlock "Constant" + SrcPort 1 + Points [4, 0] + Branch { + ZOrder 10 + Points [0, 60] + DstBlock "S-Function" + DstPort 5 + } + Branch { + ZOrder 9 + DstBlock "S-Function" + DstPort 3 + } + } + Line { + ZOrder 13 + SrcBlock "Gain" + SrcPort 1 + Points [13, 0] + Branch { + ZOrder 15 + Points [0, 60] + DstBlock "S-Function" + DstPort 6 + } + Branch { + ZOrder 14 + DstBlock "S-Function" + DstPort 4 + } + } + } + } + Block { + BlockType S-Function + Name "Inverse Dynamics" + SID "1748" + Ports [6, 1] + Position [190, 199, 355, 331] + ZOrder 75 + FunctionName "WBToolbox" + Parameters "'InverseDynamics',robotName,localName,wbiFile,wbiList,explicitGravity" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 142 + $ClassName "Simulink.Mask" + Type "Inverse Dynamics" + Description "This block compute the inverse dynamics of the robot.\n\nParameter:\n- Explicit Gravity. If True, an a" + "dditional port (explicit Gravity) is added.\n Otherwise the vector [0; 0; -9.81] is used.\n\nAssu" + "ming DoFs is the number of degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homoge" + "nous transformation between\n the base frame and the world frame.\n- Joint configuration: Vector of size" + " DoFs, representing the configuration \n of the joints.\n- Base velocity: Vector of size 6 rep" + "resenting the linear and angular velocity\n of the base frame.\n- Joints velocity: Vector of size Do" + "Fs, representing the velocity \n of the joints.\n- Base acceleration: Vector of size 6 representin" + "g the linear and angular acceleration\n of the base frame.\n- Joints acceleration: Vector of size Do" + "Fs, representing the acceleration \n of the joints.\n- Gravity: Vector of size 3, denoting the acc" + "eleration vector w.r.t. the world frame.\n\n\nOutput:\n- Torques: a Dofs + 6 vector representing the corresponding t" + "orques required\n to achive the desired accelerations given the robot state\n\nParameters:\n- Robot Port N" + "ame: Name of the ports opened by the robot. (e.g. icub).\n Set an empty string ('') to use the nam" + "e specified in the \n Whole Body Interface configuration file.\n- Model Name: Prefix name of the p" + "orts opened by the underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration o" + "f the Whole Body Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Display "port_label('output', 1, 'Torques')\n\nport_label('input', 1, 'Base pose')\nport_label('input', 2, 'Joints" + " configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joints velocity')\nport_label('in" + "put', 5, 'Base acceleration')\nport_label('input', 6, 'Joints acceleration')\n\n\ngravity = get_param(gcb, 'explicit" + "Gravity');\nif(strcmp(gravity, 'on'))\n port_label('input', 7, 'Gravity')\nend\n" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 143 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + } + Object { + $ObjectID 144 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + } + Object { + $ObjectID 145 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + } + Object { + $ObjectID 146 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + } + Object { + $ObjectID 147 + Type "checkbox" + Name "explicitGravity" + Prompt "Explicit Gravity" + Value "off" + } + PropName "Parameters" + } + } + } + Block { + BlockType SubSystem + Name "Mass Matrix" + SID "1633" + Ports [2, 1] + Position [250, 104, 390, 171] + ZOrder 32 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 148 + $ClassName "Simulink.Mask" + Type "Mass Matrix" + Description "This block retrieves the robot mass matrix.\n\nAssuming DoFs is the number of degrees of freedom of th" + "e robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n the base " + "frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration \n " + " of the joints.\n\nOutput:\n- Mass Matrix: a (Dofs + 6) x (Dofs + 6) matrix representing the mass matrix " + "\n of the robot\n\nParameters:\n- Robot Port Name: Name of the ports opened by the robot. (e.g. icub)." + "\n Set an empty string ('') to use the name specified in the \n Whole Body Inter" + "face configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- W" + "BI filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Name: name of the" + " list of joints used to configure the Whole Body Interface\n" + Array { + Type "Simulink.MaskParameter" + Dimension 4 + Object { + $ObjectID 149 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 150 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 151 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 152 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + } + System { + Name "Mass Matrix" + Location [589, 68, 1869, 783] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "248" + Block { + BlockType Inport + Name "Base Pose" + SID "1634" + Position [20, 23, 50, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1635" + Position [20, 63, 50, 77] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1636" + Ports [2, 1] + Position [125, 37, 185, 68] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'MassMatrix',robotName,localName,wbiFile,wbiList" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Mass Matrix" + SID "1637" + Position [245, 48, 275, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Mass Matrix" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + Points [36, 0; 0, 15] + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Joint configuration" + SrcPort 1 + Points [33, 0; 0, -10] + DstBlock "S-Function" + DstPort 2 + } + } + } + } + } + Block { + BlockType SubSystem + Name "Jacobians" + SID "202" + Ports [] + Position [217, 20, 324, 127] + ZOrder -3 + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 153 + $ClassName "Simulink.Mask" + Display "image(imread('jacobian.png'))" + } + System { + Name "Jacobians" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "322" + Block { + BlockType SubSystem + Name "DotJ Nu" + SID "1683" + Ports [4, 1] + Position [590, 170, 755, 265] + ZOrder 67 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 154 + $ClassName "Simulink.Mask" + Type "DotJ Nu" + Description "This block computes the product between the time derivative of the\n Jacobian of the specified" + " frame and the state (base and joints)\n velocity vector.\n\nAssuming DoFs is the number of degrees of freedo" + "m of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n th" + "e the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configuration \n" + " of the joints.\n- Base velocity: Vector of size 6 representing the linear and angular velocit" + "y\n of the base frame.\n- Joints velocity: Vector of size DoFs, representing the velocity \n " + " of the joints.\n\nOutput:\n- dotJ nu: a 6-d vector representing the product between the time derivative o" + "f the\n Jacobian of the specified frame and the state velocity vector\n\nParameters:\n- Frame name: the name" + " of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opened by the robot" + ". (e.g. icub).\n Set an empty string ('') to use the name specified in the \n Wh" + "ole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body I" + "nterface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Nam" + "e: name of the list of joints used to configure the Whole Body Interface\n" + Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('dot J_{',escapedFrameN" + "ame,'} \\nu'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input'," + " 2, 'Joint configuration')\nport_label('input', 3, 'Base velocity')\nport_label('input', 4, 'Joint velocity')\n\ncle" + "ar escapedFrameName;" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 155 + Type "edit" + Name "frameName" + Prompt "Frame name" + Value "'frame'" + } + Object { + $ObjectID 156 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 157 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 158 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 159 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 160 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 161 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 162 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 163 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 164 + Prompt "Block parameters" + Object { + $PropName "DialogControls" + $ObjectID 165 + $ClassName "Simulink.dialog.parameter.Edit" + Name "frameName" + } + Name "Container8" + } + Object { + $ObjectID 166 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 167 + Name "robotName" + } + Object { + $ObjectID 168 + Name "localName" + } + Object { + $ObjectID 169 + Name "wbiFile" + } + Object { + $ObjectID 170 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "DotJ Nu" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "391" + Block { + BlockType Inport + Name "Base Pose" + SID "1684" + Position [20, 13, 50, 27] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1685" + Position [20, 43, 50, 57] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Base velocity" + SID "1686" + Position [20, 73, 50, 87] + ZOrder 26 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joints velocity" + SID "1687" + Position [20, 103, 50, 117] + ZOrder 27 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1688" + Ports [4, 1] + Position [125, 4, 190, 126] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'DotJNu',robotName,localName,wbiFile,wbiList,frameName" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "dotJ dotnu" + SID "1689" + Position [245, 43, 275, 57] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "S-Function" + SrcPort 1 + Points [20, 0; 0, -15] + DstBlock "dotJ dotnu" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "Base velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + ZOrder 5 + SrcBlock "Joints velocity" + SrcPort 1 + DstBlock "S-Function" + DstPort 4 + } + } + } + Block { + BlockType SubSystem + Name "Jacobian" + SID "1663" + Ports [2, 1] + Position [380, 190, 540, 245] + ZOrder 39 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 171 + $ClassName "Simulink.Mask" + Type "Jacobian" + Description "This block retrieves the Jacobian of the specified frame.\n\nAssuming DoFs is the number of degrees of" + " freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between\n " + " the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the configura" + "tion \n of the joints.\n\nOutput:\n- Jacobian: a 6x6+dofs matrix representing the Jacobian of\n" + " the specified frame written in the world frame.\n\nParameters:\n- Frame name: the name of the frame. It" + " should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opened by the robot. (e.g. icub).\n " + " Set an empty string ('') to use the name specified in the \n Whole Body Interfac" + "e configuration file.\n- Model Name: Prefix name of the ports opened by the underlying Whole Body Interface.\n- WBI " + "filename: name of the file containing the configuration of the Whole Body Interface\n- WBI List Name: name of the li" + "st of joints used to configure the Whole Body Interface\n" + Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world} J_{',escape" + "dFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input" + "', 2, 'Joint configuration')\n\nclear escapedFrameName;" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 172 + Type "edit" + Name "frameName" + Prompt "Frame name" + Value "'frame'" + } + Object { + $ObjectID 173 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 174 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 175 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 176 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 177 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 178 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 179 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 180 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 181 + Prompt "Block parameters" + Object { + $PropName "DialogControls" + $ObjectID 182 + $ClassName "Simulink.dialog.parameter.Edit" + Name "frameName" + } + Name "Container8" + } + Object { + $ObjectID 183 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 184 + Name "robotName" + } + Object { + $ObjectID 185 + Name "localName" + } + Object { + $ObjectID 186 + Name "wbiFile" + } + Object { + $ObjectID 187 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Jacobian" + Location [208, 105, 1008, 627] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "237" + Block { + BlockType Inport + Name "Base Pose" + SID "1664" + Position [20, 23, 50, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1665" + Position [20, 63, 50, 77] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1666" + Ports [2, 1] + Position [125, 37, 185, 68] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'Jacobian',robotName,localName,wbiFile,wbiList,frameName" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Forward Kinematics" + SID "1667" + Position [245, 48, 275, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Forward Kinematics" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + Points [36, 0; 0, 15] + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Joint configuration" + SrcPort 1 + Points [33, 0; 0, -10] + DstBlock "S-Function" + DstPort 2 + } + } + } + } + } + Block { + BlockType SubSystem + Name "Kinematics" + SID "176" + Ports [] + Position [70, 20, 177, 127] + ZOrder -17 + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 188 + $ClassName "Simulink.Mask" + Display "image(imread('forwardKinematics.png'))" + } + System { + Name "Kinematics" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "326" + Block { + BlockType SubSystem + Name "Forward Kinematics" + SID "1647" + Ports [2, 1] + Position [350, 103, 500, 167] + ZOrder 34 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 189 + $ClassName "Simulink.Mask" + Type "Forward Kinematics" + Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " + "degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" + "\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the" + " configuration \n of the joints.\n\nOutput:\n- Forward Kinematics: a 4x4 matrix representing t" + "he homogenous transformation between\n the specified frame and the world frame.\n\nParameters:\n- Frame " + "name: the name of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opene" + "d by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlyin" + "g Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n" + "- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Display "escapedFrameName = strrep(frameName, '_', '\\_');\nport_label('output', 1, strcat('{}^{world} H_{',escape" + "dFrameName,'}'), 'texmode','on')\n\nport_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\nport_label('input" + "', 2, 'Joint configuration')\n\nclear escapedFrameName;" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 190 + Type "edit" + Name "frameName" + Prompt "Frame name" + Value "'frame'" + } + Object { + $ObjectID 191 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 192 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 193 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 194 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 195 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 196 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 197 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 198 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 199 + Prompt "Block parameters" + Object { + $PropName "DialogControls" + $ObjectID 200 + $ClassName "Simulink.dialog.parameter.Edit" + Name "frameName" + } + Name "Container8" + } + Object { + $ObjectID 201 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 202 + Name "robotName" + } + Object { + $ObjectID 203 + Name "localName" + } + Object { + $ObjectID 204 + Name "wbiFile" + } + Object { + $ObjectID 205 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Forward Kinematics" + Location [0, 29, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "391" + Block { + BlockType Inport + Name "Base Pose" + SID "1648" + Position [20, 23, 50, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Joint configuration" + SID "1649" + Position [20, 63, 50, 77] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1650" + Ports [2, 1] + Position [125, 37, 185, 68] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'ForwardKinematics',robotName,localName,wbiFile,wbiList,frameName" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Forward Kinematics" + SID "1651" + Position [245, 48, 275, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Forward Kinematics" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Base Pose" + SrcPort 1 + Points [36, 0; 0, 15] + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Joint configuration" + SrcPort 1 + Points [33, 0; 0, -10] + DstBlock "S-Function" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "Inverse Kinematics" + SID "1754" + Ports [3, 2] + Position [350, 198, 525, 262] + ZOrder 35 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 206 + $ClassName "Simulink.Mask" + Type "Forward Kinematics" + Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " + "degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" + "\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the" + " configuration \n of the joints.\n\nOutput:\n- Forward Kinematics: a 4x4 matrix representing t" + "he homogenous transformation between\n the specified frame and the world frame.\n\nParameters:\n- Frame " + "name: the name of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opene" + "d by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlyin" + "g Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n" + "- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Display "escapedBaseFrameName = strrep(baseFrame, '_', '\\_');\nescapedEndEffFrameName = strrep(endEffFrame, '_', " + "'\\_');\n\n%port_label('output', 1, strcat('{}^{world} H_{',escapedFrameName,'}'), 'texmode','on')\n\n%port_label('i" + "nput', 1, '{}^{world} H_{base}', 'texmode','on')\n%port_label('input', 2, 'Joint configuration')\n\n%clear escapedFr" + "ameName;\n\n\n% if strcmp(robotPart, 'left')\n% prefix = 'l';\n% else\n% prefix = 'r';\n% end\n% \nport_labe" + "l('input', 1, strcat('{}^{',escapedBaseFrameName,'} H_{',escapedEndEffFrameName,'}^d'), 'texmode','on');\n\nport_lab" + "el('input', 2, '{}^{world} H_{base}', 'texmode','on')\nport_label('input', 3, 'q_j', 'texmode','on');\n% \n% \nport_" + "label('output', 1, '{}^{world} H_{base}^d', 'texmode','on')\nport_label('output', 2, 'q_j^d', 'texmode','on');\n\n" + Array { + Type "Simulink.MaskParameter" + Dimension 7 + Object { + $ObjectID 207 + Type "edit" + Name "baseFrame" + Prompt "Base Frame" + Value "'root_link'" + } + Object { + $ObjectID 208 + Type "edit" + Name "endEffFrame" + Prompt "End Effector frame" + Value "'l_sole'" + } + Object { + $ObjectID 209 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Full Constraint (Position and Orientation)" + Cell "Position only constraint" + PropName "TypeOptions" + } + Name "optOption" + Prompt "Optimization Option" + Value "Full Constraint (Position and Orientation)" + } + Object { + $ObjectID 210 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 211 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 212 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 213 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 214 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 215 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 216 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 217 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 218 + Prompt "Block parameters" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 3 + Object { + $ObjectID 219 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "baseFrame" + } + Object { + $ObjectID 220 + $ClassName "Simulink.dialog.parameter.Edit" + Name "endEffFrame" + } + Object { + $ObjectID 221 + $ClassName "Simulink.dialog.parameter.Popup" + Name "optOption" + } + PropName "DialogControls" + } + Name "Container8" + } + Object { + $ObjectID 222 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 223 + Name "robotName" + } + Object { + $ObjectID 224 + Name "localName" + } + Object { + $ObjectID 225 + Name "wbiFile" + } + Object { + $ObjectID 226 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Inverse Kinematics" + Location [0, 23, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "312" + Block { + BlockType Inport + Name "Desired frame pose" + SID "1759" + Position [10, 13, 40, 27] + ZOrder 26 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Current Base Pose" + SID "1755" + Position [10, 43, 40, 57] + ZOrder 22 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Current Joint configuration" + SID "1756" + Position [10, 73, 40, 87] + ZOrder 24 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1757" + Ports [3, 2] + Position [145, 4, 225, 96] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'InverseKinematics',robotName,localName,wbiFile,wbiList,baseFrame, endEffFrame,optOption" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Desired Base Pose" + SID "1758" + Position [280, 23, 310, 37] + ZOrder 25 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Desired Joint Configuration" + SID "1760" + Position [280, 68, 310, 82] + ZOrder 27 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Desired Base Pose" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "Current Base Pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "Current Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 3 + } + Line { + ZOrder 7 + SrcBlock "Desired frame pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "S-Function" + SrcPort 2 + DstBlock "Desired Joint Configuration" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Remote Inverse Kinematics" + SID "1761" + Ports [2, 1] + Position [560, 105, 720, 165] + ZOrder 66 + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var'" + ")\n WBT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWho" + "leBodyInterface.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\ne" + "nd" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 227 + $ClassName "Simulink.Mask" + Type "Forward Kinematics" + Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " + "degrees of freedom of the robot,\nInput:\n- Base pose: 4x4 matrix representing the homogenous transformation between" + "\n the the base frame and the world frame.\n- Joint configuration: Vector of size DoFs, representing the" + " configuration \n of the joints.\n\nOutput:\n- Forward Kinematics: a 4x4 matrix representing t" + "he homogenous transformation between\n the specified frame and the world frame.\n\nParameters:\n- Frame " + "name: the name of the frame. It should be specified in the URDF model.\n\n- Robot Port Name: Name of the ports opene" + "d by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the \n " + " Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by the underlyin" + "g Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole Body Interface\n" + "- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Display "disp(solverName)\n\n\n\n% escapedBaseFrameName = strrep(baseFrame, '_', '\\_');\n% escapedEndEffFrameName" + " = strrep(endEffFrame, '_', '\\_');\n% \n% %port_label('output', 1, strcat('{}^{world} H_{',escapedFrameName,'}'), '" + "texmode','on')\n% \n% %port_label('input', 1, '{}^{world} H_{base}', 'texmode','on')\n% %port_label('input', 2, 'Joi" + "nt configuration')\n% \n% %clear escapedFrameName;\n% \n% \n% % if strcmp(robotPart, 'left')\n% % prefix = 'l';\n" + "% % else\n% % prefix = 'r';\n% % end\n% % \n\nport_label('input', 1, 'H^d', 'texmode','on');\n% port_label('inpu" + "t', 1, strcat('{}^{',escapedBaseFrameName,'} H_{',escapedEndEffFrameName,'}^d'), 'texmode','on');\n% \n% port_label(" + "'input', 2, '{}^{world} H_{base}', 'texmode','on')\nport_label('input', 2, 'q_j(0)', 'texmode','on');\n% % \n% % \n%" + " port_label('output', 1, '{}^{world} H_{base}^d', 'texmode','on')\nport_label('output', 1, 'q_j^d', 'texmode','on');" + "\n\n" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 228 + Type "edit" + Name "solverName" + Prompt "Solver Name" + Value "'/cartesianSolver'" + } + Object { + $ObjectID 229 + Type "edit" + Name "dofs" + Prompt "#Dofs" + Value "12" + Tunable "off" + } + Object { + $ObjectID 230 + Type "popup" + Array { + Type "Cell" + Dimension 2 + Cell "Full Constraint (Position and Orientation)" + Cell "Position only constraint" + PropName "TypeOptions" + } + Name "optOption" + Prompt "Optimization Option" + Value "Full Constraint (Position and Orientation)" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 231 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 232 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 233 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 234 + $ClassName "Simulink.dialog.TabContainer" + Object { + $PropName "DialogControls" + $ObjectID 235 + $ClassName "Simulink.dialog.Tab" + Prompt "Block parameters" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 3 + Object { + $ObjectID 236 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "solverName" + } + Object { + $ObjectID 237 + $ClassName "Simulink.dialog.parameter.Edit" + Name "dofs" + } + Object { + $ObjectID 238 + $ClassName "Simulink.dialog.parameter.Popup" + Name "optOption" + } + PropName "DialogControls" + } + Name "Container8" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Remote Inverse Kinematics" + Location [853, 51, 2214, 1013] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "375" + Block { + BlockType Inport + Name "Desired frame pose" + SID "1762" + Position [10, 23, 40, 37] + ZOrder 26 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Current Joint configuration" + SID "1763" + Position [10, 68, 40, 82] + ZOrder 24 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType S-Function + Name "S-Function" + SID "1764" + Ports [2, 1] + Position [145, 6, 225, 99] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'RemoteInverseKinematics',solverName, dofs, optOption" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Desired Joint Configuration" + SID "1765" + Position [285, 48, 315, 62] + ZOrder 27 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Desired Joint Configuration" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Desired frame pose" + SrcPort 1 + DstBlock "S-Function" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Current Joint configuration" + SrcPort 1 + DstBlock "S-Function" + DstPort 2 + } + } + } + } + } + } + } + Block { + BlockType SubSystem + Name "wholeBodyStates" + SID "206" + Ports [] + Position [16, 17, 114, 114] + ZOrder -4 + ForegroundColor "white" + DropShadow on + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 239 + $ClassName "Simulink.Mask" + Display "image(imread('wholeBodyStates.png'),'center');" + } + System { + Name "wholeBodyStates" + Location [425, 373, 1725, 1134] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "576" + Block { + BlockType SubSystem + Name "Get Estimate" + SID "1671" + Ports [0, 1] + Position [360, 212, 440, 248] + ZOrder 53 + BackgroundColor "[0.513700, 0.851000, 0.670600]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 240 + $ClassName "Simulink.Mask" + Type "Get Estimate" + Description "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of " + "freedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParame" + "ters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports" + " opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the " + "\n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by t" + "he underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole B" + "ody Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Display "%disp(get_param(gcb,'estimateType'))\nport_label('output',1,get_param(gcb,'estimateType'))" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 241 + Type "popup" + Array { + Type "Cell" + Dimension 4 + Cell "Joints Position" + Cell "Joints Velocity" + Cell "Joints Acceleration" + Cell "Joints Torque" + PropName "TypeOptions" + } + Name "estimateType" + Prompt "Estimate Type" + Value "Joints Position" + Evaluate "off" + Callback "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param(gcb,'estima" + "teType');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0" + "]');\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]" + "');\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.8706, 0.1333, 1" + ".0]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]" + "');\nend\nclear maskStr" + } + Object { + $ObjectID 242 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 243 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 244 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 245 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 246 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 247 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 248 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 249 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 250 + Prompt "Block parameters" + Object { + $PropName "DialogControls" + $ObjectID 251 + $ClassName "Simulink.dialog.parameter.Popup" + Name "estimateType" + } + Name "Container8" + } + Object { + $ObjectID 252 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 253 + Name "robotName" + } + Object { + $ObjectID 254 + Name "localName" + } + Object { + $ObjectID 255 + Name "wbiFile" + } + Object { + $ObjectID 256 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Get Estimate" + Location [653, 318, 2086, 1271] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "1000" + Block { + BlockType S-Function + Name "S-Function" + SID "1672" + Ports [0, 1] + Position [125, 39, 185, 71] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'GetEstimate',robotName,localName,wbiFile,wbiList,estimateType" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Estimate" + SID "1673" + Position [210, 48, 240, 62] + ZOrder 25 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Estimate" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Get Limits" + SID "1690" + Ports [0, 2] + Position [475, 211, 570, 249] + ZOrder 68 + BackgroundColor "[0.513700, 0.851000, 0.670600]" + InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" + "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" + "ace.ini';\nend\nif ~exist('WBT_wbiList','var')\n WBT_wbiList = 'ROBOT_TORQUE_CONTROL_JOINTS';\nend" + RequestExecContextInheritance off + Variant off + Object { + $PropName "MaskObject" + $ObjectID 257 + $ClassName "Simulink.Mask" + Type "Get Estimate" + Description "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of " + "freedom of the robot,\nOutput:\n- References: Vector of size DoFs, representing the estimate requested.\n\nParame" + "ters:\n- Control Mode: The control mode. Choose one of the supplied mode.\n\n- Robot Port Name: Name of the ports" + " opened by the robot. (e.g. icub).\n Set an empty string ('') to use the name specified in the " + "\n Whole Body Interface configuration file.\n- Model Name: Prefix name of the ports opened by t" + "he underlying Whole Body Interface.\n- WBI filename: name of the file containing the configuration of the Whole B" + "ody Interface\n- WBI List Name: name of the list of joints used to configure the Whole Body Interface\n" + Display "disp(get_param(gcb,'limitsType'))\nport_label('output',1,'Min')\nport_label('output',2,'Max')" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 258 + Type "popup" + Array { + Type "Cell" + Dimension 1 + Cell "Position" + PropName "TypeOptions" + } + Name "limitsType" + Prompt "Limits Type" + Value "Position" + Evaluate "off" + Callback "% Get the mask parameter values. This is a cell\n% array of strings.\n\nmaskStr = get_param(gcb,'limits" + "Type');\nif strcmp(maskStr, 'Joints Position')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.8510, 0.6706, 1.0]'" + ");\nelseif strcmp(maskStr, 'Joints Velocity')\n set_param(gcb,'BackgroundColor', '[0.5137, 0.6745, 1.0000, 1.0]')" + ";\nelseif strcmp(maskStr, 'Joints Acceleration')\n set_param(gcb,'BackgroundColor', '[0.9255, 0.8706, 0.1333, 1.0" + "]');\nelseif strcmp(maskStr, 'Joints Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]')" + ";\nend\nclear maskStr" + } + Object { + $ObjectID 259 + Type "edit" + Name "robotName" + Prompt "Robot Port Name" + Value "WBT_robotName" + Tunable "off" + } + Object { + $ObjectID 260 + Type "edit" + Name "localName" + Prompt "Model Name" + Value "WBT_modelName" + Tunable "off" + } + Object { + $ObjectID 261 + Type "edit" + Name "wbiFile" + Prompt "WBI filename" + Value "WBT_wbiFilename" + Tunable "off" + } + Object { + $ObjectID 262 + Type "edit" + Name "wbiList" + Prompt "WBI list name" + Value "WBT_wbiList" + Tunable "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 263 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 264 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 265 + Prompt "Simulink:studio:ToolBarParametersMenu" + Object { + $PropName "DialogControls" + $ObjectID 266 + $ClassName "Simulink.dialog.TabContainer" + Array { + Type "Simulink.dialog.Tab" + Dimension 2 + Object { + $ObjectID 267 + Prompt "Block parameters" + Object { + $PropName "DialogControls" + $ObjectID 268 + $ClassName "Simulink.dialog.parameter.Popup" + Name "limitsType" + } + Name "Container8" + } + Object { + $ObjectID 269 + Prompt "WBI parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 4 + Object { + $ObjectID 270 + Name "robotName" + } + Object { + $ObjectID 271 + Name "localName" + } + Object { + $ObjectID 272 + Name "wbiFile" + } + Object { + $ObjectID 273 + Name "wbiList" + } + PropName "DialogControls" + } + Name "Container5" + } + PropName "DialogControls" + } + Name "Container4" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "Get Limits" + Location [0, 23, 1280, 744] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "411" + Block { + BlockType S-Function + Name "S-Function" + SID "1691" + Ports [0, 2] + Position [115, 33, 175, 102] + ZOrder 19 + FunctionName "WBToolbox" + Parameters "'GetLimits',robotName,localName,wbiFile,wbiList,limitsType" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + } + Block { + BlockType Outport + Name "Min" + SID "1692" + Position [220, 43, 250, 57] + ZOrder 25 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "Max" + SID "1693" + Position [220, 78, 250, 92] + ZOrder 26 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "S-Function" + SrcPort 1 + DstBlock "Min" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "S-Function" + SrcPort 2 + DstBlock "Max" + DstPort 1 + } + } + } + } + } + Annotation { + SID "1213" + Name "WHOLE BODY TOOLBOX" + Position [172, 149, 317, 165] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + ForegroundColor "white" + BackgroundColor "black" + ZOrder -1 + FontName "Sans Serif" + FontSize 12 + } + Annotation { + SID "1214" + Name "Copyright 2013-2016 iCub Facility Department, Istituto Italiano di Tecnologia\nThis software was s" + "upported by the FP7 EU Project CoDyCO (No. 600716 ICT 2011.2.1 Cognitive Systems and Robotics (b))\nhttp://www.c" + "odyco.eu" + Position [102, 184, 380, 204] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + ForegroundColor "white" + BackgroundColor "black" + ZOrder -2 + FontSize 5 + } + } +} +#Finite State Machines +# +# Stateflow 80000010 +# +# +Stateflow { + machine { + id 1 + name "WBToolboxLibrary_repository" + created "06-Feb-2014 11:51:26" + isLibrary 1 + sfVersion 80000010 + firstTarget 26 + } + chart { + id 2 + machine 1 + name "Utilities/holder\n/MATLAB Function" + windowPosition [1152 -205 -179 985] + viewLimits [0 156.75 0 153.75] + screen [1 1 3046 1050 1.25] + treeNode [0 3 0 0] + viewObj 2 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 9 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 1 + disableImplicitCasting 1 + eml { + name "fcn" + } + firstData 4 + firstTransition 8 + firstJunction 7 + } + state { + id 3 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 2 + treeNode [2 0 0 0] + superState SUBCHART + subviewer 2 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function s0 = fcn(s, ~)\npersistent state\n%#codegen\n\nif isempty(state)\n state = s;\nend\n\n" + "s0 = state;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 4 + ssIdNumber 7 + name "s" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [2 0 5] + } + data { + id 5 + ssIdNumber 8 + name "s0" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [2 4 6] + } + data { + id 6 + ssIdNumber 9 + name "unused" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [2 5 0] + } + junction { + id 7 + position [23.5747 49.5747 7] + chart 2 + subviewer 2 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [2 0 0] + } + transition { + id 8 + labelString "{eML_blk_kernel();}" + labelPosition [76.125 85.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 7 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 2 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 2 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [2 0 0] + } + instance { + id 9 + machine 1 + name "Utilities/holder\n/MATLAB Function" + chart 2 + } + chart { + id 10 + machine 1 + name "Utilities/DampPinv/Damped Pseudo Inverse" + windowPosition [699 -205 167 985] + viewLimits [0 156.75 0 153.75] + screen [1 1 3046 1050 1.25] + treeNode [0 11 0 0] + viewObj 10 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 6 + disableImplicitCasting 1 + eml { + name "fcn" + } + firstData 12 + firstTransition 16 + firstJunction 15 + } + state { + id 11 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 10 + treeNode [10 0 0 0] + superState SUBCHART + subviewer 10 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function DPinv = fcn(mat,sigma)\n% Economody size svd of mat\n[U,S,V] = svd(mat,'econ');\n% Damp" + "ed version of S with sigma\nS(S>sigma)=S(S>sigma)./((S(S>sigma)).^2+sigma^2);\n% Damped pseudoinverse\nDPinv = V" + "*pinv(S)*U';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 12 + ssIdNumber 4 + name "mat" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [10 0 13] + } + data { + id 13 + ssIdNumber 5 + name "DPinv" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [10 12 14] + } + data { + id 14 + ssIdNumber 8 + name "sigma" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [10 13 0] + } + junction { + id 15 + position [23.5747 49.5747 7] + chart 10 + subviewer 10 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [10 0 0] + } + transition { + id 16 + labelString "{eML_blk_kernel();}" + labelPosition [80.125 91.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 15 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 10 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 10 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [10 0 0] + } + instance { + id 17 + machine 1 + name "Utilities/DampPinv/Damped Pseudo Inverse" + chart 10 + } + chart { + id 18 + machine 1 + name "Utilities/TruncPinv/Truncated PseudoInverse" + windowPosition [649 -205 167 985] + viewLimits [0 156.75 0 153.75] + screen [1 1 3046 1050 1.25] + treeNode [0 19 0 0] + viewObj 18 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + chartFileNumber 7 + disableImplicitCasting 1 + eml { + name "fcn" + } + firstData 20 + firstTransition 24 + firstJunction 23 + } + state { + id 19 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 18 + treeNode [18 0 0 0] + superState SUBCHART + subviewer 18 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function TPinv = fcn(mat,tol)\n%#codegen\n[U,S,V] = svd(mat,'econ');\n% Setting to zero value\n%" + " Setting to 1/S(i,i) singular values greater than tol\n S(S>tol)=1./S(S>tol);\n TPinv = V*pinv(S)*U';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 20 + ssIdNumber 4 + name "mat" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [18 0 21] + } + data { + id 21 + ssIdNumber 5 + name "TPinv" + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [18 20 22] + } + data { + id 22 + ssIdNumber 8 + name "tol" + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + unit { + name "inherit" + } + } + dataType "Inherit: Same as Simulink" + linkNode [18 21 0] + } + junction { + id 23 + position [23.5747 49.5747 7] + chart 18 + subviewer 18 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + linkNode [18 0 0] + } + transition { + id 24 + labelString "{eML_blk_kernel();}" + labelPosition [80.125 91.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 23 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 18 + dataLimits [21.175 25.975 14.625 42.575] + subviewer 18 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + linkNode [18 0 0] + } + instance { + id 25 + machine 1 + name "Utilities/TruncPinv/Truncated PseudoInverse" + chart 18 + } + target { + id 26 + machine 1 + name "sfun" + description "Default Simulink S-Function Target." + linkNode [1 0 0] + } +} From ee56684801aa8bd7d12d4249aba3a4dd83915917 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 07:54:36 +0000 Subject: [PATCH 84/92] Avoid problems on streams due to system's locale Ref: https://github.com/robotology/idyntree/issues/288 --- toolbox/src/DiscreteFilter.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp index fb1b1874a..85ffda8bf 100644 --- a/toolbox/src/DiscreteFilter.cpp +++ b/toolbox/src/DiscreteFilter.cpp @@ -249,6 +249,11 @@ void DiscreteFilter::stringToYarpVector(const std::string str, Vector* v) // Convert the cleaned string to a yarp vector of floats std::istringstream sstrm(s); + + // Avoid problems that may arise due to system's locale + // https://github.com/robotology/idyntree/issues/288 + sstrm.imbue(std::locale::classic()); + float f; while (sstrm >> f) From 5737e5e434d02a038654ed40abd95f321461146c Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 08:07:43 +0000 Subject: [PATCH 85/92] Included support to console debug messages These messages are displayed in the console from which Matlab was launched --- toolbox/CMakeLists.txt | 1 + toolbox/include/base/debug.h | 20 ++++++++++++++++++++ 2 files changed, 21 insertions(+) create mode 100644 toolbox/include/base/debug.h diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index b89fdf5c6..b4c538673 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -54,6 +54,7 @@ configure_block(BLOCK_NAME "Base" src/base/Configuration.cpp src/base/RobotInterface.cpp HEADERS include/base/toolbox.h + include/base/debug.h include/base/Block.h include/base/BlockInformation.h include/base/WBBlock.h diff --git a/toolbox/include/base/debug.h b/toolbox/include/base/debug.h new file mode 100644 index 000000000..4fb7c1e7d --- /dev/null +++ b/toolbox/include/base/debug.h @@ -0,0 +1,20 @@ +#ifndef WBT_DEBUG_H +#define WBT_DEBUG_H + +// Debug messages to display in the console from which Matlab was launched +// NDEBUG is defined by CMake in Release and MinSizeRel +// https://gcc.gnu.org/onlinedocs/gcc-4.6.1/gcc/Variadic-Macros.html +#ifndef NDEBUG +#define DEBUG(fmt, ...) \ + fprintf(stderr, "[DEBUG]: %s:%d:%s(): " fmt "\n", __FILE__, __LINE__, __func__, ##__VA_ARGS__) +#define WARNING(fmt, ...) \ + fprintf(stderr, "[WARNING]: %s:%d:%s(): " fmt "\n", __FILE__, __LINE__, __func__, ##__VA_ARGS__) +#define ERROR(fmt, ...) \ + fprintf(stderr, "[ERROR]: %s:%d:%s(): " fmt "\n", __FILE__, __LINE__, __func__, ##__VA_ARGS__) +#else +#define DEBUG(fmt, ...) +#define WARNING(fmt, ...) +#define ERROR(fmt, ...) +#endif + +#endif /* WBT_DEBUG_H */ From 02382999355f080b5d11fcbd1b2262b7ae9aaf64 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 08:50:39 +0000 Subject: [PATCH 86/92] Minor indentation change --- toolbox/src/base/factory.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/toolbox/src/base/factory.cpp b/toolbox/src/base/factory.cpp index c78e4af68..ae829c685 100644 --- a/toolbox/src/base/factory.cpp +++ b/toolbox/src/base/factory.cpp @@ -42,8 +42,7 @@ Block* Block::instantiateBlockWithClassName(std::string blockClassName) #ifdef WBT_USES_ICUB else if (blockClassName == wbt::MinimumJerkTrajectoryGenerator::ClassName) { block = new wbt::MinimumJerkTrajectoryGenerator(); - } - else if (blockClassName == wbt::DiscreteFilter::ClassName) { + } else if (blockClassName == wbt::DiscreteFilter::ClassName) { block = new wbt::DiscreteFilter(); } #endif From 077d9863d142e6c9b9b79e698d31b0b5c0b434a6 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 11:54:49 +0000 Subject: [PATCH 87/92] DiscreteFilter: Included parameters for initializing input / output Kept as private variables only what is strictly required --- toolbox/include/DiscreteFilter.h | 9 +-- toolbox/src/DiscreteFilter.cpp | 114 ++++++++++++++++++++++--------- 2 files changed, 85 insertions(+), 38 deletions(-) diff --git a/toolbox/include/DiscreteFilter.h b/toolbox/include/DiscreteFilter.h index 234af3da9..098ca3966 100644 --- a/toolbox/include/DiscreteFilter.h +++ b/toolbox/include/DiscreteFilter.h @@ -23,13 +23,13 @@ namespace yarp { class wbt::DiscreteFilter : public wbt::Block { private: - bool firstRun; + unsigned inputSignalWidth; iCub::ctrl::IFilter* filter; - yarp::sig::Vector* num; - yarp::sig::Vector* den; + yarp::sig::Vector* y0; + yarp::sig::Vector* u0; yarp::sig::Vector* inputSignalVector; - static void stringToYarpVector(const std::string s, yarp::sig::Vector* v); + static void stringToYarpVector(const std::string s, yarp::sig::Vector& v); public: static std::string ClassName; @@ -40,6 +40,7 @@ class wbt::DiscreteFilter : public wbt::Block { virtual unsigned numberOfParameters(); virtual bool configureSizeAndPorts(BlockInformation* blockInfo, wbt::Error* error); virtual bool initialize(BlockInformation* blockInfo, wbt::Error* error); + virtual bool initializeInitialConditions(BlockInformation *blockInfo, wbt::Error *error); virtual bool terminate(BlockInformation* blockInfo, wbt::Error* error); virtual bool output(BlockInformation* blockInfo, wbt::Error* error); }; diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp index 85ffda8bf..0950dc573 100644 --- a/toolbox/src/DiscreteFilter.cpp +++ b/toolbox/src/DiscreteFilter.cpp @@ -17,6 +17,9 @@ #define PARAM_IDX_1LOWP_FC 4 // ::FirstOrderLowPassFilter cut frequency #define PARAM_IDX_1LOWP_TS 5 // ::FirstOrderLowPassFilter sampling time #define PARAM_IDX_MD_ORDER 6 // ::MedianFilter order +#define PARAM_IDX_INIT_Y0 7 // Output initialization +#define PARAM_IDX_INIT_U0 8 // ::Filter input initialization + // Inputs #define INPUT_IDX_SIGNAL 0 // Outputs @@ -30,15 +33,15 @@ using namespace yarp::sig; std::string DiscreteFilter::ClassName = "DiscreteFilter"; -DiscreteFilter::DiscreteFilter() : firstRun(true), filter(nullptr), inputSignalVector(nullptr) +DiscreteFilter::DiscreteFilter() : filter(nullptr), inputSignalVector(nullptr) { - num = new Vector(0); - den = new Vector(0); + y0 = new Vector(0); + u0 = new Vector(0); } unsigned DiscreteFilter::numberOfParameters() { - return 6; + return 8; } bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo, wbt::Error* error) @@ -92,6 +95,8 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) std::string filter_type; std::string num_coeff_str; std::string den_coeff_str; + std::string y0_str; + std::string u0_str; wbt::Data firstOrderLowPassFilter_fc; wbt::Data firstOrderLowPassFilter_ts; wbt::Data medianFilter_order; @@ -104,7 +109,9 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) // Get the string parameter if (!(blockInfo->getStringParameterAtIndex(PARAM_IDX_FLT_TYPE, filter_type) && blockInfo->getStringParameterAtIndex(PARAM_IDX_NUMCOEFF, num_coeff_str) - && blockInfo->getStringParameterAtIndex(PARAM_IDX_DENCOEFF, den_coeff_str))) { + && blockInfo->getStringParameterAtIndex(PARAM_IDX_DENCOEFF, den_coeff_str) + && blockInfo->getStringParameterAtIndex(PARAM_IDX_INIT_Y0, y0_str) + && blockInfo->getStringParameterAtIndex(PARAM_IDX_INIT_U0, u0_str))) { if (error) { error->message = ClassName + " Failed to parse string parameters."; } @@ -112,8 +119,12 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) } // Convert the strings from the Matlab syntax ("[1.0 2 3.33]") to yarp::sig::Vector + yarp::sig::Vector num(0); + yarp::sig::Vector den(0); stringToYarpVector(num_coeff_str, num); stringToYarpVector(den_coeff_str, den); + stringToYarpVector(y0_str, *y0); + stringToYarpVector(u0_str, *u0); // Create the filter object // ======================== @@ -121,13 +132,13 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) // Generic // ------- if (filter_type == "Generic") { - if (num->length() == 0 || den->length() == 0) { + if (num.length() == 0 || den.length() == 0) { if (error) { error->message = ClassName + " (Generic) Wrong coefficients size"; } return 1; } - filter = new Filter(*num, *den); + filter = new Filter(num, den); } // FirstOrderLowPassFilter // ----------------------- @@ -162,6 +173,31 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) return false; } + // Get the width of the input vector + inputSignalWidth = blockInfo->getInputPortWidth(INPUT_IDX_SIGNAL); + + // Check the initial conditions are properly sized + unsigned outputSignalWidth = blockInfo->getInputPortWidth(OUTPUT_IDX_SIGNAL); + unsigned y0Width = y0->length(); + unsigned u0Width = u0->length(); + + if (y0Width != outputSignalWidth) { + if (error) { + error->message = ClassName + " y0 and output signal sizes don't match"; + } + return false; + } + + if ((filter_type == "Generic") && (u0Width != inputSignalWidth)) { + if (error) { + error->message = ClassName + " (Generic) u0 and input signal sizes don't match"; + } + return false; + } + + // Allocate the input signal + inputSignalVector = new Vector(inputSignalWidth, 0.0); + return true; } @@ -175,19 +211,45 @@ bool DiscreteFilter::terminate(BlockInformation* blockInfo, wbt::Error* error) filter = nullptr; } - if (num) { - delete num; - num = nullptr; + if (inputSignalVector) { + delete inputSignalVector; + inputSignalVector = nullptr; } - if (den) { - delete den; - den = nullptr; + if (y0) { + delete y0; + y0 = nullptr; } - if (inputSignalVector) { - delete inputSignalVector; - inputSignalVector = nullptr; + if (u0) { + delete u0; + u0 = nullptr; + } + + return true; +} + +bool DiscreteFilter::initializeInitialConditions(BlockInformation* blockInfo, wbt::Error* error) +{ + // Reminder: this function is called when, during runtime, a block is disabled + // and enabled again. The method ::initialize instead is called just one time. + + // If the initial conditions for the output are not set, allocate a properly + // sized vector + if (*y0 == Vector(1, 0.0)) { + y0 = new Vector(inputSignalWidth, 0.0); + } + + // Initialize the filter. This is required because if the signal is not 1D, + // the default filter constructor initialize a wrongly sized y0 + // Moreover, the Filter class has a different constructor that handles the + // zero-gain case + Filter* filter_c = dynamic_cast(filter); + if (filter_c != nullptr) { + filter_c->init(*y0, *u0); + } + else { + filter->init(*y0); } return true; @@ -201,20 +263,6 @@ bool DiscreteFilter::output(BlockInformation* blockInfo, wbt::Error* error) Signal inputSignal = blockInfo->getInputPortSignal(INPUT_IDX_SIGNAL); Signal outputSignal = blockInfo->getOutputPortSignal(OUTPUT_IDX_SIGNAL); - unsigned inputSignalWidth = blockInfo->getInputPortWidth(INPUT_IDX_SIGNAL); - - // Allocate the memory for the input data - if (firstRun) { - // Allocate the input signal - inputSignalVector = new Vector(inputSignalWidth, 0.0); - - // Initialize the filter. This is required because if the signal is not 1D, - // the default filter constructor initialize a wrongly sized y0 - filter->init(Vector(inputSignalWidth)); - - firstRun = false; - } - // Copy the Signal to the data structure that the filter wants for (unsigned i = 0; i < inputSignalWidth; ++i) { (*inputSignalVector)[i] = inputSignal.get(i).doubleData(); @@ -229,10 +277,8 @@ bool DiscreteFilter::output(BlockInformation* blockInfo, wbt::Error* error) return true; } -void DiscreteFilter::stringToYarpVector(const std::string str, Vector* v) +void DiscreteFilter::stringToYarpVector(const std::string str, Vector& v) { - assert(v != nullptr); - std::string s = str; // Lambda expression used to remove "[]," carachters @@ -257,5 +303,5 @@ void DiscreteFilter::stringToYarpVector(const std::string str, Vector* v) float f; while (sstrm >> f) - v->push_back(f); + v.push_back(f); } From b8ba0fef91034b2f2e140abd46858abded1a28e7 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 11:58:35 +0000 Subject: [PATCH 88/92] Updated library WBToolboxLibrary.mdl: R2012A WBToolboxLibrary.slx: R2014B WBToolboxLibrary_repository.mdl: R2016B --- toolbox/WBToolboxLibrary.mdl | 107 ++-- toolbox/WBToolboxLibrary.slx | Bin 536459 -> 40109 bytes toolbox/WBToolboxLibrary_repository.mdl | 814 +++++++++++++++--------- 3 files changed, 572 insertions(+), 349 deletions(-) diff --git a/toolbox/WBToolboxLibrary.mdl b/toolbox/WBToolboxLibrary.mdl index 9d0e733f1..4df715224 100644 --- a/toolbox/WBToolboxLibrary.mdl +++ b/toolbox/WBToolboxLibrary.mdl @@ -8,15 +8,15 @@ Library { DisableAllScopes off FPTRunName "Run 1" MaxMDLFileLineLength 120 - Created "Thu Feb 06 02:21:39 2014" + Created "Thu Feb 06 01:21:39 2014" Creator "jorhabib" UpdateHistory "UpdateHistoryNever" ModifiedByFormat "%" LastModifiedBy "icub" ModifiedDateFormat "%" - LastModifiedDate "Fri Aug 11 07:02:44 2017" - RTWModifiedTimeStamp 424335764 - ModelVersionFormat "1.%" + LastModifiedDate "Fri Aug 11 12:52:09 2017" + RTWModifiedTimeStamp 424356729 + ModelVersionFormat "1.%" ConfigurationManager "none" SampleTimeColors off SampleTimeAnnotations off @@ -755,7 +755,7 @@ Library { } System { Name "WBToolboxLibrary" - Location [173, 232, 1453, 953] + Location [123, 132, 1403, 853] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -789,7 +789,7 @@ Library { MaskIconUnits "autoscale" System { Name "Utilities" - Location [173, 232, 1453, 953] + Location [447, 302, 1727, 1023] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -801,7 +801,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "166" + ZoomFactor "175" Block { BlockType SubSystem Name "DampPinv" @@ -917,20 +917,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "107::1618" + SID "107::1627" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 98 + ZOrder 107 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "107::1617" + SID "107::1626" Tag "Stateflow S-Function WBToolboxLibrary 6" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 97 + ZOrder 106 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -945,9 +945,9 @@ Library { Block { BlockType Terminator Name " Terminator " - SID "107::1619" + SID "107::1628" Position [460, 241, 480, 259] - ZOrder 99 + ZOrder 108 } Block { BlockType Outport @@ -1033,29 +1033,58 @@ Library { MaskHideContents off } Block { - BlockType Reference + BlockType S-Function Name "DiscreteFilter" SID "1772" Ports [1, 1] - Position [440, 260, 500, 290] - ZOrder 83 + Position [400, 245, 460, 275] + ZOrder 82 BackgroundColor "yellow" - LibraryVersion "1.386" - SourceBlock "WBToolboxLibrary/Utilities/DiscreteFilter" - SourceType "Discrete Filter" - filterType "Generic" - numCoeffs "[0]" - denCoeffs "[0]" - Fc "0" - Ts "0" - orderMedianFilter "0" + FunctionName "WBToolbox" + Parameters "'DiscreteFilter',filterType,numCoeffs,denCoeffs,Fc,Ts,orderMedianFilter,y0,u0" + SFunctionDeploymentMode off + EnableBusSupport off + MaskType "Discrete Filter" + MaskDescription "This block wraps the Filter, FirstOrderLowPassFilter, and MedianFilter from iCub::ctrl." + MaskPromptString "Type of the filter|Numerator Coefficients*|Denominator Coefficients*|Cut Frequency (Hz)|Samplin" + "g time (s)|Order|Define initial conditions|Output y0|Input u0" + MaskStyleString "popup(Generic|FirstOrderLowPassFilter|MedianFilter),edit,edit,edit,edit,edit,checkbox,edit,edit" + MaskVariables "filterType=@1;numCoeffs=@2;denCoeffs=@3;Fc=@4;Ts=@5;orderMedianFilter=@6;initStatus=@7;y0=@8;u0=@" + "9;" + MaskTunableValueString "on,on,on,on,on,on,on,on,on" + MaskCallbackString "% From: https://it.mathworks.com/help/simulink/slref/simulink.mask-class.html\nfilterType = g" + "et_param(gcb, 'filterType');\ninitStatus = get_param(gcb, 'initStatus');\np = Simulink.Mask.get(gcbh);\nhowToCoeffs" + " = p.getDialogControl('howToCoeffs');\n\n%set_param(gcb, 'initStatus','off');\nif (strcmp(initStatus,'on'))\n vi" + "s_init = 'on';\nelse\n vis_init = 'off';\nend\n\nif(strcmp(filterType, 'Generic'))\n set_param(gcb, 'MaskVisi" + "bilities',{'on','on','on','off','off','off','on',vis_init,vis_init});\n howToCoeffs.Visible = 'on';\nelseif(strc" + "mp(filterType, 'FirstOrderLowPassFilter'))\n set_param(gcb, 'MaskVisibilities',{'on','off','off','on','on','off'" + ",'on',vis_init,'off'});\n howToCoeffs.Visible = 'off';\nelseif(strcmp(filterType, 'MedianFilter'))\n set_para" + "m(gcb, 'MaskVisibilities',{'on','off','off','off','off','on','on',vis_init,'off'});\n howToCoeffs.Visible = 'off" + "';\nend\n\nclear filterType initStatus p howToCoeffs vis_init;||||||initStatus = get_param(gcb, 'initStatus');\nv" + "isibilities = get_param(gcb, 'MaskVisibilities');\nfilterType = get_param(gcb, 'filterType');\n\nif (strcmp(initS" + "tatus,'off'))\n visibilities{8} = 'off';\n visibilities{9} = 'off';\nelseif (strcmp(initStatus,'on'))\n vi" + "sibilities{8} = 'on';\n if (strcmp(filterType,'Generic'))\n visibilities{9} = 'on';\n end\nend\n\nset_" + "param(gcb, 'MaskVisibilities', visibilities);\n\nclear initStatus visibilities filterType;||" + MaskEnableString "on,on,on,on,on,on,on,on,on" + MaskVisibilityString "on,on,on,off,off,off,on,off,off" + MaskToolTipString "on,on,on,on,on,on,on,on,on" + MaskInitialization "filterType = get_param(gcb, 'filterType');\nnumCoeffs = mat2str(numCoeffs);\ndenCoeffs = ma" + "t2str(denCoeffs);\n\ninitStatus = get_param(gcb, 'initStatus');\n\nif (strcmp(initStatus,'on'))\n y0 = mat2str(y" + "0);\n u0 = mat2str(u0);\nelse\n y0 = 'none';\n u0 = 'none';\nend\n\nclear initStatus" + MaskDisplay "disp('Filter')" + MaskIconFrame on + MaskIconOpaque on + MaskIconRotate "none" + MaskPortRotate "default" + MaskIconUnits "autoscale" + MaskValueString "Generic|[0]|[0]|0|0|0|off|[0]|[0]" } Block { BlockType S-Function Name "DoFs converter" SID "1771" Ports [1, 5] - Position [240, 241, 385, 309] + Position [160, 226, 305, 294] ZOrder 81 InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" @@ -1124,7 +1153,7 @@ Library { "else\n visibility{2} = 'on';\n visibility{4} = 'off';\nend\nset_param(gcb, 'MaskVisibilities',visibility);\nc" "lear externalSettlingTime||||||" MaskEnableString "on,on,on,on,on,on,on" - MaskVisibilityString "on,on,on,on,on,on,off" + MaskVisibilityString "on,on,on,off,on,on,off" MaskToolTipString "on,on,on,on,on,on,on" MaskDisplay "firstDer = get_param(gcb, 'firstDerivatives');\nsecondDer = get_param(gcb, 'secondDerivatives');\ni" "nitialValues = get_param(gcb, 'explicitInitialValue');\nexternalSettlingTimeParam = get_param(gcb, 'externalSettlin" @@ -1322,20 +1351,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "112::1609" + SID "112::1618" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 98 + ZOrder 107 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "112::1608" + SID "112::1617" Tag "Stateflow S-Function WBToolboxLibrary 7" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 97 + ZOrder 106 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -1350,9 +1379,9 @@ Library { Block { BlockType Terminator Name " Terminator " - SID "112::1610" + SID "112::1619" Position [460, 241, 480, 259] - ZOrder 99 + ZOrder 108 } Block { BlockType Outport @@ -1780,20 +1809,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "1300::1609" + SID "1300::1618" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 86 + ZOrder 95 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "1300::1608" + SID "1300::1617" Tag "Stateflow S-Function WBToolboxLibrary 1" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 85 + ZOrder 94 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -1808,9 +1837,9 @@ Library { Block { BlockType Terminator Name " Terminator " - SID "1300::1610" + SID "1300::1619" Position [460, 241, 480, 259] - ZOrder 87 + ZOrder 96 } Block { BlockType Outport diff --git a/toolbox/WBToolboxLibrary.slx b/toolbox/WBToolboxLibrary.slx index 63ee8648630abdd844422f49136f288b536344ed..9264c236b79d3af71920758d00a60c8e8e9bf57b 100644 GIT binary patch delta 27648 zcmV)6K*+y~-yp5I0uxY60|XQR000O8k7f%?PE>w&W|0#pf6H#dFcAEe$oIr?QYcu# zNNvRlq^hNA)tloi;5M-%+dT63&4Z*Aq2BD7@$Bq+lliI0y#p94wVELkgvbLWbSBky zhThf-e}X*gxXO6070gft7I|})h>{9z;MwRBjFVu!+DKU{${E@@S5l0v*g?T&WIHI#=8K-ZP&+V%y(w;)L3y%rP#urQ;25{MIzPc5tL1CksxMVDDgmgQ4|lNDreaH( z8g8ltUxLZGI28tJEc5CTw2R&|@A2c)dVyFJk~=?)fBbN~4hfA2ji;XpzIxvnc4uwa zmo__|%Cu1pV3R55)~)K_-AKqDDkjA~ZDU>GL%8CM{h#jM4<|k$YZB2>L}PN1t~Y3_ z8#u^j(HIHh>8LF{Kn;K1L-x{i+y(2QZg_t-j{N{oO9KQH000080FP!1OL3ySY{mcp z07n4;lePi!0*_{sssh>)k7f%?;#-VHv}gbTWu^lF8332NEeIQb?R|N7+c>iC|Nay_ zp6Nc$jH75@+-cwAwc~zv>}NThcc*7=4lP15Clsk6DK9-|?q`2h0JsArNG(wk-7_~W zOIQnqLZRx1s<;33Jhik(;(DfI|Ge9%)ps>wj~v6aCqM7b{qgJm?tdNbyuES^VqMr{ z$DQgv6xDu*LG(>9zZ4=KK@vEMIFf!Mp+iKTlUpT0SrTc-WF zc6=Hy&sr6=D`~YUZk3fzG#Q)Mg?BXa%}2uP{=92B6LX|nFt>1K$#r!`ly$-ihBF5e z?;if%Zue?`^?j{XZ{mL%&3+yK+iL=A{Ug~{W=51Rk6oA)ansXkiKmsR615*2?Qf=M z;^;E7t0zVjXBpts8^<#fa~uKZ?;c)~u`jFk(KLV|g7T*Ax0<_$9ceG`h&g%i)yo6p z!M;nEA0)~8h7m1~&}Yvx%W;W&tY_%l7SlOhqa2xk8|6o6n7-p?n7bnx9W5;%m@0cG z=0cvJUn;ng>mT$woZovdo~-_*qZ=qLFHTd{8-u2-&e^k1Y~Rc7sYbKe#a+~C_0qd2 zR{d{|Gd%~%?6{d08ns?WR_%H`_J}X&v|j7B+RaX*IjHx0y?(p7uXQtEH*o`B$w4ImQCa1xD8VjRDm z(^GBt@P{8Q|EHt5@BBFNf6A+J3e785y1n}t)Wh>;=Q?czhOj`ea&%+m7Q7>#f8&6E zIKLRN`3uKDn}jLp)-CZIYmUPxtblS1j>g<#KvH5{y9RNkqda>iBibRbq)(pdKns^t zcg;U2KP5R!I@T-Q{XCz^N>J?)KhotlXVUIz!5dIgrvy$*PpLRC%g8lnIK-jv!j3Ac zb>}$Nu`cBo5Dfm@%PGKh7DlRYPs!PTgqH_i{rtg(mAcZsbm_NmL^9zmJ+CP7<-#H? zg2HO|&_*$3iH32b&pj$Epzn^T!29|1p19ZJp-*OB@_dcDv-O$x;P}V$@fb*8{(&b{ zJ+I^iFrE8I4{Tw%pw~;?^Mg8GQoW0buo!1vc@vzjO@xzmow12$p=3=ck9~B1+|S-j zACaLmcSlh8>gewB=s5g3wmh@_$U|y2=FIKLHrP&PxPiI@BE!V1-Uc>S;7hmxgN^F5jY}r&)pJZPGu=* zAUPGzY&=~~=8SfaB&R46AS!r&=Y)&!n|vekYC{;crCufKh0QsSGOWb4P4`Ytn^aMN z%PgDl?%}nxMN|}BI0w$IE`!23TyZ|Ki%T6lbK3wZbae0CITpQp!~cnQTdepkv4Y}_ zdi<)MEdGHBjc6O^4A<9PpWpwbMVwi>#M?L7P4qUP6H-=ir1|*$vF?w59+=pZo_(|+ zqv5&b=y@E@3*Wisgc&`ix;+=m(pb?Vu^TITL%B^TS7W8lEV^fR4|V&cpy=t`Wmoyb zhGYQ+g(EWPpu-kadgoXM-Q$I=6RJ=a77LWH-9s0yoc5%k{3YBPto&w=+|dJUW)(i* zO8d1<;P94jd|nz#!f-!-J`nrJofbB27(+M{&F4FZiJ#okA6?T&qZUdbb_Zr(scJGyLI0N@{zd2 zhT~SM%%CQjC`wNoegn%@S_RcEuG30Z-Z1zTmv0jIE$rsVb@i8jn1Lf*5N`b_FMi&A zr`rbFP{RAr&%2GkG~z}(ZY+tcBE8+X1-H?zNsMKzPv|UZCCLtLIs=W!E*R4w(TZqX zeZ_GN9SfA3lao|~Np(6r6l!VnSgK@jHZ%%K1}9xgfMv>^o6p2Rb+)+Zg>Cw#ZmAW% z(w{+Xy)tdCD!)#D+oIB?`3)^?$Vn9Y+vx5Ajo~11i$?(b;L&T{Bl+8jhr{P13$mTRJa#pZSHvR6mxsGyiZ+PN&p z3bK2LV&Px)k#leAHe5s=90N@XuF6gvKIk)Y1MCe-BnfLp-kscyL0sp=bv!Su2RbQw zF|0s>E7d--CJr3C4{(&fcWm9zXUGq^V#b;fxZj&2G&2Q6y>sWDe@iB2;+&LF>lP;L zGg9pyp2H1)H?InFT08=oOdRNo(5#akB-LqvuKq2Y%6G1AA6uV`StMp-v_06^CTg4? z>{0Mn!X}uh&O5w2W~`4|2AX%Z8PFO12${NB#{vB|bM6cj&mB~pF0S*=ol`P0r-61{ zAlIn6a$(QrK!e}?eQlmL)F&#On>HR4Ky9{jp6M5VN{0*7f%5#%yc(D0)TG8zYFkX3 z-ZI5O#>ER4iE{LCq^4cKFIXcvi$Vr_BoU#Milg#k5uaBxrzJY#wt1=!TOhZY*vxWY+>^owj`&(1tof>OUuSlTZr%?1&be<>)RSSD7* z0;(3&iq?x&F}$hLxUOeRcENQ8q%r%BT5pT1awG5Wxl&BLB3u{9A0Qi&NUW-g`9@t) z&Lb73+~6yc_UQ`{*C-79CcFck5V+SSZ$SNjOjCFRgmOub@3G@pM7O;o@7VOmCb0}4 zKNeG}eFL9w$=u__J#r_|&|>w&D?*88Py-6@uKe~5xEqx2tBR~^??f;b`POWj$$DTv;bn7+{yi(_(RK?(bIVD za|P!Z)-u(<{Pnk;kZqX#JWi{;$wkxi?3GOR+0 z!3}+vg5}~|p5MjU^9-aElE}pYDq9;UL0BvzJ1> znwE;$WxBZ*523){Jp>8@<>oHY++dy5$ahL+{sX-V>>f57?Owaz>b86NdOBQxiz%N* zDptN?=2%v2e)$#v)W(4B9#K%;a4V~pWe_jgJRA0zJ)iPz#+LOxb=YZm08J7wqD)&k zr(F>(a*nuSfouBbmhTBWda`4?_}*xaK}zd?Fdx&-ElBNtApRJn;KF_&uIX!I*O_Xt0uz#}kVeuB zw|3y*EEH_!6c0JmB5qvGEIjRwMk9&}yLUWtJU4OMh^U~f3pZ449^`&bFA{lXkK4N& z5Hcp5g#8_phlM2?vNB6m@Ta~Kg4fvz! zKLmFtie@TXIRtIN{w>!6UEAT1TbG#pr*-ppZ&GpOwfPo4C7~Fl8_68yAMzkySQSuU zee=`>ZP=dBQ`AGXyO`^L=p52OJJ^Wy^oUQXK&KNmb33;|I1%+$(m=yXW^;zb`u$Q@t9M$6>u9nuOIrNRFuK;nMMx zkBqSP-5f4+rUfg1QKmXox~bo*+@Pa+2^y(a%TBhaE*;=7Z5~mqYLgM%BS90!dj1RA zbT}Io)%}g&TNK9bSc$2piroGP=df`;vQKo&LhO+mBk>9s_Ur=GQiJf*k5*<^_9M$W z@;)l-`uhsZQgxI!On^Ivlc;m51F8WSGRJ$BPcEQiuGZykrKPLAu}l7G!jmxPU} zX~iD;s4FQyNu1clwVF1Ps6@|3;A9^Sd+#Yalw$L!DTp2>-kfO!DhF+%X?|G@c^mim zgp?g1%&KgE10U?qHk>J_kvt6N%J++8zud`+_t>!G(v1vXruUA8zf^C7;+ft%xChY^ z?5QX&fzuyv6%Qzi6jcxA%ci!au|6Wf`X|IwiH5E%1Mim>(LJKJckzC7VbjYyb9pOw ziSG@3*m+D4V?Pv=n+vIc;`reRF*du0NT(y)xFs`x-OL>%EC$r%R{1-Zz)X!J557{6 zGt4v}SIrB}3+Er~xyKGw7~a_*xk*wWZf98o?2@4KOQF=wnlEiL3KNN|jQV;)M7)8LG)&Wiw(^ z(Tw;`cMTXV$+IGYo?slC{tah_ z_x0l~T6OOngaH~9;gJgg#Cm72cXXTJ6WI@TXp1YV_0e$+X67%Z#qhx#`?nZs0mgWQ z@XaE-Af*FeebJi`VTE@ePsyV>;?Aa4^Yy*yYrhbixcR2TJL;NH-YN0oN_!<eJ#^871Lx_AgdPxT?y>b4&4fPH71_ zhctVKl`PLj3X6O(2JP*7j1e-f-2i}ppj)sP>`AdJL)2)frW9T_n7Iaxbe2V|)XOY% zm=+@f#Fgpwv+qLT7?P*}#ZZM44nQ*aRL)R4M9*?oxIxdE-xJ5Jy0_KHcLl1+_tO zx|q&rXc836a2b_wQvL$swR%2(%Q%cd?#X?V+_`{qbV;&!$xd@R8g3kmqx|EbjV* zTJ?q(mp2!e)Mi%=c0GLYe8NwOa~kJm;`%k;%D=2#p0Gz1AdT|M{en;C4RUQ;FNM8WlT7%$>8`Q-Xf1&y=SfU-P7O@RV4`V3lEP>rtNk!?`Ok3LesR^E{*taiLZ zAk`;>83;f5)BN+@@hHxdjusey@Xkm#Z76>(i2jqE9*YtLj8RO+%M*&fQz{JEu(0atD(qkLZzxwt#OrFpg<{C<7$&~`HZqus%Azp zQIT+!Fx*&=%fxK$0{wu0Sx5|vIgmI4yr91!Xg_#(Q>%gR@y9!{hZl`{Q)m;d7~!QU zx|?J##$Dy`GoW?MW`gUJaFD83sAfmlp7+Q|75JS)H>kMXn5ecd^>+72j|Ag3aL0T&#t2e1o@O6C>#j zQn`U6cd}R;$JXbI>jjB9oh`f|SNh16T6ZK(+>(DGY9!|swWMP3*6qT;7@=d6EIN2J z<1W0KAAD14;K^-&0j@gko%5OSFu?LQB-RD`Q*dC@Sf^B8faYXcfuNQtB#F9_N)uKR zU62xWc-f)z~5G4x# zQffb5fj>o}@iP^wV&uRx3lu*aZ7UR8H&v~BJ;OzI+??2d>oOwZ@^X`kGE)i8UbTAX zWoslf1l1`8(DX8Ffv-TqL@b3HL~;P`9{&0E&+q?yRkA+w7(>O|KVJ#oi|19QhaRn6 zwp*ZTFyKF*m#+)Q-0q?4|M{Xq*Yt$L+V`KT(2E{!mF7&(w2I4whXL(WWCTc5Oly`> zdrYEMN+VQ%tCZG4)oP_K4vHH~cwHzZFldiujv}`ISxod&JqF>v`Mp}bVpb6WRUh$D zM2u}oRZgnqyN8!1Mw_%mcEv=^NO4jcB{QYovctx}?{a1*c5TvMa^0KU^PTi?sz!ew= zzI8(*7?^{iP+0imk}aIw-m%?5t&_S9geu!aKwb8N5gNRr*7r(np!OHONhmuIs_f$< z-@prq!7Cj8$_$^}&~SbjW~Zz&e{)0sW(rcJCY0T!viftEST7tvSm9#D*^LD>lth*) zs(f^RPv39TN2*o3$IK6NXYN&KBj6E)H;u|~xLY!HFu{UHeB_U^`{dd5@R3$vH7&gW zta~oq@&}-D8RU-Uk$q|2V_bgE{N#_VPn5?#`O~M`R2Ri35wrmfurTpL6SJVgjY}hO zLA@|kw>r_C{{p|BW0yc1b35W zM+DMNRLj<>w?$C!^g7W!c0RYPcSL8=ehbwz;R#U6E|HY`YL~SnDm9SHD&qwe8xC)O zsLTDpC8}cK>zPjECk%S6>B6Yj>G|J>!9N+?7xfmU72|c; zU4_L_r6^#<%R^SzQM&@%-kqDS=d;Mt5yh2k2uO0&j7|xfWGL!iao1QBY?4hmJu58j)9tPy`hjI&g|shrU4C47T31QG2L#IMVPWNG6N zyro1WsCsVNrmsYyr2eBMB+?pJnFUNLIwb~}x(}4782~VbG+1(O7|G;3scrHB^dgU^ zwt4SNCE>%9OR7_ih+%RS>#&P_cu_oe+^f?e+bW@-JeJ90?BlaQcKG8}GEq{0>3~qW z4ybXk;1Zy+JSZ+LQ>H8mcyn}A zwhPoFa=<(VJq5`F>veIodSQ<)DBlbiqFUvOJTojHdGdD$bvq@ufr?@li@oR6!Gs7TaCaWEtN#UVL)03hbg3R_Zv z`aofZnxy=jW1LfahoDu1TH`2KeAYYtUbO8*iz8?>MTrC+G}UIz89;Rz_)}|gL*cY6 zl$x|OZSuyQV)-Be{Gs-{Hj}U&DI{e2u-AP$w2b7W-Q>6TmR)9fc!z8!H~NgY*RC0X zGA+2kdn1$m9U*_CheW!9$iQHt%^8bcfwp0y=Jk8M)}bfCzLxjtA34oU$Z(`vM3%W0 zGf+br9v#-qNdQfC8J@NGH`C)ml9Y;nG!1t97w5zsxdas&3$s<2F(sIwzk3BN5qzFGC1NWC_h$sY8r+mT+c7WBb&GMG|d6cdw&P2;E{I%;`lS# zM(_2}=k$L<$`qEe1W6j(bR~F|%dl<{HM#@idH_Z1-S+ z>zV$qxwORX+@_(@9h%qvmKd%s=OJ3eVJVcPiM}yB952HkHOZRd#}b}!9v&1if@P^g z2^NLYlu_>NQMcxL#wrpWP4ggqv+(Elm^BSwV#t4Kz+L0g0vKjm^i(b7l{aKVpa-0M zg!mlj&P>L?XY`T~haFjR%F&-S`Y+dL+3T4|6$_;d->s$y2Nu)RV|m^ZGK5LvoR0Y& zT-5h(u&kL3M==46;W62*t#O*U!bkfGP4uDFh8gU&d)-U9A;R+4bN>o$`KioJiQh5J zNzQ-o0S;^EyI~mp11%9x|3`i1cs~WR*N}q=`%c{IB~XlOR?=070_tWX{YN5;hM5WEqE@uBr(`;R7A?yXEfuIQ|sdmuDfka1z=>7pV2 zLY+3*hS~QLzN6P{yhd<-=c&S9Kbaoc`#*oRzsz4rNQ#`A%UP^M9&gbSV(!9l%$knD zD`u(0VXNnCg}znz_trKrP3P|6x#grR7BL>D5#I;~AW1}YE)W2GTO^VM7xKr2&CFba zg~())&oFpkgGKEoXVNQMluS0*Qfq->URnMekGZUJ$|5mBV@Ng=b4;GQ+*BV9v*cfj z#mi6&AG-|8r z&Y2^>h$VS2-YPt~WwS5NW(?1HJx=7=;A+k(eBn&;BnoEu4ZwoChYyo@Asl~5jzzfU zTKdc*Jb$-kX-2rl`89wSr0hOv@n$8#nou+qK+y?174 z-RANAgX3;~?{ON*?-;azisZb#`^XA2FH{CZ5-)f@q6`BnzgJY!w1`U4fVo1SGR7s` zJ$!Ub;}iaqUyJ59Au}B}6>jmo?Rod{3J5|*SQjNPf|XLq)3VXz#MNebdeI8CagZ^0 zcBT4}m7`Mi(ArR<|Diek%_KAqH4Pz|XJX)z7DbzDB1h#W6Oh(Bn!yo8JdE54TkrjR zis5CkfTTXlY8nXC5ICgPd1!}|Zd~2_{4PkeA$+M3lb4}5LmcV*Gn4ruDu0o^tlW)$ zI2Q_d6y(DP9Vv$q%ypJKC`WaGf&TTc8>g@wfpC{x|AQU(XzH5DH?ro=EyPtq4uA!}x4LbhRc~Kwcadm~wxr76u3ZZ4mT4;)4_(^t7C%zr zo;L}PVYVFN`7tGnZxP+jJ?6N?6qMjVn+TeMX9rKk6NBG0>ynVhP=7jsQAyidcaumJ zbE;3so;d~aZtO9gd>$-bZDvo{SFcjHx(o~@#q%=0Z?|CyTXkH*UK2hx>djViB@388 z$*FM{e|8}yTcy!UCtg-y=u?m-H>Uj<@N>PL0s>`t8t0gvnwYoS6fM&MG0>^wr$H~L zo`k^@Wirm?-|Mx0yMNEY9gSwc-tOb4Rv)p(;# zd81(s5zZ^rg-|z3ZX;rt;#WywB`SoIm3&7GD~@Yw)0v;Db>~>1`HAzIC+LsnrexIy zc`XclC5HTozs+v+M7Occ4&2rp06zo2?Q6YuJIiPan>|seaDT%mN+&kG5cVo{1@IQ8 zx*u+MQTQy;ZtlQjaWCVfyMmpZ9HM+TC(5B>8^~|^;!?Bc(|a+rF{#|BPSrCfQ$3t) zx5Q)ze6o$Y@@z%f22vt4ZGKz}NrYmb7}||T=7s~xHzsE!A(eXhRLVOCWCU&C3DAOF z(?nt2XckosNq;KZ*YR!1UIlW%F6@VzFy%w6289z-z&*u3qpDq_kZ^Qo)coL6!OU`P zVv%^31j8&alZnCni=1AG`iYx3d*7j*=e^`nJNsx!u@p@%S^T;HiZ7}L%^t8utJljY zO_|zx@-#V16`7i-Q7l)J9c1ql-KO-tW(kShJ2()*v40bt$F^3J%BTiV5f`3{_Z1}SbjqAPQ!XdOq`c9?{wPK#0fMlW5CQUYxVvrcx z9cK0mPk#(8YFqnwjQF;D=b4{Hn(U#s_z-QDTZ9HvNrIJVbjvM*!q`$Su<<8vJeNH$ zOHC>CZ8epq6|Tl9nOV*YdRvQLoy8AwYGXwZ6?;xuR1J!Ve@ac_J>9N(dp&*oIXuNH zv`TSwD#gO=<-Sc$RE%Z3#VSAMy|LPojpQbwh7nHUJFkg_|R9j@T5)bsd7s&-bkpHIr|Fk_-u9a z)-|)HGASfpN!5WCm}3GqEHO~&23l;OEq|qf=1F)VMO6nX+7|*IQMu*-2aa6gV;mf` z`18Hd>!lMqDBcN$dJesTpzVffaJ@WtODLAIydd}Oybw%^DX);cri7QUoYBVsKFs@< zq!asYe@y>C((c3FJ#ol*?Cl$9Nur<5NBei)zJn9GBA5=BRo;K8@6QGA+ACdkN`GE) zl$}npY_US8Q;t(8pqs|#p69EG$3RHAdmc=WWh~X6Tz%$g{zK5x;Gi!@AKDAQ3>um z{%I%V5Dh9#b-(HP?q2vM6bKn7UVk9`5(?~KKqM9%OV)2xBJ6j^9BX^f)Mz@}i+34FZ7KE-Nfe z`l(@^He!x26qEOtDks(N64P8MvWb0TDLUK)CZlT|`K+ zlerJN2%<^s(TleC?thQMnA{>#6#^xK=pe~z)stStC@gk0t$@OJ)p#;^SgZM<$b+)- z)e%^9KUxWaGZvLf^rlM3S4QJjy)=zSm_1fx>?)>n?)|)&z$`-&J*`2##~_ycWmFZS ztHkgX-=SjKf>z=R^B7a1WYxr~7F3QYE7Cp%cdh(eN_d+IuYW0F$N%pCN2ESwiVcLt znEqMjekAVLj`tgDFs9MUFF?6tO|*5$iD-et? zg`!C;2`Q9HE3REe`&o}XOuH#oMp}WvUWK&ut)o_4`HNCk7Lqrcy(?y=$=Xg0`g4sw zkFAs*yd}0;=6_T8haWAUZh9(7Cz89L$n%k&PHZ4;vG;?|5aT%(;(T()8gq5z3^|`8 zu?-x_Z@L`NBil*EEz?z$HC<|p7Tl!8x-h5sf#=T+(>Xwg-LdXQhWjgG&s8nvYHZ7Y zPcg0(pO&3xH2A<=qFX|aNR5xwniqUmNy;npDggRv z8jL03H+<9s$0ltuQ82Uu#hrqprfKjkm8QdjVbl0+0GlZ4=IP$V$ZWPkN3o(|S1-Cd z`}p8k5O@k5U&1#Eono=D!`tiQ>$^{P*SG)o!`Y{k>-TrJ*O#Auy}o#V zH-C)xxKi}we;?i6d_2B52^g8rAzb5q3j>VNPn>4^d>Z>muO`%Gn5WG~O|~Vssq(1F z#I|1;G|5}?7y?q)X!9O%BY>mkJMcX&Q|f!i)i7EeKKj=+gUoTBKZ}(M<#`rD_oS z(R3Y}l|*~wNfPNiJ~6(3e{^+L+u4a&@?dA@wZ<3`l_1S9T^3gTK=Wo~WR73Zbp7JY zwI_^L4|L(wV|`K*!I#)KpN5E>ak4@8IImf92)A@r6!(uSc|iXS@Mg%09uR@paDRon zf1%$|GSsv^Qk&E?b2PtyRTG_&L*i??tr1X;Uo_8makcj10`wIQf9?_5D5WZ!x5;jc z_^qg2Dzh{cT3RTzQtLd1eOrU6(F8?&RyQsgo6oGDoXO2?I94o-M=k6KTSXdG5gP*8iI4%CPA$aq0f)4XLWGJoG^nr6&6*8WLfpCQ={&JwhBB5$@lq&0rxO@LAC z$Gu2;#@IP>7jXs*GXrE?P0^8qB9v{agtv)%XwnVwisx~ThX&$DO}KBugN7D-jrL5s zBQlt|Yz?|`SPiV4K>dtoz`FjJli&yM@AlvAA3|?VbaF(^z7p9{mj(V6hJU`vs_5lG z1}gynik%{w5XPHY;j$=Ttd83UYGW%)$M6=M{;3AU$dyRep9ZW_#T}C+)qMN!vvnLV&2ijWyW_abLg(9J@AUi7nkifG zYMTU;BCBb8LYm4#J{41z87m_~=39x&kW$s1o9{SJ%%G|!$(t!Q&a0TQ#o-9mx)3a# zSX)euM|wV}F5IGSChB`gGN|}LqTS{?9%LDurdV}-&U&tv|^{n1(zt@#%gNT`GzY_Pe zcIWEYtmD3DJmrTIxx(7%BTeKA6T}J?xx!j49_gh$ppj=)f{+UWAT85#!U=(Nh{zC9 zft$m;Fw4U}z6td48Gi};i{_>{C9e6X`{pC@@OK2_C%z)jn99ubdCUWPL%?rYYK>vM zLClrvU)%BTHrplBm1yLpT{49nxx~;GQ_~I>9GchY6Yg~Mii3k>soD;8mJ|+?dShlY z*LlV?#>CL(6d9&#J1y5>urclO?m{zO;5Lc=8jU5&(suU7P=9;sxI{Au$RrDW9z^@S z@sC$EZ70}8``ROc*_i$djlZFfMg&8(Gapkh97Nb7NNohl${fZ}+o2$~DF`}EHy(8m zc@v^Nnf`+Y3^&7d<}Me^`ef)Z(3xYs;2S;|-wupxN?k(_x{uBq>MbE-LUV($e8bv{ zp#j0|3G}=Jzkj>bmt;GdO_)XBC44Zk_x=e~9ncr13VM|9>mwlYzV@N^llC4av#*`w zC*9XA*fy8&`3km&zOVfPABQ?R%uM`aU;FW2bI1Sb$i^K98xS`HjGwTa-rP^2!>E9S z$OE{Lum6b)InrI9c&2VsHwS297KSr{<#?D+b=xrwW`7X(_E`_;$3ahoWtkInP*Dq> zM;C+z4)V0Ui`(nrD~z$-sB0HzXJ>D2hren(FBZ$6gkG|Mh%h!-S;vA&*be+No7EcK zZvSd2XC;W8h%~tbUXEar?Km)?BCiyz1e^Hv!8#2&p+udi;(p*Z-{k zfsB+t)Je+F(18+)Qd!N6tPQK0F;OdhUL=ysVGAPhOpgzFYuO5sFX#uB3u*@??uBiT zXK1GR6aDj(h4K6Lf|pWIEbziKg0^pi-4=L=qJQV?iJ9)F9`x|HKl#0cLkenhdT4Qi zgzW@_k3RoZYh;2lNU67+5eCg_F(NCC@CP2&I7@hk{*a+Oi|ZP65i;COav9^%1sF4{ z&NJCL)3 z@PDvV#Ql{l&u6?LEy3{XecvgXOeGl@J^*|v{oXTQut=CW>hIsp;^&($|89#OM8+f1 zh+4B18cW98DD$c^Y7mIPUQ{acRvBAxcWrScyhXRf!aG3{Te1wb))q`6x_DL(c|a;t zs$Q#0f@_u`R(Z(A0+Ltd{;Wc|TWkll@_z)oX(#N8vmyb!x_7+Y@=%Bc79p+BFY;(Q ztq4^jy(E=R2?F-k8WOQ-6IK zuk_Y&Y4`E4xk|p+-cp{<7f(px7Pa6+^54@hZz4q(oW-WmSAF-s1SV6zdZ^E7A-6in zq}&(;r6Dr?JamRaoSrvKBVDm{3RY76A+~U?i@-e;FF;{a)p&am+=uE7W5FTj9|}v; z;MGUD=!VKoM7Kq#ED@n{OW>|Wjejn~7kl*JI=1;o^g_FvL0V>DDT=SNG3QXDy|2*> z;+?#dD`6I$>_S9{6vrir)G6X@w_*8As+9@QGzanV;5;#~OD@D?3Ah*}KT$YP2a(cAfpHNqJNW8Job)s zNB5%luG*eybJv{riaqJQHzyPLAy${dUJzR{bDewoh<7JIbOglFM!K!JgrY<|oGf%i zF(Rg4tMJ@1mO(^JMDDB+wVYYyxN|VJ$`X`#(qAZ$X;m!sd7@OZC6aqg@^~(Qo7}L4 ziZ5nitX`OZgRFu{fK#0=1-R-DK>nu!MF0FsB*V==6W6<5# zfRgn8qE9)Utxqn8gq8|sbkn}w+n5mv$98!ot)72-k6k&6rNs4^ZjeqWz-(LGB#{$9argAY?%XGx3ZR2MNBIuzwX#JV)3r35X%O zjtH&GkmDk})?XT@Yb5ep-^wVP#i#=;*O#5bpJMWD<;{mM~rsH63@0$xG zuL>PcXcJ4JBaOlolL<)D1E&H}mwfk|-!s%~piJDka1JF>$)*`Uqdqj1vt=?BqJxhR zFdSE7pz;XebcC8E=6cQNres1v<Lo|XU}AW0tn8O3;O}Y zkFVRKqC@yM49#ONc=iq?F*C(yucD4Vkc6dNyN>QVRs{w9&OvxREI@f(yg^=zo+zs8 z;_$5`KXcG+7@m{n{%#_lQ9DMjEeJ9ft9Lykw#=^_se>bzV1JeZ8R2DhMK$`SiWajYsB&b3ud3kdRJ7#DUr=AR}o5<$r5{Z#3v@ zw4$mZQN<6Bqkm0l-n+W{@*4|^1G}NtDxmP0>pCtC>4-5|$=Gt9YIh)YJkaAw%?~~m z%#65G(|>1zxN=7i__FAhc#bt^vyFuFHC#jTTe@?J?jLzazB4sPA8d5+$?!i5oL!0f z!}E|ib`P(P?k#k zRU~SnMzK^)c5rd}&YV1a1ZHukx(lavquUtBY88m7sqRPH@8Ce@{1a`hCY4eR)Un`0 zV<01;x_C~MEg_L;J+V|$p+Q_!0}Ui;3v-Cj>T)73??3+w19@&*2?jpH+(A-hCXx>7q{v zy}Rrl9?gA6rQ)gX>zB@CV%ih@f{}^6mdi0y;D(XSyVO>?Lv6=qkqY=$ioQzkC0S?} z5j(eOxb8NdUC7wYPMO22QO`yzs4zK{I9bS&>i7XiahWqXYL;;9jYdi7Y#g6R3zD{=LemD(EgKYOS^gdMmE1v6IT%C z(Zrh_)tP7KArm)?%|k^#WhX7$R&gC3pRIb#5~8wjG48+#BbgMGsfbLSHLSHvb(c+} zUum@mtDi|uwjXTwpKGx$xGGLK=aNvAw@;=7Y$Uj zFDk-A{#$ov+AYzI5D}8eESkBA)P*+@sUeTXN$GYZhP*5jWT~)xSjaLmdjRE-aDM^B zBLH=HRMQ@se~^6&OaL`}9}}C?s4n}M4gxm5O-BAcLF3}JeZv0S_#7Vt$y=?`01z5V z97(q@=Hs3`=#Lmu$>XUHrc(^{69xa*+;D|z+RpKdW{|Nyw|vd?wFh2{B?sV@j-vHp zUugOWVc7fH(}OvB(56JUIXaJKZ-4NJtL-2>k77uIJQ`twiCE%?AQ#2ZnY$wrxs8L| z6g0{e>jVc4Y{NoD8N@SPV(jnemSayMWQzwJ7POC1l}2cyH{kBa6J@lZF=7X8(PD4` z^BjyM<&#&nosal)IElGU-*kFXIAlOC|a4m9gII4}&3#l}UKB48#9Q@P*2Xr|}QaWXOH z3P$!jR``eZJ1mv|56*2n7k@Sz;7Iof<|WY$mIPk6_(=CP%n3sRcJ*TMY@$gR24X!a zSJ3ZR)tyEV?Td~VIoTy60(?p_OBT^Fc?XOe`C%V(veeo9o=lJALq>wl<9Fov*$DA*K> zo}}&lZ%lHps(X*-{Y&<}LR^^WZKD8_Q}C>GiMX(ZP)#YZx&Rsn$6<%EZE;Xj`3Of< z!C|55QHg|eR6f+r0$~UO-K-L&j(KI77E?&AWrPkHln-{Z0KG!dSczar zC;HAnsfiWExfrZ9;D1f*yr@L7BlY?v=oPCai7FNw_oqitRwNO@G72J|*>oPCcS8E7$BeE)(AC->D#C%lq>`uVSIgr1KD~*&8vBAZFTs zUKK=5ODyt!a;{;}v^2LRN-e(Q*BV`^_&%?)?DHK+8MS_+*)%gPBG&(`vPv_6Ch4CX2L<3CoBc1GYjHzSC!)zJ|wu zjry`O`%tD91(;G$nNL{K7|>~-9PP7d8y+f*j3H_?sSVRFLGS$M++!X(P~n2KD)+>H zBE;67sehvTf@-D3GSINc+$^gN(P#o4ZSVQ@%d0mpwJgoHkMo|x?I+CCF4$XmO>Xx0 zHQZQj3HUm@x4!t}yq9pILdTUzh#=^s4l;y>l4^VdZ}URQdt?|PIfRKe1fsXZ3%o%G zA8p{iz-TUgRl*hEqFAP#-NV1WRwy@wkEeGEFMrgo=RQK-kwin^#fXMf93N=>gZ60Z zaDV1;K-{?`+heqWb$qp|^OAhJQS6x4l?8bZ)GW4nWXc{D3Mv-@7 z!DXbds}`;!E@)SI9Sh!32J85jH=DeUx3+Ob{D+sg%9 z$7U8hkC21x-yXZ5qdw$bJMy8pam^5MtGzs2HxNhCUzveOV{2w+4ikUf>=eEU<^#`x z*2@OI7-qOYrt-zkdlizNg7i(xVgoG@8-IMD-Ev&nSqfLmo)(FjLH^!RNJ)uUSPB=* zo(5$Hj!Jp`Ck@BnQ67K4{P-8+5%H^^G>_yxdPz;8SuexP)dBEn3&w+E!GwPN)AP|! zfkU#H0U~7`lFC7iC<0}D1yChD(=P7r?kp_szBmVW=iu({c5ruhcXyY?orT3+7MI0s zVd3(=U){g%cmLGXOeNi2lRQZ!Q=Lgaee+f@XwQMduv2-6you-|BC+0ToE0nHGl25f zR47h}p9~YAxSKep{lPk+18C+W0uw>*G>MgrZty6+D5?$!A91{cqR>Wo7{5ZeRombY zT)UE>Y^xSo$4R?6N5XGC4pr72u|=;(2ppT3Z+LR4ALw%JyD+%DZzEH9A0K_|X&wl914TGk`yrAz&A*uyoKQ|MK# zY+t#Vyf`K>gLUx`o-ER}W^JFYkMr-MV;#}D!=c6H4Mwks$0)o-hV%Q;S9qO>ku=EM zr!-MOqNxZ1SdLcJ`i_M)#vE2{9rGoj79IvmmOp9dvfBsB`yzK$ktd1WG8yG>92I77 zs}TebN4RzdL{!tH#4i@BiF{?8;ix9-n4cFn^L&P-FhtY7%E?4TfmdLOlH2-%(aAI- z#|d+yP2GyGF{1_0k!`S1Dt#Sge}zD=fH95+X%}5^fvKN@spaV=jVk_j;QOQ2khqNF zZ%x*!%Y^1PSxuu@&Rn?I&ycpW=)FmYK5pac-mJ6kH z0xo(zT6N(8jhFk~fT}AzW=Tp=oVA4^tJRkn>dbR>XGz4X7Gm#62>gJ#3_vk;C591~ z&prgg1Pi4~_pI%60U;KmS@cv&%N;flbh_vl!5ayKnZ%hDe=VKC8(KY^$2;OE{br@* zPHe;OGiXqL(fknyw?8kgIM$RW95|wEYGun^`I5;ulr_Dd(TIw@j<;kNEt+lIp1n+s z{p>I0d->C=izRioQM0{67uVhVv=j*f3^dBC9rx3 z2D!f#m6bd8wy9;IAcn~=_ zjbq*;3{_~^rEeZ1~nEKEGSc5j?dDfa6d^z;*sdT(0V4*zUoY|^Wg z*l;$=36b=LNfzEH!fu%gz{ulr*YXBVPUC%xpPD81t&l4|Ffwd{KWZZWl^uUSWIATj z-*n=UR!qoHk$HSxCzQYBUKcEEURhy1fOxn{Z~KfEUr-hgFg-HiOfK{VdFZmaM8b*+ zfO%xJiRA4Wa0wlJwU`cvl-~)5Twh@PF<{h*r(-Xpe|bUVwe1^qnZtLif9)S?wXhli zPQyfgpE`{vh&RjOX(a!(wIB0kAH`i?H7aa}$nrCMMiMOEaQtuy__-@!1bs?^L=JL= zS1a;Dokph}eX3kaZ1{8!~`i-yToA6V6o7S*g%$*tcwdx*rx#he>*VlYQy zyKdhjGJi`gIf@vSb;PK;_awOB+K~5AGD=UC9e9AKLvw5HViv+Poo`ieKhXniJ~awL z&Icz<%n2meM#5Pqg#~B(g>ioMh)QyJbUi|61HbWI^Q|#VKe8CEhEq$wxUY|)stjGe zw4#q^n=m4S$yj?`Y``49kZ?91=nyWUmz-$#z;XyI9 z;*Ppg^5Ur#X_np_|10>{p?b?I1%K87YLR;Zq>ZE9b$>K2Ja0BSpyfKRyc^5bp$OAH zaZkJZK4i=cvh;gzoC-5?O9qW=iq&#ov=#>sfE%= z?F|H=e&ckT%FJn?_j!CYp3ArC|1Qm;IwvoIsEc+60!m$x`nUKJ=tNixU>bO1j%W1! zyo-z%zvYPdaT6!-8fuunIWUT($7?cstYQl(d7I57**e~)=``g^Y$l(+(GDHhI&!nf zJAoW%&vGEfT1dNj9AuI2aQ8O^(3I~1 zD$@jcs{EOcL|g6bK_fi*fta5!Sx{jA2U|4^h$Uw0DyF7X4@F0dm@_Q_T}Yj26gW4m zj~aUcRGY)WZV^;dQpLW^H~|JBL_HqdqKVkAmJz{*G#dGZAn^PG0~L`|en}9{U=)ex zJ?3c(cGmMs)^!acO(9fu+=ToJ7LMjTNKS`~S z`G1l`Xa;3G-R7ByE!tcgWMZ7?y~6jM+oD`(b-EnT+LBTcfG3kUT`Ev|6ND19a5%){ z1@T*wA9Y0E78pfy=u@)TF+beFICPclF#5&yz-I(lflNQzYLSsl$O>4RP z``sJ+7@C#6gIKNbOSlm>;6A^zjl<7yP)ylXl8z3!b@Zx=Lc{Uw|5$dWHC#@aMA94U z7V+=Z-+yTs|1uCwZ6~2BQpoWJYXN;tx z`IxXo*TxPow0#N=jc|a3vD&tNr5Pj3E3w+s;WUv))lu5ISh19(_O9(n zqTOEd4zh1kaN`pz#1#OHmS5f|rYC6bhJq@`dK+*0CM0nO4Wlv#v$69JT*4Arv0f_@ z`wp5pM{KTAP|T>>)L&4Gb6b7Mj;|GMW!olRVS~YuGeY;*7H6 zek)s&!CqlN#2#>qi-mu*;fl3X82p)W+@yYRI+~@0Ky^W7G6u9&4*{iN{@ZZC*fw|M zg|TL~^4g{7cNBJ4nG&Yb?iFTGd4ttSn)~5yC0{;_j)DhS7nb>RuO6M4Heqw;!U3{g zR!U~+Pc;pXI{e=j>hu=2SK?X>h_2x2E^LN8);~S&zfjD#8gnbzpYXbN7IcX1>R-AZ z5Ze8Iah|lx`XV{i_(YUGjR!9K+uNvq9`8QBK#YLJn+pN0^3Z05BtXMRz#VS#)i$9Hz%6;W_Q5@lujere_r zax==2GAF=Z@d(EkrOJZ;a7zLcmF9GUKUI!}mN^G#t86eWPDqwR89OMA zYJfn40#>jgE0y+ZIit zg_=iDsAXCgH$Y8QsvvjMQ-0PeR^zLNsubhoc-i;lYO3t0U!D9)Qm;VMv{dv=vmSdx zf5Vpf$-~|*NjyJySOaf}S#R2vG|Q zC#mmA`noQ{#8JN-ms#jr)im|a%*=X5#rG}H?JZTZ?c0@pyhw^<9V1Ld8S^3}rCLq5mz&bdhK&ND1mz2m4{&)ao|RoU5hfg%v1N8su0v!ND7OS&i3y1y?4_dtl=%f$*+4jt+b}aNbOI zni&+&!#Mns!ICL?h(zRXvcM(irPgg6sAAo^jso119ea5Lj|>k7WQ?-m|De);-)v+! zhIbWC9b|4%^6{QFxC64s~?I5kIG*qx;$QN54!wI0&VM! ziLbGW`w=i3)a8iaTNI9Q{P5ao^-?eYip*|vgFXh7MdIJWlA)ur5yju*+~&a80Tg>L z$YKEUgAc$YwvfnTU!|LF1(it=igyZ(QxvIJCCS8b2#svpdUyfd;_*U^JuI%~*B_z& z(8jSM!U0GaygDU`S7`@Jp!6;bC=~XW?6z7>A^C95XXZoHmp1*s4|O5anN1I8QXeB1(1`Nn+icK6V;ZQa2^bvaVNrJ)$W{t^2G?NM8!oLDJAhkSp-7A98GMt^Eq0FZ18CdWQ@^eMW1w}c+D%Tj4hLb%)g>$)FfK{V#r zqc2AXtir?f70+6Uh_$$>PwZ}_LcEE(H-<%Gf-R%6Mzz}7Uhv&88kUSDlzRfnyNK@C z#`$kA$7zyo-JUpz+pNm|=LQdeTV#wiDUC zLo(GAV{@hL1aVvJXUp!TYgu_;jTxTG?#|~@M8dT1l%N6NAqF|8TIy{*(lpiMA>~jC zdM{&^MM2=FH}P9fA3K9;!YA=x_H?G+w9?}ztHg}&XX?YI>IllX3@UniEz zbZ5tn20=MDjNuLkdkmqz3-%g2U@EfHDqo5UzEgeqStW?RHsaZPEmQ|y+6rT|cpu}w z#t;g2vCJxOliL?G*uh*hT^ZR$4$(jxu!RF&VTT?N`DaQD%$?dPy_y{C#a=ArrwSQJ zKu4McN{0Q2N(wLu4xNqoy5YFF0|5JI=}920(J zi|#!;0BLpgVXH$2TXif&Q%B!l1q&TxXw7Z{cet?X&{D-Czs#&rQ4kF7q9re)n`(|z z>j=w^SanZiPywo)kpKgb9E)i03tvN}Rc??SSf#TArHy+E(HJbErT@IMNC!^+io?%V zl`94_-PlipNN3-%pw>%PP%{Jdkm%HPBpO(|jJ4~|ZSAAg$8^m;C^M!8A~Ukl!7+E% zF)c2@R-_}t6cp}ZcP^>Sd|$(KQKN?b8~yco3HuH~rjyUVvRnL3B`Z5E&WOzm_GVhz zK&+#Q(cUUM=qo$39|r|a;+(Rb{mqxj8RmAE38G(ai%0l_Gb+RZgGOK=k0{^~@U-%1 z`AsJc^_L@;J*QGob1V^VUj}cRNdMk0SNfZceb;b=;+Th_FzONI#v05`gRpT-9#>%g zrDeEvUj3^nV)Vw~e#`UAm+A7TmKW30r{R5@BPD+nGObv!(2-33@2Xd(XPIpkI-a6X z*mvig!QQ$oR1sCn;`H+%H!}F8vo_VO^y)3?d!n5}>xb^jZ3)JU3rEMy$7U|__i}uD zr!ZYp36)6$I5qY$p9XHp1?>O@*M^02Pf-`@# zJ$8ofV2^4b#j^SYavr5V5`BmP;#Q4K`95@pZXJ*rc2vTyx7T+fea&z;d5ASWL<`#= z%P9qSFZ3$#WR&lUS&_C*QIoHmZDvBk5f@nIu%DIl#=`& zM6n;6@iPhVV0FhB&vxT6Dq*H6SUY}YNNOPperEC3lx2mF{pde`E zUDNMiGrNnpKqvdbbv1UnGods@Ns7Z8uL^C)u$`JYmaY1QuR90bNza1oGpNfSHfBOj zb99&btV+!-(DVkq(GlbKfeckY(Z}gZS=V5~mG=qF8ZJZ%)ZWQHAU6FnMyXDTQu~_n zw&<};a_^_Zuq_~oPfsBgr)r+DP^0SmZh72C^`k#Yo~s|Vhg#?GCh<{-=m>_$#!Q{K zj5%H(y@Fz+o21>Aa?>AKSILL;leqm2+e}OMBg3ptP#kOcsbfBBbeE+9y31KsJXswH zB%$}BgJT8s=)?F`!acIGa8;XRFW{M&y-#v}RrEXC(3C&1V8hIPuwOOLLk8%_cSge> z^X)5sc2ca%)fOjM8)d{n$1MnV_Mvs1--jfm%k`eKo_41LjebMxccZqK9}}d$v3%49 z-}tz(fR1eH$W9*cS!tV{puv~X+=sS#p6P@y{bc~lZ?ENOB)UkDlJ^ZHM3)Vatp-AW zvp;f3z=e)KivMoq-H`+_?co9ZabR!N0I46ZLLYYybmkw$y|4EUSP~!7vkd*&YbWcKazI9N+Z(e|2SRh1n8 zt={nxYz(0PEt?W>Yzf`0)!u~E`_;oVdF2OP5T6h<;7sKCzR8jc>B>%eZeLQYj}A0H ziHetq#ip7K3c$X9#dIeYcWLzfTV=;!spkZosAK>Im5bV#_veR}%pCr_9VR}&;J#>c zhk@ufB#EYf?MV%aRoT=WN4quDKGTB-rMZ%=T&M;o=NX#ev=E$^Eh`{5=Lp$#!Z2od zkGx8+#$n(_jAiyqMvqk%bugRcIB&_?<&0QgvH`TG>7(g<4*{9Qf|ba$Sg2m)ql=@e zJUFFJ2cytHVLLd~gHYG-B@-8|1>&($|b}rtoebS~?0e%q4qdMfm@nyVA1hFcnn2_pFrmBV$%yEHf`Z_YZ z0jA<*c$PH)R*@OxxaPQo*e4gaw>$qE>SKB_QPucwZzf~AMr=Zf$+SQYI>U!M4IZu_ zuk_HJX0v2;cith*)tP~7pVTns;vauhwqWr}l++LwAksXO!+<1^?qoN~JH!axiU{78<(r$HMUOU>{kMQofI~>S$jv#g4I>^XcGJs>> zY20DfTnEgzB6XWN{F-pI}UN|zv4L{*~2G68!6y5 zSHzKaJ4ftwp{LKJApz7$oYuBRA><9ax;C^5N}U|H>==|dT3m29pJGDzJvM2!I9om- zY2f$_iy2n*tk(H>DSme&Bd;??%b(e+SlaSMm2J|+U$&EK@sPBvop4u4nFi$usuwK9Hi ziFV#BA~JhO4|BHV(vcPCHTT#=xQ^2$vd$k;Xd53>ryy;Pj=~$KRu#c{b&d|(EF$l> z;W+4KByeV*Pna29XTR~=upBoxxrBdcvm6IqYYsTq5MOpnh*|HaYVpf?Mu(a9BP<(V z;_ZE!{F+NZhW5Pm{yfz)4Wj~*=PpyZv z`=_;tJlh#rhvh%OpFQ`QqieNV=Gcgeap6j&*Fht%>0$x9B*Z=qf^Iy=X?)I8RH5j$t;PNw?>au zMihYxgdvf(sLP>|rg!>Zzo>Z9m9QG(K2l1FQmp>&jXP0D=fz_|vD8Ld1sfJEmv#Z* zE+MZdF<`dgH88@+X@I_Z;WeZUd-jY3*s&S{kydda+eQLdu`m$8z)>y)pSwN}ND%Th z$2Q++C6DPdfv+Y%>I;GT1^+gSS4+8)kFak5_`(Bpu`LoWD)6%bm0?Es8Zp5sf~Yfp z_;qX)RfrHaCo}M>Ccko%kBM}}K_U|AJEp;MT25>o(NkDooK(tbB(M^2466OS**|C% z^l}Vi&TU(|h5eDU=9|Wyf4@A$Rd?F@Wz&adxJhQ0a@+W2@xdA`Zbvw|K>ZhfJFXUK zMVBvf@_+#WTE0HX0xx^Mas}Iz(L?16Z1TAQ4Tw%FnmJHt$2gB0@orNEtgjyTZgWx* zs&7Of{kL$#g1 z!6OxKT>NS>23&6OkV`eml(uvPK7%lPL;U2Vl9frhGnlI_#95icJZ*c0DafTdIF}tJ z2v9yKJHyAwl=O6wemj219mnuPqVd9Ja8uT(yy}-O;*mbWJp=0`fdI*EH=rG|J!~=~=8Z|%v!B&D&Qsvqw zkzhKJ3~@emnUcD}sRAmiEf7<;cq2Sezq~XOsCAmMeMZXDzzFwl&x5`fN#`9g^E2X&Z_%MZ%4rmsKDEA5 zl(=;{@c2d7o5S2w^R|qxnL_U-*XUKr{8b5{0rEmM$ku;{>iow8zZak!$oD#p^6hc*_oiGw`gBspw@gVI%i9PG_(4LEB=Wu4h#p zX6M!^Gjyk3)l`rNi3aCZ;(z$j#5Cx3=IS_@7 zCXgK`d)_818r_wPjG%!8E4Q}S&P{v5k^`9<*8g*LplC2N=v1^40%5hP9L$>i-Yp+0 zqRRXmO85_u)Z@VsmW*@4K5~qJ;zKn6s6we#wPJU3bsQ)Ar9gH)Of5eu4Th;=2zJXc zPxxeQpN-myZ{(TCOjkjZGtw*Ybv@?{v&lk1uZVDSC0S>1eL4@ypZjqKT_oRY_osB6 zP_YW4npGmgmU$=ib*D0_5Enu1v`?|y%AZ_7 zuHV_?*;W@B*dH9vXL)c`TyWwlaFnIctb?U~G~0~hxhMyjfkGV=eV)KkG!AjkU~Qg4 zR7x#+A~`&fGy92*?`AII0_tc6JY4CF6s&BHJoa3rTJ?~ZapZL;+#T}P>l4ArAEqRr z#ZRXs{+3H5b_3NzNuvYkAVIw1zKt27+OJfo_qHqH*9x@(QTYqfMVxd!%4a}+ty zJn{HBZRI^SK#JpUx^-(jfYKO!bbCps!$mj2;kL^w?}SLqC1)h6rh1>HA@EJzO5~vM zM~#9%rbYZ5%n}dw0F}`U=2p{h5lA`EmB}Tp|Fpc3gZQ=pGJlY40033|IlpdzK!@XJ zyMp#IzDs0mgJX@rz22NOmdC9kKe}3yrowj?%B0~XQpGt>nOgaxpB+(zv>k!oh%%nF z@9~bbaIFjk3Js8HoH_QWu_-J_Rc`4d3cj+8d?g~y3x!xkDU~Y(jB=rB-cq)pcqYCK z!5KCf*E6?MQ1`h6s9 zIAf{W$h|HQeAo-!wB9uc1L`oK1|nlwj$Z6v$k2$Jm}BZ%D6x@>)p zthPo>X(s4$MwNaWm?lIT;gk&Ri!bQn*eoG75pQ%w*7_ks)PqP<=q_GPytqB4w}7qgJ=4V%By^dDNB`oJB~4ie*~wa#aaRN0^7LVmBBOO=D|#-$jfVJ!)S) zl(yfv`>@N}_NFTErJ9}~Elt?fRG5{ol6*3OXH5-I=z{7IdBx=4oDj(lgn3Kbsp#~v z7jtZ9F{n}qRG2~+f@Tte7i5fD0zBCwGU4(|q1shoGIX<47f^>(-C$1_01oa%q4#}3BU_|Fdlr~Ub z45e1$9hTs$&E+iBCzzGskfS8@QWwq6!dhW}4umy{WExaROfc!5ATbR9WdbJ2w*qK5NkW8av=kCl_ z>kqF6*mHe2w(OcD!^*L*|547b1XGArGBt@9+tw(RDpCxkVm8MRtfowA4L*}3#z;$q zFveepieaH<`Ye7rtD~4}hO}{B6*??sfflZ6KRlQBkoq(WECPhai)l#R5`` z*LiN#vlJ4_e?rvC@7MGigK?(<)7VHTl1!D4riaLs-)q<(Ql<-*(zU(W57_^g8K-&K z`Vt2D9~zuD3&m+#a4;~viTXv+gwP z!UmMT*h0Lz`$S_ZV)_~1U1I*+!1pE^F`eLa(0F{3kZETI{ZoHdkTNdb-%fgd*eCy{^$6NcB^^u z(M?Ve{J+4YaghT5q!wzohl3-e#QX;rS5l6mCUI5!f@%xW-@Q(3q9yQnbP$Cv)?$A;Z|)_Ga*6g+21 zJ)SB5VW|dj9N%AFwFnb(r`%!Fu{@kQwu95I3nVDS1>RGXER$D zW~P7c|J{uA%TE=E7q@hOI5<4U|Car)PW<;Z|EVud=D%Iahyo7=4;K6nE?NIb{|^S< BG!Fm( delta 527897 zcmV)QK(xQDxdMydARACi0|XQR000O8D>w^F0%E2#9!Rb-A@c=#O;`RLdB!rCu|i2$pau-`mPyR3h${_GT2-K}0OPer(nP#kpuM$K zgt6g!D47Xbg>1>4(j~L)Re$HWV*HEcfI~v2xCF~GW*K&del00%Lbfe;c z`uQ*mxzbIt7F*496XQ!TJ{OO;h8D}bwnWrNADFkv!(+NaNl568Pk%z6OjAOmkVccc zj~M@X?+p91(#faNd$tu@ry4<*sbI!#+TYy?$nKj&@WZx?^#>orm1pe#bTgmKeM(a@ zi(J6li*$oQS6#zVxJ657FqzM~!XxDP^ByM8uH!z~0QJNBwQ@6aWAK2mmWM z3rlgLylln*002h;0F$@@@&YS3ldJ;T4l6hdOMi{yO&MnZ04bW2lmj7udw1J7lJEci z6g=MPKF*Az=q=fu_8vbw?rX=smeaXAy|X#A2ubWvq=uyY=sB~W{Z;|s8z4dI5hc-{ z*|aR-Stt|=s9#mR{meTD?Y}p%_ zq-z=^TgS1prO!-Hf3V20Wzq5;lp2k)#V&5|@8&js-aUd3S|eM3IJ4xsIz!4jVFkmP z1BrK!e(yB9wfeq)*6h~tKaFOe{-&)D9$p#ske@2CgwN<&fh({A|qc`?W1V`Lj>hb+ix{@k2=y`-Vt*=@zu)% zM_K6z()Fp(EHTjGDdCm{G^1Be7OoJ1p&7$+|m z^i{WTdhvF-;wk~EPlcU z{WNM}PnY)4B~w`U!&bkS==SZK9D==NJTIl<00w4%5gg;G13Nc$<_QZP+qUCVsV*fLc>-i>|ky0CNN3PfCjjBOBqC#GS#z|SyB-722e02T;Vj&7{ng7?JpZygZl zmqRvxf8iKtlQ1RSx+9)r&2boo6;O`B(U@BdNJ@+w*C4KRl;_W6NIL|U^vN?FXyKCT zuK6eBrzB@d$9k>1pXW1K393EfN4osxOxisycneDEl)!1}DHR818M@{ShdA(E*il8b z?j6TE(WU$Xg2A7AIR&`R!blbFDLI?)^1!QqpFh~JQrEhdF8%h6NG80c=M^QsTv&uf zP+09A*(jzg(J*fHxkrTs^evQj@8{D8;@*q~KACyR^EK+u)@R|;7^i*_#r%>=uJ=F`8$6Ka%l##gcTHWJ(PnZa7gH$yCcS&%2Lok zaw?qLc)Fa<8SNfPPEjO4RPf#j7vVR5`9|c`1~6(%y-L&zn{yszScw~(?wy=AsiFXv zSvKL_qZ?_9s3^K{4xC?K1%-3C;$mnQmpXCgwgFP;_`$n(EPD5b{}b=FSn)ez1;rcn z_*Few`~wpj(KgN*uCKd3zyC{%IJ0z#w{NnW=xsnJq^#gb^YQx=-5*Yv*pr@reY7B> z;f3Ysc^u9Q-@E3RJ$g)adoGrxv7$v{H&*nPa+^@D#!8)AbkFV{>Gn%O(X+YBuJT6> z$pQ)rM`X}Jhb^e|&an)-#|v90RG};^7ARr6M=o4B?Quc*E4VdS`OO}?!wGC=6+Ylf z`;ATD@Ro0UUK&cma6e9nee6yX3!65K0i22E^S#5wPj2atuIb~GzX=t8!Dn-J<~-T3 z&PK9UZXZ|97)DgkHd2sX>zJB!il;&H>F!N->%I--BXNlh$E{SEK}|AIl%6*H29~R| z3aVY+q?N3^Vel(1-z4x`*v+x)>MyYej&wn|^`pG_dH0=e8~BD2-iLnPZTz(nf3)L| zCDE%$Z#Vve+i2G$k7cZXPv|W9N|GJgbOsucT`;DDL@T0k^%ci8a4b-6PES(}Ce`Wi zP^hJ!$5JJOv!PK?GC1i{0xVPR!h9wMs$PcfRrz)LEh=4_ z-_X(zIf-I_AKp*!F&rdr@d$t)JbJBrB!55ka2UaH-l+ez(d_?!6~D)v#LbC_-YA*R5QZrR>j+ zp5uaXaAnxBhjSO?k00L4({fF;*u2ht_Ub4d6%;c_JD25HL3Zy@Ec~lJbRJCIhKtC= zG4M&jRoRJyi9RELx4_<@M3S&pWZlW#7{ql>UB~mndZ3e{6~hW7xKiz7YwWq&f}I)xU#N`QFv-6YFy^i^Sd-Z4WlKi5lmB2YVR&m3R}(ROcPupD@-( zEd!r-wHeSE?FgB=S;GPSHgoPAD4sj0I9=Z4ojYe_Xifv|xInH^b>-5Y&4C8L`}^8F z{ZOB%aADebPyn^r&UvO^C><_P2g>t5^J-j~Qmslu~h2UM%ACYUZ>=NBnJ`szbSj=^HF)x?>O<@tRaKL=wVpx#9#X z-OPPPvwR7FPZMfWh>xnM*|Wj5VoBJfGuT#P>%|AhZ>9$qUh_`^)K{Nm#(FO(cSroW zYlkm1tZ{{t4CxoWjXgW_TnS3;I$>$QpfnpqRQ{!ZpnPJPSQQJXT2L!mFIL6yrb^?w znK9V~*A^u5;TU?bt^8TJH#l$PZb%Fc=vLT7Ys;Zc8)D`7CQeny;d_~eeeF5Sc zg@NCMcc4=O_uAwQsGn&HZ-7uPY4JUA9E<3-ckG>*{>UVj0p!PGO0{p{^BtLcoVdsC z7#doCtbTY!DA5dRK;fO7Oda>-*r&I$`K)9s^bv5OR``07;3ke|$|-y<(ZqWPu5~m2 z%zQj~!9l@N`|M4rL?fU<4nR0kYcO01;QSOE^z82nGJ` z5l|2)H+PBV2J56ozB4lOC-f??d(>>Sd+mO!+wSG->2NKkd>W}(`HGoiS+V)$zW|^% z26Xp`g6f7_S+y*Kc+uwBu+Q!Jly5VCwyf`|!A`>iXq zeDByc&K@l9-odsC=Pf_Viuc%PWDZSY`&95YVc4g-SA35Pt6l4$F}=rne5AS4lO5Z| z_eOIBQd)=kn09VK`tAqfk3kA9?Fn&BUmLm3RD%^5lU#)~l4iKI0|RHFU^AzGc*vO+ zapP)c;c0g~98y%+gX58txry6GLuq_v-abk|PWNd;@-qxsy_txDDL2K>?VC&Ar`qM6E84nbS6 zf6KK%*LE=AuS-n+)4KV)H>o)C+I$P2kx-1%jbsk<4|$L;tO_WwzIo39nUw1N&{p#((?6~CE(Vb($!TZ z2R{LcaqnH)19zxQdE{U;6P*pN70D6Q!0RS5-{3`+kU`DB@}O9c1GX|1i`JW3zfjl= z;Lm_Jl?9bK#_Qs_?SUeH9+^K%NvUhycg<%U{@l{T&Wnc4l~#0o8d=VhItTcz=DkDp zJ6M`W)q0^MMhwUhltQ&d39BW>sa}oBG)2sKM?EM z^rjRfs7A0MLrS4K5uCLO>=dgPJEY51L}atFBtufc#RX1e#`|hq=u)BSAWPsKBGW+O z3VpE6f6gg{AFt+rYD{=C_t;G*u^dX%ymK6?IytU?NB%iCT@p5?rWJc=qpqaxpmNYAn&y|qkhgJeQ+%NrFt6_&-C7Z!99pC!JdlZ5*YpQRxv?Q zq^No@TQ+@L8tFq4tbam0m1yY3GVp$B5#1wddl&CVmo~k;Gn2P+m*{Wc!_H%Z82h1^ z++0Wn6vq$8h_Tr{LOLDW#vPgIX6_(iF`y=YmA`ih%+xsc;41|=!=C2js(In_!o>%B z?y*A^hIjsdh_Fd)Kv4*Pu*vg`3U7S22VSBt6eSwqCnY^==pcqDn=ftj()V$}O0@Of zp@&IeF5<=&s#?>pN;DN!0_lq<@q68$ySfER7f`4afnpcZRz!jMsQ5u2G}c6Xk$}uiL3JiN|jQV;)M8rIUT6UU*%`Srs6Z=JKZ&4v?T8p z5%dJ(#Pn~8drHlv{akH4EIgPn4~MQ=@k_*|&1w`_Y{DA!o~7Qw z8TYkTZJt825YAWJ!4qFsMbfvHP|zMF)aoYbL8J)s0A3~F~T>C-UTTg`09&% zLWC9GeLN$N=8zkkTFuuFrmy`%Y~toW9o|#Zgz`>_7gyRV@d^sNC0<-*zog5n?3j2R zr9Bg`ptft`H5B&^t5R*}2J>|KAu~O$8$G&BhcX1I(> zI4OSt@mf8faoA?KMtAogVTIzW+fiIyRx>m3st{t3=;^jJ5!Ce39$IsQyn}XsTpY)x z&7umFK&w(sl$pwg1Y>1Yt-DyytoFcKu>NSV`sdRs1NcZD9!>I8p(bt_7Iwp{Og?M_ zDqAoK+()I`!N>u~lz}!@21Oo>;o9^(Vk|n6ptW;Y$cwpM7I%G0U-br;SGSi}^v$js z?0WFx`GlVm7c|bx*!63^m48`IyEE2u`-@7OjdgfPrrV&Tg6<1iwW0Yz;e2a=NnzSi&;;fS3#u=>4dlPJicimCZs!Fv+Rce6(rCg1xP0Hmn%2KJC8O20J!d1d>V?8btv$YHK1NMJHVpz<8 z#1Y^H{S83-!NZ%r8u%V}-ibM0H0n*^n`p%dFHOTtW^8fv0et~b&EY z9V?80y?tE_?Fw}ReyHC28GV1R1}*{aznfc9zfb7^@R_M{b&4CTT$_0h0#i?!rM_f! z&bk!2GVtBSYBMjs-}D8W!JWBS3m52vw_p=P=?zl3fn#^PSQ{tS=gXS~i8-Auydc;5 z(3QUKNSe4K|3uVCju*A0V&Lm`X<&@dkx3REJU-(tyqX_;Q~JP@+X8=Fb=-UBGvQ%? zP9L}SV?q2O4Q+H2mXsCk0q6;AwLjR`b(dJ zN)rQRJEmn{%I!FbTG#sXr4c0DXo-MhiQ++&DEv#Q{dfiLibUgQDpbYDf#((|em1_X zP;A{)weHOf7uj)hVy}P8h=|L}pH!5YN^th7)w?KLBcUOvPAPzs#-Y)h(gQZ3&-x-v1^q$PS+Ow^1N zC#6xcr_?)k*ckX-&g{gdP5Mi&d6QedlNL_ZD6zlX-G}v;dQoqP;w8}*46n- z+*l-=^7n1}z;}ObSog$b2X%QBlj96vn{sYJADYs)ZfFDpb5Ilt3x8a)h4Z_6wmazS zq;3PD$~F;Dmw7NkgV*%+y;2*f{e?aWWd}l)eRT2-tbiE2!r@+K=yF5D`C*uyvdaAJ zE&ZD*NR^sUHkZok&s}1@Z~$S2ixp=#7SK=#0;u%&!6Vl?_N69*S*D&cWl_MJ!{f4DpdOI}<|*hYNFG?Pi=)*Gdvrnh zX21~DD%a$hVFAgr|7qwha+CwyCBbCQd5U8JG+|m$(Ya-^Ya4F=a=Og7gs+!y3Z4+__o9kHfs|5n)o% z-J^GBR~pX8)rM3gYQs2~5&q(koIC&!vu1@YsX%?8FhfmJ{>^!uQ}aX6szI%B6f8dL zz5XEDcA~`*G@7DB0uP#MGiD5+I{X-!HNK^AS{6!8TADU_>rSzJkO2Nj`&~PeupKER zX!@|%eLA#^hbf5S;4T|xA~VB(uI z7QF^-!$i&N_j;{EPlA0d@6$hWnj4eBP`8LIb1i0|hB7=lteKMln(8t4fp$f7{?~ColKq1*m>p@DbR#h$NR4%S$DUzkej?U|rPNF`AU~3LzJ; z5#?m6zH@@zBODGbb8YgRO3Z*Hd-1(z!&GpQyNOUyKgY?b9 zpWkEFH1x!ff75`Q#-#-?%(Tc=EoGHAWJ90_oP31n4s>rO%g zYqZRJCQ`*hDZ_WGDZ+upH1$}Xw}cE~(m1DMeg_xz{TnQ6Cc{xo0AqMec57>#Wv=ki zzQQN^@YRMr*lQ2Emoh_yJftby-_Ve}8RL_GZ;^_k=S z6wF>j4kqk7ajREAF|JujS0M_hn~n4zi7Xm|5(a|V5T&JJSt98G@3V?p(aN5Y>HJx= ztYK1&wuG4&%LTc&G6A`wvvTf%&}2czg_);|hWHCL+GHDM-%I$8UbFEU!TFu13V;1% zdSvhaf7Jduek6Mlb+LBBFDF0N~pqktDc~KQ3+d%q3WeOcwbJg9mT0sNLjDdS#1}$p%|$ zEilY0%b(*hlT}VxBu4lclFh^%ljkmfst<=*e{#j*W#|hZy9~>xniT#yB*7SfCog9N z1P>JFK^IvcIWwo#XwVl>rY;CE9%%Ly$=hR6pP*TsGe>?AOY&g6Rd{mCW?!7m7@qTH zl*qHe)toc`sS@$I{uo{9su5c{oBV{L)TE%n`K#hvMLMaI%Sb zB>0Wpz&-k$CK*9c6jpw2;Y%RXfAh59TWV;YQq*@ z9skA)t7IUENb$HJ!rLEBIh0e@4}5m;f6XXL3qv_xT#d$FKK58F#1Aw;nv_Qr1Bb=b zduN8P+dRI1aNNxwJWeC|9fKB7k(_t;A6a2$h01_P;sq~;lwm;S_lioI7Evi0Fjr_( z#<+yLM~{wae8PY7Ytj5BWTxY$!Y!V+J?}qW13}0T>!RdEuu>{{S~i-TxH?ZSWLlv% z4l-uWu2esI<)~CWd~GPv|G=F7W)d2Qnud_fdt%^{7DbzDB1h#W6Oh(Bp1~1CJdE54 zTkrjRis5CkfTTXlY8nXC5ICgPdH4<|-MG5<`CX7`L+Ggylb4}5LmcV*bCdTXDu2;? zS-BhiU@jE!D98sB9Vv$q%ypJKC`WaGf&T4p8>g@wgK(Ez|AQU(XzH5DH?ro=EyA<~y~?ulFsvCP1y`AWZ#1cuyb1rb>+rGPX$h^ZH#3q!JcU30 z-EpQD`jC#Y*=va(tSR)4DQO&i_J5i`-Phci@cDjldG^j6Pd);%-Kp+=243#<;&*{O zt&6w8aOG(C)dmbK(v)3g(<)x#=Kxsnd#l?9TJ`p|b{C1(XiKX6{l=xxZke`{vCyUM zZt)`}Zh4dN7-q{Mo*z@P_!iOa++&VQOhE|_w27c8cy{nqJTdr9vn~l~41c8)7?t#U z>uwUMVovoj*)yjg-i4o+Y~I*0V&X_ z=qne!bntPpxLX-sw$j{I;+4+U+c(DQxycp?|^+pD3N!^g`6D z)Dpm3nCgDG;YHE2M7y~Ilf}J^lkN(3a&n0B-JB?gdTk)Ssl%ma&!-P!WMfjdQJt!1 zj;DG!*=~u+9`MOF>dLbfB^yYI(Ddu$T1X-k`^3<0Ju){O(7iD?BMGV0%coM_IUplw z15bb!?3yMD>qfJvYJW&l(Y}svOXd{F@w%`dYQl^Uu^JRjO!4*<{*0P-jUvL)no;wE zPX#l}eG-ervm_Q~!7G^<%fHC!m8hS%h%@&N?IO>SNA2vRCB;%Sxn%L%0_eS{8Z>*r z8m(ThC1wjnd77N1icC$^D3+_q4zkyYZsR~!tAs@E9Uh9%*d>Y1V_U09WmE$wi60sV zG7_qb=S0~O@`%5*z+3LE{6NBXjamhCN+Ly=2M|D`w{jC>EM*(o_?jc!{CiV_v`Tz|f+$wT~x= zZhLT^`B9|F+`PqSXtUfJG?+#bEJUMQY7KhDWmERA(I;;-m-&{ZW)vE>no6?@7vqe7 z%q-^xO|3;PXYpg4KCmK!iuqC&Rf8hppHh=}Pd97cPEX%`j?VA`tx_B^9d;D=%b&%63UXtKXA7dc6-U-pI35S?5S1omf&Xyk{-M%| z%0fnh7KraR3Zy#o{GbyM+5chM(ry@fec_2K9QV=0n;q4eXXhd7Xt8;yh^OqNTg7Dq zoWbvk3m4-KoG_9}fwU2sI%`;K@kLWUjee!oK3Ky{($By}GwD^DNx#ZW0tdB!$}btY z;##Ep3KiKV+&OzKJaFJcU-@}QOxR_<+(@XFxv&&m@Y(8ibJjJprZOocUP;w~7QDp- zY*=ETQnp)cpkkqy9%!C~7gAJpprU;t;1QKe4shVmB|gT$!RLOyH+sEvG6%&Ap-|7E z_YZuyVG3L?&(;!9xS!<(xnbvjgL%MxPR~MJ2;_hf~jy>WqG%y?l>jyHp;dpS&mqtttrPA6i`f)%sRdY zVv!G0R-TFJu{@>PldI1>&7TAf?rSva6XlmH^t1N7;0N6{v^d2XFv~oDoj)8N4t>|E zfbJM-?@L`|(I7KD6$@r(8kT*1_G}Zm4=ev91mrx*N znRtQl%U3_;(oSg3HsD)s#*TBWD2QGr21MLk$i;@(Hkb?vAvBg`!eunm7UN<@nmM!i zOr|-c2T!qYJjIkee1#}~jV5hQ5|q*`8%wIqqk#Hgu+MCd8V( z2>?HDJj*4c@J}e}eSST}_G%Moz@BfSa*RlEEN`H<< zYJdM5MvnuE&8o&7et`(dwtw1ziy_IIs$?TAd+J4#QzMPi)PussbB}NTbx&B4AZ2H4 z8#_ab=&lyqY%|e+`KBpEGmo7r;&-=7P?dbC86Mk}geJvb(`QiHh&jZlIo@BZNY39S zFDa$SCOWfMLbgzusYJFjVmrb6@n#TCYynyU;Vuf#Mj^#c=RTZ`X!*B?FWTO_KMTVr zi%3;y)D8kUB&$`=PY|Q9*fO~S3g1`b$-oCv^FguH_Pnouj=*Be%L)iwd;wOWH`M_) zn8vc0cG>h7F$FMt!!qd4HR@kdDZgf`p1-a_;{NcXTM>b7HFd?Je;5z^C%4MYN3 zfWU@>Ljfx2i-b+A4q5?k7YW##Bp9cZo(%E@EgV=AR$BMECH( zpE*y&#ix%y|0f3#mrtD7eQ9~*=`D3h8KFY>Wpey~78%J@fugBPHQEX@?tc|CmTH(4 zW_<8f%ve?BD>z=OJ#2;tT&3ezIT&9thB_S%X`SClw8!h!}Wtr2Q|!L`nSR^5e<EEqP8-v%$eMcq6-m>6flR_G{JH0V4>Hg;K|9&|Cbb9mt{_f`L)2}y|@9zik9#?7){jcM@+m9!g zrvW4LIfQGxZ(+Cq`iawQpHE{S>D7d~%uKU?+1Ajus(Wc-3?gf2V%sll4CO6(%(AI# zw0V!Xk>OJF9rzxXDfPYMY8ZP0eRy=uATwYU)N0@t)Ay2L=4(5s76n6(g`bCUVALm! zfeEW@y=XjyIDGQ;&%|cKLemhevt}XlI0x z&L3XYL}%oH_?m8O1WxJ~&7*n7wY|810DXnSpL>KhN~y}`Z8FsrzZJDhWtN6QOADn| zYMtS-L~1ZK8g87=>eeMA^O^ONGr749$BKo~<%At!t4PBUm!^k_2Ju@Qim#hCePf%X zN5%_^n&vH2k@-H;G-Jk*_6Nn2BH0Yi60~(9Z??P@K7Qhjfl=(oy-0e-*g3L)`f&yf z<9uc;k9B)>(?8XJfY`VZ$@;T^RjRxUXGyi-GhMsjnQnP+>fvswM8MQZ zRfTp5g?@3ui2*q)AY7=HRw7(<4pyaEcvD%NX62Do6=}v5_(~LupYc^`7Q1vUPPMfm z1^9KRGS#S}vLM-{1K4ycR=WV1ur@1JJO5F2YsD(F_X=$K%eP{cS?K(Km(_dy;gsD+ zgh6p=Z`C#lrZ`j6_Cz%8h|Rq!lx2^V5g~KlddrcrlW+M|wc;gaP*s!U&E!6_7j+aa zyxi%lxC_D3$=6xsd{AAuYFwGJBqSMBta;?jRED?C%(jB68@5rn#=@cH&t)-Xa>1d= zoQYM2manrdI56?ytUR!P9JNS&U^&;%;z5KvS{~w{&^DLXzf#{a&)KSH^=8|>u1y<6 z%vAf8xSzFqSO0_NGkVc@0AD9Eg|*Xo5s@iO5c)@C3Tw5v?`Hde29i>VDcH-#9$BX4 zgcAbk5RoCI0)Gzk!kDf5i1zjoX~_Pfk!H_`Yd-3jAl1X)hmLK3B)%d%@hA6XqBjKm zmIcZk#2duSNB)f+|8BEQG98IVUfLv6$dOBQS(}=6u;9?VM!inbUTKGi$x^i)YAh)n zCbh=QX0G#$Ny&(z%_&Sp*LGU2!7wb^)%~SryufV|?KK(;d#~;6jiC0_afxOSkVzKW zJc#yt;~%eT+D@>4i}tlg0<$sw7wT814~GOJFESfbFdUOG#0=&op2HYwI}}kf1wp6j z#-k1*Z%ni&)1PR-a5G$IZgRmG?uHHnojKME!n|R8J20*(H4RO4AB{KET0%yIM*3&j z!?YJe1A^OQ=y?Zzcd0GOb~Kx?7k!uT!NgpY5)dDtFH9AG^eErghd|_g?L+M+?LACp zU%S9hy02TXZLZ++HEa)kU;70<4scUo{@(o<&1PD_KB97#pmtW5FbB2mYDO zYK?BU|GLrbVTj@W>t<8C8TvKa-j3mzhgzdvYc%QyZ?K~peqHNyJN162vGd{Xig{t7 z6BZ#Tet@fL__5}=<2SI#(;54>_J=q7Pk;9FkMQ|_C*5T}??3Z~=$ED!e%bE#`l2Jc z!0r;rNVy+ZQig^Glu(q)YG!0@Sk;V)T2EG8B$vY$MBE4=l3#4ocih z+aS--O!FuD=O+sza&SWo4O$*pVH!c(cfoE8EJTr`Qevk2DUUAhp_JcCIHaI9r-v3N zNZ3w)F!<>6-?Rp|DMh1_Qg1mU44TzqL{=K%4?Ij+mhcY!Awzi$5f&Aza<{Ad9B$BjU_!U%eae14FVCEtEMt&+1-rq%x)IwYnr+P8njAhioh$c~$PuDwMm!c2Fx%u$y*& z%C0yo62Pl-FYK0wLM*TdX@$O;hauHGw6r2riS&}l*kuS<9ulzt0WP%0#?ov_wlf~O19XZD%K*`A+UHt z3b&{QCn8Blwe*P;U2qnhhN=hq5|~W=>Y+ZTh0N+8lX4xROG9LOd3!uxOwrfxH%ud4 zv2+SnQZ2@ybgqlQJrplMVN=z3dlB4+>J4MTAjV1)_tQB0{7TXL3!H z&je2%15I-f9~0+^fn9PT9!tQ*Ao-E{apLnwX*8`nM$RBN0G85|Tm(wPQp9YyFc!tL zoF`8+oG0cGN`2!45C`?r^c@U;Jv^K+k4{SQm>=nm?nVBt+Ma21)13E;x%57m<1zdY zt4m=oh%K49&I5Jg-3bsK0dcgUZfh=~C=m}Q3ms96i0RiVxLd}89*c>{jWwc{Gpj64 zn%a|~#MhoQRk9_Ldraay7r;$!*+Rt^Grz$SPxk7`R4YpB0b^jtl}PJLEKBzYix|oT$PX90Zl+)Sz)^w`S2Hnb37 z75u%~g1f)05D#LGTwHKRjd@Hu(kKamojxYW;eUGYH;iIu&#|o+?HBz|^57si&ST^P zAqz5?iD#rZNbtpkt$5;pIl^{HKn&3hD|;pAmp2Diw4LV2K=P{4@su{P6gtug8C=s21R=bO-1VNqX)oFg@ zMzIo6AvJVt)pL?NE1$iR$eH4^S5ZgrOF~<&T}SsFtAc`l?;yM$7NEQ?-XOvR=<2$- zCQHd3b{k8_jX~y+&*(cwuPscW9M;QA#2u-FDoMDbtx}kPyC{Y9AlU8=5xz>ampk}m z13MX~+*Qs5SC9gKYzdj*3MT5K@r+MZqz=iZdcddJs4LI4ActFCV(gU?L@e{Ezs#*i z=7w`ggUXPQPC~?i+9@C-X#?ed>i~T;s5e?s)sU!S$Kz;IvRu-?v7k7x8)~fr3ZJ{K zqpkI}^l}JDi|r(H-%B9Ba;I8wuwdxQ67nbng<~ zKlYA&XKD^V*l6IB;eQr5yAt&W7a?=(9$g>bUmc%l!ELli^5&d;w4_*uCYLOdqYYpp z%#PQf$9AjN6Zkf!YUfGQ?sSOSyb1WrbX(OH8F)LR2>~O>kKvw7Q%K9pQ;AAwokb1+!dsuZ>z~ zWIBHi6N}Tov;@<1GrGHQBJv!TxfJf9*3*K2T1}eEQYD{pn1Vd(Sez-#y@g~+TT2ov z`)sO(Pi|?diTzdLLRufkjtebnTMOS6`9Y+~-RebuCupWw~mqq#i3NMc5(a4TceQkqq%_s>jiwRg~{8Wa)#l$ykQx>@sfdivgTbf23wJbrB7 ze;mNsqK^r^x$GVt&wWRw;+gL2SI&5B+GG5Jk%{@rCE;x%Mdc_vE)CY*#*+*Ay4fjnbR8TlLrSEwWZ%ahLU2Z9jvzW6b`bZ=pTym@ zo-Jjvq$?bcEbB960o4@gw=@VX)dA7$qd+Q_E;)PTwDunVj@Mh$phmw5suVXe%=uic9}0X5~^h`ECttlwz~D4 zb77v4jpuXr>_O1C3<#mh25mI}+qge)Vi2T%?P7vMVrM2ANe?Sc6x*{7%k z(8BjI@g)uEvX8kSVB_0l=_$0#CS>` z&wDVPVw|5S^1tSWD^$~VPF^&FjP$vGB6LUDx zrbM?nG>@ik@QADJAU2NzNP;99VRngF)`uVw#lV@nLlW7HgTxdx#1-oV2Muh);zSw5 zGhJfr@936ek0V%%2OJi(k0F(Y_&#sI)sJV%XhCDd4%(u{;Qr+~7)Ht`uWCDgAMxjK z5_6k6bb3-cu>ah!%oVB8Ya^3bhUQHWI60pIMI0A{S2-+U3Xflvp$LB9;lE7F(lBkD zPqdwfxvxD1!5e&y4})fDv0wZNv&RScX;TkG)2%1{#nb*IuCoub z^Gz$7EN{{SHrRn?JqHJdk+Il+xad*@%mh46FjI%=d2^ghjJbl5{f-s>q5Td^<^O|o z+s>uU1~}9`f=Nkq!!UVlDK^r54HLqUfL*;!+hJip&$`$lGR&}Qlg!-c6MNW3f zkN}@jz>-CD%-jLvMt<1Gge-M7zbDfp`FPO*u|^ z=VpNz1c7c=iBc!LvP_GADWuji;)WcQk94yDy+YAgiC{=4>SUnQ#EODk9IQ3kP3*j= zM6zS``X%TUt0f637901cM^IKI;lMHqBA(fF9-nyPwVXI&Y{H@tVyWI`q444z{i_j$ z^Aao9>^LqH+v{Jc2x80o^WU#xam%Fh5Ubf6F^?c%+P_~FgiK3+Eb@MGu3^NqG`A&6 zExzN|8d|CNKCiOxDc%Sj6sBrJDO!b^wiAC-@}p)j!6!7r zuIG4{2wP-9sx$I`orSIr-9~q?QxJkgXPI7U#9fW)_v|?ZuKCz_ZRc{7c*SB-wqu7g z4~p$Y9;*91%r^#aiyT!SFbFt}0KOA{sPT0dj&c58dD=ETji*$|B; z&e8UsU%$M1^HR%_Z0nTw9PU10hIYZ$!W(k4zpvrGYD-|(*{$`(o$_A7i3)92A{l~s zlRAhH8bYe^4fy1Rg7?@kLUITbYzQQ83D3KO4mxXp;J&~pE`3$P6+og`hMnD`zr9u{ zH-L|4_X?hAH*+7s?nt76?_wlFDvb{{{y}>*b+|k8_#f_ElI1blz`8#Nu|sZbOa?V3 z?#&}{(S<|0^;Opo1iLXGh75gXKAHvzmr-OPTyPmF;;Mz~hzr_PUdICe$zUD-`eu{Y z@y<4Xu8BX{J-V zRP`HgBEG-f$0?)dxbh(-c8FNJ=gO}^MU7oV9{j*Ukol>AXE8b=Q)I=r_fssuDL*L z@PT&Aab;&ITq*N+5;KF`(NRcAiC9<)7t6dTvjaz^y#AAhr=?9F7W5I-e{Ez43p8{KCGxI!^wM8liGos-4MyDB|-wy;jSoU0h z$ccz34rbJ&szJThYc@LFuOyh!!LlO2zN2fnu+rMc2(0D7dHiF_mhwe;gx=X0wyLT|rF(#JwqsbIpPKp9T2p<*d z?9GWf?;gn1fy~6k(NUt^lMUw6FFKwmK#Ys60AHMi#;F_MIk z<$944qGH@Bg&+tUA9spUY=Z-TPxTezs(gXKQvunQ8F@-EjM*26Jk?i-NwJMQRXXyN zCzqu0llz+vJH`P9zju=!u$C{iq8lew@K<}m(o{^ z5a6*+2?xnXp2$b^QV!U0`sgYeynz-LoNq zd_J?t*y8m{l(dpgvd8ac)qOufJ#{}ywe9iu(q@@KSbR!2#s7WAo6p^HqZ;!4kDeca z|M=JN(_3RIwuQPRwhe;=w08!Rk@Adn``hSzM08$Sfx*YwLZ1l5!U&yZ`HXklB zR>JaBxZSqh_*7|Lq#cl^z6SUkxX-$0VtH;-K0J#TV!Y`rI}Zeev4IpPkjwDG_3k-zi>&$U_lo{VnOZpokQnxp7<@bQu8_L&|@yFggk)CHk zortRN5>lJ{-4XKho}%+XTr_%pCzJM^63Y!1bl*!>S;*68NS`*LI&6u~oG)dcLtQL% z_cawlDm#+!E7#`3`UuoU#0kRc7psN^fF?2+DP8f|1YA*ZhHR8oklTR0KN`b#pbQ}b z8rFZ>gRgk98FR~D&eO%%67ybm1nh~7db<%t>4$$lI^#X;qGqq={e_o?`n_0^jCjfF zZ02nFR?9YI@QyobL_C&(GA6|w`U`0qFG*H>*_h^hmGddxsnKf)yir6?^5{4{FDNC> zK`BvFqOdO1%l~+9iC4T)=rI}ddJFO#!0b)n?sJO~MZ`Dcb#sPkr0WEU>vc4W?aY^Kgv%Ab>B3zi+SC!QU35xi z-MZFEA6i0>P%tU!d-Uww=YoLD{wuF-Ch<0H`PP)qRrqEWo38Q0VU$1|2&6u;bYI|r zX{h)WgsP;Pf}s=DG@isl+uFg%)>dK z)%BcgbY;Z$52wSmiYd_qFz!OD)6mO7!%{yUBxq_Q${8;@M6oD4KbTbA#mK{gjic{q z!W~}pGMrRjxzE&|$GrDYJ>LvBsi7JILk^ION^x7|AuYvWtsV@fDLY?GdKUF}K@$;x zTe6ul#i-N{I|k+%#H#s><7@17U>m^=9A}bWklY}hjToBt)*yxgghaY_j8jhm`cxT@ z!is;Vz^C{&4_=|8O!zNlsxRD?{vC>hp6clRhHp3w+Big}DoMvU!nRX{tC@jU6zo7L z$)U4j!9)*a9D#!kls~(_it~wp`IqOv7y@Hel82A#Bds7flchsIG7P`^XZJS~OGS(V zh&kGpJex`XcND1Gua&RNyLdxx(-&3|#`imYL;e@C- zM1!Gv3F~uEv(DltvgA?gd0FTnWQd_3x08{=`M3*uoOcUKEsIeh{S=`xcUZ3lO0*@Y zwG3cKSNxsGs2M~ctR{7sN$<-u30cBuEZ;~OOmW-I8Vp5B0CT=FazneonSeS>CPSH# z#$En`$z(N=#romX5DpEZ<-JpbxbPdpjA9nDlB$NGK z#i;*_V`a}Aaa#EJ6`~l~!m4p1h`d+DSX8x9n{mC-&lU+t@rMG~X|^gc@M2mv&8 zxNIAGC?y?y?>h1bkV>vPdheSyKY2H%J3ff5b*OKq#nfPXyrfq}}hxB=K%Ojo!< zBtRl735Po2w>lh?hVmqX1Ki%oqFPj`*qIcomTa}jhs3*dMtJgtBwP}-hX~I=iLJWA z;zVtuK#7+UY>^O|r(<-3;-I%ptJ2FaKPqClivz+pic}nI83*_AchyZnO zp=E~fi<7I_4~Ns2%7PO%=ShEs8p%ScEJuzo*!{ zj~hzUKq1h859t#+(B28XWD}x^x0e=KwmMAzCwG-;%_UOA)D|stWJj5}7)lDGSMRnn z!W-k04I#G<>zq30Dxw2zZ(4ChEAEo4^FQvGvb-4ul$RF;7f&CRtjzXX=C!xgzlEnZ5N)+dL&z`{5l`WI<|{H46YhtuQ0)+1}{}5z>WiOG%OnL;Ag~sg;zw#wS>o@x zVcAa#e@PHmv*xD?>5Z_nrc>r<8Il~`4O%Cjn0DfUjlJ0cX0$xrIR}(AoeqoU-dd< zoQ~AMh#~36#~}${3IUE}p_@6z1Q|{4WG7BeOXECH&ap9PnYwF6(((!?9uozFQTQ%e zdEVCcZQ2Zho-1iHr-MFyS%kwko9y20LvqSQM18UBeK>t?Qb$fs<4W%*r|ymLIwbS) zBrJuU{`sHhy^g!T*mA|U@+hPu^`{l zI>)yEq~4w+JySC8Xxmd4Nhd#5NfJQUe@1!8TNrdli#6m2?lTeu!ksf8PO**!z6L!+ zl=Jtp=NIWlH+Z?rJ&2}aJW7;3l{2m9P1EFydf=wYMrdXGR(}@seCiR-zeE8BU>5o% zwtpp^QR&h)0e@~~yVl6_C}G)X_UkWXeA=fNCA@wB6(H8R7BRK2DiL>8lTTw3#e1^2 zajDo{#5vOk^SVPgt*L-1=O=%su+#p*#7Y0zXxU{rrRCj!y@=8$#~Bn4^MxZ4`xV6* z)!#f*vT+w5ICDtEEuhE=Cb8=qU(qfLTJ;N}wD-X*E zmx=ub0J*w;8l*@_L;)hf7?yi&AHXhVj%;fQ|ZpA%IN#aZ{;veUX2fiSh=sNdiE z*_;1CCC2_!SVTxX8YT$HM_`!RNZlO~$45&m1ulHWP={{5VRV?iBI%k)E$1^O*_D5Z zS;p3f=^~mAd4K%0h!k5hsNR)Co`Z8RGVDyRFeIA6&ZInvHm&u?E&QTB| z1!@BBj^uZEHuT)Ph(|pX(yY3U%%GGEvr*^ci5G)p#9AUr`QOv07M;YM+1sqC~8X(e{0&VXFU6HI(Uo=nlb>qOC;*OOhz~UQX~d-}^8d zs99=-j&gYuVJ3M$k_w(U?J{{%I4HR!-u=D)h4bx#D^t?7`I}DBj@^64Vt43$V70Qn zLjYW5vP4>5vWjEhNelt?Akv=On-tNUdN19r{skhov!BkC1O`UNh@|oaHBL8j3HEar zM?uTlg4*=fHc9B4+i6Nsqg+Q0(?tZ8vsIp5=r=kTgJ#ihR@&bU@;+{me&b87?OQrjcomn&ub>65L%CHAN8soNeGMmht(dFInkwaC1t*L^m1ph5}Sl{Q#K{ zkW$dS=Qu@>t}K)P&17{a9yEb<)0|v3;Z@ZX_=QNXzBbI**s`n5aAfBgsxGE`_)?NI z+8xZuLIcIvQpGSohp52#gXL%8Q`gJCW&q@*(8PIo&lrbJIf7O<>Bn zcQ?bC@>#&oY}?I4j0f7tN-Vy?Gw^EW>W0H7LKdff4AQyhC7dMSwflzN6zZ~SU4D(1(-Ezj}vFMUU+Kx8)XzjRioOH7&=;^}!({s}#+M%$2fy953P@2KnteBjlbnmZw~_B^<(VQqk=JLm9Jj&{#L&H_x)yB0OhFQX09zQQEX zs&E)s7@GFw&oabJNabcQ73=ye4luLHAUg6up}d(sg`lH=^`u`orfRpYZrr3ht&=uP zGw>&=$x%4d=sbBk#E|m9<=Cqkct%6*t zQ6kr_KEFL^Fp=VR!8W4lcRY`-Tp~u<41KOzS@)KC^k?~lFF}@z54p2SOaB_aS)kAW zis0%*m57uXRwu2Td@Z}U?Sx|8%NVQpJ&rV+__b}54BHP@rU^i2D5cNk??i~GE?aRZ zx9fyBl6p)JuIIeHLkW1yY1}%oC2rnt726oCsH-0jPXwaIupnb_jIXZC-5hfW50yLf z#t%Qint%TkU)6hTBp%SH&dOD`N#}slo2D6WMNc~bg~cS#bUU`*=uZXfG=F zp`j09-uL~E@x$5k`&-6m^TXyt#v_so^bpfcJy&coOWB+L=SMc6$oy)5zFrLEQoXo4 znLV%n>B#{!p*)LjCZ~lIGmD<&)4@6~D)HBG>O4&Qjz(cSjqIU z!u_z-adNw5+jG3{zCFAc>JJ{Y;JAf2o*&A#a3Q`%Y?0L;H9IphU6{Y|+wYP+gY-Wo+>!YPk#J zN(q&=sfCR=xKQeKzW=L+NToraW$|p_{>igR#-iHI*OOqcLo6samthqpMqL-?M*~_% zU9*QdB=BhZ!A0&Mz(S%7$EKE_l5+qtq$xf;_}aqr;nDRJf1600TRK4SQEPm~v{LSu zFs;Kz({plI>0tBymI1cQe2jwh%qh6KCOu&Lkp}+jz5Kqg6_H6Iw**a$i)K54L6-om ziLo|8UKbyPGr?Au5h%RF$pjv3x06`>32eSnNm15r3~)VuDXSTscVE!2#lO>NMA(k+ z(y!eJfP{7G{oVH?yEwtHYZ3X1K<8h^`sfio^*O(e5=bfpEtUsq6G+??d<}=~DW+n* zxS!@@<*N3J5*4ECmT~H*%>kT>maOMFR)N{AR4~HSt@qM5 zJ4pBZGIkg%YfwZ$i-91>f%m}XVmEYppX$eKGYPJ=c^`uuvybk4eK z5X8BiiUs2I#Xq3{x2~e;98Jww$Kr%cJsd!jF#)u!`-veGp2x_DSF7ccUZP~UP1tY2 zIl8Oq=t&!Ge>seo`AS(m&)>{6P2+tn53iX@T=Ts!7cc$(0!1-;1-}`zofI?V-(gJx z{f%Sd@X%Qv353&#O6)-AS{`w;#qcE#{Igv|@R|&pNqy&ojQ1u7PMxN{mrw^i4h!(6 zT7zdT{%SW9o8~}{V;ur*KNEYV-lJ84PueajY=?tWx1#WyvKk$J#ipUjVpuhwI6bP2 zXxTOIs{}PT3;s_%56M{{>Fb0&VcBL2iR*X<2#0sAnOOK12>KMyfmg|8IoCJ6dZ-F5 zwn_F};`E3-=_UVQ8-{TD^*rF~0wsEWb=7Yr*akV+ZK9&p>CyzRV8Dd2oem>3UBbY4 z#0|#SFvkfgNQf8deFfMqy2W}Zs4JE>C=_+NeB*lTGGx=10Zeh{0j`E5EA8sxVQ5(} zmT=33?@;lvP)%Odq^)zN2oRBAS{Pt%-;8qS3b^wlPJ*qelAyKW7?&}?D9XEd;WU(Q zezgz$wq-WZhWl!38u-nOh63{q1mTSMsTB)y5SOPp>UKsVLDzr*WH=$xfFI!Je^<;? zC2Nh{Nwp=-6c(roua|I}kCe?<`9l5C4hl-G3xhvIH&Rj~fZLhMz^U&4Nsrwn(jD>x zM_}X{3&3Gp%ChHjyHlZ{9maykF{C-RaJ3mRq%Y4ltjz;Tubr_dGSk<-F5E zz35Oj(j>n^wy*U*@nj#e&w-bm{!*(~Vf6@0TD`#%vfi&HS#pLd6d*-S1AP+n0Z<|XI9(MbbpqoZn((XiBZb3&=`UJOYR=|47p_<~$ zrKxciX3+3We5nVfcsbgHE{b0cP63Z_84^eGY}>E|xM9nau*laP6|uA~&ABz@1*0=o zioerJm0aKH@aoYlU1J@au=L3Jhi-VGExL6J*rPgc>Y=d7s5 zwAeEe%iUl&cMYr+52g36HFF?4Z^q`G!Au`G7&5IR*)m7?U3z7*7~Db_ZTx0qYqqAY zX`!moE<1baek^ugB5$fT)j{^mWKj%_!?Bf%avJGF-zvui>A*~&A9BxKQiPJsATo#n zP;0tyHo?LB&ypW>k6h76?l1&Z3dxGLTuXw976L8~S{WRk?8ujbu;?fe%BeeHyiEz< z{je~HE0q{je0+NwaSAg_7Eh;hq>w1$`i7Xd+wQa;5cHeE2hlQL3lF)YS#)QVMWGR;;v~*pPIRtalU*MaclT$uNZ9ijlt6j{4}iQr<-)=`yL5*Wyjgm^FCdc|BZ_M*@5D4__|NIFDuA zSs+~l>UDf^X9CFt<$5cvJ58qv7?W&E8yf+gXU|Y1up-T_`gAPP&=yfF{mH_;y3m&t zB$+kaxBT*K^X}~=@k&qBTo`v3ZqdoI=k{t4v8KoEq>b}db)}+9>C`r-0prxBk__$( z_9D#Z?Ukx<#`wJ-qgLAY`*T@bWim*wo<_vpL<#ZZ_kxi}1`VU>OVCQ&ga#98kf?+W z6Jp@yg(w%6#O7Zi2*;*U_l}enxVvf<>p1|wiOlC_p0B#EHZ?iY7h>bqbeZS`IHzLoyt zz1MLB%SCcE_C$GRwj12_>jn1^Ixvf#K^di3IdV#IaNk8GAq6v~dZLt%!s}q3ytT*n zXDNBb#F?XkyYVMJN<%6nMdscUD@~(7B1Y-7ZIbr4^(fD$+8GPewqGSMVSbo5-&KO|D!-QVm)>87#q*i{a32Q)dZYRU~~bj%0cgW)=so4;!gk zy^w!Dg>`1^9n$9;=E4$+%?N-ydRKd1?=2Ks14%1M;|PuKbe3o39Ar30@knHO+C@jE znl?riR%X=}M#+3xCiGifEOtfjRLXsL@lYa|9;z05J9hoO6P70G zMGkq{hBPaVTvhQPIAXhK=tJr5QWr+-cixcy<=_;Pq>xp3lxZ)5S^Nf$eJb92V_K-s zqK4Co4aFUxr;q%gKIhmqgd@aW7OBU0NEvF8F`^S8J7IakcH}-RDgC8xMxn9HMB@Lx z>_X$nmo`eO;HW!-fpaR@3qn^fd?F)&=O&5vLA!O=1<##tlaj*)SgjX^pl&KfAROnc z94o*mj?P<0VH63`{3HXK#4+(@vdyr;cin_rXL@0qVuPwYqlR)99-Cj8l!jh{jLZOw~a&66<$IE zS%Nv!gf?D-$DE9r?A#+wVQ<1+Qo(zqPD~?R7X>jt~VE>@j)j<4x>OPbq{*P0T%(%N3+%$u<-|s^-7y8l?v~O_gOYD2aGe(%IB6JL(6D%%(xE1!ej>bhR<+Re# z36g;a9dYB#qBegMLinTXDV?{YDmXE6Kqn|vO1!VcMZXNk%~gpe1{+ElkP>#KDdj+G z`g-uKg#P?MYy-Z;gC>jBq53t>;`WOW>Q!$JUwM0?ASv_ykerzve z5qtI19r2vCaY#{}yaxx(5Hm-IAYmwTl{pI`wklw_cl$Gt5kpNzpn;&zs%jy-Xv zky_;9O+gmkoJjDA{ROA~<_)+)2@dQogMLaI#I=r`s%%2$2H)^r!~*Tvqgu6Ho;x zz|5NN2Z^m}6pRYye^=Vi(S#_?*T;E*N$y|Hu>IXD}yjKUYL^BB_*7-VvAGP8wMCX~TP8S<5qGi*i z-9Gpw6Jc*tu`WZovqJqL$)$YQ;DLDc5)rxrxT3=zfBSyZJ}en{&90^?iyzar^0-J# zf1;-!AP=(1&dyK^!oU9CwMdYEgUM+lYrwc3kQ>< zsu=OXPPgOdBK}AG^VubOo@eo z1A$)0ztpFXv#W{p;^N|e(<01z!E#aK=qdFebRN@#zX~Ct-r|F1Uj|d_HT#`1b)q9+ zvHz$bR$cffy*|J<^6UIFl&a6q{6zfU1}pW>Hs=uV|8Y|}b&T9){<6DCO|W&w1(ZkZ zK$+p*6RFhMQ2z<5s>0#5;%Ot?fmL9$qQ=RFt-Rd3{uZJxV-r1@d054x%^w-WsqIZ^ za8GQf4pGV}_sQ4Q9(i1mc4QPKae&9Vtcll_QIZ+VU*Rx7k#Q@H$5;HNK(m0aB~gfY z^hM{L0d>UIM$gd`h&XZMYFBP_2LhvEMsb{YJ$t$7;KPP|_@&jARwEIs5_dfM&V9Od z%Js33{Abvaz!pZ?`Hj#*piD*T`wHYj*bKT;LFAPgLlE&Hm;okFk9ERT2yq5(*MZ);WeDbmKBqe6QIGVw@8T2c|C!Y`7YPu6 z{%cnMP(V}nCP03h&4&Dj|7BxiYwBWXV(4PX=xifnY2;++Uu9jh=-Rm#My+K*~3(8v(nYcPx7(<**>_< z*yXhT&*SA)e;Ww?cu95|JH1{98t764-uXZ8^_%qHlk4dp4lV)FP@sq!g>b0r zqmX*Fb>-7BLImk$s#0G&>&*N8y?Rh(3<|E|u1xR*}w0wQlPxsOPz=g^>e4e6w znYz^qfch@Dwffxk^JcRuH}mClA%IDCZi~P3WeIpseqmJo0SA1ZvdQo3f7YF!t|bGX z)*J;MpO=K65BBvwke|0_n~TQ32&sX6Hp~Hl_wGUc;P~dT%WjiY_sdPim$TVkpzcvS z7=TL!5YKO#$=~OW0m4WADMP*4_Vr63^6~Qad8+<(72v%Zbl0D=EI)94d(|Iu(O*67 z>i+!R@%eH6p}*Pl5qXoma|y6-OaU{SR3Bcq5VwpxcbD*Y$%jBktA6U`?MriA*+vAA z4)s+13A*_C!YHa~`?UuajXtppe8it`0g(5p{15o&;x1wUBJd->@VM*f@*J?#{U@mypGxUJna%c{rvrL{nBjt8I$wIdf!DKJj_r0sSIa%l3nvj z@biox9QpMznBp_9E9Ol*;QbPo`r*?`qV^Mc_Jpwd(@SFea|!e%roh`6{9Swt$N{`Q zH&bHg0Rm)-4`^S=--c&E!&UY=*@w9F$0sKLN!Q0GU-xHR#ix7YaJ0{-zQw@u#r_N7 zsT9UU%XZrqWS#O))l(iB zO)-3t8NFh z_?U{fGSZwfJp~wGw}tpJdXL|DT8HF?+y|vlwIlbQ6v3!}R!nC+xzW<}uLfi6CTm_y zW$*gpO!X0uELgDi;}u^RmsQ_ovMCFxX_omceZ+9HUbtAoJ_5R(yRm(vSc8c+Y@Fo+ z=~IPWSB?|HmKNw+m`NB83wAy-)8h4B%b3z3iHdoc?2N;cP8WFR#Qt4-I`Xk^BjGl{98R%}v*B0N6=W$0O!Oth70Q|?KJ zVun&FFmVOZ1?WdqQM%W|Ekf~#KJLTR%68-NW$bR%RQi^caA!&#JE^C1hEIl)aO_x7 z-R>t9i~jHxD!^7`Utbsr&+0~UR(4N{RKq$e_h`GNT zpk$x?F?rli!g<`RS>M>zNVX+GOPCk9ewKQBl--zj46h79MA^~gF?GBpJSxYNt??FpZP5=ho2usWQ?{$bdd5m0^`DWHXJ9S34>=#=&5B4U13m7aBFI8s*o+rhp?{d$&OhG!#* zi2%Vt9H^%2@pyoy#f4C*5-l1%NM51b$H1G|Zpyvi$f}(2qf*{ne!+YCYYoq30nHWB zNUU7$w#Af!16?v^h`e>?sW0k^bZkf|r)nIH2r50^wH&wTz3@Bq5W9uv z&!{{W|yg3sKH(4S7 z%8kr9l>fpXmoYMI6#?ZAv04~P0Iy*;SfM;fNF2B7NRbh0WBZIH_0UOM#DV;cX=U*v zVhgaNu_l8^XADHQI|rB4Rs85EwZ7;I=8g`j0~6k|FSX2hL1th5{4N_ExHV(*R&}=3 z7RlWfdafJ8M?e`#jRGM~>(AM<=(mJuOqW-Mxby$9?QV`0VoFaX6qM`T$n3noJecTgJIm(D?u zMCN3$on0Nak1L@{<9}ArMNEqMJ;o?EJyFd?V`GGTQkb{NJ^Iic|D^aB9>1Dx&Fwe# zTN-zI{aF|blf4~x*7S8lweX!w7((Hyijn}B04}7U;=L^w?9|ifF>dTNV zu-H>Z&?}>$mh%`o)UEKD@K75~LlM;JmpJbs5~rQuOavm4P}aAUY$uw?N-K?gEHmOh z^V2IQf5`?mh)NksEM2X4>}~XGRkpHe=ve1KV zFZ-c4&Sw)WkAUsnn=97f&fmQZasrUnWZJ(+CoCJM2!}FXr2KumLyW{cCiukGc-bQ< zVnQ9&dxFmdWuz(Ew(I*d{yazDeC1fT39%@NdixP+>Ty>e*fX7AchR+!xS`hJ3lEx9G^q}$f z^M?T`QH-EBG&xIO#u@%QSiaV592IZUfuVEmlHTz$k@5C2gL&6z!1r48zZDm%2n8+c z(X0BxpgOO0H#p;mw_pL^lRyC|i|4h*W}}?2l&3{0^S>3^B0C{4liGQIRztpH*z0s( zE7WDx?KA`xF`@f53dEn1H-jpW6~g5iR*G^oMX_b)iL2XVB+PvDf5~he#F0N%i2Jt!FX;av%$WUcuU| zLMc*aRP&nfgf(r5x)FdSet($!=&dw;D_4;`zp7b^G2UKk-zyz7-~9BTXHd>;H`wbj zydp%4a2#)h=+W;RZHs0+N3VwDZ*$+0<>nQ%mAAOd?1B(VKNKF^GkEQAseK+(_- z$Hw}X^tcWa*9+r>3}afaP51P3ax~D2?iw71ElqP}=o3PMe@v=sA7@dk@P(8c=jYLD zLk;o`)UuKk;I=+BR)V=~E-r=0)>z`yExoOe%M&)Qy1P|r`;GwdXCI~9#5*ix(V$ssj3+ZI4j`w{!vM0Ogi&YRq(LjAUe z$(gW~n1u({)+VlN(-6%cccy3eJ=8MW73QrQHq5N!(|O=@3fmyt%4(P2m;e~G!Om8q zgcmJ3@cm(i6~0lOcg&Z+VNmHDOzCds6f12Kf5sV zZp|KRY94V(7DWB8x!OETC`{dG+y!OK0iG9S^GK5H&%$s@%f2=iIR2DMwNcBQ4Wt@A z7^lVq_Q{n3B-eTd{)TJIt63shYTjUd>053QF5-%s z$ZhOBo6;J$+}Lk}sE5kXuAvTDGQY&6s^B>`%KSIWD{m#uSH<{k!T!s@bpsW#d8oWy z1COQ~achMBqi$-_g;wSfjzOYZ#dF51byC3VsF<1=;ui%u;qR0-sVSVIh4e~vbAI#S zUj}c_40+kY%+yHnX1>=CmD%S0M);fX1xJ*x=e%q9Tq?+dR?U4Jwuo8#l!U#u7k~UZ zH;3kbykbKIbX%Ng>mAs?U)dFmPq$J)T}SGAVtRXvCoWIJ);3)pFGR&Zg9NqZrfUOg z1Le(|oo_H^(!KPJJuUKS^xwp;lOOo&SIz6s1H6X+GDQzVe#fXWfRaEbo5*BB>*IHr z|Hf1E~23%78axP_+kANke+1|-A%!gSa%`WymqCZT19HXfP0OV+*s zi&4TY)6`ZvZRX*GhIIF1vnSzMa~2gKdT45%8KQbRDI!lJvCj}#N(i#8M*{{>k?-(& z!^l}TSt7@#9#B`VilDpp!`g$xwc(bcnn!%j`4qm_6M^Ihmlo_4n7P9ROs61{5KIVX zS(1g8{{Z<%Mix9VUI~fv`=bdjzB^+zmHycq|IZeZI0|g-@NAdeHVfF&Y9m+t=H~lK)LPg%6Na05H1iO*;3j)=I8!-9C z{usO?mEYbC>kr@ZA+a*7*NPzl77Y`2o#HO6Gg5P!`;WS{ly|k9B^LdZ;|>02A=BaG zKiT(EN9T-;NKG#E6kUVR)Gw=0JE}iC79`ZF7^pwAHo1b&t~dIPFR=f-DGj(Wbr3oZ zd=wxZ^`O5{mdb?=eV5HGyQH9Ba?X?1nPV|ihRc2ATQ?tL*5rAX#tqN_4l2=@$h06r zUHa3}P8AU0>LF%d6B~m&I{kaSnDPCfH`QHAO*5P*NHx%EGHGjZzJ#49DgY6A4x!~QU~4(epY91 zMl(Iv2ZH_muuk9en3}9l$_p4@ zP4MA^;pKb%*^FH_@Cp}-+`wePS1AWChtR?ChUr7}@v?So(-^|DlXTZ+)3}Zo^JSU_ zqJyfKjk~+4eDx81ACY7ERYXILxAZ1JTUg}jH>z-4N4lkTAFS;sqg0Y5?EE#YrXciF zu6{YQgNrR=0V^Wz8na$`$URpG6Ga}&jG5Yo(HP}yQ(6A1F*vv(+p&Fzr>(>C@mjH$ zn3!EP;&XI?xK|s6#B*2M;uL?HuAlLZFYTu=CvJ@#71^4W+TkMZBK6XT+F0ErZ0-1i z*+kQjSLyQ-oJfVp961Rvg0>8#u?DPN$dtv4HOn4P0U_OIH)({T^s86o9xA9hecZ*+ zWU)pa?ja~L)hvu}o~SZP}Rfl&F%e&srIH@ zWM~ZZyXL+)p@;)UkN@85`S}s1k|v_Pzsr_vpf5@WrUn=FJ>~ddZ3|tjG^w%2GRy~} zuF9=;0aDGd40uNG9VXi$dXqQu^mVQ1!09}rn{{u$gSF)kH#yd9q55XKNvxXJYH|c$4tX-H#pVRx6Hc zDt%+{TjuK14Lo3sJ(7m)r@SDlm>+zBcffV20sm6#&DbB_2Fwny+0wn10 zf5*OmIGJ3nBs9~Zx?}2xeBA7gDGA7sE}p_p8)FEhCqOwFtF7@RFYZMSX?dvG)r0i-@4%WNH@GmaGnR zkMs>32hP;uX;PPmQ5N3v=a1tbF#x#B=gI|X-;2e#3UQd2`VR4zch#hyOn`KH|53eQ z-?GmYWqow3RkwgJDaNs|K|&oxlID(y*6AW+J7r-P!hq`EVr$7@gj)+aM#IrpC==HY z<$Wf#yf6X|bsL!>0)bv_RX4w}atE^#p0K0)5#;fHO0E%84|)MF;+hV3C?FT-Vcf@} z6_N(2O9W5F%(0MQMMUBad=&#WDBr2?$BAGrU3}S8h7}QAupA? z!(^uDRJJb0+wTqAa zL-vkyV5<8Q!b~9uG6sD8*TaC3gAWrVUC8f?7aT1A`Rr_eb2W<2cXXjE8wpIFo#r() zd9nRJ07gK$zc;6p3(5%l_g&e5pg+QId}JUTq=BGz$B)1)P=I*8GBSd#nZS3JoKVwa z#%=|D6*7H)evdq5=_p=DnHfe}*KFag3G7GdeT-Jn?van5XR_kB_!Bn;fBEZEEKY(e z=5;iCV+=NILXP#&qiUH}QoL!iK`j1D7k0a@EG_!c3JL*N>$BkirS+jjF)IJXk7w1B zHD&U}X%KY*#9KkAe(3?^Nd{%kb>+xM32B}ShfxP1i6^e07T{Ku+D}3yzfkFbdQ5ky zEy1OQ7xGnV2GSf%OaP6Ue+AbG=-96LT#HT=XfXpqtxihsu;3f_^tp5q`G6yX$p=k+ z<`>&LvE*LSolGZRA$^NYJr(@D*89ETnFB83k5Y;@U9o6B@+IuY)(6&x`^9RrH#wgh zHRk}+C_sEGdO6bQ-R15plN>*N3gnZCW_aRn-{fQXyo3BIu{BAQf3$vShd5xSTyS9z zqoj21m|b~Q?UJ5T*(ct)8&B9)XNU^ePVr-YvK<6gzkSJhAtw_A8@(@kGnX^Plnt^y z_a9gzyAiM&tP$$uQmD?2U%)KHB>fR^ANXv}kl*6K8NtT7gm?NgW$A4xH@qvp4)Kde zW%5Kj`9PSwh*PFFe~j>JI2>?^qeK`u_}~ZzG&J>-xz!8i&*Rz*#Z45vTo^yWzh#Y+ zPfIKDivh?8O&qAOAStER=({wV9_O8iEHB5jIGMD-m_05AOn zUXdn+7~a*vWc(=LnSGynJ8=!onUpI`ix&&kD6m`~D;&W^f9Hc|MnXz1zABst82z3L zYmcvb1-`qF-uI?ZtNB(^M0aUB@<7D>Sn+mq5|{&r3&VW6r)8f}FZ-#0em(yC(J=UmMFLfuyp_{B zUasDiBc;8yzdTWRfWI1SKhIi8FN5E&b!ODE{3tc4-z3K<rGde~CNLbT^KtTze3!I4wozVKX*D zEqL>-KffS~x#}MCIoOje9hCPF1HmG6JyY5K@Yx>Rd_AeIDjLZf7k`6!aIEtPxU0D( z7xhXTqP_<0Im9qBGpaIg?Ubtg{aWp2xLr;0Ncj+yR`45kqq7m_!S7W4< z7N|>Ve?>#GW;-vO;2Btxhr(G%AL$kGop%pcj&W^KBH@on9fFgnP`-!;LVkaB-{3Q^ zbfvlGRD=GGDz^3Ojcl*U6HWGSqeA(Bc7wOg4Q!i7s3N0hY79VeOCAE5OeV}9%& zf5&$l!apQWYRXf&THwXmkA6xJAhd0Q1Q(HwS$qDV)(ZDINUdf`ME72?ee_kjMw$zZfI%g~o764G0O-6uHxB`M(23Pdp z@SmRj+{u|~GLa%2@|01AJa4cdKDJ#3H%}nljqCxaFm0dX;RsE9OFUeCQ)@^ACLGDdj7*JfK?3LcU!jEu*$%<*$ugwf2OFg zoQfZglbcF#HA16X*D8E9GKb3lekO|KhjN#-ZrVn12R9}Z=``iXNn^drDrS6ziV zq@BQy%Pa2X)W4wln?K;(k2qz0sn7Q*Fo?h>Hh012P{4Vm<=88$an!5*uMV|u60pRZC3wf2^Y3z&TSc ze0+U^Nb?lHN8(ZEBRqTbL&`nkH0qYOfqwHyf>0i7LKBcwplIoj1%@Zn+;@XnaO(7s zS({U|(D*XNVUE&}4|J=BMwH84Aa|`j)5R6_Dz@f9To_`K_L*`URsw8|2NFdYxSre=Y8A!p|xHnr24=Ia;jv zX<{xa<8GfG6#RgB%LNHw2%h*efxHK2r?RRI?6B|s>dC0a{@|%-h;ffGGh(Prw?SO{ zh%?Gi3e^;TVt#O0{>h?mx-02GI(;{LKaPLI;bz@a{E;6XZ^4PZf7eVO3Fe?>%@5I< zbrQ6@GWO~Sw3}2o$}K+(ucL!fMkTP-`HX6g$pNu+~1}_ zUN#fEU1~7Mc!XaQG5b4s3N8O&?8ZbEEi~*5~vP+av@$htY{l z>ia&TEMZv#d`qjj8l=LKkJPvRej^tLb>Wa@RumOOy_9gB?bWMq!lL4Bqd14_>uSU^ z=Up=B{Z>S+uaZl`jHs3pjy9Q}Ml(2*mZcQXTl49PnQV#Oe=f#iMzdYMZee3%*}_!N zGegv;4&HlEXFvd})%CR9(m9MnHdKBU6!#N+@cin*Kj=Oyvm4tF68L@dP4iTFt$81w zHx3$SO`Qm!z~343jmAq5CK1SPXJBd`M(Q}}9YEJ(P9l46g-md-IgY0lwUN^e!s0=T zMoGs~R;R%EzW#0K7x>ph9yvha6#|_6*>IbYJnrhg@ec$BzS&R~GV~%|GQDkX zKXTy0Uym|Rr-GPADI2z|%TMYRhMB99c|zGs9Ok=Df6)hn&F{NUXA!1FJb0K_b8_#{ zvqJO1RK5((>>e8?1~BXjJuXg8zP+E(xOWMtxMxr(0rJx9IR~C6p`?t$NfSQ8Z?W&( zdR_NQVadU>B0fJ<8{DFn8pS`(+{BFy1b~wAq{q@490jtWOGnSG;xm}gs!GpUc3h70 zOJ{=}f1C!}=i7lri|tL;^f)WoDO04>LrhsDMYInrR3GgrkGn3u7YN8xh_gGy`!!tu zav+CT$1K?rr_5%GEk-}=;w=7nZ*7I7e zHX37^Ma!};gHLm`Tc63IX-LM2s6A6`3W)wnzz^J8JOi0z;C|eF6Wx4RywdfBGfqW!7taz ze-R!-rvSv`@E&t#f$T_V4SP*fv~Q&6>UfnZ$Tr2_@0Yo;5 z7w$*#IT8b7OTnoHNA zuN4Oc%y@C@1xK~4N9DdU@Q8(<2s@p)8@_|(@pi=~5|W0%tDN`Qr;GG9J-MkZe?oCl z3@z6roN=A|-(8qd;gzW1W1^{Q`1Ck!o#-XlvPuJEAO45G9sthmpHWrP>txll1>>b6 zG>Lye`_}_Q^!rRSi9d|p%_E#{-}APHLqHVirO^hh^c*{!FR*ur%=%G-iKh3ZO^kvgi)l}8^_zZe>K2?O^cIdievfFyQmoV!kkyQh$^O>Gy6~hdRO9mBYOMg6$F;msXb%^==E`~20Y%n zyMX)j8E*=raj9`+AsR`Ee{+kdl@pCnp++B&M8osXC_ZLSsE%)C4J7}5qTmnDbnS`l zJvNyWtYw6sU}_8ST@+;y`6nb}$wg3j`(YIFdU4*k%i~qo>4W|x&6FrLVTsYJUq2M8 zM%FiHd{Y9%Tm6}j-I$~slS|ntBTS`B(Z?q}Uo#ZF3K>0oz0Nd2e@45efpv=7bSli#^W&SYL1yUbztx30HgbjH7%d_5*s`mA2Egs_OYaF(Eh^8_zt+Qkn znzH=KAu*Yx%TH)_bqFR}DgDN!Q10&v7{J0DDPtg3G-`hK3qj7*2(0DUHa8~1)a&dQ%dM(X22@~qL()%w=s--2cIg6HS&B)(6bYLE!zj4;4}1E6lH0XiE> z*^k@y(44g#6<2B0MZF7P7h-R$ib>{8hWgBFHK@?pGfMQtf3raQ^zvwZqQ38nz9mqP zhh#2+Xp#8@B_}?G=J|a$yu`7o0rz>Bt-0S;i8%@XX5&sS2TGE4RBxU$SdIJ%v zby(0YdX9Wch0k6^tWhH-(tR}yQW577|7empe9sFNnxDxpP0s>!r2?TWAV@K4eCF55 zA5KN8F3mdAe;w$PU$;C($9(*qkr~@e_fuE zm)yF4@kFJFo^wgTir3&92^L#SeX~0QHTQiH@yjQ4e{eV^H#a8pZ&-)Rd-yA(^a?k% zlXvL|;VT~@8&Q4$47t}T$yRTKRrm>lWhP|~0d29PYO6;FMtGlzWwkmxO4F&YYa$eQ-yw@VZ zE8~}dPw-%=<*d0e{wX87VTr&PeOl6F;@7cmf4brNs)ycCAOCgA8G?2phxP>?RWf-d z8OL2hY`l5Z!Yb@c@0kqMSTW%i3BF!)Q>8eriRGs=OMu;wxB?8fpIf=OUSH%a5pMP? zphs-ZG=0-(7^1s;P6$k@aEOmi&}erNERGA z6~=R~MZqMp=lr3!cAngze^UJb zympY!D$W^;joYnem+}-N?3dJlHp>IswVE92?v|zZDghdI)~79&Nevfqf3AQZyBu~r|ErFE4s31%Pxf5z#WR#COl%zbX<*6W zx@JI9)N`?dg?Zf~?Zn~MZ$J<}k~>hHjA7*>+^2L2Sz4EVL`&bmPjQdH*M%x8Nkgp48p%GcDG)nD$OggP6X%-H#Bla8?H@UO?Zg|?sS z?{mfLmbUXpm^f9>Xy}u@rP%Ee;_FLT#)@hb<+!wOhWeIK`5Wf!T$#OoEOBjrWC8Fl z&}di%waAKB!6Qu=f4t#0iUL(sA*E&H*0i??;9|_?iA_7`PO1;_i1{iE#!1WUNqXy? z$@e6nJ;igvQKyaWTncAZIbfOK;BmV{0(rb^+It$4TVgWhgQI`zlb~AIEzC;b(!HBT zRG;_L6Unse_f=3pXysD2UQB6ED%o) z*JdXhfO)OVh5g8ti z-2@=A?uJW}e|l99twN@1{TLV@WM!C7!7XyI5)GPdNVzDy-(DyK_hy6G%b&WLcO)1H zx`NpR2+Uvad*4JLF(Lrn*l_WPc&a{;qNBWl9OD=~U(V0d zedh@df87IR%WM*7NvWq7rmxz`_Qbe3fBE|HgqQci81w;^4hh-M55$^K{H_SbVNDws z(G3~!iV}=(H4L2I%;G_Rex9zm)Em=9B&OHPb(inLsyfBtR%xaC;t8$+3=^OmYpvK) zGIc#iR-qmPkVC<}P}rNxH?OZzpG}4)5}u} zAwu8RH>TKup#XZZyn(XOH=4NtBE+2ABKN3qe$R&ToS^d04h~<~LNWUaDJaLEv@=V zHaCBGmNmQ$R53?sDI81X6vK1S{?v-3$(bJHPVMEBlZ=QH@!M}(h58HdcWXTc!`{X> zCwA`p@;Aiq6r~7FJ{FzDk%95kK>;`vf2*Gyy9BNB!Ru^|elT}XL*dn@@b!)aV^ISB zyhd)Ve(lTu+ooBt-BZRs>2kYjMbqORjX-CrD~$dLUG?kL4$H_Q(-6E{)&Lt+yac>F z@@X*N@bjOi2%Wt{!WsJ#+`IWb=;K9xE^*BFlW;D^{Y-~YEhR>uZaEqcWkl$ae~wK7 z3<39^5BO^2L44|KCJHViY2=m6jrygTFcukMM!`|(@kuS;Q+<3Bn?6nj%7WMHutI$F zexNSlbei1hOh4ccMOOWJ-k+ADYz+O=*@7>AC zusIdvG@nwwgE~YOkzWm}sjX4$d;)0hynaq8KtfnBJa4m7@R%tLK%BlCHh4WG(bk>EArXg%s}+2tkjJ22JUc})e-nr?-pNRI z)CO1m^h4!XRtU?(nN>yrzbI3N8YO4Wvf8r z0z!Q3k;N9-KyZUlBa6iNim@hcK3Ra67=cxPuK6iQ#bPlT9wAN8M6#4=a;-CgFPDtp zHzq(PMwS5XbBplZ1Dj*5fBQn--k&;Se8=_Zfu-!7`aQfKvpW)ho0>=P7>-3l`SzA& zO1}*Kg==E3JS*jP;oa}E+wK=;O<)Gdk`T*2*@4qUG~s2naMX98gZR%6I^|3Hn05|O zKsL^@EdtIsJ5&;?axCDJd4*QTkQddjoz%#hj=Fkhw_)$EpHDx;f4HaMVDgohDF`Kj zT>4^6rgX?vTeXQN{Pg}5FoBOb7p5Vq8X0aGobU^tDAABuj;W}dr`8fpGxD2aCX=#s zz1^c(&Dxc%i$XNz|KjK@wp<0GDEdJRa2o~*?#>K%mjGY?=r_&khNSA&xqBy2%=@uU zZrD?M%KI&MuI4A;f2K(zwa$b2qu1P1xik7)u!OcE_Znsc7r1NTO)Hd^c`WAg6Y?l8 zW5tdZsKC+r7L<vysjjXR!jeOckpIe==+1nNSOJh8RAlE-m}@ zSz=BQ#PbQ`_Thbox6oDbC)>Pbgn4s9i1;@n*_<}wvg$*meRyt$?*y4g2M~$nzTKu= zC-FzP`Nv3`t;_H|o|jIG;9S5D4gtdHOW)=GC@%@7VA%!ahucJGf=j>PjCg$$r#?uz z#PJq==ur#oe=0^D%|??<;NJl8D zm^Xp>yeMOta-Zp_CVOY2y*fqtJ{lgtoR`Z8NcK2={I=T5>I_7?F340mD4?jMK zP~TQ8;LGO*L>mn&VyTH|`5}=JoI~7dpNckrKxFJ|f6iiT5@4KpQoGK%&?#&}Rd#6^ zzZ@dk+dD``t;CHL67d}iL09S4zVYLV$kfpl-f)=0=)4{?3zw{Zq`3b4-hU*8*v;GS zf!`WntirPL>xm?H57FO~tF%kv#&nTd80THv<882oNQlRRZ;{46kttt=4CAFcS&ew^ zrPc7gf5+!TaYXnfC)bA`koR;dYRwZ8ekR#B8mRuLAPBU^@wl8}sVGC9cwX;Yn`Mot zqkXib-un$s>H&w)IAb!-;osde<+njUR%6`|!_LogZ}F~q+0sq>e|N+a$uX#>r2I&pTh7a4)%vjS%_Vk( z(3s~#Fd*z?ueeJiwtNFWRsQX~B`}U_05?5&f;K%C;15}|jQK5;pEenCpcVIc7%ONJ zNVU=18F7sqxdGH!O?wWt$ivU7d9XHEPA@1$Iwfdl7uFaXx-;%n6(s9DKG-Sk38{3< ze~hld^E3?hb-dd7G1QA{t*s+06dlHA2zWfKeV+X2Lb@Zwt`Myp-+RW~f;a0f|HE_+ zO1II}q4VP;j^?t|-Ro>k30i^)c~Xjlyyjf!;NG4{T3L=}iU&Of*cQ$Y9@ELE0J6-J znWY3%`b=MQCHf!RWw6|3QMyCNgUt>ze+W-A*yS)%CW9a?n>+*s5=WY^OwfqE^#y1WMuIT@+>o3OLHE34$z#wjMJ#JWz z{lffKe=I&V&SaRzn`F|diJFYaSGfy&4}curRa|xOyQivh1o)u)2vbM(j_ZC#e`8fO z-vy8kI)M%}R8~ner~6YD#!5togM%zr=np7(dS-F#!J~I8wFq|)0?a5sXiJ>JxKoiC z3B40giVhR&ShT_$pM6A98Kw-x1#-Q|oqa*ScAhs!F{|Hja1BJm9&52XYq$I>RW<0* zQ}0=QhSv0ic!6813B!?}^HSxzf9u9!+5tXkj%c6OLW#N8*maCc+wu!nEwItsCU-)CR> zOh9yZq4up!M2(S=Wq%>H(*5}PdwpO{K&9V@$?E#6;K9p`;PmcZdRmIzMJB$>DcL?!W7& z7segDL_GIUbEIO}v*d%M=7WeJkhr_W<3;VnnA^q^{5rbxwud}BuC}}`+Kq6PunsB6 z&Uq|rlH&R;g4bv}we!Q`ocy`FDX(T6R_{j>8o(Cy8X{%S2R3z`f48rLqvnV>5GjR* z6;hL_0q#v%ZxfvXf}Y4Hzbe;lLGq#2YNbGx#|lzMvXMXI%#X05KsWbu^4E@^$pV%jb6y{!x8fTGVw&!Itm2ZojSdozg<>_u zT7F*NPy5-5XL+=2e<-S?+Jn{HCG8LC)$z`6&qjJ`bC+jg-ImQl%5BP_@D`pih2~x$ zCuAZ-R8-iz49AeBV?#MS+wKPW9Va65v9+a7H(PoN-8-s;Z2k*;IqMah=o9ha;%?7a z>b>;GhCEC9asBPK*;}mpN@0Ee_65~h5?QH2M=zcr@Z8EXe~NWegbcXKc=pJom_NpM z3kdmzO>;*w^x?i;+Lo5fSKq-k!&$Ho@+?Qp;Ff< zOT-(R?srRt*i4UKvv>Rk6E88up5OO2RdK9C9LDEoANXllqBFUUvL{Gh?s^S5qf2~23;?Er1Nz9`~2~ebjTN`k)ZC51`b9!5t8jTYbupc59o+bz&seKpBWuf zrK!SY)KQ&{-$sKvZ>ULH&*Gy)@?hvxTpV`UpyT@of3Ul)mFZc=2dgjVK>QV-dl~W? zW80kY7avB(hF0xuTE=KTP1qA;r}oG#Gqt{$A9_WmA128Q&;3NYOuVn(x&}zucndAS zn`^TpB^ZcY)XiYbSz>dY!0-WVw8#MmGlu0dH7w|x=yE$Yyi=}hlh}H5mjicW_x8hp ze0hTKe-R&hKMkqYk}uN4OKfaU-H6G;E`+ef$2loY#l^kU_g??4c?9lPG7^s;N}=w? zUKb9u+S>={ekulGlQ20Gnz>NaG)iM|^9dQ~2)@2J9W~5pQW29!iz^(C`oI3+du)XrqRDbCz=DBu;2e`}USdy({}bKgZZ3JC3+h_gBdX!rn- z6;1G%<1k~V7JI6Ga_|iTFN5b90838UFDD88{eI5>;@-xE6JU93zo>D2bNFx$@cDr% zCV}F5wb)dR62qhsPNiR@YjcZu;~ci(vpm*n;Vdk=Tqv#^1)uiCJ#myp<~;`TE<7UUqYEU97Gs7?_+7U&sh-R zwg5FQ&`UGW0)Z%9y+cj5or?t+Z7Ink(hK8CYZ{t6+`7&)Awh28D)yU7!R zDz4aM#(O}0SYP_VUm|cj#W;AIIVFpW<*?VDMZLTrnQYQod*khU>P+htv(3N1eGjns ztWbi!udnxfA@BEuVA|Wp2_BPaUVt|&5UolMmw{OzDe3c$N2#Zo|F@?>4GFXue~rwM zf+DZOX+RPWl4V-rwiPSG2=;l5TVg}mASk(UINwTRSv(((U$e&tE-cFQ6o20m9)3cl zIi`NK4#H9c&F$rUP+jy}vm`FX4wU^$RiY}Y+Xj9UjJZ<>`lG6OPD}oMB*xdT}t3&wS*JV+@_GFEj@>n{cn+#L7%k4@U z;gx8eA4Q@`rAq9g_ZYt#EBgHJ-YNVX=s`1(n*Yv6EyV3lax+daVlwg|bV)_MD}28f zzPeG+8+EtLBSC@Q(?2yJf1_=rvyb74aq>oh2enf-4{8L!8U03OJS>ed)x^zzsPjZA zi(%m(ah9k=YD&Q~mOX*Df430Gx@vC%?dj&nm9~tY@PhZ*0y`9U-CVo?3PAP0@92dKj=`-I4U$kuyj-;%g_!ggmmw^_K zsmUJt0mTq_>W1J5e}(_ac(!{}fERY|Xve+!Ym61GsUO3+=ZP>O=^ltW8HOmkU(HCnK%vuEMGDoPxG`-= zWy25q13@ z3+fF>(UYTt)fq`$UQe_Z5q)B7@1@jzbz zs?V=!U`f9J>S{6u{4g=FH0=wB)}+{$Jbn}9rx&2Yeouq!pD@4)jw-2iD-59}qz|{n zEW}zoNF~`XNXtE83>4ssDvzLNgsy!?RH5E6D0bi(B8823!#-?{P17X^zw*4_IsHgu ztrux+bw!+_rncI|+vI8aBF z2se*ls$>J4X=+LH9?aXqW!8pG;=ewB*?1cWK#U}69wk{CLS2K^edIv%<=#~60Tz>L z(mTI;Y_YKbo*X@54vPYZ%_Y^MFgsV){d_s~f2{~)DI$G4`D(N@3*-uw|Fbv%vMn!J z;~07>DlgKk#P&9?HmVrFQru+jJ=>A>C5-V!fxLBBm(q8;D2)GPZ)>}>dMrMJVHv|G zK&74zi_-b9Nh5>WMPvi?sH722o15ev0i@A$kyEu2Aq~o@JZMsvd_EuP!^p1(crotU ze`u2cPb8C3LEAlHJ@4^W86dfw2O5*V@qS%!Q=PgJJ#&)7eRou>PbZI#Z?j}4u@PC6mHpLVXOL+$)JG0PY@aTs{|$<5iIr z+eqGQ3XxaHjCK}c2|M2<4G`yDMr2Eoe_cZ9{(kTi%~w2B`U#`f<<$K$25k^CqKi7& zAxM*@$RMVvG|$R?>&NdATpnFYB+%Y1T*5hOC~mUW>pGexB$kKy5H}L(?>Yjvo<#m~!vE3otIfDE(}LgTXiF=^7$QC73@^T$V{Q4*$hoBv`+S|f$eK^~l3aQ@f450n zzP2azL_Lu*%8z+7ba}^hA5jFc=V;6MGHy28gA08@zw|Id{}HPB_$92v7H$|9jIY;Z z#k<|&H9V((`%{Erp&X6;eB=t&!BQjrBGYcZ*7pif;Bi##+cYQY)E9VG)k81EY^}ii z747o0ldoPfFI?UA7u6=LK3AQ|f2d!Zk`T;%31@s>(KV>lK5-Ey7+eaI!-Ak?(j-S; z9u)pTl*Z<-p)`u8IgDcS_<7M3>WkjDvaSpcNeSOBJoA^y_)m`dpusLKHuBRi&)@V4QllI87*nY7Z_G&hC*GD(|ef7anw6KP`9Fi3lxo z`rUBL)*Q-HYjT{ zQFa+d$x*QT+1E*3I1|=ri#IU1y1vBA=njpb?4yRpHf3gTf29xC-Z@o&|Mu4Oi?ba} z`gz3cb#2zJ2;;b4R9%aA!m5bM3=O!oL)8RB=#XI8EN24pfNq=D>{TzuD1{*PRmEqc z_a1>ps0ud7V)e$oIN4UFPp?x17*x-T}Xv1LPlXI)Nj9w8x*Fg|xMtDyyC;z@%T`=T*3_%U`myIHu*@ zP`)i%kQ1JeWV*B^8^QCHy4i^N>6wV|3H;8PAI@%8f88(ppN^J(BHVz5YxExJ)*s0s z%JLktSZ(3Q;S;QIgQbLiyN+u%FejrguJ{u7mTFpcfa`jO;tHzN zK2kV7f7GUUpDTLan4&M z>U!T3%llGPKXdo031a`G&2;5!J&bFng zFU`bU@@bMu@UB&mrqa*ZLtSbC^``>?>Uw#frRe0A1P=Ha!|2AP6aAhx zn5m1^R4)gzp3mK>;U6SxhwF~f&SSD!Mdq)s%Gc3Bd@P%L2_uar3+tL!mkn#ve>X-F zCr1eQ!nfTcGRFa#mHgZ_lrl>5Nl;7PX^pg!4A7vSj+stfXLCku1C0)0+a=Z%NAwrf zLic3RR>Qa#uqa=U6#h_Wd+#9rAd|rDP4S+B97s(_F%TM&2g7aGn+r{XcL%4p$!W@a zrcP-H7B@96E}QVZ!j|mIU2Pixf2AtDf$gj~>ti=%bFSJ(dXVDz0V00%1u|Vxknej0Ev8=?u;_%NR7K+}7t38=#MiziNYNIWjeaz)j&j8c$aBC~(lz z3*G@bWlSFU8JuJE@-@X*-q)~IhRZ)REPzf9VR303Y`3MP*XDMUL{xVYf2`w&>ED-z z(^1}ZgCzjGPlY8z9$7Pd?3{O_cW;dOON;{iGhMuSr^%4`55V7>&CskS8&mOPci|(o zD)!w&BTNlTCUsvwzHdhqlsdA{2F~8d1HpwNbJ5lX+LI(4&BJCRS5Gd%~H(8TzFBpq>eFRm~)R`;R5Q}2-R2Z+H-z-a{|$5E8qq|bGo z*@;;aeyKRdDK(cky81IIq51HYkq^2n0!hm`pGm*m;@`$#voc)T=w%Gd=O>d3Qv8T>Ok! zw27`RJo)EHr8?ST=cRo#ClW-=;LA$<@8im^bO{9XVtZGFZ7tbVwV%9JRl+XnqQN>- zdFKyiS}8)lZnV;re<|gT{r&lf0E|XS;+Sn;tKOujL6P%sCR_k8k_OB-gJdnAlcms= z1KaS3W_&`~7&BGy-Hv}bFjnEM?tH^paE{JZM6MAd8BG~f223%8^pCFOv$hSZPCB)z zQG@h(6wzI&M@d&{?=Sf}*83S=AZcIPv^sPi)5YvO*4Bfte@B0B-Mm0z2pFJUGOGx} zmICUuy3y!xvVVejz8?VwjAYx@loKIVh(Mz@xgKaO4o2_n9vNbyDHZUQA_z{PmWMj* z_IK}8-yXeKLCEylPBe3>{{-d^YpxUlkDJ^fYc2_yXE{Txh@Wa3E;|iy^A1Cx{yrz@ zgLyW_NWLldf2;hhsKI!I5Y~#qb&Oaz5Q2yXDl0?gC^zn_cq(|bdr7|y|@sZ4I+s%dP|Bn zBVG-@%M2{;Z9R>;cq9~fA?$$52SZ=Zl#)lof4CaO=uE#LE^QUoCh;*r^uFMjY{cx4iu7-xy-qk912nAdYm%@9=zse&&|U_^ z-}-Iyc+P{-@(Oiw&DQVpp-$s-zdAMEbpFkXh0e#`B*6w%I*g{8&BLI zY)FTI4_D6L5UXsY??mqi9;`>)*{S!Jt?K7uDUJ4IuE~H6#jTf zZnv#16?BD1(RGOf3ebV z$qhqx_audV`;-j`MP;?MLA9+7EyMDLB4{DF?4WF>UlQ6UGl)=Q&*CfIcG3@9bGl5o+dzik;tDrTU83nw4sO1icUG$8_*HBie;(_MSMi7lQAM2!h(0*blxYLG9xhNC=~JAv}` zQ#OU_{mu5%fT^I&+KKBffpzA=X~ds8S+f3w{1(#4Cw8`U6E6RQC;PG$cVGI^xz2k4 zkG`urbvx9aMU=NbtK||>f8V-#wptN5W6jS3wcfwn)-gs2w}@ZgHo^FVeHegxzQVh7 z9mz0?PKNauFDRV3z`8CHQhEi*Aj5}RIQ%cC;xw>~-SlSu?$QT}P0~2E;w9a=l-G!_ z9iPF|5ho)}=wQ_sgw82gu6f&M?Z7qBs4De$^QGzMN-B$C4~3rIe|qk>vjb><7 zDXe}SW8kpzVSZv^XG zwNLbmsSQK@(qD9GpjFnUG30AI5iP6V&u2ktG0MYyZ&;83ynfA|KEjE8OBKg+|6VeKJl)>CfEi100I18u1VgdTM;xW%AX=WmY2`wPCU z_GP)H437=-zeqS%)*aJ2O#>Q1nuchT3=rM$&D$Vw&<@O@=%;f1Xm6Luq2EXlKhe0h zXnR+S#zs)j46Yn{+$jzrS`^5-J?F^`k)vcT5xM(Bf8D4Ugo|-H4DDx)X_jHPFAgvz3=$YIR0QKTyEF7>kUC$ z2z8(sf7y2hCdq}79u!{8{2^9b&|U50^ktjN~wrlHxyC5#CY?G7ikZe`hi6jj&A4cFb!LLiNc?rK_*O- zMb89JH#vrw+Jg^=kN3mPpc!DGi4&;UAJY)Ce-gym6>=~a=@z$fIx&33&K3GhAq=4; zB%Iu{%s!S7%_#OMjZcG=3ZFDzP+bujGCRmr#HUC)gbLu-*Li>^=S7pRYiwkw=^gwO ze{{?_=)z-wNQjqAzN^H2gKpsacqQmhK?D2TK?dTfuO2smiF%^@@;l38h4FTN_Li*n zf4;Of-L_x+j7}azt=b#-`1F_k4ylhGS;y}?!LNj^$G#H67sujD|GzgCNufn`Bmv3#7w^vD z-?n@enzAixh|#W2q%DtWo@_%^6;<;dDB2_>q+VtKKtR90S%Yhv2~ji?9()nHR=dxD zVSn?l1`T4g{G3qJ;pA73?&cvDr{sosjiQQ=WDFekj!jfyz2h7UG5P)`g-m>*lZczd zJ0M&RT-gsTx3G!xelDD8ZV$CeTS$~BUMSz{la4;ebE?=vJh=_`812C~4R#YVp z8mW`f13kMgkP63}cNa~cWtE|*>DBbtB6#1>PPX}B2c)EWo^KGXMfyDFWjhfFt5pDk ztl1}Z!M~kA@_l@&Rw~%PH3UQGmNpJ3JX{vUHzGGQ`xHOHFvx0*>zh!c$W$jIT7NWg z^RDR{Ff#lZf(@~La;$1Rrkh#A%M13h*{4G;jUT3A#uwnnCo-cb! z!puM9k0Tj>Y^h?3@{={=LA_;YOfkAs$7_xB6KTsVjIy`{u~PRl{#J;yfjIP`a(S1_ zNM?%aj^9~JTKQ$7Ujo6I4oHW_&(nANq2g#v&^3BevKf6=3 zvc488Lz&-bV^k4&n6#wxHUmfIF@G|SMkPFhp%@-A|BH4P)#fp>l~M~tH-Cx8FgX^( z`-30uB#`CT3!^zDCr*G>`iQ^6Gz#zdp@B-Y#{R?9C9CVhkr=X)0#+z z+1wO)zOWd6N9YT=F8(}`7=NQKP|rG>o_2kDlO^Iow6^m_f9Ou#rW3KOmCo4y?zchJUjZk z2X&k3Rutm{yU&MAbBcHAix8Js6Y}_mIyNCyvK!v|9g)@37kB%e8GlHYEqWAUb&O-* z^ZuMcsa2M#1*HgdzQ- zrU7BsNX){)s%@0jj(%RSMq@qXeH+~)ygWdfZ;sVEZI4f_y#_(*`F3g z1Q=ox5_2w)D$ml`*fwFYk zRwDqm7zI2JfVl4T#ItpUpyHw2JO% zMVq?#MW+|c%#3>hM{R745KPY`sUU2%q{oi`5z@V!7GVo`qa15qBW?Oh{W-kicRe}} zW<+Vi)Cf#_%zj2M@z*fidW=3sq>|J~y07-`BY*^4xPP|OCsu{+HrCp25a!0;~=^o&Rg~@}LqUg&4iHf&+YaTe-FSs#yX1pv&NX-_~4`J+ihQD*Ht|AMqS1 z$~bGxo3sNu7c=lP?fk<4XD)3Av<;)J^`aXgZa&>Ka^l5w|CJq8?vYAVtBj_0>ORA| zD?`-NY=7LPi?C0Z3xXtsX5hh!36Iz+YC;g(7H3L%p}X}%BDjqd4PsFisMLtz=>p2( zzHC|wt)CUmV3>kn(s%fKJ&3fHRNb5}{B?d=BFyteV0wuuDQRvX&b?&I&eL1IDzC5Y zJk{vy1zO<>>9)&b&Nx`qA}J~}Jh4K)_>q>Xbbk{R1Yg|62)bYf0C>h1D>GLAKo}8M z_F;|+QMAGAR^03KomsS>-wXzrbic*!kKvu7vFjwva$(DL(>v)K>Ldv(PUorv%@^x~ zsJ*@X>E&`3ZUwT*lataSJKgne!(!Q%4h^g~$tc|UQ(jDO=PN$2_aAn$(pqGjOp6CNiym34({fA>eI zL5!XQh*NZg;h1{>s082pW6W_8A#@(@huSG{T0I`HkO9@&-}wSeoTG9uQ|n>8*VTC%_sJ;38Ej<~J>FxmWKrZfCr&3_c& z1q{rWRtw_r>3oh|WvE*xBbd(dMlcdQ3l{}AYN2VS^fc8PEQ2~VC=@Tng&({JU^`SA zM(!y|7h<4IcWy&BrzfbHAE&z~&bRTGd+x6~nb2S;>F#>|bm2+F^Hi$n%Yy6J0$5=D z2nwUI?D57PyJL!i^);+s5*aZdA%9UySl%kNUo)IH(A|HGr znbpu^nQ6~0%zJk%w-}XRc|7PEMH?j0cO2+*8)%}DE-v$VfLur5BR^CPe}65V3?9Fx zK8mA1N(ZJ{s6U)U(ZJImhw*n?{#maMElAr(-Ep`2V=>a!+(rwSd5H4XgFg{z81s-+ zo83>TuG+A!AZdUx?5QxnO44mB+`dhPn|RVE(AUv%m(_y#X&#ns1%gAz9_g=shzVaF;J~6m#zurPR=TtgRRQA zH^|Utvqog;zvl-X)?O(2nY>jDhG*sIH2Iz}rMEghreOSFDrS@1gnzLWJjsA6;FTQ< zKU?qAK(k(D_%(Z@en69`Krm)cApce zSnzkzqk58b9$_SkLw_;m97GGEW!fhQNN(x1|L!jkPN}r$>UU(Z$Rwk26rZ=!!Ssa3 zl>L%4u5Cjmo$pI|UxLvpj`P6bFo_Ghp9)=7kRQks6MwT$_-f2gz+dzSx!JhP&plndZMS05{EO3pd^SiLz~G3|OZ_p;cYfFhlftuv^LMI$m@_`iAgL~b-=8Xl zcP9o*S{lPw<#NwSk+#+H@!5>|OA=E5R(xq=wN|O)Q-3tfaD#7{^|qx{w1S^`Q#!MZ zIv0>1B#8fhaA?i}pe4__hQfJ~@hhwh+WtMC>i=_|oOBno@E#R$hM=6KH!M9yN1JW| zTv=p8u2Wp^wh310M$edh`l~I*9Z>>l@qPh9Bx_6cyt?VnP}NS@e?Fh;!}q-9Tjl>f ze#N7t-G8@jaF(9KFv*)ZL3MVthkrNpgIh;Xyxw4AMLl1eC-)Vu{l=nzAhJvoglrLg zZi!9~4vbLd9Ub(FM6%sj`+{z+Hbw4`Hz~cQ%u_eTkzpD7-lH4?Pw?`Wv4X`#)mxpD z?!Af*TB0`co}Bfg?yWzlxC@2@2xAdRvZcb4#D9F~%eY^vw7&$&A~@LFi~TlE;)eon zwy3aaj;{`u(UCs+-*<$D0fJ#`0u(ge$#FQ5&Pq0>OyCz#8~(T3!TwwT2p$cyQitx6 zsqtDcfT%YGNb7Po@^998+CUK@QoF#4<#ANzVL( z_i`gI*qj)CgSC0tP&xd30qk>XfvV+Z^Tq_^(CcP2Azaowp1k5leOmJY6fvC93#)Tr zP@RK|Sn&xc^*1R1=kHnrWiJdYsrU+Z+?(W8%ng~R$u(d2yZ$j1j+={b@`q_0?ti7< zqymf4f*l=^5f_Hb)9UziCPB2%tCvk(7-60(?_Ma0bPK}%Hcebxg635!B{XnUJAY~| z5iHe@4L@jxbDc2xMqJPNslKEZ5kIvL^lLH>?=`<=g2PI^bK|E%s3_smrKO!(9c)Ib zMktNi7_@!T*+))45iBX?m!NkU9DlzKo!9?(I&UpknJoxE5CPtWcrUy#86M%id-|U_ zcdeUDq7kOqyXq^^&=`?y^9N5FVBYBDH>cZ*eCD2R+|z}=Z1z={eee$_#j=9XLH@Hh z4M-aakCVV*g{?)nkuHz%Z{_N_sA+!oWCIXG-Cuy`n86MuIF{G1o{6(t_^ zrC0_x{x&C?p0C3?Hh>FJKnp~yhRDRJU7b?uBeAf}+N1OQkVg7M|48^0a1WLZ51>D z-m01|2>*`M3tC7SaNXE>d{blr=F+m*{kEmjNAuwQ{snwGYWv3mV~shOIWz3uO9jSjdq-393iACU1$ z)YFYsWYIIgJ#S~Gwhi&+9o_`W+7DN$Y0;jIFn_)U`;9@N3 zL-GmNuidYkzYg671oZ@7lE?2{Q}pJj5{sMbeZ#sa_JR$id?bDk%B{*7$H|`WPy- zbWtcb%!b%|4RUxIGurp*W9G(w=bJq4b{ApAZ?h7AoXAIb7Nr$BUM;2row164O!b%+ zm6blA1R=~f3?|FUS}|oWHe+BDor^{$5`Mlloqw7waUGHpHjZ0$4;%?YvUnS!a*+r( z3(E&%vIbMYs*69yrPkm8iY2mY`nB@qv)}VccqgsVkdKf@*%(iIIpQUQgsX$pC4~?@ zl;qIk1^!Jpdoo*%LSAsuJC3rHF6nE4!mRFW-yDgxIi6YY@99x@XC_H+m!D6aiPAnx zZGXKOcLkm*yYAT_1KP(rA^CVhrT7!zx11^1tUtHK`;j?2D~lMy$*V*`>z}esy9J9e z^U2^5rEY;KFs@0DAlYJJ(1ZcBPO3tlA)) zMTaYkra`3wXy^X^fTMncaTH>uB_bmweSb(+=GYh%lyu~*<)U&OuASxyfA~!;_pt1w zjVf+#K`&|Z60hEA3I*5Ljm2DkTz)JYfb{qosB-gOB_d6+v=@V2QV?3YlR93)JLB@g zU3MI%>Wmv@T@Bv^@x`2)bB=sbBkLzkJyMnlt`J`^+~+So4D=4*r%G6*+dZ#2Wq-6p zH%>>J&#D|E?6p);g-TJLHN*9q!d6!gY_qx8X0yKJ^a0BY*(-RH7lOO#ELV9B^Dbxp zz6HG~!4!?4rvFWj{8)0}iQ6Uw?)UIM3#gyqP~vF6MjQYbTk*#G`z(l&%T6Qk?b3tk#z0DtMgGIAq- z#!kS#<&X(}>f-H9OD6_q0*GT2*6rYxJ_>$n@F-1_bmgj!dme1tAC&CXKJ8_15Y1zA ziR;&G)MPwD-j*{tAr0$e6C?0wkQani(K`l|zF5<=nI9%Cy3B|>T?xNP=<@9thXHKs zB@0!*_?x+WDtgnqle`RCT7R^LbY^Lk0_+yvnYVS9$nflKXs+fP`b@a{3P%Q&IlSH9 zTsG4r8CYKlZnPMG`0go?$tVpXm}M|7UnkWY?kCD@VKLRg&(IQx zdzW`3qnD0XtQ|0}QSwHZuNWyv(S>~ihhGPJOR}|HtBld3Tw4&B_ioc*uLaclw824G z{kla#(Wo>_3?j4qF@H?REYE^0Taj0$6{+R7x^5^s6c1`hB#4g32){d#xub=WMO`7} ztJ4^1m^JY^;^uFhReeF_`OMYgGw|N_!Ef+Z$l}WBX~%)k1|pX_7+0KEGx_PmBnr-I zpS^k~`sNo3A`kmeBsdgQ;AGWYp?fS?-cg5_^<#DIMxUrp>VGE`Um&EZs+i-2SGC3N zWkL++GFGD3cUKLOg;++3TI$1|Q_T<5Xja*tBXVum;oWA~q#g(@5`-9LyZ9x92}ueo z$2A(KzV#e0beH@L$;+VSJMmoQoJ~;HmbN`Hl$a<2eEt%lZa7B~!8>T_fKn=nd-V;|QvIMzYG=G}q~%N4C&=kAW} z3%bzp&R9*@L1svZS;GjRSAqP=k`M$>aKgI1YcP?z8J9PVN?-~*D)4iyIjG8~Qe{eq zTKPur(^rgs&a%yFVKV5{rQO@PPJh?BJFkeC%;c3geV#j9?AB{P zg;IaDxb@&%<%EVuMTPbsaW5UF&$pWZ^0CQktbq8H079Y9bK{gpTgWr3#*|+|ud#OP zdpM#WO&F=Q$vwpqmzP4t_EMQ2SGN^yeGu%Y*mb|BMJ3SSp%@zg_Ixi@s*e*lrlZ4@ z^nC^zF@G<&`1QARqf}SxY3ScN82zn4Y$90FK5wq+23Hxi*l(isti3w*4dGZgt5Y~= zfR#+QXy?VKO_%uN?MWs)H>(G6cQN0agub`{+l znB-#uWDF?j8oYrJhLrxCpDaxYO=AqccoDA!4DcK#DILz1Rds%?(>wCmx?^Ku>b;+6 zXi=%tn*IHtp10v#r$?Y-7Ym`eF_K@n3_O}A?s5|YurNor@=_Vyu~KZj#wS!8;~;7S z@PA<$h9tiL!NG2wAM#eFUv@>vCnu&7Z%+v>|>>n6@B;n!-SuT zhCfK=^QZiULF(;1YGJgdag>DzhJo-W$bTFV0o`~!-yi$rc?N3e$B;LtUxD5A|0ZEk z4tkcID+1)l&X*0XO+PmhV6o8%z!zGTy-;YZsNrz~q@Yjv+})%8Js$OrsSU0w{j6mZ zmiZ61F!6Ne1$x3_6{qfTRVl@X)Nn|AcFhsWzl^(689fW(-09S(iEUHii$h?|VSgDp z)K7Yf`L3a(ai5C|yxg{>Zx8L429dlL18uZ4)c3BvsUq)i5MCkL73p!9i40Y|RPVqz zvnWMG7@8ymWjp|o?oyo!)6y-YTN-fHYKj_-Q(S4+B26bdjj_N zeckRFe366@1%64(i80tKm~vS3LH~ITM1X*}{tj6WW=WT6;H)56Fj4l00N~;?7oh63 zO3)Xmouy`GKXu9S3!_jB_YKMzHrX|bXCaVS+J7Obqo%`kikyB= z(oWWZlIXEH_0&HbB;?8W5$qQ;JtZ`y#M?Pug^ugG56#`_-__5aY3*rzPrO@#B+Xc4 zUUpG6JgQLF`akccZER+HL6qF<7gDgbVZNkg;lkz`gI-jc)B zgw>N~FUN~nmj8@kw=RKEW1Kq7zly3lN;l|0Yd*7?&I^79Px=Vv_P4S=-0*2goR z(kON^_Ugnw)z?f$xlgbe1_Eh*@h&H8daFd7c8z(MWdg*$w|hmctRq&Hq}i>3_ymK zZq{)RogB(zDJFrzgu!~{aif;S6~e%u(go<7`HD#Wd(YGReIvunc_xYxpOrqNxym0J zs33Id2Y>dC6Q>$x$7cr-P2L=RPwQJhGOrQyFU~%8VK`6>H{=!Ya?a+3Gx=Tp8%sKT zojpyu3|hz4@_6IZwMQ?8t(z(`!x3974VBkC0}MTX&jY;wP|-~eMzlmhk^A_w^8`z9 z1iig?)URusXWDK@MQ6O3C~sF=gpYCH(KC`$V1M~>_ZDia3q*fl4+0Qu?DX}DX?bWu z(YslXfU+K9-{^&wnx6;+h`$Y)F$Fdt614Z{X>+6;Hd6~bYgjYG_;^!r*J?{}n2Or| zBH#mzi&V<*W11g00GQivPd?@Gqe1#GnS|v6+elzMUM#wh_6hmm$$?<#q7UiS3p=`GBMx5YNLC#5$#egkMhT*NEpoV5a*QuB9$vFMu}l%Y)RjK z-?te&szc*2n6~kW!Z1vtwQ8tM?JN3&BFH3)xX|)zp9PTu{t&5Q==-vyE@~ zri=>oPH#Gm!e5Bf8fY{0&*PUr#(y(V^6wql`#>rf2O?w*^J?DAH3V1|>GjG%J+cHU z(yvi}dwBfLGfcV_TRN|-kf`vBq}oxU%3pfleMkWdsy9`h`o!)onaB_WvK)JR;UJra z3w-xb7ysq~1)uF(O_*U~SKc)A8d0uqxNNWx56RA`xjw7qQO=z*gdgM4fPcNS$WH_B zcKaI#bIML@n#Rk6@+qYG+7C=EL139`1X=>0HkP&_090o~ihd<4chXA49;jEx_)-@I zZYZ?uk!39+kXP_o*tMk@#J?dCb}n=lkuOC~O3vhmiKQFQ;4IN)7Orh$m#CiuE&ej- z!vj1yjg_5UN($7%v41By(|^qH&dIL_z7gBW_cZ&)Ctd!X8;x@C>$R<1ZC5Ily`nE} z(vI41cDnWI1!@j{fk!*8v}a8R5wz`F=?>c_l63aqK})?UK7>aIL{D=TbC!P&U0~aM z@M%JG-(TP8U_kMJe8aUavxXTq0IO38H^qNgk2EqxJI`tnEzNmpmVdNd$uBd3I$N~! zkxoL?SdqHJHcgwrV-ckwS-n;3^QTp2ZHa_0#}gvEI~6|+w16J=CX#kLg!!ICsyfZ0 z_&f0{<(zCETUa{rhGIUO?d4_Dh6T?01U7=NyTZwJG3_Z1cZ+aTRsFoF&me=%i27xdPfG1IH7_CO|i*xp?G zVO|{9U$79K!iB#GvbML+*juN6JcxS3W+Ox37dBkeInbPUJkC3bH^|EQkKh4!f2hwq zYGOG1&@*y$J{RcVyAhoVY`cfgG)NLBp7U2JqhZg_AhfSDTz^RrxS?T8g{u1cp}Xe| ze19@JWso_yjxH0D2$E%etHS-6YjV_jmCvx ztXwnO7x5x(lUpmn-dykfwqp;6p>h%s)AU)++b~KC1cKZ*bJMf?zDArKld0wpUDWmT z87NoKa(}Rbrf;ipIm}m{{Pp$jw*7F)tIpR%=&R9h{K{WCwd9xKW}7aC6%`Oh(5k$@ z{$B4XXda^5zV@Sc0NpGe{{iW4hVi% zQW{6|$&h;j;t35&vu^gSG zI_UR;0-raFa`ov3pZh1yYRBR0*)tJ4ZlE85HgCV#Al+)1u|PD-*WCofR0ZU?^n*ly zQl{WXGv50$=``utt(QFs{X2eG5FiuQ(@!Ob5%4W@7$Fr>yKKmC0w{@doqRu++>hse zTz|UfbVX{sW;=17&b;>g-hznfwCg_AkdD8%FplZu(j}+waS!!#|BC%|BFPg0#LI$G zM^ZbMn|_ZI4|bFq=eA?0lWd1yU3P?VI`Zn&^AA^b1;Kh(tQlg#h{GOyeG4R_Eo^e^z1 zW@nPslexDvp^OvU0XexudbTO7-*V^z^c7Ga)WB0d-7M4O9g1kYGE)J`Y8d;sphq{i zmXXz^Lax#eFIN22i#eqXLI2J(RbZGbPeb@(O#8B9Q=`|HZ>hHcHb~__Dgh-!lz)f; zA;o$^(`Gx$DH7sr`Ty}6x!n|LC16`@U?6|<ZY95km?LMIqe*SmDWwt zfL5qxP)8C!0VYgjM{S@IK`iEag^E_KQf!tjM&>Y!e|^8xQYLP|00}_$zqqbektd!4 z0wc%-@sm@ZN+ffBuiU*}qTI7f7=Ix&OUN7|M?8od1TcYQ3YJ3mr?_) zzBJq7BGDsZbOKu^kjjm3pU^}B;G*O<4z^}yuB>H7v#~?@b&c z_n8ZHsSGdR5k~Lt!x*cj9-J%tTn-40)GciP6blA_FTYZFTaaitHVF&dbxQG23?EtKh3aU+#KvoG2Iq$&`>&;PjhX4E- zo^x|VJ>*LFPyL$`O}SIIVt-rj#g6TbY>&j-lVP;fHlFP8JsjE@WNb$gqB>})z~>xj zxn8?)LL7TqUdi71T3_2_j_2E3c)192c0ma-6=m$MQbhMBkCCZHjWY5HJ}Mpsf>Vz~ zRymtWG~Eu^8$vdSI8iysk8$mwNYmzOJX#ophSX8_(is<7jI0`0Sbr2k`2XQh%hkbml2>cWr+_Q>f~^ zquKA3COp;jfo(RNjL!jFAa4(iw(x2qx+BbbgckD}B#W^*0I2v=HSu$YOprN!1oAF% z?rleBBRbTFP;AP${jDtGAUW?VrT;4h%b9fOYV${lc#AHZImxRvv?mgZg+PQXI0l%I zC!&f08&PM5-hYH3KgWkcAI*E+1a!8xb$)X>$5RyD>1%xx=}2Rr48?yrB=|pwc1b+8 zxA(%dD+!OurN_BS%2P-XUcb%&=VQK@_h(t=aT57TA(_ywO*G8!I8(mt^nxb&I21N2 zpE_S={(y?tkmAhhrA`oCE~IsT>B>Ej`OEjVW{n9{`+rhqd~nJRtBVJBeDA)YgT672 zg(Mrl#(_IxP`-6{`OX)Dxj?th)^5-jZTkF`FaEj+@Q4aKR=ym5oaVS8)d1^ECNU4o z{0=z#k~ztyyLERj<*-_vKFBykUuEZ+qzbTG&a4QLcghtFR#lhalSuc^$aeYESP>TbNOhMFE?zZ@C_!nUa-F?Eo5qlr+{&+4su1Sr%JFh@K7SE$@jryPZnCaM z#>S>8%H(KaTUe#CRhu(%x^+Z{sFeQ5-UfXH(SM7+Z%cgWw0Ra3=c^FvWu5PXhaE2o z^8(PP|J`fqSa3+XpcoZD{GV4WWhI;gP0Ct##HQ^6b=dAVmh%wi zDoxn@Nd2UthagZtH@c0hJ?f9?y|(#f{AAJaXAtfH{@FVzdo}iJFXPj!C#eV7Xte=b zjeka}SL0gA@&oJwSwUHIznU`Rke4#;%Lq4UeWWc2-vXBzCdMrEqU+B(pwd|dgmW_9 zM0-wE|8_NSu{GhV)^WkB=z7 zjo)xY$4F4wX0sUas82UqqrOW4D)&nA;A#zi5x#+e_75N~ucDzhsM(IFW{gba-^S2B!z17gFg^ZE^S;)rYm=E!+a)Uu@2zuL@pbok=dx~snt z%ca!$G#k%h!&Eh`&m}Ypjh}GxNqXEGf}v!SlT?*h6REPE-Ey_V1Mmsb;xYI`Yb23KG+~hJS*j7=>I- zpQXiD4)j})EUyhSJ(%I2N3U{dzby;*fYT*OACsF3lQ9#EsFI&_g%wo4&k=LGds3#) z>eq_BYi+0j1(e4DS^6oa^=ew{v#ggGp8d-Vmikq`rpni|(6i9XaNbC~cr}uoVh7s2 znYrN=HEJyG5{|v;i=Nx!es-?2^1y#|{@y%&~WAn(G`@j)GU zIO*9upFD4Lh3fDStU2Gf^YmoS<5%O{ExzRQaN)yvut~rA=8#FS8h^3e{MU$x1o{~F zmao&B5YAYe1KCuG?J>OyzZ`{awijgW;#cYhE-DwR0Spv}8@ZjJX?GV!wCU*DeHo;a zlnG^j!6C%YplnJ^M2^BTS&AIaQXSOd72$Ya&!Rtexw_^in;e6aM;lJ-H9F2wSspka zPb13-rue)DTp~uE-4+-CLjP3=lttxzbYBZMi5oQw*dFry;sS_AEx+jcAMzxMXS@EU`EFh( zZO(n1nSCQjFAUS8VdnW7#XW2|t7qfwVMSjIFu<@E2!9IN0U+9Do~I&^)PqT0j~5x% ztR5~RhLJ-|murPPA_UbUv6L)51VF6nZ?iyZizyX7J-J_+*=;zNATOLIL5&ludj~T) zJ{r!U{VfhTl4F0?(r_)8f!7#={Cq^~$}@E0r9J;WcsKtJt&uU3)8kP$K&>eJ&22sY z*lLi0H-C$&VOgbPtlKB?B_`YzK7(ay$AiPS z{6%VK?5#o6wwqE@HsZ@*xK?&DBZD}ebzWRNI zM_GTv#Axp#s{60Q?pT2@x8>Y1CRBGn<+zP8J4R~ieQut(KlR&r!P+*ox}#G3;NG?K zVh^$jZ&%u;XwtTBifu5_=T$!P=XmCz%9)2HdDoL49E68Xm;-D8nYjL2xxHFj#rm+{ zuzv$;7x)2n!h6atrGlE;gB@~|TDu@99Q3l?<8m zy>xi;t|==$p`?G;E7i}>1aRs#k|86Ay@GSGN?}<0K1;&3qIVOOV=pUnf(tvNqir!i zdqq$+!ckv0lTQ*B78G;O47WTuBl2W}FrSk}=E4PO`f%nR>E{;^?2iH?PqhmUdVjy| zpXCcGb6eHd{p~Wo5)5K2*Ub2y>fjVq6@-~_GNwc>8Jr#zYo9#HS3mDkUSuu=bV*b$ zpk9Zi2oLI-%$k4TED)+}@3nd(){6==okQFg(qzRkH5`5@pqlfi8^h186kFKU(M#E( zSB}u>|H1=v$QQwg$KgbK)&Z)cxPMalrUyA=b`dvXb=zhAYflb2v9A^{u6VzeVB-&2 zwL)7<&bz}5etnfYqS6|{b&y}tjGt=J_66m>O)ET;{9)d9v~2lh4=p}x zeL()mqx;-*cYG`Wq+7gL6S3A2pILgtq}QJS#1W+DcTbNRqujp!%;*;zb${NjCzyPi zpOt8THygB*MFb+@#1M^%0d-%vlQgwL)^4ILnT# zwU^=*P2f+FCVvAn+xemg={|#eD8YVu(0#H3-j&hQ^?a6ep^wk+BY%xHPM=;d-eL$X z;Y2*D4eFndrM%@kWRysTbgXt26f7M9>ZT(tgWQfBdRf)ihYsO;bj(oQSTelPUW*Qs}PC+5jk@4 zc6*OfR|f74>AK>?ynkNHc2JMu3!t*+PB%z?E-g4lU8{GJ$C^`DHIn;oH9`m1`he4! zHUsk&sl~y_j1<@x=U-=zUDm)>)h*hjKPGp0F|CZXBO4OVe#TX7;+a4uNTN|2y01up z79&zQ@AVo9aN4_NzW(f*MsCc~W8TMGNuj1zu9pAygR$zW@_(GP=sS&2;j~{^AZ@DO zx!Dax9}}+-B@C50^WjFT%ZMBki@(*{yVQc_3V+)MQt%JWZG`37QBQzHh4%=NXr~V? ztA#)Ik9rs%cH-^BOH;r(=LAMu2jo9$fN^elGw;vDw^9ISIo{J%77Lcsc`Iuv>rG2v zGHrf;uL>ZGguID>n^uYL=kbfu$9H}jqLyIdBcw}WI;A8fclx{8Y7 zPzT~g9!9&LB=#909)A>%Ir&EZTaBrYX$D-tQUds30V9pFQ)?ucPH=|a0f=hBnC|_9praGNYQ{?SD;0e0a0=hXF?#h{mO38ksJ% ztE{><)9uV(9-Q&pDX9?ihg8O_KBROiJr_4;>_SwWy0is0MSY>>E4 z>j-dw>G-ia7mYdA+G-usQ7&j93%)0mX`oYD5}ZEvymA~WF}J=~Zm|!{7;53vCSS*_ z^PtLtKYy=yNk|Oz8EE+he1tCeI;gj6bpl28hC<~JcS{8sS&+VpH(6S-D@@(r^FxOr zioq}8BTy#Z!{KHmf)x|xsn~NfRD~pR%xZmAhHP}6+SvNek@L4Z4Ifk7RiooQyG=Qd zbF5nU_ysdbRFuOGcwbYt?%pu4wK7z$L>6VYq<=onLy4p0O;YUqIn}Bjy#{e_o7irT z)Q+249UeV!?(;~eqy$Oj-WzUJ5Xsjiy9_|XC=Bs&_g5OiTeSz@Ul#Jy)P1L#B4OngGKF$~ZF^fU=1N+XX?Fx}Qgl>KOMlP5Ll z#l0*DLlzCsoV6io^#SANo5IhJ4QW&hYez}A% zK2uQ=gKkh_VnE9_`Q;IGFvSnS+b0KW$ETS^izaTIx*-x3{nY8Ls<*Z8*xd&6g%izn zpg$cKOK&gk1DW9*`jHJ&KUwUC3BO@yB`?~%)V z`UBC$9|nlgMyV2nb%@LpV~q?tJyk~C*&9AOd9tQ{S|oyx&eBKPn(yF)!{6@%aAQ%8 zDAR}9F18DRgQ+}euI{n0Lh;x41Vnm4$qL@=E%W2?w@Me8erG%yLP3%xc7H@?bIC@s zNHf}OMoPCAS%77phT&-4UBJdXvd$5fhgkJpdT-JGv71Plk4 zU?OUxb*2&T*B3o*%D;rHOgDKz>y}cep>4ILdPSa)7nPk~xI+a_cjqLB2h4I`ZFNVK zW*BETq^~3Pd=#GO%YQ$;UD8EUdL68G<2O%NK$)&(;zP5qyfep%Az{9dJ`Ch2F$}!) zx%9IO_7h$o&S?_$*d#=W>48 zSpBVIAyslw>~)REubEBTVKFwJo6q-Te{MZ!V=wdu_4&BQ9Df^fk@RpC_0CDYmrVm| z5P{}Sp}FVAK1c4jq%Tc-joNDIxwhU$3OvHNg(J*HNi3!P!bPOp6g^h91xkhbUVy>F z7`E5irsnHav?Cb1pz4gt`TEKj`3d3*Uw@H0ZhJ#@nN%{cBe8sTJ}K1twyX7c0e+g- z_5=zqkgEmAYk%6F{y_E?GP24k^{dU^pjpPnzx#gW>$9f@ig^@h^3D z`lb}APtw#XrWMF`f|A>BR48b2GJwQ28k?R&FdfE8SAWT7!s7CmpWxX_K4&x)KXoAw z6o?P^OP(MIFyKB(Uy}3)s4&9f+Ubfw}A7xLV%?eMLx<0n&Te56}6 z08c=$zi6wUW(eG_*{qx*gEsPl4ZHd@ZoLP-#(FN=3&&xOUMdk5%$(FFnNI`Z^q?sC zJFY*BxUm@yS-^53ufy;t1nzp@eWx~u zekeY8Q}>4@#*i}C#2_-hA4b?G(BVEr46>4p(gbe)AuNmBiRkfU9~9+$lJM`s`_z9i zi2IfCP9VB9h5nf!5GD1F+2*ax=}&L!PMIY`22X#oNusH&^%Yr;e!vU5v(DCy3U>|- ze{X7C9>`I=pR>O*Pd_+L_c;IRHx2RfU+?*0Z9+IhBrstAJ`YNgz@VndIz(wib>e?C zoyTshS`bA)hygkDkeqXDX5>th)7M}8q&KrHbqfwvyVf#>a}P76t~^MwR+fHml*A-(L>6!kkV^>YHj{ z0CyEqX>;#k28d%3idSr&kU>z9gZ}VR*3YDAy1%_;KpFqEAIAL1TtcgP z7x)>!D3VFr<#1zBdqV|#O@9tt^||U)qNyqx!QtHeiWXsf^5cb=T()Sss7>ieCKA9$^=Z8Z)t$yR=mXjenTndrjug&0+m^kqh$|iR5iM3Pbk0&B3 zs&$u)weaswF((4L(vA|p;md#B1)L*z`*-O23l%S?dKTpl*3rh3T*P`5CHDEVGX_k~ zIDXGc=gu8J&X$=8_qV4~P2@2JjignLElUeA+;PQ{> zK(7yS_fXlG*&D63U64vv0F=(~mt(;9Q>*zbg74RbC$C|br#SWYd}6pqb>m%|6%i)! z4~Slj-^l2&d&hAivU27uL#D!xxI2~)zuh`MCu1(roO!D4OWh%;cwj=36%QoTV+n#E zAYRFGvYsG=x{@h;8e)I1e&Fo4F|T!6#C&93b};yw+Hg*({NcK|K`s6;jOzQrSyJw% z!}?mFf+?vDKIJ8KGUj+kc9GipxlX&SW$E+S(d^XNGg?bdZPv~uTCdMhLpkYkl4389 zA1W_G{!^0}t-XwP(=?Rra*>EiDN{$y_R@0KJ6FmQj>7lfF&zu$cP-c83$ zJgqb26fi#v?i2rE5XLXa9j%!y>^%u9jED^(lhfQ^3aOjAFLJ!hJXs(9j7Z{YZQ0b! z7m4*&Xt8|db*_wa+-d!|_oCdNN=Q5OLdzSp2YX@A)?`U}In(E~AO-P+sWevB zs2533qWl21lU0sCec!2_W6-ZOzzN)GTru(|ZyPFw`d;>HvK63ueavfuz+a&ZFs+gU z2q)mbXN2KMT$>jttK5OUxn}>Ir}S<>^KF2r*5O3qac{?_xJ>Pw&SRPTR{p7tize z2MzoFiHB5g?S;P@E%sUHwoGSp`x>^VB46ZGHD6;UHF=~3BZOx6okn>9J>;QtaSxTl z*L;3R+5vxWZ5)g(2Q<3>z7GI)gBRWTDb2ztw66}yl;va(%c&fBsrC@Bsb zGh7DU1H0Nybo_w9)Uwhiq!h2}T@L00xlwXRm7Bc(oFD5YK-|^N^K*@|lZn+S9iD^E z0i)S`+c1~vyL<8;|3lQEr75T!SZGb~kiyX!$WDL$D#}}j`n&si=OmUM)`#7Ue5eK9 z-nUjB;x%G9KBe?gJDr?>oZTiaHVRH|Wnqmh;tFPj4`3J$?wBnm#3CVyLmmhTJ<4tO zta#KNU=gj*^%;7+?LU9a#bIY0uwusF0(@dTPfSzPsWCQ^pij%5ELGAQGLKN_QpSr_ z3h969F@&n`?MLaXI26d>{9t6FxrIQL_BVza2WpP-w~QuN{K7g%x6cvTJ*#C2q!IC9 zNGQ4+!p(l{-RF}tw<8jIqjwL!YB;-Q!|3*OeZtH$Z2+Sf3!HY!a8~rUPNFuur~byv zYo>za(JbQ7IN9&k#y&8X4C$dB+<#uzV_!g4(1B4x~VPO`@h-{ z@!}X(jprUteowMm$&G;YS=`)(RB(D0cF1z@Dcgy3)2Z!7^UZAEb$uO8{SbLpQ!Ibu z2sLv!(}LrZkC*oG-6E$;YCl8~TD}gSUkSY1o*FKvZFuP&#>yo*3fx!A^2YKAg{WHe zm)^JLUQizg#`3K+MjS;@&J4f}z&R!UdG zd~^^{3)K&9DU|Q~bI!)iao?BonRl{&67G8Tc`$4xdCSH;if?}~zxUc&87c;MN6&1v zYHVKE`qWlp@yJvSy?h>adV5WRXq!66#;w&-hn;b9VLTq~-98qgHZYv=caCrA?rzuJ-gy&?HrXL&rCg1reKY-Ux z&VvJGEU47yxwYG(lpK&H5=26o@3T=UuSe^T?`QbEXLVBk3KJX5M?kRsukJZ^W=UJ` zE&=-~8}T^|&YT63`&wjenhbxr-6z4_*_<%|*EKGrM=rqPy8}W=yxxWXBgccr+2lr0pIP@^WGe8nD({0bBbT-qH-NQC!w4Qm}aCfxETKW zVPE;;7vydn25|4PJoa3W)#0{+ygm@|JW^E)aF21xo;xCMyEL>2Yog+CUGOTAt-B^A z<`-k}+{>gpu=7(nFd~1Q<4!*M!JL#ME|@TBzAB3c@VO#{H|iu;b=NPPvM_KDzaoSA zSpcUZmumeQ*!CniJzU&6cyGU%Zc%ow8PXG`XG3-}OrL0fJA4+^vjG&$ls^eM>I{Yp zg!cBfIOpu>p$NVk$Cy!X8qRO?3&4DxQcCoz`fCfjD72F4TUUSC{gMj!T9Kc-%|YIc zD3w^(#{MT&^YufAbBsoH4cgep%uDXL-;c54Tfsqx5XaL18&z1dr`C&D%{aWWZIL^LO>PUWAH~`Wv0&Gg| zjVM-^JQfi~?p=S0j~nsDr8;B=`{??ZCXq79Ku&Y1Xxotl2}Nv~CyO9;`hz%f0T{ox zbKh0ALn?Ve4)Cm=LJ)(krk+QJ;G^6_;7lh?%QT}nyx^}@W(-*#G^=)}*V_$6gRgX7 zGB81r5dUKowenZ#nbLYT>_I|HH)=rT-G9%(ghDwbE{>q3eZ<36Dz6^Y|qal1=E>;|jPYBkXjG|;yK%+X)E1L)oB*dK7^r0glGkSYnn z*cY{2kn}f)Ub0^=k4|vj8Wgw`7YgF6L$xA;noo zKbsTxM{@%Q?B7vp;@vGvxyt%Yjkq2+;$TywM&b@MzlFra_L zsJ&riKx_XBjO7z)+Kwz;GaMoMcvrn50_ty4pioiNNLlxfFBx6i(W$ZKEt;aGY&#f9 zN_etQmIi19*~w#J7W}w~Bcry+vMX7GL|zQM>jT(< zmd{E!JlPqS%VA33rOe`LtbgwjOmo2XU#h z@_hbkP=Fm~C*JSHVG%8Goq-*1JI$MA;4@b%9wCRHl*0i$1;x628vjW|4;n*KY%V8) zym+~OP6i;;q<&unr{6W;kgLr z+gaAuC)oU{aAJ%d;OR*e4T_>G*1!LwQQoXk9!mC?i9|9WnoNJQZ^m! z-x?-BBpf=3*J>6t_#HQWW5TpVAvKMs=$k}t*Z#)#eCrZgjI$}9ZI|98U$GqE!==Y9 z8n9Me-=o&&f}N?LrKgl5T|$ST_D}v=WEEKixx?4D!chbj=8qBm61p-qME(*QN10~E zJ2h28ht-i6&rN@fA#sjtW&j|P(LZm1Djg|KhdB37t* zX}wmq2@9XCu2cp967tQwb%>L9De>~iOh(PW-=;)mRK%3CAJd#)jb7;@O~Uc;HE+^D zqzK{;#OAUGoSHZDht;lI)OHCVEV?o}wEF8x-;bqxgt31Vajti6o^o zgX;iNwdCx*BeB?${?w%!bcNlJaz8ZYJ<6Z0U-Rz%?zK{ar0c!cmcDl9I$ot3PLNHx z*yYnPe|9GE+ut6ggK@*T$2(Zq^lz@s%Kik+2%c^q(Bz4{j0~X_$8n<@AP`nzrL@SL z!F`-?g@J$TyJ@YkMY9X_t*?ra)CeZ`yTq^chEB~fNDC}(8JUE09@%0IGjxqAro4b~e^e6p#a`G8v zO^?c53oeqI^o8qCIUph-PD7t4R!9nrixCL|oiz9BG>zpcex-H|qhtJGdL#P>dOnN< zlW-R)043$s5?O4?HNcPMg}$yu?YSU77GfI1CQIt)6KwPTXEH~y)B_cgtE%Wv=EKe) zBN~s=0ZKennmD0hzxX21G{+$t^YKmv2p50;@8!w44JXLo_IAHUekBM3s~}oDgs~4I z{+eQj{XOKv&ntvK`7Ny=b2O@ zM}V}^@?WkPVB}-&H&zVv8FsgVuxvq?l92^eGRJ2Dq^&%td_4 zfv^kG*;(8(WTZmz#1dqoBQhB3b9R5jzWzxb9(D<Ii2RPHpGrsp!xJ)% z!UeIv$!y`K2&{R2njZv=$UEfx^9viM4zz);vRBgy8I3a;wv8jsS+eG9N=X>?O+Afy z7v;){^owV-%l0)#`}^+~It%Td^)tYi+3sM5te3z8Q-<6Ouj$O+^P7vY70rJ;1zord z(8XbxXL#fF{#cw`+_knY_8pXa!L)YyCc@^Q%L8lE1 zD2pwON@XJk^5MUup5Vo({`BWJ^I*m8iY z2Fz10dK=O=o`;}!3MBLw#|RP?k%ug@A>?tE>!&S z^dQ8z*FfcPQ=7S7ohS2%EFNR?;YSi**twAxyS&)&%R6v?#wt#O9Fu&IT&R;eKO5fQ zB&BJe8H_|hn;=R4{W-W$!Z>_Nt;pwCdAzncd z=2cWPYOeu4(Mx|fB|D-5I-Ttr38!ZivdmKg24ii7H^M1V48D9^@2P}!v~PsC~F@h!=E7pnU`XSn}-zVb>~biOaiQ4a=aeNl;d@@uMUN~Uj1oWj(Dy<}aD zVMVO#o(*-FNv;K7FF;p5FmEWVAwb_Vldm6qVZNR)UblaR64}S**u}teK^)VctF8!Z zzwM5O6%=524S&$3`#Kf0S71;EkfBeE)O}8$Z$~+2G5=QTds*1YaeXz)I`Zf2b->f` zT!&iukkN(f^eykGhq=@_yemL{!X2@ew}jo9oEGW!%K?=?lA3hfK&GM$3~?NV0n|34rqs;94KGPIN5su2CkvdQQj&@mAMLPC9|Hy=Tnmq_zvw3DXPLy`q29@lW!788- zu~w)$FPH_zpKuP&1P{(f*uG8i^;C@3L#5Mxk$->X(axgO=Xco1d;AwEeZ_E(eOtzuUXuFJB%C&)O{p~i)Am&4dFxdZc5KEOyUFps(;ICPo;lgg*PPvyp z#xEWnKmi2%Oc>`Z={c}q>&QR}r-{hJ2vRVb0%jPt`jfaM9C6BiL8kNi9Y0*67wPwVOh+!hJSDsHcidO}{$9SE`n*X1KjisBl<`2D ze10x1%o+^_QL=)&k6HU7yn!MWsK30dR91Sr8E(N>@wh=!8F+IDGkCp72x<85*>NSX zFFk=dyD?&z`L-%|iT2-~4v_3_QWOXKPZxi>*EJ0Mo+@Okzk__z2RLQKc0EvU!<7W? zyEk`Bt=2T4yuX9-rU4Ce1)eXxj@ficNTGeYW89J_9>2RPz4NHAM_}z3?^RuS;zz3_ zzoA6V#{p^sW`EPFtgc1j|bAfV;mEX_DxJ;}qel-_SOhq$TiPC>ndE{T= z#q{Q7169DMZyuO#YH51}1 ztz2R6DPfg2l1tcm{6)m~7QXEDc7RR#V0SSHoVq+z2mkqAAJZyjWwGQspL`ZL~7T92y(r@bJcm+1n`?cU;lf>i$+vpa; zAv*z@gb**i2C<#!mMnbo=E`TUs98hSorA^F`d6;0P2xVe&c~>~MO%{M5|`IGZD}Xb z_#1CS&emcobkDSWY%$aeZ9jZeQk1>}lb|*B{jm&|j2{8LXhO#!xyXMon`hJ>YJaG? z68Dw)`cYqS2vY}3$KV~!*;D%V49|X9V@aJ+&;*d_(z$+9cFdE3_;qWrysM;Cccl3F zZiTq^!r|~f^MhuZe2{DR?Efd422e(y4x~g5-)4`E*{zG){bX zX3>JTRx<7_?V7jHocdbSoA5&QjDFi;f_Qagx|ZHC3LFxzpgw;_JSjP#ZhkjOU11Wf ztB+_&jwNOnrPw$;KP%Tsq7n!;5d+cF>3EL+!6N(xu+hiyAY_HJ&Zo&S18rYaB7E*o zyPYhRk^sx4xN%a;b@Y(t>pQsxHR6p3!W=E~YMm7qljXZ*Kt{U-w`5#h?UU0!A<-B* zU!kTg5Kv`nAU}U~cM0A~%k!|=yqq_xe4U|*#OVO^ZRIg9 zDhkN^lxxJlds7@~0v1N?f`W_1T;}g2th_i=zs^0qZc(YTkSL@JGHuYz_2}(xlPmb` zxj6i2_vh6lE?^n*yz30s{C197rWGp|CG|!4J??)CAzQx1=F4ftoO0l4L z*3y+mgW_^&pIM31#;JNa=`hdS3UJL@J{FB-5N3Jn3zmBodgFZS(*>wb=wiN4_gwv+ z#PfgjrF-WzjP`lq;Qh2S(C<;>@FoC)iuhGy;3;tCxI(xiiCq{|JUv>z^5c7>aS^PFbFlMoVE z-^dICcvEqhNHZRy0o&I<^`o78@*&C^^_~Ths1N^!fY!c^_4hwIP%HYqegCqdq z)4=VwU`4O=t2hAOdMnnmKp+)BT{v=~!^)*t^adWl{rbewkXH;-b1p&oA&nFc>YIO6 z8MTo$^~8BTZu#&OrEO|uyIbg!=iFGQ1>XJiGexxDUYFU?q7CV+vU^WB_J)^hgT7DX zFr20=TWiZDzkM&o?8_Rdg&ywQuNbAo-!{S*&kH^5xiE5L9`!6jDgigdt9NT$kMnN$ zF&>1MOlw5b259+7X4(vGxwa2`Qs;lKd)0vKd)VKLg~d{S$TT1eD>*?wXjzc23Z zYwBBrHmg`}{KKY5K~*ERvy_K-R2K*VHfA2mm>YxPV_2~XFZ5cSQG zj(cKfwF&})6`uf3)6@qcQNz3V?2WQ$lJ{$-b=ve>?8Bk7)6ox>SKPH zq+^h)7Zzpz<6DB9m-_1&2wcHIKTj;_mkYUM`LYKy*hX-S$iae!n6336wX(51+r++L z%Oh;v+BwqIk*Dm3gaci2awInH&jC`ts5=qHjVE)zwG?KaKGJ`K>=+~eC@0X#V%J-D zkn4@}b7NoI2vM9O7P7XaPeb_kBj5xw7u0i)s9B+=7tFn+q~3P3fl+Xbu~-H@kJvL6 z2kQOy_b%n}ML9@hiEH71)^@W2%x~g-<5F^wSa}>NDG-BI9>Gy+AjL>;p2@Q{fhpZf z(l+{K#`T33^MrpZ8RN?tXDf2F-YI=hX|7Ihm!hG}%sVjnYPj}yJy=C|yaB2CAkp|x z2xUrMmA=}TpA)xsgNnVl%(Wlfzwp#LsPTD?M7f7`vNpqD0(OYq zIKS}rLXVwUuIY2Tl|nT6gXC6CHy~^Ap{on_q1nLUQlZHo^vwnR%ix}e*zoc^L z9Vd?>wamQ#dP1KqEamSQ;TwkpJLs96QufK)fd+-`p=ypa7Gas`wdB2D1*+POhvlfm z*K^o6^>&8qr$p5En^>#u7rwGoq#O7mbi+P6A*z41=4M`0BA@p#%?Po?^RvJrF+LlE zoXFe5)J_YNSWZ-Sp)ji2Cy-zN(oq-e(iJ^8H<5^&tsyu!^~m`!1MeH8C^}00BV$zeeo0i(vzDE6sc~ z7+-&~JLrbbhJ1|k)F6i3-pXeC^&YxgoWL3_)J9BFAC~$35F#%ZM@Mi@F*T#}UBIu2 z1EkP`PlWNv6gH4(%&pj?_L-{#ckl3S7foi7JCIAMw&D)ndG(LZtQFBcWkm2wc*Z{K zKaNQ|3gli{6KeR9%^&9P!NjCGxHLKFEwg`Lne#~Ac~^WY`~4)X6|}iO4p9@H!y0N+ zy$>x7{dM!|-RmU!Jsa3f?0nLGf_2*AT$(fby20qP{vk4;$SWI7Y}@-m^T~`k0r?tB z7rt{ZGNH=d{*)J4mttqnTl(AQI$IEJ{%R)3|Qxp?|Y^?tRG@UwNEv}=c;(w4uB z%&f|FuqtCmpmF1u$|OmngNy$0_nbtWPM!<)h*ps8H~~EOSdyccwjuQ@53x;z2DQ{F zYFu)|_u6LdEgIK%WX4$?QGrP%1bKhvdG`$O83&#PBWaYl($q)WHtvT#8xzi418*EU zkmC#B681Z2kJ0M3UE0(u2ZYwHGX70k)Oyx~gF6NJ@$$zW_Z9n0Zj20EbRO!nYDA`w zup6+CtajR=UQPU3A6wFSc(%BhVfa~o*v2Cqp;9~(Nr4i=^|6&4B=YI{3*?K^|cekxy}M<2#f0|=ht4o1VJ2R{A8 zGRvM!=o!5y7ZqhMmj_&(D=bR0+-eD-9szW)xxOzcSU5qQx;# zNLz|4)8i+K;}rDdI?*yqO4INcz_=_y!%Z*FrDCm$#6_$ z`9qT;p}q6X0*hNr*@F9p=(TUn zrC1vI-${9;R{q4ntZ7sO()~`|+joE%!hA!Kh7C$pFFRwW*MEvE4 z)Sk-o`GA}_E$VvY3eC|ig_B~b17TwFE~lv$;K>(9NB27?USN6W0%i}91w&rNpXXL5 z4WPZU$qUY8s<(fnI%Y*{9~xGej@Ukut40dknU)G;;WB+L-v3w=GkKk2WPzKb?3q!2 z`yYH%p9CLgm-+j*@Mv3Io#kxMXEPfwjgkC*PCz0#L;d0?O4D>j^F40|He=-eq^I8V zVMGj{mCyaT8-e>m8(@A%@buCG%2}CoX6xu}v$+fnSbcv5!#c7n7h@}7s^8j?ZSOuZ zKCe&IhQZu}K5d9ujkeJ%sJ9EJimQ6Ly4?lK0xz|Y)W%g&lTAD;UH+rHFgGL;Pqr5* z9aVrCL3iI$lgD7t?!8$*H|2fOcTQ6ufn1N-La|yLzT4*8vGUQLB_V%77BCgK1}Q1# z5ua^ViG6)EebgK`2DhjG&+T#jQaVB$BwVEMtYPD z7ws?T1|RL$Oi?VidwaY2O3EV4lM^T=)?_oW>p-Wt*hvUo)sQL_Luv!4$gk=4&H z5)FR@lo<1CJFk1T{{JLAiHtu0!wu(ymQu!wP2w$f(*^sbA|?D?kZ!?YXOv8^fN)xPbH7QWO~7G zKMD;8f{c3HMKuaMRY2@xu>D*6r zvlL&S3Iv#EhQ%=X!V|M%DbR?=-SU5koD!{)Vvxf)ED;kh>g^I+ng~s={KYY{rYwy% zi4mm16Js;Pq09Y!s)_HMX2atmUbHEluZP_t@X3!QD5GZ&LdW63mz>qp{ap%^7L4 z$u#w`WO+;&0`0EF{Z@ZsEOVSPOLrAWmTr%Zx)V@ov{sS`Y!HlyQKcu#X$&_|;_Fr5elR zC%-3-MWPG@Y*rJVgb~QfC*>-8J~ZAeu@3e^{lV{U>6xGoVDx`F&)}vhXUTf(Nej2@O3d)v9o=)I# z65pQOW{5CbPcon6>Zy;`qJ@wpEkgPp&lTCTYaFM>= z99cO8rQ3VHtb@85$?INC3vLOQB=PWdox(i+){;4vs1tvC+ttut=A&Nl4s=~L%PVnWiuz$+v=2At&iZxB~T2j|?<=w<@XmS}(BUf2$|!kw=lde+?sN#2WyTacMe2U$z<#fE<2MozIc`=KW(#7j`HJPf&^ zgHhdLbLcz+`Bv-~fiLuz%$X3Rq1Qay=Hr z;93LN!-mUlYU0;xgL+Qayd=TZj$*l5$LN<`bN_#6d-LYC>Wy(-I&d6^3pk4zy6B;+ z=P5o?#XfQKb!u#*c}YN+itS zGYEhCDVXrlPoVN`Xprp~Fw^uFz%ZH@RzdhqVm$u)5=Z8$yY~-GcaS&%99n5%&zsx5 zQDdY#DK9}5%dr&v9`8tK=jxz&yx%aftFRm*&y4sElfmkT!FNAl_krwwLs6`->0Aza zUL^G2KEJ!&e}|ZRq#85|RagLmc>N#9KN^4Gnd6|`e=i{{8tx1g%Fn&UU3`dCaN1{h zcw$(WN${ZhUy|6OIDkQ`=4Cj(F^4HQj4D5uO7s=3emZ$V82d$ikL~=Xx;3owBq`f+ z31XVW`eo>+^KeloQ^!O`5*wM-HW!qEDn!auoZG)cFbx^}amz8u;Y^xw{R685{jGn0 z^Y;f8z>;mT{@HmK+skws%z#V%9*%1>&^{X*ifryj(xTB=tGT!5u|QW`XHUOa++wt1 z>KGR3phLI@2Gj55i_H2AAsr9gID*Jw*MxstYWQWt(?|F_+Ezr`6vp>)e<-hf$ZVq-cj@i{ z)m^pTe)Irxd{WG$KH+f4o88w0qF(6oA|Mjd6}KfeFQ$7D9YYXF;jGg;9A6t3oXlwY zJ=d+G+rG8$kqMGlXjOiaH}C*R%6x`5H>BUg{V)tzw`vw|9pc+- zQ6{f!2*5LjXN=(F!f%!ib4T?Pqt!1&FO$SNAmwOT1~8w8eBzaf-l7c(*hX$-cfgX0v_#3cO`Xua_lSdYq&rLx0 z_VZgyJ%aEL@rH%I%tZw?dsL{+Oy-J5`7Kf~l%d&#zIQaOiwlG<|IM=Rg^#FXt4BWC;(eAclWmHNby;oa4xq5tB1n zhunsIkr|G|m`A8BfX4iIrC#vTrjP<09?nh(s)z%$4Gl>`$%FeuWBjt}n~KtxcfR6l z0b;XAP8*Gp`>nHkeoS8pI$-Peh7b2p6LN{LD|ZummsDOwtGSCIMh%&i%^=w&>2r+8 zdWqeaXLmdN>MO|>zbk*pvpn5JRu3ZvjDF;}X+U zF+C?g@_m$h^Ccdoi&#``qFH5Cg3iS9ti~u7Zh@WENa>E94KKu4+{7P{wrM28>?0x} zs#&YA({^>K+qGjq7>H z1G4nm(MdMQe29OX6`ZNyUFdW~%w9LON`gULPlWx1U3gZ5nVW)`9~@}LA~6sps2knN zpNQqcoS|51M&Nh4n@f>iMB+X{<{ zdvvA?dKB;5e3z;(MIHn%UR{_+$m^rU1q^%RELy1JGB1BjC1J2&76!aJCO+cVf#1Sf znn9=iX0J3xB$x=k5Jh>g%o3gh}zrqJUAg9b_()?N6DHg`7UZS zG}3UMz7T(Y3aGNhH}JR%VAJ91vimiDb3MdFR8CR#tZs^}?qZB7P}MG2PJNFYQhssS z?!^q&y!*FTkaZef_21km$XsC zEQ6i+65teAM(qKHe@Z3@b;uf@vEYFLauYAme;9w!mTKzS`VW==7Ps29V95#ZFm5t0 zAO+V=Txk)HLZ#mueWA6Zp$18$*G+4n0x=b}#rwz&oBX{2_I1+4aQqky}2=Zk5xo>e;TK9~Muy>Lnc2w7O^W+ZP z{$tFVasgM)#Fy#k0M^l2_4cmVdwR0wfU19BES+{d*Dt8+IQd)zLbT9CF3ZE&===>S zIu9ezaPYBn3S>W=wBa1ZxU9Je$$32mM{Hzk*XdHp2Fv**cUbi4SJi2}Y{Gn4zK)ln zmvSug%ye(82&}V`MqTZWIR)2GlmKWugmF&02uaAGZX4x3TO?Xt5(tO?AdMB(^apJ@^X0Z9!A~$Z8j`_ z@#UG)q$yZ@EK`FBsF4251M#nwr-o-FvW*W7KA3)RzYS z*aTq6FeG=Z`3)zH4+(%i7MXKXG@hSzm~8LtSc(SA zvvgRCM7~y_c?=&(4$xYcwqlfhYQ%w=s|PXRDCfaLNtjR(xKG!w*2j13TH1fa8}!U@ zaQ6h#y45(aotkMx(3a$HHx_D5O$n8~`f1=jT5&V$X2Mm-qpp5m*Q8NKdz1%>%b{39 zA~MhLnfjHMJ)kWS^m<5=PqVx5)DiJ#ZU{}EOp6`%#dNABICXmixPYLx7)y1A;xMuxY70@3dDit;e(Zz^JG;n z`HbxiVWH^~J6Rt!LSb0-U>8AZf$r@MXgY7-ybj8Kd9LhUexyjdT*rS22CSvQ^Gq`l zz-#g9i(vr$mUcN@gga~^jyH~;Kfh2`Rs+9EC;M>L_ZBJcG~uvp!2H2b#R_- z=A=lX#j|!8=ipp8m#J6}bWsUJ7$~fyO3J)er=v=;RtYX4jt)>$Jp$m&AA$Du7f@oe z`vOE}e5C=Rh**^NT|dV;g&jH#fEcK?rnnL+WKlHg`vI{IbxO zfncJN-^WwC)K(H-mIx59&Tv@^tJM%Itwd0&t0Q1b{nrt0Y9KjKR?DX?nr+k3Us4b@ zXecN+-3F?Sz`lGqVBbd7veFRr#9uT3q*q7Ej>6MNf9rjT082o$zvPa8Obt4g8dKs! zU$0tCJ52+Mq(4&If~G$>Pwl{;&ORQ&406wO&yZ(f{{d%ZGso;$ntrHkK zd}2v+4EhPZosjT5uxN+VxDR-<4u@|KMxx*a+lqMr&tYKsC)@l&Es!IS=r8>Cv@~Pz?!lASBNU}so>`dgnpKO z1fsQp0R&$-cRMg$;G49i+yH=y0_Y_%LC*MsgaJgawLCCI`P8z8&rfL|j27iAGv$;p z&lTLgI38qBlF&2Ze1S-cVPHze%!EsL2$$Zm36E!}(E8Otignc+PeO6@sW2?nKkG=Me26PX$M)!QUlLR4 zGGu5&vLMLBKe$1C7W}gohoRvSg1yJ^4az=f$ceV!-PE*Dj=ylpGIGps?b=8mknW6# zQ@SzGgBM%BNU>j<0oSuXFrbtqO0Y)?(&mOKoj1z%x9gM)dJYUAz))d~C*uzoVIM)a zW6e^3xQs|X}cI(;8@N z;JAHncwXqOg{zEHPtM5b^L~BKLjm2AqCKB~DpbXoBgTLP@!!-MF=4HMZ|J4F-ZY9M zSu^lT5x%hZ@Fk1Txm)Phh}glCPX?{cS?T9{#F&xD_6A)hT_>;MUY-{nLj{cst0v_$ zFBX;&^Oukl;q3y(f@d_nSNsk5d~bwY!frb03xm345}wyGv7LgKXCYu!Vw%wGhjH(J zOg+}rSV?ozF*hZgHJ>&M>G(Fgk*gDe|G^8V33AgZh& z?fcvZ_OC;^zv1gfVBQn)?`sU=R2IB{$#%^xXd4~zw$Ui4qXue%o0FA8JQ_WAm2<|} ztk@FhpC{0(Jb~NhVNb5pW_B@>g!{C@T@g{CI#bQDo!)zw{a(nCBy^db+~(-RceHTYh!o zM@t0me`1BINO_|bz88$^+bdMn=aLD5oyXmK=_vADV7bkH2E#_ErR30&${Klz7(K7L=HbDbDl!j_` z4Rhf0?b-Z$ZAD?~&*~yLVDBU4M1nL80^t23-|n(9YkSD0Iaa@;&52PFD_T3;tRcgd(>ii0)aeAfA>|N0S>qH$|8CDBhP zD1xr_3yr&#gC9SsxDuST`v4w{5b2~4u%zD4v`~V;pY-v-H*a1b%}WyZY^&k2AYLXc z$3U;wvhA3=l^`brt{T4!x2>iBEf>!0zua>u+W3jdXWDI&v4Apv`)$A>h9Qswcr@qK zaa|z*0@&m)rADw6YtT3P0WJz*^Q|9opCqbJP9iMemWy33-NYlM`Rm;dg>iSg}vv3 zrJT}O{gcgOzCTTWP$It&Ne~z)SS?;KVmez5mZwQe!Anr7OKqdL@SQ3Ljz%*l!Nb}3 z)Ud`m=b9Nsx}~VP-lp4}J z2fCy!Bx02hfSM=|rt(KDiDVa9F7d=l_(nl0?t1!Ve{mvzcivgcE*HK1?a|IlO#41m zO?>W-Vq?D_^TTFC;P)WADf1h8_AQc5_gk+CNhkX6!=zoqwX~Q3!hB8qV1&6bEHUUB z@~3vs0_9%cm+r2{MfZB??qlvod%%YUI2NXRh zmH|=SRDEZEyWk8eBU5tY)shn)Arc-zknV5S7REMakYq18Cb}jU>V}Zx--7>t1S^--mS8>tKiaZ4ocRn*y|uqV zX25UB>6R!GcJA`E%AQniU5XN{6Uhspg zep4YrC%0sH#j?q6^0n|)LY-%ND)mIh2ilFb)s1NU+?Hz}zfd!0I3YMA_zKX}WO!VE zE0;G8S)_?4`TBB0#w;AKdLTj!n&ei+yre8Sr_V|(i*eqsDgfU&$xGKbdS|84izzy- z*ASQ=I!f{1hhZhx%t?FYVZArl1f$b|g=zI+N(^kP3jg+TS1)y`O&`1jk*_m`E)E^N z$9A<|(O=urmcg>*J^wCSxSB=7)jgble2meO9dlC6dV7R#2KlpR{#fbW`CO;;tJV9Z zq>X&Cp;bzk=lD{#aiMgZVO}!0BI2g3C`;uJSTHcZ(PCJ70+Z0uP21!Ce$Q@bt8nY> z!fFa{I+BfIw&#K@tJHCPy%uq;GvzCLYHYl~(C$oE0p5bkxDI9Yl1mYOlO2$w+Hx0nCCm zRrgpn)wKTs)jC34h?M{Ak&fy3&z7bc5?xWue~0e}Dj1->Pz z!=5=8#+zZ>Wf0THrkhxq;cn;oF6<}h`(Ag!Dq(~Mf}nKYBUAtC#S*s9)b$Z-P{3qA z^UBKS9Ud6+P{0Lf7NF(L&t3brHAvUG@5wM6!?<6E^^HV-d0h7Et8fk(*HP}A zCm%@{111i`Wd*bwT|c5~$+zwAfUg?dgZ}|@VTKcOIjDdO=jY9Eg5hO%i2+evear)M zHZ_XnVx!=rh*jdN-WWkO;zOfN!na5U$&$Td0N%AzI*h~Dh)q^NqHK<`-r|rjKLWZc7 zlKU()OfXfpAEiwzUB|1+NPg7_2PD(EB30=>lD$hbPybCO{VhL-^DoIH(|f*rF=IFQ zMl^Sv32Bw@(OSp@``(Ge+{y>eTCHHd8eq1{AXzH(t7rzq)v)>4MKIeZ89H5B`4YkY z&I&%2?GE98L4OY6+tJX4Pmp@xwS>Zru@E2-As9{{v#uhCQQzeU%qV5wA})-GLjJL+ z0@7`O<}jwB7HOZO>Y7}DOKCaPv|)WjOOUp@1!vU&tV5fxPu8EIdpFkcySJYs;k75@ ze{(Wk{eAY~JyzXV5YKroYc=e|_JTb39>|H!WSjnfOaUiTQAS>Q&uXGw!_!!)2OAX* z`|;*W!y&-L8}Fvs z1u%lfmQdKG2TqXafLa*3I3e%s_Z$WR`(>r!`5Hz~?@*Bj!n5`wKvJD{=(@+?870U3 zaN~ztPYY*eo~h#J$XsQwm8Pju~ELe9=wbij@yMe1(+ zhDSs9LX~;H8VY?JB01NTG6#@U7b*&rfNgz-N{~3(!c3RwmuCan;;j4CIc8kRhLGYu z{EVdS#4ZQxKOqu+c`w|x(aj!5GSBIM?%mSe)Jw)u7vjaXJW<(?EjTR7%NM`tjW}J! zhh0hm=w}$G%ujWasvI?NcV7j_e7*Lj1ep4sZL4a8_#@q=wHK+-;63;v}ka-f-i3Fml8 z3&h5r=&K90`G|u07Y<%#ED{2><;oQ)d*Q0Tg*($E<=9#`{}~YkZP3l_Rk@ zPj<;B<(yYM>4wT+OS@`5j2uEYUNNMvQoE7Uc6RmCZO1dMKWi~x8?|-iAy4unl3z!# zEH!&+BoWLrluI?+LIpg!_BnrA(1ie-7tSEmaYc0x>%mI+aZ)L9*4+3x0M1Pu{C6&JD`B$sO&p*bXaa(Z-; zJb>Vb+Rh_ak2QQ1RO3mg9aW3O5LDq18_%ca64X7DCp zt*YGQE@8Bze(%J&B|a@veNHIo-06v3yI6*IoUHUz-N%H zWEa+?9uU<&DO%;mS9%x<>Eg=lYM(1Vzr}%w3;h9ByX|cyw4+9Oyt{?pz?OH>ujJ&R zzs*NJjO(r)EZXLOVhf=ChxvydC^fifYLV)q9lhq|X%C&k13hd7|10srx;YX={F(x( z`i<_@0IPM-$w$yO46BQaUPCyqots;Kh_(*bmpK~wV+JA?c@AB+so@(=;12{%qE?VH zjt&&aYU*bp5O03^jKdq)(L!`vn<4G8yIW2wsM6 ztBooOQW@dDNUF6lP#W(Df;8S^D#e~6=J{>=Y6k&~!mq3$WOLnz+N3AtTPSWGGOe{3 zF}o-h<_y(6RjH{`v6ch5aBAR@n%IJ#5sLa(Cb!jiYht;GdG~I z8xbN5{5NuGCu#FXD(n^QRJt}}TfGxkYViV^1e^<&ioj_bl-?2rEo%k&mcVj}&x$XO zokyzLM@D0yAM4kZU5D)5yOs3nfG59=f%QR)cf`Yg{kQr~jr*2k5ecoE5tCOGa{N8! zM3j4M*^W~)|zW5Gp?9AB%P8|ZWKIO?&pRZScReo?O^)+(3-F>Q>L;0 z_7IM0Q|Yf5L8Wdc)#pgZMDs2>?{z%FHr*$~7Pla@!XMp!d%(UB2nd#L=4cPcr~HS3 zSKljtFZ4jj_vqV{xER0P_=l}giqSU0_&@hR&t%NiTQYTY;UgCgnV7hW5s~B`SGaYX zj$RNHww)oeDJb7^8gm~YAH_u6@gb`)Jm%-{a|i)Y&m`am1|ttr9vGZ4&|V27g?=s_ zsG1Oo0yO>|pdJl?#JaPa$$upo6C{rr8Kf+K5uC~${$zX~mC2$Q8@~*k5Kio<61`~4 zuA4)a0H@lxn3*hlQ5gnxswJy$wLA#lQtWOT4F?x7j{9+ zkW8HlI?9ZPUY6h-=jf$dSZcE`6ux9Rr@7LrjT&-}W>*L=LNOz&b{a=oP+9Z19T>z4b~FMx)F8 zd%R-A6MWSs-f5NKBYv#soK-<2;!Gib@R6W$dm*S#3ga*9++5Z*uHC;{;e9RsG~7l0 zWp{p8-`9UbNx7$}jP`H}uHQUOl5-%yIeEp8SKUrZn|>iZCn${nxW z8#2GLYRwg2VFY;MEw=DdgGfN))!cV7gOFoDzUWb}#X3v|Xn4n7*$ZTXOHTkzspwlC z3(lyJzh4tHSP3ucB~UL%_Dh0)!|b|o3Rw&t5B~2FNeRy^s9!{z04w;mhkNhhOx( zhFvf(b4%;uXwi`p8qCda3r?i(MFUhxg!~wDS(d>paG>5-k+D3W;L+KCK}rGBzT0e5 z7guG{5uUeTf@tEBnb`Y$U| zCif7e_V!~S$uO-g-qp#T8zC}E;`VgyRO#N;B)!)z>R=B^2g6tZ?}OZk_s=DY!KXs} z10*18S=Aoil~;2WQ^In8Y`LlktlUuzoUNHaA<6pOXceXMlrLW5;?u}0|61N_lmqm_ zsfN{2pNFwtXAA0vkbVrId@>r`t$FSdSB*Dl=y%ySGpj?M8EQ>6lEG?J9v}UVyTNc9b=e zTHJt$MRA|oFDk9TgqKS2vgz;2=_q7bbVb0^glZ{RV_qFpMnzrS=IrCAH*EX}SQY4Q z%$|riROr>wytgrb7OAo39l1l>0*Xx-p_VXbb~q4-CrZsn>h1COs=;@t46sr7j^%#J zlCUpfr1xy1K31*$U_b6NcKc!E=Q2JpTdc?BAQpfF4xUfKm|N&ILEx+*zR!0ohuUyFMAX4#TA(qyERRo&MZ zu{F>}+WfGG9H!+U` zN}SGzg=Eox=a@Er>!X3s-(g|2nGoeqH;aaF(7j88C^GKRJeZERy?5k!tdCRSOuTvv zU#YrPF?CBHi>Jr9H@n4*=upr6h4mCTO@{HHlT3VvJg73Cw$Xu~&<7c`km|@+2nGQp0zm_B)@-aWi^;FAe`>Zy$ zc@q4jN&->rrIVgfDr4-NwTK}zYsgBnaecwC9T@}HWf(x{vlR{Gy5sr3_+&hmeo%r6 zUII6NM@q|nIxUcmr&A~&p_O$WRDqr}M$#CX_tKb*P!<`kX>xS?QJMPY9*y4+z^u8* zl7;iJZL`mL4ml<;?op1tfQ9c0@kB_k*rl_7Eaz?}oP@cvQQ>t~2`ae6Ii^S;T3tE` z!m#K&qC+|%9EwBmX9|2&*k(zdm7Bt%#T8F-A(L*Yr<6X=G@35i4;a1Z7LeTG&AMJ8Q;QJH^YGmyhtt!2{uVOc`wF)oKt6>_mHqL@;W zSca0@s*OVClaAi8v-)bMT1q@s!hg#Y*2Z|8rbF_tXnBFDRB46L9*d_80+indbR`5i zo#RMXO>*fuqK^X>Az|4b_4@m*N%%jOvnzA6y-h^XnxL6x;k;$vtHoj5Zo!{__?A-= zTSz0$qz9ZtMqZ{VeCr%X`+@QU0XQy_q_^5f5CSm)fgzkVKOk#p2P{Fa3pJz>%?=P< zMYDP%loBn?SNE1Cy)MGo4{5}}v|=G|+M5&rq4kE^+qkXk>QHgr8}+6U0|tuxdB+wB zI;J{(tiUmYOsggoi&)Y-=Hr`xCRsV7U9O2lW7%Eq@zR2&n`w&f=a(tWBF?r4kasz52ccb~w750G=$|V9J`{j@+ zgpys0lm(_?0Dgg_EKazr!UBE}Q|qUuhDJG7i4vg+ujli?SiEO{4E&3K4uf`M=2(JQ zFA?M7ODKQ)%>*D_b49bMwx`B&xI=5jiXh|i9jc)@J{X~S&LNk%WS-YNyntp(9s+3C ziRGf@jK-y6wyCXWE0n@i$}Owlt4@@Xcwj!I0-ypI$p>vg;ll`uAZ=UM1z*1R-PE)Y zr)yp733S~l=CkIwFnG&<_j>U#Ero6kd>pf9;P47oa=@cBi0n*?>#Krn1sju})p;!s z**vPc1FElQMdIsb>)+x;cufAXOplZk<+mc4aLKN`b(9zqWx!W$!H}7bPsFJg0$*?qtI%Ds-BZLPC}-B z?on(~P}Udt81@ShaGw>5BpbQD3CsGeXAj=VFnZJ}AszI$Gqj||Xh=TrsU(r9P3D)( z_$%t)K8t-EIn6%3HZFd&6aP;3XLEfj<0Ky>GJo^A_@aFClVdmzx=%o6@QfQ45GA*# z@JQZ}q;l3Th}&|15K7mT2M@T;WH8Pyku7O6>!bJ_+iFD_EDCd+4FYc4mo)BGpvlv1 z;2fSkcO?u2-V&ojJkoTl@B_}Y5b2RaXDPy0Gq^%b4uUH@M!jNHB>GV*RT4OmNkqjO zup=?GlJSk*X%3Jzz%|Gfj6E%${l&aNz&E%D$GTbC&UNK~7}|vX;`q3f8@P}>mq11(doA*X`~o*2JM=Cqlpwf!%Fsx z?FL@|wlD-UxgT=X@{Viz*vf}k+GLx~En#F^pR?>{>kw+N^+@6S&HNd3jUm9AJR>|{ zXpQb#VJVt_!ZZSF<1SEpCUv0&nyi@Z1RRmUN3-F$DMJI;NT6Y+_CbVN|IEfb4MdLf zMe4$OlX@USk45j=Z9SF-)N5a~huwV{F~MR$>`bT-+Y`zE4FQBgSDI}Fpu?8a^JVB9 zicfVIGbxPm9eGRc?V6wX<{@@#>`ukCuMEMKsYWh;$Jo9B=)Gep`3nX!&Q~2e`=|%Q zOplu}@X-AJ?Sx=h_Rhy9!Z%-Pm*vuIIkrKGS3J}6DWOFF^!kD3Cennv?VFp#xyR!X z_XNPb#w>+cp_q(A&{GxwBMi_gkHAXW$d*rMhSUqtJuX{i5lq|~SlK2dsW zVSC`EH09gnUX-$iTIraqcY%^7IOoK&RPqvkZd6bHeU6`G?B`}@%)er#LtplbJR}s8 ztaw?&$xuw=Js)ZBeiCIy(hDhCl-IbMAel?;=TY`~SUHyMFT2+HwaPPc8xVZ?O85>@ z2;b$D5)h9r?>(EunIDi#fH*Jj;TB2Z-UM2Gau&+&+t0Q0X~U(HF#1y5^x=>@Yq!Hr zx9bq-Me6TYB0SA31p!i%2|=vKVP zL-BwcAOVfy56mrKUEXjPW24`Mm0THrwe%Ly0g%wy>4y^PZRd0)?L{zJrq^Uy`L|?_ z4(G!QXysyDq)r9c1|9%G?XAx;KBEo_NAxf*Vtlpf_4@W~v(A-hzNSKx1nsmR%tpSP zYGH@hTSh~E@JBiFjWc{R9g1iNx>YL&ga_?BrMLYju3%vZ)dZb+F4HQ(n<@5xm3~?8 zxbE#^_j;~9mkZQ`eNf{PHe1vc{+VZtxSkey6G)fcPXDHW%C=Yug-9f$V`cQ&LEi@hb{+LNd>G1l65| z3?!yS`a<~Q($81r)>0MPp=)SZOc~;##@aZ*gf_l#7Ku*CL~m5RK%NDEXDtxYp65UL zO@guQ1-nl8KP9LA_y}LhL8sOhDOxVcab{vF2}W4W*8?IzelxQ?ih&#rjyGF(QyVz5 zSjIO}qUcYHVNCC|wdB1-*J3$ZpAw{Ea=>rCY)R~^=K^Y%lEIfY*00%h@u*ViX}*td zI^Rqye3hn=RY|fyA3r>QWy{3mUs+eS>!^}t-}@_$PQ6r#n{CWsK)RU{GuX_t{RY82 z&tSg3an`L;l^Tn1ut5>AhlsrvGUg_scG6-lhe2fyzmCF5Fo=E1Pl=w1EyNevMyO>A zK0hC^MjvIchzl#eRTB|&M5e;t0GteyEG_8)`Fk*KO>|UItUQx{ndgFox~eZ68$fNg zn0ohK?%j}rGSuG}AEKtt;A>Oc_82BgN4)E{uHl;p?NNOt<3=DLrWwg3Q$$4Mo&@ga z=(ODS36RSsxk!PDO9GQU##>NE@ohxh;5kU7a&Ci2g`$iD2eIs$?Ah^tb8WpThf6^c zM%`^3KMsyXjKN5MRxr;7+|q)up1lBH={y85_ShV;W?xfeDwa;Dw+(wp4+#x<>uC8Ywi|l_Z`-kj z(k90iQT^&+Ef^Ad+797wSY#pcm5}6302M&$zvM*sh^MlD)1gr;`+dFc%7ptR<3~F! zK{q6Q&DxZ%mU4neI(e5KGQm9wLG&#(Ktx#?Wf-tvz-h(hQpRd9v)eJ^XW(T1ub%Lf z*KRZCWI{&*Ie2LTYf-aewxI|*R?I;`&!<10i@I+6pHs#_FD&3c(rU8SmAyP3XCJl7zS+>JL{CU$rv zx?gvHcI0&o1>KX`avjTLfhxSMvFgdUmR(LU!Fv#8n4&l5%FC#R4=!Sf1*8qSa6p>L zv-=b7hz%SC*I0)Ht@ zbu=4W7X-AUF&=#fS_7l*J%nvD5+3jMXz4J28KoU6r>KgqtLviOWku{g2k3pUVZB#x zjU;!yqB!8Kz(MOSWgnG}KIyMAXJdllmC0FNiSbN>&~deMN|-YpOOF6uj(Wy}G`T`l zpQ&l89|>E>(~GX-?Ag+WFQ~-|s9={-;(0wH#5-xAc@k~%qf3tQ$8yGf&hCTuu<(q3 zn(tS<&AgUtz_qVrc49uS`?Bjx1g_2lSDy6NMH}+G84%+?bp{BddOVBxAE{}x>rc6i8^^G0fVbF2WpP$_vtO|;SAHX09EW#sm@w zIY+YJFUbbk{az6WAGuxMHb!rx;LYEh|$qY5kC4%WORW%>MkAdq__5w z^G86<`eo#g(OE0*#B2I)%J&Y9UosKwo>6s5#WAx=2Gr%oxvkpjD{{b#V1em>)^W+J zflI^6=HN|8)-HRn-yl%|r9*5xi_2x0*@8~x^0$@J*nCeHCe~g=KOEi*2c=2aalY5$%wKr(pW6%y#tfX#iZ!M^Zng%+5M<1;G7^0vx7ku#Z zb(TV!Cu8Oy*7k50rR-mh>G`>T@0In4IZl#K_A3_p8Re)GdE#cETSWTgz2 z*0Kq#N$f`*FVPv4YokB}-R@`pd->=BK}o$os9UaJq*_@bSG(YH;jQgfGzzbn`rSvy zd`|WakR2#v8NAKZU}|_bjm2L2F`!s}Vh`ek8mA%sCxznJ^AbU|DK77ScVxngPQdHB zK59yhL$*>fZK)J9QJ~4vM{e*X8MP(x!MZqmb2)_bkiteTM*kRvanvTX%yhW%61}6L zaj$L~@wrE29QI>TloQ^ZwwoCWGa^&+WqP|}gsi_$!T@e^?Fi{P)t(8Y#nc2E0A%%` zrk&gjgpy9r+jV~l_xGKDAG5&d`@kCfCbnZN3sA}ExKd;tvN%^Fz+Mbvbfj_DgCsO^ z|MC=TX$#h>;-F<6r&n|BYQB#|j<14*zX5!8;agPPLJ8KnRir;UHmV#nV`J*1(q99U z-E8U!*DV&6WmUdjn$(B$t+Gu=gzo`+-<1K@if9TpuH*%bFr}z}quHum)JeDyoC71G z^0NEDeE6G;-cQtgNhAc;(3^NS^T=pmCm1iO1xpjv-y}&SXCD%kVYfD#rW@vN@q!y+ zhK80;C+bnDiTQXbFwi+O{PYT2N9YPtv1&5t!-DdCj~<@%WCF*%A9BEk$I&2qV5XnA zy|FKoi437b79P8QCkuJzZh);sCt;qb%&$9mOkL^$@lH z9Qoxwg@$CVn&6bRkq3!?ou@gtf#bx*IWRtN&YM{ZqszFn7M5+cV+$bie#fVDrjt1> z=P)|CcVl|Vn!Hn2)D0)R_FaBvzs~sWdum;0NcXKHE{?Q+$J7Xk-xm7P^fxY}tVCp2 z=|*D|Erx7BO|F9opBr{pM0_eK-uY{Hz0NKZN2bg{Z+Cm9S|};Ps)V6BkQSN}2!u&N zogwb1lj23$uN$KiStTn6Xwxn;b3zr*@L?hCs-}H?r1=J4NDhB>hOsFHAEyy}4UwoW zAbY%nEBdy7rTDW<9v{6olkX=~1(V;;{JO*^>qy5XR}ExnFNLc>eL6Y1qCTjoe0%Zf z#9~}r;7d=Q&>#7kbBT=pJTHT8_h%}-?=*%-7L3fnqw>b$B3%hP=Pt<_iM$aRQZak? zgdye?)46QxKeo{eF3D+U6$Iu-HOKw0CaYn*I&6-fv^k?I1 z!Kps~%Eq$aU+(5K}>(4kzr(b`9y6BB?&cBNI=lAE}ihlq4v;Rm=f%*ga zU;K|x@ug7Ie^)8;Q~iCxe^h^8aQyD$UrnEX)qnPteSJhfK8^qUUdHL|M>n& zi@N^#-F9vA{nhm$DCW;tzrUt=?5gDF_utar+rI=q>Y`0R*#G>FPU!Ss(y}YspWjU} zC*!~6zmMwT{QCKg{9F3}`}wgI@n>wOU>?JEO1rT++Y0Bg*#Cb013o|3KR#NX`#=7F z(@f`?(<@6aWYa2mmZN3rhe10000000000000sI004Jr zZ){~kZ)AB*Z)9a`E^~Hgw7F-`#7dTb9`;uT*Iy)XXPJ|{vj*8@Gw0a+#+-BJuQ%^# zcD0ga7zU(%@v=yEbye}yIZx>Rm;dYPyT2Uyvex79w?E*2hW_|VKBQw-59Qzf@Z9fT zsXzX&fBl#BDF1TS*;f7S4}|zilHK>u-O5K!1V$ z0z=6A5C8F(caCBG+aJ}oP5%W1&-47}6aD9LDM18+An+ahA6@>-)zw4$KkEq7G!6d! z-9P^IU&_A}b=Upvk6|40KmM|A%h=|B`y=V%wEefszy4#j@8o~>{p+%KZlFVv=zpE}Kdxb%;-mqX`|H1Vc;mY*@vs)-(*Ny`KHir4`cLpbLGRz+kN^3d?9W;LlKt%u?Y;hs`bP2J znm3q#QK5fppuar-^QSxVbQ_ny=0)+I{9_^Dzy1qY{_DSFd9nWMzx?@sEasn+)bA{R zUZDSR*1sbE^jGB1388;)Y5Fhfd;1^Fd-wVKfd4kmd-`7o{_n!HFWrCoKmI=YfBv^< z{U6ZZU;kM4e+$Y#Q~%3ii2M`s-^Gxo{t5f9(Zl{j5V3!2X!0-W+vOh(_P;Kq*#Fj$ zV*f3q#ou55V@TouZ2|p%ds4o!g8n^l&_9m<3loz1k2At3`cE+N7ZpL_|JK6j8^=H2 z`1cdy|6d5H|NQ@5!~dSI|07@|`?md0;G(a$eEIkLf4}PLw|O!0{~2}oe*#wj@7wTK z82$5r{ka!)AD8*R!!J$#@t0}I*L*p0W}V&;+woS9|Mpz}7@U58OYFtvH&So=Cy@S^ zYRQYg{gK66{9pb)AUF->|Cz*VPGJ93`>bJ~kRp^L^S*S)t9Y+`&x$_}BK%=~f8LL` z{jUBz`Gl+#gxY&X^6$a87{OOgEP2mMhVOXGx3R&v=sY=F#}D@o4Hj}oJGx0S?SZ&Q zlkW0hem={#->_PL*R^(K?7)6k*75$=)(3>SE6uYR&*#H-WX6}VnooU84Yx9_cAnVt z=<$=81w@M^Iu94<3%(y27S20qE#dhr(BR>NS$_>utu@+xH09v7R?mDDjndTtz1Abo zMoOyx@i+fM0cpd~4NG^=j*BF|%VYZkR!bitZS^SjkxA!&ZQg+xs-uRTX{1_-**5%T zk%E1ai0~MLF+T5LOsz+zHBVC#Dwj;XpV=I_YT^i=N*G5EFIO1sBYoKQwpxl%)bo}n z#bnvHt9?2A3^2QFGFlJK)`FkSDQgVIN?;`jNL~8(J8?F0+(u*7ApC_sAe`-%4xJ$)&JW^Q*g- zPDa-bLH#c@0zWQlG_of?fO)@j>2aO;@K5Z!`$s0-&yo?mg%1>`hi$q??=(X7>C9%2 z2p?@d(3j10PKr%EvY)sGL=nNa{9!s-Rq4*-PmX4PGH&`BT77ys#2*ip9IXBI# z&HKEH4+qmkU|PEnDN%#TcaKiaU02Av1_E~X4B?nsDhs@kdvXapmeRgmxb~3mCKioY zz}vA`qa8)OQ77r6)6UpZ_U3l5-XkC9zzq%O_?yQPS)#t;#^4~m5b!&{_0CU%JKn4r zY--PcoJk2kR84oS_MJUUz_G$u@>UCsU4Y^9j|GqR@ghS;#0NuJpAN;g3}&ML#(w5| z^GE0^z8vZC>yjr4tiOxH_TOaIXhAt!QB8KH@!VzWbR?D%JbxPy9qdi_YpEJJ76cc% z0j5_wIT4-|A0xf!LZ{`w_vIuib3-$R5$*ebO}=;vZV=$s2yC%|M)At|jlGG`gMyjM zRy^M|Hz9T@UPAE2Q)pIi57aqGyV-vUY0v6@3RmM>tE^304wSUJRI1oQ(1Jq$APMzt zuax&()?5RZl8;N&-@G(S5ujBuT6tS24)>ZVT{GIa1?<2})Dn};5#mLfHwq(<8IKfy z_B5A1;!_bQvf6S!fEhVYWGM@yt!E({Vi8tofz^ zOrB3mp1|C~aXHQDd5&9HcH?kKKevy0kTH!Y;ucrux9On;}VP{ zHYOhhM-kt*2ne>>V>ze8E8Oc!wmFCJ5rN09R2HCt}T%3VY&>@hS5iQ5O1Zl{P2lE>?JDnP-o(_X>6GFv5wXq#y`4s!} z_i@NS$5E78L{#Jaa}2?MTbI=~l-giVFct0Ks9IZ}ny~_C9T!LGyrq|4*!48BV{`OR zUEIR2qH}pE51TI1`5J7^g?<{at2=(8)o)cT`plQ!oN|u^1_)gjw1Rjpy5X|}>ig>) z?u^a}0bH3}G+NCccW?JqjYCx)*c5n90DxciH0(6Y1J`fR-p#gu;T3rn;z0Zx)R@AJ zm{tH=K&_Qp_G-s*brAfR#%UNus%|N$PeeU?HWJY}vFpw7%!-K)Vv{sGyNzKKdfVlD zBD*y19vZ(*tPMi+^#ZpMkfUb`U-dR;P}P2P%K1Hq$0j}~?#+!hazIgCxsw>!C6p`| z#|O!Q)Ol7hP=DcnE^Lv>+`%pu_V6iWrg}@2_eFKkbXwJPaQPjDfffA$rgCr?b%X=V zAP&^`#U|K8oV&H=RX;hLZwm_uv`P;KdhvFEMQ5 zkhh)4wF4yq-Uc5>4I5;}$kq{u1TF~xH2LBzj3Qg&2$lPPrT$eTgPtInEt@g zMuRuH85r=Z6j-xJLygzi($TcZWYR_S{@d|fNV=!arz-r2;pFJ4N23_P1LomO-|#70 z=)g$h)ox!>bHQQK$nR1Cg|nTu^r{cww=P#FQvgqa_~RV%{^lsT>qBw)0cdOqji|#o zFW>l@=w}yy4Se{TxCHzR&-tL2TR!Hu!|4w9z_U2O6$+2J9|_4+xrdO#W38?Gr5c?V z9`>pRQ`}~_ziBT#NWs`2w9-s+l-=W;_-wZ$B2{8_Fb$$XLhO;EWsI&7Ny$6r8WxbG zAN1InPI-(tkk`s3;AK}m&On+wxmi72uFZGu#-VC|gSj|B?xC0}g($Ad0q(pUnos20 zCvd;nYy&jbZd~=dt&wIZTf>a;<%zYIvmlbN(Ac;RmIE2pX&OOAlo-a+*sAZwz)=sK z4yH@Tu(BiwA~Pz@R`tN8j*^r(?%lmKMAeWv_1Y;aib3;)m|b799c_FSK$+*kD1_=v zC>tMt^O|kMCv^b^*1&s-LT=B2i7$1N0|q_>?En6)VpIq)u%syaQ2UdJA6cP-TO2t&`V96QW3TIF`KY2 zFY-zH&V}H?@ZumAZ1zm3awR&2ni5X;i{WwYDKd(Hdib0Mo*l%Wyn0B#KjW-Ts9kKe z1Z@+$-c@Riz=ebwmy2`A<|}qZfR!u2$s|(y;C2Yw=Ibz#_^4ijwX`213CH7|aJHy_ zPhk!#g*pZJ{ZkWgIk$=M!(CAh6W9i@2r!|POQR!oV6WZWnGJv3y=tKD0Ek9^F6rf3 zY7>pbyF45MSL-zdYx1h%BD75pwW;Djtt`K2YTTqd)Wt)G5w2#zRMQwU8LQ{oiWJfE zt3AyXoxTzJ$j-|mFw%%i#TWV$6!`0ZRoFKF4E!v>Sx@Alm#jh7gv-0uyPshd1PONF z*2uWZ7qhU!1POB>spMrAmpVTRtI+fFGjS$0_y87$?;RPF6U9(^Ed&9#fU`eTHUVDt zWH7J<;{M8t`oySZvFo^dpF%s-q5(<#p}?^;33;p8g@QHiD;vPL`74Dzy>1qNpu?Q0 zu?4H4f8<&N)HfgDlBzJ%?j~%S`s6WV02%I7=-Xv1e{bMf;c;6X_5B4VpXNe%Ls)2m zEZOr#8ceVu8*-if;IS;007pQ$zrdXEY%qEU1@hY>YO}78Bd+I$-L7eawgoOU4+pNj zVJqtWTn!WeBv9Lge*`FR!DcME6s{S!e+VkBb$3{}&_&WH3wTPy)6!zVt?T;HZYkYT ze1Z8Mdc|AbSdUtyAT!i&FxhoD5ic7CHKOKb$jpJE1eAr6JVIJ3ZN;PQmn_K9#JB@nLQRQxc=wZM%fI9f9JN# zY+tYci_+)fNdEIV9gaO6bA$7b%bJaCP+(;h#ro^p?)nKFLtmJod3trm819#`3C~X* z3gPFOurtyEN^8h06iCqOk;h0k56<2Mr_G|rI1rq1u6RQKiBGe9iAdNEv?}ewjP@8k ztcV_|Q64tNr8jZ=wkRa?Wl!l!f1}C)=_9`xAz}L}I&m1`5?*QjfVKK%{s$yi7R$4Q z%Eja7hOer4ah0l?ca_oyEKKSho~ZQfx|c5+@?Sp7YN*dmUEKg~5Fh=>Sb-!o2@gfL z5=F8hthX!=k9$o4e3MOk(1%VfX+BZUb8I8Eo?EW#Jt|IO8DPTf7E1M)e`5MmzBC0; zV4hMtdQ3@xzAO$vsvY2{U*<=V^8u(O?ic*jCfo@5L)ql0;ePN=L4Une z{3w&^$4efqSNxLLE-4`9%FV&J_?smLaG5?4AYd?z4wS^B$!g#L4F!A$V@a78`L-dT zCKijK_zB!kvzT;gVe@$Re+jF+HnJa^_Gk(rX|^TZ&N=2sFK-#0y&kY;H2X=!aBe$f z8$>ufifMv_zIgH0XzDIn13)feLMaWopo+GH@5G7)>p=%MXvBCiDW@c;-byfeVlIxBP`szmwDtf2FM-`v)8iN}viA zeH#HV8$1g8WG75iY>h7nezX0Fun;iABhlF4Df*oaQIbpVRWuhT6ObV^i1~FVW!kle z0m0zwbIc?)jyYYVlHi#h@S>(is6EEDZ6rgvep9MISV`Pr8bnGpr<5&m)&T=vzA>SJ ze7@=N%NT}3&A-`Nr~@CNWP`#7amlY%+E^*EN~e2baGny5>d#Fbn$3 zvWh;mtm4pRbrkg*-QDO;+Fh$*fzUJc!Ehu~4SenvD6T4|k4;zW6nNcU8<6p#y_s9D zcZ9_r?|P-zoXwB9kMrO@YoXXxLViJ~J(0nhe++ewC1BiZw(|kayUD@E z(ErT!uk~OaYs5srP0L7t)e|b2U|3^ z?3vf;%Nw%l+%iX(p0Rr}6j2zQpDAdcN4yG(&VL1r7Tm z-51C%9kRO~QAV6KH5yo^ZX-y^m^Hr!u&q@M!5HFzbxj1LmuV5;BFhbj)<9q|RqIgK zX&~6$e+9q9FQzRpAVjI2TLyx%R2V1id6r_SWSsp?Qpk%NTlHV-lp>QD&^lAKJdSBF zwHx=4a1m9D+(+#0#g5_FuLRKD0<216h(6f>AwhG7g3K9eOO4sP&RETQ-ym7=g zy)^?~pRU^?4YC7BeuNxGpjw0niZOKrrxVvbfBe?Tupf86coPxs9aWRoY?__|nE?F(ni&5k5XfwM;A)^e zw#?^Y*X*-`y|T=Z(&gxYqROQQL?LfM(FG10{{sMJ^;J!?wkX{Ay{X+A!IUlJ#(^Zg zfA3eyH$`Q}#+3}3mTL8p9B#yY+V-Pb1H3rUM*{KxfXj%aLYLp`QemItz<)@Jt$CPdtKMfcA zkQtg>`;-?6^gO_n73G^GVE^i2+&VPne>;&!X9lTDf)i?HuR*+@>h$39m}wASFNztg zH}8KEDSRdPm*Jk#e-Y}|U?VAj-D@Zk?1vs?MUrfS*^OkTd8V~E&T`I+@+`9G&WqIa zeyK4sVH(;mR~W^Qrm&Af?DWKvBXhGSz@UaJIMEhTRTw;<1Ann>=M0-CfY8@!fB7TX zGBw4uipqzL%twHIe2L!~)+B#E;SC_yOr-j5n7MuT66P8$s<7#(Q=-)oirf7Oa0%Y^kB#-{PbLw8y9-^^|P$DtO;8p73oOpvpIuUla;BgXImZA-$ zk!0tet&pJ0pu5!-m-+!l2-)mO+tXa^MxPj8JZeOD;wWGDOozqUtY9wbe<9(}z|-`1 z#lobI7mePf+C3xR1H6+7Iy#sX?!K41Z&u%o;T*2Q=`(z8de*DiLM60^5>r##_-Es2 zMKZaOl)8jztq?PYS`LQn+QLJLgn621<&wiGuYyy81gpCi!(9&2bCn-bcKVayo?`06+|jrWe%9#({2WBK67m29krYZ1^U(02ekLdR0;3Le}|C56#y-AyNTVl z`~ae!%p0`(ykrPEk&7fK{%YUP^-N4wRz*REW={p-W2(`@)ntVRFCpO-is0ga4fI8@ zErpM^umMpzbx8kn(=l2T6(=a_>BGyRDJr5O zJn_W5?R75%1J16o+DCWYtVcmp+D(FVJDB^>mc4xd-Y}MZf2^b}4HZYBVaH+43-En0 z=9legqU>7;)3#k4=GnqcJ_`|Sbn86Hho(v1gUrJeKeLs=Hhxbf>p!pcI zjWRZ{uk&W7uS)?*3{J8k@&nmLQRG{l;P!h_06Z~k zAn=CY#13jbYV;^?8pdQ%rwUYk0D0@xVw#RUi$*Sf@~MUjuWE1TFQPOA(r z?&zCDZHEOeA+5?@6^|2+ABSClT(V%?0_Y=ki$5{K`lzTkmPXOGuL_LojT{Jxz=1(Z zuG~1lL)7hKkr9exoMp<+JkX~UL^`r08NKo&Uw@0bl=TxG=q#KC2KXsLL0$EUqM$2! ze|2Du{r919XkGKy6Xg=K56##Vt3uI#fPgTUYHNF{%NvXMW{9zpSzbb|4Lpy^~Rl zkyKnDo*%QwzD^v;MbHk{0RwmS-ONqQe`)$q=4BPQTm$_dh~RrobmRFGmWo7twnq+^ zstw-xWKfdf97gCh!QP1VyE{onklL9*C1THU=w4kxG296Z`Hs~_p)SRAoB1IE9DATl zY-6N5goXQ-ozLPClc7@otI-Fe=99CeQRZF^MAobaOqJGjfU*WnxO{jT1d{OCe{p*L zvEpIWa`(kvUXOIU+wqq0~tbqQt z3tGh6lmaSYC`De;ZJaO<3D=(x#5Q8f@nZtP^(2Z{Tu&%hN&=0#)`{d5_({{i{vmsl zBUp`1>?vB!$zTlhYE14-xCav)e_c(Ah87iNA}{LQzo)Hzia@3afZ^CF_z)y(K}3gJ z37=j8(72zH&pj{whffXi6CQ_%X`~govPS9O&7mZ(1kTYNZHE@%+}S6GPYgb|nau!( zj)Gv~bq^u1-duIf9sFuyAI4b!2v;5q6UFc!eE3{A4BogF!gz+93;@uce-4^0xa=Ya z!e0X*C>5sfvyzVeP>#r{EI}iFMus;Cq`*t?U0*XW=*HH{0EmNoZ)G6r%EpR;6Q+yk z45&7Z95q(Fo4-PAOpy7H;aFHt3s8H@8n_!UqY4%k?`FE;vFUJ2{AD>AHGxK>ncqZp zn{7T0gt7yu68Nm&oW|(je@?zf67_wZk&xWx?01&TR0&eTPYAhC+q2xbZ+Tj;WIO`h zq}+*~r{_(Wy1{Z9P~BbAHv?_T2K6uUUH`M8#Tj-(MzUyzNk@?wW_^RnspQ}$eO(7s z3Q@jm2e?z=!VSR zf_=4)`&fqJ0Iegb->qKF*JnYNj4PBNi{%p33d(gKIIxK}*<_0-9Ksx)%q1hHrU@R! z&+}x!T@kVv_vy4~0zE3>Xy%n0QkC>&){EiFQ$t~1y(VD|gur3ZpIUL#m*?2~*BW<3 z#YX4#e3@4*e90fze+;ZwXGIzNE}>y2flMte@lkcS8^hYs2Jf%=5EH{Ng2orcGgCA^ zJ6$%#pp!;n&WcoJ?O-#~S(mFy!%gMVR%eX2PB5#+m+BwY;R>ukeO+C zV%NO>LsLm)wX(eJd@h{n=$!|7>ZlNCi6V53s!mmK_Yo$yVfkP%tft4U(8z!X*;<>BaoM!T zLMiD?4ll?`e?*xt>la8YVv~myUT`=4q%!jQU!VSDGqf%-b7=P-F7v8cPUKa+1|!o)^O^i3jQdRgM4#{^f2h_D+P{wSlP z)ioh1F$Q#~e|?$4le$U6d+x`&ScX724bGl#H{^m?UleRj19T6~EeQO5mBsG+K48+| zr2;P)e^r|3+zhDjgHTo8q|;rWmv=hcjN{5Jb&S$Fgq7EvhIit7xF0P=8Qf1}s_ka8 zX&6a#K<(lQSpYB=f9vy?m1-+0a5RYVCelmnE6dlB+dTamrLZA6bD*sJFj?w_D{EU` zWm*h_k0r(?O%iHk^fk#yxk~5$(&yG2a1Jpoe=+*LL@r%6@r)H;-R*-$lC7P)K*+X} z@zT91X>~;MG4W0%t8E1Ayu&&mj{_6v=pyO27>u(9>LNp>-f1*)duZfSJ@lE;rvKx_ z0Mk2P*Iz=9>Kkc!ayrI(*{KAyY0(2Ac_me861lPPt!hw?1aGA_XFlI*=FIgsy@LA; zf6}ga00O`KccMssVTb*Uj3?AMZK{m9(3FI`$5z9?6E}0+&8K;@KiDrmOnfCk{KBLG z^o7sIMC;eLLt=u`J4I`-C`AwTR_uB}yq#3BNbxg2-Ko-+Ins#FL400tA)My4&34(g zOepKSQD3-Q-F-IYF|baXC-hW>HR|Xge;ESM3%ubhT~mCI<029c!{*pN(RirU)TSi7Mn6DTSsSt9%QG!)c7GR6Gt^P2Tm z$K)T7=ucw99Lxl)F$W@@r1S>df32KjlFy&NQ4m*ecb7R4^-GgwC{f{uzswFxt`T$- z=n4YmIwrja7pwpa6U<6FCb`*~R#gdp>qfoFA7>&I1@|x*c;n*q^!;clnYl*7a_wO3 z+n&J-A*5+9qYVrjGMn7CT9YZ&d)epFZ01~##B6q`NiSVOw-{b53;b+(e{rJ#&O&Ij z(j*!<(6O|Se4uzZ%6UTCdp=;lX(l>xP7Cn_!2$@EHy+)B12Y}Y!K)rhd2?=D07q6U zwwmuauKWo356)YhXP6JeIG)Y=%5uU`+`#mX{_@Ik(8V!e{>(iRs2KsZN8nr)wGvFWn7!up_1OeO6iGUsp)eXyJE2- zYkDJLH;YFM^5PVE6Y5wTBfYaxqFoWZUrg5TXj8~C-IQ^3Bcf*I#m4*KBsN2BF`QFp zRK>J$BCW*vhtyx~(6@SP27Dkao?l4eyTHzi1QHaQjMDTqPz`MqL#qZK&l(e-ha*{2klm;o4EQrfbff|1p3zOY~>m7l`R8E0PKrHyjt|C`5D) z9N)6!qkJZ+$|TQ`BVf?lW!+0$ch%1}QyN^(q2wMGOk8-=f>r2DDK~XNoiEpcCzL!u zeCsJ1ep%EYw&6(_Mf&F+YoS-=s+W!j#NGE0nhN)ePTw4ae_BxQ2yxxRef#ZjRRp+sH}gacdpTp+POz z=U%bmO{_b@rEW{Cm47C?%haWDWC&N!n~BOisf*G78sQTb?f9^k z&@BQR!l(!aK6o|ft^umm?%FAXK+os4l-k^xRp6%BbtGLP_U-i3m@Y{EbIsY_O%MY*PJ(oSl^OABy9n2p9TqaIZTP1DLjmJP-6fr!KXk0lDtrPF>JSjHK4?_goR1MsuS;Eonqz>4HqCmy zKcx`hNWH0d%Uu? ze^rkDwqG|Rz2g+W;Cclrfo?*a#w)C6OyWwzSJg%)F?9!%5#P`oX>o;aS?&lP36^|F z-;H+sUM*tiiN-xL$8XGuy;J;$g=Vvs`tn|^W~bMaT4IF^zcgOz=kLjUGcUgT7V8pUV% zg(nSyiP7LdTxb9b86OyHetYQ{6528N#t7Xf!?EGgsD1+G^3^^=+Cw0uwdSqyf622P z>K;7Q_SWfMNO={s}?jh0=RNi$4lkq6@8TyuAJ|Zb^e+-#B@_|^KFWj3V7zA>-(%B?A9h|oW!ZxNq+hTg?@#Lof1h~>tV7YT z>mh?*nY*3QeT#{6yq5>um%Jm(ee1?|+vNw@ z%SHfH?l9ACc0|%Z?}G#sf9QeE5!RG_p*s|S6Jp&(X{kwO048?=|0>u?s=iE4%V;vR z7wQoDj056#d-@?QEO|_gS#_ZRox;&yy+JT|F9c`15b;q1&eVh-OGWZj#|}ge2Nk^f z=uJ^J3MB%_CXKo}3a4Q>k6dAMe~7d(o^+XYDYr5^ z;ePn$%yJX+eyIFPN>?JbXUUrs!J=htD<1+?dW2Jxc!cORG%hg!9Stst z$ZEy@jM@`_nh2R7!|VPQTuZ9NCQtoaIjOpmAbAz8l6&6;e?QbE%KF#2&D#=zEzl_2 zz`tT+jys$OQGbbC*Zc@9E{@!*4{Qnx`&GfNwS_G88x5~@tn?es>tDv9>Z{GRys=@V zh3c)RNDLevwk^QZ5SEjUH4x(5V&XJho?czedHC#V&==7YN$P-oD#e|ISV*W`b*#2S8Rd}s;!8>KcKlQOGU*4 zG_J$1d#TRQU)jJ}czQ=D(kaCe{?rc6s}jE5)O=!>=fI+nt&~nqt_W~Ix@3yX8`LT+ zeMC&-fB4|ODLr>4YFHcLZa+S5kHvt`o$u0IKLEFpC=ORtUZe1&l&5tdfljFIKcM?~ z!L$mPI;PE?z3xgKD4%P~TZORNU?@E838~l|-?Lre-S@~{BNV*7YK`BWj^QFc;vltu zB~WPSuDd=2=O6^i5S^DlTs8a+!(vbQL5KfLe-qhm{`WQWeUiL;(+R`*<-bD(2MIoU zt?Fa1?(BY>{G_d8|C)CzvR;A6<$)gfmM||LYM6xR*eu*T3-;vIY1sw7+_mDHNy?r^ z`Du&|{ph@Y{r2=oVVW-QKg0pl!|Q%S!C!xn`#1>7n;r#?A_raB9i_c-hsvMd9aj-~ ze{b4TrT)pG_bq&fNoH?zt2pb^ttCQsLeX95fEk;JZ}o2+4IWK?u;<~l9=6}gb$T?n z?wxD0x$u%NK7-=?+7~$q;|V%Z%b>*_{e0hNS4uIlCn@do;dTYTQvQ6oD|<6Jso6N`c>YOt#w)! zwJ1KWA})6K5{r*LNwvk77NO`SALB*P<2Mf}H4q2V> znopG0zd}v4Wk~ROK0zG?+&zKNMTwW6vPo&*^uSs)ldAbS$S)RzK+Vy7yj(goJtj$R zO?lVFyJe?EPg9v~`8v@)XANGL9Nxd2@Ynt!dp0SZ{>&hw=jsI-^x zn0iMAuE&Waln&__r6@qL>qW$5&O)!tAQm5UmskapLSFMIn%01yQrK3tojA>kEdxe}Ahb?yHxBym$U|Vc`!-cS5x%^#R$lZE zwi|F&$5#{ZF}p=WKUq+?a)a-C=H7z$_SPfHN9wha@HTjDf5cBk+YzovYb5JFBEb-! zF^rZxh7Qoe6{=fOW?pC)M0dyhu88k|_1>1-P>sJpti?mfZH#SC4l^kZkki-9Wn#eJ znIo$Fi77(;MIl1lTmWYbpeXgrAW(OZ?(cCEPu=_XSLL6am~Fb@d|aaDHjV&9?1glr z;v4OEZ;AyUfA4_>-aDmTw%l!Lf3L_r;FEi@ih9k1q9-epK6MofGJ_(c^0ilUbBaOz z0yBCP=ZP~|8+>P3c;TCnS~(m?i#h!qT_Zv^Yhny=KfuUV^SUPcD$mRDTKaOoyePq2 zn_3aef%?GanF|K9d8m!4p~ZPC0>REF?U0m0c)P$tfA!ZkL_7E>GUVY8Lc1U*LOQUG z^Rr$ux(aP@Ab`6N5J`AH;}9`}-R559sA0g`LY!E@>6GiW^G@X*{jaD`aar*gh`p3N z+(lOr@rh)rM&ld9N^=#K!ybm1d0eB#%b108U=9RP)8N+vRBSmZ=76TA^TwZVQHYDp zka#5Sf1ExR`IQC*rRezh=%Y@F`2KUgV*C|wTszl4zn-P0b{E}O)T~)qvaZzu1I}t%ocbB3-ED%8 zmrM4hQFd0B#P#yBCQAMP&CywGxe5hQ^n)1Se>Myf+zB?r-JP$0^qcldW2vgMcM>l4 z^WYlcO_AF;2KE`p9taDY=%g;MY-|AX!NS&@gmr<0Gd{#Obku3{P3r_oueF{tj#L_N z1w=5Na2wehlNS=yCW84YqQ#@uEsc>{G#*(8{Zc;dZU68Gl9g&L;`ii!4Q_S4x<{@_ zf0Ttj{6r3cqz!#KUjkMeQ!BHYf2YrT4aro|7uGvPt2*&7)q=&}=QBiXsX(C|@0i3a z>g(0PgZDqa*8o?;7LE22pofAViK=Te_(XReey`NtwddJaOL+4;3pJW&L7&Xtn{BW! zz~oK(WrAI`9CKZ&?~Xpbg@g8|{iNq`f90KP)ow*=7Af^GTfuCvr{G5q^J~DdKrVb}!w(6b@f5Gtur2DCT1?^L!In1_^ zJzNbdX98}p1l}QmbzOmx(+240!3m3~-Ddb--r|Uo*a}5f_=N}jv$Nr}J+eh0aI%x8kRj|Y#l)- z>e;5kR@jOQ%g|zs=2#{LV=6_Xe<9_dYDQ!ZU^?gI!Xx3r(b|wkj9%s__p<#`pYsEh zpaLoMchdX^zLFE3DE6_jmvCx4tR=!P9WeYfziY(>P?6li_&U>|;(3zURI!VP_S?Nx zV0OEdkmYcF17kLVpA6Tu$vBp^0W7()Og^Q{dF003)%R1Ezyn@jMx>$O z0>`yn{c#G-D9ya?7#3lkoBOnEBugugzSoA+ZpE=5(qv8C$jBIYPA^4~r)G8xlVSw} zw{4)VV?Vms?E2x{#=IN4e|$T#HC`^KXL@4caOCK;i~s{b{J$b!3s>&~B?K-o**HP@ zS~7Iotl&L%Oimv;DzDE?GRyp70=~AOwdq6Z5WnwHd{r-cBWwQ(s*E^p7Pu1tdL)8j zTf(e$E<-1=ad{BrD?}S%ty|9J-xBh2`^W#_f6MqizOuf>b#ThT zCotj=vd(+$0h{+EG0m1A(jFPIzuux?D~tDU@dA~5SvYDlB;6a56OjGmf}dZaXk8bx z;Wg=`A^o^%K6!i-a*IT0*VJPpitr2^L(0rU{c)IcUBTKNGno3Ie_!keR#QJ6BMcJ? zjToJ2R~-`{D4wFAeZVe0r@09sC$AbexT_P0py{FNVTYk)6<2y)VDF@yxVQ?J_ZeRyZinK$gC>SnfiU|#F zHcDXXF5irxwrxLX03ERq&951{Tuj{p6*umtx|W9w5C)iUO$eX|Fapd0Ttc?_d9}ysj(9tv4BupS-1@r_<7phQ zt!L`qhn!Y1HF#BB!!k0Jy^+_%3h?^XLq;bOq5)K2AX1PF-u=ki`NOtYSl;4FZ(;Tc=SGT*SqjN2lJ59vpkeRTE(oL zP2{u4KO3>UE}X7sHU`$?m&h37jIQtI1#f#T8{Z*~|Myeq5W4*Yy{MC<9j@hDxc#Pq zpxNQOe+il7z4PMJ19hL%z%kD=9432%3N{1soKis+Ph@R0KqIcdwOwk8DcNmv$&-He zhLS*nTjHL4J2I5t&wWhq=pTWv>Vr|{$sMz7Dw|? zXUlZZKPUl5sX23eMh9_%uRIjJ&1izc{|Sfwf6h${3CC2@gKykhAe(LT4#l8y*97k! zkQ_2qZo^zOHZ~6#Q|$Zt_H$W9{idg8xdFbHtS~t@;V9Oo`CRjhjpC8~13r`>&LJM@ zuzdVn*%8?CFi$y;egasNKjcTb_bVj`C#%qPUSl?`%u~cS`8YgOCR3UH!Is zf5gvvrU1W*@3N(8?mmCps#1T3=P2}!RNSY0MHDM1W<{3WmXsgbi}U9%>FYUd%-Pe;J*noXx(h^Z0h>)#>#a$SK?j$vCG3Ba7_u z<3gnt?fqP|vcZVkR~d|E$3OJO|sdonD;N ztN6kg&>FtU+llog9Td`@;gpE3e`k1xi=z3}kalhu9eXMoV4w9I2?my1ry_gpw&QZ* z#lm%M9g7)Y5h8}IfO{%#R|DBHmmbgm#>Sdrn;pDlF3Ols{HnpeLjtRC^dnm6SWHhR z3-e;2rtevhS(I0%FW>GdDU^dt3jW-k2{LY>zlDVJJc_!v zNbT_G@|2gc-lWp?tkld#f2F_y|8g7efb$%2Y^Fph8R!L_<${|~vZZVp985bqYSW0p z84|v>K{Xy5Y4U+QleAjIB2;ZlGYZMP{deKQ%7TS@3iM<}+^KL+a<~&u%0W85Ja<06 zdh1DhS1&r*M4VBEmKLHBCZgkx);*-9HVl@DM2g61dzJ zzInw$yP0yXWd^%1J_qBe4W?fjv;XKp6B+rfON6FDKUu75f1KQqu27-s_iMLHfWrf6 zk;gT00>@Dp50zymMWZNtEfdSaUHJjM9o&lvisr31Pyr)wdsvN~=Ad=7hr;b8+EFR= z=Lo<+9N~MHPY?f?Qg?eDTvL=BJOgJGL4|u9;1SpQ)r3v9TXh9JdAa9r&B<7!#(tj) zGvTVTm&5mme_}H@$sqvBC4!%e>3m@^lVKy|I~+kL1QTI_ORgj{GG859^W}cSi=gqX z2p7eh4=Mv4H@~M4h5SC_E;sxt96RPa>`+PTV2$Wchdkg5i|%ulnsRbno)6n?fV6Z@ z;K$aUpBvwF52#Z|x%wL7q~pqGNn~sl{`FgLtI+WGe|ah=2)O6q%r+k6D4TI1wHowM zKW@>zHFn*?n|NDtR`uNFmO+3Y%pnRylniW`$MDMbmaQ{oTdL%n+jT_Xd79w$dF}$e zkGTiMRn5Ps9p&&M7)A6=gVx^HFFX3?H`FM2z-d7}y6$!UBm1yCS=o;e4&F0g5q~+` z1^wJYe^jT3X!dmxwE~QGia}PlJL*amVxkPiQ_J=r%5#2?m<)PQLLg?|gPLXqY zyDmF7x^`w?zd5H(@JjFEDZp@`=yc#R*$$8G#X6FE999ifc<1NuMvWwcQ<3p&7qfS< zkK|M;n$XGv+5b!iHETRtCwyR9>=VuJ`_)_@e?(;@>^ z2ZSoft4hQQ+ zw4Xk3my8Rx+r;l3n3P)bl%02O%jMICEBf3-Q-n$xJC7^2@O|9VqjgT@Ylz~6dpLaQA>e|gEA zOHG+36;l6~7vgAJRQO8uQT>#_qWb!N^o4R4c@Gr%+hy~-l|Ax040}&eQ>Qaze5SGS zHLP`w%(GJOA=Btb=yXr8{Z?#|YpTCZ*KsX;T`sW+G^`|=wrm4eLEfkv=#OXKDppcZ z!}iG>i`CSe+wh=XO2OYYK6IExe+6=kbTh9!m~7V_U3oR(`2*!V$_su*;yver$qAZ-*I(zF3te0AUrEy!L?RFW9Es3`ghD=p)uxb@^id}-`|v6 z512_#YexOdKVP8AX+)xUv<)g1u_DhpThy#k;qh@d)nWvxBXa?TITfMlXEd0`?}g( zLa5pDxchRvHQCHsY%$b!t+NF!@+M1Wa`4Mu;7y1YGgBRJualrvf5Rwgcpv*gHHq-A zJ5Aq*Gg3}X3uz8}v*Fhbk2_tU^lynshbGv-d@PF=<8&j8jod8lMxM`k(4At-NJyZz z73e_rBHhK#n_kn!jlUuo`JU`$omQj`RP`%*Rf8f$Mo9FZ#Xk{l49@4X!0@A$O)vKO zP3+$~@h&C#UKk(Uf5g(Z&C9xyUd1o6nNp0(x(u2kP!v5?AeVzmDugt}LYDaV+x@a$ z$&(|?8$1=fFHiZ}Bg7S8=tAv^FSoYUu4a^{_A67v_UAVjqWbtYe+yPZ~ zfbTUcIO8Q;;Dz>INRsV)_PUgYcNOR@X%Y1ZFY{kb>CA=b382}8EG4B^uM z%rp`~pkeF5e|bg3e0?OCVhd|7CtNXtR4nenvkX;yqucfB8yy=_hZy7@DUo*Xr7|A9;$j z7S6NW$Zu+Kx#Kvk!I+y0O5WwIb{X)dPC{5uDApI?YmV&;MQt4B=J@ZXejiC+-4f~d zcyR@8Y=rC^#pVFkJx>3ufTVWx`J$gt^2|9R3_f?zWXk08?`snbzNtCJYCPRNTU)J# z?*&-ie{;i(K92p4=134{bjTr{3nL5GOz+MJ{PwRFEsuW9WLg*Vr}(vjzpj9lh-qq; zuS_i7MpS&VB5%<2$U8beL{np| zx+^rcR@+F@p8uMHW!Nt*i&NT_F&SmR>o|fbk&yUN?67~ks|>z=cX@|PKy3;Pdq8U; zOxe+QQ=Mp-Z%g~Tk1nGK1o9j|v`kI;8k~eWc@B{o(C(22dJpcH!dZK{$UBH`NLx_s ze`ZSpHaZ>Ow{E&dGea%Bv!B7I`Co%+5Xw;Y&Yi}B1s=&}9%g?cWi@IUVw~{qu&I*Gc>px)d-BcSv+; zq4}k}q94k76RyyC(xuzA(nP)rMqJHrcLW!P{8$}C2w+-mEVSX<^QFTF5Krl$-+5ra z^fBLS)q3@2|HioPw9o2H{!+e=2roXMwij z0k?>5Zn*&0^)c<`7WZ4yq%hB>OWK6P<-qDLNgDVS#+f0ODT_7_3tb%{B?vqGOnjad z{%<{+nR!Qkr`HkVL8QALD1t;bqD&pZ8|qQW4!Q*;C|7L;BvpXC;>z&xU?7mbDqD=9 zLg)`vWL#YM$vg=S!a!fpf5jY_8qtM`(A)t5&OTDYb8#`!C2Bq4KcuxT^;5*x-U&3- zm^KZQ7uvF$;z0(ZPl_;9;qR;q>jS9hU{7tWqSlR)dP9LXezK^bp0Y~V~2xjS_M`muWRvJK#cV@=VS!5Abmu263ogfmz zw%bqd2RGV>gtoe&e~VG{r;)n*@gfPkCvC+W33HI7U%tfLCH;)GU}E4u$|~|ZzKUTW z8x4y5?+}F!V#d&}90dhigrtE#L!*L>G$yg4mv6JJum0bNicKacbr4r!(=)rM9dEA>0Y7CI`jh=K-JLwf1HAkrC;W_Jo{$+v)Mw8 zaQA_expxAAchh#2en)Ld5R+HYv8MtY2e3?Z{4rXO*!{$h=_BmfuUEzQk4rKzfj)BH z`q(&aiQMMp#zY6P(b`Kf`B4+@d}o0Ub%a*)?pw6M1Fr4j1Ci;AD_uxs{&&~B)jq}v zRSmW^(B|#Kf1L5XE+uCrGeV;jxHzpqn1lcClaQtM40_bKOdre{oXxr9V4b5XI8k9# zdf3p!OlM7zbi+oevpdKa9Tp1?Uo{s|S(3C^RBME=RX94+_7S1(`t|$o>4uIvqF*HH zi*`xV@4~0D*qr6=)5C?fieGCj8l4nWUH}^BLQ<>}f4WJ_VE-JyB25z+e;fNiy`G(fMuJBT_~0-L-_MC`YrQ!JRN2d zYRWh*lP{^n0>ts@B{&s8f(mJ_#Cu-!89}z#8gw8`PKho8hr*P}+MayAJyLN)Q^g>QVr)dV0On=+weioq{+y~b7<}$d;&=LLK?;L5^ zPv>UT_vZKYb?r&H>w|9fqPXnn$p#-#3$;g46Xa@Qm=R&EJR{ z$!*}ZUNTma;Y)>~B~8wy(X8uc6vamKJ)#!kR%OJ?4H!T@naiKix+F56Tuq3rtbBvU>E_Jf9(|Z4 z826bOL?4Wa{n$nR4&ZGvDx_;)=rmd>py#M~wzo9~NP}nUO!cC4bO=9!uXceD250&X z15}K+3o>z1_lQNtrnjj%MH%h4$>^B>Jb&AX8;xXZeBr1KmHjO*!JA0#m@NGA77`Cy z1%dkGvC7Li{X2SfFA#2vnz*BsxXMXXWjPSSB4L5$PBEZCNoHvgDNE{YQ_WZkJ+YPk zZRz3LZ3F~yANmdL@u;YrFy8H&W5y`y=2O93e<6=n(3XQ4THKH;h+O@OQ35qjSbr2g z#XLZElMw@J;$IhgJ0$kz$k15es?KJTzCX0m6K_nBvf?8@F5tr5CFE_~E+ycpm)ZB- zz~w6U`P8d8D6e2a!|IVg4g=vtB9vB@FAlZ>&PlV4+C=mKHr|?8v5bXhDa7fP)Qt9R z$aUaM*8$jiHfw;vC15ok(hFmC{(lG@;LTsgpp~j5ngx49&>6GL#54CwM!$X0uZhM8 z)F}9DAYDzE(jD}pG3q|S_d!JcWGU@^MB2bgrR}i$aRZ*{%$=Q|8*hI?bnz{n5%(Fd zup8#$#`ocN+T8Ufxh=;KC{h5perZb$lHhIMClw7jy}B>!d>2jd;>U7Gw11t=NI+n| z3C#@5384xM3M1-AH6!>VW#oy769%#``|~Jr=veV2WRCI-Zj0dqBnR&2+m+)wbGL2qHkuk+qyDR;XU(_JdRfyn06SZhPo#}xTB zQ}CBO-uVe+E(ri@AU17 zLiiHP^eElBd!_GwJO*N)RZPSMn+B)XBnX~FTVWIaNC}3?rz2w3Z`+LzX&PmJsK|2C zjy{Y{>g?qhgxfo)P#lTbRrR;C1r>!HoE*fY#xaBf%yyTww5=@AXMaWpT5__$i@Q$4 zNIZQ?zo#MAQOgf&Y_I*wTE^qJB~z|G$P1p`iIKa6V$7su8Z-r_=8%GMlxBvrFCw^n zA#L_^t5ri;-zBt7VEL(C>Qm(SiWr$R+?U1y;!fj}cxj90St$U0ZbbdQR6?jx#{-~8 zL}%E)lRIOq?rt84Q-4mmeP?C;R=J?OzUj1oUDS?AKRiF*y@PzRh-&F${M_)UC?3oL z2s7gQv0YXZ*5P&3??AlzIP41EiSOscJKF?LhNiNNBwZtwmZq+`8YMB;vE5`TsgN!WkXF`)dBGmkS( zh=S>lWf9=d-1Ad33}@YQVss}u@&S9cto!p6{*IZaG0PeZ`a00FTo{Lh5OoAca+7E9$F{eev!9jG1kcH3WnD% z-GafY3nPBsJ%3LT2K50`LSPqL)#4g?YS|Q!xwLj`NOqL!C(0#IydmVp$KGBMs?A(w7 zqth&C#-6^?32x*pKV39lt2vb>B4+6zofrbp#((^|L>qM~TfZMI$`6@+B;U-K zaC)X*2oF?KCecMIuJ1M4%m<)o08z@HsL@{wc-rS+=kd^}YDyRa2uu6kK1UmU3uN4W z!kG3mntlyrWvE-Pzk}j+zF`yhTU`TX(ZtFJVU^=(6V|dCZ9h2Oe}=tC$SE64_wCbw zVWux2%74y*!|ySduQrCeg*6HJMMd##ka7WR$>DS!L^j1ILU6&l)V7*W?tD=X2}-MA z4WT{*vhxmi)g&o;+|ZOH6QuWVpKA)IA9&uMDG``??qO7R7{#=XTrw=k)3aEusIjRB&78mgj!c8= zM&ERgo+)VirZsQljl*#5Il>z{UMQZk%AVU0%b6MR)+rz*wAr}FcQaz6L>p85^`T=0H3O0H@RKElu6RUfc*5A-q<1}lAFsD|B6JZ16Wc;C6 zoF7k0yBll1z>&|$k6PMnuQ){J{D>$9Qh&$@p9P)Z1qxF+y0~N`THvLOi9qa}X_jlg zRajf9rhP&X6bt|88+f*+f!utg9g^81eJGfArq5K27Srmh?oN5_e>ZK1h5u9EdDPjx zymx6YGIlu$krv%EnVdhYMRvbisnY6krG58u1LHN>-yl4CNKIFIdQ@Zozy*!tpMOIF zch)q?(0&_+rs6K`0*3T=)2!W2dE=J?S>Kd{Jr;7NS9C1a?TkxQIbd1$NR`&x8QkB;rSR6?=uYuCuk~+jV+0sUFT>RJ8Z^q}!ox8c@ z(&oyAHq->1_`}!&&C90ioltI##eXz-@!A8^^vch@$B@>bvSKAG>bMfo>38xGe#1}3 zI4ZjMaIOa9XX){jtKB}<7bGsKbSPqeQR+wTPQp50O!@(+x~%!niGFUliYQsOUgExr zFu1#*f0c1_nnWpp#b`9P{tOuxlewOLo4M3y}Rh=uRzs~7_8qowk0BK zB`R#zHRT#}BdpY__$KDLd4E!)v07xtmow#@&wz2vP$3gBby}4{(<}v3Dq;t~6M8L{fiCR@FUs30Lfh&#v?b(P^=-4HB$`eia)t0QB&gAP-VgwLvbfv# zqM45Dd4rW@njvgJm$$;limCTBk+ajdmvr7@5mI{FErV9jE?lL!kBn#H0F z!UOb%8R%5MRg`Si=fd|r3mNGN=S{NAP5_^Hu@cIwQr6 zH!|RRl}NN@*iSz$?{d}7ybOb*0Dy1)_Nyn+@jNjhq~Et`ov^y1Lk`Bd!Jf9c5VfR~ zdHsIMobB5pRDX`&&P6yn;m~qO+{e9sP2cbmMde%Tdg^H$_42q8eBZnMv|8#zo|Ek_ zQuPMm`-FjS{*ghBQu!)@a0y@XcI&Q-SE6mkARzkJ8fk3kPIJF70UELNx(7cWZfBs4Ffj(=)edlg|>_37m%neESz-xy6~ zt50+81drkB=y6i!8)LTF&W#^fMrXceBT~dsOpE@$dkf6L9r)z|zIh(BgQ(N-f$b-i zU3=dZGZTLbjYfaYP6iTE^!O~w!mjgIH`83=v`xgN>>~ETQQ#q{QaOXMYux}`=TNtF z?4Flez<<2R#}VtPE?E^o;@CbM0}mE;LDRt3U31Vpa!esTJ~rp;HGLlv4P`5Z=O)qL zc5dE@TDPG2_}iBwPcFd82x7kc+!WR1;D{(9D1tnBc04bdD4{{MAm_tP#hLNXm0_fW zG%8E5UT^Qt4lS3!2C!QZ9byLrn~!~T_SSg+G=H~C%O`2^%}F3_ib@v!d$iP&?;}F+ ziES5ZQBDh{P;DjC#Z9aFh3Jgh3q#H_DqsuqD!DM<{6{+Saj`78yE6&SxcD_;hK6Mp zYfWqfQp1FJ^c+c@j4pozspp}dVl~4ap-oAAgZ?{cLW7)P9Y_#a5MZGT#F&diKWp+d zrhmp}zaG#|wO43Lx7X2mI4%A#qH}(zX`xgQK=qAJm$W1iCy2GQJj)haLfZVXj~Md2 z^-%3#edM&DOsF?1bNF1tdom}!VYzq|r-rGLu#yaMSItwH(+0^HG!~%2HgqGgR06}KT8y* z*`fIfN&h|kfQvtfn-`MZMeR4%qv@Q+2@SH(dkDdplwUG~A*EyT09;Vak5J@PY<~;N zFOl~n-89sM*;7rk&GKx`r!yebncX)c4u6b5@Hw_8$~ae02;j3(rqa^bZ>WnI!RhEV zRP2TC5uwN->@CsVtSQkskko5PB>-pP}ga(@js2f(;>>&Bj_LRNjg9 zt#GD9bEIm`9X~i5!pqD@GAGjw(|^Qpl!{EVfD=GFgJw78nBHmUM_>DT{9M{!eqn6? zsLMs+1tW6lDU+?UQB7b?>(1lSwI|`)3;f(zc|r?T~_CaLku_Hw9G=2FOaYn}4-~6$@Pz zz2QA?iNKTzqt70U-=(9nRt!$H8!sGo^dFjSHwP_jPWKrU?m+xr@(CFD9U%bw8}%5= z=`)c$phcXrc8N^|dwg*%=wM~wp=J;Q#~c>qgD@d_B#;lrrqU2^DfK8y(5M7R;egkr z44s)!agr7NgJCpC-g=qYw10@~FD00}?dHonu{HPtayGPY*lah)Z5R#1H%){ZTX}nA z(b~YIs_XAjEoC1Yy!|&J3%a} z5K~n$u2WrS7Z?s;Vb92uBivDyt4Y5Kv5e7g=5tCECRp z8sm6a4`;;saLkLEa(|k+#Fy~09f!I@^2+XT=G#Si&Py?pDWW0wGgcZZL>o6+Foo@glq1MHvwac{ApOZ-tU;@IUGz2c&8suQMh;) zL^NEJqzTV1+v`2 zK}R|dsm+M*Z%v_(cg6Vrl_=S-(Qgd9xf9t-6%73$HLZ`3lnYxATg$S{igv}Mn$=Pz5!gT)6P*TWO=ArysC|>4 zPxxqDFWso{tp_GY&<1Jo?|8wZ^B|vv#o4l_-7DVt6TUz^s*Uc(XG-@P(**K&9}nE& z2Nb?q^`)4Qnr=b;e_w+ofwpwh`E_qsHA9@4DEr&}-A@1$Oe>=s zHwiAyw>V0w1L~fmlO>O9dl>Mo{I&tq(4v9I8%c;KA3Khzo{LjRT1lK(l>a>u^Or&6 zYImdOJM_!05pJ?r-iD}4yU^`W`8}iEUqAj#@_+BdD*ea%e+_6%H0DO?fodo~O6J`z z$}hwg2Ta?_?I;iK_|;DT-P8b^w|>$5B7bE{cto#qh2tr}9rquzn0GKlK@ghFA^U44`+8!lb8QM{U=wZia zdw*<>;xF*;k@Pxa0=7ekiBvR-dHqNVuQxZUC3s@sk8bdB{5*;Bk;|QGPZ>2AI8%{? z*x+5h6}~uOb+0l+b=(=IaI|=B$ElY~wM_=7#sxt{Q3eS-ZuG$4mkZZ<^XgB^QG-KH z_W)V;CeFt(Nnm1H_)~E#g`$jMz=Slv za8m+?S>e!!Voma)fR`SP-h3cOeIdsWLgqN{jl(Bi0KZ3_PedY>YJ92~MJ{0mJ__v=<@+K?8GgSbPh_sh zZt+RvP(Kz``B0i@focl>upXtSK6t6o2S@u!*F$D|0y?jTu zr}oX_&dlsoUtT8O%-GjJ@8i!0mw6~<$ROMH`G>}Iqi)l;>*`y;0)ONugL}dee~*F} z-;fE%2tCqiSoA_;i?uZQ^f14;BUPAXo}*!59IJeBv2VogEL3o4g028PIWkTY`?o3USHF4jPF!AeQI<=7C6!ReZ*{=WGM^?zTB!kK@9<5L z>9aAh@C({6Bakuk>wo=V#I{dX!XU#Lbc;(r#GZ~{cy2O8e9rmGm-u6XsG4O>l=+=T zq!&qU+R{YZF+xVRkOAZ*`$!9Aiz8}?SDe35UBr`kAwO|HuslUT!)11?tBD}xy++Gz z+4}L#_bNohrxu2n4QW#3=mNbhc{a%Y!!F7{j?QAqaTtoCAAjUU%&<(%%(yc%v%h}a zv+GJ#C$aVP?m4bVB8^r~FlK22B5Y>=ik=jkpFl;M;K*x?l-rSQ5|2z+(REs!z*L>DL@v zu_vq<=*rgbMfk>fEsNyJ9Oc7K_btivKx(X$$4eaYy^PmG3HL1obKGS&#CX3t#HPyW zZ);6N+;b^t%?qX17En~uo6$DACc*+m95w?pHImm6Vj}y6J;)IY0kgpFS!PTPE|oGv z)}3CJaVNFtc4`tv~$y$8%b z{zytnSk$v_p|tht&_nE9)e#=t^73s>D&F*)CrUvH`27aH=no{#_8u)q$Rw43}TW-JHd||^q9lHiuyaJNWVcBkn$}inT6O5+O?7|A--3;yiK)g54oum40ohw zm07WS^onFiK<59L+;bjbQgVlYxvXVnpJ^iui+3 z1StLj%L8<4SxkePy{@d={e0lp(tkXf53*^ub{ZJmtcvyqIA!_VF#)Xv^0k}&bhg7z z!hFzEdJOA*h!U%u$phN_E%l;S$ta}U0twiM;OFo0rGma%bP7@~$+r`9r1OR`6*eWE z>{2RU#V4G`>XDJEEXWe$4$ifA`t@pZ4i@0Har17d`TyM7rd{^3^hRAMCj$a5yNSqdl?QZ_YN_xji8fA!0 zR*7k?f>h+7HIDPp$m8=2F8zW_PH_)G05-i6-V;qnR=SO*HxBOFq=sL{e7uy7ALU z87l$sb%!K$tmPBl7A*caQXnTl(fodw60e@acP7}+G(pdN$*u-zxGHHY=wZV#g-`j5 z!|z@((yZ21qQoi7$Q?F+XWF|xrLfzD3an)-b+io;$k%UXK!3j~#Xdx8bQd}Irqr~2 zAimLV3V+Wk;`Kownl$GA%a^c;yHF`rE{``s-W4SWQ8`&f#SzH)gP^}7BE&be5Ktu1 za76Ce*$0ZwLlA>2*V2k+cC!oUXbl(H4}9zh+fC$T0D&Z!UtR^7Ge;sQ&67OX{?0<- zir&g7A^OfK;(uKY;(T$E-NJR_b+ZIGcvVQ0oiEVqyD1S-;-ThxQ`gynL5T4 zE8#NNnie~TsgM`kLKOT_k8Yw5hmbRZLQ?}ZV1VSxY=4ipA})^4aTeQ1;^FCI@T%y-XzQFL<{Y(7EZD_3;?3fTd^I1x{QBU+E(t&^^ zSZ^X4R+Iuo;nDK|te=%h8?Q8}XTdbU%wyT^?5=kHq?m&5(L?(8 zh(OYa&*clMPfevrg=&o6kKkmaQ;ANB`>}AsQ>x*mfFfw<@ssF`(lYhf0SJ3(7ju|J zjc2~Ss68%?O_Mu0szfQF5PMo2Cm_KA3S)d_X@3+;qsJ5|H(Ayt?#3J8+F0`|CO9h? zWIjr_lCkd!eSZxNHU~k!NC(*?*I!qqr$V26MR4xUT#Kn6dcKGRe1i2CBM)-8;KKj{S$B%cXq#hTGE$UBV zw|_?!boE<$W~RJsz3=R3btn1dzDJ-$TXNN)0wY zF+QHKgcTkQS*%b=oJb0lX?7~zEz1p-d~r~qh5NpzLuXIf@V+1dc7C9IF(~QGKV2Ff zXdFI+abfI10i+LX+4>5g+b()oHZ>W0CW`&PIc80C@ z9qDTFT*;UnyC-kqW^acfrEd>Z+a9cHf(#)8ZE;fMzb)p;nXBS^o0VT&zy!D9IDg|~ zDXOj*!uSF&U*b&|(mE9l2AfFMOo~{jxrDkdNsh9GbVlBIsxMN$o=ws+!GyKT=%oZ3 ztf4!T5E63~pj&<3nfa>?te;XeT)l*K-~)kQ0l?47oBp4Ic{3L%AP5hLCRP% z=a<%Duna17{n2D4^<7#E;^>Z6Be)O*@~(&3me@v%tey~H34uxClY&2Xgs!an((B(L zwAN8~N4f!dqbkY|2oKn%OYMd%BRSObk9Kq(tp+&^3B;k zV@)XxoRk@)(Bquhe$qp|J_mgmqCmoO=T7hafA!egD%Z33OU8D`H^g@s`2IFim1~^& zYt8EqbBUHa*6u-lR*|7N&#UBaues&%Y?hkTA~ik{_C1j^3mH?sXVd9k5<(Mg8q~H% zGG+b^gy*&=2F!#w?ScWJ=zoLgKVdd6Ef`XN%X@cxkAVl*0z>gUummY=yCj0@fk;c* ztHG5R1kUGyh+V9-i_pMz>70>~K+K$A2!cDH9)h7by>*=4Gk?^5IvAzP1^Tvdn_T3AxSfY`bZFRM{W^6$wQxD9^X6;HAi9TW{1;(y@k>9cY@s~ zcaC;KV}@=7M&X9oj}T@-DMq0>vw&^EVAtU18VlfE(_&V@gBI@QI9h?MlTp|QhUz>8 zi8NxPq}@T`>wo89^Xh!*--i>EsfBQMZ{2ZhHg>40(W6tJ;j)!i;_954NWF!@AO~Rx zBY)LX%@}PTUEi}!2w-AM0e_3Ciy+)mt-Ir86S7Z?NG`>CyY)bj{CFIDa`2&$^52u)!1bw^HEG$on0* z)zT+a-PZzmXfpb<0x+y8yCl4gu_*WNc}+?8$*L~hPmbv;-R%)FsJdVae+64os4k}b z!Z}RwF_uzaM5pQO?J^0+xAutqh&JAgDNcs^EWgPpF~#pq)C(N&zq9)A;x~Eu+fC5P zGovqM7k^Ef0?rrX3q{ofts;S$L*RrKh`*+eEjaeefoRop65cyf#p;v31Yk%0j%7be=f6t6dM+2(EV^}&2?kDM5 z6DNrx1m+k%Yrtw_Ojo5h9MnEAmA_9N;%aMEx?TIBpsxNNI!QS70mDi^T4 zW`8kCA4sU}S)Cg|sqD|pvv`AaX@L(|c8}|a%R<3@K&5nvhMjDDv{BS|k+N(t<|aFn z&z&|OfFJ*u1YKu4nDxC6$0d-ir)S6nP(fZwjU`>Ys?_oB99PWVmGe|cy%`HiE+NjH z67o7Zs>e9qVv@>=f80+{;g=JpT-STLB!BlyJa@}VQh9#DFPvZpw`_>@N{Sby+B zpcW6oqq$W;W^kW36ZXK{Px~zHvO8%22|)J0>dfY*%n3|O9cFLR)S5XOMOh*(AmVCH zVa5X!<7@09Y~p>ja&wG(?Gh=!D{yJD}KWj=qs(wV3ScXP1jC#Mixz-$E@H zahoHnj*=KrhA4*^dQ`*&2wd@#vBG#wyDXkTUShC)zj9?mqT%+WuPHs!^*_9STOZ3h z>(Sv_8v%LRNBC01LM)PXoO8aPxOVJ}zJx4H63fTmUNRm!nfl2p)Q|VN%zrl$#QBj) zkICJ`esQVkQEg*MW4v|$Gw5rk?aB>(CWXplfmD=-HD6}`+&DEHUp*V?r_N9$h=PX{ z<0K%)Um9AeITHvlGyxb9LqC*;l3*{lzpaKFp<8WJLkt7$j$AqCg=%tK65$^3S?IH} zCQ?nhxs>g+4iVuk?sh~MkbepVyXn7gB7QJ^DOoOV$_q3RwbQHc3)5-gV{$M4^loAgneM5(QWIE42>V^W_t%Mb2vwt0jR)P=Hq^{;!36$?8?(8!EYMDZ3QO9Djn_C&@+Rxewk;{|-Q6B?kkDB$*S@9Cp^H9Nze*x4Xvt~`^ERqk897b`TLEkdAcIa`=_ag zWyyX^=@m8>@U*U4?p|8y*18)$6MO4+83?Bt^lUvMthQxt`d~$*x zERIx>J%w%u#!3Rk7qutY-d5xxz+az!=>AnwNdY?1zJIl%r^5dEF$Og4c`)Sp49NNX z_e(kj-rw)_@Ly{(^yS$kBWtIfSx)#gS8&a^zpvMly0PTU=5(i}|iz^z~T} ziU{)>a}3faYQ33|5rOct>`rmGxvci$z#KxazE4PK%j;YPJS8WsF|$!aEo<4t>6o4t zIc)~VNPn$Wlv`a{N{d=TvZ9({P`0 zLe3vM-YFN%Q%(s3R+aeY4xzpLVFLZ;Fql+nz8xec*qNGs7N9R2&1MbIxeKH?36|TL z23fZmJFMnMYe1ZtO;`1K`^~vuzx$5A>t8q&gGb2<4oed&NlT~56vbiXhK0S@>eb38 z_kZeJvg#5B*+L3Z7&H#b7968q^7Sgd^<^w-Le$T-dY9;#S?JDkD=6CSJVu~sc1K&7 zJ~j7t^=Osxd_zKEBhjm)C+$mUeO}`_VQSEvS&}t6^T!>JtE z7f#A>aF+08u}-BGyh@3c7#PG6^rNv*pMU-)uKIVd0pfU7YTuR?!h4<(?wzS7`H(?? z{dzo7yGPBZ*b$}o1?3h8x6!?grk1ua&d|I)05zKJkKmGU{X8Kn# zn_}!m?KM{x!J(Xz;n!WC>c(^{)s3m?OQW>1+B|>r*Ao^^3QY^WQP}P@^bZBiS5h$fQQ~jy zLntvNSIU*9=Iu*;D$=v)bRc=(Jb#MuKEgoc>VitY0mEKAR?>_bB{Ms4ASy1);t;eC z9GSa!rwi*)sxUz<$d+?L*Sc3e{g6kzJXGtT1024=vys^;A%uN=GvSmNdO5w!4B;>V z2LbbUc2A9A+pB059x{cs4rav<&Rzsj{xVz>-*69Pl$cOWGjrjc67pnt9ld?U?8 z$NXx8P!a8kKbNzl}B?(pKMFTesXjPz?+fjAk9lB|(4Z7Ti;2a9yTMzuAOI z4=EP#z?h&PKR)u7TcWqj?0;c_3{QGx>#-Xw^sdMWUXgzDq%mSHBRaR$otz=3BE1-2 zo?Y-Kl*>XK$Olc=9u{6x7{(nZAW&@Jt0RBYX zqRLkDhkQ^0!I3y50-A9BqpUTmM}lK&bvv?W0gWzap0;Z|oiWZsL|Q3;gVY3)G{R0=of|TmYG`@E6>~buNGh$wl#rDT zEA;5xIVK5i4IBi_6gx&CEaTfCjsTQ)c z%)#wGv3*K{UE29FXTVH&p%EmIpD^efB$)Q#>N~kTlzR~%9up|hF_P=9=Sd$Q$w-qV z$cb`e>q`p!LFaLy)6sK%eD7t{{+`_GGl>|#W?jTTmMUI8!*`_#zojz5TCZRnVxg-R zDuYH$*55`HHGkA)ou#JWAmZhH^AP8*m+#%>%8!IqCZngdb~cgrHW4ax4-D6i92Z>` z^F*rN#x3*_p2Cn?oj3K-we0w<-bbS$&!t`Dp1^Hj+xW~f%^a|pOy;j8&TEipisNtj zAQdeX!DTTy%O0Q#=*P}9)lba6W&AC_afO5L40Cq`Xn#4dL^~j2>r5OE2dO>r6KNdZ zrduHI)C5FnbW1@0Ih-jgBu(}z;w5ziz&*wEX$@mHijYzPOza9qF1OLHZBkRKeY)_F zPQDhBP8!6_8*!F|j;No$ErC%jd-sU5eE3JOG_nPly&Wp{b8GMPgFf;a`2e0Oaur}vHpE^kMow#!$h<_HVatKKbDs zjbgZN%BMBLSir5LJ^V@FRiaF(Hefju7Q3|IfYm+F&Rt~)meC?H)qZedHgtGnD`Byb~*WEBi=!&R(Zi<56KwG{cP zNVdX(W2}f@fR~{L3gi7`ol|1qU=J~o$0OfMnRfL z-|v_Her?zKdF%>*Y;rg;OWzIPRebG>Pk_Rh)BLKgCW{4;VCrZ5kzCrcutI9=o4*&> zC=pTv)YBnOT(CC&t+IG3VI~UtzyXRE$>01Q!oNP?L##A3n>#K+8`EH|wtr;~l{$?Z z-mYcB@OS>Eml(fOn&H4I1ikrH#-#Zz7%!2*P(J)@fju3wcJ^jf)V|SOcoHQOGME7O zL_z$C#N5~}<>1_^8yav^pgBI^H17_ z7wGK~ws|&ASP0!tzBXhB-#sJEjn0L5E#@m0r>;Y#a8@rK{`)c*cY(|=m(r_<*d(i~ zUcjQ(wv|}rFPaI?Cf_rP@WoRn0VnLbwhYYv zrp$x)(xI$Y_Q})P=6~uVTGE+diB~??eQ%c@yI>sbf#o7VC(|hPy-wTKvt$994-Vr6 z;7|)>zoS&W)GnGK9u8(8=#qN~jacSVwzyMux&*p6E380~!(}<1cPacAsqOdOqq^#6RWz{werjs!nCtJ;4O4g!ZoM&JGcAs7fFz^d@d?I zn9ebc@FunHFN`Gp^!VH#wGZkr9B~>_Sxi=G@kG`vr_`viUjbNQ+T(D z_4y;}(lC%P62JL`FK%yHqY)gL1?#pcgM?e*u_jN#fq%%mr7Av($45kfxCO8VY3w+UEIWl%&g3P+RhI zhtP_AGk=gc-;Dc#`fs++v8sExL%1cN*w?%alH<;=TG{?paFfBXg@9i)r*?*mzd}q# zzosH5?QhX-pl6fL4=&N(>c%My#0_XUlz9IJcR*w}t{TrA(KgSgi5#YZ?1SJgbL&z# z-VeZ)#{Y74A^^>_Ka(jP%^Dru+`r%TtGnW-r+?M`C$xYP8b-(Rc6oauDM14u`Og<) zq#?qbv;~L+;wq3ToS2e6a*VmcP5_QD#Facy`$R)NjVm8U9v!MDHao&^Rn!2CbpqQ) zRDO<`4sNhS!qjAvWyk}3T=7gBOuUDW0LsaG${PK?lO+>yLJWk!o5Yv|lY6|DGA&>l zq<?V$uRW`-1QBH``E zP#QH_IbFy$DY=_IKE?UOw))KV*b{|#b|{(zZ{>sfxglh4PSkHq_pQ4RAAiZf}ppb>lhmz{%ofFJMI7KXYB zl@kcQIZ{Slg-NT4WM?K2vNNQfs)q|Q!@*>Zcm$A6)DZCQVl&Edg2Ilk5F(#}GAx+|kER|8<9wK#No zFd0TC(Cdhxzh1UQ zf6u?(C_U?uTRvr_`8GFuY=M_OY$jQ&-hU*BAu6fI6O0cT zvq7P}&f^j5cf^`1Iuh07&nDINRn%@C7Ird$E)n*+uDu~ojqL5=39O%-{y0B|r!OR6 z)bNZ!w4z?Jvwp{%{IQ~O<9+p)DaI2y_uk%nJY2_`1iv1UgyMS9=BFD`VPB4*r3id3 z$%GgrVIU5?$Ks03li>{a{GjlRl2IHE zd9VOHL25F=PFW~$tRGJ42om~azc-5w*zMOs5TUQqzQxaZj(@g(De%7y?0%(bxr*GE zr+P+_(c-ccGT(|$H|zH0cmALyyg5zx+ZyARU$Eq@^JUcOOx_+d;uELF^2n}@6ba77 zya4`KspgOcIUoQvK+3FZQDFiN3XoFy z;?3gv>l8>Yv8y2az=?m7aiUj8#|b<4I%VIP{d&~oJX1bGTckJLnBrkI^EuAbKwOIS;KwB#~7K>%uo&h#Fe zDnrCg!{D##$B|x1JtPT@wWo;pk4YGb6_r2%d|^z%8uNcZLLjA$fjHL{ZkYuVL{e3i zx^+vxRWP*R)heeV@hI`v010_{`O1bsHh#X0BSg2bP{E5wc~d($_}lP7l1ICE_OPmr z`!}^opJIZB92Q1-Y(RZDr+t0A`;_`lBlcAk8Vz`@cfP>~z~%Mbg$s&&z|3sqFpeFD z;r!q%%IJSIK!%>wTR!}U=W-FW@{+^{KgT&G|9bZ)0YCD%f>sWHJ zsHf$_#!smN2eLuT3cHT*8E)>KY?^e_1AjWVgh zLQchv+B=oVbHIG(zF6p?BqmwJjJAAb>4=&sKM@ALm@D(*ltARoVL2DFbcdTn|b)u{D&dz?ilc}GyL9KYLeU^V13=L;1G8-iBpP_gc^HqhcWl9UzIB;M2A16l=H$)?< zvdZVyHLE!6dFI`yyQp9Hw=7od<41qPB2Gj)yZS|vF$3JImX8|IBwpEGH8u9O|d4dL7U^&0PycKQVNil!MGbtL= zF$%C`@5MzY{#2mnQi0+a2~X6FDPw=` z=Qsq6XW_6m)KC-ilN_2?9!LigRPkm(rY;L1y&g@ZeQrW>ySIIDf=GX&ZD>p`?(?_< zFkL?nJ9h=EjUHWwJ;0Pu(CxQ1B-uD^Atlnju7Abn{`pYO;{H^NSf9__JzJUH=Wzq1 z@p8$&nDz$4B^Hcx)CIc34x=r=&(a>Vs3e^%bF@>Wp(JNm?v5Gdlq`<>W@zuALfYhD zcprlwNc$k92qgn`Ar*g%wmsi2Y^4Tnj=nK>Z~N-;{x@!I4st2z1h>PrfK#z3D{hw0 zvT7VdI(0rE{hO5FNsEQ=5?IoJ>GARQNqzk9r>nuYFxWT~l{%uc1|D;nUAa=X;wiO@ zAEr_AHhA_Hoky6I^IhfLwDkuOP!S6blUPhxHBEQS9cvX@Q`Uc_$p~UXDr7j)w4&-y zuQN+E3@j#w><0j|%%ry94U_Pl?az_@UeOajoz5mF`J+C4Ion^Tnb0vJrkjbE@+QR; z`<@3H=XR9?KmMiX9W2iz1vE+Pcgz(bRi54;AoIJVMK25f`T>nt(`BS%7v|32Ii{C0 zL}Hn;3~J`36kvZPgd5=*N$BwR%lNFD`=U$req=b=zYWNov@FW_F%OoRT51Qam&Ib- zyf)u)rv2w_$Sg)Ze2fnI^vIt;EsDN&BPnPk@rn&G?T=HUgS%FTf#7q-F&HS(*Q|S+4yUAfiBjL_P@;&)~<+ zriIY72ZfP4f)cALLz6_V6Z;?fSW#cbxQgON$bKpA7lmOWAtL_H&;|>cM z{3F(=O~gASSda99nccS0uTi^dxmwI?IU>DQ0y2O104KXs+>Wue+~RB&Y$?73qSJaq ziNljcJ>5vfP}aNum0I0yh}AC!8y(cLTIO_~J}wDN#M5Nqy_;_(;KBCD#u9PI2o1pr zb}@uQ1%e)7F-(z2ZLj;Rte`Aw^7#zj5LLx0Y{v{|-pde4I(}p{mqd&{I>`j>$#}#p z;?jR9P;5$?hRC`^TzBSQ<7b3V-InqFI;aUYYJ54Gu3iI)s*Tmz zdAHgU?%v_jPAO;6wS6Gkyq?!XngS_3$fs90f<%5nm>>36cR4lFR5A%IIS#(;l$ppO6LnSs6zgusj!O`c>b?_lWxW;V#h!dkT}HaYM03k0!Of+wE%M5}~_p6F2<<+V{i+pH47!T++L8QhKyFdQtFSx>ur+zEg6z<9z2N;;TT%1J=tYAEQub*Gn#M zg_p!`mmPH&0t&x9N9er!=lm&@HPfmnFc9v$zD%~YjPPx&%8E&RUE-$`4a-$#qX zI5n*v#B)gCF10`B{dSa2$*Z$@k*F>1QY6~xE>=fMhs1)`8V%X<_xWH}Q$>G)=*AI; z465E4x^O1jqY>p+z?AP7#zGJhrquwAW$izX&SSY%APS-%#Dbib1c{t8JF>_*e*MF5 zW0$L3(lB#xcOPjOfMS0P9DvS5saL6{&5|n-1qwTlQ0Te`qE79&M>m592%Xi#MHil9 zJm4acXLGkK?EC$jK)~=i9bbQ!u+Gz#{%6D=Dz`b=E+t@EW5RQY)GuPBOiKDUtwzwS z7j6Z9y)Os$nXw?_5MGoq9baArtp6TEbM`XuHb{x(lSJBBwBri4v=|ogmbFgv_ve~D zL?gyRImgckm3M5PM}AiS^o%>_uVre7I%7+5#!2CYDgjT7prY~TBUFFuANY?SNNw!9 z6XmB76E+rXHa~o3W_+_b(jST=V#|aed2K5ZTJ~_WGqrI_gQmRh-y)_qt}Q+_Rtu&9 z@Iyi8qiz`4h0*nuTsU}$n!y8CTyx=pzTGQxlL>rZKjJyu!z-!3J6GBaO76&7FM#af z_yZJoAF==zM%b&BI-*;lP zCfxQeBa++t>7q?dQ|sQ5srxN7Gox#&E>{-K0p9aaHkprReY=Tztq}b5Fm~}x^2Rd; zhhKnnb1Mq7eWHKOd#H9%Sv!7%jLx~Falo{buTTKG(7gq1Tw<|f1yHS7OP-eWV_d~5 zoK>H?svZ(Aeze?k&k;%8-}Qk^g?Hi=zP+92ACZLAoK&Od8_gB6=D$HsQet1TW7X_QzvoO2bp>)&x)X z)jpstrlNn!CsSv846O9LFLaT~?Rk291{s)|1GaL6wBk5W~D{B!Q{ zbi(O%Yr%iPClLL%kSKjSz_1R+G2TJ56^F{q^(y3J%FJW9q(1;#XW988J+LGg%PD%e z0(fcSS{SSU{Ln~|A+h#zO0zA~ZQV$6I@@a7+|?(1ml_&~FasdYD^$?^5-tW=y7nDq zKPb!=;N9Glhi|K7a8B4Gv%HjZ#7^k(Bu~f#$ozj$^bu;n8OT~|W-y|GPk4_KiMWG+ z5o;8G!Bx8*v6_V6xUu1-tb>7nUmFX{#|3VDMvd16e_Dx{poNmzy1E5lW1mnuud1ih z%qil%;J{3y+F`f!e55`+EqQZaOi&<#x0VpoaiKT0U=~Zc&jN=HbR14ns_5Sno`r?? zaY%o>86+7vQC>e?w1~OLeCRLS@=mT=uDjn~mZd&}g&K}9z3a`Dxu9OXc{J znsD1Rj{Fj>HYl4}$9y>yY~td~_xeyDP9oH}?X}#0WG&OxiVcn-0)~SO&`*{+Hm(;V zty1e3{uu-6DzZCmF~xy=t}CzCwF$K>Oiv-S0w= z3ES$&Jt5}g_Wn&mShj2VM{K#d<55_guq1X(52}40w|)W+IZ>GQBW6q*=Fzw%a=1xu zWJ{a3k>m3%cn_lC+TYuml-#ldZ z#KMP=uMg-P+pMa!k6HX)*YkhVblg0|;w#`-DD8mTa#v`;mSj1b#aRxBf9< z4MWyIII;rgZXxA=D7$0KQe)r`i_{83RG&LWe-F8o)-5D~!W}gaz2DBwc^7)(z?Ui) z?Y2rhb$C*(zv##v1I8F5kN5G9Obdo9bRewxoFtYQMO$+kZiwdxBW!=A=l)U0d$HKs zJk;n7W%#`0??BomP=vd3%WS$iiZvAuU62c2AKTX&G7krEp!8D1bU7=8*#`Cx_ zl!l(=66bb|_4n|s-T1YAgZ8e6!wG)`!}kODPPW#(#b81X^JL40pXaq=H{xfvv?Zai zan^TWS)ybw`IO)`8VP^X1r0I$1mB>>Mr!p^nUN4V9i+P{)g}*`%xel+gz-kQK5VCS2)_}M8jybkx4;x;Y2-+zSrYCEc2kM-yMwpxH-j4Z~#emyCZd+8c#nLdLQ144;Xk2(`@v}rlY4BfuhTkOjj z$sH{zco33m5&^&6IwKxE7@!W2!V4XYub32fG`i5c%twC+`_X+Mhhk7!@q5a;+BJ2D zHRRgl3Gp6=t!$nT=HG-`M`C^6lh*F1^jSHxl9?i$-lfP}|BFV0Ng<<-ViLD>H9gKG zd*3nsf}wYIZ5)bEmtXH3?%uWB9muKHu?>(Q%V;oe3>`314^+Ij7+90)O5mDC|MnE4 zM^HKxI3<5OsBGa|a66Qnk&tKO;S@YW`76pUNr&Y@6XNBTkOO@^tt8Q&)vK=GPAe)R zbp51EhHMz#DXqKjUR=K?nu}YxqA6Ete>8lEgb@lr7|Xz41Ke&Nka{W11ba~4YyvqG zX9Bxv?nYIB)FX|MG(PD-@d~Q_N#xVhW35w?lpC37#NJJq8uiQ`zoR# zx{t;87P)lc-w10pw&zK3nT2U#`A(S!ZP37#o)GXV1`PsN?mh|9<9qeTIHb#Ng^b)U zj?zg8Ua;hIiZVy-91hFnEYBIFdUQDQtf$MdZ4}>sDA>IqiuvP4!Z@=`Kb1pOVvAbj z-wJ;S?j-8lHya{8ThgaXvpUDQ%?Og|{=3iYzJtznmqT3pQz5^fH>y@#{=*e|WrR5+ zeF`L+Nuj9k`J#XA;Ou6bWmCQN*9CWsBCnKUs*0vnm-jGuuH|m@G#@FZ~8#V``X%J%2$)$|z? zOss|;xu3EUS8(=gvfpZ>Y<9iCz9l*rX1@F4r>%a=-{dNeq4YYs`S-lys4LHc$WVW9 z_B}HGaD0t-EVQZb;P{-T-+dM54X$WCHp+S!7b&I&Zu&Qdx&)F^WKzsz&S1?onlDnE zsRat*Ay`oUSOCUoC$364IwLN|@A-;BsK@WtK`+GSiuTrHQY;;jvS<~yp( zqLg*c!7`H}f0c3imFcZNOe23gx3x_lB**0tGwU`j5ZYs>(9DgxzFj;SM!wB$AVWgZ z{P+(|zN?k7h!ZHHd+jV^_(A=*7duHnEFYz&=uo_n?$%&(5N&!_VDZ1tggM<%XLY2(;|pFz>1K(UdnOl!@QryEA`gq3X?v!^lP4 z+Q6qF6}Cs#DFAJddMRVChFYh9*c=KyYdMU0O9>)E#BsZk`_izk?h|EGYgOcp3w*{T z#Kttw*fjDh6{J%X#fGN&EewA6NDnCIdNKI<35N%G^9r>kJ+li}0_>2zqlL{O`EINt zGSkq@9yKZv6!@g(zzl!j;?PG|t_}sH7hqe-*3F;j-b^sT#kek@W9va-AVr>}#J{tV zNia-t11s{ENOre)6c|RmW)In=3ugP5$4%DLgR@S9G&tKq=>~*0f9J5SoGJ<&d#mjt zE0nW7fy_}>e&LeX%5e}YD4lXc?58)4qVWwAc!LbQXrAUm@8W+*0T|!X)Wg^YLZrv9 zEZ2bIo`=3o55uPc6lEF{hR{4oQlC-~L?`+}b-s-XFlFuKd*sON_%d4+uBuPla=6g+ z_V}%0y0ej)kxqwb=Jc=|m>3>FtPJ_p#nzPgODQt4$n{H7*`_*$ zhU&d}S%y+8!4aHmzx$Q3gL+Eurkv8((S!#t>2p_eGfC3r8;0LG`l4mkICS}aYoW;a zXJ`ao2f;;*hS$qrNFoGxMbClgT&!AMievF2GQ9J>Z@EOHAjCU~&+ zf=0xjogIHMFUN+FSaB{&g^UY_Ny#K&J)JF!@0eqonz131$L}r5PKz#W0GN~rx9-fj zuO^0Z$)I|YStGb-^!k_)=Q=ESbZa98H2XY^(;#bjRm^{FNxK{JUYY$*7 zc)_?)+PX~k+0Y*VKGeJ+SP37<>g;6-o{Fzyh`sG6AmD{;GKULy%eVhgDTzpThF3)T zVhCSeR03OI-JgQ8+R)P`WZR)COPI49fi)XZ3XnPL@6nNH4Lr^kxxbm#GxW; z#{k=;io>B3=HMgIV&H4LI7N^T0)rG&FGoYD&4V6F)f;Z?oW5xeD?cpQ=`%C+3Da&oe2Z{xL`42gGR&)~dL-^HxdWc%dn~U5IpJW)FJ;*QN2q_#X@A$^ z=HgAbiiv#-rlj6kY3`rgb<^*emKRyT?o+;?jCFl;`U`g5i{F=DIAwqOE*U#?`{<%& zfW6ah=oGeblOnWwr!0;?Pg3CF@K}U&Y8w4OC;b0HeGv`%%`)rqZ;9yDq z#LzSWfH#FzkO;JS>&xLR5!ipR=|{kX@m28Y)I1WWq9|yZ2K+ncHaze_ekl*9`6|ti z!jQgcbjVSJE4=;rEPW>Cr=hSV(bpyYfXNWRG)@lr)uF6n*gfRlHwY6V?q*?Dy zOn+ym1LTK~gdVrY0)mC;o=qKv0Y_M#gTVm;YcOQ_J_yC;W<%y}dYFGiRMaw}3YIz+ zbR=cBy_%*mKs`L>@o*qe;#+g6$!3U(WqZ_n70p*`ErLxQEtoW@@_mEZbqk6Dt;|;i z8BsR6cd^@H`*eeS+^4Ay2FE6b_w-@zLCl zy~%*$FJ^oEE#ytQs}O%45_3r&s2iKcXUJV<=N0NE@MU2&;DmFF#MOQA>Z+%)89hY-H<7DsGHK;9}TBX>XAHaG5L(Vqt`Ln1|F zb`7C!My5DW^3I_)jUe0=c50a~6aCR3+dcR%sqU;eTmZbKIkc!X2 zF9qxe`{#f8+ER6EDB6)c2p-v+iE%h=vwks;FOP$`M^GdNrBI%wa?}mOv+F*I;`w?W zKf}+#Rdm-dR27xH(D1k>HqQ|90e}UJm7O@=mr7(-Z(Gj)^)XR4fQImZMuRBhgvU(~ z4+9{hflJtm6;d?-(DbGI7SndHSz+*3Iv=e29E^W*gY)Im1vDPTyq}V$^8*&&qL1>% zd2bkf?@W%;1b=`~it0x0Xp`QC!O5HLG8n{`r%9F6&w{H(pP#W{Lq8e_n^#YNnl6av z*F)w|zIYG2;d9li8O4&}kwXO#bin=O3)TS9ZfMwdokmRti}DSC2s{8hS&SSCLQq*A zb1Z+Q4`rlq^5#h@3VYm*iBFm&iyOpM~Z)tc5SZg?h>;7OG5%ql@xP}@; zojO+H%nU)ShZG?{<4!BZkY67@@pnr1^qDXy;|mtWS3pg~od6CP9_(A7 zAgs&J^YZcvfeMMdPq4+pwq6y}{qGQHJfS&E(g`h|};Yx`_o>`+E< z4r#j>IvP{vJfi!pG^~heC;YaZBr?LrG72;ckS}Ea3kEg$ZPW(F!*j?$b96xpbxD86 zufmwzwhJQ!bQ51Tq9n$wLl`GMP8FOIYNhRp&X~bi1KR8^M*ID%`BX7)id;0W;n{39 z=oDh|;zC}dCuB#B0+DH8P2f`iVeo-U-N0Lk3t4OD-h=u@AS^3w3`?d;`82O)@X|D@S)m@3M#b?f0%DL-+mxw!h*> zyz+j35sFk5R7r?n*E1!cEMHmnu&Wjc>Vf&g@^nrmEH{WY4SL_t#NY+6{OE^zFd$ES z`~mG{*${n4v+T^~m{9oYj)45s>}X254&Dl!#gXE79!3zMWPX8c1c9NNY!82#at=8t zp;eW#(O74!gcYFZ0;O`U407}Uz;pOp%cY>Sn-e4csN{27Fh<72!}Py;d}Ej2%>LSc zY?7UFt1Syi1D|DSD-}5fzUct&>sb^m$N?t^^7fN?Tz%^WebqBJi_kY~`9uDq+ZN@p z#rHr1R$*LMmCXe8W=&bTmhykMTWn1UT+m1JK&0p=c!9Y`ee6raUIGNDfQBKuGUh=F zmiu6@ORgx=?g!+artg_0O71#Oo_D&k3S*g!$z1xE7Ze!BzM7mgFe?#M*rY{M*%JK` z5G9OboC3eKgmE-=|7@Z_Ykf}u^k;$uAb$Hj)ZW+GQ3UsXA$tbRLu`N5pcP&w`a*$U zAkDabmh0p1gMOkiV=W2pcX!g=5ZsM7uie1=BYdju+B}w{zC&9Tz7Mn#4qP6gV~}~2 zOjg@B@`l3|*tzTwKP9vY^e~n2tAcGJV>4y z#RvV4o*|cUFxNBC0F;*6LU4ruktQ;S5`a$XkJ0DPk8-Cd2q1q^#~b40g4T8gbYyN5 zJ`iemj|TlUi-yQLG?S%#6PG2W%-82Kz-=x{mVJblc7dZcpRZ&9m=2^GsR<(|;|}fz zY*|Ab59p=OeM57u_~0KhEosfjs~dW7<%vtx#{IGt*X+yK2b*B`o2rZ!a3)s<+~k&V zYbEvhd*Z1(3UYsn_!Ej?twllw@Vlt*Y*d$qbf{>1k2z;X;gmU*Gc0~X4J-VJH4>At zf_`nx<%|&60+p62XL^6zuS+v&emixu#5^NAQSiSXx7_7tEaSdBLD6`SjGge%GT|8= zt=RHX`g|B-FgX{r zdr{NAy9rbj@NFJl(JR2- zKXx`eK+4VgMIOEH`uSF%=pZ}m=UR7C@rNqe0l|NygL{dO%;Us>+LUmCs?7pgq=@)$ zpT#EL2+k7OcXx`f6u5({arV;y6+r60mX!S*pdNwwo?+LoKLo$jTXfz4tRfyOyi*lj zM~@2k39N+4XCX2vy!;Il!rxPRA|iMyrW5zP-EJB?D*)I!lFCGttUe6Q8zh30cnz+DVpl1j79`8BvzL12=~k2HVa z!m{WHWI!PS<|73@##ojw4YOrjXg0@I*3Q3uT9N8XdMvJyjszMx9t*tM#w)Rj=G!*m z317_O#8niYf_G-(fL5*>87yL@o^Z3Nzl(oypJpq$d+F;*Z-5stxO+x;4wuXIh?EunBk@gjSxYX$vn+^kKh3xg0VcHTpKK(hj=bL|O zo=PSkA$@2Kl)qj2wTxg8J;qBuBNym{Yz(bPOYX*;1Xy^R6@hx3Z0rG&$W@#LLfvoR z0ys@nopWz){gVLSAKn)_(YV!+zA=oOfR6!?aF#tpYAnK8%O`Y!E}Ro4O5Y|HeVp;? z7yOD_{##o+&Khqi(6w=@**m3mGhlzV%0(>(uFZL$%^w_Q_;K4_8V>B4Rqh}Fxlyqg z#7|;;^W|ccb&2*o>Zb~}o5mX&P~2jv92a@h1C~!Ne#ktnJz;!!c|2x@ z(pF!NqF=%FSkUANws_*n!+n&xoIC}Vcuk8-*u)j<+Wn?%)2CS$1f`StU1dx){Ex*E($pKud z09JKf+2uUa&>hmAM!3au&Mp!M&?Qn{Lnjzb6oL0sC_4}=j|qM$kib~u(tAWF{C#DC zvo9hPbi=PBzL$SbTfip+=*535X}?8o{sOG!?>Y*`28tyLN503+XNKYy4Awadw+a7$pgsbv2SOy=RKC>pBQM#}I+ zSZk8vnW(S0JS^zk%zjKHJBliQ?;PNIuC|FZ(h7LO%!e=*l(d9)>sx>4QNu@*?hVNe zs>w4UJDqVo4pI-i4$$%`_C$yQXX)<;nm1h9Gxl&>=6eL6KnRJI4Yas*#Id9b&LlY> zKNtliyF18J1p3p!7~ohFHzP2WL#bw#_{ylNQ-rNk)7tLdRfoNT8vwCQ=q5@9@YogH zGpEd@1DOTEm4hU>?WAYk7EWtk52>*o2TJv zZ7rwOpX3v0`lxXfA~*>Q2L$-WtRxj6dhN&=Ec2=o`8gNAW?6rbfXVq6pd60O|G;2T zv=5J^u>f4nix(p^Y(8bsy1178_)?8k(0}!e!x;j6^NH4AP&^5S zlM#7!a6^i8fnk3IMEy@Iuw*r-g+xS)o4*#Y#I&vbuCK}P~_ zW6ZZdn1O!;dr2Tjg}8oM;qHaazyA!HF_50~QM5aSPS%%}C0Bpv$qA1yDjN#?<_S-8 zcI#)2pyI#=&%adr0^1K8C`u5v3Bg`beVc%c%5%YK{kj1D1m~A-ha!?Nv)pp?BN9UR z-9@`jxy(lg1k!k(Q&qidZK+6;Z+LE(Etf%h&-cA{ z46c9oGmiCeUP}+m<}y_&nDL^9XKg+2-uM@)+{?p}-Z92QinsWH5=<1+M_1{K>~oTK zPw9i40E{*{tgCPUKMDXx6BYY7U#gWKH+%sv;)9hBTD|q-(>z#V+SZ{5c^GN6kPqV<3E6-FCX@0XCTJNDVbK|x2o7A$~V_@;4v z`;dsTqa{(87$~+1o->vCnx_!J81i#LtOi0>;GCIIas9{{-391Ua_UV=tM9Y={r zAb)zq#H7|YGQTRwU*Jp3!8+nSolqs;{fC;Qm#V^ zz0$z>8NF*CUVMm-v0s*RY+>#I)ZR5k@T)LfXVrN0CaH_PoB;hMykviXd*Iu31`Bd} zKTIt2{Inuo(4Udwh{@l}pu%zZLb_BlaE0y!XRmi#DvklfM_G&w_agi5#UH|C-7!PZ z<6B`(2&@-*f0n_`cf4-9l9;_;c}`z)weEdzDhQCUI$`d<2>UY8Uv|uw23JZjYJ2T0qm(<^tjc#BQlfi zf${L3Vt5l62=Cn=d}!fdpBwq{ksx5Ioqd=*$AN<5nmDH=9XJOC$LrF7d>}|4Gh$)s zD>^iZX-#QwbjlLXNLu?(HVs`5z@Y0q+6$QFDoYocjL(Vi@R)y;Yz0>3a1LIH6-ST( zFq70VPWZ2_|6tZCIlRh8#x>1b??_}|v?9{eUO@V7C>gFVtpaAgA4)$&LVNLJ6Hyvg zRr^vmR8lFgqmT}EicTg#w0n){@Vi{8KhCe0T;MfGVM=x)qOR~F$?jv73dwu~V3vnh z9W)3n=dHF-1uK7r!={xlnT+0+-vy~?LOOEhWr|5QH45IP-5|XAMJ?bQQV2GaYu|7& z$$_?o1ul(R+>CW+_HQ0pI;0kxMN-+I>nAzdMQ|GWyFP>`3Uq3a!Sd8biemC6^~6g6 z?Hh>d02gsJpy_WKy4c_O9Id@^`x4dpCF~;n67sYz^51_(ULg5YfPQiPl%aib+Wbrn z=@$)?L-*|6AmIKq5%x=)+22~Fb_Y%4!*$}rX-Tds&BHB+B7apXoC7iY@X{inuzi`& zjKK7$W)$Xdn5gLjuG17ptFQH5{S&4v+ASp`c5vCr*Es&iQ6awUD(YmQPHG39h zwx3}lyOw{Zd;8qZ^i&61>Gdpkg#xN*N@|BE^H`ZC`_F?UU&I_Kh{wc|^+0`i%!Ez8 zNua45^P|7r!4L%+BaMFeN?I>YwR;@Ho} zz5|;S>+x};bZ@b&8teJxIQj3pWQ>e2bufFJYs^<_uABe6?~Hw;O7Z$texSgkjklJ? zlzyui?^cd+vG6#Xm*Ed=5(rLszPVc^7K`1TNR?4&PuzZoQW&;3@yE$!e`AMZlXPv0 znTCHi*CCz|l%DaO8Eg1KmICDQhlY5CB!;s*kpx^X{k9t(^O4)emR4)uEZ#>$Qq<*= zZTz$vmwea}DBQ?sl-qVyXcKdA`9nM))heuh1~jupjiIE!ZC+oUBv(EJL4+atFmV;g zbr7r9t0uAbtxWr$WY&8{O!NqP;MOE2CD4DvilWVShjw$m&`*6yao~6CPA_CC_A?mL z;wy(<0%N$8ioh*fks_?F$=rhJH+OMhl z+BNmoN6>-!ywXI!=4RvMrJ|DDR^)#=AHI1i(y<~Bhc{rOO1}=^6V_p~7p^vS%5B`P z=x1^2wws4cSYm^Po||ymz}N5g!PTL|`RdRU9UcCyi`2p-^TA{nXC&{?{bmo%32Q9W z25x)nj9LU1W6E2a1UYBlfw3LTvC0u;=w)KX=Cw3VtSt7UznU^@2?M?@=rMl`y^`8- zOOi$=z*hSiRj+4Ahe1C1o}==~>}GSM=7XZX;v z&&i0Tr-^EnaNA0j;5cLHA#B=yS?aTLuA!TghPpbJ)I3P0pAxk!b4)5i}J>7qzd47&h%vQ|r6JhVQE!7!X=5pkjNsLpWe?V&eG`smY z5iD%6py9>weSCn+OOpDn@pJx=h|$QeyTk}$WzF!h$%*i2}Sk&jq7^>$T z*Td4YKN|XyY1pC~4p<)(%4| z!*GDvqm?C#CypQ;$O^kfB!gOnc^CWU8VzVlci|&UfIUw!VDZwvbhNd_pL`b%4gCRm zLf#q}BfW$&2s72n65PF+(KsI^N6;SzQlf~ju|nZ$8eR&P$*U>@2}uexa`(@%3t9oF znD>j!_^i$P0tmFLZKP@}>+ObH&}S zoI^TTBS$zFFZ|^+U>?VB03%DQ)eM6%o?xK$7mYNQa4CODZl5nnfO0sJ&hVSfSMPMH zBv*m0u*1L;h$LvC2+0z9lBB^4rM1gx%1tNBd#p4GECjOzF2g2AiEF!e21-!y7)pM~ zyF;ZJ@c1<}$SI*sdmR45;0M}b_Aq!Z2p?z#Goo|L*0Mlm*naFguWD}tG`VSnAX&aU z*eV|da=Cx@ymn@M+Q(!PI>#-YSS$)X0FD>7xL^WLI`V*!|Ll&ad0$WwZF_S|L|(4LjI)@?V!Jnd24Z4`r6-fQHc_p zmN5hmN6#lbN5L|$^E*Z4i(fptJnfmP_~S|FBz=Ft0fksvL>C7AS!HOLNj&RYfDa8^ z=0T+V`R%V`=rLxM9O9GfO=n47yP*vOnmKv=nW6)1OzsES4;}^gf%|^bGXZ|vu_0vq zEY6J=Lbj#H4SGbrJM)RiNQG&kL|{eQ6e2vqzeCJO0wHqv!-I}TQB>zf%MUEXG6!#I z|L%Wf^)5Zn%S1l!vK*7kyVSR?&`FMH*4xeGg^D3;=BtKR6C|B87s9b6Jg%$dtYN{o zTcaEWseMeyMne2=H1=w6iS$g6DMQ~R)aLxcV)|zBwwVEN!R)~d!z3s!W}ynV&&^&v zle>{UfWup84*3#Qp(P4GfIgVOhsaKov$TKHe7?YRk=F4O=|uxXO9a60jRMUF589bU zxbOf3Wq-3w{WrH~x0ENSZK=YT)C8(<$pS#V^~<)2H}O zrv0z1E8BGyNw)9zD~@)*bc?FXY(T1067yg)8Z*5y55~;%*WcWyt6SZ=w!ldkWs*Te zthHnVmQpIru8mKFro~q9AM4oen45o^=f~Mj;zJMbHENA_ZLA+}b&z{Mg@p-^dsN() zplCckjP4Ox_klpPj+r2|*5H#mKKvdUinpScjAOF;>=Yk}RloTwJLrfocS-43Hkk7> zE+Kfihiy^W1`R0&6$0MX3qYL|K9#85l&8Y+!G|&v$VZ7jFQ>lF0da*Ze>H#N1dppu zb|)P{0!!_mNr#Jr?}uXM)Cgk5GyM7 z-4&+!_A=6_Pi_XgJEqRd+^7cEunc4?aTK}x(%}`0=I4Y87oEQO%=mO9G zFvMH4-@{gXZsQ)q$>e>o`YAxYB<1dwgygPv-R&mFc%cR+CD+d-Isx&0u^HfhA%V!V zb`f*jEIQVHu%>`q2%jhAf?cmn8{?}9G3nzyeL-3#fV?KvE6|(3Ew+C4_O?0qY)uj7 z*ck+07YTatVM|iueu zW#|uto$pf4*P@5CqnAf9N&w!6n@(r48QM9FA7dc$&+b)*u1mxw{Fet3eN ziCum4Y@r?>5L}WQGRg!sT?7Z2Tt%75<$NG%nQo5vjp{;djtAX{?9rig8(}^3c>rBj zrQ8@)w^f6;kTMJ%**EH_J>H4j+kRl=J(RC7-glqJfM0pyUe>hD9%IcN&(4Gr!3YRL z#|(C`_xX76JrIhmpGPl$s?&p5)S_&ep6~L*Qtk}&G-KNcSm-LJ;`$w25M8gkOM~cBDE_HC!3`Ai8$(e3k|%Jvln?A~gj$=H zY;dXgO_c{04qCu9&aoxD910Aqyj`#TmP*}6aI@iLT^3gFR>vTJdj*xJe)}{`jaZ+{ z#&Wt-a6g5r;(k71uFp8eJ5C%<;8TDtgqyImhy72g08U>?FogD0sUc}nV(yYoS^WrR zE;~S6oUAl*h>cJpUMB=9N+l!S;1LIbs5)m(oGHFVB-fiRBs%4ik7gm;XsLE33+d3r zoYI(=h*{<}GO&Yx*x_a;yz%Hz0tB2^Zd;+|KxF}^7FcwPLK}G6Bcfo*p!8(xO}GOH zAMsV9paac$;T{w0ckDdb6y!#xiizX)Z+A0@7P|bMR$DS<6osKqr)F{iZD#*@606In z3SK%)s^QG6=^PMB7_0h-@Csu-^X);f2VJ|Lg8PWDihM4ALx0Yl(lcq{*Bl{O0o6VP zOP6therozO0tvmaP4RuBs*zG=y02H51ZPVcO$ClHa(4x)h3>Yr2)+tIyb#ZjI{uqQ=}z~ zySbaoBXqcbaGcqs6_}BR6^o)+e<)zvRYl-L(JoZ^`wv@8gT4;8u-Vjj2N_*WjSh6N zUjYI|-9k}j+qeBvH0sh5sBDKMEC=1np<#*C0BA?vQ%sQ6*q_X4U00=Y% z_-l1?d*7xdoPU;R&6zVXHjW6jmq#sTgx8Gb0$d| zSC@$6F5>#G( zX>am>l`XnTS@^S4%!<6L*xEpuN0Gru-pNSWinRd&-4#VrM8Uj@xOcSb_H2pIgujwZ z9Hs`UkYW!I`!Pcx7-DLk zXE5yRKBz0GjSIplGIL{%6oO0!>RNLmt|!KSM@w`Z-0I{louaH)+|=uVP$aBi0@lmY z?xIS*^Q*@9C#<3#tf97-w1(!Bn!nH{M{wJA7Rh35+Vbm)w_U260k?wb8rHUstupo^ zj|E|e!>yu0NXGJ!%oE@=vIwZ1ur0=C{-^`23O3KjsPE@Ffwuj za5txRGL*c;du78g2)1cPJJ6S-HG~%XUGU6uSUZ&w;_ciD9}4j?YC|G$CY%#tsL?ou z1mofjWOf}I#KwNCVYQ?bKQcHcQ84$oD)dWVn`8!g z-8B$~13m)@Efxt5rn5aD>s1gPT}DfPD)4X(Pt;p#QRX%&QIX%7ZhTPMnX3-Ou1cx< za@G3dexG%gdjTvf2uuMfj>9niK+VWK1|CD}p~UYl$ZDw_Zr&uM4TrLsm1EKzDMV$J z06-Zab8?)>gWz#I6-J!Uyzq>`n#|?c5k#aJ+lOa{goD{1Ig98yd+J~8p7FSUtw$H~ zhKlBVqHs|q41_;X?48a`mZNj{7$8PPlQ%r$+oUHznr4wp+?NW?s*Je0S@U*`=)@s0 zZVf;dN7CG^+;YfRAiYPKGk^A}UMw_R(J4f-MX_ZYol@zuuNb*1SN0L9=C8OERGNH5 zXhxnC!w5J5;RUTbUZf}#LgNU30V6Lw{3x6o%uwDTl6ceE1R~d6=^J@(hY#d5LLH~n zTg0c7C9r2;6RL8XC$9?>6>!sFVBXGYS{LHM%R%-&ycZFLn@PrEM;rt$$0eHZO6GgU z9-S3Gc`R*_Ma%Ib=gh#m$38CXug4Hm3Bv%vOGCp4^g#$zt7`@Rs)Bfb=sxupT+)Ik z;wQcBf_T(0YY229RCMD#G6AggZZ3?E$&=asE1#Gx=o zR;)+$4q$HFiaag47`aK@7Dy7hm-%6%cY;?^|8cD_*8)F#sa4>(stVVJ=k0ZV+HJ?k zZDC3+n1cdV7wYKU^?)2DAR;rsAVzjJrH{ryywPlT!q zx!&mSha6dN7!M;Rj{VEuWBPu6sriN^)!Q8MCrWVL`xvi!jl>(G^w-gn2uH#jJ9DpCkt1I1W>3U5n@SUlb4SVaqEH0O*M zTzYSPoH3xdcSmm2;hH1;8tE|)HU12MJC7BRKXQ(JNIoNQ5o@J@tL9T<6UuW}UwUq9d_!y>8T_DfH5oZAW zLj4g6cn)5F?tOknb##Xwb0CbIlmju!H2#MI;=ww@Wz+PxQf2o~;!kYU5JKeKcS}yr zsaZ3KdLY(a7YTX|5%2Dfp~QD=uk|cI=ty7>Du>Ad3M@zp-HXwSA=}}*idPhXBKm9| z{uNI^l&hw1ty&G=tH*HTU%Tgi>U$0-_Cee9O<3xGopC`zIEQ=lLTP?E99?Et^|4-U zU{MxJHCTw~1f06-&8RKE-DDIdQTd*2-@k+Vq2Ji#HjEg#m}fPt%x+cwtwhuj&g@S# zH~D-AqANn(gGAtddrNbfle`|9^az1fRdwm!#WYCI6zjsAwHZ{0@ChT z@|fm-UYZYwtynsJtu4(~>E1hGF=VwnW1<`K{0S&DOgOQxzLh9Ng zE-AP$Wi5-?#x0YpFh*=UWk}^XO?^5X4l+A`C^bCKN}*Z=16s}5)Teb;5sAHtVCo*D zU|I65!O+AKu0{7e8VaC`_Cw{?L)b)TLU6)1idw~RlOXCN^}R@i1Z|-(W;US0D3-V* z&89fe=4+x23oJ_2!uj?9p3C*eJGrDcD=4A^3uCzA3Kn|{x6zb?V4)RZn%yRDUmN;= z2pZE>K4E9+hu${qMfei7DFkGqZ&*176=_#W+_Y!71J6=of%AY7J{BCE_}w=cEg3}_ z=NeaJ=v}ztSx)p!lJ-X1^MLTxWtUdeTH@nH3jR}O@ z_xvUQe2jKdH8iBFp*T`s>EA4kpGd>-LMBY<>R@ z?h;!H=PyppO+9bg>~cOlzO=b#WfnC$BGIuolB+xqv$R!-uk8NCvx8K{9DFd!>egvj zC30o6;Kgaqixj7~R+i<@pI<-DpI_+h3;y#Dxcu{vEHCCi|47?(u`JZ~q+dA74L;x@~`cb$yqA{pg1{t(Wg({rWL4Q~%C?e*LZZ_4=3L_qOixG#-9_ zCF`>Mm$m8Z?&sI1Uh?VR_Fr3nZ4EwteqsN%{{L})-|OuA*nnY~;%+Yb=>z(Tm#IGf zj{b&#H~QQ6EWz@R|8x`h26%=3Yt2wU9>`y71UTc@?0%ot7EC1H@~+RauOC~UF8%a- zUVy5#{5AEz&djf6-pW7!=l=juO9u#L=D8In+W-KEBmn?WO9KQH00;HVE^~Hgw7S=_!$_7S_$z5SFVlv~ zBDCnOtT6}zAhcF*&;X&e`1-}o5?wvpYin!P!)s)KU?3vkagHB%^8V$2on8COp3h4? z^uPZK{TclAm%LAhtnSNy-+y%-{x|a1|Ml0uEPMIOQD!zmXNn}SuKV?uDzD3G z{o@n?!_?2Iz0MD2IDh{Y{00040^#Qg{rbx@N5B03YqhT9zrS9`as2r}{yfa(3kE^( z^$h;^F8_YEb>I9~9U+RMUVnW0>tFv;{!-L!`}?o`(C5GYvaIue(B!}WnzV7+{NwF! ze_!o0`A^^9=B<6Y5d3FLQNJk9>AyG6+53+H|1r*U__u-o6HMFO z{?GsM$LRm|548RV_{Zb#%l;2g{!IS2VF>>T{!bWEAs1!q~G8{1*j5$^U2} z)kWs0g1I5n<_{ zmXTHjjD9+>0rT+#^*JKm&x?N2f+rtn@*J1+yM3E~o`v@MMditndQty+;T=E$N#0?b zS-lZh^ctJ_$ZRPbUm6{j&rp^hL3CX=&DOIQXB7Y5!}a~{hLZ+PYIR;z-#3x4))dM!a2~ zG5_{|bbRrx(!zIz=Rq-f2jkDbf5MrqmXj)~bk7b2r0mj^EL4}w%esVVHRhDV^PYvA zsecJM+nsM0dfPIr0VI$F1{HnY@i}+;UVq>Wcsg^ZOEbhXc!rtAE;R2#Gv~z({7tF6 zjyH3RC=M3*=&UfkX=-B2K$M~u_t2hk`zFuzOj+;~0go=ZaJ2qIpkb6&D-Hv0%Hbg?TvZsMI& z@oPRCI&&u=%`f1czT^qIFNCx|jl!0r{Bs?oJGLpHv_WSuv$0#-*A%~so?l^QaC72+ zMHF6S@*6J)j_?uo!z1u-sVpV>Vd0M+I}BRh2Xr8ycdjw+&u9+Dz^9IjEy2kT7ECVv zlEzX5=>ifDIi!IYTLvku^UrqBm_nF+{n|5$#?GR?S}40Gg8|oO?xEhN3zK=dJ3W>h zHg;24d<+k{on7dbFWB7c9;7E-nr|w9d*{H-q$qgkZv}&n0I!-Qzn;sOACr?jZvuAR8$aBKfp{iRK1_P2s=uS1iS^BZaQzTMv3>>qK8JQ6nmvm9 z?a=5sSLy7;VME9ywD^sGbu_ba6ds{!Uf_znnDH&V322=e9Fggr(Md5B$KW03yApdu z9iEN0ZGnHrmrE#^M0aW2cU?mpxQr3Rob*KBNMs}V1OMqV5)?fIF;BLpjrhx4-Ii_8 zx7*to<8ll8=qQ`MDWzy6_e%^}P>AuGglvFnRIqY=*C0JVKRa?7S+3Skq;SJ`*yV^%*T9H zDfIClQW5H@z{+s}Ch`5l2h(!Zp_9efm3cY)BwV4Pr3Ur2RPHH5%3EwB!7zz(48P-b z*(7&5?+fnRTOa5e774JqruQ3LGTG5>kA*D9bpqoIXj48zY zcn|<4?3|08zpe&}G=_84L;+O~rCwO$Gb%t3d_<`+vB4}h38r_YDH$gr>W1HaMncn~AtC;H~eaCr`acQ0%6W-G&J z03W1(vqKDHtx3U+CmwXt~Ycq$w~ zpU^0dH*b3}^#;DTDdBr26f*#XnjO*y=Cv=ua?<7HW0gUq1O+ED&J=!3gGcF)%eSKCcqYW`TDs@!R1f5ipRmHS_ zRt6|f2o^Y~dd5J5klr6yc*^kE;%x%nB^v9TOY=T7!68jax~9RxIjbN7hF#Np*g#@K z2jJ9>@(6q{<|=eET@~kA(+V*CgV`e4kz|;YoAc7u7kxXp?9g)kpe5MqKy6Hd3O?TE zTw%9_PL|)YacyUu_tcU#VxD0CgHG6g26%tWD=>ja(>bP2ThXp2UzEhLf*r9?AqFRb z4q>5;Q|Q;-F99?&!pHH#AFaZF8}S1R$Jt9O2f7Q+SlFzGN^<$pgI6=7U(Vlm358tj z#n{zTy&wx{@;gYz7XF;%olacYn&FX}VPDeYq(Y{pyh zy@mx&306QG8`9!^7|cfN8q7r}{n$=`CIicHDzTQUGU;Jl{DDCx7?Dd0xq&`EL)%Ah z!H6&;#!Cj!CnaEK%#!y!a$p)0W5iUjCg-MdKx zgzceyyt8>FJ^g8-6EYq;a{?GR@;pikjnNBb*~(iP#I9`^AD+86zSd)R*y6H%Y=7se zke3-Y+=YsZHdA~=4o+9kso88rU&aA8AHpNKd)4jmo`D`Q3{n?LTpkz-9(t|;IVn4d ztYa{UnWsJTP@^+87GZ*a`s#A;db#hlqoR3)iP1ZqOmn$I7Wc3doRr20t}rc{uy4%= zSc6})9ud9tT61~KAFZ=6yHW+lAd?46NN?)C@7ScNu4#E9BR;68m+@EY;dMOZ^JbF+ zczA1M-<``BivAIEI%nfVfiKAP=x;0My3e)#^;NZ)SIpK7>8^8sci(U$pH0R@i%Cy; zja0n9Js$wk654=vpnI(QVld=mD=^>YG-G&9Jp9sEekn%KkVc3=_~;|0jg-~r{K!RA z&jgo#3PQR2&c; z0ro|oIPlTfW@>wUzx_awYCU!5`u~hL)&-IXihf1KyZee@1I<9kgxi4+C7#hl3RUJC_#O4 zJ_CbarWP@r*ieocl??2aTC4>{K82jNMR55@s4Oh!E+cZiU!DD;%T%cn@)L8O5OYr+ z;eKi3;!=07bUdQ?U0-E(x%c%3K;Vp-5`^sOOcsNG8yL7b8d_Lem3|k@ETYdEI@`2t zT#Lx_e&~7w+#wDgBSf}ra=KODqdrVWK>k%`_TKVTtAUNB9CUrWIS@roU~g&ZlH9I+ zfUQhQ%annpj!kmsL2^dIbjgQik}A3{3t(1>lp_Mm6JBPF7_Gm%YOA>mz1P~I;Z2o*{xi4OjLA$%9ZHJPfPEOsu#y0t~qYq=4<{*UpUL}z;7AhsX)oaS;XNr zFeW#q^Ue5X4jL)bP~#!k&V8^o-wR4V?`%@|38D|=*R;scM=>5K6>K(ZjPs6f|-Od^s+azYzmZ;x9AzQM`DKQM9d!} zxut79Lw!SqEZ#Oy;!98FeiWU5g6LXjDV2gi-%I_|86eb$q!6B?QIH!{w)lmWu<2Yd z`7FO#HW}+Eta>4j9-@PT9!`e@Ua4V`NkKvxJ)4(ypb9C%kI{PuI8;Y2CM zLk~I}_XS(dqiNpuW0Fmo0>O~w+HsjAl{4)SE>QvnlVpG5RpPD7otj~PjeA}I>Eaj< zZDQ^>x3POUHt~WuIVf-jkMPNC)MGJ89Yz?(l`2GdV+}cnfmqlgTFy9+WF!{A*2l$t z;KgVT89n|N7z+7GWv+8JNSU$R>z|-TB5dNnHb3%x=+5JNvFNSjNE;QdcVWWiNJXS0 z%WETNP@0x~d4#eT;Q2g%FbJ$+!WTn&` z3d`oeCSU?0FLjYhf!wxK$*>P>(JVlN^q26P$8O&Tlhol$gzIn?ze8QmuR7%V^u?th z`DTKv=i&m((&hEQkT-c-1dor{JcQGnE993q@aY&ozg~gP9Kzv$>n-bhp9o)MbkJjq z>HTp4;+N#Dc=xCiInHhMT@hu5dSn%p-trRV6PJmP{ zB|@UOzT&Q|At^e47-ToHiCp`T+Y|4?{)TkgG5I_Vsh-U6>QGKtV5#(((`{l^)k%Of z$5OnDXppgpP`m0byga$q?5cK`{|xmYa2U}VTf&SbFd>J=TyPi0hruOg4Ewk_VqWuT zL-KKYf?r~n%Q1YxH7|Lhy_Xarg(mrl7ZbRpL9U*}Co$T87<>_>k)Dvs5V~FqTjFS0 zMj$Z+!laBp7~5E~8s3ce#ge^cr;Z2x@jzfL1^Gg7>P}Lbs`ivYu2-8W2*3hiEB-NoXWsW>+%V`(B_YgwOM-=rn;!zVZUq zth!xMmtVAhJp|Wzs4w-poVLfbwI<4u2$Jwa=0Hra-DWGgAEM6_uesGV--Sw+9p*V@ z2aOB?)cM1WTk}$`w$RC-YpcM#@2T&TU0g$t%W}43_K81&D+?0JLw6a2eevLm;IS(S zj4~sX*jZ_%z!cc{no(~*-uf1QwS!pbe!L9I2;nSzXM0FGp(JCJ zZfs9-al<^H9?cL3W;%H9-Fu+U;%D-bUW^zFMF#f?dk}VNTK6l8 z2j5>yTf~&#%_n!suXuHZRyQQgVX?SU?{_X@`p6O^nXnNMq(IF{5pkcnz*O(nv9Z7~ zZ0gN_)x-q6A8QGrct}(8sFZRtf1YhC9o2?}4F>nVEDO-{$WqioDqX)*JhP~@NpkxH z0mT&#R4TXT#UyF7k<{#;jYL$Cj?iu}0}G(Pk>%qO1}c;e91q}mCE9xtMAX>V#4+5j8$ za*~22=k;~db@q*p0T~QzKuc(YhL0_|U>pO%Ei0pbdU-lh(AIY1cKq~2Hams@PDd@u zbq@c4Kv0F(hgv7+ySPerzJg81(#_ACrpV*RZSdMBA6dmLhWM!=bRs{|)M$>sT?7|@ zm^>NR-z+AXM?jf6znu2!Flv|Q597Ci+^8m@NyOaKNx^4MGVd0?<<_?p2cR{h&o)cd z-qK2lUs5m$oAM-6Kj{vXCa?lf(pm%B06Vsd9bNnyB_PD)!M}G&y8M&QNFjf8*5r75 z#T}INXv`<-z51IndoQIdz|K}Cg8ZI;lg-QBZUyT5b{6qwW>o-tY_HV6w<2qwc%XAs za}S2NeaXBP@AGYUt=s&~jNrGP^tt1OIG5?mJaMB!X~^BYw=oXP_23Jkv7QtIm)*BU zy6S==Z31$>W4oO#Cjvmm;(F8z=$P7@i;FK$fyg&2U>MQyj+xHFd*woZ&-kT(NJ*vd zkg$Cmh?g~h$q)l%(&DO3RpAEq-5WB7BsNn{=pK9!pENTq(AKA%lzWO-#zVklI+A=| z;v_>3l~oKg5U3^- z@*<})(9>&m*M}J7xko&z-4Wn_sRfDpxk`N9Em+0~CwYL{qH1a)MK^grzhgZ$w%#y& z@{yFT3fXD9#2DD#j+^$PcKuiaC!4t(N?HU$Jt#DqsmFISD)+D20!pO4`^XMC`kYk^ zFtvU(%i&PM6z>^VeYJU?MISy51;l@RL1S?yHF3LG^o(8DiqecG7Nu!_+n4W|-815_ z)~z(1RWds^Of%2fgt<4TQI?W7)7RFcKa4)fl9a^5j?E$>+VJerYc^RKA8(O02S1fr z0A&hx=;k;!TxmLfMmo)|+wL^;h*yJ0=MvWuOslS*rUuQ8bsE+MjTOq%Nxe{}f{g8l z6Q}ni3gAADZz6g=h*AN69o;@fl?dqCd}^{p#aYY)y?W0XqeAD;>F$x_-QyI{$u;K> zdr4<8_wmC7RPJb_A3mIuWjNqY7e3L{g&eQ<0~><`Pmbq!W4RyTof#guX9Z_Z#rSOZ z>$887PXtXpQ%E~VFnqi)Jk%kL)5uqNq>wy_fV+`B2+kWW)d4uh==9bZfuvut>2JZZ@xz5K(4wsb496#Pzl=0Ep4KK(k z0hG##x|_1~^XL~T!-O|=N{`7vQctBf{Ck$lJb&gUC4u&dvq#H;C$5(CClp8^&M2(s z+K;+_mNHLIG8eqJ!N~bXI?P6=U{dtHtdzTt@FS7Tt=9blkS`NA%G#X83=n>JIW=Hy z(`&sWR-4+Zk5WhiK#=-@)NIEYu`HL)E=7ZjZ3A7KIAoSd_>h8zF}EE&9xAh%YD;a} zeo@t4dm}00g5jfuI?bNE0Q6nb1!#@uT;`#Fj!qanTy<(t$OXl8F$Y1Qoe=Z5)+x=d z%rB-nW3$U?Fe!bxEm#>=oX1{LHRg?OBbkoi>Ug>yyjG9VlsEB~~A z_u0ac#luG!gtz=5Nw=c$TiKI#b*-0XdN=t(4ySR)(m;fcGQ)<2<-JCA%WMHAv+yr5 ziwB}C))$YUl(@pV@MmuKXc}8CSrv1bk}1=8Y^EF9n8ZUtgxXbOm0U@3wEMZ4&}T~Z zjb=9d=1h{q`>LFSnySuxX?LaV%X#h>J(W8Cr7$AETZId+Fn6gh$h6 zB^~K+DxT4(-YWQQlW>Yd{?znk>e`Zgv zcvO;dL;04BE>Wp{8-4VEH`G@*1RZS@biei>x3b2jZzIMAa5F0-OyC$#bGxj#MqjN) zd&>;+Sz~2*ue6-zc^^) ziDl~)LTJ2P7IaBcGY7Gs@LIu{IyzphjLsF_j9=4aChLyLVx#*W-B@3A1CKf(uh>~k z^=6_UQN%n}fZ$W`-av3n)N)^BDZp?~ocmOY1dDB$>Sc?H({)|8Vh>k;;FFAx4D)d0 zMFXHcU+Ek0VkZB{ENpV%eFMZdA5(#@6J;*&Sije`jEWbZaJ;k`$#>^%|Jn}l4tYYc zG+@7EDd$EW-Ov}=T86>6?;?F^;n4RrRY#&p`i=i8$X=U=76HDeUJ~Yxi!G3EU~|#h z_VYWXc%?aWU%WCwMJm64oU5F?R1AP1WNk*3+`Lo_h|m4=_6)qS-#2eG0bi)!b5EzI zW`{du>+06YpJrirWBMF`l#;yMJ{K z3t6O8S*g)J0ZEIq)phBXac^LAsb|xU?hX}%4$h?$Uytd{!(L3UMrMwv4N=PTYneU58PRALuMW&-rxz ze({4dv}`TGGJ^tt@k@VqWLi9e!e`#430h#d1U$@ z4Wo`v8PosBPhIsMns_|dkJqN~tqR2VwzoLFq8B{t7#0>Nz~t|SOAJ<}Vgi%KKJ&i) zqrYpt7P5Dak*dlW`ei(kg} zUXK;`>_;4bQbu`i`xme*)Fonu^GeZ-?jzg|Rx?Nb4mIj=HH-i33pc@Fa#XwFZ$~*g zATn`&)5UpXPZ&cwi{pv(AnD~g|`30c>AM_kUesj&%rZ;?8hJwj8y z8o=|4drEuy9(YM782s_4Q|U1QPc|dTWo)0A#8W~DkYAIMHW0DbcY?@78!2VNw#*Yf zKIch)#8syniEEHINplX0)Kj~Pi&4XG=fY;;D>=@ZgIE^fPI1MOgjLP*!ybFU8K-nfb0S^2Z9o%+m>OMN;_}C;HqcFOiuJGN;o8r2USD(KDm?buE}{>B;ne=JGr2XBk2MKpN1;W2#D=sLzvT;>19p z@%1zOb7FmE^sk=p@A?!YlF-Ts7AyT@w2fDp3~*7yS)hu)i`k6?^_XSyBTWqS6^m9Y zs+0(J_ERs_oki#f5CN3U{S|+TS>G66DIyE&QKsU~iPiS9vm2~z;7Y*ekxGvrkRt=S_baY@6uF>I_7WCpe|>Egf)b1HEcacp z*v7jO(;p7;hRYEQ`qH_n*f#E`^}u`hwAJPR^Zyr)Q{ti1E$@ zyO-GTiYi-Nm8l+GPF2D6CZurgmK3Z|`~*ISryQ^!n4E#8MdF~`NJv-@^=pSEm+c^q zW%>9#r9rgef%{ zh+*f8{Jk85VY3fvMDCL=jj*G3PK@9y8lT>XP#2 z1x7T6TxECwB}n)D>$=1fi_nL$I`)2e>4`}D0?-*UL`YK0F*B|c=yCUd=4v9G?lkUk zdu`E0QNHhT3&>r#Q20m_1X#|*z*o`nveBK)m~E|7$ixo2)5vKR2+gW9 zZ3)O>)$k?Hb!I#|`s{;$daf=jmvec(2(oRh_(XTlK`J72ZNOzrilk9(IW0ywfHe9J z8U9KrZAUstl+!#9Q(2N;$+R0<=ZT zXy@V!)={-L_kB4QXUr@ug7qGwW`%+cfe+H^>X=H?4?CjYSu!C`YLRy818042oSoH9 z+igjvr}r2g-(DN}qk;Q}ROTV<5(w!La% zTmBt$>+$-3`jqDU8tRTIEY6BCX9(7oX!dW8J(_XK!9#dn&u>bF+%G|v`(o4AUQQ0IU)OiAvifq z&^##8GMLCm1ERuKe!b450qgr3bn9x+GRDV1cq+QO(Jg9-_^J%hC90o>7z}+X^|~D5MMpal(vG3f$jU zvk&iZy^q5m0*t&!u^|qt`>OM?FNV?>z{|{$FejEv!pFHD=ss9j^_7Z#7vDOsig?L= zyIR<348#q(lkx+>GZd)NOiy ze6i;24IkXTs4d3U+Wk;sne#!Zi-F3cFO(|FUCRYts$*5WZjF=f6oeBP5Vqv+STVkrV++RntxPBU6k>awQLzH$)Df(ND_w>z?0% z-8<3W?qr`!FpimqJ=8QICW*hZAzto(xHVavXA7W{sjC;M65@&b8_vC2e#2J0pxbSj zOc2iZ+oFRD-_r^r*8>4lO1tFGPVDt#lX4wC&SMqJeV>i=F zAI5i2(S^7JY{O_3b4{=Bu_{8G@WQ*~@OURAZg)e0$D(yrzUR10CTY;TlNu! z44L&b!@C`lZ29y}j#S$eLjpD&x$T)UvpLN!OGs+$nuO+erl1$dyV7b_HL^Hjww6%{B<|alzeW zbW}s47R%`G*G3a`M&JHW;_m8kC@gHVv=d*_l)9=#c~lm+2%pZrt%?&TH!&>;&xGnb z4CjJ-KPt^fXgde8(xqM-1B*&^iC&OdI>kcb&D=Zjfw+tFnmm32TNz=0mR|$&IgILp zzM=jKo;#|qDTZ)PVV4)=qk=jXYpSaPMcfH0TX@%9KoLyzZV@-$x54o^ZM|-d!usTQ zzR*-AdWS*F180}P)Z+2acLtrOSUWe%Xmp&U!RRBU!@d6F4W5LR6QG&^T*g{)=By@V z)x@jbig>xD{)qk}L|iO?6j9CdD0*6o7(!42Lp-9KbJs>?l!MED(O2Sd5H*{h;86?+ zDUB~e2NQ*5Y3h-0B7v9C!lwWrD}%AWun_$YW9qnp8Kh&2bGd-#VxI zD5Zwh>#;N@@tr}R%{1JA;TU}2!!a>V3-!?N=$m}%`lT{LSkQs9aNn)LZNb2x*k@8s zFPXgT)mbrRqHFSh@mewzTKM9MsG&Z@F-2n>>al1q=he=hyb|SteT<)q?{S=9K<(|j z%X~Lv<+@M^ET`oCg~W#70z2+0d8FpD)JDHUzl>d`0Rvgd{26_0BBBapw#*g50uegt z{$Nbg+GcMDJHzh=WPK=VD}b6Ivm-|r7PgbTE`n(g&=PvIU%SQ^@zGxw$s~LAY z%6t6l2E_eGyT8(h0+Z5_*BEybG{LB;(Xvw6w*{V|LxKkLm?6eHVu&>?RH#~VzHt*W zGYC*$_qe|~0Ep?DdYR&2dM%VaqX3i&%EIh-Kt=y{>yiT;jDTuxzKZe;kb|{YFr9pVIR5$h%?WlxC%3~xJ|loZ$?2qR z5cjBn#wlk_`-*hURs^vm&G8^-N4Abn?P@G{Gov#`b&)o)<;U9!`cmyt~TDqc@;WHP_!8Bqk~$mk3I)G(>FlJm_?-yng=a z{jSe{v=W3%!M$T}rSm}`C(ALf8O=QZs$JE{qz~bFRWh8LgAUvfV%tPsu zOm1RhXfm|3($|$J4I4e2rUhA&d8DQC0pAZ#L0Hm*`j=|Pr}`E9s}F;FZVwG5Gk2su zs@Ba;96nk8T3@36V#kJ>=NB|bZQs)mQ86li5zh=;n*5J82iSIJFQY-$oW5!40{mD* z84A&PJ+x~GF(m|lg&>#Xg6Xo`D+kpVuUbT_8ie9)NxUOFHza~!`3IYG%!zg*+nd_r z&>%gQ7>#giTK51?K(N0PjAn=PdJ#{jK#LmXP7R^T)(vzSx$>+@iP_f76+6p)H&aG1j2UFO8$aoI4>;jb(4Q}G z*b2^|!_ZFFY;F5f`jz9AiC=u~&t)>Na8%UA#vm}ZGQ|chy$fkE2Q6(}f-o01C9C!u ziWYTB84!w6_Yq-Tx#mk8-2{~HFJ?pdf>!a>f1~iiqd@h3bkM8DZ!$SV$fyKpHbW%1 z*Tp4e$jAU$4dKM4upU&2kjJXS;FZZFd>i80eeB+Du<@o|p_=WG$fJAghY=+wN@jg~ zX&@Df1onVh?l-seWD3u6viE(8YpZhBfzj9fB_Rcrf??h;O+% ze_W9VL2w2VRPOT!2LkbMCY@~|@P+ALz!(jN;J{bOfrB9iX0RdX{sJO9ff2dWv3{#q ztRf1gzpQ#w#cErCXkZ9m!R2_w$qWiMW8DVDC# z*EoRy%bQ9H|Gd9zjDRSrUO8>}C7T)97lmpB(g`w#3QlwOHGx~B<5tP#3L3C|ej^x2 z5vA?Qw9{>!Ofw1VrJr;FbR7N>7@G?GjQSQ@dcD-kx59I~q6+`rttm!8(dT8d; z{kYLtRIsV}4gYVF&SS|@C5WOQf5ZasmUs|e!te0jd%phB^H$Rn(V>Q_%Dm@@QVC@r zB!Fu0YdvbYRk=e>L6-)Qzm#Ig6>7AjoNt%Vx5gUm_9@jWtdPohlF9?{K`&CgJzvl3 z&0F`QXRpzqWs#gbD{{?yL;aw8?Y!7h@P(#03fBsU#THK(<%-33Sx+y*Dk-{yMNA% zUEX^^)xG*Ns3;6zW)koKBO2Li?|P>h;N#$pTx-331PlK9(ND*4IDuum1QJJ4P( z_&8TTxklvaM=>f)P8U=Fe_&6hG+o6sum-sL-k9K^A1w(bK;qt{M^uOMKJ(X+pFwNS zvB~+VZeSMKPinVGq%00^Q}7COhn&ebuJx*uKgen2IOa;U_@?LY?^5U&j!HJjcTUiz9P1rzlw5#Ty&e{v!|Kzo{pXa$B) zx+?)M0h7pAxaO5H>nmCbug62kc8@b_`mv?V-QIMfyj#Y$kLp@$}_P z!$F4-klW)|;xQl$Fu72TI}Q*4@}aQipiMJ+-f`c&lG+ zc~JCZEO6PNvzix%4CgD54>g-!6^zckwR!{Bp|NsztzW6&Zj-hS;(4;Ky`HJrsEFsq zi`~iBDFBdrTjZM&SQqNiA{bSJ#33I~b9c?~4cAJFeTI}LNfgDC5UkgOJ1^)inS0ly+0mwS~tVv@R z<^d>TVNro|bK_BuZppq;zw>3`O)t$8n`wTsB&*;Zl;H7~ei1d;Vu<$}`-km0*MXl8 ze|axISc}`G_6&)#zK6_M{6lA5n>}FAsDcJwLvbN%NBo^55+ri9h-YVzss5_wz`ss9 zlXHY8_r4`jMVV4YG7{I|!NA30{k520FiEC~ikucUeQrtS2goMD6gEw6?vsC~k6BvV zn_tAoLCH1`hG&&|e;|-iC(qb1WQkycCRF7o$jxsi_+Yct-bM%0@Wmi(@ze4T`720eu9Ux;c ziwAs#x8<^Zs>dxp840MXMVrRYayYFdOQuGcjO>IYhplH|za?$nRtN2dc1;L`i6JFzrc z#VrcUiRG+*#GC{NJ9A8&aR|)NGq;dxdLq)}7*vVT z=4aYjbMr?=%9C%56k#$Y8ArDXe{BZCGGj`{uA!f3nZ(%^YcfA9m};~J&gpWyu0kth z<=X|m8C99*>;iDOns=ASxpGPAT0F}bnt^aqe7OQXXv8(CQIULXvrGWMPNGLxV(Ob` zv380XU??0Z-$y-|pnjS6F3ooZj)mGCM~cBLy-wRWd@Z!#{rt6b)~eHDe=gpi&A2NJ zzG|il7eCsIx4hMDpkrd+#zL{id;50&JnMIP9oqCQ5|ga~^pJ$V(I&bMrcd(Eti9Jy zVt|*MGu*cn)?a`W;p$)=XtLN)tH>TNYIeSSEUCA)pZ<)3Mwp@pxNXuUq#L5ISHri> zn5TI>n2I;dmLs&0f3BS3e-6K*c72O6hoC06li!y;f@ZE>OQTh$oYy_zck>guUJ7<} z=4-6R`+z2)_01f)Q>t~BHrsQ4Ow&@P&!K>@)0|A-Z+SUvbs*I1JjVFhpxM@`QzhzP z_LzCz6B%KTEF(q8wtpU(UJVfZO+Z#*WO=oVuewJ>b=D4AD9Q|ce{_!K$KnmKDsrtY zoChsFWVB($6?H#dLe{4oziJ-W*;G*RbGE{TcAt5aaCb8cb$&(tFRTUu}$(BQFxJYXK+e-g?w9huE0=B~lEUO|@) zZvs$QSj7xV-#FlJOn^l^K@TZoJ`AtZosGvXXaBm@hNixh?T&FX1wSpc`p_V^p&&I{ z((jSV1rrMJ;DH^?;4dO;Pag#9S%UskGwDY7H^)T{KzIT_Vk&naCPT7~kr1v-AV0s6u?e!y^UK1nzV`%HRnUjWWN!Y%Mf@w;M= zVQT@HDa;`;k@-aERjFiORMT1T*VG$PFHLZn?L|fGGmexqe*zCuo`jsxbl}RjrepKTS&cJtC z1gvW~6?S~e=E`cy6eArF#xf8LJnTY6+hy@APgmvb&}4Af25j<^)Is9Hx0Wg)BP&$4 zIG&~gf8OG;I)u%xW`-|;nB!dUy?6>PIT}<%?+{0^{#YN7s~94Mf^8e@^E}nzrh>o;?F^oQ_?hr0)PM;=bcC zreS7oZt3``!aBR{pRQpjrc_!fU|O0AkGwEewDtEFIWV;tteMDxT|Urq2|yDcGuel| zSF|4}eG3XhE7{Y{JV^v!zM##U^Q$n28+lzxi_Y@+etrPNhCCH_NQb_vEMSMv#Y@IY zf8_RiOcs>_cHlz}qDC)Szu2x_)?vSQ1B#ST>;)8Bf3jEr~Ge-GvxynQ10 zcmH(0PP`)Sk+#A4pKlgN6^_qBKFm6Ne^$^(>Ok+fQQnFg%YwQpW*vWGpf9;|#f>0v zCk7}(N1INJJ~2G`!G%$)?#rIf!o_2N76Zp%z<#Dj1?2SKym&4}1(aPyU{=0{4x{4U z5cj;`;X&B%t-tKQSfj!+htC5K4bTul(QSO>>MXyZ+b!>cWq>+HqHy={i%6O5e*unB zA!E>2;+(`Y0w&DCX(E!wSIU2?Vj^%Q>NSZd*yLBcRF3C)S0>bS+GM44<=zjC{qYY8I@ErkV zr5SDW@sMw?oOV6XV5r-w_SMP-k(1*q7D6A?%|pl?;`%;vK;5d?X7OX&woxrf%AdCE z+TzkID!3>si#zcfS-I>2UzA43BcnTA9GSiomA_f z&JGch_|w`#+D9W=yI+QiPK}hG4jp3-I6+|s2V@3aG3#AD_(j-BM~0~|=e$p)N~$iw zZb9?yexSMatm<(u91~e_?XX?vD3ru=$4bK}$mGsIAO~h=z7!fnk+J@0?j7J4OV{ z!4zX|tBWOksrY;_KK;<>@)YTf<=|eFAIoa69{5aPu99DX-%N^bfYHP444-{P}n-RKGrl?7?c5Y68d&|BcooNI? zu2_U>{f!;R?V9CiK;EYxPI;sN{4>z0vI|+bzYQ(`0rmw}WQD*;Kr$+pvlf8AJ*qlA z0?9wBFnyr+e^%pTe@uEMn8c>MO)(r;q(8N`r1*D6@Uu;`gx&*_9%z6=v+e&jG<$$th2w*44f|`^nMb%U1-1^ZcD&wgS8-8wy?_9 z;zCYhpcS~Tn!K8EW}DFq4^4-m*NRePxws2QXL_F|VkYpff0m#`6iC1j(Uw`QCQd#}JYyyo*tKsyq-AKPu z2>L^z%@;?;4S#`mk|h)u9ZcGstqOJ+Q8dBg$Up~kw-2Gmletk9XHR`nY@d(Rj>!Z* ze+wmrvQa=4-`!KZE9D56kF6OOZ-!Qk>U27{UTU>YT9wLs_H6DsDoF-N13-lwc3Y_Pf37RO`*H&`4FD{&scGp;$EpJ@dtH=s zrgUs{BEN2K(SRy?r{$KI(vN2>h1CPTi!OcTUP9zPk@bFp@A6O2@3p^aaQHlJTF3<}vPI zwrv8CI*fT-0XY{yl?OgCdB9H{YK^8+U}ptN2{=_8bKm$@2hNt$H`)k#=Jud&e-DwO zU)h(!;VCH+fvqpos9ZIomXp@?#{@*hSkPzNzis&Ykn?qnSK^7;v;fNnZ+Xn5hll>~ zA0mAc>wRH8`xVsli@N6)VuHByTVkifj(+Lw+MK}g)d&Vbwu)AI?U~*~N z4kwSea)*V}PpX~^s)|e>yYSgTi6}H%o6i;QkBsp_WL}rQ%D`t!9&Jgp?fPXr1~NAI zRk7&TD2@nI1K4iXcM7u|iYb$}uug1XorxW`aKiZ8$;@!2lMBIP@g1#ee*6RpAS zl!C;OGPlFjk-6e+71%lfX>jvG6hU{JI(&0S10ob5$G>$b##ml4{n__n18qi(;h{&N zi@oIF_ZKA%ji4gOh8slze*lETLfo0W?DWpsQ-B2YT}z7G zDf{@Kon$ftl+uBv=-tQNqH*13Kwv{tenXZMb$ao39n5I;yL+J^X~#wE8yMVJoPi~ch6aC8a{nuY8*kxfArq}W3`v3?5u8vHXXGS z?Q!3Pe|c#&(rim5j1q}fGZ+$Y7w*fDRUgjqP{2f9`kDx(-n*E=m~S4?WGa?ehWG9)?|(t$^rgr3_U1_ts7`dBv7c z(E5TFmDe!^sRZg;Ip&*?M9EL6yR!33P+AX38h{CkYGZS8>n6td{iWihUIH%omFQ*Le;;U6E1XA*XFbj=ZFwTW zh~i6V2|5}^k38RBiXdd2Z7FRBM6wyRVVMKSkRw!H;7QDFIKa3q?6+?=c(tx75o{iw za@f7=nX+m9RpUnt^Ao6ll%+iQ zufySHKVNXW@~6hq9oI|+h@F+b?e}tA#;<%iei?7y6F~z8@z3>l3_|Cc6B`1o360x{ zU#x-6?(K_Zdle!=$?8w}Y?@VR&q3m|z))1u0hndRf074IGy=|B)g4=33u=XO`GFF1 zN(}KE=`Lbw%=lH0r%sM`=Ez|zO0A{Ued2HVTEtLTJ zy?OK|@S2paZnl?!gbYr3&~-#Qfe@hjz3b!7pfp!ivY|nEsELc&SewPmdY7&gT z26adFlly3^j+m4XxJ4{yrZ}3B;L@{oCV=vDe?7M;`v@U5tt%L6gUXG#RzmEEP!TbO z-bHZ{3N%`V>GEH{@O^Y_0=YN9$-W0`$=(Uhw-- zVgewh@2p0z$8KI^W;p;>s*mb<(@O@(i; zrR;_`IUjm0=~Pz{QB_@T5qB%|FPek9`hfWE=W4h=LEnv5}$of1|hwq<^wOr@~yOA{%)H1|J`DSzfKmWr_X z!Bqe@x~La^p!JrqfuhCIBL)_GOnySRlqcD@jWOjm^%~Q!bC3GIB$Wh(f8`9+u_lpE zT*DNTE7t`2w_n)sH#19;Mm+_f0;a;^#QlYi(3Do~N}4$7eura&3!eM@)25|){<7SdOD&rg)PlXMOprF#f2{6b{~o3OaL{|;5wNB5FRT$Q^}BGzzQiUheutRjI8N{I z#>|*w@uqD!TOIuVvMbWI>Aj2?bVgv2Q54xS(=t|UM0qhHBV!djn8xYyaq#i2CQa;w z2>Yqo^H(5Pn*{hU`k0z&2kho9K1e|egHB=Tc>3iF8= zs8H!^I;7BuCst#>jhY6+8~-Aue9@Cs)`T)H4b3A;%n{T(KgjGNR8i?oBK3APDD%Cz zCYv?2@^|b64TUy-lX3YY4S8u&SIG%N!NIO&b8}{mj}KCAg@5CD0GFzj_#%~)82S5J z6CznEvXUvT5Y$X*huVVB%^x_o9>tp5A^W%y^6)cSK^v z_2O8TK|vgObF{$cR|&9e^=X$a2YKm%wKiXeeOK*DYt~r;c0xbK^&19>wT~bF0P~_~ zFVz(=tp^xZf;_y$<;Za)xc49n^3V^*6U_X4LtQsI8;H9Ue{PHXUfFE%BE}KI1=^!u z{A*usZ^dC-dK_cK8Ve<(awUOD_GrrZpAkp=-zO+r_DSOyf8wxGqMEHx0jw8(#<63_ zG81lhErQFcFwUVaaCaPO+mH>|wP1~;!c$+o@as{o$k{5+xWU3l{9|Hm!WOtnLsT5U@|u^+nckH*vbj zv)+%NCBp_H#rG)w&FVv?bcM) z@SuYi&C8&!s+Wd*jIRdiLG@06^(> zN-=E#*YVrtU(5VrS5aaeke7!8k53L?j$+FM&zfh{eLukHuHjb(&jXd0U#To;Rxux*tvjF-iIINfp4g_CX_e-@Bkm+qNX#Huf704aVu*vm?F$7Xv z6>p)G4Qca%27jx>!hryQ?{38FzNeOYqWk-4f0<64#+*2m33^WBL|{~iLQv%Ue&4Zz zieK+TfKrEUP)^+74ya1@kYC=~d?z)I#XdQMI$kDEM;`MJpm9sogsimgiz12H;5fGQ z2(5e|9Mb0ip4x^ng)1D-g4MA!3a!X|2gd9g7`MtS+N>A+Wxkrl{SOl9ZI3~oS#}?3 zf8L3Q#l9tq?lQ9RE#vbQh@m#leskdW_8Ke9ba6+}CG|ddphQ5IIDMnSybN}%wlyWH zZ9!h(xzTZ`S;l~Z@7@e(R1$!39EvG4%39z`VVRdF5Aj)q1-(r!xM>x&*JWffm`d9O zh@S(^-zoe$;`AwVbicx5ZV>?Xkvy)2f7yH7x``#^3n%3d1bBmMs4UDyf?t$h={l6B zpbu_L^}&zxTaPkm2q%tFMj3Qu!yPfIpLl_7Z;b5_WmA-_Qu0bSpA|w5(c~FvR)D(P zjz&&=K}^e{S1ij^Y0J=A6>5W>S&$!IUh>#=fha%&HUz~`h_dkM9yp(}RuL5we@W0w z)NH1;6WJEgk}G;!5~CQQ} zz`@qPj!Mx9g-@SF*FkA^pTDgBxPM#`BAj57qlF%Hvit?8dLCobebd`7-G@ zghny+9sB_0d0|DLzE6B>_n|b!e24=!I=*1O7F153u>pqKo+w(r6o6vOl` zhep2n>)E)t9s$`yTk=yLz|_Ot8vBgoz!1#vSn6IcfE6%&5Fa%r;h`+me>>+NHfZl~ z(z5YfX3Fo#htm>?wb&f&=8h*Tz%PkM9WYifM{OB&()y`76b%og zO%#f0y|hYd4IM3mrEvB3jkCu#p;GdA_7RB^dt%rXIh)a~#65SA zJ!{7k6aEks4dh|EEVW|;o$j{b7*|)fOy7BFDl`im5wJ-7amXKxrN?5W+Ry+B9THRV zLGzb}s+*nll7Z|#f1_}&hPEZ)WO|0njpBe`;&dPYG6k@$m}RxR$7waI@dKPv?Fh~{ z(T-H{u_Dxp7jV9&qEzUv?kGH&U%32?(1tY90qyn<;p*Owf02pYsAOYgEEk}Ab}Esd zPcsS`G?U;gU*&S5ecxu5C4xc%g6$4M+q?W^w5$}?b4=}uzxS)A@_qvyzfl1BS7y->EkajPEfg z2LP^+%+-%#f4&=d$H(yZtf~m;W`+oO0QA(m`yQ{HFD>1f5%+cp@2NNJW({shZ# zEL#Is7&(@Z*@fOM|?{E3cFcfApKu>xe$e6dY}Ic;Bt(Aw|-{ z9VyjC`o5~{dyyxmMn&)ty65i+?9GSDXlbyZNMmhoW8(HH}hAqP16q_BWb~rm{ zm=}PlfBEyPh=&&Ydwv&tm9X;|Tf>yli=a&NChs_QBA+_K01YG&j|VO@8OmwN_ux}N zVeQ--oeN(~DF)WxvZEh9wBrMD2*{r_k2#zyzVc^)c>iJUv^YpmHf_6$d-^z$wgCIB zHGwMzD=tGe?@_GUjaCm!{dkabA^!PD>|E`s~Hd0 z^p03n*?)l{N;LL4VodN!w)zZ{K@XRywlURc-H2tmo$*0FN@`5dXQKlo?08>Pz ziwsJnYLYWs&9zT0Up2UeY4-AE4;V@wUqXaq9?I#3Kf#Bvt=w%{(Hlx9S12# z`V{h;tLMn!xA&r!nAf-Eb;}#7>~uT7?><`qra4Bzhob)@OJ*X5f{sC~I?BT`8Mr{6J<%!0Hw_>MUD z{4nB|xXjL4ynA3<;kCOM*gyJ^*whbSR2-1L%1nSs=>3-Yq_c_8o{}W`=5z$0zOtIw zPvH_zv(7{&Jn<%ZP18f>zr$Xee+)H4E%Vd{8M@hjknDveBLKVy>f!b1-hKo8@V3vA z+93KW1UcNzzSv!SO4$} zH`cs{`}jgBz>BMiX>UIV-1?lFD$4H&K|$U65nxD@FO-n!9K~)j{YWO!~%Ry8QkwBmer8 z%K@xe^6P4#y=gtAmBR*qDvZW24FmifJ^%?o_P-6X1GU*^Pqzf>Ux!c6JPW|UIiaO zlAo&_2F9)#G=RZOh8^tUW^#<7IP3TTnP3}q2K#20U{{K?lOdkve5Hr*- zH5D4QkNJN1y3jnQvsnHb@FNSBR!?~&Mtr}&(c~|x=a1>NX1RzV6KGZ)qm2^og(U

$kDNg|7XNDOiRh!NpIr2s0}Kg_UweKxol(>vr!p1@89z zVvV!Rgsvb`2CQR|W#YT`*=uR8*M)47qcZ`(@1dB^`z0CUX5=HU+Q!bHI#C^LPR`&e z_+ZIU>hB)(iv?D?f>i^z41cCl=}bkTe$;{7`fay(`FZT3f5MGLC(UelTAX`p*aSxk zB%Dj&irEDT-fTJ}qTk7oa+Xfg1j3yo%zkf=-~(dMKD7M%z3V3X^jZhjBo-7|YU3}P zyVGj>m9y#P_t!Ub?=T9EG%sN9N=kUyYjEiC?9+9XG}*I3lH+|oD~Exef9Ge^!>;7f%H2d3>um?e%hFSBp@e|tl-2<9S)R>H^ zhi`FIqZ+bkoL7VUi#0esoguQ`8`7Fpm;^Y@W4S}oA@Div-yuewyOhzYT;b3p-n;al z4b};-yJc@Ip1plu!s&s+7)*u(P+d>KeM1{FF6?p$f12APx6qw>?*RqHwLWA4E?}^0 zq%uZ*yZe$WQF}5YRuKazY7M$C&hQEs^9YDvCQQ?v$q-~0Uk)goK%Ag!k=yo+>J6oM zhB7e{lR!=uQ~!nDLlgPLCya(sz@4ri=bjJ-dKuSdoK=p8`$afEU z=75V_jh)nBwH0XdJ+?~34GlyHi+*=lc zoSHy3WgH~G(PVx6C4FZp*smZ9+NuMTYZxO!%(Yo%RtTd}u_{(%Ns^3^=!*ojy=0u- zmgt7gir?WUIN#eu0J+s^I5lS_;%OJd5DC^Oe-$ESQe=%Mq-#!kcYP-4qg7vG8n9AL z4k`nsH$dk|(!BGG!;@TzseZP6ufrYVqs*gos5DYjH&Y@L2PT*)sW(0`aWDcvyawFs zV=5vxna6?IyJm0>st_ePSmhM8O~i%H?Hj@T^DJAfaYK;tvNeo4R|XZ5wR5GzUmV7< zf5uy*K2+8)m&hBbvJAT(5#10+F+j%G=5xsLg{m)#w#L9(8k&a=-0P?iCeDP4RlS6n ziH|-PJq-}XOCFb$xFnksZ@Ngz;#muvIiy8u1XRtYGBj@ey`zP=1~g(%Y!!MThUM@g z>KH(~nprkFShNG70P^?Etg@_qnAk6#e|Qt3>lR@!p6Iu6fEdN?l?L8OJ+4RLvPwYz z`g4FjYvVkS=z=KvRfG|60i-(BFtLMe$cR(Eu?2{8y91iSwrxzOxD1DfNsYt zAeP)i4oHtoKKZZr zEDC`JqW<*jE$ObcID26lwT zVnYXaridx!#GOHv%yyy@a3|&OA#%C0Cna>EvjqO_-MFCoIBXDL@Fw^s72DaYDEgN3 zx)dgtA05oOZ~x#^1jM#+8y8HDe+Dh=qX2Ni+B}B9}fAIwZw4emQ2c>-b z0T@dpfQ8Z?7$yOkIV}7LnzB%u+lvPt`xEl`x>CwdVfQSL)Xe++L z=kg)YF9sI4SX2_tf1;RXz*?mCG~ygPaXD^pBi;ISQ_2OU7Lo?JPnI9+&xYX;;falU z%9kV!y*M)Ta-I&;$Y9aXGnk9*r~VGuO}61igS;?O^+#`QlE9+)Bt`U=+;JcIcZM^0 z;E*ntXfj1mzOq1SoziMANQ8qt+{3VoByG2(82Ukq^R}3ef0Ih9v36iw;ki!MYO|m` znUeTNFEtEC6#Rmb;dnM5iDRYMHcD{>FS;0pDH)*?Y|p7G@^&hrVZ`~jwhKtjb1)J) z^uT7R=5KPd=xtB(^SY0x(4>?!lW#sW?v1{H&)w zzOBN#Q(nGdf8HaH&<@l{yaNd$#Lq$x=#@r1P~?@>e^;{G6S?$`yB=mvgaw4leo z+!#FP>X}InfutX&MRhmzLfq@EHHPCQ691(>xNkd=x%vmZN&v@x_w2bCjGBZ@qrbdnOUvUyuKidJXecw{1F)s%+S@q}vQ_xVt&z@*#n)8l zV;GJPRX)+?fsDYOx5A0QI7DN@B(dlL4)R2Yq7+RWoN?2p zw27m!7wXb2z1a3$<-jorqDE+#`A}QWB^z#k(LR+Q_)`qjJBsk=;7Or>8iipVZ~eR) z;56MOSSNCBdnP>xY~-u&7#CFL&XI2}f8di40?-u40snDy9^0+LU=V&F7WB3>z4yMO znhvJJ(_eB|$vGr8l77v6Ly-Vlom(=y^FfXTB3dcBSjvmlZA>IR=~V$Qz39V;WarSPIFmR6Xi}rK0krw|LZ;AVZ}ZC?KTo4irryvjiG2 zdJy~~M6#rwenilA#G84b^8D3Ef7Q*4IwkgtU+c&-K>}^}I>^)b7v8guO>9^eKKQ!I zcz$@%bNejUF}$h+U!Jh3!JL?!Zrc`-I6G!T}N5usI+=mLFq;D-8W zC1>&*juFq|CaqAoYnxhzEh!E1N=2vfU|+C1XvtZ9DALP){*y0DTf@XESsYn+0|n|D z8bk01H>33A)xIOo`x_}`e`WRk&QwkYqO_kpZmKponRl(wRolTd$Ovmuau5Ijs6-Xs z19IIgOnMJ(lf9;cr{B?xl7PH{Ic$>*h(=Xet@5RS20ZFn=o zJL!1fo2?VGUPoJBbJ=tW1XP;GlK1HCWnOmLw7B)?Htf z5Q-&71wgHIL=!R)*;5Ho4G_lsdSN&kNe735{T0T)dS*-B{@e1@UCVdg%gb(|CiB4Q zsY0s0=FtcIf8`PgTZ1@?sFS&3;Lim)g(y1PkN>Zf==xrnwD2c31n;h9dqww7E|P-DFLp4xCPgpM(Qx$W zHI-U=e=Qi`CKYcY!zrNZ~IE>a8^BpWC)cbOJC?BH+C5)3{-C z%BV7I*Fe*$BXFPWNCNjbYH#4EYIHrS1_O$nL*F>p(6{6X>8WF6zFQOS5$3+Yf8~|! zsGV-DR>Y)+jR{{LVa->l#kJat&4Z9})XnxjSxy!5kt_1~N!?0DGSwbt^&zrhtO_xa zZnsKgS_l@cM>or>sr@)~u?}Xu`mH%%N@^ZDl!L3w-#wwc?b!_@WAu1lO2rEMdfX^`DSVKT&w&=HT> z3Xl^kwrq(sI$EDL%ZdZsUJjpeji-L%OMj~9YX>O^^962^RrrwjqQb>XQqSOz8V3ZM zEc@}!!gW6!6a**UGPXtSHp_m@D<(0P&8X#QzmW}++;j#n&fU8=%P&Yje=p!%H$F?* z$Xf$&g?6#;`-cY1*ZQvUZp)rL&`AkyxX=<$yT^pC(;fA!GL1qKV6&hJ2C3|mjEQS% z1d6NE#xXC-lJ*cQX$Ua-Igs`x@CSyX%;w==+Vw*yIUGaub%P4K5SPr ztUOO&o@MUt%X*H-#tO^l&n!Hq^dMtI0SJ<3GiW8p@p|meo8N?!O~3R!PL5?~<+qua z`TqUyR6LOx1wc>o{+65};bDM?BISg=>DBU^$x68pR;Jc~gthb`J52ZK9jbs!yhyf!noR#;6n7<%$`sy&0I>0z+eRo$| z2fTaH-%8f6!v>GEf9vh)CW(PLXBLD0t`Uyj*U=x|8=F~`X|cFU7|q{_K%^6zmwASm`@Sf?d5I+#d-rH(OUXKC_NApF*{(oXC)*hu79W{ zcC?qCxF5A1%7$9i*PlZETGm!d zXaZZMi70V7e^86zw8qDq0~V`Ufr?oXL^h7GM_9Q`T{ZlS}?ky!;8JgpeHd?4k<&jz8d== zn_O4jk)t6IP;?if4-1vu@_h12?beXHs<;8@&sC>ff}|pKV1Lu)wIsXSk5S|Dw|uys z0ky{9Qh_u=b$1LJ1rY-)%4n(8Q@S8L#1W|y2H{)z&bVPi`)=Xzp)sss|Lwox#~Ru_HKjBjEIr;PG!-E921%6M z{>JkJYrF|u-hX`H6Es=HieP4LhyeS8tq)FE@*>!KsITL1!f(|rlls)imjTu_6* zxJ#ox92hB&Al0R1ZThh!U^tmnFssDb-SX848}qZotfu5876^t{vo}E+*60O^>ggwD z>Y0UZ&drsKoE$QCbBfwt+Z|@YO!Bjn4>=-~K$xjnY=6q%vrO<`K$HN3qSqUYc1tDd zC&0!2$4Vn-gUeRe$l%3WF|M2dlFcB8tJEwQXDhJSYG6nd<#vHFj4J8v*p|GWkrnRu z)5fv^OJIww7%Z)et*G)?30_{CyMlAYgzd0vvF5lCb%Tx^2cSrSI$}uzjZVSzg9|eb zcn2YxaDRvz+-YKC-!w3)KakzNu|F__>Pu6`;2h7BEhR39><=%}V}gkj5O7+|m*zZt ziu_wX%$QNI;1EQr4lB0p!M(Yd3u^`uqG;3?W5A#=TT3rJ)Br+HSf#m$yAjxs3-qF? zo%PP`_w`Te%V^h{{g!w5$=1LP|E=c);sc6`NPh%CtC9i9zdd4k4FZ4t&u5bxURJ>e zm7hCrom};;Rre}>X2;ms$76uFJdRXSf{UkMc7Csb)Q^?ZB;H3Gp_{3}?fOFXB`w0o zE?dvIk|OUQbrU{LsYKuA^#)R1K4rS!(E&A~F*@p(6|U==7Gnwd#6K!!18*S60o_L0 z@_(?@K&T3^&Ikr^trwpqIY?>jSHj5q^{^MMD}z@RN(d|6dNqb3WY;y+n^T_f7g3M6 zwiio1se27l5T^t@KR|d7(t$`8%d5gM+wHdoD5VN^&be^F44q9~12#8N^$_87UH7MD z+Pc|pPJlQm;D#XaE@5oymTpH8=$4!Lk$*R8{;k);y{Wh&ksaPn95RuncU(Nq(MMdg36M6aTA#nnAWQZw9#95%23GRkg6J={t9SH(-wG+HUR;q?ok@E@`<76V%%*|<)dGE+1EGk>cJ6CHAbYO|J zLar^+%=?x=Z1J=(Mkm02KV%6DmE}V6r3Ew0$5uG;UfUwCl3;mrY23x>-EwTz?=X;R{H-fD6#KV}7hrjfh z%9eN(sasqQbaYKfET6~?n}48DZ|EOW&CvH`U{c+G9sHx^u9f4AA9uFSPmn9erwGeq zj?oW^^GF7aoUqw++^hReViLLKX-aQPO4}b~mT~*#<>9Gz3`^54rC-TpJHhMyKZcl3 zWMW6}bqV!qvgLk7U!6o`>AelQAhq>y^wN0VUNmiF{D1Jzt%(d4*IT_A z@f)4#x{0sp6KYu=mJfV}%uI&?k6NPhrs5xDT_FJ4bg?ESgysf=Ega^&MGSk0OxVS_e5?Ml;pR4xU`72a89VB1fb? z9FeG~)Uo#&i~QS>C1)v}8Fk~XjJ#ePT}bwH@DZGCqpQ^GX1pXqaz_(LW?0zgj5oXi_{p_`2>WM~MO-3Kqk4Mt*fv zFL{f<2i0zp12&9bKt|&S9Cy>_r#BR5g_XCyJ+PsgQK)1%_TN!a2&=~}GX^V(BCJh(^$dwZ2XT7UZ7E-^F8kM?tZ-p-wVq#7gn zNSx3u`EFZ}$Jbl*^Y3v|LA(KK&QhzyF>dIgm_pS^eArPSl5&v2Jcx{4E$FK`RxmDn zS1f3#jA4YLd`4|Qv%R3p(=R=G9D5T=>_D+{pGV=ehSG_)$8kP_cdH}t`fviQ06PSh zqJ0ocYJc_Q_0@B)Bkg#jInBMzqOmt1+i0=YTlUrvg*g?p+SR8=0>Si}#j+)0`?3q# z%=G{YgG_`Oya38OCZ{1TX!ORLwil2ulr^Ak5@XPB1h9TYR{SRiuW@j5CR zSAUX#+GfPQpbho>wO>v)?R!fSXeS|ALDh%P2w_pp_aqfhWvDMf(3c8phE3 zniJ_Gy1!ndDvE4utlLx0Xo zmK9h?)Ig(B5+|oz-U79$wmQF%Wr~W$Vftg!x+vTL@j}sWn7@PP+?tGmv4V<4_hana zv|h>pe7g?$yCCm;b*mAD81ErqLxa>{(a|ltf^7Uro5neLYcceo(8SK4uJ}R5RuEbp zK#-|^s4-g%2Dyy$$7N_x6nj7uY=4f%6CTarIC3gRfQ+F+l-NNR}AGfV_sNV{jpd2wMb-yH@cR7pOCZ~JfUdDnD@ZmO)n{gaf zF{ir?&*w5WlES~iAlrrIt$#V3U_KE{fkIEy(epj+jD}DBDON)_kvm<2&&40RGcd}6 z1q2OnWR(|RAd%}%?w@Vm+_n6grVooeUFHOi)ez4q@`4WJJu+LHA)23-hrPB(DG#(^ znPtx-oJl%M4cKW$B7)q@jp+;8dXSrhppubOq#ZZhxuCZ_Lq}APV55 zjj{igKKf>~R$P8VRgt-W-yL0*^f8c_q0l5nx^*xm8M&u6!$MaXk_Cg2aeeFIB`lsd zSWV6G7&X9)}S;(N4Tb>INc{pO`6VpbO#N_h~T9wocm_3Gds-C)^ zY5XEL5{k-A5ES!(6o1{6&I1(QU4qo^R^Me@EARFX!N&l~Z*)TO!KBtJ0R~-y?;mb5 z4KImbZmIylcPN0|AHKrb;rIwEs(i>4Bx+CES)}y?YF5v^GQT6kp!53^Z0!J$c*}yP zGQ5&GVhG&^?nRKHqjwwXG`oGPn&*vJ3Ce9_2(agq1Lie?pnuwLv$_8G%J=SO7qI8D zz*@=k@9D0^inH5=G`a3&Zzl^&RnWFKND^(U$52$fhMNGqzyxe59%bSbpy|k9UUR&G zK@DA1IOAnyiwpB-;99SI7JL?UwCVwH8TZ4H}UVR5&LPUw~6EIa8zt7pvEM)Sb%}*hUWv_C;G5Sc^wtZ;T zaBmD`XL)S%(p^9II)-6Ge^5GGPR9j?h4Hi zRdU7I=~hf1JDIqCTaiMwoS-TOdLj1_C}7gd zo;V$S$;yrj{aYOfxlmXoO79#(GZ>}8x1XnDkij+>Y!xRKmOU10!|k&^GC2StmPy<) zW-1Uz(|^?u*7^*J#inTTfoTeHpcxlbk{*}Mkt+M+ndb>+**TqGyr3p+IjC}Y5@@Df z(tW-Ju!)K~OI{pr&gf+HI3)Bj`)>%SLFz=aK7Mw33M{mqI!{9I<-*Ss;HXxM%~s z3<434t`LL#063usMJ~cX-9>gY%c#=Sy0ziOefnn%kAH5~$xVdVa$=enHsxWsD!AOr zc`i;0P)lttVf>ii=a=liW~ODxhpKW|SQKH_Ga5!ZWDbYh=jiVpc8rc9S|2CNhUAwY!m-2iHKEg63PprYKk8WeBNc99t~d@vC3}Pth`{d_q9sSX;jqlX zPqs@*5pXY(;lNyiI^4S=1Jnj-rKpB4Lf+9%4<~!Jra?7EWY**m^hvJ}KF=VOD6B!@ z6XMTfWY99qpm6)!p_Vb03`WXI*J{y_vVSqF%TM`)OS9!jOWH7*3k?BKdK#ufkSaR@ z&N{N^<8vH0lQ6{pols#^<;VH9%QBnQyQ>X@7v$DRcC zJqVf)Jdx8xlu?$Z7LmWJK29$B0Ia6W&862Z@gA0`QNNYccnYo+i>2n=VHplKw{i#D z5lG`e5n}o~yX{8S?Py{I!rBoTp{9HqFI2#tY@oboAcbJK@qFnj0Tsr^x z0Cir0o1~jd`s_L)KT9ZGVT0h>9P1U_yAH)gsHQ~gV@rmSY%iHly?^OwXH-&J7^9rO zSa1WU=JGquaYTQR6Tp73?3RLq1drpiwjf5S-?bcR*PtQr)6W(Uryl+&+mGqrPcl`E zz)fQHpYEc-`5T69Ab&pW=i~Yg6KLm3%Uz!V97{fU43k`VT(SN258QxIEiTs^(8V^%7 z92*>c5g@mh0NBpk256WYw*uv@b)=gWafafNzIwUjtCfW&1iTH}PvC7^coj9^epwFM zf7M~2;+3*}#zzylC8E*Cent)PEv>0e{`Rs0^f&LByJ|$dwj_R#{@&nj`VvSmWffVI z_165|ee~I@%zrI#70XX*Hw$hSQ4S4V;KIAm2AMhp-tzk#cidG<#doc;PnNn=D}W zc4K-L6yjEHBxTJb*#*O6R}nv24RH=PiEWB^BaQ{_(tolXjZ*jXJ!&%|#cNCMU+1$n z41AJD>rc*)YsiO3-&Bj`I0<50gu>sg&J*}4= zS!}KTLqMH+xMOtK1oVlW77maQ5wL!iwbGj(dCcru2$Z_M90?D-_Oev5QAeuet&HAZ zxs#oBmoEJ|0=#t&kB>*3EF&x4g%?$eSi24%>VI((zc%&u#FrN8e%R6b{Cbu=Wp4LT zve!@jX1SyFo_nJ4v}?ydvK)#JygaR6#ghM8M=#mr`2CnVXs0s`1N^m`Xumin!K{T} z3jK`%pIGNO=O(jBmIw*e2fG8@4?AUVZHH90#8;8Ye``^Oc*dJlUj3*fUg=Y;03s?d zvVQ@ai;Fz^nM*75pv-+$tllc0n(}o5P44X?i1<8Q+v4K)&BJbT5dibr10;$BYHzy~ zFw|C-OmA6i03xjmB*P0YBMR(pekFFIeyN#gajpMOQ4|*bQ}}JZESWo33)#yT$L}X~ zW$JNb$Rg=&$z$7SM{`ab{#wOPrVhXBLw|iFk*vNl4giuvuZXG{GI(aoMb)K8X1sX8iCNhcTf;P+soJqK z=pfHyG`PkN?|1Bz-sA>^^A@ru=6^bUDacgelIqXko-Ui!3%tU>Wa*$08=1KkK#6Jq zu%3E~x0Np^TXMgUyIfvWt z5$!AsCl4PLYQp^vP}?@PI;zM-PQ>+sL9sgtD~Zu9$QIibcRkAG7AT@JnwiWYw-x^gnd%cS0@<4H~$$+0DfQr3H8-s>xEX;2Z{ZLpjp7^?1ReyLI2v}a~5`DKk z65QML}Ne+|mnZ)cq-fr@o&&1?8@DBVOpC~D~N@%S{1a?^5@8`~R=kfIDOIAEy=i4&1u zhnSzhDO{Nkdq)R1Xn&R~tc`F4saHe{jQxPDh4QyPmMP{vxD9o%N`&lK4c705ynpGm zTrvEcs_OH&T%>+p4lPgPW%>0bNUA*}ANlnBWZtgnD!--8Y?V|>qIC?@(_7;*wx9dd zz8TKgIFAAMeLZf$atj12i}HWhX&(#y`;0dnPf3_nz>Jxlihn=tspKybanoXLzjX3a z7j|PfyK$_+h6Q_#b*Cgw!P(dMwBM0*nqemFS4iuf?!Df1WaTj*D5MIS5z%T@QQGAk<#Dgk)Bgg z%Ja^(2gwbIVt-UE00E<@oNEr>iS9UX9-cXdpi~OEb@*ru6j9qV^hk*DO&cUk_OX2RUWs(KI2oCsl*8I*5$E zxn=suLzwbwKXC3e{?AM`>V;K&hhRHN4n)a@lxkR%R)3P`LaO5==fz+)#h2_Zk)hascRZ$RdPZw2jQ3y-OYb-i zTUQ3WEPw$v*Ov#|fG{cU75)f^3LhmK1K&sKX)uRRssMM7I=Cyqy_BleBAB{=g3e8> z^T_-XGJoByznRoay1ysD&J&5XIKTDfng#Q8TrN`_Or(^MW+J`Tk4so>^P>VU4v-JH z3xMivp5mrzQSK-v8dXTBFQ08=NApAmk!aN0;lA7!vo+>c0B}WQt&_m4&?e}k=Bzh zRXTOfT1g6fm6hH#@;=^7x|kTDAKr8f15$(Pb6Ys*mNFXV4FAFw4 zchM8y+jyjuC;g7n=>AZCWAbTeQBqKRE$WO0GyxID{j-1|rg{%lKc&D6=3x^EUG2W~ z02;#3q}z{CeUX`PN&ImAidEvYr`}@f_jmTGPO`AD?Q0e`pkSMSCVZ-bni1MqF;H z#^LG$!Sw>5>5tsYnxYfgtqY$R5jBp)+j)_`$>;W~1jbK`#?!;?L!hS%uvUO_5q|&? zD7WkKt`-M!=|e(45U>|T@Ln5s-(2z4qV%(t8YC8T_)&-l`Q*~P(q@MF2oK;SCev8q zhHc{%rj_71$*?+!5S%XBXE3>_5QiwpRK1<- z^ycpP+i)cn7vPw^a$4P`S}j(N%qYL%{?NR`$O6~nP4)TPY17r7b@4hoD)iDJk5K)5 zuDe2l00!T-3>i^$;$Ng zcMi^rkqKEHSOS8)c#hj0pr)%k8v2e~4}_9f?gqht9s7r>G$DLWb< zU8ApI)APjH*ELY=Q{*}Md!TTW0X{{W4fcoVpe=I~jD{!-z$9G=Z_+kf=bh{njBuyYFQG>PCIAGXDD3G0f^vyk!<&SS7I83c0p zG0jrrfEVGMy)7z+wyd`R$@T=G^}-0}jgHQfV$VHF=ts343IyQ4g<@HWU#UnhrqQ@S znkpsqY z2T_Yb9#~@^3+Y7pN81GKxH2GHrQ9;@@kz-2nCc$L>JG}0ITAqn6vo9g zAs8yk1({2?%Ly2lhJTYSuU?%lkrMJSRz`#T4Q!zPncDM1dgl0nE9#Q6!Om)_wPxmW z3(EKcMPb{T7u>NRgu;Zi+ThaI2QyiE)cum9ucuKIySCWHw!7eMV11@CnOh%b$Bf7u zo!Wo>(?u2V<>($Tc5NXXqAg!KSFOA8%^e~%`Rqgid8b+QJ%168<7**K-$XWc7W)Hn zOGnKZ6#sJSHz-0lN%OXRxx3jbq_!j}<2S2)P+>4`5}*#urnLajEf>zSJJ4e&u_P@6 z%5TEcW#CGx(i09qI2yIfBzDwCOu(>=gbDmyR?jEDpT;|RnusM80O@2SVn}Lyh8S#F z8!SjcA1ZOq`F}(P;dyB}ilQ7ehRY`fwU^j(JbVAx_*gvkFhYmgCMc2BK-kH1vDV(> zP_TO3AVI}A#sH)vmx(b~*t>(?lj2fV#yWca=U{PA(*YjHcY7zy!-_KkxOT~^sj}U+ zdZ-$irk>RZz`ut}=CfITNJP{-`dZ4d#fbX~v@&irCx7_MqlD4D_AP>swDGF2@jj*;WB5_WC(P)7nJ^lIS3S>G!b4yZGf+o@q z5f`Iv-(_XY;dkW&>yDK$D_`*3qjzF04Gtj}Cn1@Ua95chP!TNM^Cni!XSw}7jvy!* zb1e)%vVV*bspd8M)B_qBS_jao>oTHA#c61G{<_E+EQV>VY;EbW{f={>4w*H7lu6pW zXfvnX-M?vqa?vc54)EA0idiUJ3y)nq?8Nouk#bTdNnf^S2n^58MaBt~@ z@74h9@VNhg%l`Uf8>CK`nvZ?kxD1S&?RuAAS=qjgY(I@2cULk$5l1w}OBkwyc(%y>@*=;kPGlB}hW(8c6I7IFMsWw<%$QhQ%cYsL~A65SuU6CNs=PZ_n zL@+D!_(^liI<#&+>}7LQboCPg=~xI&(MrY6vJ_fKe_L@k#@C3d?xRZr#XwksVz_6u z_azCKYejZXnb7sxMj9F>l1I{ymlI+Sj^=Dmc=S&xW9rt?N@)TUlz%+h*q8hdE!icy!;?m_sdq^q5I z>a$L-Z`HWhNiMP5s(!K`a<9?fTbIw`%eDgHMp;{8QL0`7z`yQO1X5ojZTcuBPK%-& zQ>sx4s&1V8wQ=!YHGj~S_?D=F@e`O9FnoBttw!b<#!K4BNz&w%?S;SHracFTBadUcQO@r1R-4#@o85?r?gP zG$K{m?5(46Ii6Q9t8ytP>N_?89SRl~V*%*DTzgK;=W#D?{D0uAeip^fw7)*z`mIpx zfiY>45!kf&dX3WVJM=hPq9YuGwR^pc8=KGh@aJb>hGH)VIxfw2>}yUS6bdm3hRFiRl=QkmHv&d94wDqkjP{)j(1`jZ%5v0F>@cik%8H zrK0k2oR$_44{u}C>ZVai$EA9)U4pmwjq5N|SBANn_oKg4I8K#R>9l_wowt^wKoCVg zh(LHyi1*%;;k_09>zCPJgE@O~7ji>7b?Hx6zxiigg2?f?;N;1Iq`3fmJ%eHysBgM;EHibT>3syfk=D zT=WCP=RB5=yU_%!;(ZY$;fV=YiCNs&kWa-|;(vCxyTD?OcrWm$$xm{t;^mYghwkLCJ%4%sko1=L3GwV~QqkvF z^Pz~=-mT`=E=*wi{q=v46HGXjYpCTqK$sP}lv(*?$DV}xzrgN&<(pzorc~rI6z}G; zmw(4py!>_;B#@4rq3j$UA~bN!C=9s>{a|A~3r!!gv+z2-SGD1aWS$Q*5_Y?|Qx736 z3xdWz%#8zN=gXV$BG>I3wh>fu-%^>aodj6QYn=A>*-D7$@M51KmR9x=Ix|;2-7mPY zT;|nvD-R+$fO4S(sUo*piOz$L2T0Iy;b<5e|}TW4VGj^DW5 zVUf7uOA}wVw{>?j6>5YX5-+Q|vj>Cb19}f`t>}Q;6QBY3w+yjd(CwczZ>Ggf)Noja z{EU$~lP}&d82oT7So&Vxkivq&8~_PG_P?GuxHmagDrzxwV#ls`rOc#27da|h8Gj9w zwQ)blQ8;Q@UDi_)HJQYtbbQ^YOUZ?yB<9k#<*HCJ@?k*J7~-(%gQ=@;gl*#=B0a79 z`QQ;>v_(O`2Ora#-5H(a=ikSiQZ*;j@5JiQ)vjLl3pqvTBdwExOs%=z=a*3N`5|r& z8Pb5+x8P!#QpH;2%i!?>$8e=u41bqfoGg^_=qd41i+}!#LYCS6R?%Y3i_noP9TSpW zqT|ia_C1zM7{Q&^md<#?5J0?MMAV+NlwBs!4J?0qlL&+!XNkt(Yhi_*L{97 zL_&uAbZnqf@e@_bKmc0GddN1}O*{Z_`+jA;7 zM3qLlC6Z0x1sykDaofl&R2t6sK;hVovfa$1N9XS(pZ9|LyMH%cUJH2PfZsr@FZiO+ zD5(v3Pzay3wp69Iz98X=F$BgGDIz)%#kp6CvcIjTVG_~p>?>&y%QOnz-Oip|+dYcy zPEmB)mhA5U+~8=+X)Au#SQ`!L&FdI5W~YeYIGb|(zGQM&gY`J<-B`?adoiLb9gn_v z#M6cp0&E+!V}DeeZqK8^yOwPoG$S`g)iK|e06KwCzA1#OH#YFl1p;~09cJ@|Lz+~+ zFokdQW!zXh$9&ll^b4~Hn-cGO@&YvT>sqXUt8EH6k(m`|=-w`PfXBgAH1o?X&tq7< z=3G(h-4u)CO~FfI4pwrM1o z<}7JN3{Gi!^_IQmvnWr!gG@Ddfq}8hJHL(PSXdd#>baLi`v>>A)6{*aKj3fhzCh%L zNw~{>ihs&MZ*QBQ>%Y0ZSfmlCsTCX*?~V`8n)U}%hM#HuePZafRuQLp^6lfM7#;-L zn}~9u*wYsD{)AL6rmao--z)X)Pa)O}!aXZygZ!*ImHw z(GT)#Y_QUqD?gnm>F&gIsj`BD0T8jxwFDr934dx}O`eBB%kY1nXbQc$Lj&Wcy4y$4 zIYpXg{~C{eBX)CeSBiq zb=p+;#uE`z2=?`D4ZDG&wdy2dK?eIw7=La{pEv&}m7}6m!a`^H8G`(G?LWk@HNjs> zEHL)(n`T*|O4Vd8h#j_7;0AklQ$k&vL#x~3+QW`+^PAJ_QJa%Z(v_YC^dq+hEXxl) zIp}xHpwXA47=IvyQcYV8KvUv1LY1gEkDrXo5vNF$;L*!F_jf}8?}~TdJX#e+z<&{k zb7O}hHK_sM_MzWOgWXAkpJJNf9KWjGMvwP+6%6nd@8-MLxZB$iBiVNWOCa?P#-8K6 ztVQaYz~zfjq$lWdD<3aV22N;27zY=2SK!OL73Mv%Uq7GUIiy;TP`nk9&37-W*gN`_qNpb7CvV=9w=Wb?_P=@qPbkMklk!Ob`PwvYnPm;qhEmNoiP|*< z^Yb`%S(9MMD&f`5mjkDOZhxrVcB2i0q3B;2SDQT@>oU8(m7rzq=Wj3dr$epz`n@93 z2gVWTJ&V+jo0Ct2-kJHm#v85nN{A2l=vaC47SXSC9@!L(1zizCGxKTp>uvc~O%MOO z!4$$LJ_m5XOFrpv?5js!JvZB*C2aj)0ly*UF&+#0VR0`;Z-$DTjejE~U*re{y<>87 zkqA6U`VcHgyj17363T%vP0m=5osenE2P8%qVmIJb6Hjxrwtp^k3N=hEqM)YbI#BM{ z(L@5zE`_@{g9)B5bikbsdc&68v`xi_m-iP~Le7DsW>C@5Kj2fp5jk9efkKn&u1k6Y*aYTLEo%O+Gx# zctamldjFn{+SeL}&7go`AC!(0nzxc58WkqLRkmZJ?xA9z!;9B@iG?iCTw6 z=FU9N+dqD%Wy;{|YFB9JhJBjx@&Q{E3Dcj+K?rxwTb{4OIvoIE7JY5RuYc*G(x2P< zdtVHlo{W4av41!8zSZ9_Pqr`nusn4ztxCoy^;XJW=NUVj?GR-5VXns%Z43Ef+VXZ} zoK!@gG*M_N)1QQFu(+mdN7vj?-_y$=7^;SDT&d%b^L=xBEs5qk;)LRdu33HMFmem3ilJ_VHV1Il+#SjGv_O&= z@G+kY>h&nt{c{FsK;3FOyusHR-3$~_JLW%4Yli~~`RiPScD$!i{KhZz-)tF#l0$f0)xwmmMCp7G9Zv**(&Mpk>h4s$kB$$=YJ!vL4vXUO0M>!swlE3p!Y`JZ6NQ# z{;y5wT=4<0hBC(M!vcO*2C)+)5*X8VpWu#NkXR1~H@cHJAv+Y)<-MPCf-c0Q5-V>D z6ut;{Jh7Q$R&O58pS33W3V|_jGAdJ{IytGajgMTFxI98<-q?kENe2-)Tb0RYOl`XW zCx1f!8uGX`L)j&O%wnW*P#1usGJ4p6;I*LZ*=^q>~6F}9Jkx3L}S)Q!&DebW>6kbfTLr=a#P_&O5t_HcxHTVd@wpL`cVE-3;f@Gk;0 zrIuIP*9K*CmntWoT&g49FtA(>^R>AHFR^BNWbh5&f4Y%CKf0c^VzW+bj;-z-l(+{C zm}X*Cix1EWM#?2%(e2kOymqOA{-n|S6y-6dL6&)%QJ!eYLi#&n7au*t6Mt_p!$NB; z7B}Z}Pw&oCv&hzOV~lzsupkVLR%A|QhMvsNk{Q_DcNjGejm#Mgg?$AaT`F{XK)F|$ zU94ft-Pb=xzz?47{(D}qkmFa_kVkbl4>01r1yr=x*f3eBTt$k)o> zmSqqGxWUiYZf;au9Jw;!Dt||Np=4Iv!z4U5@S z7H4NOAWx}E*Q#7mWVp3{J~N}OeWtmP*m3Ub1_27Rl2X-Yar?XD75=fm({wTK^DVQV zk7Qp-#_QS22s&|42mP5Rvz4Xj0Zo)Aapt#VdNzcdQR++;2nPADI=&PyDm2{2TdQO?++BP)jmDZ7}RP;ya4 z@RgRza-JMQCDOpLdw-hPR=S(Fefps}g$CAD^kbv~%47%FQ2~ChaxJn{uq^n+!2YBj z1i&HiJ1*=y5f6i8s-9SkAhjY$t9DZvk#^@wnKtVVbC30@O@(CNuFMnm6Bhdln6jzw z%Gks3?e1lTvJ99N>(5k(ua0boB+dinBeXhd$^wNu#%SC+nt$|tCEH7jjp0eau~$4_ z{A#Q*gUZ>;o7tO-XZs$l(A`D*hOp_wSn#D>f?6;yc(U$gG``1f{6azyWU+gugD{hVF zB2DAC6!>i(!2C=NT@0?g{XgpTqg z+nYVn1&>ge{&uPJ8~=Mzm}BA1LCxfxm`ju`Iv*W0;BGxZ`V7f71oCdv_m_$EEy(O? z?r&d=aRsVfjKJZ>#38A3(0lwiYiuTdGbnL5@atn*34iUd6nCqaykglQaN6AE{K(8O z`cBtOKc!jf!ZnHC&7d`E5-ombWp~di=uvs|{d%S)=Y{TxbYb)_m3B0v74A|-D1dOH-xQURdcRy?(a9tS zBS=RT^dsKL3tfhAUK08)No1$;=tvzwk!v(_P59C%t0zPHNOah_u&)yZ$OZxyyxG>a z_iXl`WxaK!I_nb9Q9O^J3=Y(s4}BwAz*G&nM}M&Qw;_3h@&@Cpl@axAe>PY27-1#( zdm4BDHNcrFAIOiI@tJVbrrvjWi`of-Vy5$bOh z-E__2e4cYVHFMEZoO~HL%i*)!=C-{-M?~E&t8H>_}feyP_NBFpcOqZ_9Y@$*OD9&?OxKIkCQsm&wppH>}AZF!M<&OXiL7Cl)m~A8LR~#?Nl9a zQ8k*OZ)Bk{5{J5v&b4{XQnP}I6HE4hf6Mo}<8`4-AFQgaD0{H1ov|X`vbDF$ZmoN^ zk-W}k$6M&Vcj{*?b_eK9)z7p3bf$O@?e5H#)phr~)py>=y?n9|rS*q;Wv{;&Reub8 z6dxwoRaYba$>_>3%t10$?C%RuhdD-hXpRztQ~m4RFK^)^YFmuwp+mXMp&D38lz`tEpIz0eSTUzI?XQAcR^ZpnpP?U~r2i zvx8c~H|J1w7Z=)mn=B zv#>>cs0QHz&W}4|w7h6OW~hHyG$M_GxiW7Gd}IHhQ*>rw5`kGGL=IjVzH0>>zS0%8 zl;~Vi#r$31J(My)9>+fHa+qG=o2QGRIodZgcXu7zvi>y&&Al?qb~aEq0i=cHuGoLK zusd?G^A@WRnN=DX|L^Is;u`tD~hyZM`i12&vvF(?=Q{nJj;M6S{3nt=1rz zFjKU_f=)z`6BO^iz)pS^N*&_!lS3*`UnTgA-S}$$`2$|&;3xa=!GbuhUdLm-IXI(u z`U;{4KZUrn?sV4iq1P+y`fhBtf5|O*ir4dy6H-H|D1MSrV1uqm&7@bvY|T58PLtdG z{cY=R9TBT{Q)7M;3MMHsFY@+ zeI?Z7k(mLR#wea)D~Mpb4AccamaOBiia}nNd-`mLoB}q5ALPF2HTNv`xgLWTrHi0U+$UrOwdw_!AxNL5yRS%jLj z3cA%djR`-6fFOV9jV)2YR-nmtT1WK=d~oE8H@xOPD9INSDW>7&mCMe(5+>RnX^sWHd=6gh0$Yw zOiCteg&pvh6T=ClfPLN@rh)=f(-A8Twkce6ZX;{yV<9lGj97Ef%^rO5!K2+SQvxXM zOhuVTp>tPD6C| z9UGaK%ZYzd5=bs7IBX&ZgurzRjU04t-F+Re`x1kNHOo1BLqtw1pOKuDJCOUm!r#!} zqi4p>2Ql*S>HD^0n!`>mDB>B(j0oQy>Ix+E^ zgo`TJ)=wJK`b6aTd*%po_SS{0Uc&&wF8P1xSP@`z0Cuf^d7G1dnk{SV$QI{!Rtd$E zDjzX?(IbxR{MKb8sL;$ZNIF}N)4m7U36P=}H_c)>>SOYxg0+sPaO7SV6HJG6f_~XO z2lPus(s!{H&Q`Hu-iG-(Hc(ap6y`piyk-3@S<3d|pTHdsE}MFvmuP2I7j#;ZESm(eb0oim*f_X;jH3e^=tRo|McK9KUbk^n;EI$u4P3JOIl zX?C)Im%)dy-c5~U%R_+J<9V*j&!`|Udi!2@wNbY}#6-#>+ zUPr#?M(b|<*S*Yp^mCv`Pb%vXt{E-&tQCGM2ylt^9W+Z}G?7Q~fbZV{u>Yd(XNU2O zN7M3vb#`zw=#UI{3|SdOXLL(H1SgLL_6)06G+&VI{pkJxVt@_eN zLA{t#Y(B$^cUUfCLin;ZjMsm-ba8EOVcvS9WBB5#czxGbUT(*lgHalx;qQZjn)LP# zs1`1#H}P#XLXSHe8@M#M`ckeJ$PDgSJtLIac8llzj-_&oGPez?5PgHk;_MTpAH1iC zA%Y3A1y4aU)`R>+4b`yK8hRso(Eve4wTY?$RSi`k|&8RiMv-SDL z6D5A2lX6QyHR4gKU!G#5iGO2=f0241kA{zUJBH%mTxw}RjBoXH;yJl~t+>1Q$lk{p zoo?Us(B6F-_aaXS(J6oao_nc2Q51J5QX_2`Q@uBQimd*2QlEoM?A>2Ca)ZMexMsY& zZTYC9-MGm~MRd!OYy0$HcuGpQOLx|~6b(Q8^NYL%hF>k$oEz&B^iTtbB*1y^VOq5u z1MOK`SPZ80Ldu{{^I{vHd+;}(1y+x7z<2Ih#3Z5)1iOO-%nW~o|K_u%_1(c{+cN)Z zlN{gU!0icIR$#oX>u@pa(?sejma97$`{I!$A7ztwZPT~k&aUte0D{O?ul21Xv}ECf z`&+BOZ|WI>Ep)4}u`GM*4D)H@1+-A>xFDT#?Mmxht9SgUQ-qP}=lMVyZt+7w{#?9Pv$GzE*c7cRha*!(WpR34``qf!7kUcgam2sR%ojLi zR5W^O6=n%s;^=a-hK_(K^OydLNT*rz-OHSIHJ!NG^iF@dcd+o$dSm5^HR8LB!W+68 za*RoUg57F+sm!FzcRP$AdA@rnC5H@DxPNd#Z7Ph^+YTo|DTmpP3NR7qAMWMre8!#2 zH^MK#vYAV^ctM?y$Swr??C-e`uj$fo16fQvnuzMgxu>|m#%CIvfv~W~YmLIZrp!Le zVDIhuo;`o(7CGU!A9$b}%5?CS!f09g_gU+Y0uB$?V|p&$dfn@`aZ(4|>rHLW;K<4i zUc~Ogpcd>S%h*QAR({t%+ zkx(_7G*jhfX1#yg;gVu+5CUqk?bdmgZS$oKz9@e@ef9nb*e}j zF4ofdRb@KR8{s^oaTbz5|K-R(XIl{>s40~pB&kE~eYe$}`Y%CdZ?0e&uu zpBqbDB|X#0w2A2ro3prY02sXevmmN_j4;ayM?@j{^qDlG<4&lc=d|82Tv8n z)%X$cw~~rVN9en8(yn#S1TBAWS%m!t7{;{g6c{cv!uD}Gv2F~sY1^7* z;BxWt+^mr3jrQi8#3--E#G5;biveuI)XE}YA9{XYmH81!SfLG4K!B(cyCeKLhJn48FM8#v2`C-x5L zd&vEU+=GV*da>Kj$&m-4QPAg`&d~ZJSa$2QKabd8qrQp#+H9Fg_xU5%)t5c1?edqJ zL0y{jJo>MyD%*vKU&URs$pg;2uta}>I76X5U0`2PVcbPUVCQSJ!>;~*eXa?A9MzM% zh5P#&V(+{MRhMJ8TAy`orj}?g5|suxg-okHBaN-UFLQ}T;`TFp{+%0|jhy-2s`^f) zf=0{WOl?_kZ*roK^26KdM*$w%sdpAVmG6j;3=K=)dgMa%?fOKMv&}-awTOS2$4kdX zrbe(%bx1O&(QSzbx7nxIpCcR}QLn?o^~#tz?5i*n8Ht`Ss^*~ZswSqnOCl`&D_I8Y z^w%$XIqEyF7E#C7&Df9asgSn&ru;pWFo~*M9?BEejSIY&g2j4ZmwXdI-W0eoD{y~$ex|VsL6I3j z=$V=Mi_L>~ff3L*$W7S{7l3b>bPAh&F(2uGR?8RnHEsT0)t+Q^(+k-vZ1LX8H||Jh zR&Mu#<%?#$)0zuQi5lcEp~kKnkN%o>?X8pHOzzll?(ct6Wu@Ute2Y0D1*RJ1uJF&X!6vz+?K#jxt&tGea30XT-=M^o zPB)V9cLSBI&z<-y(*SQgA9z<6>l&*AV5_~5=5VMt-8C)>(D+k_av;-Pl`=+}tG*@> z_TkUr)@%EpBNy1U$ zlKwzMTES+PuaL){q~uz$U9Y&!^Ox# zOzOctam}0RP6%VWzkqak1LbHYRZ49|>lZyUEqb@!Z4EV_%datl&kPxRY0Qq_dWAZb zeGrCulJoc={$L-sXdig+N3&H+6PTeq>p{0TjrNFPU-IvT_aLI}bG5#}aoW&*&Zv95= z&iw#l#gro4gB~1WFm~8Nim}GNuV(0PwVngL_Clzj6-Sp&BZJtk328CanshB!t+Hld1z7f@I7nQFg z!?=HZF}rum0f!ojEI>-*vLIM57;1Rp<5G42e4T$ybeLL)TIZj>MCHA*#av-r{Y>C+}K$nI{^Agv~{ggeqC5EuOvX1<6TxW9hLHN)arbxZC^{^ir6h zsp1%Z^1%CAH%z13acL$ShDs(VsV@)EiGV8~!pQT*N-5n{8iZ$jg@c@x`9Qx`?_;kB z!qSM@LtRjq&2Z`r!rYMygz#G%M)H5)D8*t?VOM_uL-WnD^*_Kt!8|t?(@*Khl{nJ! zb+O>O9R4*bvSNI&3+Ue}CTxE0iZ#{En5m!$U4h*fzj|i9CQpYw^Tu2T)NY>+D~!M7 z-`#7b`^JdX`Z&=TTwKdo%X20N4{ zY%lIXz>;L)Ds@&%Z(t}WUrTv6M+V6aoxHRdMLB<#tNZTXr{QY*NIV&S03e<`a{(9W z$rM5KU{LK%Ibx?Tr86zYc-2-jxE*rbMd8?m4r;i^FTLNj?UWgNex-k3o*UTWLYxj! zCZYzL%mDdYkDY1KHc-`3mpAI#RZlyk&c0=J7&C*I+@ak_SgP`ZuiZI#lyGuKAX%AL zJWF%NV>4u(q8Wa7MiCLa*#Iy<-6Q&YPvS(w2R;~NK-Q~H4fR%vFQe$+VhGtGqaQnd zRVaqj!}!6qgiU6*AO?S^kyZ?`-+<2u@LiwBW4?-Ji*FX~;&jiNhGn^kfoIRhBeNpoo7RlV2iB$t>?Fd>n~~ z1~tKF=<)mUYpyi$KpKB2zN)R1Q`FZ!O`fpXrR9R&u-(Z4^7~+{@b+@$1aX{Bl!A(| zAJw!2;xim>?#>}iWLfkHZS`vk2NPuFk@dGFiCdl zgclv&7I8+cZ?U_v{B0x=x!`%xp*Lwy%Dj(aXgiKmc$+9`H-w>SOy#dpQ_fBJG`+J~c5uzClr>B)E{9HwHtxwKUp zxK<{Hs09#;zbqfM{Gx&UA};d_X!xN63O!#B%|d1O`_Z#~rRN+P3d{gHfg2AUfy`c! zTX}}|J1T!9%C|dpCQ^=_#pB0aHc;PXVxPb65*UXb>&UR@=cFuj^ycFAJ1lY6`S{N2 z>w!#&Nrl6(U$%K$m2-5oPv|dRHp`|byE{cF9xW1j zlX3dP<_sb-_12E%%FESPL(8`#j*Ha)UK4icyRd)TMA3y){0;#Hxk+twZ=|VK<4w04 zXg8d6*~8l1k9D;B;*6Rf4cV*z;>gRRN>*>JNUW^mxbN;R-7dLWr1}a;{k>|Xr+Pzv z2lFCkc%WadqCYe;1lr2US~DLfm)~99@+@ zXAyq^mnyx&1$OB&pc35QE6zQj_ynHd6*<=^kmU8j&oIFQldN+x@ebYxqa!CQx>xqW|n zE@m4J(+N2xK5D=|4oa8hx5TiPsOGA~efvG|DJ=3d&HJv#is z;1{)G+aYkrTU!DVUu{Odl^8 zpip+<9z1jLfFEa@ZbG*^7ULzGg@55WohlCg35QILc#(|o@G9J1IR-|*?hAh=@^1N3 zfL7L~>b8MVL+&64p919dLv{p-n~KkhQ7hGT-`M+QEKW@_=_O0;l@ImIK$QzYmSah! z%5k^7d#%ri(TZn>v2z>E;ETZ(MZb3N<&LUJl)LE3(zcHIZaA7QGZ`J0S2ZujhXDT^ z^3ID%X^6j_@hh)2xj5X4zp8(nbC5{%PTZ>J$5Yc{!(Ro29+2{;9#w=9K*Vr@w(~Fh z3R8{C>ePOJR|j2YifOz`y`myfRzY^08s@8)wo+zb?gvIM{@E1XL&TU@rM8+5)l1dc zyK-gBXt7K=<0Wb~;1I0Hsr(YxmiJzyW>>W&Fwsz@T5qzX(9@r||>ZMRB{Q))vp1{kY7y zuG=S=c<-fAtYv);QO%pxeSFtqvq+8V5PIdk=! ze^yniTic&L8xPxz_&xy!1GwFH29>4IYdxcR3m;md``~^M<!AQu# z3?vZ)tWKrLEbKTrRv>D0LJ#0sArbQ7Q%jg;>&j1eez_uv4=;bIvKNBbcoILeZq0E6 zDnmtgs7laZp89r zuT8bh=B~J`Zsv=fnJAhDu61I@Tc_iV7aO1N#9`u++`|Jlo078h(fhjm)K@Qx83WTb zh02Ox{G!+gg|UCli%}c};fka2NQ11xD0fJ7o^?f5pM^-n3p;AQKKzx-Tsr^QX78BP zEUF@ImbWi+1)p}H;c9+SyjU5qN@bxTa0T4pViqFrTPr8j?cC0Opc%lm3vSD!$A*^;tP z9m8VR*8A6S)L{Q-ooY#~h9<2B^7}$p?jNHaabciD5VJcxGo-RcD7UOZZ1YvLJ(a!5 z^6-zeW>vu}A;p-;RR20^eXzvU(}{~@h;Xya9O~ZMhiLJ~SX=yr@qmRR=MlAD4?>S4 zT7}g8Moxd6Wx+_L>O~3c4pP%Dcq`5Wp2hh;bf~Kgf!G(w2{0kYM*?;B zl+FCo-PdP8u`G>~91C)#*akSAfli3CF&H$?y4BwyN+~+Sqp@EQ*l>-6F9p*}(7^tl z3?Tpf{8tPxckirIy<=_k@@#kpv3LAAJy$guayozh&YTB(St!dd2&2l)-3#r<)QOm? z-TUXB!Xq0``36jCCOu|OZ`jZHJXD)SFY`&X!O|ju6ucfv zFU+$E-#)X`*SUT0(E;1?bG=#?2*huY75B6|9QCCXhjP*qlurWuvK0WlMubg!L+y^; z*QtLE1nY!Weati%Ak^v)uUOjsGvadPUU^=P#f^tXsQ1dB8ONQa=Dufe{gKg&h#nz@ zl3PN<1c(q%N*d9~T=Me^e{EZma_b2b;GU^{^~FR>HoUPvV@NED(|VYzl$N_90qf38 z#J|?+@XBEgpZifvtmH&!_aEG&DyI*_+DU&zt#jm3Ij=fc;yt^2?a%y_@$Pvup9$DZ z_$ZOn5|Qe74hf^-%>Pgm7q-INVx3t~7-G^*${s;9aoQBaIkN+k86Xcc*@F*XAac>-UMY;%7w zmxANSA08?~T~nDcijrEnmG->*$q|xC*(O4GCcm>40EXrOnj?;IbX@CQ_)D}7m2v@$ z<-Wq-Z1Th-CXp}Dj?vXMM+Mg5mf<2(;;G9?knikSX|GJm&B zN-Rk!tqg;Vk{EX{WgL^}gWj_RYWCbEd^|4So7obeS0}{#=NA zxfb^ymkvwevzuLjQnp(a2a8LeUbm;{(J4*4Wy!29KR2HRgZk_N(uuAx#07tVd>5fM zeP3%{ZR(OstGS%Z2J4*i0NF3S>XH;C1%f5t1bEmhVUj@-3+7-or47Wh0%D0ge}=lF z5*!pLmQCaa@Sc9w3mlYdz@?26|0ZE++v&C*^V4Vkr4bX)DG=M%Ev+p}VAf0Ad(t{5 zO8cXvM`k%xg};(N8`}&MhjM>7zr{T)4EV@@EKY6Z5KA$+`EgtN_5gpA(G={b3_*Dq zV`7V_-mU|TDLA}2CwYB8HED_6DB?$PO# z4j({Nd{euzM~Q|-l&z1D%&9t7N<0TDwaRcG5`zb9Mw?8o2w}TAcS(N&F->=Sg#!9i zRplS$Ev{g`rbUw-H|kCi5Z1am@w6%w{`(;Zr4z`tWQK`DcfsDch33d!B}%0cfuV;L zjh1pTb?(M30zQKsWWg{}X2G{x*gvK@6g;i7Sy-vzcfZO5k_~(Y ztGEsREK;?Z;@X5&7U}Q{$AIm2^hYKZ;c7mAyyIt>Wt3}AoF&g`N>T>-M6ZVa*`6GN zGM`@Wm?`^<&rFfK+f7#FXhC~U+X9N&e*vo|O?MVwfc_d%^ss+RR1#0LhgXh7d#Z+n z6ego|GP!6!4@?t3DD5qAVvyDqDTh;zdLL{T3FJwb%|xj8W;B1=2StCp9%**H1%Y3=H_^V`!gvH_oCf5p%2O^u_x$fmy?@kFx6WJpKu+ zQ@~*=>Ue-o89sm8SAIvo^p5+~cv-+sQVK>mMAd-@%Y$rwd*T&}w_(sf<1$XTJnzWS z_NcU9!5q8j?XtqqVfpWoKW7%6<8E(YR`|B+Q@sQOD+^~}pOsqe(DfdVvj63Wm)nt{ zl3rugXD<4+zfy32oXTdgkY3H7{w>lnsCkrAJK~TY56yqEW_S%6qf>Wgm^9V*OMvuBy_g4V?*4(R9s%+d{9aUlCsfkl3vU`xWNqKVB`6X|6;)%2) zy$Sm>4vBRg_nJo$wxrT2&OpY+As2@%Uni z`LSiau-agHjdBzH%q=6m@%OH z8VxWlA29Pzvm(P{TGwoA_Zmj}XnE^nsMoV?9i$7$raYuub|K(}Uj>dm5XTc^WTjyr zq?UgI;Se>NgJc$2#%wdAOvhxd##f_IvzMU1bx8N>8 zVQ^fUMdZM|SYFHs%ws}{ZVMLS!7!CUYn*>Oat7^yAU_qSu3XBu=JJm&VJX~X{e_#V zJPd@6pwg4uj!x&$C}9^xP~nH~IZ@VOGIX0nM543l;T}JaA^L%^Dq&I+E3fH{KKDwy zBdO3H_WeF@YrZ5Ri+2Po-3`?iY%i@z5tbZe+NXNjbaiv{N_V`C{ifmz!93HR1Q*;lklqlSvMd1SeqF)j8`jB+Az2!t) z1JArvjp-PDonY$=mhielUarr{nVf&LN;kfBjyGb$xi#0D9{3J?ttt023#v+F7{VsbR@m?Tdi`ijExxM1v@oVq@%3xgf5R3X zjgeFA!ZRZtW+mC6x(|kr;$0EmOSib@tEhhgGt8XKXVJf%*0QLD5AFV}G;M!m!L9Cx zqmPLWZhF*7!6%GVN%4ewV6&in@R)#aErz=Oh4gUcJMX5s*Xp!)iRhE3<2533pBgtX zP=vHU$0NcimE!ho%==oAQrL^F`b9~KTbVR8f_=*_?eE>`B0Ryn5)g8O= z_sR~+Ux_y1aFqzNB~;juPp*G04xZYOltz}$-Wd9$aXB86JE-?$6zC0cT@G*jq!+Z# z-m8%W8@ZccE~hKCjv)GV--BiEOM%599ceB98Y%hxz+@@mQ^W6kMZxw%jXvVj`;|?A zEHvu&L&mS#*!(SH;MayjjSwltg_ka6yWg+f*lujJDl@vU-~k@EIcI-pmGAsYtNV*3 z4qiAMDk)T8UJg{uD<&KB@KFJl6fwUeAMo(k(Dmo9~HUossA*sa=TnfF*2JSAE zHD*&LCmiBBVp@L-4ZD3pDj^u2f&eYjYl;`lK8l}8djr7)>%;PVD z`oh%^CQ}x%h54zJ(&f4Jl{ueWAA7V^hb--w77IO;UP;0 zEV=O*z|__~vB!@*SKbvF&jV{^Ecsd!E1c3yv}fri zXUx(=s>Y_5yCZ&Ku~l|`9zDjrk$-6*#8Hk`hy zX|*xg&5d=%wgrb(bm#P|MF1c`-@g->{=NN0A&`HT_82OVup<%4h?38pn^(B>;Jh{gu6oMlk9v3GnqI99Y=r&Z-xq=3Jl~l~I z4~~D*B-yygD2GsxEyBRl>y40>>NP9l@g@dTA-ElE46 zPS5c>rgUonSY__;SS>caPoQUnpW$v7qCK=5r<@0&JY3`uE@Xzd%jC@hBq8PaHNt8) zu?kk5WyZ5Df3kOC&TJC?M9h$cIw1iZE3JPW(m&1#_-1c`vpP>nZNdqF#1{s``vw6= zi>}~OE@1nEPX{E4Pg?d>B?uZ(sxVNHm#P^#&&Fr=@M!bvwbk0k8f+>OO5r!tPwpnA zl=>|gY?b6LE_{0p40mRO*qB#jtpDv#;6AgXdO-#5VX2?;B=Lo~p~(bkjyR#T0}X$j zDJw;&$z^ywRJjI3#I#Vz4W(CLlspRWrPqo`IRaEPvTLb_pS>Zp5%s6VVK`!~A2>NY zW9Dg|HI6Q>Kun664An*CHOaK2!O{oVZ$d;{m- zx5#d8A3_nE#BW^ZK=Y6w2BS4CZ?o2!2kPDw0VX-SM;OX`WmL2*&St#Vya&Cm3FOCi zK=e21n1vk6u|;SyO_UY4t^mN0cV=kfsYQ?{V1&*=bz~MrKsrcRah;)a44CN-D$#2XH2+v}>!ObSv^?c*9O_E(Nm*j!1Q)R@FBQChmFMo$nhe%ydoAc1{o=>PbC4FPr`7o*M#iTfKBDtjD>89bE1w)30|!Jkr|DV zO(Mb8Kxj%X7L>1IT+7m;H*Iqti2E|ZWb5NL_;6)>RWH0ro-r;q9hI-^ljb1nb8sXC zV9~{ur^W8&NBfPe*@J)GWMTbaTyoDtl9#HdJf9y=MktLw6jl-9Haxx2svXH2U#L=C<3OmU_^DgxNLBW&b3~` zj+!#yN?U1lScG23hbfvA(}zcA40<$}4r=XWO-MIyG8SPS=#zh$Dfd_j19}!0Wx%n^ zM2GVQN*B;!?YN&$4=#BL8GfJ~@2O482{^Z|K0tjSE>wIeTTlq6*b8a%^7!LUrA^0)B*2}0_Wu)n}r(E~d6t8j- zLzF|C;b5-kq3C}(lkj5{QeYII$?githD9Q>zOvzt0ze(IAEZI*sSlEd1pL}7a6=^` zE0S?Ll2s-No^biIr8c?{|4^vHnOgq#~(%)K_O$gJSPR4AD4GOxhb zWg{Z3{Am{{?-Iya$9j9mj&v?D@@tGXPG)Aqwon9y#9e2;9>jL=;xcmJQ z!Q8OH)*jZ+RI_^IEfV*b=YFMyU1mTZyWkEBs|u`*h&~7rA@h=P2Z!o!c`vi>=VzPJ zhzN$)6WV_~^+pYeoE923!iVmdn3WRo7oOnY0?j}yB}3Psy~W}kgtz$v=jqS<+zM=A z@y!Ej1o+QgxZxdti8@-1?T~EhDe#2`bNmfcs!T)lgmWwL7Cfnt)pd71fm7OqA=VRc)Xgts}cUu$)A7qh%-<)7FE*$4(L-ph|=U(&oRh0 z+)bv=B$4~Y#J~eLyYY$jCREfZ20QbodzBCm1gAhgKoY0vWWz`=D9Ks z{g!QJ_`U=>6A~PB&SOjBlOOjJ_7YC+KkF0L>6ikSQ+5t6A@@7@8M9O*<@3ewpk&BK zVq|~9(%C*Q%=7aWYPe$#%+?Wss{s)kYsYGE&x!E_ZORSE`NL5hQD(hU0(k7hpeY?{ zN7U*KQLnItE7$rN@R0~V_1Z|38P^T{MSTMPB<;Sc7-8~!h{-_dw}+8s^j-_x66v}9 zv!2CB>yR;}j5BtmE&H(bG)1PzWR5sQDIMX)F&Ck@$s@E?ygMM~-EM(3=tqwPqH zGyNfJ19kUFf(!vuqEZA~6xa3vq^-(^@H7MJ26v4X@i#L&*ZhSPxG&pWK|Dwva}YuR-=#p55$2KZ<`# z+~So+?v|Bz^2MQxM*|%_ zstmBcKWdIe!$jOFO2>G3;#ORY)0?U&mzQ#o88zR+H5y0S7Ilf3u*-`FXPSQWf3E1K zX8*s-vh`DOwhLrTbN-ynK`pNpD4lapMta6~m zgM|FL$;n=@BZzaW{Q%5?&j>YF4zG+2+rKAIHwNwh69(r{=)7fWi(3^icEjDFf zvqv?b;} z&+Rx#V(ezT_$8kw!!YAyyB6zxBmWX<(8EXWki*4#k@dL0NZ*kp^g&>GZ4T0>-(k3a z@fiYM8r;sV6_3sjnKW~{NjV5*R(H^ksC=9SBct+`BUtLOz7Y14&IW%9O{< z_=YM?##VI%^n|7`EDsU!T0kusDW^9X%9;(I%~%D3Hw)yNmW~!Gy~QBg%$e~%9+ zJL0X;AH=xG>;W97OatZhGmG_WZq4%Oa)%xIRlGsbET(yZS>k_(C?IZeU5ETn>1Cq# zD7oR*xUtaEgJjB!05PrUtkzB%J>zVoKChBN$dG2h%d|+As$>A!AyAvJ@AhFr;I)px zZPNy{PY_UbHhptWYXy%f?@f{`$QT^$Mc)0vupsUEOypSj$76zr4RE_uQ({Ch85biw z4PQBm&|&V>y5@f*2M#|8;Qm~2H>83u8o%W$(f(+QuuPq*sv=7k7(ot}^ z)wzCJF>6jEb<0%Ih#5kb6!g_mJU_+t%dcnnMhoO(3c8F`nQUHQ=D5x@{JnuVEyzFdZs=^uE3Wu5`{C88t zAFy5d@vw$UoITFH0_j)M?})uBH9Fh)e2!sfdLgT>T_X1Te8qFI>zfdL#-TppcNBk()DAcFH=~84v`E?#xQ(gkH4yd1 zb`|)D)D5-DTlmH)uTP(r9ogOYi^yEpUZw>cu8$FYmeI*{mY?9ktPs2H_`D3x&lsc2 zc{F?|qCc|ujzdK=In*;&Ap5WR6f^{ViP${hm#L7^1Na)5>w9#PI)YoTF*Z+!zu7w; zeUN_}eo>)+Eb@fep7$~oY7=1#T?GfJ$(N@H3wI7kd*@7Q*gJTaV-SYO2Q#y8w=PSlK z*XIW7HD?9V32Ez4WoLFjfKBHGyVsgSt?Yl1mL(|$38h)=$jm;6I41N(F9_LNOuzrp3 zkp$Jv+c#S>=R8+JCG~Me$YDT0S(^VnN5*qF1Co+kKpF)R>KlbZ5*}p*K$!b%dxMxW zGA@KKVV->p(Ex^x1$d&zzAo1|rE~gq`8zVgA)heHN)h$VV{cV#G}AF#V6T7gE24S( z(lbsTKVis!!dHe2t7B%c%!Gd#GG-60{~Z~24$ z?|pZZeqU&SY4ZHa`APTEnnyqNyVIFY$_4QbRJ)4HVSB}`bOC>-gRw@GcHn4Zxw?fCUenGLO5zeB%%ID1@Gh$EW=8#)Y-!<# z1;Sajbj9pRVTAvZ)~_h_I_@ZIi3XFmGrML7mJERsUu#{OwgNfFY1Th6xN-&<6!ORYoQ+MvB$ULYP6DrM znbfUn2Y32LOzq6eH+YZwiQCwd7VsCrf;CZXIr}Q)+}8=I<}nB?L)h zOej8Hh?Wg{Z;W#7(YCc~p)b1az#o^>#Gf1XRIPrnG{tnCGhSx-Nn{uvioRw6O3IGr z{{$r;KbEwLyx+;vWE23bBY|b~>W|1Pb(|3V`p|#vqp34kD#}=w6;dyg24_bOaUuVq zNziEK-S^-tztGC@K8Coyd7HGw27Ep(U2vcvEv6CgdZzQXm8BBe5_;Viz6@D3{2#E= z1$YoD_=`ZW1=|dzDY`4idX~p}dOdbaSwMWG;PH9)Q~}@yfx`o(e}6v9JET$!i?!^0 zx|DyFP|Tl)?Rq~;!MRYD|Mk~D?tlFS6MupK@$X>yAOD`^#rhxro_6(Q#9Q@`I{VjO zf8N08U;pv%)1Q<#LHj52|Kk7l=jk6RP5=U{KRf@|U;EPi&;RkC8UC-o{!!Fj_pg7yhH=RM`o}oMX}$d^>tFv^w`FYefBp48 zioYNKo$$}D9`ZDv{`FU~Z`=Qs+Klz^ufO_w%a{M1{`b4Ceqa9e7xKST|Nr^?^Q^N! zWqT90B_7sdT>5uk@wU|0|AhYydjH^m`%}yJ|9}0T&GdfqwhHxM&oucD75cAd=xu+D zziao;W$)gKj_5bRbzyH^x{Ez?V{{v7<2M8dv)ryAj z007%S0RT`-0|XQR2nYa9K(W6F04+ERO8@`>000000000001W^D09ABpY-x09Wpgfb zc4xHv*OKf&mLv%NN=nYlw4k#baPZ#B8Ug2j9B_~~aLzftesQz2s;g&vWo1Qr;!3!| z5#~nJ&e5Y9f%~uj*VT7_Ir3$#$KmgPh5iNn>tFIA9kY5U|Nd9c<^M+f_5b>}e_fCA zFK3-?)!+a6#r}mPaJ29L`j;xN%WC__E&Tf>|J*w2{G`Y0?|%jV0{#U8zwbBn*T1}f za}4X>|5|O^^xr<8^F06Mg#Tq+%Fh=B!OuJRKfC<5tE-3hf7KBpN%HfLpZ@jV{3%cTFCfYLk?tQ;rd>UM{cVc>4Eo>a{m*L{r#P**`yccD`+ENK>i+g0 z9bSC5B_7sdT>8KNwU4)@zWz_>zk=_-f4u&ecd|dT{3ZMQU$yuBU(^@He{Wte|DuBb z-hh93{@1%Z@^l-QzvV^oUi@<*pMU$;Px){En&rj%Z~yvdFXo>~>UWkuZ{YubJnP@S z|MhR*KNEug(URm})c5v3oA>VXj{*OEocHp-5BxvDv@hNN`G5Rl^#AhjX#F4HKfeCC z?EeAEzYzc1F#P`4@Bf4$N&HvjzoUozClHZ;Z%F(v>f7a?4f4MaQsn9R1zG)nKZd`-@2>v_p?}Vz z?&C855BeqXzy4)f@-<(MoLZ+BVmsdI@!$9L&%wzz#a>>1k$T%dMEc)SFr#oDdW^=Qy5J%m{Lhx7w5@@k&P~*tu6;JWYV})~pRcrkwiGsxm9( zOnqWtUg*XC{_R_X2w?xqs9U&EXaMWo`thc1RSH&~jCI=6c*faAe-*AT+_is<4rFA3 zRJC>~yKMYI47Y55lwdiUs{r;^4HRo-%5Ahi8I!v)cI(&QUbz*E`#5}#Pv@rNVjR5Q zzUw`m9Za2y`5~p#($mMc6!?536J0876+|9)Q06_=&NO;|pW!ik2i4ZP1k5UJw$)y2 zgYvwyZ>V~zG%RHfTZirX-r6?h6@*F2C+%WW#Cw(-CrG!xA?Gid66%CGJ+CSXf5#scffVgSBuvA_HP~4q@RPF#*N3dlciylJcok{E3sZY-mXoT$)Dw zFYXKV-faB_?u-#S`frJ%x}cOm4r&^C@lPeqvZWu|aET+IH(+h;LpY1cQ;&cQccRQE zqoYEo1d<5$d%Vh-wN$hhj7-fj*EPdKYOz*M(Sy-{?S@a3VGw=yM>uZ7LVle9rUBz5 zTN~lE+CJ+%)I3-L{2MD3%~ez{_qTis-yHjb>Km^Su3)YX_M*s&sZvobAQ;ZRh%t|F zn!UG@C2>a^l|!PI3LM4}eyK<10|)pSTuBY=hJxE?2xR5^;>?_X@{{A}v1?eWN#AR+X5btx*CN<1xB2ZkfJmAHPF|{K z9adDJy*?%@(5afMPZtiT>(A2o6@||)l*Fu>A@Geaxg6C2xI5eI5JhJs3rd8m~Lap6rF=$vL1a7$M zX#u#V5S|VUi3vQOS0r9I&MjSmYgz)J&}E5etjMb{C+To97JSDjK_5Hlor8sm3f_)aX8f(T19TUxzNK>(1-Gln-wZax*Qqf}-cBL`J09*Fo>|fi+WSsvu{qA=aU0}?EBGo!;&XLqXpiB51?_!e$~3U1IG?Nq*p;7ARZYK z0phVx%u z)xTlmnS#_1Icv(#fekdy05edu$Zn<`jxLZT3kZx1$b{}+xDOgq>sO*}P(LShOGE{y zXx|{8tLx=CmZiShhLm&6{cbMB&`L6v`<4x3ytRnGaj$gekhJW{L;<~j{!Zt>J~zqy zLfGX8s5ml2o)A(`Z9-Z=Pkc0}jxf(gTG$Mjf=^RakIOIijfQJJIzN`YI-~wyZ6>sB3+dK!zlAJS1?Z1lz3 z)D7K|0@)qrFiuj1K;e%ntT24^ zZ-2XhXr9zpj`#-Tt3lK)uWqt>pkes5p03Ylk6Zck!ESmY2_Gq(^Z>4)1zCInXA1cg zgVcxpn_xQ)b84-B59T?mJuG@g=#2|*53qc55b!at5ey<$YFz`j#g1W60Os9w8p7n& zhxw`Ktz_rZ#uzk%?ySEE5vHHe?OjA*5*yfw7UGs#P*g1B8|CY7R#(=WMZ?#>oEZLh? zWQ?I(2iLuN9Fjnsub@|RaVRC;@IvFPdN;Iq9Uz9aQ;1E>jcy^4oFF{>s*hhqdb)oq z2>FO2b<+srXl0gvRu;j2K@OyIo5%V@l0tZWr8L9uY)Z9I?_!rMpF5Lk;z6FlafErK zN)l^%bPc_K9(t&lTQ|;a+FlnP6(XiBTjZg5bYoXe4*%eR@rdfEuV9&(brcSX!bJ4_ zQW~7dv1!6am~NPDiYqQE-VdKjyjyIrX|8RCSeXn=j|w68uB9L@SQSMf-1ciaT&(em zy$&MB6B$eH8APJ%zxIImS!*;5lzzN1TEu7PsyYdOU4s@Fnt^q0a5H)NbdiOoT1(1- zte!VqJF@3K#JTH)r34I64_b$SfVE4UPG%!~Pl6`g(fHb&0S*{3{)2&1i%;2^ZILTF z5JKH*kD6U-Q*3x^KyH%4r&b6euh&PQ@5Z0h=HDS=y*{KCEZ8eUW*_N!!mGm zc<>*hou}^@!)&#>sab;iY1P)zR^gcLX$F#iNaXpF_|ZPL$7j7bMmrit2lwiJvGK}7 zv4O^7iO8=iA9@yAgwtpI9l*ZmPh7%8;T;mOC}LC*fh*+2kxFkRb7h9t;UT6Wm$QHm zd`AzM7xT+e%_1WxY$`ZIdOC51(D}^%s=L*AG#%A@(MQsP+w4<-K*X)7Ove&(IuJ2` zg|Hf%;(~=MKXmOhL6fc-4+z&<}eeW2PS(+ zzT{g=?t1Amu=Tkd-}4d>G>@2Aj9;}zFV#~y-0Q<0&vb2McjX{=FN7n!HR!iJ&o`e!4vtL8}YXpYnAt5E*GUb@2_2>U^v};;VtE8Os8>As0Uf#(yMUu(f$VDe-Qf!ca$%z|1D0ZOJAhN-5!Ot8VB5=4x{#xiyG7o7X<5a@m2`6Dt}v4yXGmbT6$mN61{!Ox~~AuFnqR z=cH;>&gA?_V%DMtZfS9OK18?{4V|cJTQ+uZnVZ8DEW#sx>qbt=g0dff0Fw?emolp3 zjH9gaN12{-saP%;IZIS-AP?M0=#Iq|w7!1J?OQfH{tILam4KgD+L9m0P{Q<+m0x>l zz$S{z8*tuBgIiq<0%5=`SjEbpP(UA}rH4QD#|S=9$mU1TQ(2VOMaR4M*DdI=9ozCFl)iH6NzJ>@BD)K<2sV}gOk!eE~6`R2k|N0*l5Qmfag@&oID zWtWcqIh<%Lwpd)si2MU^5!^lt$35Kj?GPeIQrL9hY^LC_RP;A7Qa7)i+aN)zgN5W= zWV(@VK~{=d_Y3qEg!rdQ1>5VqLzLGCKAE~VkOJ{PdZlDBs6NDhy`R)^{4l{-oAXf~ zP#~c@s=C)ox4(PbZ}>16i{D^>PscV!eT%R{$R?LriW`qJoX$#>O+sAW(2=6Sc-&kYXu6gW}onB*-T&9jj} zb~H?JDB#b-cYb6Vd4&{07}XjfWme5(GsGcaS>DuOMpcG?3}ufMT@#fC7x0ELS10kB z_m<*m2po;Ng#JVzn!W{eJlt)qATt~*diBOI{V@!orLm+~A|W3hXG`yRZPd1pZmQtQ z?>uEd0S5{(o_Gk^JlW2FUQ;E#r!hU&jowcl2k=!$5jgzx8rx6q_bX;OKFE zG+O^=gANYgRkl=PuE~9E`X6(!qy;_DtY{5=M?v}lOS%};WS7w0(k)fQF+2{FfPh@#WXGjFF=SgTL7RBe$P0e%ovkx ze8Da0h)So2dlfL$P+J{H(;*vbKop~Ch@9+OT!Hoke|0GI1-uaEt>-+ANw0-6#aClo z>SAN)Z0oGI*p)`MRJtZJdIPd3<~WaTu-?A`L%SxI4@4kapo>31f7BZ1AHX`GmrS<} z%gO+M>i1jh;YIPQ|$V=S5xAQXiYI=oiR_(|3PsYKRk9PXeeN{FaAhG<0KX8+# zbh*1kJG&(QO7g$2KcvaRucnGED+~qw3!lw@tGNZDtfoKQRukMq?xH^t(<;Fl^=XfA zm&30@BFUBS+^dsDb*OoddsntrRIYVviu3BBR}2EY0yBEtoSwjiZ<15~oFXNG`qG_H zsPid1@wJv)Y8!Z)gixO(hbO9E^wI4Jtnxu_8S{nNWv9=jdeia6ZX}>FaeUgEr~;pV z0M&MU2sQL7RbpJ4A0mmb5P|#b;9oc_v43N@!hDXi^R_IBUbax_)Vs0T@%7b}Q}z?V z(lNaD2-4!-Qa;OXjOG1pA<|KVw;|$ocT)%!C32=fiB;;i?|uPs2Cuz&7;9-AjAp$4 z9KF6S!XcmcVCeWF$XYQ?C3Rt{cy?2N++D$|ffjKet=THKbzo~{Du#tejeX9uM!!w; zYQVh*I~0ni-Wn{uhTM5f93)L{C>Ebji82;Ic%z!xHony0kgubwOYnq!Y5*|5YSnOx zh=-mYixIOLI_sc@7Lv#U`WlQ?Tbi45b`o{5mfKN4p-pHXZ>tn+^{_R&9PKTC$X>O&~+~_NE8h5C+(UJB*s_E5vWuaY5IlyrQ8bU0;zbP)7^~i z;yu+Qv{vuWuj9qOFr_ey%$w8Z zhTKL}g%3(zA9Nu0eh9zgOyOD8C^cYUu(CX`?GEkDSFgYMna^SVz;Xl)LO#KfEA<_i z>5rM#mTT@^*xx+N#2s*LCEBROXXGVU3qs6wYFjN$O!8VXYKgs1B zDyO7Emzu(>A?fS(I^_1R0h~y`CCvCSDA4yIt-d0q#QdVyV-9+X>+H0F#a9wJHdT~- z**WvvHVzoGu^xxd=4+^fL>^qb63dUl%Y>{Bhm_MVf*D9HiiJH)6ghpdAph>!Er`f< zZV86ii^87kOl?n4AW9j3Qm>w-naRxNPBG>5<2XTQO*8sfvnZ+|Yvpb0?rd1Nz@X)9 zm%aqFx&UllzqUyfWt2bp7zca&E#7lFAHTY7u`$v#AF>~$HqUvt zoHwXQmg2z98m-dEu^#=#l3lvETd$TV zSAK514(j*LZWWZ!YuIJ+#%B6?cqpS9^?`2tzWGrRa2Q)`0eW2Ij9q@nh7c3?A@ix}- z*J7D?@j)NH>3(Z}A}0=gTb$l))|zC94X|()!KRH!&ODRaE-TdQru2HnzB$Kyw4g)x zE!!F@i3NA)ycn}a=eQVD0Q9&avwcZ(%|9pGt3qIS9fUCoO1y#lYc(IR95y=9-#Ygj zP~Wq*TZKlBviJR4w(c;LP7aLkM%D$Y-X5=fu)Znh?&c4FLzflZ3eO73id@eLHgQxd zlP+q|Q9bx+61e^#4f~4IkNc%SIAo2zh}kO%k5|Nmsp81{Ixl<|D?jOhBc3Puw&RE4xmsKWMUaW= zC}ztu9)u)+Y}N-4PQPE(HF0KhO(MqZ1PFnNZT7E10BF{JiH`nUpya+D+p3}px3JKR z>nwv9o;0z$q}CBy2jb*|!);D~?&NzmVRgmBxw$k$yj0D`0=iS{ z2LotehpYV4y5^*1U(y;YsN7z$XeQ6A$b&0m=CG_~@V;m?G=G)nN&_0}kkC~3G#nSF zRRgVb#=_3v)CM)6w)yv56T+kyfZ+P1L2Uq$cHx8@6hc>c9*&3Rq!K*NXxHN#rs)&) zOkDGS9X=OGC;WWKne<^;cl_H8xq?+A;!^K4&vIoe>2a~tP`ss0bez}Xn>=nPZQfF+ zC^%rDKEQ|wg6N&!t^F7tmW2(md4wuK&SKAIbDzECV+{PdM=X|mZhXYK6WnKsh0mlnpmZVFw<~cePhAwoZl+0-QwlH zorbCfw797}3YYTc6#s~tODrd(ob0b98ik<~OuFFje5%7#i+rBz+}?7v95)iB^OzEU zy_U6(A`1QF5o*kVgs87!)zLY#83YVHl5NNfv6|kl9zTgc;%X4y>5>ycIDcyQbxfY2 znZ=rT`lk#+l$XAebN<#Uds6??F>()sUxu0vKtzk+E$>g#lvA4g*oca<-SNkpQtZ5O zTBECoVR^-Xo8O@SlhHuFL9O}$V{3eWjm*jYSc0WvA9AChj;tn%T+tLi2s}&bL4UhU zE(4(D)W@wYiY>k3)a}_NIY5irL1xvOjAAe}hH7-F!T?qgwJDpJ!2trS#jB`>T2+sd zPN&gJeOE`F&C$V|S9sM5qt>^8)w79B1it*ZR#%RntC_sID2szv5p!*@n^k3zff?{8uBhJC`N935Z60Mg!ta*Z(yuPeZyx#WFkT(Pdyj5LBwItL0oFs_6D+P8!YsY%41h! zgbnvIdmVTDWn}8rdFPab<#v;!XDgHxST!w+x*)iU>wKPBE*ggU4c){p&eOitR0ML+ zcd8r~O$G@c!t<1$ZViK;t=qv% zPdi-;g*soSnb(*WEk9b~&ayVkHcFOw#dZc53VvR=v$T4rr^8$K_i+yNG5}k4-_sa{B#Y6J*QyYo z{i=_mqN139qFJebUMbabVXuO;@)cFCS2N0P89D#4sEsK<1*VY2s>6zVbHJLM_GS_L z_teQpTzZ+3&cX;gqLV!sNpwDnh27q&hQLrP(@32fzT570_Xlti3vU*{lalxvv7LW* z98=)?LmOo*M;M7Nkz;d(JJTftC17$9LB+-1A8I&PNJ$ZY^K|5=`3b_cR$_bSKbus| z`8EzyYR{|)x0jW7C5^c?qhAgpZaw#{JZ6r2GAEm) z>MeDGF+>x8723Lt3+Ck7<17oR8*LE62(-fJT|O)n8F%R}U^mTNxa`|!Sby&V>Awy~ zbsDzO_t$+0*Ivg?UgFJ+e`vr?iI?%{;rqRvO?}J0Rp}Um$SSI0YXZ6&%x)llJ#ri6 z8#|-A^s%lg8rm92pYCNk2&0xh%_~WJ(A1YklSjjUTJI7T6U3=!m0k3Z0y=RPm@{lL znl|Vjzt)W%4&D1+t0X2c7QZv^J&@(yk@4k%9dwGt+f!#_RLFY$^WLzl^wB?0JP3G7 z1{B3&nRKuKEy#jMuG|`%4yVG;AiQFEyd&);Ej~sI&)us)K^2rOQ?)rU6!-yVU^?6L zK`In~#3P4Nax)IoCCr)%b?L-UBI*OYIV_ zZeKql*b~9*yhQWgp9u--e$T#O(KoMbI9uZYpH#T>HLpHg({`hDbjOg(9|9Tem+}Xd zQI-Qi)Zb_Li-4XuZFihKHWmS{%jP3 zitaZn(2qy%A$Zx z%@}G_$7~Pq!TU>~J0yG50H8oz8uAUsd|#-!Kfm7W&9_>EvUNa++_Tip=ejrvYPvdu^f;V-C}pSKtom^I_m<#F z9MGh=$5EkJitzG5ssq`;jKWHPCMU;DRtKTi-LJ!OL+bO+{YAL1y_bYG7ZQ**PGrQn6QkG zxkZub^FBB&d)CPvs#i>s$ZtUUuMA54qehz^+idyype4*~{>vx!*aV)61r+3kB}YD#Vl&rHzJY@!>VH!q^w zD?&q)X)yN{=dg&WpY7Ct;g8ZrBn46ceZ_Q)qv%Y5`gED)2u<28q z3k@Z3)O-~ta1x9lYr>i|%+}C|bwdK!XrAd{c*L3CBdJY;vGQr~7ea23!?N4Lz-a#S zjpmmkb=oQ7$OfU|t~L?y8+!jdk7nuDmvuRWKw{fI-#V+mL|U7F9hNvwFDmq^c~w3o zAE#z*8pE_U4gI;oa30D|QwWkU(;whsNgv9a6h*(jC-lZ}o39or!AtYlz}T@-+i$K24riQ1>wCdmdU5C> zXST|R)}&p{!qpq~5nVVYi*5IFT*446TJ|IF&-I~y@>#{Se4btUmX5gY;&W6MyAC_R zz5KCv#+Jc(HE!K{2=q=dgVwsneA|chxpe`<5*hca@4_K}T3OFU4j7U{drwi;06~g) zYpv@-vyCCcB20XI;s*%+50-J5DHprpx<;#ct)8P4xgGL!Y{;s5|Jy-v@oO=uB5h}{ zYn>#*Cpql31m=ajuh1Q@X7ru4j?*k(jX^9Dw>k-ka^HfWBDZ}akaVl~Rx8dg-!A~G z^Ij(e$pR8*L#&p8QLU0d0CqZP`{M$=dIs{X6ny>ytpv>JaK*)kQDh!rIf5CZ|G zo1A2W=q>~ZG~GLy05S_K!RqH)iwQE>-oAseAjkPJzcXaUm~y}Ruu^M1Jd@Tz$2>n6 zZM4;nB4BSWJRA8A+s!Hr3lZ;{scN@gUgChX0%{9?%;Pj2GUE{;pohaBDM`oVmk$W` zpY2VzK}>0XI}uF7Q^mUX1#qUAF6rJd+*Y60IiL6mtK5EOedGI!^}Vld6-qh7(dtj#)?TDs-bxrk4$*{nQ&*~RR|&{b`J;zo7VB2_u&L97Sx&F@7V7A;XWez`w5W}PQ^=ev`In8>xey{$iAjQgyu&k}VfVi%`7tvDLtK!M6qMgXOrE~v57MhYD zY9B?+x5ei#S%92H^O*%3v*jyg-oFh~%SG~hba<%sGp zh##F8|9%E1)FoR_iJ>&d%{e}&_7fyvI-k^k*g@ZufsT~l+GgXMRb@NAFf5#);%LDN znVNqMV%hNq_Pn>WFQh%a?&c0X(J!^M1%EsvnPQ^WsrFDmjj%@>bcaneB(P!znOTvn z^u4{9BExbA#|owxhZTkf+XuuDd)PL%%4I|(%&&ZAeDkJ}>l?6`fcSc${byN49v>Wk zoG(&Te^S<6k@3V#>q8WQb7I0YNistlN{c*_&4F4S|KJc@N=!xxkI04}eVDQD;Rzfj zB8V9jD0&j0mZ%M3LFelhlLPVN>$a}t1L+dlhziHrOh!XgAO1OdL; zK0vk#L|dLo(=)zimH5eI@Z1_ydx))ny{8_vw`($aMD2lkeabSu9JdewiH+?%`Q8z9 z-aniGrXp`g5MYhHsArC!i>f?R!78XMw;V2Bg+d0CDdV88P<+i$csVu%+^78pEk~*< z_$B=fvs35!Nmv*?Q$A}Z=bV*;Dv%bQ7MNN$eM`gGU8?d#fuy0qJ>EZvI%`CK&F{Rn z=P$AN40^xOBJuV%b<2DNBFL`FA(dh5&u+c$RnyopjNY7{&dgS_ev;{>m4VHo-(b)f z>dcg*LZ<4Glv(_}jID-XLI>?;a5IVM=FF~MJL{rx+uw;gOZqu4N2@99;8zzH)Et+qDb!|?tV~C|Gv1pZ0RT@%96;^?REwwBN4;!SK zd}!~ZEKiL4Dyx+gyEY=y68s2RcQM-Yxalt4pz&BpfK_WcD;u02NHz=PInFp;7Ng+e zO%6t~pD!g{700p)*+)&srEg{O)vSJt;3l#E3cl{tHks@nK+8v>#&z+3?H(JulQz2M zC_mv`tie86RoE}*HhSv3&SBmDQx*y#E+7UCrT0+{M6+?$WS@VlD_SrUM#U8j( z_Uz%CJ9u2J-K2A!dD_3%T`d?1Hq>ZdUzTXJbLR;nS#ExR=zQ@5i=r&?&-3xpY&#sF+bF-|dI&R&5%8Yjj^htrF^BNuQdgF0g8D{p^uS;nVdeQhP8 zH#tv>@Q@)mJ0st#osJ&S4fSHBMxOim?g8mvGqMI7zT3ZzKri`7#U(Q_B&SZPQYJg*uPSUSz?a6>+Y))Gb1$ zR_fAt!Z^8pd%V#10#?tx-lUQ|2nlPM@=s4;Bt+q)JU-h4>fwi9r+A-Vn@X}9fylnu z^cH{FZ68o1p7DrSgX2^Oahs(g}rO0Z?ArYCcSp)rO`a^x7vH|w`?o}l|<;s zRm*L-KpBesLHc#+t2NG_j@2tH87DJ@B$hDUs_{-veOwt&o{MsFNK6AgXL%AlE_}~L zkJkbr&`D(1K%D=iOx8u3Ph;xw7$!WW_{B3A|N7p4P&oItZ{2t-4hzX#@@CdS?k3Ng z>D}qVj~cp71tk>zk2PoUTT1I}^Vh^Ecq~k;h$A|_4HV2j$WPGqCXMvc>ht$2K-byL z!Y;2kmwK+pzCUUD3fLfiv|Sy;xd71Beodo`QSOyyb<)U9pJ|S!65TUX7~E3hmOx@D zaAIA51^La2kJsxn{D~$ADr$lJ%uXUHqt%4H2K^%j{5&0`&2@>3Zf;~+!j8$WN1Db% zp=r%$;^yyi5nGZb1id{FJN94%VXq7l(MJ=A8w*_G`Y- zDQG71%xknU1s#2fd@GIzmWtbWV6pdqck-e7Ox;r4iJUKea1y@)*Fz4-nOt}+M)olp@l>-JmU-9*G0@II~8VAJt7$ z7<~nl+`Ni<0D|b?4C&Tj$x-4&?%}9l;=;J`s0Um4DhFxjm+YoV!Vl{xg>&fs4R;2? z8Si~EsM0PiWMQF(qTeVE(f$#)hZMJ~Xzt(sr26M46wGrO(D(3isG~{{w>J$X9fzn-w!#5U>gNH1ca0K;pRm)(2}t_8xyDRN1dX7dKK4{ET=*OzKm7VG!j}7xW{z$ zAa1w@mq{jzT#o*KKFI8aq%fIgzc;8g-(fUQYD45T5GYn&gH6|>$G$NVEv4!M#5$vA zgTpF~1$Kq6GMO9hKmJBF>(~`@^t_I-Gr3=@+b>f8TEoT#1+BKHG`!9v932JJguY>> z@1D*2C&4al%C`6ocH&dK%+n?^m~MM*b>UlJfLiQtd`C!s%;>zK{f$KBRTyLKL5`-nQlCkoypwG+j9gYV!DbbqwEzRU50-@4YR z)S9bkvS1xq6H>M3-5F~>ng(`#q8cyy+3N0SVsc?Dl4YOOFZNMvc$x>wtNEKAL;KJF zK^|cyo5Q1jpl@9@tidh^YsZK}R5^HS+Dp033@~LKkIRX-Nr4F+B7>9NtVZw7iBximKoK4Hfq zK}r^KGW9|J^I@N?5a1`4v5WMTuY#Q*s~;Oqzc!b714(t7_I39e%h+Fa=N~Q&6sf5? zTEAB_z@4B0;FU|YCc~UR&vpuCUop6&d7aV9EW{D@$N`hI?=aBEU_iuHxR?Gu#Xq@G z9Pqb)fKeRq$S30~!0_GGu08k(`=|9-b;4q388hwT>Lf;@prR%Pwj}D@vh3kCAIOOw z%&FHttR%8QQq}*FWaIV3Jw0 zx`C=XXKw~+gPj0ibo18B(4P&^{*CeY6^!`P4XM(UpVNA(AO#t*$yf#=KjN;^D z7{uQ%Lrm$W>zJRoCo8tOlkWDAFVYKtzgB{9gFz%|=e_+&>ic0HpSuM#{W?7oUoY+6 zR?~;oOC8no`6a4XVG#aznBi_gb5Cc2jeI;Yp@A zBrlo@f@|yy)?E<`jD?3IYpm!hRb?+kjib{BUdsT}jDtQ8-@hfhmO*coXeC8lw0_<6 zok{JRd-A#|T&jv*ZOpdPKE1BjF_9uytUqn*zQ-GIpjtPY4UM~wv1pf{^{cc{ZcVHV zqM%mmWjYIxOSe~(ROH@>C&TI9gy2%C zyr4!d;c&Fb^}BSuTYs8xh`V}kjPWy+-%39bpbf5ZG95#yM2FLbSbiaYDB&!p@Bknh zCE`}FL5}cLq5lSJu&&-RSHN?05P6;E0f^es&6=0kS>mQ#e;8wOYehKchbh0~&vM0q zaqQogGefPYfzx(Bv}yyudZR>+_*)Ho-n{ta&rc33{%Kfh61>5dp9df@oB>3%FfGq= zfy~y~RtM4F-a6LZvW$U$%{KOJ?oLldq34D{QIYZ+W{Ui-D3e58fk8xFDI+m#jbhPK zrQlK|uue=z=@S{E7yN%^5UtaQYuQDg!wE&?vQ|yjf=<`Dl6*imn4gu**^UdioXJ1w zRM~}l(hE1LL}S5}76QZbqa-Icl56#FIYl0dowd9Cq5DC~UTQ9X!gtqS&2QsT7<<*( zUc==w*UB7Zq!Vk>nRZCEz-#)T{7~34^}Sq2C=-EiZK_}?Mivs-y>Hen|EY?s8wtKJ zG&(+D&K9EcfPT{NTNM<;BptbKJXZ0!(XJ6RmKY{oP@&g%gQGD7v=gq0%`8j$op#ug zTNh%S7Gb1M;BX#)b0u=*Pp^u8UzsgdK#ml)6PnLmiPJ{TF918aP>*-~zkN*gTR2{x-F#Po@q zUK?k(g0OqTvD*t+r5{GUInmQ1)zyXIi=>;yv`1r#kR8@}P}ZR1Mwy+RzyRYwvcai4452 zOi;F^tKf2foFbSNEUa(!!>WBaZAfl2WylqYZAws5tw4VvWCr4C)S0&%+$uGk2(b8zv-txas@+JIy7`5c7Zr4+jr@&Bw{!| zFKU9N-jbI5qlanWx7@x~wXw5weEII%qRrmxwtzW*^4)!JC$#%1Z^Pq&2cHL~%BmEb zwP}s{!F4yt5rl6D+7Kaqg)$NJulol_(ak0>H7^=D6z@tuXdrjz;7F3NANW+9BrL4rDp-4lP|c#yAeu&6KXSrhS13~58DCEpmXi(gAq zGhWPpPEM9{>bd#zQGS^DdppcYaUSpp+9x?`1w}Ug;3zcL!Rs=Yxi{~2D0|mPW{0vo zkVjPN3_fTNY`qeJC)bqAWI876bp9JTOx}O(qv`H`>_vVi7OjJv0Dk&dzw6MqGk*Pd zeMLlPZ#KOdkR~FNn4JfO;l9laQ`*s; zxbR;iR0f}~<^51ub98Qul;BglMq$Ip$0f)1)fLOlrI~l%@m8Qcs5F_QJi}99zE-IB z_{T8x@IOx;;s#-kc9N{5UmvKj-np5J7*WVTWy#;iWN)3kJWRN?j*Ue+IuHF!pp!9p##n#S_Y7{3HH_xXQ0jib2*ijU;Ie9@$iJPdsp9XV|5lY z<2%6}vGz;X2Dm_WmFmieMlF09axqOpRtZ83*J!CS(ZaKMU_7y}I)@_TT`*H>)y4-& znB_rkj>~dLXU5w-cOyQj#RXfA8lS8C+bS0ALMXyTd)^EV*v4YF){D z!{<_|MKO%7>HFrT*yQGrb-dL(#a)THeA9mhxIIxB0S1*x)4 zmnwdP+~Y5UR3qc}u8u=`TNp}z#wU7)=d~2cf45DEAZShRkWWqMVWFGQpFvHlr9YlF z=7S1fi@-Jqos|unyK#AA z4lR36aA3wde<7OBy}Ryrb}Kz_Q`|9#$m zqMZ_P+BlI|g3PWUkz(mW$0+Hb$2u!GEZ7nhn=LSOwaYV{*Tj|Ug@|w?{JXW3SWGP< z^S{9CuleC!#pYQsu{WiE5-LoxKg{>pJMv9lG(zCuR+_-S%nGtspkR2xvYnxPL;`rR za%sOaeY$P5+op*E^`yMo)fce!J8R=Sn!+XwYE}aC?eV(oBFcGPe!aEfch6r6JG{e% z0Odk!Xz_F4XN{$PuD?o+8`$NF^Y#J1;lrEFFAhr8cw%Ubkv{oKuW9^$3OK+)bx(ul;rxvjHS+UZW|``vMU8s{f@q6ZE#7_qZ)Rr1{#}~<71!X5^?e%v~7DvR9M%4Mcx3R$Q}pgunu1qeoV*4V9$Z@``E6>Npp^0JJJ_tf$k!*punpL zN4;D4`rTPGy<%TNAJ|I*qgbkv8x-+B73c+jBivDn z%P8>LQv=T5qJ1od^+kCVRw!=XwY@3M3fPcgb(|<3Uy))az#X7pzi?a?NVU?rPeqm5 zSvGeBXJ6HSK+PR(Er+0fGLQPviT#}(|4`el6gEGl1~Nq^cw+f|5;^T1UV@zjE$t%b zLriue-`)n=i>X*(baBU;?v!Bc=pzrI=cs1KCU20`Y-JUf(B;vPIhL$>a&e`*2PxTZ zVVZBzj|Ekqvc{0tbCR{u0|9cV8OA(^a@akkJT=;XvU%g1AzXLYk^KHmH?_@G^8hzM z$iGEERQlF<{G}5-ORz7Uj|ufy?0ID2(TnpIV0!)BN5jc5=j*C|aLSv6`~fWF5udiZ^<~2HB98DI z{!%TnEK*$Gf0_;Y-zNJ>jOfX?*uYrwE6qM<-aiSNuz!D5(N1fA;i%~Dq7$-qpnYtF zs-O6Kk0X!Hyz@f^Z1g0D9&pz*+R|e8rs)xG(!&0;hTj6!ynV^?8+T!$fLaV*2o^lOC+X$KyT?H*9!M$ zlSAE_f25vkoyb*j$PtjwV%e`4?^H#jz*vU^3_{}lbkNSFyDBaMP~29K5{I<+kdcTN z6!}cS|I%IwgkM<8YEk=@=?>y3Z(&Rra5|r1DN{6f?m=gox=2~zjf{u&{QM0j0tIYt z$izSwPTuvqSjqk2&-D%;V7zAg1|2?5R9zVLf7t~KF|83Lib?0x!r&Ji`cE%7K`Y-N zJYHR)8-U%?anjx(kjC{Zfw^QCH1A=LyjY)eqt!UKXQ~Ux#~eII8tE~G0%UcpO|Q_VY9`o!lTL!>U6e;-Sj7AKg#f=Au@c_PMGw~d*Ec|iv{`T4Y} zbj_EMD4ke{3fcXREG{b`vWA2hi8Ro1gzJGxGZgg#tO7;>zl++QN)Q@ADZ`{=ZM^{{ z@#8`g`9^?kQ~&~4Dxf$9-LA50iWzv-tL≫u6YaD_&zhtMKCVNM4Zel?`uWe@#~1 zDt0v82dl}gRD+LU{1Co0w9=|_eWkxIs@fM!Aar)&w4bbDLO{XNR<3b2E5I%-Tkd1a;ZX+X?%nFq{b81R+#q9xl>TGB6K2`cFukg z@^C(%kNja2hZp<<6F6_oG0v>Le}%P(`19y4B<$X(NavAL_<(<_@z@bYb@y?pukj!- z>nl}f;5?tNf;!29GRQt7pg7EOLK=8l|=y8{s>aBts_3iT>7A0I_f2C!_aP+bt zgszL8gmPQ1ti;{D%fWab4O2(ZoV)?n$c$GOdM3h|ItsNlPxJ4Z;2h)2D8U`CePg|> zzOJkT&2)sj1O`7l&u=?C(Or{y-x@sZVcDK<4bWI`eujb?81dUCSp`&H(AGc%uKXZr zT`@UfwP20Cn(+j9HAUxAe}NDNcwir}wv&X@h9G|}Wu}izWKcg1%vIgeS~^g)9y9fG zlzB^Wc)`gekMknWf7~d6Y!9r`ZUQ7B zX%K1>_N@fL_cQI*$JpuFZq26jpoH;;mi8NAuBk!h%$#ms^%-dUR?d|~S!|W?#SHP% z$CeVt;~Fm}cQNRs+0&ji-*K#2vh-AuTdVyAkrZNh4j{jhKWiVD8FrGrf_-hs+cnT2 z&<5UfgsyGe(beGZf6>uO=tpH4|DB^79n$`7h)#h=wYD#InjaM5wM53ZXUOdTgc zPcEp1m9KAD-fd#4-eS3+X;jporYBs9{yFxUL$;OeL?Ek`e^^`;AWuY+$b+K>Tb^=_ z;f1NXd}^npDs@h7iQf6ks43ITKF$v|m=G!`?1x}XLL?V?xdwd=y8AoOoOE-jzf;aC zJ5z9Q%qXYKn?ybEsiFxElf1sI-WT@1V|db65VmGtrEK~NMKSaQ$yNG>ObPIUFxy=$ z%A;-GdMRPje^en^MP>T!NF6ne@@&iDsAZ(9AW^XAu*2J=?aKE!d%&!g9Ky|Tw$|Wc zF64uJD{AXw-9jbZGTfzTGy{JWRg*07Y;$X0Ga~bdSD6_(6o|&;ut?G3!~2vtR!Uvm z9&<5@8?~ZQ34&jiS5k0uFqHUB-;FRvoXho|&P1pMf43iYNI4teguCdKq3n5^1CdjI zbvKg3{y2kSwt)=5cGTkRq_yXCSt;QLGt@DI#b^UDHTcGeF!TJ8vJevi!xG=(g+PR? z8Zd~;eXSDu>#iS!qc-!R7RqZCtxj_Xk4;QLAgw=!4k6WnEpYm{Pyj?D(?Bp%9-^96 z6T7_-f61*q=mKM#8YJ9JQBU=1LFVIks`eKWRA==Rf7gC@E{uIU^C!6zOS)@Ne=V@= zg|b-@@D+klcP5;$-whh*HeYW-)@4$9K_b*rb85Pj<8n#Kvd^oUoR)RU`hxCOj(v8! ztlem?ZyqRhz0vYOKeP}qh8ocDvTM)ihq`Pm(SCk@%90${x?-;LM9ew0}hZASM z!(=dCJXJ!F(AD9=$zkk8N#gF_rMCrb zw%(+oHSOU=Rf6AfQaTWFc?V4%%ZW6LZdGeR-CW6oYMz*UQYZTK0s@BE3;K#Qx(mM{ zpO+)ID1Z!UuO`}3eZIMJdTEvk!f{yAf9U&sN6|0TE)PwGsSfn@lFgkYa&MREz7SvD z4_kCGvTEDgS$9iNUTX)}I$D9{Hr=%lbE4Cx3QMkpj`8n0q_yy9JE%94dZ`zyok{c; z)V?Yo@YqyRGwvOdWVID8?LWDVeLNfgJ#5ecqQQ+|H>=-9q;w&EL8>rW7a{pye-Lo$ zF^A!=vEQ+`-ZVg8^E6#da6*|d0Mv4c3~~VP0!vnpbW(ILRK&Wx&ocFEYwNbxlID*V{i*!QCy=r^qVF_P@>&#{ z0|ymuFfPm2Htf*5^;v$+KvQM~f88!m-L;O61>8fhC&ZCQphz7VE%%fUWpu=tkXtN+ z9pAeKPpV9li1OysjI}~}7^m=u$nz8>tb-<(rYuWeu5hu?=!xSzK2O;)w2jusXBv^w zgM#C=sHMo1Or_#TQBST^-0w09XA{9@L=4L9^6B!9e*z9DXe^oetlr|%lHh*Ariii{BTHr5E~vkog=uh=d94&jSfs>0=mz{5xOM^}^Q z1X^l+s~zfd+aK>qBw4y7lR-f+Jm+CnD%PQ)^b?#&V=|`Qv7zj@aq5GzsEGw^j1Fm4 zl$?>x@HK(p1b4kwjBxkBe**th#9bIn;o(4D*uy*AnciZZZ zuls?A*ZCxqcQUQ#U5LlC3zF75UuiV}a;-TwIaJ(fR=-bCwfF{LyA#xH$!_Wq+o z!86M)1{%d3L56|oe@>?3R&&CZGN1g1ep_$Usou*V^N@ZA9oK;2fvTs3qpD6w)Ws5k zbKp3DS8G`sWPG61^fyrB}qYA*Sy>)=#e`azrCqeY+ui1(}vH^4%3N z6J(%afb3^9i3m{*XF;T=vi9UspL%T)$E*Zsumc)`nRk`bUxG5wx+p|446s6)q)p#- z_(lJA(J#*de}&dD=y0?ZBv2&#NO8j!J#EMUzSNb_Df>h646Z80up`(wI9QnU{X42P zxa7ifY$KEfIGbkIYkg3wE5C**7BQSQj}4&C>WJcJsb2Rgg0kAlZ5WXZeH`!iM8JA4 zhx^-ez<5(>r-3DjcekV&Sanw`B(#A*c^m^kp4ya`fAKl&I3GwS-hyEDIhJf$KDHyT zI5UM!^EX-6%@V2fy2tNC^1D^UzBB>m7SIjCdF7k(_k9ff|O8|jn+;tVOGh*;Y}Dnx0j z)lLzxf0y(P(1HvunpHAawzRh=l@vzd=bi9Ai)0_@dl_uwKJx3c!N-=(_5)eS4g;!Q z&a0Ex$bOGD{QZt2*mU%*SheZVGA=?=a~*PFlm&Z-zJl3~T$dVp#DNE&kNR2bP~~bW z>IEF97}Ae_NHlXs|@{T9CWGmgmLpVC$B~oj8{) zZ<-DtAmL$>^yoA*#;*l1@{})~M+wEI(`vOePQ;unKM4aUn6&RcxqM7x_LB+DqOO;w zic_P^mq$Xw#ySx0_j5_M#LSjNy{4-^Lsv_l*41(t~u zf8eMu^B3e#t26mu1}kZNB8E4846Qe3?(+Ct?C>nDe!BPQ?=L zUaJgga#}dny@&e=s_iOWm?K%A$YOOBrX2j*_@iuL0*@ma4G% ztvWC%PQTJw1Hhd|2VYm_oaZ6yicK>KYVYTFMkw-N^Q+Y$8?VNeOIy@m-wsysD$^Q< zNSJrt%pzT<^7oLMb2`WoPL*)Kgqq7a#s>W;qe$??l}?HN?!i)72Gg~}GKPkUe+U%Q zeQ9>gAB()QLDNUNcNjy5v>JqBp!o2!oY1ioYiNIP$-MiN!4qoO^k#aM>deV>d)5UDdjEG-z59Dz(@0APSR$%PU(3s~d zMG{%@gQbqp=K~G1qE`{7*+e~|eNi#zQ<7_EZAjiuT?#SB!_3MJ5bPS)oo3snrDV(ZQW!nWh*!vQpaMFW@YJV*h= zLBljLzkLyU3w*02iaXuXu^7XrGa*nX0m~j8T7x4*GDXs#X_qxNDE2nZe=lo-?u$Mt z7kq}WC$kKu%Uj5@^1O(w+4>JVKxZKF=m!g>_b24$^GE!>g(PH8ObSLIUjk9$0g?g+ zI}A33!XxR8?@AYOK+GV}ICaNS-^^vA28C(2AjliWH5(>8Z9$ISRwO5u=cM()P@YhL zn3-ijQ@kV@+t;P*6b>S?e=wnm^Uualxpq<^2!7y40M56#p|2n_44A4{xwhZM5!{|~ zZCvWxXHo~Fc(oM}4A-t;Y>FjqvtDS>Fwvubx$RKK1NnsV`PNtKL8!FPL5n4!tEMdx zaPgs65_8Zeqt}(8cl20x_*;vD5YL@#Gl^`1G_@bI&j z!+KH#6c75%t(U=6f48wAjXqu`kz=klX%X-Z!kZfGs|2&`Mf$$xv0y&e~qD(jN*f&9I*WBp>FqCW?15xga!hR|Z&h58p>9UjTx!|!<2@1St zm(aQEqLrR?6eF-4mqeUg@g>W}>}ln@xBSOYoX{{;0)UIT%-gR$YMcYwrQ`|C$2UIk z%)F9kb{fpBM6L5p@bGo&oPAIaP9 zD6l%w%b8n_WHXPm`gOw(^s~Rn?$iUPT@aA9zSKX`x+oBq>mFmx5b|bN?vu<$xgLMv z7Ltku&U;^KOKce;NI?Bo-_7ygPMvSP(j2Q^m6!TFh{Ya0>Xj_0_I&>1-M&|j0tD!q znd)fxf4i4bW#`H6AUZ!8L-s4#h0sqMA*h_EB%sU*lo4s+W6F&_>c)SIslN-353Gxm zk&ZTnGs)=&LsQr;Jd%&a;CJ^81d3*CxVkl9%ImnE>8npE!z|{QGNQ0n9aSz7KQUR& zy#`=xUjn5IlAAHw;Xp&8NKo?!Xk;YBX!vPlfBb8Rk~f1S2igL9s`V;+wn^YgQiTAG zsCxB)phCup;9Zvs-OwZg#Py1U-4#9|z(LFC3A$z+q}KQJ_mmLfJdm%-J~vp;XPo7g zq;|eE{+-h*!7##`3P@OwxX)d=bnY@+Z3*{~xBu>xSDw+3V0te}J$ZX!#dTTWi+mYiV$AlI;}llsyI@eWK0U47F4z5XkQ&Cl6ED&PIS|GW@~+C8OQ0J8Dv zuy9*O(i-I!5nAKtVn@Oqbf2j@CEX8`;9>K25&Y%;W9 z8$Olw7=3wd!{GpLw+b@;&5EY{*@~Sw&4DjRJe`s)DPbb>48yt1qU@^Ooo0prjb$9?j7Uz=Tt6tz^$FtjAL)Dm;ZGSx9 z*ak=EJg`j)Y?^|;Pmhai zi-jtOP^7=nAww_5j*>9Yw_K<)T%(ipysp^wJt=+ibU3Il_2A?Sk~$~}r**C#Gn7J} zm+*(itrRKi^jlA{Wle?ilfu~yBTrP8?>DdOHzL1C&qX_1dP8Rx8SN99m9Q@?Ks+Q zYJy5xqXTCF)4%597$1s=UR%a{=%HBB6-M54DzdT67*j?(XKEX-ulkQ&rMLt2?l9|f4)FFzdMq$25CvIa14Lv z?BdUZ!&+>_)|+*Js%C%xTv{x0^!Gt9Q#x{Vm=V8xo_F?EVQhCi>H(%zHLL-)((qN1 zxR5v}ej*K(T{KS!)3-xsY9>(?prb|tEd+VTa8)r}KY_xuF5a&e(Mun=wRpwfgC2cV z46cc>zRvC&fBob-65l_2V#Mu};NzJ)gOaDM45@fEhM-0(cP~xtXG>4u`j`(2z@tF+ z#TX#Wcjqu2u-adYk(ROXL(OfKGh!*UzWh#UR-=o7moCwMh=A3?0j&_R%=vqjAMeY8 zi)m+O9K#f6GzRR1-PUsV_eyNn+?)fX3w2 z;G5L+gK*{-TrW-X4oXTMKO5;n1tBWJwp`E?lYu@B2+m)+i#Sl~x8L;CPt~_WSW_eP zvuw$11m?sJG}ldZ1;=_rOe&=C(UzuJ5@Y?IznMGH zmWE{_88gmB(LsBwC4NVjwz?O|Q|o?0U-g<6e~^M>;Hb}g`1ST4M}3ft zciwp;q2O@!oi$S{d+BoZJeLD`9ehhq_u=y1K1ID$_j|+${2G*KP=BoK$(%gg69W;T zLsBi2bQl1;$XkMvqy~%1eh44lEe%;7hCq%jqVgPg_g`W0ShlIq+hn!4^`uF?H$*Gd($Z&+r*FkCo$AaX){X(+1 z0fUMxirF6gNo8R&Qw)}f-(ZdLFGwVBc%MM)?VSc+R6O_Ge2E}NW~YW|9%Vf=1@b@Z zSs@nq-deD`_&R1nhl0kh)dqCHS*um^f2M*R$||xuIefAFoB znSx0g%vppg3v2LInAV|xr;+AxQg0hUFnp|ULAAam9CV` z99yTuRq?M*zN$MP0#G=6!s`}UQ0enSj9)x>PR~QF4g;cLB75Ri&5G)UiXe~mTS2=4V%IZFG1@?#eiw6(T7HeQ?a4S%SB2J84` zXNodj>V=uU>GGqmgmQdtWhbxnjX$9{Np92dLQpTv6h}XMZ_oG`6ocE@>WeKWsU1Sb zrz841Q1r`w6oe{olm4(V-(b>*y+LZW(J8U41%6t`jp`?&q2vu5i>7Y0e-s2E&6n^M z{F{fZ@aA4{v8+a?(WX|?puKrQH^Vh~&Sf;Px4 z$rsyDY`mA_w-6Qg3#$6_swszF59==*}NsUJ8e`nraUjj5X#x*=T z`QSF(e;VfWwEP1a#?~o*Vj;!QT)Xr0z9qNvg8xh>E!&~#;@^EYG`c5shv|}Xeij@* zA***RE=j`n)Fd~7{Y_N>*V_)I)3_{lVID!hB{+NnDSIc;4l}V-;%QEjHzaUb*0%+S zzqEft7?EBJakN%H_`AKaB7p45^BG_Y7dk?<=0u0fFAeaSe`oZs3x0vK!iD1E$%}|h zk)A&h_8OX{(;pAjZr$0!uMt>YlMXjsFfU}*m|{M%^y4MG|JEQOc~Zm$dV@p1tnL>;Pgf6GV40${G$E%?0o<{;qIELGH( zBhTTMgzt?!eEf%Y%T_M}v%}z~d%;M7IF|V+U3YgHK6>USH5hmVlN;Ct?UZFWcCGR>5At{^-OuoAyhX`$!38MY*lX zt#d@Htgu%T)7poeA7fN>krh&r)=-c0TnEo_f7dP(zQ7o5LT|09?OS#Yx1dS0nyR%9 z1l_G%U6)&|IN@Z%&IBIBtnKrbXB#4CeNAL}b9dg1c)vd3kz<}3-}=%L;ZS{8Y`8|>;h@Q`esobt*g(L^35 zq|Qt?fA%K92)(BvZ3VBtUjKkTX|#QB-+-wPqy#Yi6oHf3XsSkqa3ij(^}mn-HSI{feLWe+de^4yWRKdn}5zI(?wInl8BoV;u^_@tX&Y1 zr1fG^;T4`b+%++b=}CahUqvc$av1Wy z0DvGto^qp6>M^076`CKz<`Bu%)+{5TQf%pO4N&jELd}QAFR(^k5yqB1fBE`j6Qi=g z84!a(6U7b#^|2VDRsqgd3y`*wCLrECt4=U5Ss=RjN9afpVAlDSsZ0^u3egKFbka zft5IvkXfIWjcJc@TpUXif2VMS#$H^bVPI5bp(GCVMBBA#{5S&n-NO&a89WblRflKc zZ_6D>-NawfWFQDTJXcWPN0BX~|KgD->dLRlciL}n-4*uf)|Jqviq@U8g!rB&ksG00 zVK8Ikt#>*Y#k=}Z(mdk6UUuO(74nWL_J3ZA?0u~U5~~`dUE{M;f3E&HY-PDAVj{`m zmqb0j)o?=pQ6h=;+)6UKA}!5&EHdB|F)x){9H5vq109T6p`E`o|$(`=tWfFK6+EVnfzcJ^;w>L(V55W%MA@ zeS@XBH$C<$)(>hKtBYseMDQ5w12cDU8Iv)3VkI0mNngDOe<}R8n75|?QmpjijinFK z#fXC&-C24-Daw2D*qrbbG>E-P_w3k{hJ3GZs(;OyBacp5> zWMxWkM(6BNQO);7wrSkQW{woN&c*txjy`}$&MJH2PmtrhRp zWclN8^O@@{k*`fP*xjZJg7TFwlz+v<+E&}k$xI(CVNvw@`n?5b{|F^G{?;KR$|H;< z)@98fp(>*{(Nk2R&BC{Kre{uASb3RR(qp4PA7lvbzb9y0v=Iuz0W*x8sgIi>Ls{{Z zGhel}BFzpKv5v-(_#LDoLYElfiq(ZwTNpi8azPM!8OzP@R(NwU=L8W(7Z1-5o*eGw zf6%vFnN>^|gx@@v;5O!z*`K*@jDZcrOBR9YH;OPPMNALxr*{C;r+2NTo%;K))8Z`JuY)7iuYP^l4<@hAJ3G&ukA zL#~|zxv+aybd}&CUWd><@+w=gG+-Z!e=jJNHUO3ofApF}lnh2opP^m-;#U~l0V3bz z>C!o^JxwI&W~)Hv`~ZiqwbtAO_Uk)yp=zgRW7YDZTA0MiX>;yW6^kRNa)_3GXY5G7 z0r5h943LEpF3`3z*YgS`rklo!KqGEd<7w0K{TPPQ02ysXZBEsTiL(Wdzc&Uceu0rJ-oCO0?!6rAzYY5V@-WaB>-|M7Bpw?3j%UKn zPqI5k5n$pv-MhCWv~5J6md<0!z21f>kV%PYx6OWqBvk6 zh3W8&Cs<3BpL4*O8A&=7TPh}sr$8C9ez#w*Py$5~T z0gHUV&bfY&6MZoi92hxx7q^UsauI-8_8p=x{vz2Zo(sC}bG9z?y2Hx!e_MRl^B4#) z8Sb$+b>FeNdm)rv7Yds_?B9b`X4$Og`=`#{aU~swgEIjD1wi`0Yi;&1lsY;Gcpral zZXi*ktw*};XN-U4{o~pWo94#jsR^VWh~pJ5jfS81TQMWzbDM1u%-R0;=a|*bR1Bu2 z)aX5Gd6W{r!96sc@%-*-e?z7&Z^VM1K&18ixg;0bAtRc}nLy2lt#!*+>5q7ruyIOe z_>STzw+{C`t#q*Zm42P5he+|)l-$wc>prjMZ&0)TKb%-k&vJ8q29OzC&!^MtLUd!) znEHg^`gg;200$;V58oB>9c_!Z?<)C+SS*VWAN9v{x1{uz7g$OBxd_jPEjL$pS@`RFqv=8!qGdud_gN)ntSQ}FEko`Q zFl>1Xzo^d%<%)<{{sO@?%Gvl>K!xPH8W0U(`H=^scwCcd(E*b3e62CpCrNh>calr> zEB>Gx3r?4XGWa#B+b?F2ST9_#b zr43$C&>j5sW2>P%DiadaLabJ%p5__pGvWdQ5t6d#D z-DNkofProiw(BU+xm{VawIKsu+?9q&a~W$F=}4EM94jA$+&qO!KTrLloh<<+ePyvI zI|nIA>1JSXe-5DED}kv!-$C;##mwq|h|9*e+!INxJoz#fG}_l_vtrsF=HG@g4{}HN zok(Cif8i*Rj6Sw|ZcmQcG7Ia;U!6BentYzZu#esO?M-}H`>%35==b#0Yo%Bp4!E&$ zx8TEnZj_?NQH_YEJ6nk17cLc)jKE`MH%sJ;a-j68e|ZFMUcv20^&?knFO!~2&h!~Y zx<{m*h!DIgLSIy2VAP{slFe?W@ZVRhDP^&~+f%D;)PrC1;z;ZS5d?oN-o6I zz`@wFQVes5WnuDY${L&Hq-XXcg9M9w?)q$VZllt-YHjW>hJfj-q=L@b;K*`kBx|>X0pgdqVoGwdU?vaFt_HC3I#61(sS={hF?+oaEP2<&9SgufOds>QhCZvFA?u`p^G_Q5Tyb4D*JhQjG~6DmR|E_rwG4{E+2IbfAF#M zLniYuu5=H_vl2T+r6H0CMC;Zz55<3-j{>7ZoyFDuujUwo}a&>|RO& z#Xon@mtBcXUV)mzC7ZS)EhR)2H@HOw>jE!5kOCW5tNMY# z>I@nLCXWUtfcoXLqy`Bh_eNl8mULXWA+Ae!2bq9H@%a+2%3S-ce0B+ue-%-OUT;Fr z7ACrl1*E+E8LeXY#K7@A`418Ob^U^ut~7p|y(A~c(tD%>f6yO)%!a5SAPCgT+}S<*)>3>%bSe%s_6* zXey&rlXR4q-&#$-PS1(Ne_tImgeHv_!mRBUfCV=Sh3X(rD&36O=0xR>$;_F;4(!{E zQ>f6p#jRYj74;H$pv>4_&Hh&F0K9JDd1_^`hv#H{bV$n!wVe(C_lz3Y?LL9M=1tSG z9u(jSqFu1%w>jN|70ElPfc*xBq^qa&Isk>4^Tzb^C<@nnUaBW zZL_PwWDWgyM%sqJ5U{`e16or)f+JFR1jo zF?d;WmYJ*Jfy3%73NtG41ivOZ%G8iOd?MvcORKUsWVU@qKTTmsauXrq{;ep0)k8e- z{9OQRG?FF<^Ii1@5~5D|4?FPblF}e=3;eg-$uZ-eEB#4NfB1b0y>6Gm-KQ(EL1S=0 zu0MRz+8|ANfm^c4S?NAkPIrI(H!$ilRVg1kEKz`^V4>UZjQ+C2fGDb^#koy265MGb zXRmM^I4(>w2Q4gM0{7D@8t0B?bIyX1!f4g5hhbXy9;v?%m_9Bso5M^5e$1nSY?_KA zh)rYt4vg+O3xEu+GOrKPbTKg~YLGwOldx|B6a~5J6`q|W0PKK!YaKky0%L!EHKRms zG2El@e|*(Uwg8+V_V^3iTj#^fSIg1k#992z(}}{1xIqgb`z+jG7E=xSJDTXc?r2Dk zxPlI#3Sx`!(!f#AgX<_wv_QjLs)4%Cl&S$&tlaTv2aTig<0gSo?_Qun;kDbjar3~J zg*A2?I0~@|xlKiD;giq|2f|dzxa8|T@+67;f3^+tCBlOh8o@ma4qVW*Hzs#p&my{Q zNI{>2n{DVL9jRI1^SPWOyrCE%r#T>Ub~#iVHfQ|Ngbym4rb7lwXpy{YnPyPC-F5AP z$v~P`N3)+>`A#?_!Q+Lby!!htcc6?qWXxF8U$pR$5$*UYPhmRKIL8wZxi{PDRkr{k ze~y>Z^UGQyWe{N4OUsZsBvRPSn|)_SeK_%+MXsN6T-r-wQS;==rm)e8KdWb1CdrPe z(Uy0kNHDw=S(>C(Ujz za7|JN`N!THPvQ-lAk?U)MRPo()Q@QJf1NDfh_bx@2H_%k3pfrGn5CaXiKiKV~l8#S%1s65dy584WW`;ymK~W4Y)!o1$xk z!qP)&u8#&oJe6Jn-6>!D~=cN%QK{|1s(JkyO#;S0}aINe`~$01^T)@ zzP2JNItn9dZR;h<1^vpYr!H*=IWTdAOre?14ajcLcHh=AEmK$gO;A`;Qo@XP)-L>} zDgz>n7;Zhj9MUiPBo_K&yN&G}T{d^E~IknD%3BmoXVsEC|& zm@!7DV&L%Gh4w0lMG2L`-Z(#u(MaYOQA^=1Qsnlud;}Qv(4XAE(ECKeyN;S`J|ZxK zr{qDd#}%bQPAH|_ugdTec3*v^fg;xl+Wu-;_~V-g;#+L+3vPlbfADt`4ZUlxe>@nt zfqZQAa)U98&zN=+Y-_s7ssXH=iPT9br_qeh?+d=M@Yvq=j6cR%5yy*&oT6_n8*O`2 zkTFOrq>iI^caf=1d@7*FQl@QkSlg0 zolqDB=$_}A>)`pb3Eg5*5r7IMyD%Q+Muqi;bPNOnnz^=8-cR1}2>WNBV(fZAgM ztOMd`j!o*Zw2UUVw^_#u_5krP&Z1;C`+97sHn2`F!yxKZxVMe433UeFu~Mf09;FzBP0%o2Mv6Om~p#;m`rs zuClYuOH0PaHjxLZ6{e(;3ZqLYK(SyEpMm!23Wiw*<3P0r#p{zltZ4)`BV_3hh8jEo zTLNatdPT$9LTgHWKsx*8G!oSvNb5GJ!sCVw5R?Y4{Gd_r%XgF_ub|)t1gO{tEhpEW z&#&XQe{a&pX9NNR{0PHHYTap)>jkY3`z-cF%`U6Ol)Q05xS20UnB%HFyASgQ@%p z6!FGNoR`9KR#A?}xfZDSpE`m{ncbIKtcz7wc&eRv=WCi%)EDMJ0fjTInhm~-n<~Fs z;qI?Eu)JLtZZ`utanZ<^K}0SYrSScWpHD*UBP4MhAa$X?MfI1ex$ozV^A2;pj;q7~ zf4INSr~Am;e4)1wy*nKHQM;tnA;us$S1h^FsXa+{mww6?Yga`5MK`VedQw0`A-w46 zhg)s_j1-&Yx6i>)52=YW3p4)~NggIM+X+{7?|f|pLSZC>RSZ)tush-5zEu@nnlDD? zA=I^^;n;J@1C;qHj9V{&)wV9#(&6rqfA!^nB^7@iT^_uEsq7skG12%xxvg%v3*^G!eS-FJz(dpnZlV-_^djs}GDD1*&+ z(t#?OUk?Yz98kTs0`a`o)kMlBe-z$DTfl`8VoG(F@{2Z9;&2cotdSy|h`|UcKDgWg z0#UO>8=9Bd$I!5S3#|P^zW`tb`Q!u@4R^Qq<#(;RMKbzpNIF?#xdcivwgK)7^oHpd;uhVtBye2RYCp{LXMd6i&k)h6I>MEXDfv16o;5Lgv^os> zQqYg}VL-m_Ut^L*)JhY$otK5q^$RTa@bYC*d=(v4kaIxoM_Rf4R_E^v)eEX!UpBj#i8z=AMveL=c%jraTe$F_jo)g@((N@p+!ZQXG(?>$}Oc{7!>ZVKjGm7AvfQ{ry1H; z!Yn62f&=zs2T(2zCh-+(y_(+og4`^vwAg@Id@o=^_Q0$X0d!Yaf9Yazm9YHSa9H=^ z2k&%_+&c`Y`om%Ur!&0-PcNwTWE*=t7@>%U)A47A`Th>YD3|r$wIDe|5Py9-lmIWg zS2~_rpHElKN&s3wrN4HkOLZ^2G+Fo8HJT=g43L@ufmI|wlZY9BJqg44&~oyyU=}5a z@l9S<6n!tdPSB5zgU0QKz<=>?s>ALtfyuvjf{NN@Vm~jOiU0;g0puO5XvNe$>(yD; zNAP(YnhVFJUvhKa{hcGzHrI&6LlWfFL9;UwdFnzFqq>d97@Z-nXMVH0`+?YTxB?3w zOSkS-k!W^E6McYI>qw%CgioLSExGP79%Yg>zgr=^ORhk#wPs=R(0`a2%ODl;jN2DZ z)b%A^BNQAWA1k4Q$VpTaLUlyp0~iBAUhT0L*>Ho?siyQ4H6Z%5t$B-!#Z(f z8v_;entQ7vupAq>hEOfF$Z``7xMdjBBYh!b+p&p-cLyaoSdws{fM~XvykhmcIGm-M$h`)m@L%YWCxBO^_FL)$>)^3a!( zVLQUeE5AL$g0(QQum@!f_n&hW1@e#c#3r#uSXcRsFbWuI7@^kWMny{0|ehp21b2XJ9?}cZ&kM>*& zh_ckQpYqznZhu+YmU|b8&WHM95j1}RhsFXGAHpKp#82RuFbQhN2<@Z4GiX#SSr%@4 z*{r0Sj?fJuiRph|M)za(Wbl}!j}Hd6V z^5w+YjKSy=$;OZ(M-;}+>zTbP7uup&GXW`I(wv&ZvPa(uk9a+BhCjU^wp{{0NCLso(```(Fo|1C$Dt!-}YKDIK z_(Iu>8h@746n)#pC+TJs(xyvtp-7Y4V9XmIsI zXwV33?xRMyWG|?yzkcY`{D@v{H9RWR>JByl!Fx5oxH=qkD0kkk=D}H+$O4{mjAxI3A%~@h`QN z4vb!YhroONBUrshpfF2yaj^;K+r8FsKYuZABpc6=MH7dSNKY#7Ps0^ss)9FeKkVn@ zcsAp6TMEJ0-;M8@5P9b_^Vx`@Dhymg5)W664u+Mk$TzL}n57`T`3g7Zv-`viU-Y+s zz|k63NoYlBj`Cm{c>`PIvlv<&29wh8mq|UgQFARFpgg%6hWSC1qF(0ex^7xE3x9jZ z$PN1ZJf9#xMt9PBme~Y#gs`}fdFEiU^b;41wgxtg+Nn9Sn*2LO-N#QC{2JS3Z}@3R zsWfBgOn!ScV(`iE6VHKbt{EeB$1Hv?UDvwxz8404lBi_wT`ekKZ*z75k=91SNMaY7 zlL83JK}}P#HWzm@sYdO*Zdn`pQh&dTepzl-*jtMJ4mbWZ5vaATaKn@$Lo#cv$&&{Q zj%P2PTIPd^@cYJ+X`RI5`mKHH*OS1fVZAcxAipPM2-C7P4SmKql6? zsa?>%Ce~$1{-tp7Bu$XvYfY>dcRVlh;&ZEfyb z&{lJ2;Utr1XUva}=ir+gCsf*ryU$UTk>Ya#$TR&OxPNW5 zZQ$S`qZ2St^uj8S?U@F@gIT};ld4f?#B@w&&KRb+w$7YDIHs$2tHt=+7oLFx&N%%K z>H|t#xRlQ6Xjk7xZU4Qr`69yXM|V`nhf?U&42u1QTADB&5akNwyU*ZQrr zr_7|`YI7N8qUJgd3v~2q<&9465^OZ)?48LLeO=m4Ua*ulBenN$W%8ZY2TDzPEjY$& z{boOHSCk3WU9-igUw?e|pbatcZnrlO-Y^@#OR{I{mj;$XTs0{_zws^(1HzdpNJC+!;Y4^D)?WA(#E0e^|fJLp77U?4WH%)yRv zz?m*$=}oG@ClN@Os!pE#nY|R;_teQNaO=YBH$%V5et=)%^)lu?FaE&YI!5Z_WSCy@ z>IY#7mb2pa=5dX#XNl*gAFZo!%X(|{;9P@R$>`(i5!yi!kHEd)mI7h5BB?o3lT zezURSIw04WcinpI>2BXH{5mMra&DrGh{R9!$>6_tdZh!O3Zp`lkx&V_wgXO$rG;u8 z>F2k-%Pnk6sFBYp&`2-*P}Dh{_!981y_tT~%IF3-fq#!>^%b|}{$;d|ME?5qD*@1a z(c#3xSW=)j0USx+1dN(6FXW)rUB0bolrd#?9+ycZyu^jCm{|GEVLFW`G137u-YWEx z5@SJ`lf)V&ub!FtaoRMg<@bKwP>i~5r~*qIXFnT{JE-2fCafKW96iENXE`Idkr|IW zvpo`Aw|~*fxYdwTS^F{$roK+r!8QDXKQ5F79u$;sEHdg)+tNI)&2^h#wGEp{miF-r ztFxYX+u}iK>OTb$by24JR8%X>UWv=o$^0_bqOFk$iHsaGxX7xxc+9zf2T3XjS#A<6 zW+;R5)2Ti*aRS&!^EUVMUB7|*_lO4;X}g28&wrkN13r9Np}g9&G;qbQz$9Alp*xvA z){kG~xox7{rjHv_Z?$fxhn*|3d|Pu_Lh)Gl>UyDu2AH{veef7ky6wQCx#2)+K&#hp zw|1v~;OGY!KxKokUaMwzl)WLgS;#H>GO*c$j-7T<(5TQV!w%cj9;%jwGLmI*x>XyT zzke~m!4x&K+FdO6?wYIsVO^Ey3a-ft)YOcOFY|r(&iQzJ1L?k7aCuL-gY0axW5qUy~db2UvpQnF(G-D5@0UGmVb&S zYAv+B=<{7INEaWLxrbb0eZOC!%xYWPuHAs|1Uuqkeg#G_|j$o9`XY#=wO&OIw0KxCh@h_pwx^^+W*wht%N(zwWA-fd!&rG08FJfzT&n4M5i zuT}+Fc7^={o9BL-Zb%CZzfoDP?tcY@xU8?^$cG%s%A%J#ri4fPmSEgz{I;z?Oaz%T z88p8Fiy7*T`7ccb+WZ;m6eLWh|AJ{u5ibpdjM6AW80c?Flf_@oE_tn@8p$(_Ibp_8 zO+xI$jgV(y$y#VLCI`8aoR-zA4{2dIthO*oIA<)w75q9_ z-Nltg`sA0rY__yk**a|}r;$vm$F0Fm}imm*Ac$bp4~wC6+g0RA_sp%P|{}nB3 zrc3n;fx3DF+j#-Hq)9aV3!MDS1eLtdn{UR?*71#_aqOglGJp01d-03wQ?kP$KdEG0 z15IjP*-_kQ4ZU>a`cQt?>M+0Un?3D@Db39+%EjWfD#?c0vDa&RC4U8QVs)q{vp~LHyQ(q(S*;WSk`WqO4v2_O@xcDxl3E;{V%Q+)@6PFzM4`)dt9lcHt zvLwZ$#j5_PmfaWXPl)kBaB<1K8H@@>4e-;`?G4MiG+&a@vP-uYA0Oq@M3rmDVw>}t zgpI{i7pdGD)~bD2|LA+E)dD}(CPkd0+Ncijdv_CbAb$~@9Y#jEiNOQhbL~LfMyUed zUIW*3uZ9dz#2T>2I$Or;`oU|@#ZoLmwn~eL9jaoW?E2RvZa{IlkNMk=*nSNxuw3|> zOH}c2pwm@J(Kw6-;677llK`}w6~$BjA#ooV)5u1?^1Z}2j?le>L4FBa^BUCgr=dQ3 z+(@t}ZGU;1S91)}ON1L}XK`WpO|IEB0p2aEmX#V|RYM)eBI^ix#28{(-VVujT49WC{^~cM zbE}qu6v~o+y_SGCICNlX0e%&Ix&PLhx@uh{$bV!~Zbn;1~5s1}*zh@mO@EaV}p>jSQCU0rW-sfB+s?o+l)6R>dI^feZ z*+J?go9W8pXY9V-U>mBi8-n7FgRAQodw-%2{ds-K0?ofF84Ug#;1*OW{_P{{Aop*n zvo=xjU$azyb;mD37z9dtX~+hO;NIQO`#2;z$@Qr-Y9~9OjaOcmpNak=Idi8Hw%65R zB)Ssz5I?RrxF<7@gy1;atUbL^kcI*r)@fFT!bS@%{Xx`^l0sUk@3?4wl3&;sl7F)H ze|IHSCL{^OT{RVa9=ZKcTRI)t)gHZoFuFvMCJuf?9htgqAe8M_v9Avx3BLyCO8iA) zI|VJ>31tug$=Vd=BMd4VgIda+$>pf#dUuGX)uF8c^~GSb;p4zub&LlS>^bC_jO5u@ z#gFO)fOGo227F!rdK_rZUXFO0pMO1QzozuS@T;qT=4@!U3V9=c|I#Tc#7t*YLai{! z8#3)-2r?~8*dTID$AF;;?MRfTCj(IXd@JVXuIzt&{t&sdYoB{M)lG5We%2{S5y#9tTE9j&)FD*u6_-1 z)m+l;TR52k6H>C)E-^E$(SJ=zbx-q0VdZ|)46^xf6J}al&>JUB(Zf>{96okLU%uIi z0UF0kA4gjmU>qj=5ev<#XY9-T~ux@v*J32+E`+$H-C(&1IwB2EW$h$ z-qFpMYu0(T52bPxHT`7A^NQPB5n!C|@SgMWkI|SsW_~^v@4&!%rPYCaC<1-BcIc9l zcJMDmEwKFSn|vKcxrk!WwTz;mb{rl0v|C;xofALDa*U8&z$BU~ZzFOSgB4~e!}8S7 zFTNvX4R$Ggb36{=-hV`8&3zDT?q$)ThbRjOjmA6a_St-&@P)_C?(1yI5ESm~*M3r3 zCRmmbcKy ze0JrCa`mqR-_@Zma?86vQT6>R>oUD5Y4a(@A)c4DP{K4Owtp@~QWGOi-3Huu8)|wP zIn+BjU2{H4q=DY20G#Ym)GpkI+$tZyv9>ps=+#@*WNF0A4Fd4d0c(sW11U zm9H0y+fh5NhAr$m2#{9o*F&?PNEJ}-$C=08W#n_t>{6j!BW2520)Z4RzlZAzX_6Cb z$)aI;m9duFn|~4=Pezkiin3DnmoI1Pcw7V8#UWCECJB--pO*!v@Hb>vGw`@k{jN8# zrHL<~F)5&1n6zIWM6V1frb_6OxJNqz(fbH#XFd|jw*LabtL zw!269yxJVh3?QM*DyWf*fU?4lY`^7Ve1S%3%1?v)lGDk3wrUXk?FUr!;KGYza=}%I zI`Ei|et%R0691ls?<7SUFY%PVuUFaGlBZUgjvKiq(Z6-`7Q_N)?xDmMj?@q!y8^m+ zMDz}?<7>cW$7R{{*AY0ovur(H!y?q>PsA#3FDIO8Q)mb~Z7TQQ-eWJF;w-^T6CR?_UWZi10`ge4)ow{g`Hz4CmprJ3?v1j3y z;eXCCSMQzmcP-6bEHuQ)lW_pWqckW-W|SExQ!|7?WDZpdbKl~Nr|8oY(#$r&?&f=d ze}Y9~$+NYP-Cg2U6dcLeDlB#?{4nR(_&X279V7%)Q?Lx&wI+tkkXRjWO_UBF_=>!y=Vf}p&T5^>(pFhR=Gk+}G z9QaGp&RFBseo8LBk421tMQj~=NkKL}T8{{_5OB;2Bl7zutq)t*_y~MG0B3&&?^_56 z590u@!~h;!mk_2y00jeuEEm9UL(CjeY_dy?7WL5)jK%_=wl3!<)LsLz{aM-~-za#S z_kQ}3kN-3%c4Z$;(jAj#l%D=h{C}s-8c7v%eFidn{fXyrb_5?sr-W~6a^cJXLPs{* zB-M>!3WDVKYa9>7J@mWLS%z|Snu{LhSIdI#%=25Oy{T~Z1mM|YZRm{kx}fX4fhnpy zV`1{(A8c1bs?%xpd3~+Cx*Gc#oHH0Q#4TJnvGz_Ze7St>@O(6Yo{gbi{(pieRDN9; z=HJ-WzYuzc=dI8ZHghe2#<8uD?;l?%X8clNO9;=$Q^H?ePZ|(_nZ5uxL*Lt=`af`l ztt)K2<{~S`Y%N9kHa-6zNoTPntr7*{2V#NS5|_rI8`8aa_6Msgso1x=M-l3b&jc{y=%GA75li<4&4Sy@y;LF9@a9zXQ z2lnLLcg*b#AhQR4=D+u9$t$nbW$Y}~2%fhUdhP7hTCr#qnyYhs1aqrFW_R}7q3`_B za&1%~-dnA%);pRaJvF;HDYg;>R`jp2mwjK$?3cxYu#CAwOw%P45stmE%_oM*dh}pgSm-(=-c^@P~r$_0jls`7W57ay2Fiw^D z^#dbs;(D#k7wh#llJLhm`&B>~PY&D6A`Od)MbXg^U6FwBxp$=Za3_;eVmA1A&<#Bm zBuw^LiNN&E;g&tIVt<)|5U^Fi6-o->D?%{^6r!_;^#CFvQQxkC=~e9R<877$;RVM6 zZuIS6!3MlN2$Ri; z#nGcKl$sqh(z~$Gg}#AHolUxx7dDy2>kYh z6LQJiT5!BAxzd3)|G# zp0TLyzSVE*@6U91-zAMT>&(r%H|UVP?ztHu&!vD(#1rFKPMp}Nhbe0+2yG9cM^4)b$P2%>@I#exkZrfY@b;dPS!k~n>f?>sTQR8=b%nqi~ zWdhG`+J816dGn-3*!x-l0imN6STvEif##L?RHQcWDX72S(f&?@v3FIs8aDc*8r9Zj z-YI1`zK^(ep$>)n3|AQ{@R(Ike)G`IQ0wZ`M$L1B9JpH@%k34_7}vhECnwtDJ^mfp zXg{FmyU9!ec&7~s`Xxy3nq-FLFs)tc>{J|O7=K8BDRMzgarb7D&zC?TwNDJD1-_JY zUzv!;^i3W)y*6mr!k2DD;17GE<~mhSy`R!Fq~~XRbVx$p@Q5;aETN15*OWQer$Pb7 z6?LMItwH?EpL#uS$SN=(_BQ|*%{yFJ+!E(iC<=)JDwj5t19+ww$Mxj z3xDA}Ly@4OF&#q<7{3nnO?d)yX(_bZ{H~@k{_Z_LPIB1WH)*e@2sgGwxLov|Mo)DrUHjEd{>ne=qn=c0-JX*`C|YgF_vr zQp2~N!wrEKmmqW($gQ9A6J7TzxvVUrt$#)Nu2yi$cGOCExo>1w=I<@$Ag!G;r_Q4D zwCz5}k5{bD0%3~WFCZ+G{@_V)RVmAw(P|g?@Jqp**KwfB__Bg*4h1AK$EQNVdJs`PRiZc|zg2W#st;X0T5%vNU;ZsZ6`Dw13Vj zXic%An_aciq)E8Hl6yY4A;PR`nQs~d>&*sCh1D)>pl>Qw$YTgbsX*x26AxiN>p~cd ziMV9Gi0CAQNqgufo<}4BfP`}W` z3e-#z0J>`BXCPpd9^JNg46=ks{eMuYd_4xq5CL~;o7PsCJgf#brk<@52O+-lXr-5? z^MLRdzE-&blB-8YKrO6^8gx_jnxeyJ!+}~OiKRm3(OU}*!Cs+J7Bk zC*Cc-EhJ27l^zqUNFcv*FrksWGSJ_MqUw~LfFU` zADI8#hl2Z8S(QZowJQa;@qhZdvZbPdqscq{*XEMDu>_^75rpR<(GKtz{b;j}+x{^; zl99#KQ~@@gg%v@03(n$XRQ@2j9~1A}Q5I@lqqs$Yf2s(0)3qSVciCW(x7Zs#4*E3y zx`^L`zQUz`PAUzc{4fWcTWvNX@KTVr%|a6<57WNB12vqn*K2dT(|=?)&9r|KYxO)7 zXW1;;Z$N0ld(AnX6ONYV)7tH9O1HZr*^#0lqKZr-oj;%c zO(LkZFj0QKsEYAlDSwznE7)8ga8Z#siE^7_oW$NFE@tc2tXV@Vt+v`_yxTihJ1%l+ z6;S=ix?qw#&iD{9)Do_9h5V|9&3!a=b=u^;#lSs7_B{d;p-cFYZ+9(5RYE?yq&mvWRTIz zlng1;`$wUNeXmA5LdFx{iRR|P!$;Hzm&XtfF7=Q%?-!=38SV{WN~9;fKOT zid4T`OqaYc0y3`lZ=7E{?;%?QSkwX+g3H4VTI2CBix2UR+Mc4cU zvw7`aJUL+$PU?~P?UFuDxw(5I+Fa<@U{%@AEq@cKu9!^RR~>tieXY$~%|-(r=@7pI>%wIl64uxj zzkl)3wk0?otAmkCCkKePiRq1|xW*%PJR5dFrfE<<02UH&BnuJpx|QD7lUP<*stl1H z{Eo;A6QCZ-16&!9EL9Gs!I#$z8-+fSu1-U`e`b1pEsO7;3ql;@O@=Ax1|ShVf*C;t z;I>1>wh*5TTl;yU&7z9&5vplp2>aLJfq(Kd^9V&2Avk)y&yUfAo4?*~SYXvl$W4Ei z(gVFJy(W`5;0xg2+Mw|v)XP`(d*O^eLC#4d*4MdHM72$*=(#}*{M_o3SCMc-s8Q%t(@bCtij#Gf&3V1fquByvgnz5Z zFUFTI>zxS}FhqUc`Z_xsiQ<0NNC?T73Bq7KH#Gc8{kU)*4>*5MpC8 za-}zno;LH%2ele8g;byTntNtVT7MY;q}~A5QkK(oGTLS`s+Kt&c`(cS=&)cwhn&bV zWG?>pOf#x(S1$?CF|)VKsmR=aKzN?tHTT*Z1ZJ`jE-+@cS=KJQjjZc# zQ<4Ae^&~9HN-Ly@V`wyiS2Tc15KOl$4glosuHa-#{(YP({9^g6=syaN|9?&raO*mg zKSeWQI9`&h(IUmqjd%Ho5F9r8rp(a*>LAzbkW%*p_f)(#L{=}_)M&REtu1liRV3j-hRmO|YBnHRSWOvx8+kafY_{HW!q@Ewd zLw0V9(51F0dNAaRy}?1TV89>{l9oD}?rvHomT6nY?AV3udjvkXms&TNZ*2gC-RQeC zRmL3&RXjzfPW>!*HV8~rWin&>Us+HH>~2HHXP0+@+9xf>_tGpl4Cn}}KBmIBli|M) z2HV3zb?*9c!556mu7BqxYx~A0L+t}?_J3=5)pG{F?GEyj6{)iQj^C$WK(x&92%0>rJ>&SozL)&C+(quElGP ziLeKjIXjJ}9KU^N>;OvnPJ(rOugc9;yBH=K5MlAopplAtW$ zrPSPV;Tw2S474w&A?+)i7Xh0cIC?r$shJ6cbpk*B<)GW;m0iX^+*lx@%a6Sy9zj!#n;mP9oXxho6QP*&_tw z^<|N;l)K3iv34jdec=N+zNa`JtAlb}teflM3^7K`x_@FI+q!2rK$q-I8pIwmsUc72 zH0!yF^2MWv8imwfS$rjl_d@a0}26_qQh*^6X_t5G~JGxi;j9NhKAcpv!!D z-G|tKGk>kHBH2+#x#k~Fa_ZB5aT(UO>P|Ndzg;>ThHmeXeWJpi0{g|=W#1w31L|mV zy-d03vIh9&T`#k6Ta&-|?Oi>kazuDWYb@<;I``(xl;lE0`Wb7A)F5Rl66@R;Z+e6Y5^BZXx*m2CKM?D2)52GM3 zWlpkLnvqiW>yn>|CrByEK}0q9Vnzzy2q!>ZH_f$(*<7m+FCz4YcCqF0w)0!9*}bzw znkz97bPo1W=0c^O2|PW=II-i9*U!rxrwLc=+`i%~<0L993&TnqBJXf6jKYXztK37@ zE`JgetEjDG@3?SQx(a0m2Y6WIFO6RUQ;eBj@ zfgbM*`vZnYG=i;&H8^NjyB@WEm_=J>g~5@0l{2&`3Xo;5ZQHhO+qSKDZQHhO+qP}n zHs;SnolMtSm7J)8y-%&yv!-$Y0Eg<=ss}F)lpJ8(M~pSQHpi?4$rlgw`M8w;27h^m z730{0UQ}DjwW++$tkZetT!az>_pCp+E7q@bKP69LSMa4Na@!V)(6TLXESCK%89`#G zuYcvUmW_b%!!Qk(7jKMPgt1^|KC2xL6YV8XPg|AT5p1e`ejR1S8PZ*xKWQI_5U%*7 z-%Cr(Q$?=YNw}p57=K}=aep!Mxqmgn`eE(8GF`3Vy_fVo(d+eXA1ry+^xdGsuaEkB z)UxaBSs^5R>@RZgbLrTgi51di<>#~Ag}vuCK8%7#NU)d9g$Foz=jWKP)Rh9O@4YM5|Fk-OI=;hlx0aNSjnwtuL0e7&k{ z|4UY36`f6+1WA|Ys#b3MlBKQEH1hgz`?ZGTS(OXlieV``S@Krk!hrinzL`ldRFhSm z5jAHo5yLnyhofo1$eZnn8a5PI4@T$IR>M03_#(#9TZ^2|+P zmAg<+fXzX>)}uc!)B@s`-F9qK-lSIp`<1T9Qbv6rio!i-H1vC@z?G?Q8$HeVO;ySG zk|!jw4bqYOuzQsc2>5mA_}z-qdFA>+_;^BcQFh90h%qT!5tyW1-hX94(1P9U;#M4xWnK^Buc{b#LHS;l7S` zoH8Dsh6hR8HF+Du#z&;eWlL(5Rx29HtjKkO!z|9u05h2kG=GGSqoz+LFf+xKi<&~L z^=q_o_A9i^U_YN04c-725Zt_+1To-*EBRwnU>0qqSd<*qD5Pke#{@Dzzo8pTI*xKW zB;YLx@wZ^WYWSRxC=kAeBPx6N54v;+iOp9oy6#$KlCozyuEcoStn*(mnkZgzne3(E zvnYEO7NJe4xqlFzr3qD!vF3W1eglipYQD%nT|~U$?-Bk$^0(>V0>_GXCZEnS6Oba1 z+e;w}5}-<`>~%l%18~GE`F-CuhlZg0U3czYcjw?@lkAv0g`jB09U)Qyb20i>rjtAP zmpUqWlIsrP4~%Pn9);3W>Z9mmk+nGiFGoF1dn>eRNq?~>%J_n-dxH1)l)=mD248A4 zD1Aq(G`vy27*;z)Erw4rfenlrQBM`(}N)@KinE^zrBTwZt4Zmk^mG{ZRmiW z^@^HXP~TSVQ*z{UA)|u+ycjV5^_gw){sCmIcmDVF}Fely_y= zIoCoHRiypqV6ry@lXT43x^qOa*=qJ92zU1r+*Q6CurzADkhLb!o>Y#&xkNZu{t2L5 zGK<;Wf*bo?K)|yyzb_PT>NWCqXTep+Lx1>PlWiS=lvVvTDcGDu7xJq!34R)AmV7sc z=@=-Pl})gJz8ZiL>1KZDr6KP1kYE#;F7;f{w!B}{8rLLxxBwJT+bTwY)C)ILrGYTn_UoTxQ@+=cCn z+?9jO=%y8~6QYEhQH~tL);mEu8blyvEuKY*`&@?>6eC(|0gt|;UzXp*vC%jTU;*0Bb4Nx$#bv~UenuI4WdOr?V;?Ch)HoXJv6S+mMWjWPJpb(tJFWZE(^ z7U|H3iWxpLQ^xC_a=;Tcd6%pc$x4p+{RGQmk~exARuAnvTzfFHEHbO(Revn>0o)yB zgZcoBS5`sKkddA6s9u4BE?wtho#D7LM{q4~c26fQXUY7gR5U@1p=#Ok?Pq~nExcC0 zyZsD$Y@Y3iMS2%mo>75d&3~}N(^0a{g#}|RsSs2|r!jwyj>xrjVFsvc$gDid!R1NZ z8Q!k;_e=(RqvOAmRS>>W!GDjIA96~MWJlXJw2RRdC(|j!qM6_Gb7HdjS~7hVl!zw9 z<{P=SfX_azDqxHX+5C45S|5|BnwOV9@KV@s#FJJ{{l@HF#t#6e$bTuKH{$f23Jnvj zzSOL%*jym9QQT}Cmfu;dlHJsxgZmAqw}x9M=zVIIZzFXO8+_Octf9^3h2BavEqJq; z52s+tW`N(Yj;69f_>@IZ_hGx8`0qQ52~IeM9`*2gtQ&R&lSKQrxK`ek?lSUS^Y!!g zsKzo@nz^WGE8_L-W`EbGy!VXTveQ`kz_1uF==JARzGU01Esu@m{lzJUL zR7~ia2pBjsGHucfxI^J*T74v z%{W{Q2$&R$-cEBFzU>u}qG}%J5(meHA9s6vg zk47dEvqQ#(7#lz++=-<$9h+C39RE)@4f{U_Fom@Puym-4H<$%Jv7dlGgR>z|BTA zM$ue4RA_s@_Pt1QVpXhtp7>0Yl5_>6wyDFEvv=_>CBIIcf(4WyuH=Kj*MeAtppn}M zD!;kCzx!2w9+>U_ey|5 zO3kTg-zLtjdSAKpR?dnbZ`J5 z1uiS@_yBwD6y|X$1815EvRX;i&IWJjb8gv`tkE^_wcp^@ZAC;j(UV}$KSRl_je_?_ z(X_kR}Qlu?yxz4ami`;s!v+BWheD1{aiI;r3MnR* zDwS`!FAFJP(V#G3=vU1!-S;V6E0jDmP>=_MfJN`U5I@q{q9`PH$X79KYX(4ed~Jcm zD)LV5M*a7`;vwtW@{}Yki5hcyU>ss{L{)6N8w}e-@MG|ctIe&nW)`#!Yk#rYEfCA^ zCRWTqcqMBaRr2Sev#QuC%UjMj%$B;+aQ%XZr;^XfES!Mfj1?|vL8`$y6JIrq5^`gJ ze%<m>DU2wKvgi65{DjityQ()m--o18U|9G*U5 z!XQN~^B=-sX1t#Gq3AKGG)*UFckP)||4?L=ltz;`a_|{}kE#M_@Wrx`K`j6uQitad zqZ$Il=1~kI%Y2TjgD7jBSqm#rq|##TTfdzpx0X1&&XsmiE*H z-qqN(=y9Bo3A+cNq_~}f(rf`S995;P)3e7D(&}&bZrnZdS?VKpN6ro5t678w?hG)} zlxC*P0%R3~%`VPLhFMVFHLE&aU-hQ{E*Xc3-n9yqfc_XjLobYgirHPR-a*$}=Idqq zQUAlkkz?5M{xWZO@_(#1(I8~-Z_OXm{&edJ4mQsWa`@WQR96E1JoHS~(>B}8(xY(s zs=FV@$7^r5vZ0POOy8GgBZ=2qtoGC?d&rpOd4sQg2vay_K;S-K%a*l{6KftnI7A?r z_sQD+XCs`r!uwSqVgP-&t?#5u`^l{l2k7J-261IA5%?9E!++!3F!pRWc79x*c5F<) ziuiR_#r+s=2Dv^5$|VH5YX*_3l?x5Lh(M-2MRzS^rB0b1NB4I9H(~+=LQM$H|`e$e*)~r~!2|tfPi0C*vNU$3bHj;J|uap-m4lC14@Zt;V^o zOR{f|D|Xx0iJ-AbNMv(58MKpwwQ+2Zl2H!l{jIU$Z+|hS*SGCJe-U?)@d%d~$t4oC zHVLlxloX)Xw6UYM%BA;tKB_%-DHOPiji}Vv(0lHgEX|Q?HXm>9IGhW zmwVNLpFLv5i7V;cKUsOJBSV>6!_q%HmJyjDr3$=oGlAS5APJ|g3rWr0Zy2xqrww{w zsCb~j&ws_!8@14{7uM)1Mac9F3Z@?c#;&!s+ry%lHGgrv6KD*+IVYjprOTfSW)|+9 zIg|;=g&`tt)QxYHnF5&UYXkfAa*m3?*-6*U_b!TapBLry6K#>Wk zdZ=|8XQ|$a{mvgGJU>vnz{OtTF4?4IRN7q_K)kfS!Bfy4q z-?5%rus;c}Rx#?Y5bY=65X-~KyQQ8DYu`rh}Ji=S1>9v#|R;?E4WR(~R zw(@dmL*}yzGSw$L#FiI+XFHsqHGk;>ZttvfW1JR!4t}=P(l2V2VI&l^wLAVSL=>5W z<*=D+05L$$znZFGP)T?e(Bn2(jogAWK~lQ6*tJ2*shI}XMmCMeKYb=N?}4khqP-Rr z&&BdYt)>>HUXdDzCJa4(*;8 zSBF^!-zml$`)a7uH|q~Iv1=gMCnlA;@s+P=J4)kX%=`oXm2T75&)~_DOr(p|F{i)e zp2PwDW(;IcjX0s?e}am!wrjql3;=%`V|dtm>z)qxCsVb4{2t#A997l%OT9QzlR0Sq z;dDzL@>fmV4SWSn|#jL~N=kVI}_3d+i=Yzl?9UXCh=YIoKmftS6qETy9=3>}6^=81nJ5SC^# z76+FK)(i4POzPdR@oWv-$ywMDJ+E2=KWTMOVt0o6No%3|X7Swiy1GM6!Cd!S%VOGy zpIQIFEGWSw;i(7b0W)b$AXHqfAdYWi3L7+c%Y8V1LYRhxjA;tRBD*3o&qRs-M^RR113x>;{|`Cy`{tHfLc%0 zMA$K~>ovcBEJPg{s5PIsvPL}HjWVB$oGTdb=Amr@(`UiN^XL^_+2znytV!AsN(H7r z*4eUpr4ESeS)#gsI(r)~Cc9I;2}Zo-VC5z*U6#R9tsM}fJg)K?4z`@?b%bvL2O*7h z_%p`hENlieu1p?n^G|=ts?LqlquW|P!IQg1HWYg{G)Nyw*J5c4LcePItMb=4c}VVG zRaKE#v==66a-VVK-YBAWLg)Ad-S%Czj3dQ(gh(Heo;6*gU1|)dR!upw#q?r|_#}IR z?hanP?0u-M-$yY%UU2ys0nKO5UnrZ=eyM8#X_6O&bT$ucO-g?fC|KduOroLwohe3h z!J}XkPpvFMN}YHjpfU}C5$0mc`Z_$h5PA8n1=|*BEgwqD3Puqw_mT7HDWC2OCe>Bj zg(=pQRBxJqt-z)w>TeWfeYO(5Z)!M>(J}})aKlP{oA)PuRG-zlCIyiY8kR4=km+it zO*P}kHn%?~0WNbsfQp1 zD<`c!ocn|yyCG83tXAvj(qagxc-D)fpM(02nyl($oQvG@Tbb_X3X(I~Jg1x;8AAz? zh>MCLL8PCb(4rgpVsw}}$9y{9q=73 z0IiyDxP97XFp7X1yUGQtK2B}E6^sGHTad`Hlwxiq+qqVj#SJ?lVT>S=Nm3!KQ-|L+ zX!YAyH>9#N|K30Ui3I73cvG@FeUJ3pwoIIye)q8%0a)PP=L8C21^`xM+I7qg7&t}Q zbiY}reM*0h>Iz=ou<3uCM9}z}UK>El#;gwx z0r?=RVa?w{id01&y8qm4jVIb``~f%R zW8`nHYGfO3i_%PUSAi?Tj3aF^X<72AHo@%~0F3r{wpY#!oU6iDllzE{1L*&ve&a4b z-G~;Cj)VpKU_w6J_(e4vn`*#^b>wX%On86fRj^sC*Usr~hzI%25`a_}={uV3l!JX; zQd|%qhk9^+ZEJ-R-}gS|2RuS+0+`)}IhAj?>`ARI=x>D)ey>7>hmp+km+s>+ZEZhV zJqwQ~^;`*r#fdQl70&|n_s9DDrqW!%(aC)2$3!i|a+boY&~@s4Y7kyt9ZCEm&RTzA z29={Y`XoriYZT(YZ^qmtc7t2a_I{N{rVxDQP8ns}F}Y~loy!uBvn=>V*6!5S^seA~ zwtURh{m{#HtvDD#(tm%j0BqTU=#0|iibDUZA+ICbUj`Zey5`{(ybwPIg`qsMx8 zxq6!3{J;qbDA`?4=-|ilbi{*9|HgkE(mlj?0a(yf)PPO_m4EJrb9hxq#A8G@S!Xqv zL$RvbG@7+XmzR%s)YE=*zaQF_;wE198!WV_3xb3KpF!C!J0v+ZoM#+IwqRh^h`&2y z&G~Z+lr6@cSuPR+Y(||@*y8dSiO~JgAKj%GZcWB$r12Ys3suYicE0jUMwNfsq@h6r zxw1>R8OxktI#f22A*uaOr}-hI)QwQ~^*b3v5oGYqVrA9oLp6TdEtHY0VQ2s4No=eP z&s^%3+$4Jp^+l+NGcAnw*@hz8-0i@aV;w^jNMe5ZFf1(MDTAQ*k2hvZnQFn6ZiN?B z>ds7NT6TWTQ5BHjz4EEI`|*Ek9hZe!!}<13EaGs%Qv@QY#G0o`Q2(Lm1MZG2_?dH7 zMs!?~a(-O|i}Q@E*v9_B+C$zRDpc(nMEM@-3^FPwAZ@MhvNbG~*tDu+yZOl-_r0`v zcUTz!`Flcs+je;a4DG39vM`wT%NEAtIp8;#_~OgdGv-z7EB*WBBe#FnUiC{?aC{Ma z$aLICjwlfse%4krA*yDpZAv3DTMMqbZNG4c2C`>1P}u@i^O$&(Dx6DT6$1a#=8ddO(1K3ZjFM83-hZ?66#$Wk{<| zQz_+A9#Ic4LzHEzOjCa@KVRK9T%=^-yLjP1-8-wW#y<#_OgPLq@@I7>RPByjVpJww z-OEb#i51v(?SclXyzv7Z`suiIyX_A`GPo(Z+8cU4)^jfb~eS7B<0(3a4>x$N>R{)r5ZmQ^?al zP}P_;fY4HTLT?#^zpUbFc~3K`EIoRAw>qaPyou389>nFOQPSg3LzIR~!B>95W~eGS z6cOl|mk=ra!Vfm>NiK&zzRpTvz?O!p8O@x|V&iJt8Vo^n=~yNy?CLE^Mq_Bon$6x>1bG8O!;v)0 zmeEbFfKe?tIV%ETv>Z~*u$dZD-Ly|0>xqA{vPaz9Ig(9Ocbjc%-iGk{Q)d4$_?P;s z%TrIhm3r??oh4S^=Khr-io~G{@Dyj{dlYAw=2V~mJGKrMn^;iAGRo+taoK z?16;>vSDzh?n`S3eiRKJ{Kunh8ij{1Ro$hyK}ytC!Rl5s zG|61$vOZ}na)xph86{&h4dYX;+6)!)(cX@|26MAZ_vXS;hdIokq-O}4C3B5n_O@yy73i%Y4Z|H?ICTcw4P#e@88;4!{u{hSEO^iz-is<#A=Xmp);} z@jM&+aP8)Bui5CNaUwGI8x>GHzfw5kG4~!ZROHhsQq}TNK4gW6QE?mHgra|b##DGT zoR{LY(+EKytYmp5LYmuDBl}@9yl5Du)Z6PFYFPG~gCs4kdCNY?@UthdI{qpgdOMH| zt>(i;Vxp(34yMh&@5pVSlUh}SGYr|pl?ehr#>SUp|=jA*tE%1Mi$^F6XF}wsi zJS=}KV8+YBr3c9m@3Ifyz8o+Fu)c#b9YMfihr*?k+(j>ZcD5yz_96uLaTlS6IlQUbPwZ9xC&CjEoI z4)RT0D41g%aAB{~SU7(*kX2WzM#w=FIsjR|1AQgzSMXpe;Y`y5xvs`O>;U5uRaF zXmrTiR1XxP_Wq45{BsDv7mP6?%Qj3p|^;N0`{R66CM>B0igaRw6;U8N|TApipmN_=$Qa2?~%k0uzfWJ#b!6G}U z@m@_WnxyR6f^a4fwNc6nO&7;ZwEYqs&0&rOFP?w3qUQqGPDd5 zTk><>h9M(IO)Zj3T5rHq0#It^SVikDG5UWb;j*wa6Kp<|Sd0vCZmC&iB2sWR;c!P}ONFj>a@bI33dea#YUaZatrIPovo?bma+ zQEEJ3uG8@D$C{hO8Z(qBcKEgEt27u{UGn2MWx^f#~zjW@0IWPb29Q49C0R&BscIZ8>CVUe&0lI2st6X(w1wn&Rh zvja=cY`aQb2o0rnhx>oTViFP@GSOF)zqstw4nO)csf{=H!BBTfx&dM=YT8=c><#ul zf;_Jo9TUZ@?_gzEZS3rVfB}tDoDPEX$wc22J?(V*od+riUNAQkTFTj%@mnmZp(@BY z+A?BDO)v>AZ;~S8WS79&0!ufjBrYAK?Wrnm-_76s&u2!v45@#25QS5ef`eB(_hyMt zhOG1jhwT8Y<2a*_`L$5L{PUeY>ydD`Edv zb`+z}m!@-N-*taxnKm`7fo+Vlm@8}017ST|d~GmYuwEy{i!9_v*`V4@xOsI03NpNh z(Y?V(|4h=3Y6vrr-<(jA4WuG}7h{uQ4gpX#>>Y@k3``{h9LbSSU}+Pw+`6CO@Y(!K z%SZA`2tvf+@CG{C=C{DMggha4sCombc1)}^Bi^CXa4ml=Vff~VNmXfNt6jFKmbgrd zfWq`f*;i>m$O~JL6#=mW?vxWWw_b2lG7Qc^_&~oV9wM^Hr#IhLI#;-yO?Yo|A@J$Z zc?mrjeoCJ(BRtq4q>B#d9lK`@xgnI&ju1{C)Jd+v6JBWacLYfn*a4T6Hx6+YU)FX^ z-PeLj?f`$?dC)u-WM~|B*n6{v!E-)px4%T+^Vja0jAP1_@BZGzfDQ zA-sc)WI%pAzp34=H3YvTxflYa`*;uo7EY>y1krz%2?`jh-Gb!w83*EjIA^N8tw)L` z#6TUk`@x6A+9+`f4~18?h~9ZeUsMWfD4m1Qh-GkI-X|_lhZo7%se;oInn-E)V3ewk zttLh02*|Yg2#wr=5fSAZtxW+=Pkk?kVA~jjUNgS*NuuN%YUaQqxt^y;W(G(0!yioCy1ue*&`_8Ri4El54 zIY1$1Q=$13qv6~ ze6T8mu9MVVomxN>WgaK?Yx z4--)sSAh@%7P?zEj;M3!I&7Qb8r7Jx;-40rr3$dY}{&L zr1Flutc0>FJ(j|DSR%tQ)+dG5lNl`$(@*42hiMR^Ce(0v``8V`uu7iLh7Ny-&430Q z4Duj>4h0X<3T(l4Q%WFr7OK9T3Tc z5=o}U13s5&%srEVE#9#S28cyuUTpeD4T!Z9a=6ny_yfka`p(@@(wZifWJ^ED^f^G? zcGj#PZfdOD9-JU@s?{N#Bf@``HBN$ayu7QxvWFU4Q|HeWhCsD&dtBne3ipA#fhG<; zQh1N@I2w*5lX!Y<5SJZZCnysc`(84Nj|$dEfV`TwFa@vzKq@IK^yoBei66$J^_T45cG&@aZo-r$UR7-yrR?|7P9}Sx% zT~nxtYtC-60&NHq$%wdHe!Z6c_!XW=oq^4KhhjLy`FTIsX1iCB4qB8Ep^yqNc8a%) zx^?9?WJ@#tHji%3RPc}V=nxQ$(c1@ML2IC6+s#qn+8)mBQr6ea;o@73ou77!e6=y^ z8~_&Y1^VDF{`84Jd%AxIyB1dxoy(>KJrl5UN7pBL4O<-gj~64fAU#~$Y!RMb4#A&m zygA8~E0XSM1f}E$xhzxB*D*FY%*Ru8a84#=%k-{7@YEvDDv6MHSI@pz!R`tNp4t<1F?Xku1#u7=+Q%Hq)Zzfp$PX4wQU7KY*+6KIV`^iOJp2wtC$S1Y6 zp1%s+K-s2bPMd#o{rU$Bc4BV|rR+y4a=90B;q~{;UKd;v;I;OP zFy9TSoRBSH#GLm)4UL1k;7XwK0Kp)|`h2w+y9l$q57>V}$OBo?dTK#BXoJaLB(^GvuHhV>X4Yt5!}Z>13oq zdJHhuJn4Tyn$X^WP*Dcm=2B*4l++T8J-)D*{e5%4w}_s3$_WO#Mr}JB^zKKEA7xN@ zQ8{Gv{s?=%$Fh~EU7oqTC!mE9qC;zv0?#GHD&_u&L|IV}B2}lr%jdrQ?zFca*Bqte zh7{|b{OC~7{fpox8+eng!@D)P7nKJ&(D!%8}RJFOlcu%aBR0*?4s|t+D z;3i5U1IHo16@&6T_b|^=LsFpNkv@OtA#vH}U`$8StyU*6H=YJq8;meNxtM{BJ={1X z^sRpYFuCRMVbPmrfEln|ygFsnFi_8V$P3q-pY5(UbTe;~j+S4|rLtM`C{a$Z>Mr|) zuY>Xbx?i@h7(2;u(489De>(2j4<0sdGwjwn@J-wV0;FxF&)&!~S7*lYe(=EN$71*7 zt9>bmsOg|XKNPB=#|%JA(H-18W3qIV*1dl?xbRHZM(TFfxPZ#orbkipjb0o1@W%kU zLss~2nA->y8yH$P$unp1PwRJqB*&sdXAT}NbKpEIN@dy(kYK*FeI47@$l2?a?;H}+>5WY<9B12-h#xtYvyRb zx|pIW%|^s}u!I@1_H;_yg>M)=l-JFtHELRnP50dZj^+x1Lbk~^wRGpIj*LA|`i{Vq z>@I$27?5DwkiW0C4De4<#XXogB+-ANh#sPpEyLA@Qa|5a<0y_Ze;4S@CAc#L;(r^x z;m%Qfb&juw_?0r+5TsB67Ww7|zl&pwXe^8(JZo__{hM-Kry9F!XsjCns(?{&+5Hy? z5KV~+>If8abj>e%ed#D?>Y3-B40RUZju7I$Zyco=kds_XwtdoCb`Qf%zbJogNaki; zw!^Dmc`cVd8%OnyE(=N%L;ni4q;`i1Xt6P&E;>@ER)_=G@xz{wc%Olwz zCf?%o20B3ZnRI(_g3wIF)lz>0HqLNy_aI>);Y(S?pAt9NzdBWPN=^_;aez!uOl=4< z9&PxX+c$LUKmqZ5CamtPi~{$@CV@K&&0o(Rb)AbNV|>;xHL{-PV(viRo_4QuP5plU z{k%Yv`3Cs?Ay@zYn(HO+_5EeI%$Sf`|A;63yV_PM>|kL+=8_g%f$3G==&K>>h(fB>N3fR=v-_#Z?3-?~}Y+n5U3 zn|LTY8#SSek_bwwT^58z zN>ST>0R(Uij6_rzLv+dSHAHA?AfQt5q9kL^neZ@woJJ+_+*pOSiZmy)Q@+}u6ED)Z z3uaM`@b~&P5Pg3qlisun;nE&6jS%m_jT-8#VbDU>q$0U?xFUS?I@(fR@IC29>K+$T zh#8NAqh_*=NK>vUk6m=m-g;+6O=5P`UI|?CnRFUAYwAKhA9A=p>t>UpQc)UH+PMoe zSe5KkCmwQ6p;H@c`PAX9Hl(gIKoDv#-WPI!2=X5f^wYJhg>8= zi>-H^NHTja?QWb)?@ClnTTk}qE^s1t1TW$D2z>t9N$-Vot;JC4XPkzWJFR|o{@&yF z2^-8S=}t>1SM-t_Z{dF-;yh5c?#5)wYFj|IR)bnbtPirCgZ0vKd_g%(pz%JXR`w!^ zpLBo8h2KBhHUW70lLfOw ze1HG|lpz5A7n%wG|1`^3+FCk0{Xdq~x9koX5PbIP>bKL>h$3!Cf>na0zUt*wDw}uU zA%^|iI_hIPn)UmP$>j=EY!o*tK^cwZ$(VnSn8{r+c5R|?YC5V#RmsvjL5TI_s$`O% zK>j-a4q)zQEHvuQEQpy}Bp9N$<6nyk`z;1WybJc}E|n&QY_*_!KlE&oWe^0DK`0C` z1S1>e?u9B&TFz|Qu-%TjQnJ0G5e@~fS5G{%q8<-e#j(a3%xe!99AeFg=8$#NNXLK5 z)fzqbA#;x}o(JS|S~VhL>WI}j+wWQFt7xvW3Gnhtr$E;H)GCg>UiVS}c*q>2?Udx4 z8k|!r;5LtUY6`SUl?(7>`LyTkT;$FG?x`|TU#b&D1EW+V8+wX)f%J*%2r^~^8$tF4 zabf^Ps(?aAi&H>&dwN@0^D3pdyxD((1hqriu{@s^7>=4eS(d3gmMB4v=aK!`%aFx+ z$I2|WDWR0KYgSLmkr%}R4Us+JOH-!l>1DpF{EA!zr_btH8?{n4sBqIT=sgBvTL4$jm(XJzgjnEQ@FnPZ&~JZ$w=ILbioVh8t6Dxtw!ie@-9CR2+sC}x zn{tPqk6x;QCC;3os>uuR+{*P~zG>vhZ8y5|vn~4!cwO7|hYhKJ0>o+(%(rPR>cRE% zBQT5pF`PH6ZQ8Z8=7A8x?hb8FNL4f;r{P@*BfO;()*fn`X4y}1Tl`j2r7%lFCk%Ph zkm-~{!RbFE54NdWKY&md56ge87~5eGMX}i1X1!j+<`ULhTu_a6XJ2*x%!izT%^HV^ z*`Z_xy>^CL^?Olz%$#7|`U`pAWACW8%(uYs;vR9p7XIu&w=y{kj9 z(l6zcc&=3~`tO49V#0rb?Vb0$eZNf6R4iX^=+U5^M~K`rrB7SW@}4ngO!xiPHCg*@ zGtNA=^)!EB`GrwH@eQxQe^}L^yFSdN&s0aT-ODUMF{d`Ji zsET&{mPvc1;9fiYzEVF!KSRR|@!#qDd5oT??fKHKxqQ1J@Wg)}(Sv`c8PW-W1QOg| zeB-x$e{HDwJn8R1EV01;{_g1iy{;Xmbz5!i`QC)_eZ8ca=7f=b-K@38B%a2_`TdUB zeeiwZ}mV^B)2=s0LyBX|NHTBFvP+ZY^Y zK6LttLkoZS{Tqq@Z2P;j`ZeGEy_-k0zxvb%5Ld6+_@2A!^Rucd^O%49!*qS`^RM}P z^Lb|${JEH8cxggcMMvG>|Mwp8UDp@w)N1mS%Q*EuycV%)^=_=|=ltum1-x+Fl(|Rv zvNy#!<@d!JvwFVgcZZ1cb@&%qL`q!GugYire*k|4K>EKr2lSGPfq7nr`!0od@toy9 z2N~v=@6YvU-LCTIgbP^Z6X?$wDLe=BWF-G}VDWQaFhVQXzJvAVMW^Jk7-$24%ax(2 zwQV_^i4-H&x&YZg0kefBC|{wWtyf(-Jfm_h^wtPLD2i5)=jzR>lcMmWVUv<5nJ?Xw zzhi$nCkTQ7bnc}I+8QFubsTf|60Bi5jQs1*> zfS5wzet$3DfIx*f_T&Pt(&bQyu!kMLA2^1QRzc0aK0)XL%Xn{w7NKrqc&2zwY!iIL z@P%>nc)b~u(YdEHi!&mFd4D1F<_bF(L}q_dw)ku42xhwkiE^gMyxAu}m^!?ZHB=|P z+HC%?6CqQQv2s!dRmHyZ244vg+&-d-c{2rwagtIJwi(%-=6%!`GYIm@+JbN?&;3V9 zAjEe=(`aD|ns=5N(d!zRLuPAakBg+wJhly-IXTB;&u-R)UMEBA6G}!+RSGb>`k{ZH z4WtJ1K_0#o2RN?;Kvp3@Tdc*4X&H}BNyDeMr zPlz^Ozz@l<5`(7-!lpzQhd~j5SO}e>1yC=(VP@r5CW1e7I~0JzM%ad1=HTWafd{E4 za7;6^DU)I3b{dE_jE!|PM;b43w@ZI3Egv2{cfPV@>d7TPanNECA3&cW3&}XPA);PA z7(^Q(F(NMHnY!MA4--{=Nw^t&kN6w9fM}zQ?kRP-G*A5VH@|^6F3rAU7s`u;axi!e zG+^rfv|6MpR^EDk>*ns*K^LNmaX6kR{JE}xk^pEGDK6WFcp3yhP8I}?zW9HD`9fdV zWWEJMV>Fhf?N^AxH6Nq)dAuQ!1xa`1tMl}I;l6Ameal4w3}Q@DWd50|ld<1y2LLN< zgH#f3?=JhGXKgCf-T{A~GutoL$=BdWNIZuWo3@X>h$TTpFfX>QSp=J1$?_)eFcp=h z6l-D-z!-4?C?pC!pJb6&I?I16hWZ9)do2*Hr0lV=7-LLT#wOzVl)sgOMd{ByE5|Rc z$qe#TD+g70`0kL^uyKe-_V!_f?gcS;oCw zFg!(>%H|LH84-tb;!(8g0F`0J`2n?vuIq6T#;C8Ck zleZiK^a1_In2M`nq7WuK*3q|Ak|1qlrF|@lEAyH2k%*{NZP=JGM_BTvo;>e*YJq(@ z>K-^eSda7Z?9pL2rb+ch#`KJbsr~A?hF#{(u?$S6cGu#Xye|nArbzP19H*56Nb^n* z6dBYPmnAY{T^Uo{7gK*m7Q?b%%|%p0gEDsJDmdA%T$+2h| z_&OeA2fCxQ_8dmB7Uo`dYgRQu`-W*E*3 z^yOX}@(!<@{VEox*Tt^V&^JER?9Hu8I6vXBMmC<~^6s%hy=;FA{x0dezHkg~Vh3}y zy)_c9cyTK4ptP_>J|&XF;J%q@0)(-HOoo?VvW+MKP6r-^%VX4$6!riTV>59;ZgWX( zn>%BKLb_0KFxQh$`ttQmP+OeR)xfv{Iqkws)v7q=SSmt|Bhz60>ZcR9N!xcPZIE8RRY8r<^Eg5cn6apn<4w!6-^w2O3%!U z1KMh|*ls#Jkqq3vvDK5C8KIdNA9r&k<5U}T22ti(<2yI$;q7qr3=AfAfHd17RKzR- zDvp0~m#IJe$HpQko!SMK&Ie5UV<3sI6YgfU#{;5L$R%91E7Fb^ImKl5=g%|o8}F1sEB^gyLY3OuA7)%PrsT^fH?1}&0=NS2nboXk<@Qwv!_=jEL5J@W)78vWn~ zQ0;TjEy2n#a+UQ$MRg9~?{`ea1=tIQ^ggM~endlaqgz3DfNK|mMN5Z~q4oGXK&qXBR4u)ck`1?nQr=|Gx*UI%c|82vdabvln~tKG}|e_vAOzn!u z^_gF0Vg{0%jKXZXp~mq&A9_U|jfu z1wK->I@_1{BC720D(I!boSAP2#(O{0tQ=q;?PSXF6KIm|&~nQ_pjUqut^b^x;qh3j zSTuRkwUz^M3;{)5nGdmg6@U_1veD%NHSXSqBZaY|)W24!UH)O|e>Wg7>xG%=vQEUXqIgS&>Q*BaHBoZvcikjOEH37?yVCiAs1GH#A(#}^ z4pPi3Uh6sBBN~4JkS?(zFivwo34i>CSo=_|h*W6U&jY4KQ z>6CP>x?A{rCB*)yezSp}6ds7gkoIc-=)gAO5nTg^Vv2YtX>nU;WAcGFbj0Ye*D?zw zTTt$KfGlb~HLybhLmH$l3oqs0c>_tP@3+k@JjrQ;Z7_djp0~9E2_aj%Q|I{RT;5AY zZ^}tvj;uwk1{EKjdGv36`3X*sD^5Quiigw(AiqI zpee!*O>=*6!^S~1EQYa$9UgBROqb$@F?{(V`c9S}KB8_Psn4uIvd4b6eY&)f zgeNXYaZnN|%-<1YFFX$b3vAXulwQbbF$`#4SIe|W>g1Oh5=UgtfdqY0y3q&nS1!&Y zsupZF)fW&&c-}f5dk^NLQNQhdyEp*h?qfoT0Gxj#%^~4I$Wt2Wq$I<{RQAR$JGKYR zQ#>~vn4&A<yCy7IW&iG(%wc5eX8L1V~JtVq=JB!E3&bo#Ke@wPJ$ z^on9v;Hao&)kOAHK3IuhWeH=0QjF|N(Yaf$@-t%Vz{YZbjmz($QPH~VVUnx`WwcQxV$n6sh2JQ(agf*AItDK-jG zG7&+X)!U3Zcv~WaT@n=H^9>JK`v`X+LJ<)24zf*l#bcj=`BJgcWs%2UlJS3f>a2c0 zd04G=YcRdrfA$n#X={U*I0OmMeDn+Z;1FuQ2C*fuE6Lnc_z|uSokr8n#2Kl%JcL< zt<3T(&BMKHH|r4P_V=Baai2#OYnpxXF=q!}5L#pDr;bVE!Q4cl42*wQqZ2n$Dx3*Y zWB^|L!2S6BWGLtlANDZRi$`~KKH!HOy?W30prq2rrZgEj$)cpw6zQk{wJaODla={C z$FrAGW9KuUBFk3XkcZGwEz4ioc^xFcGTRy9W^Bgt*VURjw#ebtBf#`Qw&>H8zReaI z>mRdkt|q1K%>&vCzPNumI1`&%(2&;OFMb8@G=4(hp*RLUuGK?9Sm_79vF;>hwjJEo z7+X5aWCzqlh6qUdh|L^GEmMS)$Vm=w z8GsUx1jnnE&XL3bccjTacRcm9uJ!fBn@pHdd#tK^N3)l`B5i*Z`}n*#PSdIVI@zrF zkM(FTPRAqg1(G4~s5nXx1qAZ}Q_YEh;urw_EhkoYKfYM_A? z<3Pg$EU_ms$@B2y_C%orvV{m+ICQoSjU}=^@;t1H=kWMj@-@%xE=x2_s5A-^*|dyB z4$_A=Z#3xfz=MBu#`fqipzA}C#6Suy#=$s=3_v{gz+9=W%1?jGdZ&E@H7hbtvn?xe zuT6f%jo0sHxN_qqLMSL~l6S#ygS_v^w~7JWgc|npuL0i1Y-I3F&=lO{;DC9!Wqr>bOv`^|usT9V!t>lLhyou{?jiZK z(4nDumcrvWpQco&Mn0;Wbkxd6peoDw-r6R63!)Mnt+0qtEQHz zbfv@;ot}T2L|-yqQFkBo)9b-Z$jml1X@W@4!tCN}F##rGhX8pr>0?m=jE)VJYTvnS zxlgFP`XkXf`&L+yiYfs&H+Ma@^cl|P$CpPEfJVx~cYJk4MV5n}Y`cbJ%(j0{qE3!MvQU@&qIp^d@DuzjiiXZp zlZG#yvF`rC;IlIHt_GY(f&wrNNcFf6%=o}brPdMAhGvPn-*kp3)y)}|Qj(nO?Z#Wa zOA#pL!bSMY$F2Z6K*hhfz2*^d$5518(<;6>CG2Qliz1Gk75XJe2sEGy;l;f0z5VgD*iN|e!um5}*;pMk-eOLX#J+(O3wM&t< z)A!!f3Moh)HpI}IXX*NgnD&$9+~W~cE5}qLO_#Sj&wWOM^8}M*pF-SR`dON|t2lE5 zBol%c)(I#~#!cYBeOh!LkVgiBO6~*SxgR(y|GW(e$O1|wg2{nC;XOFk4kDR%L&!Tn z256su7y7t)EW9a(SG*5VF`4uVc9r+gEoE>53tL?2FBN@ER=NCzLSjI;Ov`%qu!00rFmeLP zj<)+&Am`J_{S*gyaU4mLdF6o`QL+WltbxME9&z^qMj5+wiI{(6_Q%x@qvU7Ib}W`B zrx~Z4n&1NE!UcT9B_%Y2R+ae=&VXG)Y9qdq^*U#tD|ls{IyVY8dk>0`$Hl_fNvu16 z;bRKhfh5NI7+upz)#4V(^D}Llh3lCE^rN+85WiaLZEu*0?l&vO_gH{Ko1_ckcr|&; zO|smu97coMwrQm?^xkEqr*AY@sq1+tTa&(&#kC+K#cxF&@4c+K(LV%)W4v85j(9%+OhD0dK$9|A~>mNsdpf97|*P)fcG1-v5EihOg^m+_B$BS*ltsua! z7$?zQgWgW&8SlXW7tUn)-m})sdO8Ac3iwip<&nk?-ZMa`O@Iw%zNK+FrF99Ca4+Q` z^2#CTs^$0t)(QdSPB(B_5?8V8t%q}u`s5T1W>4;;O2G!Otpc?(y3=rGR|-pi`0N93 z`+z3OgC7%)aXo9MGqsy(0qk1l-R>=C}7zL8KwhYmhCwe%;fn zkoP2uBwOk4hNAO|q`@mX77i|@UG)T#Kb!%G;jC5?06Sg@KpAxA5Skd0;0^5HkRX;}9ZLkh5YPM<8ntN0qIB6J-`b1VyLMnOb|=xt zw4Jn?Kb3bM&erH$j1RlH)IPvh!AY?KCrU18YROK%skI?Op$23Sbosb{9z-mCV8yr8S$1Is<-Ky!|H zdX2U;M^LEpWe1Ke*!Zh$^u^shI-%)URv$M+eJCf{!2-!>YR^@iQgMJ9TCCOF<>lXmfVd@L^8=e4>jhud6>D`j({o1-O zJ3<-7dBH3x8hO$M`mze}`=-RFcJwsu(c){IP~s8UZeyuflu3%c-LJW^POwLh$t2EJ z!Qs8MxJ&Y(_e@kcN-(0Wu{icsw{XEAN-|Lep>VBbSx-6|OGj0IIcLc0i@MZ8j~8I% zIZDw_A7KTfijT)riKL7VKJj4#Vt6>`UR~en z$nW|+b8y3t;}cX%JV=%`ixpUx=N%XHoHqn@pC|bkS3ftfRM>;+I#Y`{)`uaJ=Jk0E zAX*BQsH@#j;@L2N1~#H{l;U1UJ<#!s#Z}aaSr8W#2Ny6LI^~;;8tTP8a$2$~-IIg6 zuAMOZ7@oZPB%;U+3sOflZszEEL8d#1n}I%w_ks_CkJ1~_0|aLH_LiZ3ywZ8!D>avb z-GX)f9Upb5-d*~t;Ue*RNq_;Oe7*fNMDgWFVamAWddo6@Ix$&&TgU@}jTh!S>b~ik zFqy9osA6jTDntwDI`b&!23IZsR}V-R=3b-frr+P?>qQMn64^D>ZE)I*X8PF+$3M@& zrmbvms;tCdLZ^Y`Kyu4X$beWb{LI$FwiqPK*K)+63gb1KV@WVSqQ}BBfu+S-OJW*0 zTjxx|WvpX=bmpBM_HZsMb&jvy1QU{1Xk>KBnc@4@;YLXyqD6Pm9C9gB3fkf2Do1)6 z*WJDSR=)eW1;I6L_I3fPL`2qMpFS9IF^i;heiA!yCp5ZO05}hMzZ+ye)^8w5rIy86 zz(E4Qd-WA~;DFElkL4aTrE5-1u&Vc{l!&#ds3*16v4hr9JOFhNMRi!&~Ji zNsLB+TpzqD7oh+mfD`QtouSYs8AkC`t6|ycn$>6|6LI^^3^G(p+AfQ|PDdq+OMP#9 ztfSi9ZC>lOdq5caRjrkbmi`aMo%nah@B`RQwV!v;O^xtIZr#N2CISwOdK>$MvF!c? z8<`)7+LZ2=SFA)%eD!1FhaUK1ZFUB2&qE00!v$xX~X48=EK(Et+{%%)YVw*^6l^8!z znt{>Tf#8|RR2tmy>?K_6pykIp_2_T;gC0Y7H%OW44hEHP6g@-DuC8=SFH1hd0Mx4zMMvYaI7e~pf91)xIrl^a zFkTTTJ;fbNikIA9*4nEysPyu>^OQ=Fh30@C5`l9gd~)2!lW~lw4Y55=R`Bj9x0eqI zj;;p8+jgGBOZ0hW^|{wSd)rJtHt!#MThK3{z2sV8%B&)0rFV_D8-2aaH%4E7)>_(Z zE}58Ek%V45xgjM@rv#YZbL-bMiTfeHmVz^1aH2xf>!moy!OU}4?uDJ76#sD3M|o;> zXPxWr(?kzIEYQKa5aH+y(Z}z4h~}P(qZ}{t?qLN``Kt1{N1D1ZHdeO93kv7DxkO38 z@U{D-0m3H<-3@E*{_Sl}72;QaV@5A1k79x~6Oe7~SBABN3`kqnlB}f@EQFo~VXbVYzwM)~^OnKM@J>Ku}Rs;>xV-c}i9q$$gT9+?5 zJ6H4V=Cr_9ZhX763djy|4s&Mc-U7iWLc7#3C3Yr5x+`DLS|6Ko`ZW${BLqjX%rKkL zQUFL&t$gZv8Zm(q3 z{M``klAQ$yZu3i~aiZ-T62p!ZqFyWs8<{aZI=xOG0?e~o*WMO?aEK|2%ZlxXl2C<~ z6%1weogpt`kCLg2$iSGqXma3pQq(UOEZoHPt*L+Os0Q>-=G#t7)HYepjbkCAJ#BbEBw`*YhVQ>#pyUNthfoxm zJ=xVF94X`9F3xnl61=b7h*Iwn_-D6N1zW)H&+>BWHNXH6Aknx$K5O6AzJbAJA5Rx9 zy|QwqtQV=}yIiIK_RUy?yO% z0N-)G)?OJsO4bNtQRdWmip7z7wo+gDn6=rAFBiEO>X3;_LWTe>-2rZEn*-0`77r*H>bx>c@tgyfR`l< zz3;ux^7e#?P;{wDfq|D+=p|QR*Rj=MBJ}{%#;|Uoe5^Zt{TYC%J)?{!ls6K8KG$Pq zS9mcqV$GYq<(2Jr-Imr7hC)c}l9YPr=}#+v`nW8DWm27@$(;CCpz7K z713|Sm$-!FvN=R^G&>NfNoB_7;Pid4lms^k$Iz~o3E8eZIgNhW)EJzxUL13TKOkBW zGW`YPDX4i2BtewEC`Wvxk6gYtx_@Sn5(_rPP}(g^LJ3$78Rpeb-wiB_HKQ`T1&xk> zocRdpAR;yyOmP{AJ|MME?~GGj^~~OX-{sa<%=guP8=0&CaZf|e&pYZX6>uX!P322W z_p9Esy{(<~0%%{Xt!#L@Y) zB?k*kMM%I19!_?z#jE7RD+6$L0O1~&&eYRR0GZsw)(`) zT0h|(yj&_&c{JF_)02$2PL6RqU)4*fL!MVA-ox=)WgIv82maXZrCEcM+ zOpSI0Py}ysq=OlC=!?9=E%#4u(>q=3|67B-elvhM2K=!#RGrM}rgOl{boF}YZ zz|Lj32<{c~+i=8IKbHDz_*&{H9IN+*6jWqR;##p33h znwvQdttD4`?tluDO&!$G$2Xk5afz&llWyv*NsU*O89ScVolZXP1ADJ*K~Q>_!DM`V zX&^WAjfKG7r0xlSD8_yVet#Zu!?DZv30C5c?aKDz%mMz3YmFbk4mDF#Q{`^gmR~$3 zR>rkK%=RqbyFyeIOpgl6S68K%k6?S zr)fqYgAoJbH{Dw>y}pCW`~qt*>^q5kWlBaBg*)y%$_ImgSPHIfroAH zXgFia?3?L-hgII-Xmz9V)>mD0r~Gs`f{~v3&}*-;+OyKJA>Peuw&_urFRguSo9{pV zdS&kD6|mIrKDU>BK0oL?p{2|mYP0%$UdmRo9W79UdDu;x!4bu#4+|+hEXo9sjP+-v z0F&ojAA?{adc$%EIQNtUlHXIKx3yn*i%ruI9Pz$?T@LJJ8+)z1WgPfy7UmVai-wB< z`uhSHnDMh2ee~1u@&kauhYG_85m7imfWLE-W*?UrNq4z1ymfr0PLA`mZPyYr+|%nU zumuS1Ss#eJZlz@HivmG7 zL6DMvnzlF*z0zlqhE)9yUt}y&y%zeC@6r+&jp#PXTYoQ!CqVas_3bsulj;b*emVM7 zloI}QKUV9>o{aAKBp#d}=E0|g$k-1H>wCRR<>8n+J0$qX7+hc=O=K~Avhlfulf;Pj zBuZPWPg9-s=y#0_5g1i^kfrhjmGe>+K-h7AdH0Qcjzk+g5CV(bx`h05OX-TIZkI1U zn;F_{;rijE8LC=EU;Rjwdt{UyD2*Ln)E>P`Qi+_p-|n%>SPuel%F7PvXcG%}Tmc{HI>e`8ObVW@6lTmA*NmXbkmR9Clu z17FN?3m^fJxY zJn^n~1?|+8MN!Yt-|kix;7HY1Ez$XpH79*05WEnaYI32!U+ zr!g)z>u2XgMbI|LnNLdEF8YjrLk05sSWPsP;O=dwcBnakr{(q4sr=EC5WH&%~vF8gp^&iiaVXF(duQ*c)OOEAPQ&p_o^RUYb!NXeqT zc#5Qz2CpkRr>ia6xL7dK5vsr$8NXsI0+YKo@hMFp8J#=mUVfJcJ`;q5f4{bjg zp=r%6dQ=oVsusut5QZf_KIVtyz)8qJLdQi*an@ZJb5)J&g($IY!zXZm8YslfB(qxPV{r z>{^OjtFfhj0{>G7BEXG+V1BHXXn~q(Gs;zUr<0llSEl;4B_8vChKyzL;A1FLqDu}0 z?&GAO7!qGWrT$xW0-Y-rD&96!}zzxY2^=j-j3$N@oA1 zEwAo8tM{`2JI>=d+baJ=M|2WRH(gwJc-52N9v%J$TL(xhCj-Lh)srC5X_zlvt*h<> zb#eq*rJUiEwg3W61oGNM)M+wzIy-_B3&T%BJu6i|ulp2#W(QQJ;PNL%U|A>7C#{v? z4lr1%Gamo^5;5Vv1Ab)89B{iJ36ALPUC^Tr#q|oWAxwP;H&wPJk}9P~x9?#@7{gC- z_=yT&ph4($td>ygKqy6=hDkB}0q54V`q%d8cpmE8M=iTq%wRpXtY;e_L#KRk11GE$ zhKLa;;|LpnP6e$+?hf!7zxyV!+J~XquRG~vpkU2Q(<(me#$ef>yUXQCI3SX>0{SLz+Oz*rJOXxd{Tt-`hXs@3tHTy8u>xg~nw!4k z%19B{)H+UQKZ@)fN9ev|FHm2&C`j8ot8=Yv6R``4;Nlw?fh7s|r_1j|r@c@8R*Z5G zAWi9ia~pf`Je^nZ*pkn&^xI>+y>IixaK;~+kd+Yfd>wgp@b*SwTK{~7`A6rLNp-=I2SgMcuHbMjcAaM9E`M|I@&KlyEFd3sFCFxXh90fLbUs{mpBs4SA=4 z_?|SR>hSW^P%9g#ZjyO%Oi}b^CMu1pp&lVeMZ-os%^#{%A2ZRr{uy@O5+&6uH zXf4FOf1b&zi*V^3!@;6i8bmc%N|r2o2v@KnvN*rEywTrhxvBZPp>>kC!vX35t~pUV zxJY!mc6{ySSLMQbn|gQn;JE*muYjkT;!?}kL`?ndCO(li1b6euBO{0*IhDR_0*pU{ z-MlQx-9tjX7_4!QRJ_FSlQyG1agfx1eAgj*2-e0oZg$p4vo=aH2!dxEtBNr~l?&!c zWEh-pGv%}dAHr*E>3d*nT)gY7N`q&MefBQegtEDStxCke!pn%h zfwT9#;S$L-u_i8{;t#16XJLacDbz5PRvmdrb5THvZ;wIF(VGW{;k*hXWX-#OzS*{l zl@YJ6Wh4!s8gvI;lzLL%W(KOdeiEXpweG>{nVe}rPN1)#-P8D;K|8!>W46yGda#5i zJM_^Mec?DXF^w?WV``8Ud%35p;#N+@WYpI#T#yyPyZDX@9M!2-Xe6%Z5sjL2(-c(# z1BOK6LIXr^<|3k=FhUc!ID3VEvdn$>eF6y==m`W+cVs2U<{SF98a4knN$0U8ClW-_ z4`P9L%fb~N3J*KH_nxmGTC>%W`p}sX@$SW>p0h5qA&I6S6IiSGentcxa@6N>QRqhH zN87@fRNz|C9ZzL?P#Hc!2kX6ZR>Zz6v_P~SO_ZF?x>=G#XWMl`1Uz?tgT=CiZB^L5 z*OE%1^rJBz{qOtHVS@(63nJr;f@P|nU-3c5bKJrsnI9Af+(w&55;!5^+r z9T#%*LOI~G+orsto=w(ATW&)&hOt*gdxzw0{wEM743i&}}dHB_j!J`quCX5`;UD|%|;jlO^BYybTy!s_9!i|7y zKd0gPGJol!BHr)laJSBqJ{^>cFzCl?48{{uxqF=T$u3Z4@I`s>rO(pL6}KPEcIUvh z+ueaC`UCJ!r3KyJeX%;kt}{B=3u2j$%mKKuS?>fsBDGC zm55>^GxgmY*WoM=yIzHY!HDRKL-$tn{l$WF&j~$^r&TEazUxOzZFa!<&K8Y}WhFS9 z-p29Yrcg9NIddV?RG^GF-5X1!ZR6{@J+A^;VfNF1m(qXSxJxn>LFqey`MZb5AK_bP zxi;Cu+}4^>d%VVjwd1cx^}x7Tg!k$5il>l50>7CI!$0<8IpCHrDSiXLm!2Nz0`M`+ z_8w~vFzF{wW`sMq{cmmm%wwR=Y?+)u(20>YyYN_{CHI5fD++GN+QF19{+*`ghxJL* z+1XewZi%KXmkfEZ)~*D^q!Vxb4ss1)P)RH!A%%?{LP)KN8TIw8kfc_^ z2DdGyfI*(PAchDuYDNoeYndHBJ9-1!4b=_WM4I)7Oy zRA%6KFeZf)(HxvH6z9+DOjZQ-E;2QdUFL{Yd`D5^v#xkdyy^ zSm0!hXnflQM-tkd*;`|&jlZ|Y+Wv6WG&V$bbyvU=+K?QB^%EfcruQ!$O8^mi)kDAE zdfXK&IUrFme!(cAqz4nO)jm5Rt#`+lbOb8F&4WVxYqFbjB&~xyok(3A*2vBx%%ndS zGyICn$apd5*jc>cn6Gl*W$LU;KzrAJB+NLTsPAG{tNLNn%)_LwNxud=U_;r5MU9Fh z_I{B}PJy$2>ZxgXAwq4X=u0E>*Tch#bQphdm;T$iKO zmEHO71tzs~;>iBI@TQ9mxcGC{rZ$g5GO9DEWZ9Z(#H^B@2Nfypb&!OByg-?;URYskou^CLt>S z?C-ve<t*Th&M-S8#*-nFoEdr>QT(0uG+8=`msKH%JcW!#L<>pT%4GFzpu*t(i56snkGJvJ~1D zcT4RL?63;?1~mc1Zm+2u(nSoxFsDR`GQEiKM0bNeG)!71?B$2mYne-{)rw8_ULTqp zO)lmu1Vjs<;bEzg#m{ zVV|tWmTfVQsll)j4r_!Xy@{ndl^FVQbt&A$17|j82=!>`$^+uHHQd@pg7Fs0^4Idp zNx2XhLDEjLBcw80yjc9qsJ+)KI zwByNB_kTx!Woecj zg-@`+d~h5`@j&@TK3UT~*vlJBuEoo86GW`|73vEbEs$EtOJbzE(d_o%>f(q|>Gb)o z5g{9Y2Uux#gtcyuIie6yjC`iV^!LWNe`90#h+GwaQB6<gP}SCT5u^DeIEER_YFp$)m1!0Pr;Q(WH5ls8yN6trVU~tU?^kTyzHe>ZIcT zGHpPZFL^8V2bBxh9{PDVJBz=k&~t+KeF5W{eo_w%X`;bcMn@j25;1lzig*iyl~O26d*Oz7;)rPCL? z7XvIR&^GpCGV?@6*PgX?>C=jBAVNJvMRLI;88Q-_{B z;y%|JRPuE@{A)uQ*{vS$_qd=PhP?NGhHg+xDXL5^>p8nGVbr~nTAi;eeEONz3n*cg zTp1wmC+_EOw#dENDxc;$veRNr_8>BYQaeXr%e<<9^<6mbE=njNUX4-SZ(uJzcnAj- zi7&g9He|o?C57F@9BJfJ18hGzcq_BKxNAdNFw)A`^$pK%!_4jIu=p>xTn$ZsQbI#X zhizVzrcy5#tt|{6Eo-tT?HLQ;DnS(||{G^kiCQ zESnJX#P>Plt+%s_>L;j}69M)mI8h&44+)@(U(BbFkh2H;fF23U12>_6WD8j`{r=_T z&`mhuK4brufW=?m9-{H6?LEo!+G~!Ak7t#$iQ$wNe-e%aD$WhQCCVHWfVsP;-@v21 zQcG=C2RJumhJtXlMA?HxV4g||dz6|d;jl5Q{XM&C z`}S&D<7ZL{D4 zndW$#bSB*VcYh4(KDWv@KU>-ZY?9+cgUdJX8t;e0>w%O%NkQ{}v}1QUK%D98pvEv7 zb=@Z{85?lc;{i3BmLA0TWS(4ktZ&u?uJ2F?UC9w=s#y#C?~pRBNL}MP|mc{{GXxtj~qN*4D0RD z+~0k+&+t$Mg%&k`Y=%Y(b9bF3zq>gs3CfmEG~ZnPwEg@> z`6bt5#GF=;QIQQPrgL)NV0FR{mMs$alHT?e&(#XURDb#aM9u4R_qd^j7MCvuBzYh*No1#khlO1 zwqDK6l>(k)+Lqh@J)F+&Jhy1BoFR`?HnH@=GA+pD_C%40xf=9{gK_WydesRQ5TAMK zJ$QNBqE-ivvi@$xA?|f2QiO+Gb3Q%pTB6(Q3O=8Y^kH6M7hH^o<(k#(7qrxvaFD0s z-%N{|*9+l)!N=Nc#NmL|<@1B&TItr%zzvov12}^$ui7PCbji{!n?Ug}cN&?Mzg$?OVWq_|ZA7`}N>okcQcyQ-6ig`#TC@ z6x=KqVhBQ^7+B{RG=;vd69|wKufZ(iDN&-{PFi*cs)F@5R@1m%rCDCjfp=pE8)Ezu z^lsYon`$=e#L1Da#LUz;rv&ACFxoA@TZh@mvxZCYX&}SeJI|oWU;IwCQBIBDjw3uu z-k8CEbs=|psbbtYc^mBT!TCP2Uk&`NaiO>|C_CZP`SJ9-9Q-G;hMgsDKh7{9>ydIO zQlRk@XMcJtGGDk%j*ig730>1>2s9^s3r`uvabkRbt`2*R8&yP}_DdzraHta`@+bn^ z+z|nJsb!p86Aoahm2y~+>h7kvyj~cC{3AMlSZ0Lbk}^-mB5S9)A6aTV(+2A<>H`xu zFTbcE%`*#Y#m`$iChcLm$m(XaG+CJ`-kIOrDsb8|mr}VQ@fj-X5v|ptQb=8DSI842f5>mH)1s9ZYC{d&Kd0g;v-t^EYF)`V)dUP9CJ2};; zL7YEluTpRcecA4?bo|S`UYhsLrbz1^-}`iQR{x?69LvY}H_7xDxlo4#ENF?}VbES? zaE3JdCVPg~iNeS$*`7sEA&W9T2DwsybNQ8XxrHSqD%!YD`jqr6sx3i5jb7ZTD(@M5 zSCtG)Y}O&-ICgF?a>IpS`o8rIPykT9bkHx*k(Z9e29(3{PEpZ146s3FO%&#lP^qeB z3QJ?e^{&c|;AXvjh@V>rH9^`!9)bLpW%k*0Pn!Dk)~_^;LabpDkP<{S2PSZTbUubP|#QFz>L{|;qYTw(=eap(YfMR5SgR$}VmDoxP z5H|YI<)NmTj!w~9bBa)s7AD8wdC$wK^l!25KU76v=>eXhb@{KBJ)m8&f*;}euHb|; zZ={0BjSOoN5?HSAviKw4x}aOI_Fel+bcw|pQUA?-)oUHMLXa?DSjRCL7GPf0%D8Ep z^t|c`Tj^z5U;74vs4=O3d{3Ub;TMCPU`D{C&+c#jB%m@d3RC%_aZ%L)<+NQ3N~m_U z8nMEcgkMYYZE$&1;~f=Qk)vS4i!27-AEH!P=oCnQ zyzoww4*N2Jk;ysDCWrHLadA$!+t|qIr`<0_oJZCv6v@_LR%vN}(3zXJNXt$e;JAjB z?Dv)g_|csUGJsrzl_>)w^6o zZT{ZVy+p$?q-py2^x{S>)F*HBq9;*A6}VhjBJ{BpOw$+i9_EhCdz|DBB9jCUZfu>2 zF`bW?)UuxMI67s2t;{{#Du3(Eeoijq^y85Uar47dTx4AvKJmqK4ahvmvi zFGoMftYwF&)75KYpIk_v*8KZ~x3$vFwuVg;*BV;{FuViNdf$oV(MolJ@pq&7Dn$Ss#&Vs5R-N^xcgo{&Qyw$b` zmmD`^G#b(YvsfnGBsR9AT3sjS>aBmzEXyQl7sZ+eFG%9^4PTkJ1;zORlIx9OVT1WK zo;jO-=S;tUY1d)!U|O(u8C2{*mB_KV3Qoj^tF_0};@pjUFVr0Ck$CL#_8 zwQcV*KZ3Q{^4Q7of}%sRAzxA*?m3gM55cFLowMdhT=a_37cGLn7k|UU=uIQSy=Xsw zyU3(x{-yf~T&HUWoDcT##N(yk?)3&X36+C>Ee?6$L<%Q&&>Yla;CAa{y>$ zJ#*Z(0{SLn#k{Q2G&NS;t~2!H=VZSA^8R}&b?>zJPIh13{2n;FNgs4z;V{i#`+F5p~m^q7j}|IuEjr{+e zU~MxB)nME+5Jvl@Z>Adm9_;4yJ3c-HHYv_mmN83)Mr+#pn5MlvQZ1ArFf@~}8`*_8 z2j=x%73Sju{tI|C8^P`!O)U=Sj%?r{Eq+R!wic@&&(rjp>{Sn!LgKV|lvmue z9t!~_Q`uelDC+aMpji4P_A2jx-@)On(esr=I-#C3QgNXp;A>cyuU>Nslo2E|*BhFu z$|AgUkPd^?kIH7s;tIbZitKQo)5^jzmB2-d{PSGTU!H3Vc^mU4Fp1FZ=D7M8Z_ie{ z1K#aP*Nucyw74m)!;YU=<)OLm;XF`^)~J@2YCcbH@?>SX}DW|a6WW8`R zf0jWj*o>WWaKD+QrKSjMD>q=mX5^QzEviKlhVUyyXy`N@#jJf>FWeW(bt@}uJ?`1r z5dob#T|U;pW6I?f}o5TlSY5+FF~@no`Z6ZX|8qNCNrmdfC$dzeT6&ATdJzJ z`j?Hqcje2GA~ly$)*unY)+IOROC4lz9{&A`Od6lHQ-1&s9rmL2Bc+AiTKS^LOm-A3 zX)XS#aV;kbV8Vd^-a}HAU37=)@&c}v(54=9k(VX0Zo~DH+DVy9`l_N$+iVN!IS207}U641v)2~Cm zDuZS!UO6j^5s>moc6Q|pLw?WKl;~gRV}8nmn0!V7^npKJ#|-YxD4(?YRi=$aKWVoC z4+B;yz!O<<2RluFlS(}^uoosYadLXiU`@U?=T^7$Sp|N;DG36;ug=8kt`s4OU{UA=w>JedLnP_JIs3c6+v?Z<{rLAer^iXjOXoO*`4}_#~>o z*!XG!-kd_kO$t0UHP2XC^|9L0X!Y8js&6JXDf*JM^yUp`#o)$xBPLhIj~vsJUR<07>2{ilF4Cw*s4QIF|0y*4ekD?W&gcJFackC!Nv zI}7y5#3KHG*E{NYbYRr_8%E`nI^KZyq4ZlvF1b(li4%uhuf3eeBg`Jd`Cz40!zONW z3|#C;5@cZ#g6*#&RTo&}=#MN5(>|F3hfq5%E3jrCE1{A5v_i(AfRF zfOMzf<`wog#>hQW!Iip#ECdBURvWOl-&>zk*%R37Li;cm^Y$4T9De@09Fz;Ez3o;c z^K#XHb4se8a79I!>j@)B3LRg|&V!$x9>26K<-g0plC>ybpqD60YDH{V>%2*}`gDCQ zA;xnYc3dn<`a<0t$t8p_=7_6(Zb;Gsna`#_G|r&o7dlSzhFTf;`@c7ElYWA;*z@8} z7rx+s)JhCKLhmD9EXNUL6)$ihv&J2sO;;3uw6TsyJ{tw^^-x8bYu^Qc?>AaP)9ytr zkhLvXP~035GDP~G2Cjxk1A%l-9Puo zdw@?Arv_I1LhYV!jU*hVzoc5YLz5HE??*U8nW9dP0Q)@Em{y3MZLE&L#$*_GD=;H} z-mcM-QOo5EfHelPxsPw&U=g?(U1giZFh-R*+_pUvhyUm8_y>6d5NlHZ8UZm zPrS^@fFTt>Fc9!*Cn$6vs7zBYV_MI>h z@5WJb*#RR*Tv6yc1W2o%vZxQjheb_1(QP>2yy5>U#9_f8951>Sqmcku^uhZwZ5W%*;SS^ zt&}wQG5jAJ4T$)ORju@UR@BqcTU~gN+z)2SD6?54_h(>!Dlda_MnJ8(9zWm12RATd&A27hG zcThN2-;cUO2)~|N6D6}-sRYu0ppiG3L@>OL2&ZH9{W6E>M#bX51Zj#QKc3D!!%|W0 zzT<&s#9R{qnbFa>A@Ol*;&;cc5z;9st$Z-y%NkIs8%}AnwE5s8@=_=b=SougBGR2X<@JOqt8ly7mZ|bl?4d^ZNH0rKr{p zsun|hGisJRks02EmV1ZJ+iY2(d!JKH7gGQL6D&YTc+`7gODwX;F8V+@q}}(bsWMnR+&+$lHwR zihwmLu2!o~u^M%cW7v9sSRFENIw5=cy!azjH+)#Ov<>n_Y4JXGx%kU$P7;Jt&56cip**&g18J)KMI67{G0U37oFUOU}Xcv%R4!icfB*!qN&3ac)6 zLM+~jO8qh_C7N}pLRQf*BG+uotDFgzK73t;hT_X#2Yv4PAnZD5KxX^ce#4UhFWmu* znv(3pCR)Tq1G{KyH$T4~J#@EV<$amHXOS%1nSJ++xnSYz=g$54kpr`t%mvD`bvU4% zJ(XqbT7WoW>1f=4-XuezDpU{>@6MY%3jjbszrTvacx>=*msS{dpFz=TkI9SaRSay% z88ZKk8oK=0`KdoR?6=C)do?v^cN!iyE!hj5S1wncZv0!(=Q71=#bNC5HXmQf0UkY| znyAk-{3@GyyDIDA86pI|8!#GtT`tGb0}n%tto@(xcU|p_DgQopEiVv|w-?wem1L4WcVa5*y+aWbYWpr5|e z@>1J(^{72Mb08JqF(6 zv0M3u`Ci};7-fgA62?NWnW}QxPu=36Ni>V^*Nqq>MRS+;Mv5~Xmu%=INKX%fJRx0y z_H!eo3_uW}%5szeDg~C7?wiQ{smbl{wop($A6{cs^3#Tse`C&JvpH9%EAWWVra`Lx zWD#B0D==-YYS=5IDq2^0CgSC- ziOrY}7)uz+e?lRgp1dg1=M>-0kgp`(Vs`ma77Y!TevyKx2SwyEA%+`M&%u{Yh;#L- zR77IlCDSJQ;;&NyDFv8*Dqkn{^qt>XesgBe0mn*sXifi}D&P^VT2lBLx6^iNr*}4K z+h(yYK_aYRVdQaUD^h1W()7BGu8vu7l#UBZ*_vWH@|Ky`(i52Kqpq~Ws9&1nNmw1zBs){Q^S&;DY0VMy$`^MMGY0IT ztlzPUe`*W}ioOM~EB(Mc&qZd z5gq*)iHodJEx0!^@uR43bjWlPGG_A*R{~E*f2|5Ey6my9)kc0Oej$enJ(d`Fns`ho zyPFtL#MJ=%NK^s#Wu~xRayx9_SO&Y)(;*rRDh2utA1B3xGHcIIjAXTSuCP_4kQmr;8jVI+e^#^%gzxzdB z!Z9LTVhm6b)Yr*3KQ2tVfQl`aNY8pGk$iG+$o6iD?G5NY?=aWX}Y?Fc0rwrc4kZAuy!cD)n#vH6K0jIGzN00{Gd z>V_2|*mnU{UFvX#wkjN4SQRI;Jy~IUC%F!Lfu7zc)}4~)#SwjhDw`N_=zCR_J@iK<^kmD=W@RzqZm3%6eUf_qM!%rkynOKrI zE~!wW$Yc6#?u2_<(G@U`vPi9xx#P_tyJN{jwcPL1`hK6~Z>yE~yM;Hi_3Rpy7FzBA z7#?_9Ha{uVzeorn!^{_hf4(cZ68qocq??pr0?GGWwWDE&q^8s}xsMc4Ql*|BI`x;b!hlWGHU1>5cR8%`qYvey%v;*c9mcw|BSjB&+P^oEGWS&Vpu7w_xu{+a?k z{XERMUxovimwY^Qtr1s<1)@g_K8)NCXWa}~QqrLh=7C4OeOhw3TJGh&G1ttC_0{D%o*pN^DUQ94}X)-3MXz(S0HrA zA5@ZpRa9>lf8h*?69HaTw61%_sN8?1*b@d_zO4!{^n!_nCeuR&F+u=S5)=s4av(KJ zI7Cdo{K|9f@Xnq``;x4f!t7MJa=S)m#}P(b2ldPSl&P!*oR+>HYHBF!|Z_%dh3W9X9e|}IRnP}*LpBZ?mO6l>hTC}f_C9M0z*O&`ZQRROd32tpq;A>Z56qtVQPz)I zbZk2~f6u7q{^@&>9}yt?P(`xFc#LnqMSIRJr}^22qc7ZSl^41yaJP8ifNBs7l+%~a zMW@5Lq@wAl1w*5>oxct$AY0c1@%D|+_=GdOZYyX1M8{C^8B7~`UhO&%G0kuMJ4cZK zB{_Ba7Atx2xe)bJA!%>K4@Hn3Bq|M#4%1Dvf6aA1fk$%M2pJxOL&ct#IJmoPbZcQ_ ztK%^m&_l*s3Zr*?E70ff(`e{QnR=$@S;R5HO~$>=%-(~gCgo>mA|ISwSMhcA0$CGB zL{|vh8K9?yd5>NkTk@eRYu$XJwdc&SH%;FUdeY_iwH+}LhSemJrmGZ5QT1`Lhi@}A ze_c4gQAIEC-x9vyYx{U_wWfiyiKObnd^`Z03dq_)LYqn(E-)9KM3qz%JB9XT{RD%{|q<;lcs9UWHIR+fSSqQ8c`dB6pBpZVi!m zDvit12y(5xrqyPu4Wt4RDS(o;qSIrKe+j%|sQC;ug?z^5esF#JzFo%;?I(NG;Rq4H zwk(LuHxh4D*?HgYyKp-)La-Q_}4MsF* zKkR3(@R~1=sq>(tAuyQfw3ijgbvj@i>O>O}kZOQoKp8ZCyg6ll})Vd#5;Ya%_1jx`0OT?{qIB5&^`tzF=SI6S<08;J!`ATK6^ZY0>8(BhIR z^T|z7pvna>h2^J@zBms=kN-pF+s1V>Se70!tcAi$H#`46Qrj~5@9dnwiiAP*FKmmW z^^M|?%mxAyw(km9jo15Dc=gL~e=LV6fjQ%x^NU~uygEkDXI~fTErc4)Nn_hAD1X*D z{G4SAKIX-y87{Om7<9mOo!HH4c!0d$2SiIPunUb4~cg!~7 z#WS^zTk`r*Gc>_!0!;58;O3<}mKJGj9<2ODIiLztsv|Dy(MY}gzVYO^ClU(=#~hLl zetlu4bO>>pU^7Y}NI!^Lf0xIOC*=ifnC~< zXEFxu=RQEM^4XN*AulRPHUm=!d$34ltTQ}i3^!QaJr8l& zyt=6XQ&4f@8&1)f!!v?qjiO0|T=}|UK7peGQlkSe|bX;X*c zo7hu2{)q(Ci9aWr_d+>w5y3TkJ%R8QDW*7WT(P4wHQs<#xxkx$AKb`he+$_8E(qdT zJJ*H3{()E*e+A~u(bHoMRX?qS;=eNop(*B^K2U%Cp~r`DLMg3L*^_ISb|B*lpq>wT zaT;3N%Mt>y%W9(DHn^-V!;d#|**tCEr0@;Po06q}=aYu~!W`<$Npy<=lhitzHbHIR zO!Rhb4GE#maRUtJ{rH1CV%%>0P&lTe1hx*|>b+v= zJ~zhFX(+1WxEAI(A+INrNft@;K*Gf*0~Tr%(l71cX0aOMmM5hKi>k_4m~Ww&`fB?( z(%B53zH~+?)dK$nRQcFer`Zl>R6b=3jYeC!LHQN*3$;UBO`N_g&FJ$fw>H}66IgIQ zy^5_2e*s|h6Da40{>8@^d`y|s&SZ}(EpJe~4F&U*$}=hqHX(VN5@hmVp?ny-2DTXX zarg6%ENoibZnVkLtb!ks6ldYyz|Rm(*`#z`STNIUY$+pu6Q9J9{G{uJ$dv43Pmd#M1SI$4? zv~;tnq2dcn)chm9+X#>cD%K~}JQK70e?|Jo)XuzMB9ku)H^fR+{1E+u`NCuOy1H8k zz{PKvnBM-LoA4|}>HzAJH73+rtOEK5C;mwWE1rB)(6tOxWHYJH*LgwWx`Q->zc4(` zE002XB6uG;hWyi8O@Sf{+&sIT&4p1e-iS@ zc^p~`&dT^KpwbX+^MvOhmF@7}y&g=q+H;gG&>Jad>u%V!=AOXt11pJ!M?u4m@*%X* zzjd13D|mgoE>)z%2>Vj1ffeR*f2aIa?&OloclK!z>-I!^MumEx4Fs3^EfueTNueCt}Lc z{E4XS`&R%ublKZ2M0 z;C9PBNvyhn6-`sa8-}7~d7 zBQB#(C?!1|BtfJ_eU7V%e^G*YoR-LeTVhVt%i;zdgF@^ZfF@oMPaX*OjKh z$;k#sMu$%ZW^p>|fbnqK5JrG<&P(_ihxdb06OUUYb1-G6fXq`#lQ@ZrT@&8l%@Ed* z3Ud-Vm7Ln^=8)qC4KQ2&F8YEUVCmvfikcHIJU#0Ba7B`V{z=J?e_jJsO!GIfUQK=a zQ~E{gxDj{r=J^CVa_P=UEx{*u_Kqm&$E0zLqOMc)m+j!weK8UVMsn4fHrsuz&oF|@ zsSEb#&J${BZKi!XomDD!iUAQcj<<}P9-?aw*!nunjo2>DeT)0Tn^(UW>+g`J$3Nj} z6`#93P93=N6M{sMf6FZ;YN{{;>(wis6!dmMBN>GTMAjD3nxVQ2kv_km&KZ2c@${Po zV7X^24S*o@eWCT`Bs#cA;!u14R(`q8IM{-oCIeHgr)!wM)?^2vNBDzU_tV ze$X~kFrD%zMm(?e^>3o+{w%mM7BP9rlU#z&ZfIK!a@lXCf31pSRuhc)_Y@3I7CL82 zBBn8Xi#LqIfF$KjzaJr3It@GJsrmI`D)m5p1ycqA3JnA3&neDlZf53w%m5<_YxYqA zd|1gPIH_p{`YcA5``7PEihGx2HbVgB4mR+o>lm#V`FI{@zZ5iLo>j(;lNJlp5Q^ZT z*rkaZ9+A-je@cpEbliRP{^icM5byg=(PW(%-dwfLVeu|SL~$@W$03p%e+K_gT%;h0(g*lPEp?p}5*xf6N{e(-GeQ=C>#1dMAW3d3N_| ztealFk~xF0M1!R?yE!WoSTk4<==kz;-DW>7~LaS!BH8x zq*gU(XdG4GB$5;yHN3OP`7A2*b< zcyoB3#v$>YdKenvv1TsoVQ314lGO?9Z+Uk@+;u3U5w)Dc(EI5F){c#^-uf>sILMTr zf3GLQ#K*(Qe#q?0!x4ozK97wPt7%g+q!u;{xCSKNpRWnAafMEKJ9f+%+n@}A%5Q6F zjX?acw|{_^IX)S(;d%oC6jD8wn2tN*XScl2Y(TJ)%PW^o@S;#(sN;1&)4ySZ3$Kp^ z;~OTj*qg%wzC35dsy#AW$UXI=90!A*f4<~9x+11AHf{j(*^@M9`y~qu!_H>*N$u3F z+eFdl+|K+nd{cbAVKTd+T5QO{|E+qFY0OlUtAB&fcD4J_wL2PDTpMNeW8z zZTX4h_-A0A`M!S8-%l_BD~TV@e{=_p?B|d|zQIOT(9 zK>bqrbc{#)Z*lO``Uc;^j|~}}?uho7H`f8Yyx;z3h)9K#s%V$-mmda4I?#Z-C~P zQ8=0(;4DBD~KgC#pzoC`>sXTVW94i(B0%IiffBu{BP!*Z0uRA+$2V#fwSu zu#@#s4s}(y6j3=1@o0c9ZMc9fXa-p%@*Y^MjL(cT|6_D5RBrDQ*1vbRE6Wkhzb!=r z`jAKV0u1QCCE2Z|k9l9Se!pl6pvlBh)6`$Q;(|b-SR>B+`Fx!pf1HglWizR0^Z}3i zHo~ymM@1mBJt$FVr@mx*(yM)xS0070*h#2lD@l%<81tO0{_w=16S*pr7jAdR&f9ay zzRSSA*-8GQkkPnX81T4tkL3{74Lca161eZ@2jLC(m(PN1@rD@2!N(d;%Uep{a`Mu! zA;-PC{L96zl#JqDfA0s9`YCQ$@Y1UvqPEj|qCd)zpDAXXuxK4NQ086|s0E`= z>Q#d10mbW)c*Y$QTA#8>PbOodUb+?4lzR&NRuFBa|JS*sn|Y^Z$y*VlaY7z?2@1lI z5U-yiDZ&)?aWfd0|iw}H6~Xx1@_ObkoDH&wgAeg%sMJn&<^AE7_2wYO;9m(&;5#{BfKOfFq{bWJ0N(e^1b5k{~~~Clh|%P0gKaGxFE4 zRec%y(C$kVf6H)xd+WfqD4uUH8r2fd_2M{_ZKR0t4DA!75wN#%ia_*`i4?Btm%KRq z4@GyMR7rYk`E*g5+O0(IXYw5#cx}(a&N9P0#ZYX8sJr5l-3~N*))%bm!dNr}kWG>N z>E5N+e_`Gn(I+jjeWnm*z(i4;j5;?EEo?l$Zo0Me$u>Bo3N%~=IzznJf8Q(;TzC$3G00gpPhPm?6SFgk zNQmw{r4mTCH1ZDakPrYN@Ytp6Uvnn9Ic0Y@f7aY@i-@ie?{7H%`J>+%Sv|U7IEIGE zVv;1kg`6$cRtvKfaDx{cGi^LCAJY)@Y2{7Dg_48Dyw5@_B$0mh-yCfGTr$V|lk#6! z6dGZ(cJnez@bH&!ptmR4DH;aq(38Ls{7uegrFlK=n|5cWMi=rOs0QU;?qr}nim=g7T35k zc^W?pMh=pwjZsQ_*iT!F+=R%Oi-y4#f61Mb!RiIT*IwI*gd+VU6+j_BhfEML$G{LC znwz5bXnrVd3%G-is^mP#odyemp0|%KLRUPaTp!efY7Hl1^Io2P{H!;?wl&rw^Baju zN$}8#q5MxTKGI>;c$P3}lVa#VvLMTl5&n>5DxBe+W zlUjFqX9eK&PnvhAS~l7pKR*yPf4wt?zmYW3EEb|bX!GU|YPYPU3DG+};}9d~G_Q94 zR5_#9+Jg4d1t`40M|S5$5#L2d;xvQJn0irO%4nqi+q*K=L20YD(73!&t|wE8QYkt} zuCISGCP=dv)ZXHBqw4<3p+2JSoEqq!Of@o*v zXY^SxRZ5?wqDnir-ZZUVulo!fGAc#R;|Or7=;(TB#Ya{`Dxq>``XR$mZXH8aAG~a!M0n*l9lWv~`qVx32r+eBmA;^oBs556Z)-tx6Wg^Fm_DaBij_ z>%nz!L^d7S-CmG9f6?^Ww9d%PRKTT&9`f@J_OM{nYf(QjzqCAk#}f|2*|7m)tTSe( z8t(>jTKzS9BjrZp{V3N~Fi@_jdz$fY7gF53Re72RFoMEdz{FFRGSZtsi?Tl+*IW0H z!HiE>B2RN9C5~cp`0u?nv#QW5K}j%gPoeE#oYt-|Fgov_f2t{MQ9))l7dI;3zU}bf zb|v=c4&w#R?p<2<-ZXnQ3{HeDG|n8w!?bu5{I>WRwQU1}L%(;YtHTL)`nl-zm*C%w z(kkt@i`)W3sCZyXk<-57>P%4gQ2aRTnA&4PHe4(ye{+!a5B>})VyO51AyKWm3ZOW0 z%IFAdgi)G2f7fn$={Qv0>O@`vZAB#Ux0`VtvXP!HsaAxy*Js2idNJP+-DX%zMgAN4~ReyP@n z{dpH1pnTvJMM9|H#x)a+WYi3mr>!DP1?c&`QequZe{087nxj0jHto4Jh|GESprH_P zq&8t}i!3R_^5kgk62oC8rw)9i5c_RJzID!)&(m{X08}J44+^mKe5B`ar6^&FDV=8G zM=aA#ZuKs=LE+T370QZIJEHvc%6VYz#aLK|Igubm$GXFt^0@Xdo=28jgB03yXF_Ni zT4FsAf8;&w$)9Yxr*8M>uj-W;Rq}CIvr?Z`^uw-txa(~P{Ja-J=F{7{sTd1>&#wC0 zev9?IcTwW1#$IZ!0Ft5I5-TTd?irut)8<^u0aIRx{zYcfkM;xO#zRi9_8)cpY=T>J zYPF#mIY(o5vIR)+Z}|*SYPrSqxeDZ-0;Uxaf7#$46#sHxoYt)?MRO4b@=Sax2i28O z;Xc=>qnoD)(^2}2`uyCTt7T!@uSBJ(-ebBjPjYi6JKferDK(9n@r{IGY3^BhfmBiO`OHfagC0xj?c9xN45 z{G1C_7>%vEgvBzY={^nlgbEn`89V+)e{LZ$-_-TTd)(lBKn4${WBel9APt@!Fr2|?45pl2tHxN;=1(GBC8rL(>Lm_rLgS`=W_!8hMc>g^l zLANj&w8#|yB&b9{!rUJ0+UPA3^zyWRQJkwNSOR;7G&en4S}DL7oF#C-e_39ibBk^5 z8h{x{;F^Y;ZUO<*P}K!y3DL7%sV-gk%Dh(JOee--_FrWoX6A|Bu2 zkG{6YCPUfoakRu1zZ#>!x#1w=sagl)Ps>`hb_eTJq4A`-7N83~XO&Ok(r%Q&@NTpg zaF52++ALb~Ll5_#!9wXw5}G@EfFA+{D>T8De85V9bMB9toh2uNev4VmS~86+qUh*=LTFAacufPAYDUCB2i#rT259&CwyYUo2t>G zW?{<@a8ZNnfk}5Ma9`i%@;7#hRBeLXX?wERSspi1)uy!Y^sV3nvR9%I`P5jbdY#&w z_P`*jUA9W7L{gm#FsDtTX=Ey+pgS&Z7P(Qypqxx9iO5-ho>wtuAOZrz`VgbV z{zh@UNj%j|#E@_+P9^*74<71BQ&f;yB?N9Om_Gbg9)|e-QcG1EORcY%t!C0T=CiM! zLB=8G3E1bke~%3Kyb?-bECor3SsTc2OvvPVjIT_ugMDN6Ao`y!Ub*fm@WTmTMKjxp zGXbtC-M_^U;~0N0fZs^+KwJUUWx*x-<7{6RtjlXLw?dVuxW}-tp-l^JUpv@!Vr7HZ zI(2*~{9MtIr?RNQx*b|(7>BAlXrIgAN*k7ZUG)$re}!ad_y_&_uWxhtD-NUjg)S|8 zWzNS4(G-19{U$S`C85kFW(N~~0Qez#{fxG}{!UaHZn1C-@y;bEXYlKh4?aQRjh|U0 zoZhle(91Yr2AqUo?RPv)N*2V%zGW>(fZ{2xMK+l7-Kb#z)S2>0afCxK*@g6D z2GCl3e?EwybH{LzQR~kUFUZJB5bXqS0yRiAH_}VBXxacT@g~p_?j58pRPfSMj!6gn zNA-D~`A+K|4K-ggUJs=Z?_2T)8N4){6Eod~sN1rt=6N$E<+%;raUa|;9kI%^;IlYK zWn)gJOj?Mrj$1DX1AN7Y_7`DMJ9C*AIQ;rPf4Sh7==)`Sxz~ZfG12^y3o|r`)->N3 z3?}zyBv3!EaiYc%8|WxnilJB~-WBVUXJ9UCZ(;3InqCP=Fo)W%pLTJxvL`E)9CA#*GWo3`46ell#-VB(y8+)`YI1@Po~i}szYr)QUEiDIkv zFyvmWuU#r=H`^G)s<})-2CLWfNewa~7bBO&(y!sG7GcLvPg3M2FriTS3|wjLWNi{G zgBq2lu;S%vO9YI95=q0ime5o1kCxfhe>D4#Gv~CDE=Ji=`|KO4XFC)+lxUL!h$FzAd)2{&vNu( zXR8ylh;Z{9aUYB|+UM*{%i1d&?Vi>F_pQInL$$GG&acWNwsMaqX-$UI!+2z=f2r(7 z!|aqSq|}-D>!MTaPeO350FlI7Ew?bi*o26Vpk8hm`hlZh90pZKZgYJ?mi7(We-cgJNTf_J;aO7;m%e{Uaj$vp4R!d7TbOt&Aq0dG%~(2iPwx`jJQD&sBw zpzHNV$$ia&jDkNd90L0dRzo7H_RsL52a-r2fu`pegN$eT3Ao>-#Pd#9lXF-NS~fXO zbl1$Ky5e)NJ;iJIly~>ns(3&<2R5OrAFbRH`fs%4mBr94LH{?wxR6X zdEa!ZQkFa%9#lWS6?(~H&0R6|cTD&&KiFYsyZF&aNFr;njV*C#bszoS+(sQdg!)pF zDrB}^Db>@Gh2V!oVYQ<~>X25D;crgH_9^-)0zCCRv}5qi=rO*pe?t56jiyD1lFbf% z#M`;2eq2P#*`&>sbj!mu2wgR`=aT9Ei6?fwkx)%VPtXsa9;Xx@VYwT3XJQbOZ&6GO zxui3T&(8R_`EaoYvk=3w(LjUhUzW4C96{))0l+c$FvHA8)Yh3Ja1}bI&W#dQ9Pz^W zLoE;{9>HvyUDSVZe-@8qchWzf5BvEzp3V3o&@|K+ox$j*^2`FId+F$Ok1ofA2~I@K z()t>4)ma^IIV!yp{xNnrO_=c0kr4-`KLi<$l&&Z0$q@W0!P=48sn64my7jthUa{*NqoxV0DD7?3KfaEnWN25J49TI#dwAS6e=3a}S_t-(=RMG5tF$`( zt)9x{7Ru7{9YYI%Bv1Q(rSBr?`6jN~=YEQk{0NtZcy^JJ$`ku~hA)UpDaiR_1Ea5# z(BB8Dk*a4RhvQzhazbR6nkx!n870CpSpyQtV5p1rNg(AC7q=W22};^bjx$t*kgDnl zGfIN*PN4jLf4W&&gXaeN!{tl+O6#-@=pC19usO+FgIV?8LX2jCQ zu{)=Pf3O-l#PXl&1-WSJ%{m29Z$U_eY%L-jWB=r za5tjVsd3O1N?nuNPG}E)8F(TQp=_;)h0qU@e@4PyVL726&&3Zs9L~M<_pF5^Qm->| z$mb=n#ZAkj_(kv?+U>1J$wWIplD{V2r#l1(P&D}DdLv~dy=T1pJI|B+$&L6bAO!Fs zWovFedn5OKuWh+>p_`SkS!G|ke}2}v0%KU4EMuxQ3aE~^%L_#WK=?4%{-Vro6Tup? zf0$?0`LPi#sNh=rV!K}d?oKNDa8v^%9r?W_X^=rU7v4w)`!LBgDBRa^ZCLgJ-l z`$>Da_{=n$YlFpAi7)%BCGJb2z0I0ZpgpGk`Bf8znx9zs^$`(yri%qK9z4UmdZaH$ z(%rMCHz;sTiE9jikOH}E!pdg6OYicV&8#_$Nn3Q^^Pp4qPQv-DiMUs6885A2IJ}`Co=SC zt6AKO|Q-!hi3r(=F_CXQg@$l%IH!oZ3*81{AFE zlN@OaqE_hD83TUt(T@u8vq`C*&P)?wPWRY)_1(mJxBBCbUEh$Yy)v%8f8lawyZ}lZ zP+s`9YGkv3&)fnO@|)n5&hdRk;JRwGP+)(e`e<64tS1$@*gH%Gt=9hX?m(b%K*fvc zid*QgtM>Ie8&450!CMH#9j$$?-pEXZJ55=|vqh%u`)|c9H+Tz#5~YfTj*i@bUH0wl zNPddAWMRxO(Je-eiWu~R1oHS93 z-IcqW3S?^D5KCaeDL4;98CnNuV9C$Hs8_`{3RzA#Lt9v&>pHKtlF&XWS@mS#L_hv% zpBZeP zIp*Td8NqV*lyf`j3`Q3yH0?lH(EipUc{rlA*T#k4t#f!*8OT?h4}{znVBV2dXeq-Y z-K>q!Wfq^gP*{nU&r~#h33-L9K$!5&Wsely8ELsso4IFIe@gCbWs^F&RG>bpaCit8 z&*KoPlP3j%9Cki8s@2Q$=PnC0p_;l4OJgkNZu)n>E#>&36T$g!Nc<+Wi6@ScWa55; zbic&)mj#UJXt8Dp2)YI7gf@W-fyv#yf8^F75>w)dC(C+OH!6n()~h29i@J+2n+(do=k5s-AzK4=>g-Zu>nCqjw3@$b z{SJv(cj)Xu&oI_p6{>pt$_MXLGw{XpfyJj(_+skIe^n3VUA$G#X=CE4O^OOg6#-pi z%-=m>Bn8XQHlsyFSSe&~7Ea4Qz@cy&Pr#!;5w@s6EJqy)6>NsetS7G;M~rxP{v8o1?|}RTE1cTwMN`?Ke~GCw?s>`}B5U4;bV)4sVDxL|fWb8@ z(pho5Tv_nN0YPj7E1Zpk2ar#d)4_s4=I)_q5wkSXmV#7;x2Zs!ey%syqK{MR`}`t| z3OBu^euq2Da6a)mw3TboEdH*aGD zf1Yc)sY5$aF5Z~2?NhLTJ4Up}Ge@7)Oh?4CfcYy=Q|di=3OYUmU{4o(gfHQY zHpSAPp-7DQV{~z-o5_|(lipE5><-2ef101YC$}^r?)2npnw8awOU%rJ#H8-=^{qjm zR8+rs1+)v8r#pP@+YX&cCj8yaX(;3Ft#Nu7x;lLe!(}hA)I*bJeha?DnUeg9^F3fx z4=m1bvnZ^G^*bOd!4nac=B}|hD}mK0$UR5k zSXU!O!!#Gp@tepecGsk?lR&X@Q=c=4T(M~YX@2Ar_n_l8DdO9L?7$oDD#_<1!&v*f z9zB6qPpd8hZYNAqTH0n#+u93->hz)(f;2Q3I?Lrih<)0ukfGBBgwo=hx%D3ET*2j` z$pV8Uy2Z5)m(a-a87K82Z)ffMf4qT!K&buhScoa zt`fPfjjOJGAR31$$4pa@A2gm&tI2w^OOTVjK^%3{nVk3c^HK1M?f9}ue=jw?{zC<8 zfKj8lCgZVzA|&TZF~K0fv_s3`sRbo+g^{&REBG?5d)JzQ+(N6a7Rqc7Og@}yaeVC| zoCKWY>mcz9m&mekApAxZClCy-Z4U|l#*Oi}7o2tFe%HQ4G`sXn_L`3lMny%BWQMdn zLzm!P(GTmA?}&6itarb)e>y$HnD(TD&3zu#j%Yj{IE@68o1%rh*TA(TT|cxG$qZHR^Cq(4h>hBtB>LqU|o;Jjh6t>Xh>G{8dL@ zzb9g9QV3c?Ym;LXKfd3ub;ft_9M0qy-JW<33eZ^&e)f1!ODYUlkh{6kG9 z?U~#FhUQX%dPMHo6!d3yWUBPEOS{Faw8?zmv%q>vvLF@Z9?!mALs7D8`dK9c!m{ypZKUU&~ATUpmhXII37Xe;|l{Og82!E=jB)&Ej{dS@~cXV zZ=hK@f9@I#NR5T5!_p6XA3Yl)7aKNpQ-CmVoF5&)% zFMXxJ5=ORFS{EhH@q3$aMBq9r2Uy4DSt$Ce!J})ymbIiBn_G38thk{=4nb&Z*~dvQ zM(959x2N^VZnkWO02c}06iwYHMM%bi=)GfLYV|r+-IoBL-b`hdX4$!8t(t>cxq`iU ze_@>Hn>q;tM0%r;<+y`@PR=o)5d3!Zeut*nu_hhbYw{3x+dA(-t@1kvL=7ePFy=&3 z9jZZhU61{3lEdYtRUD;AZjAaKDZ>99)vCO(7^t9YL6naki&O%pl;$rP%pOVWbsxQ^ zCmOAh3`&D6qvM`WtkEk;yC)XKAm^#Te+P*?@`1c?tiD~LF<@dD^NgeQSVBCHTXPBQ z;?$Jl;in+3^`)}Q6AEO-7{mZeQ0Hevy|lUkpO8*;#9Bc6yw=QG^B1K8{7c#SFVvcB zmMmq%p_tC69atw0=DC9j*UYdDIt_L)!N^?ZbqaoR-`NGyM-d2fdCm6X$ovImDKv- z+7AcMjEa5mW8S@~4#-|MzwW(!06_@0&liPUYS_AZIw^i5BuWK9qsIzv)8ha;K*Yb7 z`DimQnJnt!F|q0G@Qb4*sg3?2dXZ@mC8Vxt5HvT`jV+7COn7?B69B^a%NJ!|rkiJ`sj#e{hnJ5TWn|1KnHg|qv5SL2 zDINX}kB&98Zc<7*#gNZiFVr`rDpIJLbphc=3aupEqXP6Eg*^b`g^CRcmT6xS=vljF z3%%ldDd^1kh*)Ypr?(d|Yv$Mgh<^djpRgYsY{kU4A;uKkLjG zQsyL0WvqjTMN8UU{9b9E7k|sX0PJg4v)lJA0@M)mfK+@1~xap6`=$VdAMn zAyyELlje{P`}mBkq|^+aR5hOAKir}E;)bR&sD46k_14WKPY#LW`hW6PUaQ_}#jy(X zxp;aXfE|r^Sas}BLszuFD6_WcSSCgDvCZVRSi&DYZ;4;Gn|u1>5drk?eZ!uX>}l&T zua+}@gThjf1EPZUB8I66z7k)?KP0FM(KbE-5chA8u&S?;;+vS4Wa*lqSOi!P1F&1i zR#nJYN(R0HEVU_ZsDJA#)d-C4@N&j%*aeS@7}EO7TO>M+=5<{$a^$sZ>3_Xymg~Je@CxD4Q3H#u zEQj1Dx%>pPEs*X00T*In+1-Po(Jg?3jIM(VyQI%!obDv$29@tsY!!sQ5<-#kWBqi? z`=a8*MAfocY~kCE?n3z2%k_D4zvU4I}CZ0$2hw7lk^76P*;g+XY7ehpW<7T zfei^_CY?@se;X=LGH(AK^BRZGA}PBhW$2~?YpIlrvE3CB-8N9Dg-w!eD`NQ;{=GZf zBA7ix*q28#yOr;NQ+FjW?YKE72f3A5oKS!8$dtak9m0s1UNa#9QPI9I{R^ee3CmB(X8p z(S_&J8ctZM{Iz3H7q1od`+URleIBi;H8_cn8 z(p6&WrX~70G0+dIRV2Bm4drR7oU0I~z!1dfJXd}5*Whq_fwEURzSk~VCiG~2i>hOx zj=JIiKO7dnp=f-Ux8(ib%q{5fWgbV-M|e^fR)5){w1>qAT2eMoHJ;H}aOf!*MC0;i zrHTn-80Q!ok)`gQ=&dM-i~zoG-ICp)kDE&bOPUG@9a*&~;-w8>jNNiubahDiA?YVKRQ zs6^fY(k+`vgu7J!rC^o*&a2_Pn#ThQ+QR}>yM3huf8WpE96^gj2Yl(dT*U3`ayFeR z?!x*vg*OM3b|tG%(SVZ<_CEYlH0Z-b(0{d4`t%@<9L?vdEi7bS1GyYMi_1uZ@jt=sM?`;|^%grF~s{O)D<6IyN+`jcAb`I~vo zxOEuP9CpjN2an}^TuJwsX+*3Cs|N$L26>(Hot#6SS6*+WpTP~OoHM15@e92{sefj- zBn(`n@o61P`Qnsp(R<#Q*%ub99vkKyz^PbF<2mD~1AYBGw&_xaH%6rZCjC2)6B>lL zf&dBCjeF*p3<#Aeiy>ZX(9Uf4J>*Cqcv&R%giQU2-#q2i!2_1u@cwq&>CkrEZDDz$E;CTrJ)7U;XgnZk8On}7LiTJl^a z;x|31-BnJGqv5VNrQ#fG6y`tfPSOW1@w6tn;#e816g*TUDfgpm?+tF{x3Tx|+m7Wn z>kUeu`~r#<`^YyGz5VxeH%FNTDtDypzyUXBb`nelMSp20O238(IBpccb*$6kz}l{1 zY7Xiqk|ct_yiSEG6~hWk(|>19$Lwwo(V&3ak3Vro0L&&CRPD7=h*oE7`tQ zV=7Qcf0pKp-)z@ZYf8U(`Mm%H$xvu-Bn%B#!RTr2fQ3@8$#8j7Oj@qNx)5_$i+4!c zgA;#9co9r+3t}XZvJq5x+?LcbV=zBu%!FeMbS%NBz6^Ntu#Qj6zJEStHU23x9(Hpu zC@^ftb^k0>Sf`uPLT|55Zu)}g9hjX=FyBd+a_dlcgmE*vSXI7xZ-QH`io;8aq?C@3^a(#%*L!M;MIaQ;K zxod{#6qf*b=YoHqB7Xz!ymvqA5d}wt&F(F1B2^FYJn+d9I%+u0dcSbBlDIyOEA>#E zvtZ(u(RXgYl=*b*A@tEn)9{LJ^_)hwZ;_DiBf>`!M5*h+zS;4p@ASWcBk=AogWj)` zXqoCNkR0au>oa`vVJl>~5<@^4(>~ z{eo;~Xr^-fr2e!@RM@z%g~}S|$;w^t$-6)4hq9+le;L=grdQ z;9dABWuV%&Iu4Yb@`D*+b7M#+82~tg>r)@EDXIpRdN6hF>Xt21u`FekY8$o_+lLCsHx% zp1}sX3NnR`#?ix1p5*ep4@_)K(2uJ9!VHp5XWoQ9bYdFa|NhT1Vu973Xx&YM>iA|+ zy~Ij33pTI1G+jE^5bo#F@i$6Q2;hP~HvixZI)5jjq#J=`2&tcbNFjpy;-eS#QbM)) z;p(X!Zsu^*99DsO2ZFW}cUD9`4OUQxS>aB?Ia_Lzj3N#)<2GDr!%YW>DrzU7d1jdj z^v!D?3G%zUn}?{SH!DY^vgd>~_$s>ac0mX|W*$9xNBj;iL^|;@&tQg=E}(LpUxK?g zDt|h_%0oZP2&+*oC!as|CvIruaH)&JqkraT%ZWin4mx8LomPBb8MIMgsB*Q}59UH} zC69+h(|`Gk<2domwG$yEL8LGB0%0$9Md_q_iM+SxUIokm1A_dRrpP%hb@l5i=h8EN z(Xa=oQTt1!j;t>l4-pEu4%!9rw{yQ$^ndZZcPvIW9_ghXi21E>D(?0(4ORS>3y?Bz z_;Z|%;&*@m&=6@`rN+rLS0E}y$!GIDoK{!2z6F#xcZ>QI%Mxo}4Y z_8|LFgfaqti&-k|-n30ahC~kkzO`A*Ffv@=28`1&uGek~IRnUe*B(FEEFA(=I)7pX zx&UN?$&~sEJCB9MpHws|USs8J#Moj+9d=z z8TG}YmIHpl!C1Ot(&ZQ6V&t?-j(_q#P}#X&Sh@#8yVkm(0KR*em2VXnj#V@(;eJFy zo!o!W8=H`{GAuVtMBvX z5bA&L+=(AKy&1i8-lvi-s#rbJ%`sg$_N#SM_JRa!qaRTC#ZoY^Mo+FsKYv8}(en@> zh@iU;uPJJo6B>Z<_W~37<-$WkbN?l`l5NSg4<|Fh2MFrz$m#@oKD-Cshhblb6Hbx2 zsKecZE_iW@cQE$i6r+}pn?B@F(?clefmH9>fH3_nKgLH5zcD>jy`eZF9o@kcRwRY5 zoPZZommc?P?C~i1}SGTIOjLx20 z&wM~=3xqhEVPxjz5MJ;;ieJn^0!)pJnHuOxBP2V|k`pnZ&AofCWWR?V(8Yj3`H*~( zh{Q&cnZ)eMf+;M(oDI#t$D;`D_F~yo`{yyY7OtuY)HjEHDjY}jOMlu;oCKS!GCaax zO_wwet*(XG_(CK%ZHN~uQbV&Rn*r9Iyw1Mq-j*s03Pm>0fsEis+`c#q`1g^^b(iF- zPWS@bzU7E#T{HfPX~r>>`px($?A`&6d_rj*eGswCSOMD$+aj+1&o$FDoSxO?rxt zPv`RkhO!SdrS>t~*qhIaHaIg5F{*scYW}6rpv32#&8JuKYG%F;?#qc{jIb$}^Rp#v z7Slg+(8lj-4mMAo@~oX24Q8-Jv9J(Xea&uFpHCuD!}sY9(|xCsmAHRV)@-#vjg$L?K>UExHzefqP zk%l}>4qht3P{k(0$HXDIrbc_Z`Hiq~fSW@8k;gR7ITC#o>v z3Yuah9vT6)jNY1OqTOX2a4aWSL!cweT~O9 zN5_O1F_Mj|M1kNk+1;4$<8qlm^J|OL3xoRK4&PPfvbY0MoV4L{zy$@Tfae_A`Ws_F z2ep90Q{hGmveYp&sRR@=bN!7`h5~`7@&H?{XT@M5du--~Df>Cu9O2a}U_*d!Pk4~# zsphBE34go)R1?_B$B)lQhOMZ$BEAupq_8*L)t;lP0E8efwZhz8`Cb67{nZuRWtfyce;nGAuxF0)p zu6v@V`5m$N&R@VCCYmZ!tZ9Gc2VF}fe45GNKP&^T zZi{66c&@C7UOJfXbdtoFib~Vi-RJ`hyJqmcqeBd1o~oI_tfC)n6T^;o0TI2x?xh7) zVSnf{Krx>)7hV?!a)atl@;1&P_PO6w(o?JL{zaZWc#0!RX^7-B*TyCS-ijK}UDe^q zIs6zJYIde~iO{S63Nj7t?tX5UJKp<(DWFuICQXLh^FKw*r$M%rC$d_Z}O)>#gM1M}{ga8&IqcI7mU`lfRqc`6tcv0>BgT z30WT*12BRm!QQTR{mhQj!fY__PMn3AG{#e|U(-ej2LMDS8-gbE(I>e4U0cY}247xA z)SiXTRqFSLgcB_bS6kEukP3E%=R?K=gmGo1v!oD4rHfB znKqvI6Ay*&?bAy4yRU9frhfVRPH=4~${}7PnDy6g3z-?B!s*`eJ`elFerL>9eoPIe zwfh=vZp&%Z0^VeEr}omRc1`PB*?+jPP%>;SRhRX6>mwR@dwREoaGwhy`UbOKeP-6^up-XZJ^ptZ{mbrYf=Udr z<1OxM4Xg<|!4UEg#Yr;?eYmm__iI?9X4?zb8p*m0% z*$*S1+B-b=0Fw&lERES4Hh+6YNHw6<9(TV5HMQ@QoN7z4F?(TXqw)k2iEe8$%%&xE zorp}~8w(-w;RS>|7BOX5sZA11XP>R-ac3N;3p=lrLalO@s}_h#oI(W*(usc1zl>rr)6^2*q^INIbBatU? z*@Z^JKk;$Bzk4k49IB9$3gc&K3hp~+l@&s-#clTUcgQ4AzE1GxD+W+_CNpl%!7{V? z5kBMeE0^1NSWd}q*MGQpB*WG4wAVHTf_vr!4}g--qa52=4z~j%5SD=e2Z2r8MZig; zfgEAJDJ~FQxX)ohnbX2qQ|Q=&dJdFCOkH#+kT53%eH+UDjz-x}V$4NSxrO(z&M_)s zF;Oq^x3Qf)w5~aQaDA!I!Semb)w}OWy0#3fO#k~;Rf!GLWPdzwDhY8S%0mlV`p30C z5_bo#^^5(kOGEq{B{*f~6y1;%K?5$*FgI3V*M#}*&=f(hUO-;YaUFc7>Q;J@RFO9V zKI?S#y_19w&=0qP0_3IjdZ!`&432hME!0Ootp-ZiF@UNfYUMT zTwb3S&pn(R3xB^|W;JvdKTuuZn1<0M?RWs&?$Nl)-{vSjY*Z;#m*xXzkAvh!f=ksC z&%Gnt$Y=*>wKF_YC&SL<+CRrJU?JUrNO3#^kLB0(5oly#$b3cXZwXu?mgTL0mOj%| zmr|DX43ReofOImvIXIUTGtt)r1N>(X@?9$cBCjX~ELwUGezFM_~auhOE04zgLlzPP?lzUr!I7X_klcaJmbve~+vMqOfs15KQlS6w~0Q zVQ$ML`+tG7sI*;4IpYT?GS4%RPu(%ma~cJ`omXjbu85d}41tvx#*v09dU$!oV-KneGBv#xwp3xMS?PgzLkkTk1yTi;Sb zL&vYJ!zq?#i)xRhx%w!s{4NG>^vFeB8r8SlWq;#Eo8c*b7b^r9AX3S~+17}4pG-ut z2fOMZMI7guk1OPTk8PG_oKUb*H4FoB|i{;WYxNDSGo z4B?KelXkb3x*%)#B2iVyC)C11zg?kPJI%la^F&B+~%pvK@Qhjz8Lcscl>u)CX!WxlALz%h)0qC``uK@I`JDn z&{suQRwi#W4z+bDnXfE;s|RbUnZ_Z>fYH{OsUGYG@d|e?)mjnjU$#YhGHtohCiR#z zTjG40D967R%j`TCx6S3(#q_e#BVdI*0e^u(UN>g2uyu81K1PIc7{f!iE4m(zlaXbd z>eZBlE_wsC?oG=MURh0>wm`s zv_R$VRmg^eS*MP%9L`DjT8J%z>MlB$KrJSao~nIo75 z4d%UatJ5yP`R-h)BJ{C)e$Bo;6L!iNmif$hied$Tey6n{qD8Wt*=lS`K{YT2hYgbk zu5u=_BIzqShp#x_!4aAfnR8mZbbmx+9tTh&`CuLZ>SbLnMP>++QLY#1D=e5KwS%%7wQ?Vyg+mJ5$U`!P+3lIl@T@5pN0)3g0vQHKz22o_|2SI8+P* zsarQv|F9Ti9S5Q{5BYqp0Q0l`PDHXr0dS*{yeT7-QTK3;jto#U&kOq9bPrc8_;GCs z2jvZ$q&xkGShB^tI~~y6x-yhbOQgrlMR2g&r+L!Xa9SsDRl%R~U#u9J`Cy{t?Vvpw z!`5Ae6Xgo7(~KafX*wjuu74~7kvCHZ&@KvY#o2w+>7GCMA^(7d`VI)EFgPa;BygKN zFBBd&+kTf59?KiE2^3k{j7PBvlDUz(u`oo;V8R%<$plV!eJJx+i!}UGh+hG21;cN9*-WGbl&eB;?$7j zl&a5I68&50JSf774u1%L%O_67T<~8m%4W+L&~N+ZB(F1Q307y}03{7_bqp1$zU0J! zl4G4$S9=rE@plq~oE{c1$ZK{YA9}ua{4T$aURXm+6z|mejL`iJ@NtwGp+biapqis2 z*M56i-t(uJ(HexwX8hT^&}lL)t3U;tULfl~1^-+X33rz5Ab+P5^AwL$T~YQx1ZBVW zLx#G*;$4Pq;`m%`mZJSgd<^ZGVB%SSDbDJXun1$W4V~ky63g;Yu>}Z++PzXgFu@|x z@&R*d$cqmqQ}_No^U1Jkhp}+ng<=<1Vwea0%&N;-4SL6T1~zPOk%H}W<0G&Bf0Cz~@H@_et^6z2Lpz-J44rPT{16hEfk~=MQ z`lp$$ojZ!;!ympCw|W3nrGWAXA0w5VqPKR3a+jvxTz|h?JIkixxtDM0S!R1Rl03XK znnzFHsRj9GI`L=Lo$0X@otiIDB)cBWfxMG=%FI?* z4B>}anty_)Sr1U56^!Ek><)q${_i5lWF@Y+%}f%!=wt3EWM~bLgQ;lU##%TSC7j`b zSc(ZWbDgT#Sa}C-y#8`eY_WS`dK#AKTk>KLs>Qo5sFK8h=%C;wcY91sYIq!`rL^e%n96D#Mdy z3Gl7v04bmad!%A`Uz-+BC$z~MxK}}G4y(U63kMe7`=F~Aqt7X=kIwFXPAzS-2BaZN z`h+$;$g?mJlPpX`K9DJfJ@F8_Vv4zY#p-N7)iu5t{y>tW!3MjrF z0v0}RNzYd24Nl|62};t`o3LNiR8TQTfqF19ZAvyaNy$Js_+rpr@BrH8C;LZAWq-jf zivWN%7roWPqD-#b-Q(abiLq&@SUiG!IEbGD)os3=<0$963E7agTI6+T0O-_kxn!@p zk2mH=n-D7~3g*_VI>>1x7}bwq5}sSEv3nf1DxokK{oss7X!1c{6(uKzV^6Cj*tc{} zj{&TTGziva%u`0AxP_i^H05t-S%10o!(LA|i(tOT2?N^Ip(Oq%b)(HnC0OPV_at2xPDP*E9zhW_F z+luM6NT?hA`G)SEg-G?a?7FM!H^=3CS8;8C5>DN~HcC38tdZwM*--sF&wuWXQU6Z! zk`rR^c&{dXdEjZ80-#iUKP)@WSAzAyYd2r*9_n}g6qa(nV*jFiXX$i)DzCjAPtyTf zwq3|axqzvMlaOV4QkEr1_{fI@EE#BW;8v~%W{DD47dCiv)Lt^P^^Q@kK2z>VIQE)! zTE&v`?b{y)P^*1}Wx85l;(swPssM+KFVlxb`3g@FEU!oA7owfsE-qy5?q*h)X{VjB zeZSwkBg}Ma^uf1_L;|3zVB?$dr7%q>FOp&SFY6Va@uH2!$Vjcgo=}mPb0mWVc!Pk+p)w?9{gKQ}gGa@P{_+!i ziBl;mo>`4n2X`K1$nM-k40_`JCC~eG>cuOF#38Tnn|3lrAb)ea&5hJ%M(@#2E1Q6$ zzPxpwCSerKwpqp3wyCm&*3fO*D`1ls?u?0e2B>)kJ_O%Y7sRACAker(n%`*RcrVS| z;_yDFQKgB3R`sl}HSH&u14O@Sney(_PW#s^$lbKaX%TQa+h2bua`pfL?>W8@?wwSI z?radnB0+W1f`0%UcpL$Z{oZT@jxOD7>#q03Wd#Y z^1i&FyqO}7$-rngvx6q7+o+cQZ14PG15XX;DFGG6Q-31{Q@h*z_NpWn?qN@#{w!J? z_&`PO*0%Z?5Xg|A%z|8L_9>I|i}<-8#R)D2P1vvNvq6(lMrD9uGh%+L(?8GFSg>+( zQb{^)U|TZv?3RaxGc?5?tUa@8dN0_#^^!Uo_Q$Kw0J{Q+13OMKxo@>}hXf~3T5tWj zZ|9&h2!E1I&@KsLyEm$-HXQNR3~;3Rz*Cll$k)TH^DW9EFX+u>Mld9JHrg7hofv`8#-6BQq#d zkiY}h52symAxhfmkt6qSu7Q|Pe^~P^7dOddQGe|gbOrYOQQ%6ff>#qU3vKcw_Ijo& z7=fe*2BQd9BJ^QgRu5if8_0lCF;VGKBV1o8ocJ|K2=y|7tjj|Vxo*oI`$ysmN9 zxoGVWd*DcJaLk_sSo-`(fM7uI0cU9J!ZS{q%Mj_b!X?spLIWe_j-*UV692Zv?RGAQ zWPhh$?xQW&L}!`IyD~X3<2(QSeOn2Vw#Mef&Y&!k+ASQwi+TfxkN~EMkHL{zWi-3! z9uOZo+|xL{)&z9Hf^2l$Z(b+*Hgcc|Ja+t%$VA7EatJ z8M>MjC7yH+RYrkM#huQYfUK}kWK&r=8h>RnS8Ni92zPNIuZ57bC;{B6ez!2`(&}eV zskKKKrFc8xld#c(2Ol&2QEYTjT7YT=o?`E;M#3%Q;(IV?pr{-fh;ko|rzxz;VUqp+ z9RiMG$6SlB?K(ASv7YIzTj21n{*Qcux^ z0FO$IcF(M5q4$s0Y!sfl-ykQ9>6Lp|!1%K0yY%hfpfX5q_{||sq(bJC$TT!w&Mh9* z8MIKhIpMeA#GPR|_5%9@rG7wX6ClOQFEi}>9bo+LYys5g_h-IG7?44y{#tqNDh;{2Dz$U~4-mhdI4;6fxrgY^l z*jb-$A&;jtFw-az?9!I4R(=;Xwcuu#7jBuv7)~U-ihQx+Zi30B!WH@gk}>U?76x;O zv^3pRz%#aE$NjuR4|lzEXMZGajclKyt?$c69Y~)t6ZZ)Vqco;H@viP7w~$uaHNS0R zT0oyw=SB5FE;4c}Syg`p#*a<%!^&XnjMmNbTVp(I#G?qfbmq{yfSl^|yaI1cCSdmY zCxM@NzxemK`@15+qnl4!Cu3}6!o%k#7+Aku9b z9sO#e;DNitbKuW$&0(Qqq&INL)ZT$zKDxy<)KeEp21*|eMf*1m9~j*^m7LsAMzbt+ zcaovgQpaYsgj4d`eSaW52U5$>A0AW$$n|wfh!%TxXBqscSpMu&SDN{(cb)oTvLXgI zP7(1ThwtK2tv69x2|ycBkazA=pQf?tFc^m)I+x+c>_6~+oOfW^VP!*|_)+iyVqah- zK2;AtH_pG^H|ShdWGrZ$fPXmR_5DiwN|y)g58w{; zyw)$KiE9De#a!9iNoT~$GQAdz||uZtf86I-qMv!pk|JYFMJuzN)9LC+1P6T zEtCdgo=YBqZGV5T6xAJ80hV^^^h~;EFKUq_bG08v>NXH`*?8)EEKc0A4qv`%3`!`4 zPamovjhF;+WM=Q{V8fyGqv0C1fFHO{i#b94hMZC`uiPSE@7`{zvZ@sSr};Vq=wxRi z2l$g7sk;XAgbyIUHUOl{%9Vw1*c`3HADbbu7fpb)rGIaB-N1KE!R_?eV+k+)IpxC? z4NLA}QPOP1`iWS}Js%oy)VcO?5y(hCjCgOx`ZM%YRqF13o$x6WOayYl`vHb8$e`%c zOSA1#F*%ZcZY)4jf6J+%0GnVqr8I5j%W+Qt5{DVx%5_Tug2`O#PA{AN8omDt2$iWA zf9S^T_2eJa162q?2Fybd_B;5qjP>h~_@gD)g%+2F$j zD&QcA&IHp)!BT@w+uN4ilI!82go)PzDj|D-gCCzpBWdYj;A^smguwwjDW4u-+zOB{ zl7H@_IxELgy&nl@re~j;BfU?*OG!j5u=pFduz&q>>LJGN$`J|O(-g-k`31$#)UTxp zcG!icQXWp(7~{As9k7To*Ey+xJ+OFItyO3hr z{>#NpUAJ{!uU!eW7$S;WS=bXNWQ$iGIt%DuAw@0v{Cx9#SRV?E@g1dlGf7X(UhMii zy}nqs=beV;jQRlKGMaFIHOja}9qO8>(|@Yc#x-bOq8RH`ivOI;+-;o1?{KzTVOn(^ zpIn$I38qQ88EpU;K(r>4H502b#s;fn4`YF#0lpGlQd>EXCh5 z(^~;WgBfkioNbFl_cC!59=M5>TbgPmwyKKD?MK4px5=H@(3?URg3IKU-jLMBSbu^1 zcO4gNTN4kS-GMLcMG}Rk_aL#~bg%sMX%>GtC8Vv`!ZQ<0@etUVR0UdlsuB3UW4<6& ztHBJSxDs!NHhB~{=#W4)(3y1Ffw}bdF90+=oW=(y9kh?!hjAgs_(s?-)97^N-&GL5 zgN{AOz_mx&$4Y)I@%BB3!$fIPmVa<`!t!v)?fk=Lb+&{qZz*ol;5UnLS7cL%=?GD} zgIS;}xNrwYVbt#;e5O-QTeVa=$IvmY28BAf?+H{4+~#%2*A1^^qDO4FKFr_6P(iTT zHsR3o3HWlaNCQUXEqvo#c^Kl*&2Hi&=TVS;MQv_LXd%EJ{wAfpe1Q;f41YN(wa5R> z=t+I_+OP5lN#r`){2=i4(8l3?J_tWEVIvAk@DR1fYW{$cg6P6nWM=hE5p;5 zzzx53Uv357uH`;K!7xn4@EvdaUv~HOII&m;$)xF^F`x=|0FH9sK_)to$v3T-4m)@- z%lTJ*fBf2Fx8+0l>`71ZYagSp5VRxVB?yGd!hbJU*MQczb<}g( zg#gTO?l}wVc`K#pAjn$&lyA|vDVujpqXr0c(rT2-12)1kGBeGVw zb0p|S=ksEpg|=&0f*o7;DKFeKDiJkh@ZjW?Zm;(d3XsMs4%{rG?lcUI;~a0SF(z)( zmO*q*4kkfD@EM0!vbEemqM{TYmd;<(Gy0k^&6kRODEPm8;1`k~&p(JI(;AbvH{yPD)&{6r!+h@osn@2rVs*&J0@kM``IO>=<{P>5 zym*$YvF7I#vM+XPFDa>zL;?vllriPSFk!nGf*q`j#NJUpZmSbwUE8Ffn5^~uH#O5QI*6?tPR zxVu>Oqtjam+UX!vV^J)>vsV^#dpHn-?F*pPH3m(oW>C(HyjP2uLwDmGluOQTS}gnf zky2)qH1YoF4y{EGI=`}}{J*`x<#m&(zWcy%_cAapLe=+J2_y4`>w&Ht0I368Ho37c z-;r5#tbZhCsP}p8DEiouOf|uRzd@&=cVPY5^aOb+ISnt7HOaExtW(l_9_kT8F(A8%^RISQ0K-?2JZxq-UTO?m>Uj@>zdjZkzc;-U&#jy!SmmZwrBC1Eh1@14||h+y-1+>X-M?n(|O> z7=L>XcQO?Ckht>oOfe^}#t&pa8Gve5gMWhN!CgDxO!qp?h;Z#`V-#n&Z4anqyS?3Z z`SOFttGSc@qW-Y9DyUqrCAOZ@c2L=jxd9t%k%DSO-*A!LNepQv9EByFZBnv}Rqd5~ z-A?5;1E!hf*QOoUhgPIlsAV}RD{@i9`+o*njeF1V-SH4D7fB@W>?BIiiXgv!Zc23} z;rPt$GtMGi@l^5lI$!}mXu>d*hND$r_TOd`Ap@;$Nj(kpDao$m+G2a4^qYJQDs-4I zRfaZpHNP)T`WumE{GmBL??R303aWfn(S=x~KMy`#J18hFgom1u*faxteigENeSeFl zYgQj|`}?gNVA&hVk-~XDI3%7K;8$8Mg^C)S2Wz7(w+kAt9oC)qC>N(_-oTg}^GDD( z$iwyz?gZf72d@TR>ndedyx#*AKs z{(D|1$}XUi5A^^o{8g_N&Q z3S62$@aS?}UtFAb&(G`oBK`fkbkn+2-@t*4N8e6yCtr&$lKREDiCr|RxPJwuKhLH`zb=@qNg5=Or7twv-Ej&()OW28o5f@<>bc0+v!G_ZirQZ;a zGXly_8-WLWr2A?fyM^Jl41a3#`BiB^{5awv#Y$QmKaG$=*jU0GLf|75So3 zE!-Cu_^+(@>UEaew>$?)l$=dC)W>h5LPX3gbA znEdA$<7W|WLr_h0R)6vAryWmhM|}*p^9*)U3EXnsgj3h1)f-5! z+OSn%&%?rgssABxN?!a2x!Kn+Y^ABds6UDw+8w85kHF$+jX#J=cTm{&iE|cXYlxY& zEKzYodfu`?#|97n$mgho&O(FstLsR&qEhyESV(bbvRiFf@qhRL$lW;T*3nr423#eF z)E3ZHmq3_hTVDeW|^H7){IeIqst!^1wJA@ zGTv_2Yq@8oPCtXHi`U%2)8ZMBkJBP5fBd{%lLf6e2VQApUU=EB!YD%G*I0CD+SR2P zc8YuRf4UqFh=1S#uP|gLyqgo9T2^4%-&%?_5m}twRCEutxv=5nJn*D%CIk4M z!ZwTT4}W3SPt1hWgQR0V^Ygt#tu1tVqx|8rAjg+ zd|AEDDIk-eZdxGh<&xIj_K7mTGQI0O3d7vCdI)=sPDabcCVl*ow`P>3>s^%}HvE(*|I_{8;JV>nh9*8q0}yiBPpdHCI7QfybL2?e z9QGv4BKV|R9HjK_*|O=0PoO`zk)AZberas9E?JUy*v?*&MMe5ehVUYj(F#tK2#a9Y zC{!YJ(`iZ8^ZXW!vtQ5*z6@l@bcPTyGk;fza9F1ZZPhsEo==^Y^X+v>=@_UxN8krp zh4L#h(1U*KrXdR8@sSTyJ_$SuJ>9}o{!l$cpEv7jw3_^+p*NVqiwQ8a9sgkSuR|7O z1wzB}Dmz7?myp-F@N({Faak()_cC@P_#p26h5=#F43Cj{fwr9kT?UR`BEok9gQ(-sp+(qC_!b+ChUi{ zCXhpDDD>COgVINlaPW;qvQm^wOb;e7aY1jIFAipe$xjg4$+uTn=Il3FThdYiI(n%70%}p7+d!3c`fv-It|J0$@d=-HO^qr=%5VIyryu zM~^W1g0yR+G6w0|jdC)w;; z%@Kcw*$=4Q2F-K8omP6|6yMRr32xw#pz=_ZFO_x*rOM&Uy>L+_^c{IvRUvs!^4Yoo z*C)VWdr~d(qb3UbY>Yfx=mj`XZV*u#9=wwtHzENExNTM8q6HGyH#m{2Pzu;}UE#?J z@)hOUw|TZ?ZpC_2nGiD%?SJ=9AKFb5V3rk!K#z0RneD?E_ z%6W)(q;Or=bj(awXdlW5n&!HQf&e2vzz9|6^x4r^nu)2BuCY$+AS6YU(6p9;*~N~# zU!KYY!~SZl;#D7#WIFVZuYdN7^KolkhZ()$yUx8GykHT$Hth~(VSn}^mElPnoWz5l z8v0orgoade`!Q0V{o1E%%**swj;JqH3&PYo%3ff=N=G@x@^K)K^tnt9zp#vzj|xGe z^*S{+)ojQN6W>2#^=QW$@-@doqQc<(+oe65l?(}}6`H0uAu}q-K z$Fi-obhbIGJ(FO6dUEvxI% zd7hd?xc34v8(UwphZLxm*{~scUY=+I0e68x+Y*yw+5o}f}`DO zNDLIG0xCwN<09zWM_%24vRO7bn>$Z$e9&Q zGk^^k*&r+h>(tF?SsWzhwXFy(xnas^krqBF-~>{)`+tF+JU;;+iy6s&S}49sQUbeEv*%iyQr6*DuHlATb<&IPxh6J0+G~6$^%MeUOkeZ=-4gUfE$RD!QlsNGdW8b z#Ne$O1;6z>=(5F>qyxSriY||vu6=a$uw`{)PJjCTsIAh0SmXKD1j~s!?N2?}_j_GKIw+tpy7^_4I z`hQ$VpX^XIXFvc_K&`*;5J->tkS`dX>I!^8c>HXGJgxd!^QS~Y`ubC{?vJLeb$0yp za6!=ma;i2XWj5cY>QT@KW56n?K-=ujj=~7+JRJ}!yAEPxd%}bj9M`ycXh7Uh_!eFV zF|jwzgglwe(z1L(v4??2g~jP!dT*7t0}!W7J!XGIS+)LgY}VW1c{{3sEwo3e7R?Mq zEl^DG-b5ZS6#NH3T>Fd)5kO8!7943poKf|PA#Kr^fY(XCk(U)QaYo}C6~|;2GqS#x`CUo=EH`a_g`kP+it!Eu z3A%s5WPt5CECR-;bIIBC?T`L(r>UcV4oOf7j!7g4da8({&w$^ni&d}DkK!vT2;$@! zKk87}Nb2!JL=@J~ACNa%PGfvK`15?+1X}jrl4fJof9Iy74y*WzS()aKCDC^m>*i?t z25VHpdC4yJ)-uc3gH@U+Pw7ADj)TE#qxyefj{O40BdQe!u*PG9A}vEJWe>OsaMX9S zsmTLCs98EY@1xP2o=xh}#BjnbdQ6G;xu+Fr3eK?jGO9~AU05T^zC7)t1#lEAUXS=t z9#I0zN?0MiRt-%rxS#@~yWP*U9bh50+A|GHQv`OE8Lh&7%@2PDNI$eVl-yct*w}UO_+~iB7ZKtM{9LD2Qi*TGC-QfFXGL5_m#Y< zy3Dy@0v-{Q3!X|xsiq(*tRs>06(nLXxH!mM)sNA5o@ZU3AzsnOpX zvHLyJXn{8^+O=HNxPEyK&s3paxC?$Rl16~&9`sg4H(k}&7ka$$0~3Or3D0FZ{(^5n zLRA$H!+J-eDix7&F-`0|3N?Rf55Cv^Hs6x|TxMnj`(QXQv5Fq+&Dk`+z(<9ae3P%h zlDqHFY2p%vK^^@z1&r;3Jbb|ppD33CdO!T~3osnqI@9??!{Ig}-1HPqTg+haLbca> zNBVg<{7Ho9B&*@%*$U_kFTwaM+OfAL zmvN%gmp^km{hHoUkY|5qmnr#{$+Ccr6jr4tB~nEYCNlzZFYX_0dGXysV0?>M#t@$x z6;L=AK%|8njH2DH#6IX+x=m}XDH4Z@^$k$84i9W!w!5^1$HiaFoLs_Gdt9&ZRxvh( zDlF&sNrvgW5yd`~@b@q|Q4Z0?mTrl$KJiF{dLg6-PungTE`fhS4!ujUpo^4GYd~sx z#np#YA&sIRe9SX z0C|yt_6w}GF~kh`qFzoShSfqKw}Y{gw^lJfNpC)S`SM9MfXuQzIzXUDyzcfhaK@Wx zfM2m^)o(^!nu>pW;7t!P=0|A1K7zcXm#Wx|+7^x3l6*j-oIH_(SK1i1Ms`{E`FOF3 zC;0bUmGMcBWVE=_z6gRDhFNfaRJ5OVd`hVG3&n9IzqETn$dr5B&5m9CO63ITzJ~E# zR);jW?-O8=`kAjqQXw7$toe%J8^eK<`cOPd!-2%J81sMkc_iCSROibsY42evq}L5! z?Rmc2$#Kz8#>w78hBdYC;~MFHdrHHi(cl*2>u#QlmhrK&gKu()kR90%s^T%HM9iv2 zj9K~#RXZ_+(vp+-udb5X-mP4zcr-5)dw=`28Jb8Ldfp1 zZGi2pkLxjnfBbApsc;HHp67RPbX5?5Wk&$W36l8T-ef?mNgWRv?xxHNx1!0d%f7GuKRI*86wFn? z)2>n(U2t23oQ6%lqQa|mm!5~&&>%|XAL5llVsY*_b z)g09yTCPvTL$kPIn#WB0Z^He#KC47ZQHFm|bU% zK)^7_1p^Ur$k$twXF8b@9FvjJKC{@b&5IO3>Dry-`7zz{vtyrU_HJntf@I(VrJjF$ z3y9#UleS2tGRWX&@2+ z)LnH+HmR{LT0~(>+fQwlpw0dk4sw4Ck&2>~RjdGv!t-WIR3ob%kS=%4eD2PA;DTVc zI;+@vlV-Y1aL7gndk?6m=_qLnQ>Ov+`eSAa`3m-#ZXwO^^awJfhy2DLy?4yWbh_9@ zU%~h7-=IV9upwu*u6>Y)>_O%M8u(3zV>4$R32tY3*K4KzIZe@Xt3^)Jtg(MrTMf&{ zYq_d%nr8z2X)Pb)Di7b(bcS^JYJR3padk9aKmkhRuKf_Q({ zsML=v{B!=^kSRgd15pDTx4BaMpL#yePRiJpC*-Xits1AElbKbIqe(;QF+7MGFR$#I z(M9(enfki3Y5&AnkJJ0YX@!5Qt2H56xFeDq4uhjV3cs?)&l4Ld2z!U4muA@RswZe| zD5iThxyA*JXF4F#`?LnjLyvr$_Z~Pk{HWDdq)z;NUq}+~Z!7{gZiN-V{@UNh1Sb^0 z;+V)86zqZN>a`PqzZ2vk$1$}Pq(4)Gt5-5?{JnL2#%_qfj!{Q}w4{I9Goe<~SHey& zfGgDzD@G>^_k1k5*lmt~ovC4rh3#fTM~YWmUl`o&FJ+A-NljDwG6(qQ(z_W*t@|B( zwbH#$n_(RLhckAkbzs$wFR&)IujsRQL>(cbAhlH%CHmARh477AN{LR53RT-qH~>T1 z5D;Q1-P0&w2R-}plK_8$Z*fyqUhHQGP>ETW!SCV~yS z*MaZ`!}Jd?vV(7aeTel6U{EP~79rV`z_m~FIRdDRj?^Hnq@91FK}(P(MY6-1D5vYX z!^o3*VUm|qB22!JWjui69N=R#cp-TPI_E0_>L9r7ZXHEUi-6RSE?&4msB!N;-6`Gb zh$RQJOdkbp@}Xmp;0RMZ@d_BxuV6;dVW&@V{PI&tlW1moHbN6%>Bi4`2au?Z!Ns+6 zH^d0nf5r9&!Dy1WTM{#;6c=yl+JG=HiVqGkZ_8}GK2Zvq`GJOcTpxligL4F$4MNz?qvU3t+{YC+T0 z*&&&CbWayq80nIP99$3e);7tiv0*jM31WCr3!PZ_)Ej?F^n8&^iTt?FB+8=A}n_NRM^>m>bfBJ2$_Az?JSEZyN-h^vTxAkk$LJkGbU%ZX8F} zZ(@eJ3#`KUtOKjhgyX7{SRj(3om7_<=c_PBko4b-yCrTQzpO7PvMj?&E$5oXIur=X z;dz2<)!lz&ZRVgE4G={obvqrXpiEf*#1=^D>YJ2z>=h0Snc*=yP~gZqY(O(!9RdH? zWw3-W`I!JYimO&zmCh#SmuL8LwGvZ4k?>0i!1K&tnu^;zQXP}GV@YXw_(b+gXrFIr zyX}T=ApO&CZzN)Xg=t2^8+L4RjH44zefL^dK4^d3Tv8SUw?Cgq?LG9ol8Cl1^wr_C z=zrV^cV0L9`ZAWm5YS~{H64hzu};VzlkVEPgF=S-JniU6L~nG$m)XdNA)!*Anxml8 zT@wR}j?luATQGjtj>y*WHqq3wo>-6gBq*d+8vrt6f22yC^ab<@W>Bb5+HdSB77NT) zG3tLBWBgw2#hcWqM zxrwT`)WK`Cw!lu$g4RStpV%E>1aEG3V_-qb_Cx9S^)m`h%;NY;I@lh5pwjcFA^&QU z2qJt4eK8uG;K_|Ah3u3r_{sP0kg7^7${v3{;X=umqv3QoHDH2PN#M9B&3?+C3)A_r z+#N{L%ESaeh$!R$BQ^X~yJzz9=qH*Nhz1}RQbcxHvtIxrXfO2}?&c93K%n#!=9&n? ze@F7zPOmP!G=u)R30hrMf*BS5k(NIlu)?-;O92f`kFy+AzlcA_T7VQ1#BVv8<{^KQ zs3-R}z&L-t*(^Ur{D2r3k-0Ci)Y-4ml*!uM2j4_fC9hCGECk3-6%emC&F+|EAZxxx z@y*ac0Doq(&KRCMFHhuchtX8ws!_zl8JfF)?n#k%9q@Z)fj;V;ucE+1y>N}xho>Jh ztuMQ>L=ldcZTg&pZJ{5#dZBfBBzu2yQ6?k7yd~($oRP1Tat|lFaJknjvwk!n2MuPk zedcTWr|B7|=|HR02`9DwIBHmtKQ}0nO*DvL>X??VY2oy$cvY3f(f9S+XQ+7RvB4@( z-1t0ll%^y7i%M=jubr4v>qRh~0x=BJo!-Y~1ICVB-eKtXl;MTy=F0X z1rg=6r)=b=xhzSHkBswoC8*g0;Rm0}%gSs1BwY&3xM0lt@2f#+9a?Ot%_diUztZ<0 zH}izIg!;ktB|t%1HHlfwnnt$?n8;T6rR5I90}dF!>zbxRF0U5oy?FcLqB%1eNTw}N z0zj;S`hIT*Z59;S*a?tbT4jHk3a!fMmyzG~6C!j4))gFU45w`JHx50uYN6o65F{6~ zxDXZti4G{y*9lyg)l*rKU*vfV7D*|1WHRY%N|0Z5NxwS0EOQt%-l;J+N>#o~?n$CMw> zv4x2BMd05~uH4O?iwN(;YdlUt*wu4lBxJfJ{>MbJn>~X!IO-}8b`uHM2Qc6_gYE)_ zEaiNUkEfe=`<50Eskxxe# zSz$g!t|7LW+GY z+NX7dThGaGeHZH!ds5gN&67^EoPOCDw9V1xr4efHu?(AvE}34g_Y06&0K81&>f@w3nbrvi#1}U##d+)5n-Eccp-toxDP`-*-j^e zdD{DdpkiG^)_hD@PwMht0ah2mH0*d!kCRr7bBBYg1bp93QNedHcyuFDSi*lX>UA~G_h15wL66N0>ZOG;#gRi}B|0UBEnJ)7E}0t8KJ97fo? z0{Tl+39gNjuX|TgzUiNvF|iZD{CXCaZDw{y?>rm;_J=oKSCG;?pDj=sUpgjBX|#lJ zj|WK#3nilte}V*OK_fJ@HG5Q{$@tXHWC1K}M@oP9?=X$Ig2%x~#T;yC8h&Wz7B=dH zB0eosdI3TS5=Td&b5ginW3hVO&M-YSduBirvv2Fsus$gTMXWkxahsPaB;r{(%~iD^ z4;1m8%W72C^5=oZ;Og?3`{8~B6`rl8&#$OV6eoxX+q}sWReD>MDM$l!NI`#+_r|_- z>%xBpq|Y$=zsIEAR4BjgEy0mj0H1$pJTRl|rDBsS<&rnw>-UD;+-CgIWng203jFMtB?9J2olu@N znTIUD+~&U8XXMbl?4G9JCl1il7dwCU$hrbL`QsX`J36tF2CpGGkLw2QPAQ|hi*qY8 z$2I8(xZWDu$Wvz(?WSudH@<59_ysa_I2S=(-NtV1b%fnNd+{?jjDuIZVN3m^SUXvB z)&zV%2OuN|TS4gG@}kmWd!%1LOJ_(`%86wT@^L$)AMBUfU)zFg-duw^VOLJWqPR3; zAwPBFRav#zjAa>FoGat2qN6u~26;pL*bl{`jVEQ--t?#4P!ld2vsQm5PDF8Sc5wpS z6wlr8asR+D--&(rJYq+==kpw=dm6b6Ec}vQZ*WKEscbRXLHnlpd!6Et!khH|z5aOS z6@CC7bmte9RIWR8mY<@c^J3^e>&U!g_MF{J97ykjD*K=u%`1)>Wak=8nCyYU_pga`Q@j@5Sc4J)cQ3Ns=JNR8*{3IjM2p#yGV#!CBL^-e#yXd z{4_QChSovN93jR5tXGF@j1icV16#)78IFym=0r(85*UR&9qfM^9Zqj@@h8@PmNsIm zw$FG*a60(L@OE=8HVZ3Iqm1Ui^K1SLwTM(h$&)m}2~C=neMlrHx^{Z&Qc3ZrM$~Fn zkd^xMN=0_XyJlj?0^B3fTuTs~)?rjz5PCLLIB!?Aw+TCetj9SmlYVt z)j^D*cnS~|NB3SvReQB zpZU;!?R0DY(H8&u>(4JR`q#hz^ZTdeZ7}|c{NMP0{CW9@4nx%cXZr8gf9QXI=Kq}j z`!mnq%lWU_zmxxSdG$a3H2w3>0{->az6}5Uzx~gJ{*QmZ{!z8V@UOq7w+R3G$NWw6 zc6-+s{_7v>w#{`YS~ z`@X%M@V{IC|I7L3*%p7+?QPhWbXu!<8Q*!O+tObD9sUpKeZc?mXDi?5|M)+<>ix@~ zjv@c+?R|g#Lx=wB4SGA|?=Af2vJdaZlt($uMe)}^jxyio<)39$y%Yay^Z(Z#`un*a z^}qkG{|8V@2MECQ@4i*<002!t0RT`-0|XQR2nYxOEI12G0000000000000008~^|S zcW7^HWkPRcc};I*Wo$1>VPkJ%X<=@2E^~HgwEBNn5A#5hC5Zl&LhZ{A*wyrIwrdvj zMijm1-srve{PmY#wV9r|v$(jxtOO}ZDw&ZP8FAtqN&oVHUw!wNBVX2f9RB`S_@AM_ z{v{vMF{_92?|=Qd;@_yh{@?%YU)H1i%UNez_4mIb^gp8nMfUw)|5D|3S#AHrrK8SI zcD#T7{#WQP&|hE}{`30lUtSx-`uD$9+cy1I5IoQGpHK9k$E5@j2!gEg8g_tU@q+iYLsfBODy z*}Jz(e&oZLW&hFX9WPJg>Ffexm`Wx~Zgy{ch-`8KX_xiuL@Ac;&L;m|n@8Q1={XaNrU%LPE z|MLSM|GQiMnfl-6MdY85|G|qeME(=@uMWiilOM7FXdv>>D#`zT zfc@|DEcXAhXR-h8+2S9M|Jk$f|7(AK{nzMx-39$8_d);O{BMj->OWgWVDg`k*CL8w z|Ixz8Yx2(r|8amo|Nps>`Y->#6Z$_w_kTu@WZ$;`1$OlHmM{Nt{U2vt{WdRP{(pNO z{$C*1|MOP-4T150`WsCB*^j!9%ltpE`1Sr@|1vH4nlDGrtkdgbJKpN?-xq)O@1y_e z_QLe*tGE4wtN*oH^5XA*&EhToum2bloQCrMO5!yquz#vO*04|LBb6ibK6K|-3BU3^ zDy;WShBzjCTV8`V;Pa;g7qE&SeBUEdc;AeRk-X1|CGT;`2%TVgHZ~X+osng0Cj;Q) zx?v87ftNQ~DoUA_q7AWt!is-_@O7AZ)bnNhur2kO_Jl zP)Oj$m6Ox_-~}*i6oIThHfF98QkEKTDMu(s#a9vt`L>j}mD|23Yo>~_lU}8%TT7r! z;xFU#KlKByWPsYe` z3&kv@tUDo2Ls;250ZzO$bbgJ6wldQQs@3{OAU8_adTm&G2WMB|&z%0uKU6fnT{#bD z5yZPN#3>Fhf>c6Z7P=Xo$mE@A^+iZxSScvz7dW_Vk zA@LV0$8?ux{^5TkX-ruo%Cqxpgy$Xxn-@-;BBxACdjb`ZidON!efB?}`Qci+(Q3BiP5;n$LdoJ)Y4TQX8vd8xxp^Ko;vay#m=oS>hk zz3!E)U=HPpQn;VAbq5}9n6KW+{w#*5c%7-~(wTV;ZM1(s_X=nkDgejdVwP+)HN|&C zB~-c{G$>h3ydlSFvygW|6mY!caZH;9rR6dx+|LeO-L|K zGPK8*G?RaPc!O(~n&rDL{P26>W#zJf_HQG2+|L179^6mAQXYD$x`%)5%#l_s`Jq2f z9|d{jqn{R{LldeJ_M`$9MAygs9*OInBllgjoTrgvBk-kN(lXbG^C$Wih((`#xM9Dw zdovk~A;MBz=emic7Tt-e#){lZ@MiuPbHfQY(TVm>v%?`=1)NU)G~m)KM8PgN%E^0% z{+gvY=5}fgCn`jzhN~){@gLh~P7{SR&2ge2Xv&BxpT^7}FeN%r8&>|iVzP0bg2R8( z3T=Ht*<$b!Ee$2>J~+rWR`KK~<)|-mLqCCuZ59k9ErChjD@TLWCaisGuZTtg>=faQ zD3O&Vj!s5gbg#9k*j;Dx_TjV5!3sF})lVb+xKr0TOu)O7$>h_qSSSvdbO=iGEL*W; zHscgkBXW@Jv{tjbLt}$W^=rTwCNY1#!3o1C^l#<)8v0k!S2@vIN0Lv*`M`C=)LR>b zDYu@$fU9Iux?#>sCz%vguZtJQ^OFK`t!7{JwU&JULz%AM8C2m+TKe_WG&Yp0;`l6? zHz%Bz|8oHq=qy_a=yGcyd6` znDHvD2g_U8n8d}dA}LB>1rZ#kN-PpE(28(~f6UT=%x^=?Qe3tU%epB)*gy-z`@uX3 z^;OGlO*8*Dw0d|UEmrzOL(cYr_*2fYNC~w@bBAgJED@*N_o0R^>yZ;? zNE%>Z_Vq@`b&VJjV`qObfM}I^36I4?oj{^9)AzUSyEl)W~-9H2eMO2v^4BQ7Ib4I z{sYp@^81LLjL;$YpzO`wWs!%pd48nfuEi-!WeD#0p09rebigb~ZbM7bn8%>_oyOT7 z_tv!-hRIH0vqHi``Y3kwDai!Qv5zQXaajNsy$u#W)-u^%Zh|R;s$;$=V6)13sIjSH zZWo;htPN`v2*YWYSy67}6G%oq??A~pu|~afIy!)?B*z)d1+QO00-6V7&-WzkGgaZI zDoZqYK$w5oqXhh*<3wFQMB*{vLw{geH(99p{n>NU%7_yS3l8dWi$rgwQ4(uYlj3)# zR+ZZsumSWi-4;OFlxTp>i}643n{Of@+l2}%+6v1i%n)&4*3z66AJH;ZU#Os@eXCCI zciqdtQlE8=19@_mIH%RZ6wUrvJ-szRrVrSfrLBL7g9yMym><0wpKM3T*s?(`x9s0tvDv!d=#8`j3wmwX`tV^_nUc8?>2W~0+={6M3htCP` z>DH?93=>}PD%!3pVk3PFjwjazxb-i~nXpcy-iYTmi!R)GLoIVlMDb?ra0+$|48gMi zb%748@YO=<6&mbPdZS{H=vF4zG1tbMi;pn!S5aTV_tKuR(5q=LK2t}zfjiMwOyhrp z8w#ID_eAX_vFeWx^UQ17_V`wNbO^2qOAGF`MDdgf0u2o>dXbcV(Y!=M)uUTHd19O3 zzZgx}@JH$CwW2ec8$oBzVR72?BocFn{`%1wh|$UF9C;e8gMQHL%HJ3i-`b-E2<3eP zL6Kt)cJp2I7*|P#sMvth3#8&92RnZ^#-oivi+|OZea;P)=_0Q|tcI84?a524?`a)` zp~o06silA)`c+zrXVfiHJjNa<#Nbe&=06T3-?*b<0buR>O|;_mxg0&_5G^2Q+rS1a z;HP(f_|&sIBh0BlNM1RA9HitkV>%9-B{o^-_^{;FYOX5GQzmeaRYU=2!G3>?v$Qnl zeEPeEj;IhnC;h=0iB4k})i71Lri3Z4&pv<-Y?;bxGfuhElBBa%D`QRRrd5VZ-a}>6 zqP0}8zH!2bT{bH#sDpv;+kNq7Or11}3^Ks^xs?ljc3oQ#V=H5!$?KMLf8~onN|9HU z(j;Q>L+dlk8lD~xQR>`=Q#yaiq!kP`M;qVr8s!O$b8$(1M_NiObl?1oDIkrcukyVy zlTLpHKSlY}r(}Y7*p;>c37Y5Qn&HB$AQ66kz>hC|Qa6Z+IPicbm85`%%0b+$OF3fo z^#gdRha$5GKx(!qy>SeY6sv1=rv1K-^>HKPB+6$I-b^fQW25fX)@gqvRfzTJ(1FXO$UP&8-amVk+CvI#!ukLYsnW*y?e;){}nTN5~A*&^@ zF~Y@n5I=rTnodAA=?{P0y1v?Z@iVT$6zиXnfxHav&#(OCiCRH}ZRW^y@7m=_f zRJ%HLN>+3v*kiDMUby1AwA|9C?V02tYn{~O(2eVV>)$cTFU@WrO3viF)XkJ!@!y_Z zb>U|(yUD%>M;*X7+|TP1k+d@ed={5Lj^=&8-FpT@b&i|N-g$q#+G@3eS;p?|1RB)2 z_#+f&5^?=kr{2oJL5Et|=Lu`U+V7sjId7wmP+6;Pj?DX&i!$qrZ4#+KYB~SOGa@NE_qRi)nh$?4O8*fKXU*QPUQR~^z@U9; zAmC^Yr*eQ0mJXsTy+H{GompMw+(JoYyo$yV7_jD0)0Kb60O>d5-Gg6Gf(J@UmihZM zc>2_nLR`nLf?9sB68T|42X*wfk`VrE@zy?rK~-~F#07m`9Oe%>HhWgl0v}(|MQoH$ z%d-FFgkTnu@`sWB%G4J3>RK*-eSgo~ADwF?#jE5+8sjFJViNOIgP%X;L5?OISvsau zg1?XJ5>|gffP6!-+=kNfB0An(MUThuDPNYj@PeKauvQlqkI_#8A0180$zoQIiKOF?RAlH01+sNuta3^uDmIGGDUtb)} zuXp|Sn+>A}vOz+a00);uIiPnG*6!CWbymc4N3nn1Axf>rqTUZ_0tAw{dR*mV(@5~c zuTT&YqX?xW4X5qP+&H9H#MhXVQ^*ic6T-qn!LE07L9FBt2l<#Ppi*o1@efIb@LMvkAQhTtI2^|D6R4!>A;>X$~y-K`e9)H=S2;6HSL z^Sm9VT~Mn_EFm|~E0&#Fk#GU?IYs2t->VnmVr+~8odeZ{q#TD}oPXp!j2H*=S%Hww zgyZmt(Kwn@wT?W`ONQdd?*Sru0%T-&7%zVmbYP6LZ4i}IUyQ@bwD^QP&j75;psQuf z!$FA}OI)yh90iEuWAu)w2;sP*YWw?vDwQhrvdH3d9Ziw;aV#HU!k$asOqsG9vD;vY zZM)Bc?(=EUuE87Ajisdqx zBFo%fQXo0}_XOWfLoQ7F30RMps!q{x)s*I{>h&;u-7)!ip$J1yCByQsr}f?N(!}G7 ziYLLj`a}%HNfZbjxLaTe!uxw+b(k$F5EIbW3Lh{9xHvCUIonfIH+ED#JNti!ni6*+ z6QM?tjlhzE=-Dr+)w}&Gf%4t5$7+EHW;qu9^POWi*4btOZ++iQjR{Z`k_M7l9&vXy zd>S%-ylGyxRJ~W!UrQidI;qy`(lj><+v?3ltO8ts#vTnFUOsL#NKji_A7fgKs+?h4 zO@{}}Bq$2xtQTjDA-{E2K!|?{mGP5vn;M6er!>CeCta_XYh46;$c#5RRM3XS)WVj=Vo!>qBbe@5=q+RRA+%5K3HwLuliYyjBLB77^3I-zhKyap#-Ofg z_gT%$7l>@`myt%kN6kH43Vrt7;`LP~j~l1!%wJOV6r`g)eH;V5Pc(ncX=$_MzRdMz zAD$4p$L;$yq<_P>6o)(e?Yec>t35SJnJA|^!JMaQFgnbnxvcPv52$012QSfvdr;f+teJ|#QT7B$ed zJwc2+Y~^~VG_>!1BgcPRq-MB}7+zK>{9?0wCF&ukATE*fmhUl!AW9JE`?vjVdew&o zgjRt4icIF^U*Bk~r$g|s6j$&;KfjfekmUrJ!_c%wLL*+&giBNZ;$i|#6$Qicu!sdD zug*nyAOY%^pQV7XV!2{_Okr!p!qRo2q(#Z$J!I}^$S?Q{Tq1vMg6;tk%P(5Fwj!|V z`Vb!s;U3Wwx~zDzNa9q)TjJnaWeZQ zY*Ij6VeMTp{r+-}wtSpQhs2M&#yIy<<+Ey<0@=AAQP$@^LMw^Cu<1Df3Sz=#0ma5q ziZa^!NwGENpn%f;RR}kq;%;4oq$5oPx=a z*u9AbRIhH)Gnsoeo**mU!@*XfC!itWznEK`M9|5UXIeE7cwPNUolw1=czIh!xbeN_ zJygZ)q{B-?3+zvDO0>;)1s+4}hKAZ4o2=HV?M_tR(J+6dvWn#;M1$j{kEW`aFCd;< z;-}s2ng#hWlc`@WAgHvW`aRkR(wS-;^}Kp3Gymu#s`Suo>+;aBqBBO7L-trn>6BN0 z?&=72m9ato=QKoM@3XB%HYktFpbK8EsuF=Kd9vjMsnIrVo!SLt?|lW~Zw8#j58!2%DUvVp!f9GGNC)5z9? zklf$lrUl=9E1v$wx})FHVnR;N4~iMzkh;A!it!^*Y$lPkog~yLp=F%g4BT@m#@*Im zc_*k}Z$KT;W5AP#Wh}#n@9q zZSQ|p&at}wraq|i!pQ>7toV<$2gq*k4$$CX&cQUg z@OH4_Ff+_G%_cNvEaY{U%p=~`DR?${!bSiO=B68;a z8F@_rvHL2m{Fv2Fucu@H&4$8-peIy@h`9&Ze%AqX$A!0wwsLNEHAeo`|u-Sgg7k9TLTzb07N~;8dDN9q4LFSdAW<@SJb5nm75}a9i z`jwUWe%pE-IT$*SeNz|~l&s2t+;7OdiHeZ9=zqx*+9^=c`<)}rRs7ZEgd`g3$Ao@2 z%`J~#bmNoC3NY7Lu-0ItFUz?QB1R1q21VHQYdJ{URL?Jt#+54e-$OhWGxD8X(bIA! z;i-0i-{rZ!%1lYMmoo?htHytQ-TD~2Oxl{>dcIo8XJI;NS08ufZIxwnStcsmKnt&b zJ}-&NC;Hu=(44vwuN)4|Bbn0T%-SmXUfUnNAG>y6U#OI>jaVL}mTW#WLp>v2X01~l zyMEc1eR=q2dj%DM{~Yu-IIuLVWMGIKHY5YPM930PUfW&_DZa;$n-+gKg=KG^(QYoC z4b#v=2M_~@n%`H_Z^UN!l5S0f+DEN_>NVTI9b5v_q@~tuj=QbxkTWRDD#gf7RS6YE z_%(t7dm6wy@I$`u>h=$Oknh36BN_f$I0b$&#gy$vY^_41bR4xSNh3B>Y2&=Xz;Bar zE(Uxn%(o3}&a&L{m7;&S;#L5W;XT*3YBe{>ypwH6%;E>@r@aCnkr`?c?ofyu3NfC4+J9lv~my~6T zT*iEFQd?4afEPSQJ#R=y2|p9ZgU&&IV>}yLIjT`hO}AcjNhVVU+q=$0KlDyCg#&jvS@~ky~h@5KkN$FLd~h}-=foM=)&And`*7?xrklzE~3&k82adc>Ic3< zw)}I+@0y9A+$?|UL{^g@MqA0_y%Lc}P+l-m5kxB6nXykH#9f0A`cm~07rtAEp{umr zpX^siykcC3gQSc$U{&HB@+N>}yj1C>h2j!3Um*VZ=~eL0WX7Epg4h(thcKSn3|eOc(rz}~`+(u)dT9C;_QHyJ5Knvn8xt&n$W?dsDT(k7#) za)rJ^2{$Pd%MT8>e4fs(U{YVICd4fYtTb<ncvy_j zyJ~-69|5F}%O8P^@tY2hqas@cos#^k=m>`7@7>^an)(HO2BW)DUm^|NUjJgVe`GM9 znf>?A*AVr5_MFu;KtL=)Nn5j>o28IU;~p~}%QhP)UlU9joZEe^BA6!8=&MXe9B8w7 z3UCTNHz?A&-6wS`2vX07ZJohN$a?t3ymo)>7lAL8?DK1$%v`kQl`c2$oSE%7h0H)? zM`!R7>HBU%4v5xn9)3z1r$g69lb%;F2UplYLcSXVUPwpa-N0ad#<%;09GTsoYejU=={p(rjU z!MdT&Mhlz`H_KGvr23892sPTy3vm0?<(xtZDzpYDdR$EP+NN{L{84Ku3$1o}MlRdce2Jc8tc9Klg{jBpc z?>uHuU`&bmjxV?}?mj;7gz6t!NVW{aF^u!GSx*=s{^_w07JT)hvWx5rXXYNX;Bmui z%OjHa`(mduYn^3MFa-h<(@K9`bu(FfH9CiU@eDw}2Oj$ltQ%7wv|UGQQ1vM@k1pvE zV7j4j2vzDbd5WpVM+dGlp#s)T%Nvm^f8!zOLgXX@bAMK#!c34iyfC0&+Rv(R5N1RA zL*$7zK0D_QjD>^4&W)F*Sw=0V9QA?bWb-YA={C@zQ@|yt7c|r5CWC*K4Qy)E>^2NW zdNqZ5G-w3iaB6QTos^v|XfatmziV-)5BqR!lCD+YgRXxjO;uv z;0O%xQ}l27EiH^T*uj3fucG{Hg?B`=>OXANS`O{bRFEj}Yyn~X+l#IW?H$7dQVl-* zrjpRyI57dUDynKs<86Go+Z*SkayxyF*=$be>C;@o9jT-9p8bLCo!X#je8l=r=eu~I z*x?uWPR|7>enWry$eLP+YDTYTOFoG<=HX?G$9Aj_Q+s8g0=J6%f)N>n)s3yNFRnPu zl#49w(noysCtNha>J6Y`_aT3p-*U_FC0-v=AY%QXNXc7(X3Aa38-1l4M;SY0{{TZk zyuTw;4Wk=EThnUL8qtr*1azYHrGE$w(7-=G0BoZI zHu>w{*i+OIOwU7q-DTJIVL7A}EUhYedk);u?IRRbtHoMT>{96`4CZOF!TIB^VDY-g zx7i27pg^~K3($?Foc{dr^%Vj|0OBJB_LL&J_91P;^~J!V6tFt(LZ4vF7t~|KE=n2* z@qXDv-g}jbJ$(Xyj56arxNo3fwS*oHvR;828^P+k&y^9^{&QZP27R0sMLlqAML5)z z>$!b;DA&Mah!5Y1fXm5A`D*Zi<}~MnR0pZ@_7YXC)=oyTb}1x=NOIl&t)WgnbqXpb z%uM~(VpHckf!u7H=bVRx)$*dpYe4i>2^6FA{DD1s*Z5k0!WD{7M9hrQO8C~W`*-Ek zk?_d_AK%8}Ck@8eP(I}&f-UkFyPjZLnD?aA9n*_#vSH1s~)GK8=*dCl( zS2>_dm~TI8v`u!t_=#G#iZ7wN1e^n%J4{G*P?}~cS_e_U6wmJ;Uc=f#E9{k5kQ7#o zUGY+Lg~2_4FI*N#H;$0R7vo>b3P5IYb>Y|K{D?lzH3ergCAX5o0Ko^M3bB7)lHrwq}y}e1n|uVtvqiuC;@UYq657$|p0pDrwKflZTXPTFofIFOB>_Cl7>$)zf7VfDhBG*) zsb6=0fR)Nkr7gsc0@SP!3b%naSc3u?d8!TED@SBdN2B5dJ9~-}WzIusGg{3@r-GQ^ zwM#nP1880}B<}cd7`Q_1vLTXIVl=2?Eeem(!xJr(nq%j9&m~f3N2%AZ%4ql%n#9P4-cMWuh6d-cwLJ?=GpEUUug@iw{BX@#;fOPo!#;Tg-c zkLijj7JqR*#+RY?F0PqKvQ4Yy2w1xp>cHtDYm{2mCv2W>3}L)T_E-jqlhFaOWeOaX zUgcdQF953qj5pz(nDWr9;Ln7yPkA>^Gmf5Xy{%haaiW;q1pHXvm)D#_NjFNm2Kmr` zbwPI#C}HpICyFPP2+4#no-5H{ho1|2ihW-u%5`W(ZHD&Fo9g4^6hi%LdZqh13{sOs zS!W#sgOZpyiYA#S8bl!iL9arkN)z%V3h_wwh^tl9-!O7TC4LI!`LVvg_BZ@79y{M6 z!&y8Pf}aho zrTm^5J3M2g6drP1r<)I-apKKu3lTT;BSo>3lcbGSNTpcP_*-p#dKI89q97iB2>4b) zp;^eRDM*Nk1);8Y-Dsy6WaZM>X$ez((E(GChtu0LQtz$^{bi&o!~ne*!U>5KLWK9(@m3trq@UOw$GTW%-Xpah{r<)x3|uUvl02IXFvBB?Uox!F*t z435bJf{)G_4^Xb6Cs-%@5wFtEi55^Lzn;UpuD56x__lClKestN<$hs*M%TtY&~4Ju zS#N2*=tYihT?+|@U|=V6gC7xpY^uxGG~n6|;}Tr@shjWFL8lB~7Vs;0Mr=H%hldx@ z?e?0yQ(d@{E)ib{CE$!f4YVZ2MWc$(8|B@6Ax_3<71Q7qN_(d?+zkL+4PBcNsI6~Z z+yHqEfTfa{*4GX9f`*}g*@fajDmEs~*`!()NnvO>iz<+Lb`P_*Mq||xr=OJZN|PFp zweqS2|6Xzt;HKmtp3?jhJ4`u(zP#`?! z5qPd*pn?YwMPIl^l#zA|{1Ut^+lGtc)785^Y*JJplT_R%(-dgbf_?jRX&e3GQpo2! zN4Q3JXBhWG-cn3UifZ8X9qx_bIwi%=bg)G^KiNygC@Ot#SU1L-lwIc(w6zfNwN}jo zn++ekgg|&5P2Qq^PVz*iWftBl>9%l5mJeL`Xo&5MhTpl(Yo%UZ^PQ2LP~oJ36*}eolXI$ECDvrXo+Foal{gTW-Et0&fSLF0*zhFXN<

(C5tlzM9DM1x~4;*Xx!Pgr!axGe%X5fQ+ z(FM>;UFw%Fe5Pwh{nQKD$fHf+3|89T)}fFs%(NPh`oZZoe+-a}Tp#w3*p1yuKYcO% z$}-M!$&J;20mz#JmB~`-rt0Tqz~N_lw0G>d5NA=_zfctcJxE_g`Yt4=f-&X-tV`wk z>u1@p#>-3`c3X4cbkSKyf6%0T`{Qu1{$G;Een8Lxi%DGAKM_1AlXasyZtMfXd*t@m1RDlg7qCcj#i* zJE$el9=FM*8sZnm>ufvPZmpa04Wm1Y?8Ua`gMmsv`9Wu(Ebmvu# zRGJ)s4@a-+@}3nFK$|MvZVdaNJu88zmq@Y2;&>>~dwqI1W3u~i^4pO1yA|YqS`N87 zd9BRX-S?IPlB_gz8K3eAil}7=rTiqloXHog;qRx>ujsnb( zh<CbUD9vGFf`9ZSb^A z98!ROreOr!k8RS`1qnuf!s@YjPgw`s1_qTP9Xq@qvIS?J`o{9Lm87dgCev7=DV3LQ_d`hOsXl z4Y^-@vsx+I+FGzO02mR$+ey+R5?jBkxNfZ0qGrapqK?X%r*9{xC|!krzHGVEG6GN; zuB|YX0vrIx@LG@f9jx!R{rt6mPH^&S!qRFoS^zeRo1O|@X;62-WNW2+&N2Mn#A21E^bS@~|kA5EGRrN@J8mA_3n8Y}a2+x<- zyZkvOsqz*|uGk|FR6?nSd5|19SPgqjdCYmsW|U42Ouq{0enMqMUJhR4+6XSm7K9{X zGwFhG+*d@!n5&oK>0=Ck{k_51O0%&Q_vI9T@IyhsF-=cvz=2^4u(eW%T)YSTtN{_& z=H;|wFB1d)GdqyN7n@#t1KJW(V@JdxkDkh~h5-W~j(vwXR$<70y5pidKyYQyzYuzE zo0HpsGy7THDO10++UZ2$g5Rr4Of@e2h!8Dn@wm;J2s|66gGsc6H!R%h5;3NY3Fo~F z=|aEru!xnl&$$}yuV?rsxh04Nc1q!}r-?ZTqXY5rwShV+urB!Rb6^cOlI=jPY;>WC zHKKvet?ftQarMD}4pUt8vkCKj7o>N;^&`8X4`R7F9;v(9f_<>lE z(~_JsBJIdRS#EBBiR+%w;Gdo2XTTSsB1Ycm>G zbgXamJO7%0FO$y#*Y$7#lH*GD&UVp33@UBi8Nle_JvmU#7x^r`FiI7*f01Ct7Z8zQ z!heG`oI;ut!vcNxfG8m6hTP%#&_!Il!*JDcv11&pw|J$GCmDwgOO3fX)=r}=QnR{p z=gOD|P+kQk=aod*WDeLqEgF)~F_c=!DIH*&>y}-Appz>L8bEzocPB9TF*cQbm3I17 z7W@Wrk$On=eHXqy%>BBNIQ&qBgYG&ik}~6w+QB`>NE4}r|Or&I6JbkT5y(fyn#SgFetBUuW6tC&^2)hg~N3g$H8u5OR<}Jg=$SL zZ}p6S?|E5OpQ!*Yb0+u3)Oz!gG;fk1EY)Mea;Z0`#lGT*iriGaRV0kt^(3v%7 z&QTIS1Os&O8tPK-59XGD&ae6VlRe*NaWwp+O=;d5b$iGjQN} z_EyU>CeQFfLp$HfKpZFpJog2b6G8Oa1^~i;YHRX*4TVzpZRKT3jqspkY!g~tk1T6p$Rd_8=o(`D$|<2JMrnoTtx*wx)r;)4U)>WO#Qz0={* zXM;fK{(#VL{~%sTBv>i6@l!(mR_jml<#Iq0;U7&_@_IFJoI3pv4l1;RMMhxc0V5`u z8r6s9Dq5KmK))RyAEG2HE4r<9(5y9oiJB991|2;|GRR7-H5Qb?sdP;HJQ7^8A_7cD zre->iul5C^_ShF)TPg=k*^Nf(2C+5bDd-!{FT9o|RX0*o>X|on+_2G)WPPZ_o5$sf zJb|!Wy7b2Bbx>V4qU09gz-NBQRKLY05mc?g_}`1OzGUkA+U{3~uNrf(Z&cKO-2DS# zq84oiE}&gvw|XIc)hG?@qyy==R$Qy+L8e|jX$~*oQ**c2(*U2LWRqr;y2N6or#uC< zuM_2N$u|?@EjyhGl51hQc!i<00sMOoBfGQ|r7vZAVe_N#*qp!u`pkwAesqUH(a9Ep z74GE8Ys=qfo+Y0b>oNl2!KYP!teSk_mti;R)9FD@iQCs;tv<2XV2wQ>0LX?UBv_czQnu! z;tk3XF=P!wo=dl*?{_*tSP3>X2bWydmNI^fPImFAEWOc;J12|iFyx&MEQp#_HZo&7V89a=m z=smhJJwo;pq#w>PXpsmUW*x7@=JQREiyEz>Le_NClBq4DsWQ#9vip_o)mk8v zPU&@d5`$W?2J#fX@kete3zwhr=SSh&c1T*@Jx2MWkP`B}m#FuD#njh?LB!cHcA4R zjA9{`BCTu5a0kbH>(nNR?WtUblPGy<;x@uN3E^e~Gwt)425sM8FHccl%~zSi%J@>E zJNN*sC*LbTalMav&72x zW`=40n*^y`!gf@un8MMp5NUi=&4+9RfkCwjqfO?A#_rQh4n1%&A{s)DE+`rKdaTF)@|*;`JzL74O_l)G-i(GjW4CJ%ppvI<2g#EVb#RwNLsT+_m){ zi#&!JVwKE)ck#3}oFxf29#9W>Zm%tYQWz6N$o>c#`q*z!H-la%exsRl7J0U7l%hJp zLY$f)p5In&jb`I8rl*8M1K7op0yfS|5T;3d_Jo-&B6&qcs9A_@Tn*yMMXY?v8@RSb z$V#jUYYXW0WMT>)iMnyW=A3U#tq?Oat1V%uEpI`87grksJo65v39TA>y8Kn+&S#0Q z@6_dbbBM=qX~oGdDD*#Czn0!Iz2_aUMfZw`v0;=cHjoEAUmUud%13VhsO|G*HG|hs zHB8K27Sbj`fJVLj&!yr1rK4`iu(yv!E}p+Q%X%ZdlU7{=`Kuc9Hk!p5T~8OCPp)zIltHVK`ZO1!J8S)<@g0 z=zFxg?X(#$w%9VZzOJHMEI4!~hjC#+YbjBG`ZmM4Tm&@b`@8S=MDM_C#Ur`(O50ex z(QcFD;r`Gy(B<&o+d++pCPwe1*>^cQFZexBgRFCaQ87f>hXX(H*ej(BVTgf|myho| znz7fj0%Y4leGq$4Y6!{-qr}p3J`I=56;&|!ogDKNdWwHp&5$>wS8gRKp8D&{Ux@pE z@e2#_B!F>Ohsot}zEFsF#rZvJsC{)w-);7e3pcj>>}3A-8t|6$w{o)ZbkLiDj$eLh zk!7OXWI$>pBsWv>v(3sWFl_N!-Wc=!rYh~a>MDOg?;zCDcd>WwnC+l^TpY+mBTMar z^a#aR61=z6qCv`c>*%R3dm={nGJ&;!(xn7)f88Hr659d2Nj{=UW(R=UI=IN4(P2Qc zzog3SZ|kM|Jzn(#rmv#Ooe=WM$KiCH__}4^DNmgE{kcz&$y!=W4z*BI;lO~>&b$_J z;^9cWHNJ$N`bP>qxO}^*% z)$g+8(6{WRm&Nub^%{ha(F zYmp}qBCMRdm1BjTcq%^=FqW0KX$*DIJVWY4=M&^I+v!k|IZ7Ucp< z0JwAG2tm0?bE%l_q2c?y#Zq^4WRy-CK~<$Jmm)&)TA?VI{gkeqQ!OJglr`hP`*+{q zE2S(3KFB?=h;N^Hi?3n=LPkw{neZE@SCAygH&MVv$HH^ir>Z9bS+09bMB>8^>=E<< zp6FEibzx_(Q)9Pm=*^#h{WtUQLsgs!wrEakgIdnA`w<@yPU75~un~aeLfnSP(kNpd_f=~w7i(l#E*xMp?A9x1gROrqrN!cwa1-8d4v2{yzmQ3>S9&i4SZ@al0` zBUocL_=@glK@bMBNuIJ%Z)SFf?rR^Y6p%m?J}<`8Mr^gc7rJ79_du$+Oo9K_+4L0K z6x|swR$?+)WqC3~|0uT4m3xa@{8X;Psm`-70f12Vh&k@(1 z^H4_1I^yQ+{!nHipU(NCr64`B{1-ZM%0-mhF*H(%bp6}fm&Xpd?jcpeosNi)yTx-< zXpVf=>QzCept8_^vp|>rv;tfrG>K*pj`B>56ILriotV#SIsWzm2A|CZpP}MgUraVN_<``EZXxzo7;+-bfzoosW2bl_yp>`nkyulS-MubNsKS z7%0m;Gj6%a1^o%IfB9-M`Or?~I;nwLDDeDZv=H{+LG2XOP&`!uk>OH|WfRP<&m}nL zTwc3rU0sIw=|{ZuOoHYo?Ukk7Wv>qZB#Sxim;s{r&ZAtCR80(;i0Wdhl}1Id@49)< zw2#-62qwgTBDt7mh8LP2!EcyCYD-d{)^{nyb35Y)XZfKYw#kN^`Mu1%mhn2tLS5o^ z4@8HxDCnFR*B;UqI@m4FCH0G-ra&&6e8vPAKk_XDRNiFf3nr-7$yfj3$umv}RnI~J zAN0a#l+K|Zpag_(VzfMBG$wQ|z6KEZ{()sOzshWX^|UZh$~t_?IFDhnp(v97Zu`mu zP<}1J0mw`$%hmH6gK5sXip6-!jGVyCZFuW{)M~>ShF(Kgt+R*7P7Uv9I0Pen%v>m@ z-2g8OT(HRUz?2qMgV4-V>)TG;sitHsp(-^6>uetIhfUWY2Wxzi3X-}I)dFMHtc!gj8&f<-g$ z(P<3Z){p#s9PIbE=hJ;1qVVh*Zggeu6MQg#n{L#pcZW`V7Kr_XP5zI!5r>+;d|2L= z^VYAIoxO!mHCt-^);8sKxA{bhvL#c>}*nppuSLSsiNch)_8Fc-asYejY;seMN3j3{k|;0*tV*U zcF_Za9c&E@b(p~iC&MTVtGa^t5yO3dAe^_Oa`a$?+Q=mjPMwXTg`I$YX9px+@W`L` zranoFDsWTW;TuJj=tUY?puOc@Q0pui)dSnSw2Q8Ki}$QhJ-SrvH)~|&3f!XuNl*w! zeLP+4l4(_HAVX~YO?)$ECeZC4jcWavTl=B$<;jFs%BM|`So|}Esb2)Q%2Str6h83r zp|%A>ecadup&xb$TLy*P!eiMcmh?-!e^U4cG$9|;RzQZYtEo`uIX~xXC(~kAKiM-o z)G((oVmjkgFFRGB@6g6LBHf=VdmZ@>LkFC(_eZ4(l=pLSbc!yohc8?3p0ztS&ECP$jDh#bL@N;ToxR`uAi->3v4_y2dREh!MGC;koFXvv(}Z>-PN`I zWpo$?x9?MiPb$tHheepR#bJ~ACTL^+hHc2%7O zRL>A81giDc;-;3h_%%NrV_O(IU}_J3lL+4{sZp-4=E%y^M8Hsg0xnwJ2Wp}$6s6Y* zgj4-KQz%4FV;8mh#)v5835n#|2=7jkxn-My`<=z|XwT)0aW5G+J{|C=5^Vc%keajj zt96sE&7V#)IN2=ZD~{uZ2R1|wCs4|Bn{@#n{NUGYy)T`D*|1oO~j>Rxb(WbL$j zaO3SYF%uThIH+rX*-(2*&R<_(l};>3&h#7PHSN5V>!F9rh{v(DE-Nz)kCPE|GH}xB z{w4`6KYTo{_|j^jeR`H(^ei=7e>f#a<9R|^cwB_|ng7HG6)htW{+(;kC6@YbMvjgh5OY!%aUpp zPd*sMeID9^5y>nHk^TGXDMZjd6gJ$`xat6%YE9Jx<8L{SfE1JI^EzoZP6oK2ACR_R zO%@)xJWYQ)_f`E>RzA&`x3TiI((_Lehaux7+u!TJ|JL5;%>I!W(-eat(3UzDWR5yq z>KAzy7%8@JWm%3S<5!zy7W$R5e`}sNzM)OwwW_CWC{pw2qhRqrIAQ+ zvi2_$fM7PfUmxD9m@+J>3d2!yo-E^(1;jiLvh{Y~+Qtd~EWha3NAcXMUo*T%nH(d( zxbrQ=pJve*1=1DyRz1H?;DeDDYkIcOs_`P6w$uH8CYdz^xOqcDGM(zCBNf^1PNgDY zmHjQ@KPyIuP{^5u_C^a2aXiCbsnNFi)BNg=MnqQseJTiBj_(HYwqKpkm7@-Wm?KFl z*p&*hd%+*U6#S7t2y1MBVq;JKsoHL-MvTvNs6^z+ynSQ8`y7EbP-!845OR)+V532+ zF_V6O0PqKgnNFcUGf+7bB1 zoaD`1qABkq7{;+c)9SV-)Dyklk+NYO&x_R))0F#TNur+w89()+fi z4D0>l=8G71>(fKK1G0d0ozU%0xj1@ayr9Y((%7pN1;>1U14xE;+M>eRaKQhqOry2>EJq;0$+?6%j} zvtenZ5B_W2^ujwFV!Ty>LX-^Q9WntF)g30Ws>SO)0Q}G=e9+8@fgDnOAI1KE5OjL7 zMk)^F?&1u@FUQJS#~DgsjjTZ9oV4&&ueIe*42TA82&-6_B7z@Qlzt%ygF(t#`H#lj zUg1`Sh|F`fNSeIG(<wShU9!-X$5C0$-uMVd`*r#V4 z&b988upuC_SjWA$mtZ=Zs&<~X*5k;1&e_>KbA7fl8Uq7!)ANO-MR|!f z*EO^f2NFSsE|!WM2ECLbR@+RG#-_@wpZfdb+RCUE5M8Ebu8Ou8`vsiLFMah!T~s%U~rNOQ5aVtSTx z0OXsKa&@OF$fOcv+r_bIN(MyC7Cp%;_EZmfPmqb=+!{Y}eMj1mq8sy7LuC9b!uny+ zgSPS?z+iG0$WK&{!4ZCcB}b(2TYt6DV%QB}loL3qVQLJ4Wq0DGfSvf!<%)BM!KUR> ze!zM7+Y5&MVIAD`DZi72%&6Oy#2do=FehI~N4SXR-whGsYXoU*pApd1Txf6ljs)IXT-- zxko62h;p-wtQ`UCdt8PsBOO!`fI2BigLFjYaOOy8c3CEj&wd4 zCl8Y`3n%Lp+pUP(&3}8IazKwQdbH)620k2LCJgrQYNk~Hj?rahPl>EaX}Swi!$OXL zhGShBQ~6fZf>AAh)sJH44;f~FLhX0#Q%#X=Uyl>VKOHi#gw~andyoICo+AdE5*{K9 zS7!J)2>Z=gtOME}LOvdZf}B%0hQ53*m{(EDYBYBW>`DA;KW{0RWn-n#_a96AT2!b)nFnLN;c0{cDgERcr{GMg%Q#2gkY zjhTI^PF~}B?<$0Uj9o8&e!I7T_mPWOV<08zs)vVChvnyr?W`|NeuOB z5>FQH(LC}BYX#VF+C~EC+|p#x6~0irqeGD%&p>YIe*QcHy<-L$s@S8SeGVo+aiZ*E zuBd?C?5xgz#V5aVj^pim2?*mG(2M9(I7FGy!6{(g7qVY}Eq>cM;FaN&>TMF^F8D^131<Etf^&4{50?$q8+wBWR zIY;<^Va|7NY*qZur7v=>ZD`87RkZfBU>4+LdD6WP0737Kk1deYhznn1+O(?#6KJ}30FA&xs zkJV{kGfv5)SM1;yb*SAkQ}bQG`TnTRisqxX9lK38}i zImA31|5k3i37O~dHP|pHzes`*RcyeKo@c2yz0VW)N@x+!*;X1y3f82Kc^Wob~9(R@twpR^KdjC6=Bd59O zvZumlfzwFmK?1yW4L{;e2YlB$xevJ*VNc_@Ao``h90Nu3z7;)7j*S}`>Gaowg9a=- zi&Z%2fUliBWyT;K3_A;>p>nx@gZ2fd(UD8PI2T7FCn}w28e;#LIfiapt zIOq2Fv^gh?+;(z+e<*QCYVr~=Qu}zg?i+tvz736sk@S44`3=2cDkKYkUwPW6)wq*K zz!b!L8M8)G{%n$4O#7t}ert<;@UWbd-%a1DQB>p#2ZgYGq{uhPiq0bq%qB5im|hJL z9z@eGNjoP&SdH5S10nprZ6kc*VGI!G_5E+6T4Ei#CAC#Mn-g9bs>AOZER3_5^rYco zyA0svwakZGmI^y`*7Q4n{V8Esg9>ETOUsM^y?#Bz>Ix^EGOab{mLIz@#1@7tfsHQV zk72)WY<9Z3xlT~~>n(GnY2%B`z^y`FP)pDHeS{5?I>+7#+b_ApuUw~seN6BLj6NCzGl&QLe!+#m8CZV{F*T3 zwjURGUwE!G0}Pp`$vS9h%K!;L_P=Bk>BVe}RYPQsjaV2binQFq=oR4V_f9Z13?=gG z&o4%6wU*uKnld|oh)OHq7kNl;-__}F3Jt7RbfCCLSDm`?&XriV_88%|KWy)z>GkPn z2S@}3*%*8`X;{B0wV@~Qxj>s-pm}hqa0edcb<$s%rZ#A5atGj+V&;70>N0Ab$I{ao z%^?u0&?7Scq$3+C^tjyuh0G|0tOxPnp&)Se`A$HD_pkPUY~?fc)v>)?ERt&assPSE zS!LX$hYtzrjXj6#-R(+WBsIEK?L0Ja;*W~POpM6Z+xwAZ1}k5P`3=*T*1H6I91^RF z_B6N7i(k}HiVhoXP7@w)2wL2J!?4j0-H%Szs}11kTo`u$F`4B%)B0jU)TlvjN8nr{ zFP^wb*ceoQReiOkDw2?Ms%ZCHFw1|8Z@mEMGA0{?Y%ktzX5yxRTc*MBDLoi>vWj^) z_W2Y{7fvy}#f$!cPNq+YPxf~0yrB9tqj$#O@5D=6AvN&~&V-A+q+ReW6q!GJhi%#Q z+ixUp=yw?{0&fO4Qc*w`K%vE;+KUQ*oV#O=Zd>bb?Tf<#8|3EqBglxe z?`QP|-H>lqXI9Y5H-0h2BhkmYtPpjayU=O0^%&Od;fFH2$Jl@Gm?EPv-YEhZ1sdSX zC6e?Z;)z=w?vyunz2jQYa_zUoOf1%UzYJleinua$Ou}yJ5JABqxE4kI6g2(1@OlWK zp#bE68Mg2#C%QXwVlIB7HX_VH>&s^5xv%!}#_Sl%zw`Jq(7&<*jMha$18j;an$j+rW1pY412|YxzL2Lw7nyRLM}Br-ka^;y34BBiZ9tm zJILP!-xoE7eZEzHed6HUmhyFps{AB%3*FItTwP-5H#7#{X;`!dn2mg^XeXP~&mfxd zH(NE?`Ps>7W+jc#2sm6AvjynV+0uX?oKIknJ)x^9;zFz;Cp(jjK4M=!v3mm8o4fFT zy^!C*#KgyGNKC^fA6+#jbb6E2$L~EKpO&D#C{cW;n~v zU8Im#{3G8x9F0hq-xX(@$=ck5%zkBRG|#K9B(8j8mWL_A+Cn-=j$8a1VRB?cihv1? zANCi1GGB9kEO)H9NnPotCsIMF6MAibFXK&fz`YFW+pQLHF=&s_M)41BO!RZnOI-Ql zw)AMekmi#3a7hs44zE@h4oiD@5gtf~SSk)!_!umUVvOk|QM-O^Mb)?JK55(Dh_F9o zCvF|Z2Cw!{`J?!oE1Tdkz#~gz>%4l0$NhBF=%&9-niQ(bEpeCpc_(z}0^&!1Y3rXZ z^2qA!oM;koqmjO;Uuo51{#s&kT_}sAB&M`AEXL;Y@3*z}U6xBLxhr$c^7ZT|Nr7)V z4!G&a9+IdIkA;Q~+0nw$%_Gkat)L#&+)v%iZctQdiUE2uBo=Wl_e#G2cgZH?rh0Oo z;|TURwL!2wroTZA4;>_KJYt`Ja-p7#4%WP3X=^LslupWT0I(=+A0rq(C=s46jy|Kw zVxO3Zruu1uQi5E>D*^P-8tQwIAM4E7PY+<@V`P04P<$1h75e!4;2o5wO2cgE${Px4 zE+Sq`nHNRcUz?s~eYd9Spntz}>n@3QM2#$poC-L1Ye_&$l|51y?FQk0W{BVr0IlX|U6Pnf)>)jJb6hP_J@ z$ECijBdYxB&2Um7K}ZvS=A6`{0FX#gb5@*IUtL>FpPXRQhY5hp1`Vw}(SZgf-?mLmhZJP1y{XVa;KWd zUFDr+D#M6@$3>HUj)o~-K6Z_=9b-${PIHYI(l}mI^fX*mWa$fk9?_H{~SCCbqc#&Yk|W7)@L=@Ub>CKpg}Z+UX3ahk}u znh2IrF-EyVTM^!W88<6^9<9=};s63+v#v6g<&&Zlnz43b*^?A5#de5BedZl1LvA31 zX{mrgIt-_0)aF^XY#iu(J| zXEtnK42MmN=|(-LsNxF}-z&p6)Z?_@Xt9+*~%&O1w*Xth3WL@#w~wq4gx>4K%Ytz7W~ zlE3FTOox8o+p!o8Uemvj1MP60_5cynuSh1Jj=r5$qG;ijv%xQ)t&mbIhRNAh6qzlq zx#E1CrbR7(9rM>>4v58uV>oC-xXrujF(y258JDEG z)>G}iU}8Ujvbcu4{Pe-8{Cbr3@&D&LlpGMDS4h;buAl;ejF9|mZj91sLV9p~l$Cfr z?3p(^a?gxswgapA;AVG)T5DgC#0-O>S#R?rzXQ*IVdBYAxCBbvKFL*eX=l4ox~7u0 z{#%d5?$`lmUlW+M&pVfVn4nfZak!@eLZk%<$JF>H%7<>N4D}10I$AaC$qdi$19rjD z#7!#j(@G~eb*Q#WNDuD;A*7dx;h$f%yLTyctxSXWBW@Y7K(ac1y7=>3#7VJDz{w7h z5tiP6b}JVjc*~sSA4FZ|jj|yNp|N3%46FQC9svQuXH9jEY zFh{Ek(PazTA}$AJ)em(1d^?Mh%OGANIIqc<>Ha6$>t=Hdum_AVKJ z{|Qc*=1j2U68cnY-a{ZaSjk1FyjBg@c_$o+(Z_OrvWS6mEhi78Mh(j%Pm^h49(pVd zh9e~ITZ#h^xA4Y}MEx*f-jM~BH`4J14esO`EK!GUBt(mEi@tO(x5c{1D9ZLHwP>Wu zi!Rk@TO&Ucxnv#VJtR#@H#O59G~hLVLxLCZ*d)_FQ2iJ-l%4vy5T8BruSfwk!W*~_ z7mxU2PtG_TZ?#DSDq_VMEri}=pa)OHREnsvHAU$ke6x&iXb>s zj_&11U#cnem7%_)#2=4}5HF8^IiG&;FOYpcI2zHzS#ABf)$BdLao=VMf<~BtaSG0Qgse%oK&!4>UH_OUETY zMMQplciTzkb_-~(xFe^WjbBMdl!Vkoqg}UY3)LGPbCU3vM|LS@|4}@DZ(?#nTR|ZI znRK1$XP6Xz=Ik}73@peJ6+{l6?rz+s{H;^x!fBO~2gb>TIO9kCe79lNfF?0W{XOQ} zcV!p9_0|QHmdXPK-FA->QU;2mTf<941h+g!{X2rx5ssBfdZQCaxKPQ%6CNrjuX#C6 zvyIl2+(H{Ni3Gm_0@bR2-2fd!8s#Oc$|(n-RMd*6i0hgA4VzS~Id%95z5Iz}<`kic ziZ}Qw`$O;UI>LPMZJyNsE!A1yG*K`Mv$tdcpMoOt*x+rzr>)+@Ug$H!u&SLznKO;^ zw>;GBhgUJkPa0hqfk4>@QwPN0`y`_tu}2}wkyZ3 zhLPlcRS9W1P98eVB=>u6l{((CC6c3=+0#p(AN`d5qZ`voO>8JkLy)VxP>!#DlLx}| zgf*!)YLJugX>8vK`-+j`LUyL?&Sg~uLQcjH68{esR&|Kq_-(tv9F1tgHU*@vm`SEBM#mPAvAR6^B(JTpmdF zoJit|rNnc8tLZj|mH>VA%{J^P6-Kv;K>YLCrgnNr0DId>ExmoyQ$gsRM3mj#@}D0n z>KBLj$U?q{5kCg?m5I<6(BKv?VdIm(4U$gge$g~jGmhF}ZQW8 zJlf7H4tcS9;rBux`Gcs?eNGb_CR0E)W!^*rppSNcp!Z}?jc}hq5x&AB`A#c&yNsT; z+xsp#2l!RVHz6y=ONoY|jGMq1$|ISE8sjd{WZ5}}2^To!H*xw!G%>Ag^6bIqa8+G+ z#7wdDo1n&Qv?0|tUj!+!uZT=&np@c~$(azPez#~M=%c=Y_~4zY&rmt=zvJDD+R*Io z(qn>u4Nb)L@nmQ2K^!j2YGQsxQhWvZ>*E|_x%y1Y6RsiZ4+4%?wY>x%R8(?42d!8i zv@O3J8Cgqaq(TnKOH1XZ1?I;ukx_fDKkqpGLg|Ohh&P}Vkln(=$Ol+B^XXQbt{3#g zUAS#GmCTdi=M!E-35h}vpJu#2Plo*T^Cjnh%UOksGghgOZBnhz*HlWm4`JRRnl>M1 z3a=2{H@{g(PpAXXllD@Ntxw1h3DZl4xxVM^MO9n^U$V-#$JRe{WUK!Di32XzTq&E( z(zR>15Zjm8XI{1v5d%c5!xhW^+7MI z4~pYTaCZGoX&N=@NtV~{;*_7WO-p)BN#T@N>4<;+X(j&Wf@Jg8@xO6*PdVQNNy=maP5&9j}_W#J=0Z%1lV5HmkK0=YdQHO7bJ zRa5{(XG+1jVU|m)qE8Cs5qPAG4fB5wqR`$j9wK`HnRjd^L47=EyVY@q=H$G1k$r^U z$O@rmEGMuMTPwc%diu0Y%Whoi4spB@E1#Wo{cAdv8g$N5nA*V)d&GIKMUOXst3Yv{ zl;!HsiiEeb$CwEM%9t17V_fCdve}w&>+zLtMuhG7M@ps{#g}AwaS0ovnOn|{z+r)~ z2dNdW)DPb@XF`Av=%41!)+XmH|J$t~Qadk>^4fi|<=?Y}+M-d8z$mtvp>CGCQ-rdU ziG;!dLh#J#?CKs(UB)frt}o<&KCBNgj;jsGUerb#ubX#JX&wS5=L4T*WTYbA}k)Xjxy#i(E-6 zKaC#>X}2JM52*XTNva`mc4$90_wzBqust>*^EUr7Y&5Wue1FOZ!oKr=FZ~&x1Qio$ znabj0&pth()??xGK8wQEenXLM>;N-B%)bm=(W;CC<(xqJP_`wcU{q0 zuJ&S~TN%aDn3Xy{-Sho%u2^6WPE$CxzG}w^ZB@}&SuI80w+p&L-5q#VQg+ee1KK3_ zoc2ml*0TjgIurYHl-68WLpsG1f4Jj>_aaFL5%}Akk^d&c%r>{3i%E1bjiqDHg*fCp5&Cq^VwRAj<+XTV!Z}>?yEMB9`5`o4K8J*lGGc<=QAmfHj+KTn z5!txnNgj;OCI<}YjV~yJM_#HM5UUCNO4$7dUO529)1z$2MZ~>Ke@5rQDmw8%My_d8 zZ+2fo5y*ei$-LqI{%YOStOz}b^G`NZN^Qem(Ob38{v59tGR3roN+|~;#%KcXemL*M za%hH$TeV-eGw&N*2h!q2fH6Q&s*)`v?O&hT06I=XyB!>|%n0TBYn1N+%qV0sJ->E{ zksn^veNTqWQXqg*f60n!*)#HYNs2wu@YZUfW<(I@L9N|g(uBp?06Gj42g*c=pC7{t zdx_PaPr&+h0rcv2Oq))nHGfYZxB-IkrBjC75FyK$nfTGNiv28%!{&y@R3NEdW>9Gm zk}VR7HU;iPtuYT4s1v7x+8X+B$pbhPkrtrhp3x$YL86G~M{T1Jj%xsIc?UfX{AQ7yP#P zh4}!7=|ZrGEK2M(^`f9{QE7=p5t_v9q{9<4>yd^i`Lxk?y z^Z2P!e}JR{21xQMy~XJW7F;#d;?~zxu1T|GEO*{54|2*iso%71?SuxszCuz`ICF&G z&u7eHjUji>118-9!#Gb<_d`q$T1jg5<^x6@(=)DX_p0Oi<{R$Lzy9Lz@Ye3Q-bI=6~@HA#j8cclKTM$zp z1XRH(%NnaTsD3?x6FLMUj|k)&0Vr9=FKID3)G%2c3o<(}C_B9}$MW!K79*)dKBg<2 zzP-@!lx3fW#ozrOBNWg8pQw4{xz%Y{(}0-Oci-WHr$ZN!n>TzC@CNeZw6%Yzvn zf9mjecx2yR^;+KrXR*wDifbvl4^%YoO79o2Iy~ApEv1Jn@76*C8!Hf;1icT?`wVV( z3TeNqhxof2L{(Em9UwW_Xc8*^J?h~H`i48XNP1Ln^`eUL%C*S1hG$hV+V}$7=g;Tz*8p|Po;$W9>O3o~{kQRLwAf35bRa)eVtr^}01!D72r_<4vr0?mcO@p%y4 zhIH?e>n&Rf9xjmGkTqn7&L_s}*kKcBchITyANVts&RF>jwz!z4U-L^<5W8r)xZm*0 z@}TO# zyXBBu`*)QG;^u)|&jEj%iV5!b5I%9>emdFZaW1DVk)MMF7X+iBc9+j5e|%h`7EtjO zYza>z5};F>B>YyyEcws$oOiVPi3Z~Z|7$qwiMK8~^Ymfrc@jU0gxuNp-LI?6az!u) z$Ykm8Tr^oL!HJ{R&hc>#&TYaVD8=OV96HCWjIZFyh_+jqADdqSj`zceF;=*+R=Q1= zq^h6dG2wcc#2x3R>Guefe-DxS*1L5~@ciax~6O zV-?K?CEL-HodRwZne&kSO|xuQATR@DH81GEwaC7%{l^cf8#8u>@9LesnLRV z933x#93GRG2gn(E@iB9dlD8gvHH|ad_71*{1Jk$%3w|-x+;@slF>)b@+qQ5-^|UEp zuoEJK4)V}8vfoNC(Hk_Q*j)fcB2wr=bm5>mH{czRyb}1l*8F8y8d4E8cI)KGb(>X? zJpZ*bZQHUBup~7VfBlc#I9=hwwSO!QKgQ#FLBER`-COvW_u;;?oj`l3rh7XIZ3 zMo$s0&-N=8Emr>C?&}s~5{g*4C5-gKV!go0uf#Pz3<6%Tf7P0~KBGLvnA(@hv>lau zqx^$4lgT3L=)$%Iq6v~0YQu3Mu2_8)8&M$=1AN1j(D>X__+hx-v74t}s35rnb3 zH*9PX{sc?ke^gD>{+nZQ@g08mD^E~Ot0z>BdOKyKZny8UE}oO#ybs$5GfYuTl4U#Y zVu)u5Hv0UUG2<d@l=~K;Vov1zcaEzip!`QPLL<~wfAeJsa<6EvXmGCBNY-2%+#&Ms zoZKINn{GExL)k;&BqhKPoTaR5dso3E3Uc?xx_TA0SHw@mglbU9mkGZVn5GOt>pEM* z+%hN9BkDG{N;ZT1vTSihHp=H?DMhcO`}uz1-=7|LG+s7ZZpbqyc1&Dtqh)N^u-Qm;$?-tY5LO%>OzuKbE0zdEUCkbgz@HF>?#;AP>#hFL5Vs}-Z^tdTHE>vcBPsd>Lt-Pg0VpM*%NGsXiNW(1^EY;n_bZIHxO`gZc!SQQnE zb^A00o8wZk3*r5=w`&kl`WuBaV`2%6Of202yu1YtJ)_8fqOV~B&E+P_UqD+zu@|_&t zKLrn4ot|xIwzsmEnB;>JNn6!pmRWR<0>{j)-1BE zoGQ~c^!OP}+bA<_l#Bj(R7j3UqjQ@AY1L~eesZL&cah=}_K38>okihuNj%eKe>urQ zg+c^dx}#c5E|tC;UVD(nfA-L!Hiw!A1s)z0RD6rv+ksAW6Ox*7Z$6vYmAiiTi}YoZ z*L}fIbB7@uehZZQCIt0Ia_^W{oQOvipfcoWt~Kv`)-K@Ldkw`1G7M|c78~Do8M)=w z-?Liu_F;*Okt{+85gCfoar!wkKuSzpAryW^8Kl&nahI@DZNGCnb;lol$CsZ_nGVg{qOE zKrPvWy*ZOkHrMM~QJ6Hke?RdEJcC90F!%+SPQV*2=7~^;#oM09B_MGhKes(;VucKw zFFgoM7-UX?yv|{DT7&-hTHI0?gzt#2Qy?le__^a!dpMlz3NCezm7?j}iR+ttUp`kxZ96rHma@Me}_BItuye7stQGy z59js|m&>sdkC|c8Vz?swZxJ!D-G4fDB?}n#b zna7JfSm^ZJOs7xQf0uKZWbcYiIMmWFL+C)DZ_4M#FEgmf-D!LAFva@nbeNI-htajf zXIM1;0#01X@~_v9Pi)0hOSfSEX-(%4xm+>uj}>%t*2BrlvIeEKv2hH00Z$czrlW5x z-=Ykvme@wobKCeEZojUE)~u&V`d56arU!7;&>G^|_dy3$f0fsQxwrxH_L+i40kJ*Z26pgLzR-w0rz5N?s*VITD);470#v%H4Q~^kFx8_GK z6A~$#ypVkB_KopO`xG(qqZ&8nRMSRzUK$9xH;TdjyQ{Ka;;I{8CWN#m!ZyR5Awja& zDHr$Ji!eJ9e=z+FKn*W-aOHng@p9M|ApOuWf@3`fSEA5Ck0^KWWeuZnI4RG$|Aeom zyuvNC82B}{qO@BeWhHOE^XTaJk@PIST| zHTg68EE%h44SMOu>}P55srhbJY(azPM?FgA#_%2NBc_2*eHW2sIfPCdNXmNHLV#kQ z<v{u)biU@?>>QRm9um!37|P+@ez}WwLG-hj8_z! zxT|6`kCjKsX(V7~Gdnr)VnE9b+j6!|wE1_oe>xY@B}LE`MFWRLumiV1ppmj5tI0{E zzkd9+OXo;7Ll_~x_CuqQvl|5bN0|n_-+?k%PT1a<*4c|%9 zRd*5?%wI^rY&L`Vqd7Dzu`jYh9S4lQTULgEr=heXh2!15|8NG2r#>e`=#H5leP7St ze~Vb4RZR9edp4MJaZnp`bBUounOGdago2+|EcR!j2EWy|eBRG`25ff1&1h-W$(aJJ z-mxk-BttWD`VNs~l6z*M!7;EFboTCeoaCO{)S+!RnXfNl4;@65;ZHOX9zA0wfBq#u z`38z!j!VkT*TASs$JO3=j`$3{UIGHEhL%rgL#(ZR9o_|e`NtqaJLJ7R4OkZ0WrxlN z%a$Y3#SQTBYoG>R)m>3ntLcyvkFsu?3~`HGLtLxGm`_{;R~k!LlP_=11wB{k4EB-)hssCB1r#!-9w9{TVn%al}OPl^hV!I`+ zM}LagPJU1H8^owuOH&=a<#+8-*W(}W`cBE(6Y zY?Ij9KHp(?fD>!IdopE@e?1qaL_6k`N@W|`fd~}2qFjcShywCZ^i{ILg6k~rlvcl3 zM+i3xt7J57!~xdy+MBDJh%)Sj`o69g#KxY-1?qnTE8*#W=g}gDE|{gg1E4%jRCIDF zVl-{u6e6mz&ANMj3IeHBnkCo;R-pJ(3q*_$am+8F?#0kjV*v28f3(j{c`Nw(k!V7G z2-GJlMQ#iXrF?`7wc# zGc#9Wpgu@_A(z?c^y2gK(!A-Unv9!~g#D1?ya=U$LEK&~e@L=ZPSMDU{Xwx(Az$b+ zbn8G(2f9!V6g>Sx+iyk-{O+6R`$!{zpq{qq*UZB0CPZz2^tk^W ze9fm>^OuK??_@=|EknoVF<^HLA&>@{N|Wlcs0i;KJyogFJZDx*uP5N*J%2>E@$k3b z>W4$5f0a{UFKuc+fNi75TSE~iW>$S}?zR_UgfYFL4H*MG(~5?AGQ`ui!iCyf^2ATT zp`Q~$QcGVZSCcI+)ZT9UZZ}>`F#HtY@G^z@evGQtM2*>*SL5jgh(}&5v9)1?o&S~| zbXWrS?(q8?ko@a?ii_9M55D;)#a__p<w<*5_RVuk7 zFZ^CG!kfQA-p>h|SUa3C{f5GxUv|x)8F+ZmmMp~9w`L7Ady$zy{`dj1A;Gn<)#?AP z=h#;oFyRzL7EHYU#Yp1|1!hZW!C8EqzBQQYI z;xG@Rzz3S*K#O`^9kw^i`rB)P%{_^?f2mnX0-C+fn;sQ6Kfji>zFAQ#f$j>^5^jqoN`A{oYkor_Zo^KoZ?q*2G>{?;~cr zO?X`%<<1cCi*BPNnbkG$QUZ+tbC0L1G)R~A*mgpJ_U_%Sj}^7Kzm*|ar!1$Ye_b;Q#h`*ry*xj<=_D*u zy_%GllV0nzIVZH?A>0qX^-Gs^ubXA){OQI$x!oJ#JRG-_xhvx#f6;e@Wm+4ini2yW z@oDbc-XUZv8nOw{W~~SWuW+vQe-l|1P8OV7w6bnM3jtog`hB$GW7iXzqo3k7##imN z0o;{-n-8L9uy=jYpb~?YjtUrKFbzY!f4}nzWo9p5 zN=tlV1-^HqX#sNDbV_Ui`r-C~jG4a71yPzp;_v4j&0%aH=#gpff}2V1LZ z+ckhA(d*l+VaH~J41jr3e>tzYMsCCo0f^@#OYD2^dCKJ!!+kokGI(ngm zssw&TWaw=Sfn(#1cm&>Su;){N>l&h?TnKA-8y17ErYa`cice0Jvmv5mXaKK5EPLs8 zvi($tYVH=0(pop){INg~{O(cGbSJd)$v`1)YCON`?asH3h#Qsge@QMyL6#s=$RS!5 zQgmC~u|gI(%E8RqBV@>|E?&F^Eb_bUvyIb&VRQHdUQ(%{1pmxM`Su_JTVo?6 zY%L$)+l6dPPGH-}e==1Q%@BtBCfCD#ejVGjj$r+N{8S2Xh6&-)8z%W+zO|GS7)(zw zCa1u8Ucg+l<3!4p8Gg$%+0Z(vSJ zf_N$6^rw5}pHJi4FV8fwbU?*v-f`bSfVK^5-Ma8y0GhIse||w(bBHL(Ov>-D=PH;O z-wF3M7d5%|{>%y4(Z=Rp;e93-FAh)ND$&HaCaBv@WI(pLEeJ)j&k`6RYPA3aDJ>3P z<~qpBz14Z7pkErqNoHVZBiYJtV)#67X_G4y%f7R3uN%W5vE31$D(XAOz42RErPV%x zDJAg*)zKK#AV@!9xIhk z>J1>xkgttd9Tq{vPZ<)qCZ5I8RWIKGoWMbMQLI~)koW?BaaqH84%UCdgph%mh+#p) zF5dq3{YP)%z!p#{Ux(C}?y?5tR@~VVwy?>I$rGz~DJhwrxIraXsQ)ul&!J<1N z^Y03!e_{xs#e5=5iRyQOd{j}q&D#ugfUs{gU$1nTdNG7!tB^Uv6o>Pt<+M^Rw@A)D z{Y!)oA(1-y=J#K%h}_U~`_a5b3--!+#-9>rBTI}KW$NPWqTm0MZyctFrySS}kGfAS zl0^`9Yae>RH#;8X)h`F5A}ue+T%A!}%Y0$;mEz%fn`PXfvYJEUmf}b0Ky>TyExv-z{MuT6-gMa{ ze?uJh-KTYcx_E2n<5oPFrpRLaFIh?&5>awF%W-UuU_qK4o@8H?d_Q?iiCF8e=z9QF(((t?Y3fuG~SWc zZ9v?MY}8Dem+(@nUxp`=@{z$!jcaIuf3Qb5Gpypg6ie>3J$tNuFi-fjKrg~~@&OGx z|2sAnWqHJj9oP5Kc8Uc$)Vy|GDPEacj4r4q8_#l1_nd5R_AG2QtC0~=6>XYOHW*pj z7D4nqjaD3`sv0~f5&InRA0t&ZN5IUStVfj}5(Kw8J{JlMup{JTh~n|fw@KFCe;p-9 zF2;fp8AiRzs!+jdFFa9~sL;X0Jd%I`!0{xeJZSPY2A>o{f#L1EyfV~|r z94=f=gYLBdaFaweoNQP3*R;e}j!nyH*Qzs)%-FR7?MMG>6;fh8{#l|w@WOwEv-X76 z3ILOO7xiemBPdUw4m_mb7$NI>e<9f>UBP+je7>*eH3FV$>Ebug$5!4&=n;#3C_N2V zn{hfarCLn*gvw;@jJe}_ylsJlSb z^%jynZz;|(UF93f`4Om}{sNfN&Y!j_963tnwW9BA&M(!dd`byT_m9&5_V|Nc_?3QY z3LEeFo&bOYTsbgR*ty)bu5Ex_Bc({xQ;UZ=w*9ZGB`c2tr!klNUJ7U7?lArA|L6QH zz7f}?>}OXMvoKVVS&q$ee>G(`tKJ{+!na&+VTZnl zHrIDtg7-B+@H?3FNIQM!J@g`#ePuO)4?1vsI3`%3DMDjrm*#S0z-pa31iHVhC0b&5 z)9pDH6p&d{FI7Jcd&TMPEtyIzGym&R+tHXmf47e3b9L4OXwpFDe~d#JhL*Dh*(?ye z7tfq?|be`B{%z(s>})sVjEIYhtW zKA#<0KmFI&I5`5ny>iIsc7OWD*lp){Dep5!=#2oxS&-r4n2|zqAUJrH2Fq23o4*-uT~OdP@MtTick1 z*R`(&o<$Xoe}w@AO(MWXvQlw-=SObASrMD&BD1?2Tsn#icB(6yOE_?-8unp~J14{C zDt(pgV$+}RqI}$PL7=%W2pS8bBB~!2so?L|wy>xhv0&~%FEldTJSwX7(EPI+e_X%( zas4G9c0`8vg3%KW%O7{yNRy84nCX)aE&8rFL&9@t0pg<}*wcV^w2P*BYC|he z&;?)uf2on>AJO~X67%kvh{5i+3;@D`rS z{k#oAdv8=gfIvEf__;p>u5Zaz^_C-JG#P9u?>lrzQDX6~;I2Q9DVaKS^X0;_oOYXW-I|5%; zI2AZRNew`d<*9N0X5Vlj^{ijs=uA=hJBK#IAG8En6{ns-S*UfcsHgwSyuKbJCd}=!STG871SO>^tcv~mp=L!evfzqe;rinL`QgKp{1g(yU;E)s%1sTG~cw>(RY*M&nHAk z+tGyy-_sY+IEXrn0tVah4FUOehkaI#GH0r;+~H5VWcuFl5JYTb`tm+Ds$=3V*viM2 z6w%)w?dxQWBe|A}7{UR-e zzph4*>6zXF;W&qEx|jkwtNwS*d!AqWyBq{3l|q$IMs9am4x(d)a5=kt+kF%Hgpnfm zB4cdu`nuGqu_B=lyL}L6W(36|ep#Un&2DTcDy%jZT3gk$dzj7mr~pb(rPy4>7__e{71mZ$PgG(HH8P0`!5k+YX56IMh~FLy;1V( z4@2!{2O}`ESuD`ha=SN>#K6ER)qXGR)IVB<2^pvl9U1TAAeY3~e<^@N2}*{aOaQ*V zH@*e(bwP#Fx`F(iz%OJ6mC(zYoAGnU;J6yJSQ_qp+qhWkfZI1|MrU8!eD@7dIgvU3 zdq}$!l5<|tIbH)EfG8DS{wq$oWKBF9&h#SEy~`)Ur7m|z=r8U#B^?;fVVxetLJApsI ziGk0x3EZyTn7>*{5R`V)Ym@B{P}^D8?8oX%zyeVQJ(0JsTc==N=Af9(_O)^CmEDRaQC9fEQUHEYm-<$yG5 z_#L;6v)Pl=!NCzaPfQoskofrWuY}Xm@%N-irNK6@e?j(*Xq(*jacbQ;AfX-9_ktfh zh$9MTa*J<@!rahexN2hH?^LsJVBgKgxZ{U~q&fG5!z1)*p4endQCcOM`BI56hx*$&q)?*~makbf*QB0FaYBSJjsv(s%M@diJLTZhwlvQ2Jn&yK9 zIOtU5#`l&+ohx|=g-Q5la!Ql~|!QszXXgbRDWW5TosUY@S1K&2rjUvD+jUBK=)px>-VWsO-mg=BE_V#F+^%dK6l>ZDwM*b0yhV}G$_0P^CHuQn`HvCGHo^nbgkn0 zEoLaut$F6f5~bYI00BE~vAi%Yo#*&L-~{};T@ht;ck|rRObv9dEJMXLmT3kX`sElt zN29XI3K4)a4ur8~FR#5ieT|>$f8aw&y94~XS;$lU-4I?W3Vu-aYHw4yx{^Gx11XV) z=nxHwR*=4WDsRJ$d>o!0ID$?8$YCJS=G9vHty|N(o3-bk2pi&m&jZ4VSM4n2(h7ik z`0b);zt#p_-pLwR2>=N|_P=*vBJWZV+%H3m%)a?zNx$5kECO9O5LjL!e=d3PxG#fd z@2+02Cd>P&YSta1YKN9xFuz{E!%AhWeTHubDi4xh;r6&uBftW%MnMO^tLba=qoR## zMmh^4r9QTQYuvBrL-oYq?_5T>P+uIUqOr3ULAKeC_u;gxB!0~ET^FgS-S5jq!#$O4 zqc|~gIcOv|+qJ)@#f{CEe{@}JH|TCm)&^yD_csh*=tz z*K@RA%$SI&W{Ldi;e_Jy3Nl}ae^3D=9`g3ABOp)eQiqR|kKdMB7jz@fP;U%lMm@!J zwhP)1`e=VRKyli{gx=P*3j*%V4)enU%{;M*s|e!?62on`!He>0e}iy&l00`b)9~m9 zL3Q(0C}*;^lk*A3!^@luZ6^;k#E!{*vKq$X2m0?|>gP#JSIaOy`_ujuo%fB0@ZS90qz*bY6Tj}l*X z6xdL~I|47tkqU_HN5KECOzQ?DzdlDQjY?=6Cq#KfgeAf(2*y!h8-j4yc*f{~{LZ2^ zPSO{pmAqs@O|34uA})nVw#_sadwavTrx{cHV&*DPWp>dEtSY(UH*fr_qU^8falabOyj?HI03ohddwPL*KaR^t5SnO4%|0PUg`)W2Twjb(3t zMwt`GTVfb)=+f|mQ-RBO%zBZHCp3FsXrOe-H)d#9KJ`L>Z0N8g%_Mp1EgLPcor4A;f8JrRv+eH21jb02)z4Vp7QI5Y`|4Vvs=zyxMJo7a*!M=($VuU}T3O|$@w=vz ziXkC2Zs*}mgm{;aLkj)74n9;FC&gll)sF@Y2_l4fM&-N0(R@{uhKgQ&G>IR$Tr+y2 zSY}A|RjwPX?P03ICYQPu zx0~3o`ynT2%7~z4m_y>vMxK%3LgZaO(itEwR_~C}Fr(I5IYp$*Z!O0y{18l#XJT!| zs{S<#P>GmYO|siNv~ZP3PGLPa+yxqSBpABjIFz)S9^SA;xXJg4e2MV**=!&s=yAeJvcV>G(ILHyNB!6J)u9*s^JlQT41c*$l*b zjRg`U*n)h4vH+a~r*Hn#Q*8M1H5E4Ub7NA?nXj@g=sO>ZGjAue%GE&(zN4!Cepi^AVd7UfBE_- z^LLMck`zzjdA*z6GdC>Th+3VP5zO{Yvrzwl2?0I4y?ASQ{bT7omK;^KDEdJR@NOu) z@CeTg@4e^iFV*i2I-;sNLK3Ny`>ch@w6w}gs5?lu)`Wv^io_c>Xp+b$yJ_KjQ%Tc0 zEXx(u^5&c(Yzl?Sfmh#leB&r}e@a&>xxUUZ9j@ta)?j@7rN)3;G<^H5=}m; z0eKG3@XGua!KnEdIQGTH19rb$uP04JYjs(PT`$BDIt`WON+jU!6u{Dqz;nm3ZmltL zmNb3A)Zv)iJfOMXR?gc953n@^PzI`rH`ElAsl0!vdIs%xf=Aw3MS3{xe@=>v`}S0M zK7u`QM^lsI%?*tkMv~u_G<5FBZH9*d`W>F9rg%~#3@yJ8mKK3pH5W$~DH2x3eKy?3 zlWeQzf7Lyo-wq?=GvjIN`E3~Y5s}dYwgS#idoVacN)}a6>6ekr8@mm0c)|2*g8W(1 zjE#PMuHFl_ zbh=1Q3XUr>{NjLjm<%8fT|N=x*3QBZ(-%?4q1z3c%trlz;#b&J#(fUl0Xxe;!+8=I&J!+;>cUU zHnGu#y*`lPt7!iEwaYTb@CF{RqCP!5crfJTMhZCg+HOZ(&7=eMou#b03#N?IP_V^C*F9*biWDL5nKTH9GFLmahXL zh{t)g$S5-i%7-NQoUjbgY1{&D&POGnQ?s^5yt3am@V6#3f9V~uV}G7HW97Y#`5vsU zidpm8LtCUZ$6}vBdONKRe%3|tiqr-8h9u8$7|pE)gi;m*0>0pBnI)o2!5+Tw1pnzi ztuM4&AIo>VfeY$$LqN)$sFnA7U#hmr1JGaE*V29mw+rk0StEx4HbJ?R2>Izu6V${; z=E$~q`#ccGfB5!fa7>sGp~9c+<(qqcxyi&U6+a>jF$YxjpPeR_u^QyNSSr^2eYP2e z^cr0uVv$F=ZyY<;FAGWt=eH>08RVdW-ja;mWV8wH4Wc1AoxS!AK-$a{)R~&`w@8#qO!?jg>l|yxj9c5V3yh8>T#CwHR6iMkJW0 zz<0Pl+82r8%(+1_(zJo)=ffDnZErK1vtC1kfeP)P_@H6Lw@2ToRe_wmE`6n7jHBWO zOuabne_X^$0P@P>@6q2ZTUDraMCwjeK=fZddt)Vjh6qRQznu1PAd%a_RP%-e0GBqI zy_!@)32yY|Lu@nWRF7xVSMNJ2N8<@Y3YmV)B;#;u8`e;r2d6t5g3X2sfb$Thfk5|F zE(vWuwL$mcO8`*Q?L}cLxJvB;^h!a=3^ipnf29Zq|5VZs%SOA*!M#LqR|8ECectX4 z^H7W-_)iA42!$#`%<)dfG6DhB8_N`u`-XHZb3?&Zt&u;ORd6zdh%e@Ek`4AvM-66n zd@-QqvNk=LVK^VY{M(>hP?*=P0m>!ZI{>FDYf4)H4f?K^F_V$%ZDCddag_h*64>y>($x#1+ z-R;fq$BTauoqrHI=uw7bvOD&g;8?*RnZ9YE@kTw)OVoh?9q=22Qqki~pWo5(hH;>w zqP4b}Pf-8%ZYv&(9D4b6FUVo|{7VOZ@AY3MZ)b@o$$?HK8346=1}oNdN!F;iSjFe+-<(ufgu}LWt!Bp>0Doy@jQ5(9ljm%7QsBWW5CS zy(Z^twOh|R+Vzv(nf8O)69_!$ih+AR*+HzByBn1Pu-rNRdIwrff$Sftc1o2z9 ziRapzdcF1fN>qrD>UH&v;0K(wUP}-)X@5iOo>Nv5 zJeP%WvD|xMTilxgZ|=%J)I7JEP1M<-Vj*e31(~7IFLmW5poW znGqcGt%>vIe;l+54u`Kqyh)eW(JCF^wXJrpqOO)1X82;407cPAH9UyJXlglJ(?$Q- zp~LK?_LTvOj6xg%I(L>nU!*C5T%vtYz4>BU|)k&YJ3_%0&OKQ6MXX6 z9dUU0DKTF|sZXUT=w-kHY!~1MzlnGl9CE+dfdVr0*eLfUtZH7HK>$bbuz=U(ml0JW zo#aLNe|2^}#JIQlQ#3-lS%mHYuR-to=BPff*2*>~q${UW0KUEActZb#1N)tZbu4*; zj0~sYq8gzOhZXxUV;OP@&h^Y_@nrLt=mJe4^i9; zCo`{QJy%MgWN_;W@}^DW97^*PuB$5xgI1YuHuM7*VC8ghovVOh9su|9*kfOh&RI4o{4wlwuOG;= zKA-Q0k$=44I*5gHdzoxdY3!sOE=AwbG?Rz`0T}DAo5<1piLdGSHjplU5Z$f=G=_uA zf7W3l)(7RtZ;;2>28ekF%S*Fauwl643rv)K9iW~(WbZo=i{Sjw4GZz@&*CZ={>g<{ z2U+AnioeSpPDsC<`Yo>|?abWuBHQ_u!oMId3ZRQrx zT-p|`oo-KxQ~XmJhQxpedR#o_6oMKk4qd zDn}pRD3;3T}l>dkNZe076&E?}fWys%uIIBMq*YXLW9Qq}-a zrGJNg@7f-^&qGKA;zOPn8vlr8@a*20ZVSu(a?lM(=xM8v!2-bN;rMuI(M{hREBZZ% zO>{`)JU0|k<+=`O9CAkBWLWiYCO0~#NXC~s=lpLsVNKwF;$^&U=u!8Ke{5Dv=#YZN z`}eXGsDLUVx7W^Qx%G4Z?uE@co=gsU`F~{(lz*LIBId#l=#j$^R4QvS*@kE!{<9~3M zouB7Ci`-qCl<_gs)`K6UQExX|r3E$b^h3Wb@PfE&CJN{)-BVKPQE{(+?_9If#GGc?&p@4tXOWCiHn(M^P`NuZ9+mep+;%)3*^68eU=@b}3VI!hG@59zVjL zm}9Y^Z_DSh$)iS7+MmAGi)`4@Tc7OQ*sT(@k zn%kY76v4Jo4~R%4#if0XLwW}Scp%;~YVTB3SROL=2WcmAxRKr{3NJ%? zH*mj2N~n6?xJWPD6Xi`L-Z6xTx7_7*Hg)`-`aX53eAQF`r8}`P#ZwF@E=PLW(bC(C zBZ}@J-vL$}KFs-d#;_^xIO?SAGE!Q)kRLiJ7}|A+a7fj2P*;77_kTbNK9ngDTn>_` zIi^*JpVBaz$UDzXUcM+1`&V~&z$h?YUmd|R}Kt&5l$0_`*y}Z`(JJ4M16U;iKzE{zwsN z&b+j#)k)h4?LSdhy6Q4=Cq`(!J^$)r>)P*CMV$uTDhZ{3YtH`0HO7cbBYc6Jhlfa< z5KeLQ1l8snrINwhMJ^E8@b*vT48zrv^P|W-Wq;ywGJLs1hIOEl-3xR(F2jGARC<7a zR)-_!pxN%f&Aa=bVj0Ico)FK?Z;-ClLodYNdWwJNu~tcjwFX;=t@zF3Al_~<4-&ri zdZK^XOqCZ8=Ht`Ru@v;zHw1A#n%DiW{sGYF=@YxjEAKm4RQ>1FhU|5~X;%-zmZ4R3 zV1MEhxel6R7152+n$WsdiiG1!^VfT)DD(m#+2{FL-lGA?#Znnlds6%lY7qFES@QR|BX*g++ua*_aZ(vK;vz8WEN1p?Dhd2Uu2JxgnneR!VkFbrY7V6F_(b-M246=d1=1A*{wU2Z}Re!p6V3_*y zQ|IXkRLre&hkwHoSA*tx0v7#gKVOLAM>j&@YQaz)IE|>?9)y>AE73pvCYDF6S2>i_ z^BB+@Vd94?TsPIhAE0YohYtr9Br!-d>0c$%;N}<`NzOdF#L+d~LHsH^(tp}@S2Z%( zz1uIs0B9NJ!b87I(&ZaS z(kG#maCPT9{7r5~q`V(A-Za#=C-wX>FC(#CRt*F_alA#1q7G1#SAT7^FsX_MQ9kou zBu)*^o)9n?IvPV(|Jt-56h0_@0mtFF#!L7( z-+69q^VQ7W*{%9YuYVS|J$p<1ZC`71u`$&`M4c>S=V(8Q&jduD_ufKigKWgvQSig5s27ld)%ecnK%s}kS(vl9b*7*nXa zRjxelX8zp6lH-o56o ze0~OsdPK(}_{HdlFCGdk58d(*U=n;ET)6nqSAAxaRMuE;mtzFZIo>rBJq>n6(_0iOpU}Cl-k) z8g^Wh0EoDl_fNEy=Zf*}HLsmG7OVMX~HRp<`bcAYqQ)jbHUWz~q zdf~*hRYg8Ky{&wDgWdqM5&}L0XTraQ%zr>3uxa~4BL%aoX;;Jf+{In?K|*?=Md&!z zlHM8Ywl(MLXd=3fZ&r{SdC3=lP?>l9r&c%6 z+838^XvmsYsv@?KRdP`$JZaCLL78S~8s=uh#<$qcNXrw8_*?Dd`SE^lZ7*9E(0{Je z)P0kKo`Pw1uxFIH_6uC(G7Z^dsQEKju&hQsd9Sw_kn?KA;`vy+u zh`oi~NaqSrlqywq9x8wlrzcQa1m$9Uzqy9LpQ5Mq_KC|JZy4yvgI^u_$6%$y^=nyz z*-{N=D&Uw%h#L)xjH0(tmO$R9Lw^_gN6YwYg>maR7(sqZV6SD(Sz@9x&nz`)mG_9E zU(4ef*5nZL33-ou#*%VKM4Z(1-`Bg3Zas`ICwnc;G&ix@d4J&xDK|%T;5-WjEBR%Y zkDh|^!-&{E|J={akk;zg0v_>-nwnTQvcSfjG(NA-sZQx*a^Vf4cexlh3N+P0Jq(DWEmxJC-)2E zkd$uyQJ-^!BMiPxg}Y&eg@0yaugsAEmWh+?8U#3Nd)U|0@j|&G}@0*RJ&CZVs7^o=%w7LR-A7qmkX9(_^YPYX^$t?2-ugYKsmybAl|2bXANhNNU( z9*0PsaTvljNI#wLo6Yd&k;a-GLp5bdI+QL%`$IYIvYRw<0hjmks5 zN`E!3H~{)C(uWkZ%a*swl}ecfBfj~4WoIjC=SB}e!M`o~p`B7|9pmFc z0uNwD9unq()*UW)sQQJ|Bvrhl!KZ)+Ph5kmW@}6UjEVUp9fgmbz|sG$8kR-ZhR7B| z+X2b|>T3wz);+&dr_-(iawIp!ZB}s8uo!FqzF*r5FJ3E}>Ml?h zOhmX+6n|9r!gZpx2}GZW=sB4WfG!4?AONp;eOoVmW|Z?NxZKaNy6Q{;U{D{ceEP+( zv_V^d<>T8&&D)DswZ!PT8c_*^%_7j@%5B?b&hu@<;9_(W4e-CGZ3e%-aUrO*FI)$B z{HAMY`fY%NO?x4`xH}LmzbV#l7@+1#EWE9RrGJ-(r7OLKTS6?_sjvjMq%a?SptnYP z)GxNQNqn`GW#rsbCXd@m3vitu!ss43=15BHIdz=x(Hwst4-LuwLdD|jxg9@VwGOxi z)D`ag>8t^hRDyg0@@2zx96$mTq!bjM2ht>MKTKjeA>vKgzmuB#lVlZQVLMY;Zz%<- zYkwmkHJf)4{}`A&ujW}k7>Kf}QR?SMDp=$S&=*m|FWABUA*|5sT_E;i!&Xsd;^$8m zdOj0TFDBq;5>8~|cb5YN*W&c`_#rt-)ysP@B-v~`nj)_a2Eo{DC6K;mW&JIxuSC&L zK~y=_xNU#MZFyn$!n_PLd#*@(Te}EgpMREvRRUSwnOzDUMH&%qy_^pOu+)lX9d zjdseANw>450l?C?Xvr{N8S_Tq=YGjnHUSNz#24AnZ!)*&7rSS=ELzgpDL}1}tzfEd<0S z@6ZoBlYG)sgn=CZRx2b#E0YR;3%@*Pci=P)99?-VpJSL273q16N?WnmjaSSKCa>sx zW#9>})*TaZw0v99o0lD6lXdK0PDI}#={xk5rQ>Iq*(>3U7-aEpf1 z?uT~y6;F-AQGA?|1)s0OVPk* zwxa=4+YMU!e8zwZK8jh;q{#p;3Az+s6UunB=@#+wi2M-f&8@ZAiy{ z9dd(yhC~w6q0Zx`V^57I*&h}szx@C}cw?puUjchQpsjyyAZz^PPN?&Zd+MFb_!=Yu zHJ3}61t!Cm=n3wxkJZnisaA)XlaqvGWS^iWLoY>3lU&bPky6t=aDV5kc-fEID%G}^ zx_qtP_iB+_)-E&xpzKYgS`p!s9 zLEScy=$fTL3g_*6^nbSDjL_E+tGbeKmC^@L*0QwE9kll)bJy9idLk#{+Jz3q=_XPdI4mnIdv|To5?zf$#K3Eha{LuvbLiz%uooHn)_^C8N!KjGLg6nUUNP1Wg z<^5{F!(g=j*WHB^gP?jQ+TKl13XCSnQW$1vSnkvF+X5z7l7AYI#quZV$!fcLqnd{9 zv)5a?e=oy4EW0Js15!c5`g^W%wE7@Z!Yd{htk~aXxxgUhPFl`rAn=@muZ+ZEeZjO$WsM32c@`tLD9||6YOEN;Ta4ihotF)Qrb)kJ zy`5J&?Nuq3*~~634mv=7;l$dUcFt(W}X`rYYhpQx$$}&+X_}z6rhaASIVZi8{`3 zqM5Hr`ow*gJ!2J+0LzXA@3g2lt@8-WBu8ls46&@rlz%WQKu14x+cL@%{!p%!8XgIp zLew8nW;Of=(2~{JP<||TjJky(%zU7r!-1u2G;q3APT0}FC^(0dvF#XHf|zi zFL1H3=A}0^vt708EpB~)#re+I!R6?^MWZc*Pvb!t8g}B#;TPdFazm za7eV*%zrtLG^RZy8Jm{=_BvYDj8Hq1dFkIO)h%k@b+bYN%ERFvW&R%72e^8qo&Z8Y zipw6P(#(V>)K;~rT-1I|JEliXN*$}hg9%1k^_E;0|BV^v2^r$f^?~r&lq2LVBpo3= zI%poykb~Zv5Y$y)`K1yxvYQ$QBT`X(mqk)%pMM0>OK-^FJgW^bv*xCBhRnv`;byQc z8I*nL{JE8poi80n2S3U8W(UFk!+ZGu0N0o1o zP@3#L#Zzt~K}+Ay0Ef}vMN5o)xD!5ds7TvAPjT{r{HVf*ma6f0g1!gunUDNqP1H>isbdq9qDW zaw*b$e}44o_TFX?Crq>LPR=4Qg7S{3K~$>*Wz*FhktS-p6ugmO_yd^LA_K~4)4Kq6 zS#(+fg1V8wpwVeOwRuEOd$m~-3mx(Rkbg>;{ENYGFzA{w&y3ULl8yv!Ij^mN+&6ia zOk@z9Mj!qPqUbE13;`@>Bjahs(jTUc&cAJCVCzkqENfs-*1F_9Rze}tYA0CkBGyR> z=iWF5CHig+G9b14b(1!wY4SuFf$Y`R?9Pvj167f3{k8EiIgJ&?041t#y%zLw9wV7GNIx~E*q4;;DwA~Jai zg<-(o&7%f}as_n{0C}0x_pAQsmc@v1+*bo2a$owO)BS-T`r1urmj}Y^%(UqV)!S|~ z%o8odFZg$+EKu!$aPt>1zoD`&=6|ZK&D{-vkroiB$6TYcyxpF4Bf0pBYinU_*geyS zStq8c??Rbxte_?*{_J30_l5LEThegt6D@Y*i`o;I^jRN!?hrnj_BV*blgH+19uE>U zOwn&@(h182&?ZP?r}TPp@aj5sxMU!d4^KS!)q`CG_WPPA*c@_YP%TCR+<$_Sn#05z zx|J%H<3BXn6Uw9$8O;UUXIjBSn2qHk|JFeOAkdvrplXSCVT^`tQ0O zKp$9vnj?X6y1JWtwJ@b~@P;%W#z!Z9KvVirFjbs1iEsZU4Cq6MJ(-rDjQF!!X!+-wXSd+9+b8s<0QA$GquMhJMMPj1C^?m4`0KvAq@u_SB z5NJI`*y^*}4mByKMq9moYP=&4lz}Nv6KIS=UO@BdJQ!w|Vx$S{s zSs8+IOGugoLJC+GyTmB`gYC%Wiz>^#fyALWE>qe^Wq)S_fp++spDn50zyx5Vxe=ZG zehrh=8ET^13I;DSf9Rgd+oPn%A2s>{Y=NB4KAB?q-$-`YSn(@$=beCF;39#cUPBIP z8U$ApnRJt7QB*^Gd4EUv6=(GI+w8Q+!vABEK_s<2O=kwcadbDy%9Ggmw!a_@VQ^{+ zKcOs+h)Xyf2tH^^E6Gqo#8i$McUc)tRW|jJfpam87sZNIxY;?1sM`rlnX7BBP%}q~ z6vTu(`!P(`F`nt~DfLSgcM0EMIn6xkVXt^eKIcKwc(iI-uYUzeW@=%7B3F&Sb-UM2 z9ZGqXxn11t1a)x&5XB!cl4-;8#m~@SzFZ*7JYb(#Ej<7Dbui(QhKq?6y6-tr3qD9x zJ4m#JCDDiqHw}j&#TRsToYvE=r{{z5weZsgR01II+ZMNol8K{;+Qv9+RPX_vGWSoN z??bY%00wq;Vt+P>_8wJIN2-%xGr@;QV3hOtn#6Lz`1vxK&j3_QDEFn%^bO5=U=9{W z08tC~_;6Wf6RuMj5}a^bIVKHzB_+H2xeOpnnj5SV5p=S#@C(3n9Edk=EDi5W$My@$ zW`v5P?;bgMpan|u;t`Gs!!oAKUeZOI8Gu#&KFmd1`hUqmQ4y$2#xl5Y@k&j}w4?mv z2T)@>vDag1X~ka{X~*VRZ*>9aTio2QKZXV_*1sLS>?`)0k@O^)$QU8brbiFDJt~kM zBHhsXd_Lue?|93zj$?;U)YXgwU4o@5uteS9s@{$5&ofDrbl&Oqa8ybTS1b&@Ney3# z4nF6s^nYxTq(4bThAZcQ#Q)hM{HY0>WZp2c_fyYPY;TQR5UFX3QBn7p!a3AmV<8WU zke9b1@Oiue`nF?9gk&W;Sp| zM&1T@ixAGRr|MCT#Bue*ML>!VpG)|L{Qy%$kbg_3v>((udiik4@5~L9Typ!drY1MH zCDPz^!Uo`%d-|ao$`Xq^J~!-w!;~|~tBV)ztA$ZRA>217bmnfH zIVp*Pes;4hxK8hLfh<@vS=TTq?@C|yYJ1a7{fqP{ysme6F8{$Eh07YfPV}8&g#3)jig4*@kve4EiaX&ZNGs8~C;36P(AL&9!$O8kbLkdFj zaJ|QOpXu{MQw}7x5?%#X6R%&mQ{ zq%1iv@Mtb!3b{GReVzd=W{2llUz{v9s)D88&BR3+My5Gz6u&3A5pYzwlLP8~2Tn6t zpVCQm1#a6z`;)x43MtEHbAN!1$&wTU&pC3MXen$8+9;C+B_9Ws%EwZ=R|?BQhdzD? zhkbH*#~79XAAm2wd+7E7a+D=7ppwCP!Sl{$UQVs7%3a_XUK6b;Gv2I#hdu6D$r+%N z49w_;CH8^5@mPki_{|3IPZvI}v=jrgH2oOG*b_zgTLYTTY%U20DSzZyF4SCroK(Fl zW@1!fI{>pdi~VX|zHJ+kD?E0cL6~^iN95;kHSHi2GVbXt-=Bd!CO#)m>-GvA;I1aO zi-Y@ev&(9d?1lj(HY@G7-&&yf(!*MdiO#Ua-+l-E@J;q|-i%G}LB&)ElWF zk>oq$gbOq3N03OryMNGLMAGo(s5ZAL1UEGY#o(BsEfo#-ZS^n7gZxvSgEFmH9;6S_T>c_o{GrWe-Q8Z;Ulo*X6qVx7Fbh8d9@0XHHFKJs{gP$FP;Q|k z!5>q&>&bjhonw-t0x{HEnZtEx1L+202Tok@a2H2bWd1Ay`hVMavyM#kxGvp?d;VjF zm!xQuyALqbeHyE^(Frt2U{fvm^`1wTN;;DXI%<8<`FyC{g}M=or4LPC-tC3}MEqzp zJ3jD`B*^cg-4-c=O5eZVg zrF7SXK}0j!g=zpU-tBAhaIK=SpX-``c&xRp;F7C$rHt zAyYwuw9K(IDa@#uSRTLHZ-1HvA^TtcqHj2w6JM9dwttR2y1vevspv6iSjau>)}1?w zQ1s{Vyw#W(dQA85ZxyB-Kum}7aYZGO1*XhkYUmT|My37$(L2|EO+qFU>;-xb0xDM( z1?=JFdjS5>ZE+xN_gf=6x9(K+=bwF7;oSuWZ(YAQ04iDtAeU{0O0e2V)nKu5!@sSd zTPV)gUVr#VbIS$-cDLv}0RWKloOx`xSjwan5=`>R%NED%{heIhdD&7x%ug`eP%tb( zz6uEqC-x4nX8^72)|`mS>M0h)P!~P>kV`!1pKt$ys7SCl-ocFnjI_XgL1!^nc zcqaR5hA$6~@cMb>?DQ&9-|gIggROjli`-xNPk)}VzuvroHxLJhr=jRvO}W4I^=rZ+ zNjk&QF2Bcg<+=E4d@CjTB%dljN|xcpd-VBBkj~kd{-fzEmgH8VAo@XCh-oQkL5mr7 zVzrp*>z~FEZ{Y}s?eUDN?#(>e1zO%1ul_yj4%@AzQG|*%lh}}5IAIR+chAAsY?$8* zZ-0tJs(nyvKfg|1p2o6uK}3?LL=t(*m!}StuY-tGoCp&fVu|7MwfHRsC4cCN@y9H? zN45{H{Jop=tM0@LJRSoK1jC1uZBWJ6)RW&n58wwxQ4a(6$phC1<}0-qQ~85RSJ0RU z;-^Q@`=<-X{t51%i{BtvXclQ|F1eC_9e)VOd%)`ar`<~gXm0~VK#sBC_TzCh%QN(h zl)g=Vft$)81GO(WFu!B29RXKrJNni$KORHe5jJzx!lilK6d~BRoSK@VNPS+E392O0 zlX~J;H(a8B;2YJwZ4y+0`KC9etL&>lCp|RZmY|4BRJbvEdu5Wi`t8mqP{ToDQGbwD z%d1i3ZhRFP^1)RNeM+}rz15@{2e%&3+6%sYXnoE=$J#2-0H+bh1L5?l5DVa!@~KLK zZ`@)g+h12q$Tx%L-AooDV!h1(&oK&Xw`XTj%b#-0k94eoE1@=je9kP4^eb}&3^+i} zt>OiQBf64FZBRI@{Ltq1rUKmNd4I6*q!vqhv+0<|xdHlDELBvF)TzZdKqXcJk?RQi z0W^z9SrTJX{ou9wvZP_o)V;P8!URmKbKqiMdC%%(%)2jQS$rMLA7zklLzzrO9B z>GPyQkFaH4e)>XcGQG^(+^MEv_UkE|A=Z;U&%dc;wjB@uP$Yvve!uMdXG;w65;mB- zq&~Kb9|C|tu3jiZBQ{AQW5tr9eA%6{y~5g#*!#q>s}vla6dpsFh!3F5bo>%|Xr?U> zPvli8-Wbbp7*^x%js2cTNq<2tmE0)ChN}yLRYEyBKN zb<*XN252)5#F!(@0z-olr_D}Q1LQ}@4}4;F&CvUau?K8`y&J$N>`~27!$-AiBhfPu zM%UsE(L7S9pcb_f6rUk-w%nFHXjYPve)an@(16+AJ~@0nEu4@_R|4vEFJ3%vxG;(S zw|}v>l($PA8`8!s;(zZp-Am(&Ze|EIOc}lUH9zT(Z(cwbJMr{QUtekCr^oEii8ubP}ji6XI_ zH*0g1Zp^qd>>6!UG5CpF-PLSogEc>QgLnMNyds?%+m>wNtUshe4;y0cGd;gsPl=|-YTBs>a8MJUdILLOUs=`aKYTu2!4N0B|{ zC9Ne)IDa8g2!s$MzVV1#=;ReX&Y}db!$(K-!!@D@vHf80FG_i4|0J~zcPc=$Q8%jPoMSh=|{(>WZqk`n3vY%g2G z1N$r<&fRt@(TCQ^jOOKw(&-KmyAl|nSd4hZDvO#;UA)&B^cPIt$5fS=NpcqUdtjQj7^Yt+JO zH{4tIsJ|Vx&s&U2LNRe&qHvrcC!Fs+c+qe8{ZFrT$*rzL#Rve279+Lr3TLR}kvSt+%fJC=Ht^ff*{=ba9NTmNh2tqDX9DhXYNtOoC;3i?^{M8nhR>5~@L_E#(iPb!k zbf{}Bk~A0no_3p2NSdgM^)+VeCB_4hnX4}(l^uYmGlNe!3NYQ(7T5BIKgPX4@L^vr z`-&MecLJ*mFi-mD{eaxL6AJr#tyH(qo_Z};uz|zOs19)|N19`Iv6o{dRZ@jg%VqVuag0Y0}gcKOdQGlUdLN&dLDUI5K_Zb%oyM-1g z&sd}wFzfGT{*ekrKVz!{!LK?jL6n1svweXoj_x{)ey1Ll;f#ex8_3kNQ-8o-ewjS) zL^m*B%kHK@U=Q~VK=0q*&u%od(LtE_P`}yoBaWFCvoI2L~w!O$A~2Z`qw`ExG%X_KHTd@UyFrgThPsuXQMKBGtbcO*dTD} zhLZP%0cAAfN#r`$R3m_q_J4fiZ_H=XZ!iyGeAC_QE}~n9=?_m`)Zlj&~=KMNMSh5MQ-0RItCgu73nl;ahEDTu570 z6kfq5dC@v^Ds_zBrXQ8f71jWVbaY#Ho;yvxLC^8L?uyPJF7C$(RLw~-D zxD$VzdjPlyF%t8AiNgF@UtC@^4G`msxJga!S5WfFg{e=9&^7u~bO51HjRTBFLeMQ8fbQD>+sboR7a3JH zv)oSIujJ~CzoQz#^WOQ;G1TME(aC_9zfNyh_SvF7^{7zsZQr@^9BG1_W*Xqmm z1I4iU{eN3q>g$>&5#%>W15iv_X8c>j9|j|(CjSKpiD1l`L$U9$(C+O{eS~3$+@=`n zB6jYcR4i{VBW*f4FFsC=_949(+TbE+?yNb|k|}LB95a7`cRvAV;Saq|=p70|x?I;E zy%!z-Al`TYV6a@B4Mf2y@8*N|-J1GKn+H5vpnqS?KQ+0f#0)p<3Xj;mx~PNosV-oa zp9T^p$us(vn%I5}&g&7*ud1H50&sVNHEQ9BJ@uX3sVNa$nq@sI$L>Gp+Yi`|6wF)1 zJjvHbib~rxT1oY^DvN<8+?uhnv6+p^vo{H4$`Rw1T@xq6DA>^bip1pqx2UrYmwqN%Ikbhg9 zV1h4jdWnjUQ-Q}kihMC!(aY=b03jj~iC8^j2_c7Z{-9HAyrD=w4PTH)Dc=R(>=&XGgaHlrWP18(A~3;+Pj>+eOh#q?@)Go7so?aQ2enwj zs69Fy6m&^rS2N+~ilM^N0th`X-GB3Qqi^vEqC-*z3$F*jB(Ul?y;?5J6R-MJAxiR| z&jut7fU%~MCWtzzJA4+Sj^TVHID90GPf?%+U+?5Z0mNyI+KBk%!|3J^v=8PEJn5Z1 zpqr91W(HSez+SDz@oRJ_&Y%({CJ`Rb&wd{)AEG@WlsjHZr%>G@l4nYnNPn|txO3p* z0NRcnJ6NDpLnhkh27CTU7jJ7Z>`!CAf!k$J4u1^%n>`o#&INZA4=;6?4~24H@S~lW zVLgO*g&}Dgw(|iK(!kvz2+H#doH2LlLmk}CeceN;tx@)Z-Xh? z{3}OABzx-aax`bH=Z(TDq<>y{=NhM~2LXS9fup|OB2&e)sKpH9dEbK0>~ZVe+%PdM z0Qa2%V}*tCIkTLQ`%SF0A0;cZh<2L+4t}!=hF{=-KpT?XB_IBpQ4})BnqHe5xgP7Z z&$G-%j=&0^z-_$w`ROsGwPkk*3J$H^kYtGRQCT9j-qM*zgdLSXcz-U-3kl{6?#@W} z;Pb8p{0QjDO|JbPb%1IXU%?#l1%Wni+m4?sG^7*#Q98O6RdNjap_u5s1AiCeUME?P zJR8D<{mp%DklW{rA5^ivUQ`xNBO#>aK0>_!Tbr(vr9z3MNXvc^uLQ7cVPb%Ts6F5aRp0D$@OI^+-oFZ-@ z1`lW{fam$LI5qSsg~=O>L_A;Sm7xMRXcJWRi`HMlJAA-B$kCuDFcSVeAF`#%BlP+p zV?zT+dQxY-v?a4ctnW)S!066~x(k5NWG$oQ;Yy?jO@9mu!{80$-<1RYigp@pEax=z zYfv+Y6-emOK*HbZuV~U+Lcd5rzzr(hLD59y`O29aN;7Z8OZs>HdCFZo20V)^zD#wa ze3h5I$k(4=ybO`J`aAOmY}o5R_UipM9v6wdk415#^6S)#wd zs(;`!k^HidQ$d7ZKQ>4948c!usRARW-vV4_OR5?-An2d_=WvPXQ~&l7hmyd3t@2pd z>{A3=_G`7{&PT)T^^7b1I=J#nE|zp#%=p`Zf=3}p-f$cG_xO| zeQ^#C%CAzWn31|)Q5_8@w`=-j0e=Y9bfCm*8ad-ifXqAWS#5AxP}2_Yx`@n`?iJ5m zr(BRtYUZGU&Jt98K`aa>PT512)*N~(GlUV7ls|*Y9arQ_;_jYm^M&Uz(BT(GGt603xiYxIBn&xUepVomw{4?yMLMOhJAPgYpZl6E`vN;azdEqDaLWVs;~bsYg*?#&+=i>=EW=Q8Vh zBJ94|61n(3Kf8o@zPL7K%;xgX$W7yWi6BCo-$`;Z3RB4dZPkT*)8sKk*rgxMzmTl$Ab6|f8_kV#daQlX3PEzmg)f-PE_yt${= zZRHJ71-d_VL@)`(GsBeY?uACD|0Yvw1dm`pQ6c;~UktCI5SEKWPJf$|`|dhC;sB3o z;VDr-&NiqTo~T!FriE6WWixLUNrheb}36sESNG17n6rgyh z`XvsHC3uF+(JF<@1*&GoZyZhrXj0-$>LlH`&SG0zgIh!4_kWRog(3C^x0;Ytmr;XQ zTYUTucuVlTlH5w@3|FDD=7Qzn7{UfFN-M7B-x5+8*4#NiZBo7QT!sEx=5uqy4e;HE z4PA?tIhsynPW=fm13KQ{nv;>F*&T`rtXtXzgYLzxWxmd@wXu`I3OD3ugx-A6E?0(X#fLoL1dq^TvQ{qA06BXzYx1Z-`PGM}Vbfl{m(Nx| z+hu>fTtMiZ65)w%-tiG}A0&H2>xG<1vD}|7i#v-7M3BvGU`t-vBhkP&$M%IO*W~zN z7>;2a&t`p*ThD(BHYe%=Pg0h$;WgwuJRj5Zd12Erd`QChwPDPVTlzR-&=Pe+u{)v_ zs3>4Px!Tf#$Z=r3X$tpoCt*kjLJu$d+bEjMN+iD=3V{792)ooB9YL&@W4}Q#S{Hu> zdW69L_KY4?rwLnNSPF40k9|=QmiI57jKdeY19HIe5v6~hHBH>5GN4Uuj-XlW68M;4 z)-)jh&Zo_L69b$BDX!NnfDlf`qmn;QC{Hir(l04$VMzW*-1r=P(Pc z9uc-9O(B0FcsNYjD2#v|T0iUq0G+~R2yQRlvGfWHJOXy9&1UdL^59EXnS(IT_A+jj z3r7;f7uB{KI^4t3($m93w}0mei5$a8)2Z;Pi?m!Np-b+^oE`v ztm=VUjikT#4hRza4)IEiwEKo!W#V6^V*NfQ&y;@^jq?|oqK}*EL`^>~GTRh+4iqA! zD9Hv-D1h9~EjRbbDrcjTY=Q?OD(dwLr|(AcK6L{*#U zN_V$yx`Y09+B;I%ug%M>nj_--tEnn|dIL2Cx&!13Iv1$t3n%u+d9ihXwd-xBOMWaS zkH&`|icwdGa)Uc>pd9LTyYJ642E`D2A%}mNxl9v+@cGMP$c?V#oPqD}r!Q5&?njW# z(#DC!YbP41oaOK{kEKc9Tf_QtU$z`}tHnPHN!q2#b|+SrZ+NEi+$bh32!rX(TO|uR z@NRB;kAJ6r-?Ozc*1|cYk8-}oWWaS%5u4%F=Q&`(j=+0TAo3eJ-Kian-3^5u7k_`e zfm;0|d5JY($mw5s4Rj0;`-#iHfR>u+!8{;Vu!U8dmTlIibmk|&O26iepWntq7U|McGZMrsC)fw{~(5G6x4CjASc555Gd;bFriLci=fxIk1T(7YM=z6s{Yp%~L z6=PCJxBz_1$~SgRJ^`Fd2gSx=j5lDTnO>kPv!`8=gWtgwk9#7w1^HFzNVtweLGL87 z!DZ`0x6Xy8@WMdQmKjaoM1+txe}*<3<4&e-Mx#Osqf`|#$i_k!BKKSF*Dikn+)8a* ze*LpE@$E-P#0_W1Ub(I;gdkZ_ni#fADH`EJ zG`3;&N&?X{ggesT{t8hPn>UW9dd7o^?%oC$uq!~1(JK?0x$*VMLfb;X)bYfpD$sX~ z%^_Mf^F>-=3x#%B`igdrSk zt6tCNf`Eto@HM^H@`p7gXm#?6T6o%g*_xOjf?uYjG`(}Rv#OOv{QGc;k-G@lt{?!{ zalSvsrRsigqEUqG2wktVFJ}+{!Myz}yW{gT@=-3D?kqf43DX(hrbB<=Ei0f!BZN-o zA^^Z8UMQV5AP5-Jm15k8ZDjm-{CqF?r-cOqHws{X0s2dslJ<9fN1(;=-;F0?XqzL6Z&Xs_DJmUTMmgQ7rhLZ{x z44^vB`1ZW7GT#iIyyrR@dcd9Ii6Q)U<0-x}0D5~R5>em)0eycW9lbsctjUm7r+hxS z$|-?8=Kww>J&cb19?wpve*LKUO|AF?d>+PE%B+EMe;Ks${rMD8B&1tr3@l(G)@c6L z>8r(5DzJ2{EO%uvn+6RRI868Y zvwlWWT5@ur7bw``nS?SKyC(l`q?FDH%JkN@9e<$&)~BYfsi08SMwbyteho}e$bMe9HZM_ ziB3Pu3ub>;si9Zn^=!B7<(^*V&Ip2IRC*OY4=-pF(F3x2@cAd4jK59HT9NQ($uuH{iyr|9T2z8uxw+uU%h*ytDwHFNr zqlLCTjpXtue}Y%uiklELN4?Is&4ZPvTyk>t8gNm*QZ&Pb;vi|THeTv?hLi^q26TBN zg}6(02df!{-)@VTKtJh?q$Z2mG&z6WI|^~(nw>W(8o3DvxNwRr3+*7gNe6uj(R2W> zPNor?6TgV(Hy3@%iOqb>kX=IL9UgzC)EC@oV_XG%?;8A75FVo0v3xbF;Yc@tC({9S zukp&z3rgN7yC#?iBlcv7*QEoMb7_Nb9s@62ZALs8k2ff%yJ~ClKAQNa2@8LmLY(JI zZ@oLG+Q410GCT8c7lb#641qri+Yl(dX~#ezZ^|wIjGLJFiya%(4N8Wqgx>*dw#CEJ zFuHB{v47m+QtXJ^;?gnB&#iyQ=AdTI{o38wnhpp_=ym9?XqbWcxN0kx@q*V;;n`5;}gRxfE^gm|f%MrCa}_R1U){q8$G_}b3m=xL5ynI|Th;N84e`Bf^6h?We|>A!GT)YM ze2JQUX!@^M*f-2CO}@i%hr{UK`Y8+6#}&AoJIJ*HTG`Q#BTwoNt=512{0S-n7=AKd zO3r2N7ij9!sb+#6Q;wDoK1n}@6cMyyZ*{SOd>QHVmIfFZAUYl_4?E;<%u?x^9m0kz z!pkUTqrbsMw|uJeA)*vNd24Y%I~+qf%-pM2DX(NRjVbsXU8B$0jC%q431GnSN!6Qb z2Gv>*)G?)?n7L+;kr{vSS^pP)#O=DWbbSgNuhz_*$M6CU!+pMcK?LQNl$AD66?O!N ztJEhkgkRcAFO>KarNT80xjd;v26~fVcm?v4pKZU+Nr`gOS4gnPH~8j}DQ$fCh1Ofa zr8l8|pNZ_-h)-DUd|)`BlnJwjY_f`rEk6dg7vHe1PgL}5UGEIylw21SSdEB)%7~!aGD&AUfD1|VO&qALZ4}R9l#<-hVN`8`PU;r zBT2jY*uUA2W+h7lrF1b*{3RcwvPe!^3ZtDL2otvUgDCuHUX#c$3;KGjKPZlj&wy1- zeDZyZm5_J1AVSBlcHVH!=%NTpOewLF)>zd(fcR-N`^kT4E}AA&3Sq?v`Je6$;<1?p z26%Z3EDL6kPlTMf_d<6E3e;?Xth zJM5_+$7e3)W@9vn&)TuNq4^9q`aRUsJ!d_AwF{weUntp|5B-tDJ}JLwW1EF%d^D0g zesQ)Zh}DV^DpySaZKdGJlUGDH968FPmAn1QgF*VU4})JzcHCs3oB#PUNmM zTaEiorejq`hsB7R(evP=yBL5KEtLo(=L6nT zIk0s_)b|kpi}>qjOK`|xDP%kcnz=FD>(YM_{Y7LpX$DH#@T16M_)7}t7Rwub(EmFtRr-{0_(6;rU%E}b6gozu zvv@57E2XnrpL%niK$y=*NQ=4A!sml_^M`kE5c7uU_^H0{qS0RRxj5->o-tc~V#$9L z>#m(my&sRlB9$8o`AGX`eOu3Kt{pyP~Kh8O?3v?eQfD=*9O?P7|s2*zD zW^)%VAa5#vobUDy`!|NlA)-IRWMD5=_vA4>SydM+_@Eh;@imY`FR6=AiiWj4z!c<< zVM21`clXtaCq-n`Ee88cHF;w%H~fFbf*N{H8YBWx%IoREPU_&zVBa1@Vq9#^?{jlt zcM+uk|DIv_W>>P`b{?wKF1kaVJF{2RD$wws_q$#&x)i(k`!pH4x9I*{b#KEpKfZ*` z>b?Fvu$UH&gFoteS@bf=-<2+VjPyv^-S**vN`6ivMOxb5uoB$&_2)gl-u8crvp0?o z-_$|<9Hz`@9Tp6B!z<5m7*B&>JcTRVUzms^m0U~L#nZt7Ylp=V&r47Y4K^V3yAlR# zK7KtB`nP*`#OGZNM*7M;=L)kjk@r2!#qsyn?f6Cxd1h`g`j;rhXO-b>=%I2uZKh(X*Xw zPa>8rX*KEnZ$P#m`5027w$#UbMi--5y~rjOLpwU;p;{MS*kQf#P3k#Nw>iN8Yr1)v zg*=(lTkQvjS>lk=Ir@MuyV7pTqWtom(=@Annn{>5L__;Qkx1B#luNyWe1KzDm53mfS%e)L zNvhL3nz2nuU#nRCdVBHNP``v~Y-DSdCc|S>c_SiPSIP5sR3ko2N3FImI8{>DXtr@< zal6ibn2a(xO-#Z-T*-gODPFHTg3Q5+SjFZb#K!QZrVe1mPubRh)v05xu)!!`dYBhf z{SffnB&V)p-wBpDmBJ|5skNDk19}h`x<>&JNBL;7`a~Dvhu^USFiJi1(|JD2*#_`^ zrF-J{OU-$Z(J&VP@{ualcC`^`jJSek3dP*8USXO$(ucpA(l~#WRxGo4c>Ni0v935G zF_B-5TBeG>_^+ix`X}7yq5>MFfy)H*mBMvj+V_|&V+t>+mxhgv8t8`SaqBsV-Uk|& z69By=GjizA3RyP?|0MDrNOM1TtE{^-KL2|^u91O_T3ch1JagLm9>o6_p#hu}Ds z)Y`Q%{_$o~2hNSwH2hDQ)(XbDzMV{K&>o&pUQR{J^>gtk6df1&V}R-#??j(6-0zbz z+ip0U5sDhvz-K;{$arI#veSim3~EH;=W8=?0vz5;qB?(VO3b&f*%NuXYyM6258kJ& z=062e&>fsk+93E|7WJ+tHWQbHzdBT@ih5WUl zZ`LI+k5YfjlFmO&yZOzQavLcSa>TVO1}GHdPqcrU3Xe)RvMI~kFrCZC$KDY?!U{L_ z-uS!9FSF3OSuO^}yQ#1C5~Di4)c868ar#2hbe6tPYp!JtpN)!redENab}LQYU0tBd zI&?voC~rT1SJ8l3=wOlich*B629k|}X(*i~*~Py*%|;;~nfi5)jR;^@c|ow z&%=MBoRx*7my84E`3w$u4=NQcJ8Ob)G~P}iswrhN=~nJu(<^n{o5q@dI>jKbEF(o8ldWV+ZhpYpB; z_qjba;NNv%%F{e%7-MOvJU;9dCtF}5e7t`@L?~;O8Gcl#dw@D{I_CI$3*&`>PVAwj ze2pLvh&%{lKco~}VTNL4^xfbTXyp8&q8M^SrNQ5o(?L3|D^qh-vHx%wpk=uV6xnKL zb2saO+kI5$4S}*m5m!UIvmCAksewiQO?gOxYRyifxcj$lR z#QS7aJIsq|9XcF9+E4Y`Ik{l@5eq6YaflBT>Y%bQCRtQo4UIDKWz3M1s;St!fDA4A zQOCW>AkcCia&!d=V()M!ir+!(Z;)AZK1YjStX*{#h4JhT=%W!m_d)axR*5R-64kLU zjD=5CvDqJplapoza*}N+y}Ot2=CyxRq+LE{OKu^SWr=e$+CJ&hWUkd@RNK2+biv~T zu7$Cm{HK=LfRivdcn}d58^qnY^O$gGs z2#hz6`c1G5(Y=_sy5m-UA+h%gqU%0`s?>f@et_{cK30YiL?k31D%LIj&l=@hHf^Bsm>( zLYpC9)f^4>TugRby7m!xCoFE70GWCWgQvmNpfaZ-$CjZmIpG>=`-Xo9bIdu$elLpq z>7e;WdXJH-gdciRXZe(7r{-y8AZL#_*=+u3L)=d2#~V}FxPvi+b_0OyeX6ofJxl}hJ36BfY56t)RK>|CxK&C<6?!&p;=p6q>R4p?Nu^FFjA zr4c~bI9ZjeThhEP5pjR{AnJ9XVU(6`2Y`y-PRSYpsjnpUel4Cw^gomQ61F*(VaNuR zIs}(6`p%nE_>TzQFd+|Zfkixd6cMe}1#Sd4PlWrg_#)A-d?3Xex4Ve#8|2qVuJxJ> zKW(n>rTHB%woYi?LETEbklm7sWvuyyIU>~I1Ie9UcSey+*MEO8ZF)Dt@1F~cgHVCU zd20%zwBoo-xOp^|GDJ6}S98(VqZ0PxKPrEqz zCdygIhfWXW_gR02kemV0LEEf_01Z8&~M{7pEt4_ zh``bM^&8{d-DdO!5^NIsQ$EiudA}f_1aYtr%eJ`?I&!LH7k3`T0xwPIF`z*_G5+Oa z&8a{%Z1r7!3oKgaZiGR4p-OU`x7_54b!tD<1M27-P-_wQY-fc;UQ^i;rd-Vx#K(Rs zBKoZ95@CNOVsvkxyaYr#SX(95qvgY81gBMPs=MxjiXwm6x%UHlThbus)mg|RpEzs4 zd+Nh%@9-SJh~eX&0RwQexv0?&?Mi|9xW|V!aN%jAwAl>C&wvIDCRh&Uq{>2>2`V zdbbBdObaRDwHq{{`f?hcGm!`@1*YmGZWB8Q@MWK{((?Gba)<&Gu@GYN?+p^CiE{W5 z9%Fy$e2$gD*I5jFqu)lw&)rL2!%}Jt4|i3bQ5STi=z7XD77|Sig9KGD6O6tmo-z#! zV0L04{A~oKB?bwVWHON&BPJM?tv|{~b*OkUr3~D29FYylSg6UmAB*CdF`tiho;ckq z2KER}Du;O>2{E8gJ9h^uh5NNqpG^~(bclb;Z#?a3GRSk(mo-_LcxiCr+Gl>O?R=>1 z#nE*+k(i>A0}b?FT>)lOpCFpdq05$@Z^1#p7y;mC!Xx8LRRGR8<6OleRWf)e3Vpsq zXpC;;6CMF}@#n@5$_vrIcQ?PJ(bzMN;<-Evi<^3yLjHc7iPz+V1^{nsCr@z6Rw{o- zTu{+OBQYb7L!5PQ|D8g3a$M!6k0%{+&Kc>}y9Y6jfhBf2zC(uP@oDnH-5(`gj{6pl z_ffuIfQy}=*DD!%tjxH15!e8oVhUU-SxH)c*RoK$`-tEjCA< zQvH?t2#>KoKEoT(4m)8vsL*r<^=yCe{uVedF}m2f`TZ5q)j1hN41D)p9d-zl+(<@c z+J|BD+~AMcXst#0G0*3z<-dBAWA6%!?O8ySK$0k!P*md4c*cY#Q%KNK#qpO)Mgiy! z>HC(}t&RiXg)OBtJwW(>FJ0wy!6!wtU;>e!*qJ|l) zK7ZHyy6w^C;#IR_-?7X%=DL6Uh-cc18yI3o@!(ro84awOZ|0D+7y>+s((@8NdnSVt z!4E%(#me*o@?1k`DjTfs6#8Tv|F#vTJdKUHa11l!!+CPAXUl%%<(#FA~YnLaaRq zfQvAyulsD({P*lteSudKnmW@Hg$Y=qTZje$%^6}@(H#F?Dh2W!-SNmB~arw z@`Rv1NHXuAkk>axcf@`y`3v$SEH;5yF{2{cfE2wNtD!XL;h;a={hyAM~q%4p? zXy$A&w?CY8o&Xn00(M(SNq8bm zbYr$s1(D&K(x}%$ewH?n`1Ox(f3c)!G32 z=<>dDV*_)OUrTB7mOMyZ-jp zrsRIGGGJ%awore|&!+C5lD(6CxX7U}AySa0n~b*hf+oW?A{n%z=?8udbR(Jf=gY9N z{SmyY;jJcTE1T^?o_6Y4*{BjyTYygqpajToepRPJ>@}|$VM7E``xG&<85cmg5f+Hl zhj2G($M_VzAm&!;jXcm?r%@1wl6R)}H_z^f(q0bDDae11=(MGxa-mY?jJt*gj>A@4 zy|q;xK~UcaASxMT;_3^a5vUbY+fFBvhB77FDxIF|K75<-bf4Z18u*zOToyRvgfukP z(ZTQ$v=|K2_gzyc72E1fiimLbhm2dz+F5C|h*hGaOBK(bd_3Ng0?=jQI#i4Ro25ha z@6BGj!WVxZdIJrAe-Jt-n)4+X>qK)l$+DRj?nKJ;!UCzK?Mw6`-YS>wjnkcQBiHf7 zkNyLFkPpSUbbKKh{sgf_hpbqc5AX2@+2HhSG^br#l#aiMe9mS%-l;p?SVS?vDZ@tC z@x=F3#j#9Q?V_1WZnV_tFr;ZadWStJulH7VHZ*?&VND&)kE-7Sm`^0yuurPtk~~+) zc?J6sUc-LF8m^dmk~J6v0@oA5oy1v9T~_={96TY#oQfW5*pqRt4(AgIPx0DfCC$*4 zH7-_$mZzIo5%VTaBN4Q<#A0@wwp_Z^4SS-TdJD(%_hKE6TCVUiq_64Rdr|P_J_suD zX6t{S-+R8%;p>iCsJN%btHqqC9Vg0~I;JLVRK0AXOn9)fK*vPYbVE@-;gs&ebj~kl z<1h62x=neBMadIre(aJl?lq-xFn-76S2B}7Fw~yPStLv|m33R0A*cN*F(8;B7;^q( zr+_1E!JN~;qQSo3-Ffui9YZD#c2WK5sT6;+%yV^C`p)w`0U>TOov}e5HVEG%Ykudq zf)FMH($U1#h1d)osXY)6m9E5MFH@iMEZ5nno667GK# ze@xgS3!&C(KY0pvqW3q|phz{0n*1pgRgfn2FOFBw$-&BoILIE;*uy`}}HRtw+ZO zdJK^G&To}f-#okd5E#^iudTT*P7r^taSRZUh-RQCTM^Lya8hx5N6C*m;HT5V&T-M* z$URasJ`DhHIEa7LGu^XN?{R6l2V2p=?!H+wjtXFGyoTr+_+r;U9 zxFM@#9Q?@}#o4Bp;DRt8Bc+!;zf;$>)XQKvPqcy2lg&cBx>+eTCqdQ!X;@@xq-9d%p-mA5IuLSzTGsF80b_|nRr z^VDar(Xs1_ty=&gM85^*0ssoqu?iC#PcVn%mE(!*h|b2 zKklN`WnuB>%BKqLK1$AJ=#ym)65rbdgQLdC_`Z{VV5xxt$)u+ib!mTfbhG4=bjMf1aLVB8==;Y$x+$kFZC@G8~Un0-m2Co_!VvAV)31Z^*iPU8!{1HtLC1nS(P2NR1B@??__Qhf zF;(WUf)8z}R3md@+m$c2!DmAIi3S_q_~8hm4_i_Ah*mLyQ|PD5F_Lc zCK`U^2ja?j&(Thu&N-^`BZYC*(xlnO0qjdV8!#6aiBo?$^kg2}u)P~Zd0rcjHEdPG zq40~%X^=;s!9e;UT@t_`RD3s#BL0u%>MWR1WHtBa(brt?sIvG)_2aY zJM!Wvrs6`$t*6s|m6_E56CVT~F;)aZ&svc|t> zK!jo2rl`IV)3+cCEbXqs2?r%jg{$>LQp)nhmc4%y*+-Y=bFpbq4X~K>tld2Xd}oUy z!D9A-Om?yl1Obxwgw-RE76k4C*j@gvN-G+W?}p#gb&QZl0;9~V$t_c43iPSC532)i$Vx0n zyVNEdH#(R`7elir~1`qEHju(|0^IoAg ztOcLik0q_Ck%4%_gQEsL9+5`TJ`ong4abN9SI*gOj8T4wOWh@ZmHK6V0{rpB8IxqV|Y=wWt0u4^}ue&u| z&TuM6U8)q%Wi>kDP4%`zRy$0UZt{33A!g!(u8Rik@WpnQdk0eo2pm!IZ# zT<3I!z~J16l)E<7wwzWa_G1+_G_XU_it~@B8&ZSdgf~H;mTL=DS?(8Nznp&;n}`r4 z&A2sA(I#92ev6l1nOfN3=y2@!phccBwZowut)~k z%o{M-aBcN8RRySu@&%q2B)NYc80^}=@Dwhu0!+86_v1LL}ch{MJ#1*jc-+d$xa z#6M%wam0f()`9?E?_c~Molt0d_&W0z2geTyv13^AN7mYrq>zR}{{TUuss5Zw>P|-vBj1*|A<1ZXu*mRf7g3* zlUjJc{ZtxGKPS`6p}@(rGl0gC(m?>=k@rX-ney~09;^kd0DauI)0rPUoi=PE&vO4QKqb$+5T7uivs(sSH`aU@K5?=s~WIF%yJ^YQJdYifm1lJFR-1Ev+0|un|sL_%9pb zbCK6(CW`S;8X&$2DJYwqnMI2Sjw*|QGfCHFXARLF2@!uhK;bGt zjBXNj5M;TZ)(oWM|3{2tRtD~ZEE_+e~y z%f1I{Gqzq5pnK?d!QT_)7jT$d_cM!B*JWQh7VoJUSuYJ_hkX9-13S@F+A5Piu<6*q zK5~CP0M|1X#g${+aZ)V8kV%?YF-|57^EFI3CWH-~+(htX*N_byf_)Hz)PGbacC6oG z>{;};XK16+x62-|^>rv#AmhuF_G05y9^G;FwhOx1bS$8YFT+?ZILO4N zznRVRJP`>^(Ki9PONgQ<+qSseElFG+!AgJ5Fa{INawlwgH+Vsw`|3ug&=BDl%9Y~L zSO#<%5k{kMq8KVud1o7Tdq4K+ghUCuZ*01h^+B5k`2}c!cs=766=LkPls8x5Ii+~{ zgCa0ZL`(}W_H#sA=I9#(aGp|s4Ii)?c}Rk5LutTrZqpFY@HzTQtC!qX-da&`lZJmv z`tqy?SjQ;Nbna@dmTSePuiLg#j!UREo|#)v_K4}wWf$Fc$|B|o(cy`I55!3wNskB8 zbsk15*Aj-E`>~w$@5xA^2o$b=30md%3DoSo2fwv$PEPp_R*?~nPcX`>P0-%riTn&; z->7>YL-E%1my6#*n^`+ta+CY59yotk39CkT_=_la; z!!(!DgYY>}Yz>E`9YDMzBz-D0-4}qMi?o_0v=ptl@2ps!_@ z&Y`8jBh<9S@c9h~7fZPu8pTc&aHyCVBkXGskE-OwMZ@njR|XL& z_KJE>%dI~pf`QEGDX4tyxg8{2WvOq|SwP!RI#F)b{E;{AhVS;JPkXa5;LLM`rBNN7{NtMj2 zWLQI4r0?Nw=x7T~R}tU5mnZ>}dSf;Zg1r1^0+*fJ4kO0~{n01$6B|QDA&hxTy=|bl zu<_4`yqq{BUduistqVKQ+=R4b>QNWU+%ur^@A?TL-i=BwKr8#e^O6H-938Cucnb7H zI!Y-43kTF4WXadZXAa|ZlFKO}1rm@g4*JG>K-|FB$b=YRoyLEt9`O8_SB_rt63|=8 z2Vne^OmK|b_k;VziEcLe=zBsV_?CpD_$!Dxz%4Q@Kg;$QlKj`8f2q&7N;n~MX`pVw}IuA)XW=2%9G!!hNF1>O9FOB?M z;-mwEF$q~-DSUsYL^>;Pk~e1rG>Os~C`&tXyig7pt> zp%Jw2LIIK&jwLA8{v_090ro|Z<-28U3U*y}uqCiB*%!D%yud`637ZFflP=w9P!lSX zXg35d?U{dU(7XKb*^E44roh`;Yzek5$YK%0Tz>AgJH4|1Oo#Y-Av1;tKbtN}le}TJ zaaYTZtdrysNGDtlndu4BZ=3|;#AO@@amL8z{qi@!DV=^VUXMz?gAyN)LaFr$7*4!t z#bw}q4aQ{{`4%5hr#=C|9K{S#B4M-e=t(qU-fyTr7SFe8~E*v zo`AgD{KQb`Z}WRFEl~0UKJ4^dm)$Y~7xvw;;}NXSu2Dk>ZDl=t_W2AEP~hOi&*3sFff13=VJfT71cCg@OI2UPkD{tTxMpG}*#-UBvBr82C} zQgSDxOn_plrhm*5G|4LcZ0&GYZ>Kz@gYU!oYm9G(Nl_8ffqm}Ff-b_f$P|9*KMyr1 z(zy8pXPs*Q4KeFzTD!Wcg9qB->8(snI2P1T>(wzNN;;6C^pYM)G?Qz+lkA;3joqN7X^}CDLl>_ z*rcO0Xj3pooN-5(eNJp}E1)Dv@L_`50hjQM{OgETL`? z1)DYAyG?BMaE)Rqwo{moAtg!9AfdkzYhd0!ny~jSqmqwK>Q3@z9H#20miLUvH&jHX zwO;j?spo8NW`UjqAJ*8bm^mNyVg!FU;VIZ_3l5EiMPss12NpLQp%o=C9EM$455?e5 z2D);xfEguk^hX>9Kpy%Y z!CLLx2(#kiIz0xk@6q6u(1G$z>gTIKj=U|-+vlv}iwAgz>nl@~-H1>-%lm(M*qyLT z-`wHK9lAUG6vLR=7+~MtZ~gub4Fml7XO4Bw@DXrGbDrXSD~&?<5gl;Qwo_RSKP*HM zJ->le)BwMDg8eLysXDV>lw8-r9eYWwb?m)QsR$Kj;TOjg)}}nNp>a4n!dUes~nK)>I8A zUc!cfMBn1H&p;;SE2x+OkJMQKPkM7z=8B4x8Pp|WE_I3?qb>}OLoNLN zR^PA<(7Q2Y%zK9l{9V&3nXFboG=*Q9HT@P)x&R)+CJSX@D#;;=LYsd<>Y}Am_I!Z3 zD9@ZIp=6lAryO->dq~7jr#|$G%76*PR#RkP4__e6w{Psn=Y|`CD1N&mT;i>I%uM2W zSiaIM^P@Bk;{=BCqe$}n_BK1CWVT~+8Tj0@mLPeYgR61<7F0>vKJ9lO$H$)i1y=Jjp}HI=N(`qrA;ARp zskGfxePCLAjV-_UO^^umo9t`!RC=clcfw9W)~|c`@K9-6z<6g~h&kYh9X_Qe;pu97 z_TvEQyqGYRZDM&kPi~iuK-)TXw!mct7;Fgudc77$Wy&<060*2T?hJQQX zz#Gd+-`_3`_l*1T*d+5Lc3kUs^nh* z{@w6ba1Njt;BY@oF6&+o3s06N-gC2B%eR7R5KEkbw#u(MIm9YKbD6X{>gG_{S*iL9 zg`0SQoBa>~4=w>45r|E+XNHHZAJQSPKAANjR_5N0N!2y>T-Jhm2>n8aZD+M|E%@mDVT%zJYw0*sr+)tr{$O_j>e& z|GQ(KoXj@DWWHpU9Z-L%(FB+iUA|tQ`%SpDF3A!16M8RrFsIRTY!tKnMr@2p_bsJrZa@eYlY3 z;LiZme^1}N7|yr-F6iiZgQZ|YVbnhA+%2TC*;$v%5N(<6-L1#-dRz2E2=0(CoZ{#n zu;&`As{AADlXVHN@Wl=XMjdDN%I~P$CEOX`49(F~7l%rv zD2H{s0c<`TdQt_mEVbRj^0)G5D%!s~nENoTh!`K_yH#wu?Z*bspBXLcU)m2yd&Xsg z0*z%Zeqcz-y6LQCBDJ=1Z0${ISny}N39>wp>U%K|Pb{E(PF6lQ3yvex#pt^NefNLH zn5Iy$My`v{XDe$jRur&`3O$JZb5#l52z2rZ9XPnYXTF1Ta1UZ#!B%F|elA?MF#I3pQ zu`XC4zZ$rfXrPauOX91ECzRn-vKi_`ZyQ0U{F>7qpA%s>(#%iP!-{!Y7ttOxHSU2IeiYEhAe+7Bni=I_$NdI z1^DIt-CRT^&kFtAr4l#gQb;^Z_e8&-)q*BWn%vFAVal#EREvL}?tb*@{G{|DJnN)J zftg+oc+Svmx$&Vb0h-*}{_6$+Q9!Q0!KHtF?2m)RUf7A4reJ=#AZg!fcWSpH$Y6Tx-?9G0SZWnDl(&0il988TXHUTO8Id$?YpWdG#s+el=wdv>pmou=`!MM@r?0*+Z#vCjI4gx zU2RgjNelL{ghsHm5{BO>4ys((o&FR^1G?pKvUe<2ah*PbZ*R~E6#0P^4m0Reg+RW_ z%$-&ueHdsyb}r@|Xtp}~p9}AD7j(ULuZ{5fuoBQvTNIUJkMM6Q!G6hrs#fC5Xy_7X z=OsLDTQxNrk&qlJ7xBK<9XhX+3t#h!>#uFEx9U;Gc{xWuqa@ktXS^*-Pi1D!wwsQ168!t+}lT|%IKLll#%cD5J+1h7+O z3!wNLI(inlJgQY$y2!9yBuP&H&Z(Ij6bIUzqCGO}$l*MxpZ2SNBWFoMc-R2@$<+@8 z)q1VQCFY+7eh>)K{@BhS7#=*w_Vng-9Uk}b2CNUrbn;ESd-I;+U~y7R0EZ7ICPx$G zDDaueaCU~56nKRthpYx@g4#}*Z?Fy~Y=K_p?*d-?K4ESY=C@+TY33H42dW4s8l{KH z-zTn%dLwfT&|H6insMYc;fT3e$&}1IBYns{dpn~GPnzsS{$acOx_K9@VLM%hHd2+l z-HMb`=7!&r^fq&F3#d^ar<9EN+RQ(g%_Y29E}8zL6v}dT9WAwdleyGjAVwTqO?37V zS?#q57S?e0x+p$xV${G01E+BE-2A{1*Lq3fDU7?3*7H zy|p#&Q@$`koeeE4*1b-;enq>otg+XD&w!v-4=6L0(v?DYp@fsdN$$_|=0Sy=Q)FoQ zX;Og@jRY%1U3#<{!oz$;P5Fj)?xp};6-Vv;NelI`zoDPu5S?(_!gabl^zQIoH*3yT z1p`VNq{Zcb)IgC3La{w)`eI+m|9!%}67dDjB`JE2$qXI4e`=jqf2MT%KD0>rsy$RS ze9NG>FypeLN={<`xtkDG`_iebtcs^AP_Xqodm!ZhO5L^afJU`9H5HT+#*0c!kQ_J) z|JyC1m)k9zvMC_uS78k#CJng`q-zCaj0?e1DY2@5FRbSj78hUjCA7-x0nL+MT>kCq zhpkfBZ;DK`a1rnaSdl%Y!i?Uv2|Kzhyy;k#q6gr z0Xn36WFTgR0m^(29{FMNpzij+_z6~=P%b+&C%LZZ)J8` z@Ah_oY8e+?9D8l{9U{$r!An!qCyZ6&NbI%OZ5ohQ@H@pA&L5Rpw&S6_ZR1TQg5s?& z$f0EfDHHd2|5Wm5&sc!rEiv7N}5ncHYZo=7H^eAR7{7}5KsMSk41wI3V-A@XC z(lU(VcNxlq5!JF}!^0_V5j%h*7w~17sA||E#}iJJ-)0R)+zSL3buA0)NE-Pi0LpU# zk`6M}E~5=&Fq@8%zo#naIMHGnSblZ8tA&;c^&&mzbXE5A3d*;IRu&xOVNJ}y4EH@v z=58yfTt`Z%bVcJ00MLHr^Y?Ns@&YG+-ms~?V%K;HMDrq1z)#*AT@NihA~@~mX5e^> zE{v0eclA9CU>}A2A)1fM+0gfG8xNDM2r;=H@+x2&@1+%mp5uRiDcj0O>l&I@5kl}C z&KdoNK^ZvmfhYe3>(U_k2O% z9Q4lJox3~(g8Yk5`3ITp*M;*^2*5@=^;jX`x!j_D>mx0O@ii9a4I&+08zR@e>}H+Y zPPyw!{4Twvi932}M%tng= z0=Tsr#SUbTOkDmj5`M9n8%+g&j&~{Q<%s^ML`+55!haP^HVWtz3{!H4r@60_4ts1w z2nh;eSKoi}1Eer%eYKEUu=S`UFQ(vn;5z?_G=5bu3yu1kyo&;w4Z{6@aN$H z`pG4KOT&>(V!zy963hKzsfWYcNV^Q(YwXK zZBnQ`zQcDViX>Zc_=bHLLVW8(8wd&UKzW#8z^$(GonkMll>t-bYD3VKnCe9A!gc-n zsBnS5%$Jin^nd(WQq8b`46~=*I5nV*0V)PVz|=XNBZQpb|BE=V}> z)8nKMMy^)*olbmt{3@olH#tmnS>KzAJwjo62BWwr*1h<^*);-RnGHHC2O}u~ft=%8 zM^Xk-G68R>YjyoThh~ncX`FeLz)%CiPpu>_S4={j`wz__(jHZRs`~-YDtQOfV9@$2 zSKV#MwTFK&A~zVKI{2o)%a*u=z;M2X9%=zaJVpgIKT^|HS#p_B+!c^)hg`QHA_xyW zP+&L>@1*LQKm*3)>=hVk5n-5EH^9S0Xr3!vpv;qhM^gq0g^lA=v4#l(9@FB)(RU<# zB^S$U{--J-@(RR%Qsm+Rs#0R{MgQIxblUV8ej0($(5I`4CG=PPU5YBD0A7rL@B17w zgaf~lB|LSjHHWfi<3%s=rHYMn`;~_)6Ky0gLc^VN{-Qeny~`K&2;A`b$*1KFjusTN zv%vc1LiQjT1-`4}u<_8w_d|bvvKl(c%-+8a$zlYpw}Bjg<^k=HeQM565-KC;fxft9 zuca>2h{H2Z$`BltWALGm&fh(cjKhlQn@~vhpm%p$R6;{BYrWUs`m~sG z4VT~A#vzpkd8WN<-FT;S8lg?1#)UtYU?=$9w8F2SPmdC`y`-nzlee&y+MMs3{6k?o z+-=eN0Ftlbb591`gy1YN;Y4&Ho2d-}tW)1ZUEX+qda0(Zq)TlfqJR64ZP;3o%RnHQ zXhIr@`DtT#?OYHUliZz=Y;+3eq*;59Me_5aYl-!vY?0{%m57Z1dL4v^-6Id1C+_WKsu3gL;t_UmRsHzWBX zD%F?fT)KtX-Xmm<8mh^V!}AH~j8k6cY{krbkq$*VC9Li`?&MG19)xZ&d;C$(8MLQnW^IR;g>9a@gtPEK!{*J}glyT#Z zE748OIg0GVyB=;a8^LH{iL!~}T7&4o^6}wF} zYq8EnHj8t+<5KxV@Xzq=4vId0Q3ubw)-ODy_yYLH0;f0r!vop%(H%t$<((pbGFU=3 zH7SJr?Z1(l7RuJ=iu_6teiw9~&F$=*cR7VncF10^`PkbzmzWQ)Knmp>79yli7uf?qzVn^&&LSn1 z@MN>hIE=MXfM*jjTm)~WqqcT`+TO=z4$RgjtW(I`cd;fvErhFYik$p-=Y3a#eB=%k z;Y$Fa`w6!H_zZ1QBT7termS4`BuGerQ2vRfWCQpo3vfF5{8!d{HM&y%wx!NZWo#?@bU=K6GJ-1fB|Xo}$8a~T5QhU|AV|(+VF*Mi8ZVjnSG(B1&)Rqw zqS0?_o!iHaF}@+o+s!q{)nzYp5M|0Z4tuc|5s|NfObtAF&>jI^Ga-uJe|gk!f$XR; zq2l^pD=Q2KKHl5rHvs@|esSJJeIey}Q{`x|8(gtr=<~vqY??xU3^0Rvc$FBE8X8M` z`l>L2(F*nqXYQns_SBLKX=s5ExSml?oTt~=#`oF99J$skJqY-bUTXgl&YQ-5(khu# zpPbeKzA?K!)NkH;7njsn3EY4-mQ^asPoWzfLM-jf`RWM$+UKnuW}V#rK&o@srm3bJ zrxUh(d-8zvjz2(uHrzt<`+prsJ1Z3QnX)$!d}TF&m)Ed1%53UnozEDL!jhlLZQq|y zxaV)9#)z18Le%g!y?@Q=w-orv+8>bv^UolRQ(F`zbL1$lFT-7e{>~kxABTx3!nbPJ zj-sN1hG5%5k1-|Q#5V+cz-{%UE%0x=|Hcmlib3S62Yp|E^?3a2yW8{%T@M}u3ggXD z-zreDBo)9|llx}shE^o#Uwkibw6W&*vN2#LA1hztP?0+}pQb_uu@-d2Ie6;su z{%|J5N#`SQ#fY>Y&)$;3b%g8om+y*&Sw zdkQrHRz0FpZT~@ThDL6LwIuu|HE&A^UT2&ky4D(fY z7!4BN3uGiUw6KRY;N-VBG0l}jm{@=540;BPLs>_z|Ts4f$2VN7fOep z^J#N7L8R#S$|P*F9zF)QxoDWr2Z%g<`<(OPO_7Rk>JNYCL3njeC4fftk2cNJ(Hl_7 z`xuUY`QoM)o#6_1tL#VOanJG78JYQ;vjw$K^>8)9q`q!h&tz!snIz5L(lyyHocHS{ z+)`42erjUS(%){R0=paA>9)3#Q*!P1;zyHH12m8Amzp9@Rt4Sa33ws*aO0-6py8Vh zmSPfK#f7b*@wZpVZ$}vlN2h@>q#YD$kMwna9lRXigm?pUjySh{f^z<(O{u+QxU$>d`x(HJ{=zOL`{DCXU_5Xk1=%#CF7#k4W|oxz0=@(gH#PEs5;1! z079N;SIs01QY}Fp=XsUUw~KSUMzeN~{o>7}qplkVl+hN-kg;_-HCv05c}|JUXlr+W zI%<*QrgS<)sJEt?`{_`*pj^)~X?tkB7;+4cObbZnmHhd@!prV50ozdSIg8c!LU-cw zq&NlP>8ya4@P(;HUPVS=9XYo|v0IjJqnjJ7m5`Js^}~9h5&&~V2ZUz^enO@ygu2@o zl!$!IT`VNuCY?0U3pm_^Fhq53lK9DgDqIWPP%Et8BO)F&Y8NRD$LQ(7VQ*a>-wKM_ zxx;)M!&%?O4odVdow9S6Y>*9Sd`a~kSAZ`^=6WcCAz!EE==Y&-4$+CyLLg=#N6;NR z#22JUgr1yF$O@m(Yw~#29^2c0`={Y5I+hrSi1lBT8AL)dX^%B7*K5C&#K@6L0oT4;CYe$Q307>@6+^OKG5U4Np#71pPXE}!bR3|eI<*+;esjo?{iDSiOY&s}X` z0)ky~EZd9MmN5+0dJydSud=d#rSJ1GB@KI4f*litMJrh&q~F$*84%O2!?U@MVl_`c zXTRGmQ6QUqkfw3{v~0vL&a?e!nZTap?u|kp80kg(kr)#hw<^lU%)nvF!uR3@v!Z;)CyL;t$Jlc3nNv6QvVEzEs^z5{ z&279S{2lUpJZ9S%t)#sxfna`9^F-_~`Oz;-+Z0F>m5iISfPqhcPD`y)+A5wbt5pM8 z(yy@3dh=zlO16Y|!&zP&;h*jhG8Yt{79`&z1iIil$12ZYV~0Af#SR z5Q5ZSD?aOy!@5yV^h}SZeh4Jd%lk`?xq|Fx`)8Zrc8wix zcwut2#5?Wpn0M!BN8X|u{mtYmrya;j3h7(H{T@PYIfBV+ilJF>fe8S! z*y{2N1|JNe0Lrjdu&cYhijFGk1881-4~6lCVf%p=36&Hy3yjhIJ1L+~jh~wdZDxaG zWge!q1+$bMuX?K>!I%WBUz;G~ApfY3J3r5eQU|Ah{!ZD@_?5jJJEla!juci1NC&0`9a`iGtMRrZQ{ zyA?!#b5fx>``(zIwOWeKugxHc%W?mq1As?BD9D&Hb^^(sI2V0>F9aPp6~@f-AwY^c zbVI)3vi;_-w`n-P{-}H(v417(q5Z)!X+**;kCdv)3Fj6aX-GP0Z}P zC&xG%n8cHpN+3twIeNH!=^WX`CM8gJs1vGraV7-=N4x)~F zH%i9Jy~p&5R6bdZGR1yr|~@}Pbcl07|+2U`5Wv*xjPa#nzVW(m?55OUR z&tOQJk;f!$Ka+7YyO>grf->=uCz_i8l#eoy4syoe5{e2aX2u}{7KHt21Z6*I0jbO$ zNNhdr_b*b#PEkMTtx8v!Q|9x`kDay#CT}A#5Iu@HUt=+6HmbD631D^9+->wkscprZ zb`j5Ym`pY2>3c(JfK0@(ihMzCLJu2%u!}tEccz)4fL_CSZI24jun{Iblzou-IprM| z)*|lyIfl}k0PmA+aU*C)3+N+ZoLWH${S?1*KG2X4s;U~%H4nsiYr$scR&~>2GcM+Q z2=7byAWj|(Wtc1&5q618Ke~+eo}-`n{SO#uQ3%RRN1+f{7&2H1$aDKBV@4W(B=w6I zBup~`g!-?2> (S=(DveNukiYPn>i*+CreS^N^rwY|6Y8QAE|7@VPamPR7^ZsU)v z^HU#Iu)EX8;+YF1W+p@QO*==F9vFMo3T?z|b>~GiWhD@PF#H^Ofb{7ZyWaT1%5%h; zPgh1LzI+rHNsWQugvcnVdV*WC1v_;5vwpCaK_(!P@$PE=`e}TjG3u)td zl2cLGmU>EscsVI>1Qf+L3DJHI=80822)nA_wPSBK27(@d?LOKXh;I7$4)85v9^0R;M%k)}( zHJq(FI&fQ&Z@CsDji`93#KcFnSG2q7$jE*LuRxoi7n)oTz*(Tqm2Pye7n^>K9sTv3dN$ zMgo&q zQ}2Gr!yh=I-I%51=jGfuc=Bd}KZ6jBrD^)wx7_oH4NihX*41OYAr`^S|P<6xh zXZxHKw&}6XYLNZ?c_RXp`wzH+o120)I2>V-6(UoMhZte9UWQL+evDfD$xRJ0fI$Y) zxbqb-$`Un!M~9r!+F(D7&t~ct`jQW0Otb-O7_c8G;1Wsbon<)X*xdf29cmsgYn)6! z4U)Zo>G_~UkfD(734?c`cJ_mjiBGn?z=+7rsld(OgysOrOTALs#(ulDE;XHH|Gox? z@^62R(_1QH2L0qGH_Iq+ODmSkdEijyr4_m*3!_+r#6Gls25V!ujPm=7#-EWW21LF+P^+j=O zYs0z63{NwlllzK?Uy9cyA@zW)77zk|4SIizPWnOy?e$@wG zD&Q(Q^O^Jd**;VTOt^t+lcrfv0l|1-I*V~UPtC+;)W<0SXd&|Jg*-jY(M-#KkHR9R zp(GhU-A2muhzcT~x`^KRG1h{nA1)3gRh_-Kg$J5p84`IeVB>Ehl>&cea$=}#4o-r z_P$3ilFSMC{f+Fj`MbMgNcr@CZxO^=rP&~ATW9ZpGpC>qh-n9{7z6}MHr z>gW&o9UOy|idg-o{sxFQ-^Fl7@%xIgZ+j1^0{&utCr^$%nx0S%G0eSbsmwlPk^_+Q z_GSV;)G=x^HO@)5_$1ipqg^;X9|uwpWe

_M{!rf^uUSj^$wCwm_@#W6yj{scmv#R5Y1hBc;#K(? zZnkj}0kR~bxplH~=3`245_c=(Vzd=8rgEaDrcQ4?La~%B#VNMiV$}x%*fyP-?J5H~ zI_2xNp23}^#swuX3_EU)XS2R`gl9cTfD#s%V8qacYg^_We6yzMJ7XyK8r!_%Cf zR93K9QZV4L2@On&fI>_o_8U&@rTe=xUXntX9}kkl9Np(Duz8J(8;cnx@BK1XSgy(l zWFx#a!;~*z#hBJAnfnCVxVpVujF2*fscRnI9aGwGGFP$SrTej3&k>m9QLW=L#b{TK;CE;xnP({dD{ia(n$}^cX(1wP$btXVF>%G7C63ttaQs8>{u!GhBNgBke!+z zKZ>w`rWV{uDZq3X0m^>uHL@>^*2CuX*hy9b{ntfm!&X82o>#&XJk z7oQ3{mjW!L;{{#&{nv`L2cO{8FzFl!=US)pJGf zQPrn^A9g%g$6aDel@l3TK%<%sXRyxILZH9L;tMhmE#Bzxxs{vX^$lCira{f=%7XhH znY!sGR2XsxFg{a`WlO-4OX(O*aFG>5L;V{MZ}085R1*Qft-m5_^rj{?(Oy$dCBr@$ zW%=pSk?dAn4C>I4pDmtnM|t zI$CzLBY3Q?Ku|?!*wpx)K>4kdUX4CVN+(SmF~x(Xp)b@nfKpdbqU}%Q5Bvx|p*%T% zI4yyfT71A>o05`W4)h&4fY*GVAQ^UT9}+Spd-@%-+q7Fdnff!W3JAv^my<(=vJR#T z{z%%%7v^Z8wN;S(4wsNTZ!!>q$NK#~h$s9?-|jG195>81iqRo7Cxsj-gH6QeS3*Jt z-?-nrnvP8Kqk}uVZc(ox)w9$f(aOeu%^8%2n->B?`Gb!+r-Ai`!}7)wvdV8B#djJ9 zyY?u)wN1JKe6#mR06&LaYx-MscXY$?*KSHzsxY<>&xcIY6+ae4kz1KRRBM&im}bHR z5Qlefr~Eu30z8oI)u|kbQw4-7k=Y2{{CF8}x|DZVc@N-0kdwoy1jv?=kvBMh{jnx1 zBD$*|;FiI9v$Vt&3~r9xrIEi7sc7pAJQ&^np()*!aDFyc8a~+zUiu~E$eZm4{FAbvgNo%1d0zA9C3d) z1X5=dEPFEo^-1aJTJ0=Qzj3I(wSj= zNfjQQ1U20IXn_bTaTQaRTz9e9s651=|@+ZwF2zcr%(Ph z1)Mm2iv7tvz9;bG=T@yYRK-HM2hgN)1_o$WGsMgO(QDnbOe5icejvVFfELofr*qL^#u( z7hS&`S=DaWAcoO@v7^P`^)(kv4O5m(-N_*+%w&rxGrcu`9^B(ILu%8kHze@=-?hD3 z2GtHB(5|uu}r*exw-`)%|HBZ)j~}v z-COFs808y(gQMLmb@)l`esi6>M7OZyha>9#mf%^=|K{v^29c& z09((SAEF!1ri9bEgmD~Bfq{NT$bW0z6_$mgJduR8`WM+xh1OTU|FrzsagR~KyOruYr_{N`gb zh5b)|cr}3*J-ayibkR6=8vi_a2gVl#CN9{?V~~qF*Mh~Nj2$r7SLojUh@9dupA)9< zN~t69I9B}R@%+a>kII%01U51x&C}rtQ0~Xq%JCULLFd_UKYjSxobL{qHEF+iRX889 zw*-N0;)%gZHYPmrGz2mF}C43G$h)dPOAatv$y_9J;S* zRev7|6~1SUnWd#k<4?%N64;WZahk){&7yY3D%nl%KE`#qN1w#S$iL;`0rOJ504urSvh8Pa;!nb$81ux1fT(44JtpznE*dh4yK zgDZC~;rqQ>RoUw3gjX+3q&Tl@<~4YKSFUjlS(8S(M#?hMf2xdA)1wb3mI+vDfh#s< z|Gr(to-1+SW*RS=UCFHO5`c#Xdn0z0x-{!3KBTj|!ni!1$341=(S|jzfY02+qk1aM zD_(hA6rQ$M*WTV3^pD51bZlGm}-Z0rPWY2+!?0s%sq~OU(n}I zZrs#D&@|v$$ZUFrRulT{UU6&|_%dzz@V>`hDL4C}V{Vdt$}&i&XVVac#<--{PZk+6 zd@51;lsl8FP(i3T18XLIoGC$83PD0FhNO&~t7k&UQwyoJw5WS2v+kGz4}P@utL~$f zR?ww^`90&&tr$q*`NxPLlvK}u^e66hiNHqN+7ojq{kzS$Uy2=drCXM0ToC}-?mpY} z=#p)Gl;*a%BdE>D2P}TXs9JZj)wUFxVDwywNjg@yTmcO{w;z2;Y|xN9Ed#@X^$wg- zdS%ZU>r}LQc%|KpsCylX#O?V7lR;}Bb?t5wUp}? zP@5`}fp3kcPB4e`oDztyTmJhD#~_~{K(aL^}jv9^`6bjs3B-8tmCQ%5!>^ zAW>auYlbFT@wpe+;*zv~j9`}+7aw}ajS*dNurWaV#YLG^TPfaDXC;B?W4~yOGduYq zxO&MlQwmpfK_YFjbqDpg{A@pX_tR`W$P)vk?FVJ(>#j+p4WMI+8pG~;J$ei5?B6-# z+nw@a$#%XCp^@c28(VX>@O=j=0FW-}G=^=347P$y`;gZ@uOJwI02e^$zlRKr91M`G zY&ZkV=h+yB{JS_kT4LNLp9o4iFgeG`ghK{3`6F-UBVQtVyUz7LrB z;xJ0X;Kdw&jE#&R(z5wPhD4S_x&56A-*vA_KsgGvrGe83bj-O@zrpf?uIKt_xw(;X z$Ykiy)80C1`(|Z%V`zA>J7Q>v6RtN3t%Dv{Mgg>`%Y1O-yHkXjKGZ@Esso0`B_6;) z<7356pYE*n#xt!@VM*SRNld<^7RjYE(^9TC`Y*HRV$0lbAexgj0K)c zEtoW#ni$v{9F+GKkEBCU4T*jNk$vm4f8MZEbKttXJT%V@_+pA?CH>R5()TsIw6!E{ z5h7W>SwIPPozWQ#H+HP}^3d>n0s^3O}QE2j(n`aD%VqD8|!V)JTUP zB&?@@TrBX(%Pc8QSA+E@qducosNo4Cc7A=S_@GP3T}o<@=)^Rit8kE4I8NzHF*=I} zc|=jlHQ)PjF5Oe1xyZ>`PJmF3 zLdn9q&tHz&mW!8JFjkebR8YUNcN%4w*OlpiHZ3tF8IVt%R(AF4u}W8aB5fwbYN2pf z`awU`XfZm(@eon{sUZQEpWJdwRa5ZFexy zrx5*CzhCVX`QuWyFx;FyV$63mJ!Hv~f8P7y5c(>a6(}00I^tZZus&A#ZlYK@$ykDa z#v5fTIr+>%H+^!BIT7WVv~=zH zQSK+>8u~PrqoE68wV2fue);o}E0Zk!FNlJ6jNyOXCmc)j8vb~xJVT-&8$7rrhqt}H z>80CjJJ;;fn93%A>+!)JRQ3=hV18qNXSbwc>FR*Hc#_Pcf)FKVvF1nTb?^yvZl!H*gJDNMk!VQG>;_rc7UCEPLz`=`jX6om zNO@Y^L`R*C(ZAf>yrF|-VndUZGhyld-(E zvLa6Lz@`g??f|sr%?!YHI?kiZT$1VZC7hqQeWF>R=Is{yYtQN(DgY*Ll}m#odLm|s zB$#+tNDts5mt#IZNNLcgGQLjT8p2q8^MWI8%(w3rl?Q3~atH;-tn)K}(&{pewq{3H zcJk0gvSg=@i^sCnqeu!9;pFc-gj4dwX(yKaqES%cG|wV{`qd6;^zC&=2FN?k<6bJk zLmP=C%d$|YQXM8tHZqLA$mCmhh|4cmJaai&fS7z0MMPHl_xD?NBLJELg!zz^sv#FC zMwPE4FCUSnLRAJR+qu<$Zi`Hs#zt*eQ}(O&f##(zfk@HGL=0G0f7dRk9<&tqF7vM_ zWX^hL+O7DEmB&zADZ~nwhgY%zt~H(xOsOP)nuS6D(pXW2mh(w1e3qWCzqj3xjjw&T z)wJ5`9)G$Ga#!a_R=nYux;Rf3^jDtZcT>@q~s%a zPg!2G6q|h1jvL(pVsQcP#53j~8}_THH<~`jE2L!#xu%ka)DlSWVDdq!SXhZ7jgLC< zyWzXClrgCT^$Cb?FsAcDt^y+Oa=756nle=IjgY>w8`* z2ZaK)-F7Ok30T{Il<%P+SDnW%L!crfFC!8rik1{gyxyD_&OC9quVy3;b4_txJHY*0 zn8WtSSW7~ojwz*-V9NQ7S&uzan<6{rHxisEAwSun0VKJCH3=&8k^1?SR{pgj{>FAu zvdHcAZId^tFVEfbF6Iyt)lwhv^%<*`43&jpRnb?G7t~~bNRLfd#mwoIdea#lAdfYi z+Oua9$cVrWdoc2l5vLrv_tXe<9gPn3AmE*3w1jim@9U`tlq8X|I8OP8l{F2hx+1oxN7 z1S+0?nUo7*O;3RsZl9{uBsA?`3lAdV*ukDwE4RB;V*Hy{Yyx`69V{!J3d+3s(1jn5 zwTqiIAXQj?Fk+hsgwb?{G%XpjZ&C2S80>%GZwnEK!oxnx@(hfWr38#E2_ru8$a=!ke!rbxY;-^>M z(Et{rACFEn@G<^6)}Bi`_G`r^#IIib z0t}PIk=96_4WW0Bp|M~C!^I_zfBv)pgOnTgQg93ZnCllAFezSgD5q&fw$A=Ht4kiz zzmf|j+uKtGJFBJ4bC`gRdYbO>J9~U(F&}3J&s&%Qn=;h~#VLk9NX;Ey4We9O!_xj# zCh}6ZJ>)cm)em^ff4%O+1L7_aXy3ShKZz*}D z)>763SHz>5**nr`E|-TD%=^DNX6QMaA+O!?&B1bN4_;%qlL6j0dd`&++_Q;&Kr(>1rM5$%(Y!yuA(2Tx=_1HQ9lkJ`NQ!r zFDFWXv!ooJOWSaMkdx3RrS0rocHr?Eme9?XjKhE?T(DB~b7IS^Uv*RS5ca;}^#+lmB?O)$+<3z`w z3S}N>C9KH#{VTqCQIi7Xn|^b2r(-AJ+3x;}!;fd?AIJRuJ>LxzWZ6aNIxtasT^25$K=bfBX-y`j7vS7v=gN|0C<0*-Wff2h!Z-a&7N z{A&yUZQ1*GV~SVkr#%1XKaL{Xrsdy?m&CK}e{KH%+C%@ktw;4A|JVNmP)i302S22_ zj9~!)Ce{Ie08mQ<1QY-W2nYZyI15Vv00000000000000R0001YXm4y~LT_YwO>bmn zY%fH4ZeeX{V{lxr}6K9e}(@Q`s-iHF`tTdtpEO3-xL2v z{q_I)_kY{Y`Y%^o?9Jc*iqQXx5)?TMfBj2Swso`rPq)styx8gf`(L5IK!1T@_|NZO z|MK=RZh!x4v+whN1;OjO{`Ertby{l>fglKc8~^WB{_EYha$Ehg(qte@6 znWyvL|GF(lx|aXb{cdVsK(hBE{Xe?Q`*!}@oc?L_zxDf{$1u%l-tNDD^!Ly4{O8gA z?LR8K`0i^uZq>97fB)-{?rVGhpYXpx@6SJfp8w0+*`HqiQvCg|`uqAX+Kb>ni$8#B z&_4_4FVFvac4wLI)B3lvs@{wLJ`nKV{|&7F{ojhR+W!6D{>;Vt(@FdG^5+HmpL_iq z@-Kfw-VP!9Kg##_FWP(mpXGc1`A3ugZ0WuHZ%zMCKpkuUfBql;X#c!1Axu|27nne?k5y6k&+`7wo?Qi2WxVvHvI_^3N>E|8ar+??V>*e;8Tpe;`}^ z*Z;OVU$~(E1RwOz;(z1rr2ccSD1rS8@@L&h_&-V*q5h)%dE-AW-go~0 zf|2?!|Gy9Pe{9|VJ9}iuzW*<{V`%q(a{Z6{|9I86Z}Af5|0nYB|AM*xzc0n#P~zPx zF#Tse+5kU5z`r4_%m3iw7yZBfWnRmzT+fo(<`-ip-P`G(6Z>cDf2zGS{bKc&e|Yu3 zHfve^{jWv3r~maIO@i}S|G%9Ql)xg-iP7(jo{bsRb{_VGQ=_QTk;yb ze*@~D3S7i~!bpFwNa1}lZ$=8#3(MZ?nh|=z4jgPWe{`8$eHcV15N{6}jUN;7%F!&h zRbRHLji;n-)QNE$wE#LT*mAVdQ&9_o@RU1b(zdR#9I;;PHT z-D&U_W^5bB2JFx8$?lK{u`1<}ND^>ARfOEF*>X{YBL7M#FR{=xkVy_GObV|Ie+^vK z(%k~hjBew~!rPQP*u6m3U2XUZg3V{syjuF1gx*%#%~tCLhR7^U;IjX{|}iccE3CQiq7PV$0?eM zlStZxJHfD)845oYxVf>XIeW}m2okI-5NqtZC|vh7UYmi|dCtLTaNcGQE>(f71%Jbn zQNV|vvlXMEjLJlkBMbqW!F+)^y4A4pQf`@Sqg* z?MLPU#-rV#ZN_%8nUYOE4MgP<(K~w4{Q_FqchE_)%g_XK+Y(yCVKsvcj5RTZo~akm za{0i*O+bAs>ox|jjkz}>8?~_;6^+Q3@$_33nXuc~SV2bOx>_NIfBkZ)5YjGG>p6?V z&Y`C`8uIq(57xo7@jHR!4C!$T6=B*`GR-M6tzFh}C_cJI zF%n%o>aacY?q7TVe#6MD&q-xDlno`CVla(NYnnl2agTk=z~Ta4$OGZp3;z%|Pd2$r zlSBM4ZlQgT;zsk#f6aU)K!0tpbbt2S(6*X(hQx;@5HTcw_OHmwPnncbsmf&4E}Sc{ zNxqY+!Jtic`NvtX2k8#->84-MFWWzO+X9k#Qku#o_wFe+tBupN4q^h*2) zfIz&A4iQzON8dKEPbnT)j*4*3fS!^7j1`DoZ!@%?U%x`#vmzZ=W#dKEo-7Vz>XDhn zSQ`4q^aBytaS_sawesNkV?)XaF0EAB#HFpJQ>+BygC_bh%XRnkB92ZYU0CjEyoh5H z2faKF#@Ul|e?owg4yG7>^p5=8s-WU;I$iI&hpIaT8=XiyRlI|w`RmeQU;)KPf3!Ug zN9oRyO>My9o69UJt;04qd2Q%Cj@Ep{y13b&yfAo=8F5WrY0HPmzHUD!S}4x<7GNK7 zn~Kn`GUu^kYhKxIfoGEKjM&;IX|VV-w13@}f~vYEe_?>bc{nV!CC#5Bj$FK{)Ir?Q zJV?>650F<9575Md88q`&+P??p>@5(TGp@H_AK!-wp{sS}G!A7lXvf)+x#@&Zz^@n{ zksn;(;ienyN7nbSa!U~lck1RZv-U%#T^!}_o>JU6`mD#v0oDPLU#fEP&z6q7OJPjH znv7i_e@VnbCs=90h$TFOOn^Vx{cno-X%;b47-3K@SU9<{-Y(tWHdMe}_wTqr@Tt~3 zKpEJ%uE4`Q16-co>vKTV&sfnKH?*UzFNHUmep7IWCXmUVvnR2=9s_`>X{nVc+#+w& zrD1-9ElkNVrzeL%)^}edUNJu zEhmKB-^@KMF@A-Pf~PNkkVYu>Ss3vT@bF7%YNk14Blb~o&!I>bZJ>lSfZ#6iJxo1s ze{SsNz(Zrw^5P;3!^ZGzl^KgelSTavp@0R^AI*9V%Yw~GHuyf;7%9Y{(p zL3ljwHjj;!sFz55zPre3V;4)l0hlegnyh85sXkKx{1rY--hX8ar85~N$;`H5Jy}`) zrpxQDj!4fE?h1q&Wx8bHqL5NvYpyfv-bT#D>E2!4m}IV{nNVo=B&XE>pki>Ye;SqZ zu0b}=98_D7S|K>@xR}r4WULYoUk`yemcKI5)YgQ`SMqA!0Zk=!1Y-D$l+w)cXyx`k z=rwR0q|P;{GkhU3{p#^yy2fN zGbl96#^TvXd58f$Y&c>E3-&!rkI0TE`-UMp0I0xO{b#L8JO2P3oDeVX3;I8_Th*qI z3@(VP053usV7%vW-U!HrkHpi>wL8<=waENZ2k9|N`J2w7#*XD3ll!ASSZWd?vMD}q zAhDR68VTIe4dE=3F+=#1e_l`ZV++bZxT1b_k5YUNBvrp+>5>I?<;#^I4sjZQ&vf|Z zCD7v#^zLC7rBVk>5J$Ni`RltME1ZFGb`LXrd7(x|R%j6{ zb4X8kwRb&?!8%r3A&1wozaFW0J<^$8!=BgHCjkR zC_?W~nAma@T1{rmnr5y|8(kGq!l%Q!fKo4GzM#AZ2MC5wv-uvf=HpOOBELl8yDOSa zq}39a0(0P~_zajSzM*g@4#N~?TG~I>x8ulM?sH?yt)k>p_1To>g8i=c_EdFH#(Z8j zu}Whv0c3p_AFc{me>BKB{7oH+#cklMf&rYAFt(`V-eAs5bM4XA?hSvPe{;dnDPKt`(8v`SMnite zaG4qk#aHf-=bKj2yeC)Dvz(D+ggd5xpbmHz+wFoi5)nJjl%ztags4qA^`v)ip#e zD?}M2_+j)}e-61BvQL|seZ9^5^^4Z&m8i4&S<}5?ajfzTWARlJUOX%;5A;Jsr~wH( zdlxo%b--AFx|VV3z{&!6<+=hkJbh&=kM((wwdcorP%IIWhZmDP@o1q2_j9~Sn|P{v zDBSqds##v~(g2>CFBiu4Mw+K?uz^lUR;&NPQOU53e?%rJ@vQUvbQW$dSf!iW)m|#h zKwy=(ut&;LSMC=U{BXE*IatR^Eg3?Qu5=Iah^F9h>#v$ch{Wq@J1Zn-UFrxjJSNqO zI(Nu;_8P(sTSH$W!#yp^8lDzBDq~y;4Z)N1VZ4R z2ehc{;@~qf>bYE-GYk9^bcQF;v6f3Zxx^i;e=dA|V@ouC;1GtNoQe$*XLbi~a)?_R zAWFIqMyo!3hq%tuMf;@7iE8PRecSVtX~*6?!RD=fC%Q{SQ;+=6`EnNi?OtD$sV;rE zDK*qUeAZxb>TLtOrYYn_>ha+b+8b2E@>@Tmb9{8LvlG0`2+JBE^X7yCpuJ~4I=e)= ze+0vKEDLBq@y+AIRo!R~_KsT?shfjm=YGF4DX@i zjn5j;N4Og?THk7&A@$wZ;#^hxk%($+Sqdb)RAEiyX^~yYOF23x#2dPa@wE}VDcYd- z*+tB7lihCS0g%RsrpZ|SQsY5r6ZC;tf0JM9_4I8*PN7S>ppc8Grr3brilD8s-|3DB z2<$6iaoW&AQ+Z=ZZ3~$?H&O=UvDx!GA+os!@8^mOeVk{bq`$4{5Ht6U0N!6*oP3~a z^m^zdGVgOOOE#l_ms)&vE_xHi{VoLT=3ItTItKijDp=Ms9lh%e<>;{ zigao%6HQ}yhglD&Cx}RfShy@dA@QzCVlfs&?0@(gq=Y^W_bv{RRi}VG_RyCczK$O< zRcD>s?fuHK&vq(dnBc1FtQ5+0r?=yN529U)ZJ66U4ZkLh2C`A(%7gpqaxi4)WzW&f6G}D3zy-W z(-?51RBOy@NXLrLo+&MGziTt$-z3+cArVf}TPeDZ-GMDr9WsKG0V25w<%s$+M3=W4 zO{~`ZX3Gv)i{CKrmbMviQ{s?TvPN!1Y~+>Ax_)w^5ik#x_%SoBp@yqUnJOQTziSm3 zfAVDJ?u3pWn(>}}5Q8I)f00lSNH%IyW98`B`&|@{ZZRD1J3vJ8hchbJ7^A}kv)V(b5C@7jOQZgGe!N97<3KIo|->h@*AY2;cG*XokBb@e*?e=>dh)YaMrd^ z`}D_Bv+)&R7EtY`wu$gjLh1E6c9ehJ!igN3W))O6-*ns5I69fG+%s9QTf=FDLy-_r z9fDJ0zXk~Uiu@~@NW7VCoM55&A&hmSW+poiY5Y>@cW^(9NcD6gy^A+=PU!;@L2%5GaVGJ0 z@&F9vDicv_6J=`f(0c&SN3gR|u7ymHKE?$Q{etWRJ082pe|IS@51u!!Y03e9*OB(< zBT%eB#?Cz-_<-Hlazy+q7x$a1%i%l9&wHZM*Qo@`!*xWi31&TuK%XKy4`jcIHH(?6 z#`bK7$|?td5O!m|%0oJcD?$&uZ0G3%x{B;S??HDV08{6TW^a z{1J0YBE)BMe{KV{#Qw1AB{D?N7^@I{u1_!W20wT=YIV@`{NQDe3tj+%wDa8EQ)@M( zx#Lf!?72(b_#^bJkgk}qfX1)pzJ^w*&MRMBq}EEB9dhNMW17Y|oz1 z(iG%pG8hfK>+CC?_jmjH!}u&e1gXP)9^M%2#Fy%jf1e0{^candCIob|W-;vxDk4G` zIw70vEAeJeA@4jk0eEfOx}Jc2Vwqz%p~b<6%SsqJo?< z70mQuo{X3$3@q#f@mA|oOMn9JJopxyyhF$msfP6vzQO^=CWjgh0Y#VW&C{nqwXUIO z;c>kRxoW=Rf_sABHB7;2PjN>es0#@6KpL!Tf3N{N1b$S`yycIKada5Jd3g5bH_Fr3 zG!SLX$UsU8?>NX4UICq?f1WjxsWNIn4MfFE0NGi1DTmM=aDXY&Tkp-YQl~L`JpjkF zK%7d)>)bKgIdXPVuRQ8Lm>ZH~ha7wO8u}E|tcC$?|9X1o+2?OdZ$`w` ze{q@|dmC&5w;#&|g2ss-3Ty?R%8Y^^AA-eGBO;rEKozdH#yM%T37{`z;lCL!)5hsx zDk9yk`O#{~bNaPM&(!no=xRc0j9-$Rf0Ymx+GH#=OPMeRYM9^PF3~TA(@yd%Txufd zw61d~WGrS3Gm*vkWRq=bZRL>%%IFK0F{8Pl!NhT%;gnm)?Q;7bRuurNS zF$ZHn7q z%C6MEO-?Zu%{cbRKn73V)K}`Mjx$$uQxSNHy4j4n_TUS>%3nevfS)INf44gd3omO6 zDP{9YIW2vBS9}R*>NilKY%K+wo(@Y3BeSmI86Lk6~>RYChe1g}FB$VtQ13AgvEPbojb31tEYfFND3}FO(!!MZ z%=y}eTHK5eD$RVTe@Dly4&A2=IC2)qbm^07e$&=#T8eBjYrhv=c+-M&xzFYhtWSEe zrKkb?|=;kLja_T$;g7_r{vErnwf2gL( zoF9hwC9>JAf2^CDKhDSi+M6hDL37&fniy2%WK|xfbVYp*#CQ(}7M^FhN{|{FJIsQl z66G_JC!Zvt&Uc=&xiTdOj>|9${bNX=IX{etcU=_}AcG72?t`G8tl#al?0;>ECgE%?5Yl4QFQB{E03O_yo8wMg+?y~qJ(72a(vY-C zhNtlwf5VL~4^%Wx+t;SY`~Hr95zi6CxVwb!C0JD#G4WEWJ1MEu3-D&HnLf*MM&9^b z{DO{9#V?2IX>>>ERL8LO#^-xG@Um}4hhD#x`Uz8HROlI<109+XBYTb(N1r-R@p{$v zH%tKeE7Q}wl@hYS{T`Ifk6K<9Xs;cX(yj;v3zdor5yM1tItN@3PYu#{ zf6YVkBN!Y{w)4CxE0IOdM?DF&hf_PDULPl^j70Rs6yU25#Xn0~!W-?Q-9c)r95p40 zZ6&lNK?^Pt@?Ey__OqA+awR&bxeVBW*Wkk8ewx$jF0zdkC^KFJB1cEA{C> zr-Z+Xb%F;Zy*LSFdXCY6zFBtZGqKjhe-fxrPca<+VilF(4XSA4o1%%rnp36h1mx|D zN}8rTJ5rxFKPlK}+KnrXnM*meVWK+8!(N@89>5q1J7Q|emTsn;0}j@k<4HOcm-GUxyh=vT*} z)+ICPAqClPW1+*EDx_C)>4408bK}vpG5!<)G{wOjYyB!c0a-|FsoL1X{m*N9xXIbf zeD1|V-_WlCL#*MY?v;k~!kVYhe+6meAV^fK2o$OgLpUD4f0E%Q1h?L1XfByUL0u#j zYIUo2!e6{xdb7`{?*-)#FtVK4oKXD!npi6R)ehegl=2&llt38YYS=xZF~ZAMH9wB4 zP17$Ly!$oud>$Xfaoepl=egJTSPBu|Bajz>;F%EdSRsVKZ?fgrUSHQ|e+>hc)q%A( z>QrNR#$n=@h!%4Jg~_qzW#0PS7`QP@^V5fXnq%i#6XDt3b6MO+wEILr4L`#u!#;1- z0#T#(^<|l1avlyEPw0EG_p?dcu9|o_-Of7w;CL8|VHtcFnpA3R(OPxUX;;B?vsFq4 zm5h~T6*uIc_t-D}(Kp~oe?OT0Wlm!YB>vO+qFVrRJoPmpL$fwI0v@k#4V0ObF$&C{ z`~0~J1x$r9<0Q6aO`D_0Pf`{O{w$vuP01c`jIrBUSc15z5F34Pap%!IswG5>@>|4g5nW4{3Bfo3&CaqkZ zDf6>KLwuM%VFN2rk4VBV2)+9r#u|8&fZnH0C(W_R*zY9D*5M6vuPw}xP1A(FpTL35qRTEbw=Qm(5Y04F6l@IPOgz^X8(gcv#D z@FTD1iKTs@Puq~`(HH3Uc8E78!0gZ&#pEsk7`=%jiuR1#E54<7-9~ASL!Z?pV$cdA zP3+fg7{fP%Lsp4MN<mO+J5R=0OlLWipq^SKw6%*Pyu2 z;MwShW1SrLcjO`)Tfjg6T=QHhy0FdW@B9XE>tMbCvz#xZwvzy!Eem7RZlAss9nqGk z9VDu8{)1$#e?w?H?m_p&l^s3FG;*i)EY+&{y1m@>k9FYG}lbULplOI+z8NfIVB6d_ENajtWKJ{OE3IzlO5(ZS%q%U*81@pCp2OSf_cRpQEGBMN^8nLR>s*YLX!(U z5YOiT@zL3)}J}ep_!FTvvTcd74ap7^Dif4@#`lIk&Hj% z>&>O(u&Xvd)0iT%2L=r@BlSZ0a$~IHM=%QQ<9{C++L_KjVv73Y2=Jg=N`l)KZ({(O z?(WF!R1izo$t8~XDlvZ8vy6A0*r}nDNANW{f5}Ng@$jAswGPDEo+0tWDd>Hj1);ed z<}=K)V3|C)2@@V)ZLAMI(sQCBLkxa~JA-&+?D#V^T^{3FFP%GfF@7KwGk#h}HPTrD+VA zI{G^Du;`I@%}@HWadzQP?3+ryWmJ}tbI*PHbS5FPq?xQ#{Uv5f`fisXU)eE%e`r1Q zOZLzSDSC?1if`Si!;pnA5B&sWiy$yWdS%+*^~>Z=Ha5sfnGigE!JtR4c^~^YAu`<)-nJ6|-2NBnV$wQm&y;gxw3vQmc&RU{% zj8T-k9q#N}ez!t63e)v_>Wk4#e?>pgLj3tJ684;*!&Dh+z{LIZUkXBOhq!B;R_1#z z*B_0wETU#`w>&a(MV1u>#_NChCX9beJo#otL0_RzG~5Vt65pa89?EMz+=jc7y9~8O zn|&fqk&}gaO2OBtCy1Boyd8+^pE4`}UxKTR!ly;iuPXhBZ0T-w#!Z%Be>JSjRIxHf zswJq(ai`vk`3~bSJg!wTJ3E~{E_Y&B+90nKwH;ATS;c&#zr7epA@XCl4hK!L<-+X! zLP7a#I=4}C5&JT1&S5)@C4ZvK&AbVzbf(=fmn>k{vo<`V;e^a(L#NlzvmoW`yx>W9(Gp)rW5cXQ~+fb3Vq|R}OdwA?` z$p=NbR54fi3E#I964)@-h62;eXS?C9; z?=iZ1l12q>-0+o%Ljqd)3#~DhBy#7@)KBt`QO$s?=qE;(f9W&3$!`r>r*3opeRJ}a zPujM=(pnvkk)SxoNFAl4%GinS88^|zm3}i{s}~XxsOhGOnOps1;l6nZQmDxp;tQTS zG*2*Y%dfHow$e0n@f~^y+xso>%1tWcMViA(+;LExPe=1h!M^ygeiq!%bPoVkWaX7% z;{vC|o$dEkf4xj8N_WoytxX)GiG3EH0VEIV(WdHSrI5wtH)L-4=Bi>&W!A96lWBIY z#Pj#W+T}oh&`RPuL}s*e<+b8~;O>hN>st3!m*!DqDrCT2WuSF^QTSZdPmR2s(*^G> zX}OVVmLSL|=k_}p$09e+{Sr&Y3i$oguB>fh9b-ll4poo_2_Gyw04(2_Az(@Hlcg&obGMW;G(Jc@ zlD&R_)%mE6V|I}=-^VCiP<)fm#SO3JI ze|i7@uIz}|-@&@)H@RSh3vGy}2!twIPmTLd)6QWfUSpzeD{W&)n% zBAZXeQDk#0zgVMAg~(LKf+0e|!cn>K7croTXms#Ff(V%Cg(tXbJq8sgp;HUUs2HJ9Do;iJWff=`P6~ELwof4#7bCQTT9Z-JlH0(vV`g_nY}b z@m$|?e@Qi~i7^n`_&Xc7$QETAe(4a56hx0Z0nBj;r>e+(xJO!$LNXEaf9>t`c4pL> zlAr1T%dLXrzYulAow@$;r*d%+n`~qT`TBqVgIo`KD8Jgjb)BscM^m6wGT&^8Vj?sc z<1JLWwxSxlk0HiExy27!ME4{_mreO8ub|OVd#1~QpS5ee&Pb_xj3A~Rn`o~s4K;mZ zuLj{elAl$O8^K6?!NqvafAvt$_&qdV>|CR)?8Cl>*I-kyiBMk8ozT-~L1^a{W4MI? z$(%_IL_6_Xaxe#cqnBYnR*_+WvKHziCqS@Iamk=w={fgUs{~!KeAJFEg&qKiVy*SQ zYbwp-tJ&R`{u^)a%o-CczdrOAO)lDG82SK@J7mBrhv$)FES~mvf9C$fAC?8N%4w*N zAsx?oTV`co)9VQrUZPQk8QdzhMIEAL$X{gjGN3-TwB8}4wQe946y2B+r0a{e%@q*% z3Zv#)PYJ*A`BuNKJWnS?r6q{&XQpswbEfI9)#@28)!N=R0Q6a9cFT!oiwX8-ru3Fa z+mU0I{Ct7<1aigae`RNu-as%n70aX;fiPz+bg3pY@2=FS3Wk68O9n-nt-)xtxqZ7Q z^LkP%7+-M;VdQlu2lkmsGoqjYt{=P}m9x>C};mu~?%LL+S_=rztaY%-cVJnamjhE7Zke>{*ReGC)=&Hz>bt)_M0Xf2sYmUK{xJfIC9e0GrF9R|7nz zRgpEV!9jkscax&nP5b!5n>(T;>=-zhV{P2>1~3v^t2&9P;2CT63w{qn#3ZQB1hW70ka z_uG~ve@fDt$ZbO8;^!6vdD=fbQZMZAT(W~U`(@o5iLC;`Tlje6L*T!9QfC*8$-#SU zXmn_ExtRIg7}y9xhq`ayaO5h>{-AIGjcZCEUOTBb2b0DC@u^!xrcImmb3p3`L1fZE z0dacq-AU!TubFAAjLlTk%RBWxiqCS7JIq!de})Wt_GCa{S|W?;7=MtlqM{F(8U-aM zN0Nn%0#Roy33o?Jj@LX%fRFYZ2Ls5m5uVM=6m;BS@7lq;c>PtINZ@+tA`Yut^l>1I z$9gk-P;XZhvIBS$*ARp(+VZsC zf8t#Vp&74(nEVkw3~nA=Pc9!d^#WB#II}LCuXa(?n^J~nlg3TcE2W~SLiyp;28}bu zypwRl_4@c>v)*sQ`U1S4B!|l8P?yck1I~TJcP&O!Hf2m^7}Rqdabyk7hG)tKz=cE) z$s~c;;k(9!DbFgvAQVqXwH?qpkRzBge`mTDBrK^mNny#!BJO!1lQNYH6MfDN4D1&N z9&+U&B2u-8je^yAV4j1ygx*C-27GPRwr5-}S^mPI@Zgqu3DJeQ3M4x}ua8LwtYMg~ zv_~$pj(W*Gx^<_3`n0x#0(koF_cV68cB6L^KPtn(j+!0E3rahB-ZC=ERHBBye+#eF z3Bw*bf*meh-a>!HT}eufEkD|qGI$pCJDlYH{5fkOwanAtF@^%yVIWqc*<-z+8fM^-ymdI zjCGT>%up9Rm@SblbZTRHazjt$e_od@HJI;>`<L4nmAl-8%(yB# zW`x%w7Wh#cFhRTSN_ubgT3@gFYgrwD;4lD(VhClm$iQ>6kI~=e)ML2|f7>b%U6_U) z+ka>3DR#K7cFPl^@DN^yVB6B@T)FwEdWr#tbGA$94QGDmq3<@=8bmTSlqZx52gm`Z z8P_kj!3jXT7VV21nC0TEE1nWfK?oc%F2N$F-07AZu*W?QjQplIj1fyTe1>mo+%NoT zgUysh%y}B9%+>)pxOKIEf7}Go%!j7($VI!^1S1Ff(zU5W7z9hT{Bsr-d$#;BQqriOf!pG zgj9Jg1Ow^45?m?4pfuZKfuVhq(ao>o%HZ0-s%ioN&*-uSh-0-rf0Efl`*tF)RRK#BLEl4As|xLcG{HUk1>u-6P`)3z=J@SWKu&*0nY z8axLj0le!te{g={wbEG2Tvg2&IykC1jM*AA-*454a$ zers@FZHOu4g_X2rf3C`J9my^6MRa2ERp6DDa7cFcCA^SBjSB9b*PF6YHKrh5G<%AB z+C1`E3RX3;9Mb=rrnA_3mRW=71u?*Fh!fm`&2WOdUH#Adopr`Z2rW-l?WDU|H6@w* z{exM!thD{d*I1QWb8ET~ib4t#yF&}b$ODxjhsW>iG#+lRfBACI3y~_m1WI%kMI3Zf zL-CnG2Rg1Ab{|+rP*fAHg|w9djBG?+`@=IBj|SUme`@ZVOF47=43jG6r2nbM(&TX+%vo*LRGWx=!g71cD~+%|y(b5#q(sIV z^&uQ(4-{<0;W-Z%PFwiJ1Y|~m=DA#z8f;Gf&X5moWV*#zpqy!b|l@@F2TwYhO^W0TUIx@4|4L)Hj6?(F zp?ukaK2Ye(v%l(c{)Q1datGLw67ul&~ zg`@lte}=DgPFZNk5~Ra}f~aYbh=3lpw~cqJTcLGe$?+y96P3dXH!*;cl|Xx80n`*J z+asa(R2g0HC(N@3*>{Zxxh>qt;i}Mqy)sFp-TkF88LhyI1kz>OSrNWTIpTP7#xk=R z@2jy9z{jGHN->yQsIb7kIhVY=!#==mZPS&ve+V)U#`MGd5Wq_2N6ocLV5xs$B4r|H zaICOpG|1DOYPN0A)lIc#aq@T9GFbKz(uoLKnXrHWIzZez7hoDC-K`M$)+;|a&+AC& zwy<`JOh#`a_`b8!l6b%Ltk9Rt;U)SK4WdibpaeWmqC>DejRF?6?AZu1h9F?M7S@Jg ze|mnI!#YLeHgsb*U~>Jqgp&-=Xs*js$SArDjaT21u)^df@-|%sh2m)nOB4yRiJp$E zlBvd3v0|sb9mwb}4F(4zk$U`yWhkri0}z%rMw?tPaP~&9GJw0x3l3Bl<&+8|xwrBo zFy8pNdm93w$D70OLK`vRO%CPu>$y{|e^gqStycY7SS&==6PUv>AWUn$QYfdka&j4=O&8L_Bekhj?rzqM)v324rI4sRUdF5=TD<&&`1=X4Se<2r> z4e!?mB^u)$?-Z3tk*uHWdY%nYlV@#HL45I9wLzj_%U6h6R%+n##>V^^TE zcqTHlEkq#;7+`gNuHk;BsZ_A0N^)9?Dp#9UWaqK;22$3DcBB2eu*tb~v2b)OxB3oe zPB1qQANqZ9$O_mG00A3Vsvn53e-QVmV0~t0Ugm#OSC7NdrKf@VyDZI==}U65!EYFP z!xsDszw2_j*VbWN$P~Dyw$;x-F56&-rM;ZAXxswKXb~d9I{j>K(tMTHFnYWoNJW8g zs{>URPs>q^;jMC+0@<>myFE;_-7@7b)fyam2^o$pF9P;^5|8Q$Z|A@_e;}x`6(@%# z6-W9TTb>H^N~)FUhngSj3z!uH&<44*9Do7ZVGTh@CG)*oyvw|!Pi=XH!xd5<7{PBe z4zMzaB5vN?uhu?VIZZFPNY1fcJqTbG6d}3RabO9pdwHB@0Tj$4Mmuz!non_|^(1&* z26|2$qeC6lBbBNolo}>ne|K+PLH4MHb0>v+tEB_QzOZ&7-&Q)@#9y(~e?0~CKDh?@ zK*{Ftz<6}>#(+NzutkqTIB!1#|N2=UzWLx>BaM0kluP9`golY?VMu-%WWH{Ts1IW{ zf124mxcqmt!b&#S%T@9I-X4#jzp2NKzxknxQC179ZGO2e)tjb}e_3xl^*ms)mDS1Z z2&(CMd+AC^#P{d#jbL4-?kOGOsjq5te#|j|?Kn)j%dN!!J50v%#0@o>K)~5mSd)mW~KpwAfZ$7m##PyARH9WfX?3Hx01j>Q#5w2gE?_!_ z`eM;0$@H*?&b4x(ZJqUyz#0A8rZ)a~2J#sb2UVqh0N@qS5r_$d-$9=`7!D*n8Wc*m zY?wD4Szt1wWut>&p;B$GGNu~hxXJV2V{qxS93Jpde=;yUg7K)U>~GCDa7X}F{5Aj! zioyqaU~#)rHARw!AI2wfSnNO??uV>IKNKK@vc$jH@PqvMx7ib9+H6uyj@$yK5Pq1r z&*Ho>9bCRsVDr>Kani#>ohUpfaiX*)ABIgngK6DOUjP1Q(iO3qTLrR8%Vi2+DSrP4L)r-XLAf{Ay7}{2y;OFSY{mt!>Jf)p0 zyDS~{?k}hX*2A-i!Sg7+qY8xW7+9g@X(~4ce`6Lvf*{Vy6drCxBRh#@6Ipm-{R9^m zMZ{Lb!)1s;SO=j^3BKA6O@S=`-u|Umo+fV$%9e<7x*@D7ZUE^!DzA5*L#CAW!J+3s zvRlp0fCq@FDZ6gZX+`FC8|PUdn0%mvp64_Si~!gOql2a|-3ACja#W%>UuGw#;!DX5 ze*`yKZhC<@nJ&=cGe~x7(fB=CXSYVdLt=z)`(LwrDNRLK)0u7ON z^!50@X6nvil6`4&3?6^~{q`|XY*~UI;TXW9&T9N3I_O@7C0uNIK?l)#)nox=s*e0% zr@XoDcLa0bV|SwPs>=&e+i8&Dok_^^*WqNV?CN~5l?=Q^?tKpgYwLwBB^HfLe`p^G zm{40P?t_rv@6qhJ6y8UdDnH^r&2n|MWx6E}U63(I-9$JYAA(P}m59aRvxWuqlA|h_ zKKClvBo(0X_D=wUDVYCA@bzBvd#!uBVpFYJ6z%ux`~dE+~&VghoY5daM1d00waRLv5LbE~0M zI(ueNDLx-IN#W7v2P?13#=&SHXB<`XH$Dpg`XNM~CG?nk*@-=82(>mGe}KpXOv@+$ zz1C00SRYX&3kvsli~=wPR*!=God7^dDV5J5NnC9l5dIei-yz@16Di*ABskq$vfAIu z)z8w2$jBdA(zq;V6v$xK@hAe>4C8mNss88RlU4J5HISY!(d~<%_gN_?#K%8ul^4dM zrSO{GOD)hHO&r${Zg6HWe;Z;51{YMCQu(eU>VSsBm37zf#8>5&tY$L z9^Y)1VEHBpAJeFD3fbN6phM;O_O?PliSk&&6621N--r&hqJ%8~N)ba0T$=L=y=tZa z$ZHrdqIIl%-|NK?*k)F`%4})tkyO=Yy{@40J9Znt%An(ge&5=+Vq&?BlWD)h}J;AnfVk#>f!b9OyoRGH$QHC!UjEn6y5~vIJ^1PIyr51Q`K|^1NvSKfrL(^{+3}1jlM-g7)%IZHO)Z;S&kq<3 zlPP1PRsbw(1L+9gjdRhr{%p&6B@>H=e7Q7T4QV<@f6{5`QK&gnFIrX*J;dY; z%0xKyfiZ5+_wCAH=wOOM>lXk;nmH=yZNLu=yELG<`Vs)`H}}0}PH)nfa*6maJDW5O zgWpKnA6pg*JJUXgVxTCwAfFC=Fzfu=Zv>8)zwP_^n&6`Q?elkrQF)ZiF51Hem7f2S z@T(pDZl%fLf4RG)O2OWz5$PL!@AE1PHfY3G(}pE?LQKG z11f=YWy8}eF&$Jl%a;7L)%B_K9DY_gx4w}eZ@)imNK!oEW!vy1Gv~Pc%P|^Gz{?;@ zmyxN#mcb}$nnoy5Qic!cjx{Qf={at_G%f^18Bkh`f4@=PBmwjA-W-^RwOu~$1K-Nu z8bCwC&mv|pzAk%Adkejyi_+AibReB{qnbo4XreYST6Cxd8**0|alRwL50;&XPSMfz zN>rVNJDH+ULGASSi;Fdj@cC}!tIC&wqX1JttiLI*S<+t)r&bA8w?0spY^{9PkkB|g z9HdUCs-3{a=6^f%=+Pe+es=b$#4OsL?{9u`f9Pp;EV%!75q%k-+#JffKhU5g?E|40O`&xR2 zXYeD^WN-Tdr=-CdVVA#P{+iLNmUC`C=foTNN!$J9`-D$T`uN*0q^GC?#{uzrbZBXB zck%G}q<^0P9`n&CV9+k8Bh_}Nmi6>0rPBQYUpIU+;rA$Vyw^!HE`r2Y@ToKmY74&j z%{5iUFdv3h96|g#eXIW(l$mwErcn8luMn^a%*Hk&ZK@If>CkqoavP?V7_jQ?sF;BN?Bam`KeIT#n|Q675>0d42n-4r0UE2b7~EiL0TC117Zn z8-JzET&(Ca;_6T(I5hF%8!{|hLca0$qriM`nW)xc*<8lnOCqR@Ty}SQ_84OT1jSv2 z9Ss0DT3?Qd8MztcSgxeGXM!v(;N9dVj0ud{9?6{kQXl3n-GE;Ib<_Mm}@<(v`Yn z!h4yC=U3Ovd}jrN%3L+;K5=TmXS+A9vu~q8g(!05J~1?YhXr0e||~2}auPl*u&R#Rxx>3^{HHC0nLeidI6*eN^x4 zBDG)Yp-Iv-JpabPZj{8B_?cv2uU0S%7cOK%_N!(MA8G5l}{TttcOTL1FkyKGWie zcUW+>bCXhPe4TO=*CAcc23OKOECuRI!69x~iiE@8Fh8IjWp^_>w0~XZ0PO=TO{EQo z<+SH8D<7gkvNUN6Tzp_U59VPVC#y}(gdohvSvw=#2J4a(U{ls#Om~HM^;z2Y7PEMH zpxGQj?plY<+tmkX!RC_v3t4v&9d9sD+C2C~F@P9a)k3+aY7i~&rWTXSAT^zXZ!wtuA*EGJ9JiBawT%&Sf>ku?(SKtT!;HK0*|~^24QZiu^Ig z#=u5g+DmAq4D_`Y1}p4_Tpj+IEfR7R9-L(_L(lwvS$OSe;0&BsAE4>3|nEW_V`v`8FUoPmmT3Hi)K&#T>zt>f>##YKw&aQ!s+75cr2 zXBLaJ`JvZMnu>hr>-)ur&k@fi-pbAFYv!84)G)HvJ|>Zuw}%@SR>nQ)q=ZGR@{88k zyS4Hq%-G-2KYxaHK)toHXTo+=`sbD=yZ5>gNUv7PR2)1upb=bk^)l(?zx=$$z3l+u z02qi-U%-T?my`?;XrkhT+hl%lpg6ZK5kUA-4k%Wh-oTXz5S;**j-fP&Zh6gxf?-%^ z%mp(@?W3tG<#+wP6kj*j)NJ_xEj_tg>GK;`_#7Pjf`8e+5j+hV^`q=>0z&SszeCXI zvR5;D#)lsaa^@i_l?oT~ zgC-x~BY%9KS4I7+>j5!oYIHV^Y{pRV+ZSMf0Yi&cSmwX8DbdHF5oou_Jp3er8uM>l zV;|Y*f1Pp3BUJUy|7)iXn5+WA^_8Sedo;M7{JpG~fOvy*n1r7yJhRjuKQH%cXKNY+ zy;%;(dSFHyT>I3Z15hkNlQdm?&&F{i9>w3bEPs)JsC|ncDXR2r2YUPc{%RQ zkU7514&z1We_EmpZU@;z5f0YhLOd+O|mr!K6 z+18ewE-5TX@Ey8$D*CL-d$KQB~&peaKqn)ViWbj~O zLws+4e;t5*KHezDfXbiGy#2rAZ$NPk1#3Cdw|JT@b@0@;unCmI_}^%UB`n5E;r@KGY$73I0+!NsN)$^OXiGi2i*7?eoByUF$=t_oUDr!vP*L zN_j6rjiNvm%?kMaiesy>t|a4bkC~u7Tp8hv^RQ>NHzpJ}k!k))u_?Z;tC(2{1=Fh| z79-SH3kL+50|Pk9AUlL?_ z_zR|`Xg_;(WHIvp4bpx(NcD;9g1oX1Y*_ zHM8J1h7An@2`pG06gNP6o^w(z1wSHKoUE`FX!8Z;C6bOXbrCb3@lT@G@_+6Y;wGuM z6JA?k6r{Qychj!keB50e^F6=^Yxh=bNKy$Wd&V#52;${Z37M$6)ai5m8V=oNu8v*r62n&VUxe|DC+QC|fGSCQfST~iAWpiTrdGgeM%5B$sXaj&Z zLtG|0x) z!6gp#t9S4MII3r$`IZ3WR<~S^ZaYCu{DY*)+J-kwhBK-OrKoRZ-y0%K#1%BgVWIE= zR%h6k+CMGhAemCGy?A@r{6H&=0A0WCF!K^nf^wIsC%1q?FWPc z%;8AII}jwLfTcypihnfg%3Op(LN@0m0-0NnDJtSa*g|c3n3Js(+`o0WrTp<_jUWh( z+VfWyA#F%ug1p-ZtCv0VgrgKOOY7+R31w@pYFNl7t(bzLy zic|NmZe=p#gAXBOj~HsmRY`SDmd~Ve9qJP^iEHcG@_?7ytGwghq zQK9Y?AkhFYssp3@>2l03b&Wf{J&a4nyAWE{AkNMc;wX~+G2z2U-e_>um6m_3nNIhf_Q3Cgky ztq)o)Raxs!Pk+;~E7IeUqq2(1Mb&2uXBu~ZDPg_oP3OuIu-S)$&*fwdQ7tL7AUIRR z(i;I5SBN&>0K#;gW$n$Ty~e+pEpR;`D8cKP)aJx(nFUmk;ypn46y*`@;U17<-UR{2 zt;DcKCAjPxhNDQGT{v^Nxpn)?Y;SA7(M-fx*`xTBvVXnWX2VPWMb|B4;a7#2budyk z-^Y4mlAfIP>Y}v1mT=SKYH_}(czD@$LJLlF&yYfLFjIlo=$i`G6W?rPeJ!!*ou6&< zQ)e2ck?*h(-ahOJXH!NVgt3~@P!6McX-m*+zP%f2t{#62oD8ABf2m`H@X&opmPwbT z7W3W(UVjkmyA19w-+Ar^(jU zU?tos>HaUV;dkWK;p$L9AxCqX@9O8tFiaWf=k4kn)H_0JbYA@HGAtV8>6_Ro@=*_7%5u7RGm87fnb znSXo>mECVl=v1UyD(vuxjk479(;Q~B&s0Ot@N}FR@Sx=E#z{Q3<(2&)e^=BJKKiJ% zN8b;bW@YCWoL?ZUK0uZhX8%sCFrob%t&R5!s@XLx`X*9u^6bF!{32HBWB5MYT$s(9 zpxw?HWF?Q(seTCku~{bmWJZ&P63uk8rhk8zK2Qo9GcgI z%7QdQ#c3SA`m~1#9x1|GxT-or>~~a%yYHO0$H=nrJP`MN5drHjvve@n{_aWvuYalo z?bueqV7D@(e=gC1Q<4PyLdh9b0&lR(_5q#jhsG_m(R`-M+K08Yr{6@H)-O9KpKaW= zdovv6juk(d=42t@<_%$j!Swtk(=qf$j)hxFcs%2+B?3X9+ z7@*9D2@#`!`vE+>6y5@xY8cxFd^u%l^c{Fx5-hiX1qfB*6Idc$`P?>D8QoSoFZdZd zO*6qi7AoxHO68f#!*~&?i+S1C)dYI(UUT_)`$yT#c3`ic*nN!4^*&l0lYfDeG771d zz`9$XVnq(u{)%+l>pJ`LmsJF~EHu6ixv9jI0yC_iA(5u5@L`Nj=!VhW&)vN#=rM;n zV85@dK&R+Vf7v{{DI98`?Tv8^yku#&f0g2Tc%O0fh7?~m^u>$+P(n?wcXz=h0+mr= znch27!Z150#@Mpx^IrGPynlEObBbvJnX&Qmapk}vgm$2AwkWo{Q+;xS#_PDDI#QFR z*#|@0aP8wpGCoCBSAu0cH39Hiu=&H2@3_w|xALw|^L>V)Hs=achhiud6>6`I*G4a{VHSqRO_b`*am91RVsd(R2f9*9E*l9b=&>k7yR z171+IMJh11Hkux#Ynoll;UTgozU z-F4XNdV{t%oRFt84}5A8%4oNA_Lh7)*S}289+)1y?Y}H14veP)roG_e7YyMCZaeUp zh5l^2iRIWgj?9X+U3af+0k`KhI3eV-8{LLNoOtI6zQD`WB|0|+aH%C3f(v)~>9fh~+w`u% zu^rB>lw~RHG|b{#_ zP_};f%72Z<0>c#y_)dX?1&{PaIxv6B*OX6bFBpK_k`=iusG7OjBoxVRZlUy`JO|H@ z+PQ!zztg1xg-x-br8~AArIZjP-!z*N(9+yC zQ%+Vb0HsEJ_n=6~|zBZ>e>LWY6i)04H@QNZYA|SfzcH$Q{WE6ZFA6n=6^%H>jV=VAz48=Kdb2wWtV~ze9G!Uv&&vu)Za> zIkW>4&6FKhN2U+`IywH&Q zP7Jal{Ck_c)hm=3SS{e=*zqwnW<{>RQt)I`6e?l^mZo5w-+^jB%u(8FgrKP4(BAp8 zqX%!ssEqzfHSOng_zg{u@-qOKh?qB?2eW;RL)9ZvG>`>oyoO-N?z}>l> z1W47xbFU{)PjTR)KUitIfuEl@Iv2J`TU(W4t4prPMi@h&(|`Zj`-U}xj{*G3m9=CT z5z3+*%-0lcTwTUJ-o5bcH?*ET>wya-&Y78KF37*-+^-Bk9CmEI)0x654O>cZ2!GH9 z3~8dH+|5~^FM43JGx|8cXw@8&Bln{LuI8(AH5_ zt-0QwAT~LfPpII9)OY1nA}%QAb$z`#MxCF|#eq?mNT=7=j)a1B~CMba$oVz_Sqt8o7 zV7c5hP+W3(4E7+wN$bXeG*v=T1}oQiH;Ne*X5bpTyizaH#=p5On`8=qlwwol^jn%Y zam@JugFlEHr%{II8LTgI(}wlDxizJlTIw(^!LV}G=~f)XgN z2H#D4R^JR2XY=rez=RNrTRjk(LwB)2P{@T-0{MgohtsCoSdU6Lg%;a6z#g)#-|(kB zlKK0?SWNuBMu2cf1!SVHsa1=>Pxnibi{apq3gm6n(%eVI3KNg~S-nekOa}EzC2qb% z^L;(Fz%xQVKg-p~5a*vQ$$tpnWnf^pT7v83jac#DV;-auToutPaA<(;Q$v7q=nk2FaX=oXb*q=& zWC-Lf*nmmtr8sG%3H>J3Y?(-H;nh_F8Ac}r2V|wHFwv!&B?sjJLw{KK;imTHUdQSj zxh|PMkt>@AyFYeaCQ6V<*iO{tPFP=ivpJVr*n79=I2U%ty_rw0ODVK%d>P=in0(z< zm@dNWM*(iINSL~+=S6S-?fJDkhxXmb-@kK5+&#G<08yO6uD35<6#GN88KgA{cq+3u zGigQFhYh7a#SKZYseko@v_LYumUGI3-|+ie)sU4X|2x^ah)y#OcIF^H77Rbm57>|Q zY6OOr71fVU3HHi*|NKeWl$JH3RbhDe{O(>t{-E8S$p*SY8?|EJ#E7*DLb>z>6{C&u zvoYi_8!e5Z!&iCHHG9PK6kSZA8#fy`N(OW-9H6N}*W{hN0DlWEqxJ3cwf%!ZzpvD)+8%x3SFcCI`i+%0$|Wt7Vw}4BvVi*luQ;3#S_3Kb8EZxj zcLIWR1eHL2*(3=rKX&rUm`(6R2oW}!QEP(Zd-NikSKt8Uw83gr3mdQm13Ez%{*DoW7-D2US6NRbc`+t&Jo-l9!Bx|(S>4db?DS=&N zD_%MeKSoykJJcY^+oo`z3SkyW+a0N)l%^3ewr@27@$VGVC>?S*teoM2FryI7jBWq^ zt3R|G0KuF0%rMp@SeX|hZ7J*M4iOYR5*?!e0SRRwY5pR4n8ZjoP-D#9(Ps$dOSB!^ z`eOUZ6@Nt-u_Z`4uiwEU*c3-FTF&`PgAJq*B<_7scFL!6a9WRk&fM;0f1(9u0{I{{ zu_6~qMDp<)@5V#~7)Cp81haNMJ!TFFwo%ORuG|C=JBcf6cQ67{%q^QB z%70{9jVJnQ*$YJ(a9?B2EaWFa0hQN^n-HZqkiXnucuE8_7;ciw7MEx+KzJ1=Fx{i8 zOrv(wov_!#Ndt@Kn29o-r74sH%zzFI14M5fUfB0qjE0mJ5UXJeqwPnBevs}tp+Wy0 zufou>@eBPI;^?58fueC$Nx19~?$a^2;(v34f9UV0!6&|a_NCjP0FS+CII`^vgIw49 z&W6fBt;tGikD9L-;JJJ~irA_Mz;F0EA>y>!1Ns3Vz^K;Iicxl>eD0+~mKZ)*pb%r> zJ3pP2Wuh|Vqw$%dL)-{dKeH3lJ&;rHJd%~$^aAAo67$hC^4!eAzzS6A}aFvjD2A9qdsc*<)bTjq) z@ju-uvFT!7Z%naAY5v>ju}w;OWF;k{UW=~zNHMv-r;f7b*`-E980Rbr5)OvMutS8e zDN}z>(u8LFS7~(hf{&9BaUse;=6~xGYwmt!72vOR3)*k=&0}t{iSL*MK{cs_*Z(~} zR$_1*qVS#bL#0wFZOH7gT>8G9&6Y>oxz9qe$ZfQdXzjfiUNv@d(x@z=hjK7l*$ru& zbH67$?&`i=S=rGBUsS`KOL~AtMI_Q(+vMI1&Cq`AfqU{Mc~XA50Br>1VSi@JFc=R! z{g~5U-iV==i*s`Qx!#NL$gM#Kn$}^jiqStE&!lBTXjQQ@LoR#BI6OMGt!b^u(?&}0 zdXz_?B{0D8*4?08bERq)h2|5#Mn@k(%{}M>LE8#ai;09CS5SUR={mmROBA2g=edS( zBKSy#NPUsa=ZK|y0-)4OV1JB=!0#yGUsqn($*p$bkC6fVgdg|N*RQt$pMe~ieqr~0 z_i(uU2Enbyw=9X&Edb^cK3}-`G&xyrXncrPNk&@wGG7Ka)`pZCNgbuO())w>9>UMr zN!K6t?=S_4*K7teH~Q5VL5w;|71DTmX=N%db?~-8((-q_LxeIJ5P!-gv(d&h8z!RH zC21M>|LxbPkFiYmJL}ry#sTN6voOXcs07Y=o~hbTX29dVn~5l%g`$$(;$^AA_DAOa z)?a{D%b^nR8?y~oeC%q=c-PA)VHdw7#}#+<08*43p9JFX=cP;52P@NhCx2NP+ZxeW zA0oGnu=oyD1GAqVYnr-R_zc*>^#p}l`a)iPXm>Ase=*rUi1dXah;#zr#RYV= z@AmqgXab^xqsb2mIL~oGBn=-kQZK)`)Bu^f{2)8XN{tvI-aeLt+5gUZ_&s2}(^mdQ zl)6@-sqJZh^?$v74P^T=NkBr%79Mng%a#`U+Y6+pcPD``owOA176kzqoAp9Hoad01 zJ1V>b*RXHK;-*!ID5mf^E!Hw0$`I`h1uG!m|>)bdRhUyE+qD zOG&FZ8aMQY{`hbelfQFcd{>wN72F2Wl&a%bAzlJZaDPA?6Yj6(fCU#d%yeo}pT)EB zJce`*(^pCU0eF%VJBY{^%0Lnmq#yz7cwMHJwqU(tk45u4k80M&`@jyuTd!ul5zTt~ zmql}_ITQ@8=JUY%je}Vqkn9c%FY^I)R{ee8L$_U_UG5@;C`Sq#nEMHuIYKboc=v6(;0T>Ny6(XfSfNx zZ5&d6F#HgP&RgV(I@nQw>FF-^AwE^q0nt>G17>$Q33YNlfw*NC^wym%9C^`PIVD;t zoqxa!@2B?~^qmf_Upf0ow)WX#hP3nVZT@IYe8w-l<$K;Dfynq0iK=kFy+$J>2$xyc zsh}iAxCVAUdwF`$fc<`-UDu zYvx;5?q6N~UR3V7M<-DF(m%iAhW0LD2!Bk`vH2cuSZvN~S@Ezox$TF>^sht@w;g7`+qs^ zVUVYRJH2)n$gdC@rir&QoTfHKHrDk07LZx!=WYS$TE`LjdHgK)FimuF`#TX4h!X!z z0ODHQiFa-yA5p^Fth94?4^>ePp><$1PyBrRFr^f2An(BX0Ee3eK}y3k_QRjxjR}%J zyWyGt0?bR(T$VY!&ifE~wu~y&w13X9#N1JGTj0>8An#dm@__hm3m8!`F9yWnJPy10 zcukBUB=Xc1VtkvAV|iQ0%xrtqRlf#yf)tuIxz=AV-6!q8ec32Gh7XmciP$l~dS+?O zP1<$i+nF5)%4gSn2nZz5Wej1zFDhqR(7N^UA4%u2-Kr7=(GOxkPD6r7B7bL?ku!)K zzW(9+MqbO7CFnkk>@N8fq)w4le;H-ax!prp@DgTe*GkB&O(2Zo+;V57?>Rbo-y}zf8VdrnWiYKw9C-8U!}*6LTRS8cZ z0gCfwqw7cV89%C-ePwxINlQBbBHlxiNQ3-%ly|@%uiG@3irIhHM1SGcf$JAM_H&#= zCTK#H8@#*Ea?nRYX`^^!@Lp!|D*L-~jLY8Nu$R9v7eqt5LLMvc(RRJrk`>58`m*r) zRqEkrfKv9p{GRcw%cV7wM_aKb4-9UhhG}w7^4S;$dW_N1b7(6p2IFn zx(;!SM*8rapeF++N`G7x6=dd4j%(VvjF|fAzwZ~$cD`Pal5eH4Qmfi!nen}x`~tOc zc(F0{DSfjrnTv!DezM#sn)#PqV+6KiP<@{);a^=rQX z;f)yxw8OwX(l_38%*%_l(*CyM{wC7j3hrG^z!puPTek+OHQgB7gS}eLBb0Q2e<@Lt zV;c0!kV6}sHh*@+vs?^mR14!$7k-7Ck@OR6+5JGGfi;ggnsd8fWQ|}U$S~D;&o3xy zbX5L3Z$h^~DdB!75eNH>HF9Z3j=5SnS&)b*4}vqfZ#E+z7HY|{iSJi085rUTevuv! zy%I1E{7FPX8hZe<9Tf^8H&60A?`XFKJh@*iZWO70iGOWj!v`P!p6eM5xzat}wJ#f) zxlg;lpxYuX_}%5j_IygZ3G{~Vn>J z+=8v`O2Q6|o)cMdQT=dzNwdO;5nTLb`jnPA1s?CF{&xwt1@y;)ydJ~|r_nWLPLf>8 zglK60nSUsVgomkpc8BU7=n2ek0fV`pqdwZb;Fyz$rlc%qC8*5wN~N7&(XwT0s!0ik zkx#0GiI5`;W;4t%2tt0^Oe-;u#zyh-Ba!2{(PJfY@7Y^Ko3&P<@K*5ioE(XSa6djx zQGwsZ%T*Qvj_!onKi3wz^n#io{$p7XKWQ9ZNq-|#n?<$IHV18F`s!t#d8B77StQqS zLs>3B0bSvKNU{iHy2`uiYK%Gq(*{31N>E>y|93avEDfS z!+#W&U?2Jran#3$Yv14=11hZu5_AXiD_3Ed_{`%B3wJaH8VcH&$$myST>}tVK{QHQ z;6AQr1F&k5l-4cYT=c=~ouUoQmPlZ);_928q6)Cw6KxYbhI@5%M@Lvf{}Z`#Hz!`K z=f!(bdaX9+uy!nPx`R)|weImH8Qcct`+q1J5>W4Pe?y4*ypFO$`^4+NR`MZm7;#Se zkYOGgdZz^X9J|jm{YuU*CDwY4!>T7ege*OM!+_8(=Izk=)P}#vXd6O3U8d;Z994bz7Kt=r2#ph<8;g5ZGY?2G1oy`|qGlGwO0 zmKFJ?VQfQT1PGT1Il_C$eMtIYCE6oY@k_$`rRqq&g*+AHdQiJ0)Y2EXdsnfb;H86) zErrkTi`&B;f5PL17+?!Pt$n;joPU3@igh!~XFr4|kcogkCipa;@R?#Vn&NWbVX|z- zgg*3?In1jmgH>?V^Q}6df+oMlVb| zw6g!?>u(7rwH9*>;F_#_>*F0SdhG5#L38k$sXM<|&81nqO~l)Y-uOtbe?OD0=m# zmMQ5SP2;(6{}*>g(neoJYi}$ZJ+`NKO3_PIk@ic~_X;d8W_9n&dmc}tH-w)+sH1k*vFG->_MXhbh)uL73e&fU zVewnt=o1zBz{x+f`~v>h0y5dLdN7b{YukC)doe5!>3wL)9`BSjfVZ@Jq( zAPsOd3DA!t!oS4x{>}{pTkAnio>8A6;)D51!Dhcg5->#pWnM})B7YdZ=8DY#hH7v^ zN11@w*B|#4^Br?pEEzq)L%+)IWOdgQ8+tZTpkuif#px#eLRowhE6}O0p3?3E^I^Le zO)liZ@=KyRA>!Dz2TK~#vIlk%z{gNGK&8LcIzg?82m^5@ul=y`)_^dlEW{6`z}CeB zALL~kw3oq(1Yrj$z<+BZk<~ne25Q2uCs=I*-G}p@P`U`LBd;%(?y$b4(Aw4fcy$nVA`A+e{gw%MM-!Y zqT9(OsT^`dTVd$a=hFhU|9!4J8_TcSyua_ZMNQ5(SOb>aK7S2s=!xdtDy*2-eeX*m z4zoSLx)^-M#9m>`!w4;!2EWIWk2}b;{Ob~y=Q-~_$xaBv!7{A}cem!k;l={{>QRe8 zjqSgcNLf=px{frh347(2pefVuL2QG5g(Glu`Z^w6IEz7{$#FFVejNr7$OexmBI^>A+tb=* zBu7l2DZ!5mjE7VlmWU|O(`rV#)Mh6dvIHL@<2|&^{vGAvSkOrpFFJ?93{XdwD4HP* z8gcc0GtfiuD6wC7tyUR$EhGMjA?J+|uTGhLPl~18Z+}{6^jkJUyFUZ=uP7(&hBr*? zZ!Guy<5WCMei_L(1H)GCRq26jq7tDi6nRi_{p}`l{|P%y6L72?Q=p6oj+Z7FTbZ=x z=M;S8@k6EX2w=b0hF+;(iYxzco1KthR8z^2h*=yRcn5c-_N8%styf{q^!6ozR8|r^ zla^x0b$@zS2gfbEL^`Ic%Kx@#n^%6gagv-(%5M8cqVLNJU;Ry)d2j0x z4)wu5z^m=F~^uy>^ied05eRo^HrHdbqrh>O0OF5cok&6KG<|c^rKN3 z`pKyC5W<2%xMPxD5J%tPq#4BRmM&d8uhKBwe1AaIjpgyBsDf429;s;mCup?iAOR~pUoHm(6xfGJpbM~yqpPrTLH3Iyp39JAQK=8km z?ZmLY`ywQTuy?{uppl1T3XA^EZWu&BVL=Un3ZCKtVyn&gC+A@adU(V^!H^0Us>CTm zUc@W=I|wa6j}73H7cYJ7NkE^#v}LGUoPW$0wY4>D>ErnG;8$r6mqbE`JS%e+7^W1< zl6MDfXjB8lD-?CtE$0RM0JY!B_|U`fN-A0&R-#aQYU46N;_de+xni^FTIyc6^^h3p zmgFR}mV;muPOw6#8-WlNjN)Nl>1Hh%=0 zSISP-_`}44{N@x?^8qk&MV6!5ye$cK&OTH~So?O0g?*h{xH=kYs?E`*`1i=2rc|#{ z78F8!KLB1{!HI{w__>QR*2UmW-fg@Z6lS3lj3x-(v^W8%G?kh&hf@*un6F_IH3HyT zA`yU^+?8;>ixDgmU6*d6D+mAWOn;BP3A7sw*TJfwh0J_aYa%)w)xnfERn5@t!(QYr ze2+)XpwyXcC~;C$(+Ji11RS}$)fkZ4#ur8emkG}~C!D)&#U$+SOVVAX4RcL4h|teV zE4tem<$A*|zhUHLuH3qCpkFC3;E`ZE`0NC+$%Nox!G@GF3*j?BCUIWvnt#Xh{Vd=^ z3gvTNomL*`D&Q|68S-cn^XwlZ~b8r^CmU%c zmWq$+qM=(nDiPizndgGt8#>q|<|bozIQ^;|d|a?!`vIH}*hjyw#eZBe`SsdMS*jd$ zmdgE=Rbcrn#hIp2kLk*&$9zff`8iB9Da^%i`m?|GD8lcY1~!%~0iqxw-vQ07n9|FF zbl++O^PPm_c`2qWzkgyp2v^YaS)Dg|jrXY|^szSqRgBeyWKpvvFRntWxndrh`VD1Ix*paMjU|V{_C`UEoK?2?;`xXXD0(0B7c`}Wb)zeg8`9#FzZcc z+SaroZf1Qn=8_v>ri{jq7-3ukTMyyvi1O`k3BQy2bBr%);K)iXQ2wF5GU0yxH5U6` z-w%XkT1a%@vctKG92bapz3Zva;7si=7sHCH{y3M}(}icD@FW5=NsU?#@-g-?a9u}A zpU9y?Z*`SFn19b$3h;_syuZ!2Ol&Faiv z6&EdRmRub-TG>Rf-61$XvFsNm9Zhs0Lg3n*N?iU!{H`(3XU|tKp<0jNAE4MT8YzO4 zD)yIM<9~5)4c%3fJKym`mtieV;uhCRJ87jW%Yu=7#SeBo)9N{Cmkb}c2P$m%?cFr%ObzQhO>A3VLo>P&~AWgIy>d# zs-Dgh0W5JgG*}pCnsC3_j@X~23x&x$O(VbtD}U-&`ytHfkdx}U3ih!B=8L3`=JA3! ztDjl;9(|fA1oZ3ix|>=lEiK*s>R`eoN-d*(?}s0(8a~$f`Bdj;=JBxA)&VrvhD@gy z{J*(uUZ}WI$Dmxg23#LJV0dj;n7^_ig4E(~L_voFmvrNWwkAB|Zfsiq_jk~iq`#fc2 zg2G>pIxNq}zrk<*Zmi|wL6V5IQ~zY>Tz`zWNgFif*lJ3?6w9D+AJoh2d6*=*Uu3l3 zMCi{Hpy&CaHVKO=8nZF32gTcB2N=x(LhA-T;WWypNSX-`ei0qVHi0L;DK*KP_Uz}l zv)g@P2d=rX1q4yzV~3J2beV+@*!FslIzYP!&pSlww;Rhfai_n_r#6kxKyFSCwNU~~|^?h~^gqy^b2bdt~0D7L3(YXDW_xgR*e zE1Uvqy!3VFtg|p<)EPoKU$1q3&_c0sbEL5E>s!S7oPq>VMA|G{BNu!qJ+TJLCm(7xfL2%< z(TaHu8bwddJ_%?d#GRW=Uc*}HLo(~65<4>oz3e@vTA9eOqq^&d6A^jyL4W7dbUGz{;km0Zvc3KJwTr(SC!*$NXDu;AJuhGH^DV%L zpemZJHMIXlq4t*KrAOg3G;c~JU>iB6&P2#uLhqPEiPvX<4t?i!X=4uvS&u3?;yRnl zG%BjGKYOS%yI!d3FEh$6K7tfFa@DL$T<;qcJer=1@ppDp-fPo?6MrptNwg3D=n>V^ zYuV16F^9zdhC^q>h4c z*PZP1NIzt{I@2uDEh? z(uQsg<8gz6#eZysRJ!VD%9PA42d=W}!-?B^{yS%D(EEQiFNQh3A`FsteP~d{KP@hn zW!|}+MO&FqI{y4jUGwI~z_NMEx5IuOzu?4Ro@eJRrLxJ&4O|>VLo&q0A|pFrF7COO`@es!X02 z$~VKSL5o|fH6-dDZ)Hu;pW(H%`EDaQsiY)|GED=O&oRPyA*^Z$?!-2K`>)z(%hwv~ zcGuItdkS^6g)oIn{26Vz6b4M32x~O1pTNcgyE0LAl_dX|8HNGD2v66LHk14J_9b#L zl?ZM5TYuzG#@Ags{#{@BFw?6GO2$$9t?>oO^i>f2eslJPN8S{%jr{HlaeSOn8cajI zSaTAUmVwO(K>Bw6oW#84zV5(SzA?1+ICzr>kg~aMKMIf-uMnG2!1)BNxwU`cdsTh1 z89g|5nr)7=>0_XHFdVx7#jfv@0*8B#Y>V&y+<*M!YuC|{ka`0QlXT9_afv@@@^G8W zXDV_VgLF-x(Nf^|@~i?;U?(cGbi`<;bV`9-bAg#+iZD z9MJ15EGcM5QVHQ5PiCN5D^x{cKHWYZPO5}YCm^J7p=6&=tlMsZ|4ZBBrR(W?qJMRA zGn5Jh6;Q&B&3o zjWYd9iI#a;7JOOu>=ozzpDnApl(D(W`!`m#7tj>NY&RwI^hJKgwA`;BnUh63r<(Gp zFbWs*nzB>>VGe}SOUtz<+shYeL|*l;k1~yncRT(gWWX5qe~2D5scNAN{HB znh4)UesRu2e!lbB4p2TeNr1WlFUr=r0^gxRgt51IYGYTXWL;&!9df5wui4hjG;p|H zzL*dmHM4J)x1$3!=JPwG@LR_)s)=oVrbkL8kz}CKjk1ntkJ|J1j7GNP?0=A~{1R-h zmlZfzHJX%xBjHH*WVQ1RwVPZzuN4q9ndKSyh?0%BgJ`fR#+P^u&fc+6-q*Qx8UPgM zA8E3Q_|GDbf&#a~a6jdwYEHf~+pI~j;Di{(7x~J)dJ+Nr$xRCZe?kuu?)BhyiR}Y% zRnS9h!?0baM1Oe=;aTg@TYop4MEngOY<+k);HCKddQ&N=BhGAB1iR!*PHgX;7gdC@FTsV~=Kd_dlzqE~q zUvq7Sp;JetC=+Kdz<5jQn_RLz+k(Q-ELT&)AP@~?6U`4gsj>`@g@0fy(A#wG+_qoG z;D7L;HH5vId>E3A)`H;m#p{$3fpwe3oo7l^7u9kZ7tj9{&5v_rnk4DJ8y{(-76B&F zm7x{ocoCccVo2L-50Ria<1~=v8X@}#zu;(t-;Vc6Ay82O78O;LAY|{_p5S-GQZR;< z6sW0%5eo!f8>%m&R)2b44gfYRK+k&0p&J?30!Y?gZUw&hy{G9mB^QiR3xNUg7vEr2 z#UR$3GMzRFv~6w;jsQJC!oRCA-A-mUuJqax_vZI0Q=sb>ZR{^szF~IyHI3+Y#(RKi ztXNyPm~1XmUI*oNRAu>_gI6E-?AY0g79#1Mphbmxo#WdRueQTub@hLuw8=1xTG21w zV+mO|qoK;FzP79X;og$9DTODwp3zyh#H$_Ak_S@T-b0rN2wPEorc{@EC)zzo4POx+ z5*?a9)jxYQr7JgHw-^9-rRpongCTCp%l|1BzeS;}ZB+=X=1$RW;& z;^JtFuh1iOrPwNecat}QEp#A4ompP<=KR7d4E3_zdO2c951m)d`;Ad7bA{He_2VPQi2tyY>E z_;Dg1Q}To;$hSHO;X+YSu(gvHnxjirz0tLP*{uCel*b zHa<#xhKs!0%lN$2l&(D19dLTd9I~lm~5C z!-Sf6oxGDvY`A1@;*qXfwe!EnDB6#-<(>}Ed{@$>|O{$1ayPyB_lgy28#JP~`9 zmE~4|;sC!rMbiW>QTahMZ;{Wrag(yeGwHPyZ?4|ENq(8>>{1ZpEMj|-W|7>jWEg+M zkc2q>di?ovUHc3C@4swkdxa|csa2G`qTEziab=`Gh>EmKAzCU6h-tItPou1y{fXV^ zZqEiHTs2sIxp98@;TMGX(p0gI6;^1)4#6wRNS!`zzgoCh|NM2Jr1@KF%*Bcqx+N^r zjZ^Tc!$|4^{qXsHAG&;K981r}1#y2Z#z4cG5&$iI3>(eE8pv%c+1brE1@R@kMMLoc z$9oQeXN4uIK*nX~`tH=C0lq$e*KWw=!bKP-AB6nNJfy^Y2dO7eW6W+zqgc!~0R{o_ z2z)C0%HEtkqx$}RKv3fi>4%BuS>ivBht-N#>Vy2~w=PtYNHq1mX8$U#P5PCebG#Nw zoW4C7Merg*fOdmXttPJStNk>lizqJU*jt-gW2WW0h41+T@AjoE7;l{pQGog)t>Pwe50zU$HkJpi0=iR{ z6)ZHm}JrL$iO^nWs+`Sv`8x zhcjAQZn6QIci3OIbM_hnbE$(dVo}&}UsridaS3kv>8-0BFW=F#Pivp93<3v*(_x5D zrwT<*+gLRCi<9;E0@a6{uoS~uoZagNs|~H*a(&LKh}awRn9-EQK7TvSlz=D!`eA}6 zUjo`!f^oLOO(0&^z+vs6YJ6- zL;BmHU-?jnTJB|3{5T69?(k?*8MpmyxG!`RrcSW|8i|u^@wn$ggK#n2Zz z+9Tgzv)zm%>37kuS~}7$LmYsqynuGcy{W5qjApQRcdn~lp-fbUK)ann>+BHc2~`DF zAuGY7`SWp7iqU^Oq%0dgMO>|G2(Avbuoy+UxNZ1y*5|EpXr<5XGGrxGC&XGD;V3Fp z_J8mmwHa(0%+vt`_rLL1+hzDUT2`g%Cx z^|jTLn27cGd4%5qd7xkf)M#MZ_1UHhMvh1oxsjB+NbP?;q-!=@(0;s!=&T!202M=R z5($sT;ZV&_ynqN>dkhR!Kz<;ZiV8z`b*ae9rKY4scA9|oH?sQ(5OH{MF@!Iu`PME8 z5}eCwve#@X;rp)+sH?>1-)*Ec!~#Myl7b=n<2mi_L=W?W*(sn^5=z)raDAAMd`MZT z`ZR}=<>G%jpx2JJ0WyjxU$-}K$MUqsv1E}8@#|G(LId}LJM^#hDt?eWETqA1BBHCR zDMtsfgTMxFD=D4yUozCoC#2z4KISDA@X@tOtft{8OsU(3(Z)& zqrITH+KjSj%)ZSj@Tw5~<#-55l(K-8&Mujq|p{ z?#r#o>oni$DoTw)#4t5QqEzaR%=;NJ+zLc)VM37=Fn$pjMDFWlPW`=2cA{TPVwM*^DR05|&dq0<7P2~Z@VRO}(QrQ_B7;QY1I zYK1zcY?L^$r1>$CzpeY3#WNm?1XJ5+FC6i$r$+mBVb%pnxdmIDRVCs`%kNu9aEDH; z%fsfl65JUsMR|?`ns&giCrKPLUvI!hivoYiAFT{0H$J1)3co`0b5r)xjATB4*K3s_ zUi)z=aZtZ^TNE%r!!OhTFLi}+OE$e3!`D;%xbe-<@8O_GR2NAaS@hVXpF93WM%^0Z z5kcm`yF4L032p#y1n?YcwMX?eF7SeP>abC_d=)YmbJ*8~Q3CF<9birCsGdej@rHkZ z)=VK4L{shlY99`fP-_pXInQj-*(KFegV?*i$x+|Us~6?z=JNdO2BnXk52dbU5pRvz zdCY0P`M|HU&yO}oh+5TzZc_cKm>0jMap{POff{}iTUDIHfP!hlElQmG0FFGs}g zzdUht*YpIXT_z49HzTz|%FyeQtvi3U4Vq3Gq$Ydh+d4ud`1U5r(JMW)%Zl&?f3q5p zlU<2iNoky&E9lly_9D%L;5bR~B6dfv=TjaFwI3h9SO2s@N8acL)3xo?z&10*?caVuCZ9ROBZUbQG^xhq+~Rjz6c;IwCU%xb$k{4PeLi%4 zv|1xjQ+wT(-(>w+)7*V)E<*mTqmNy`u8|H$Of=1jrv=(;F_ps;shOjj>u+&zq?Q7= zdquUX$G&c##HTe}BX^lZpF=mvP9+JYhv=N9hBq^oHf4{RO5D}U-z$GgMCY1L$wfWu zXJ3}@_yp-kpvLbBs6CL{pRKJ4iU9Jr8^J9A9V*o>=PMP9tP-E_)h^@CJ}Yra3lc_d zp@JnI`#xxP@jva`_DCH-tohbOtZSfT6MHSC63S z=W{yzJ`t}*ZO(JTC+UB18jBy}UQA-}fN&$Jp%rse0CB5l@WFYF?C17<*C5Ve{`h8R8=1OF&tP%cadA6j^^0Ir?36LMxMIgxVB8 zn{9Sg@#w+%L!?~Xeh7UkuErg4!v6^|i>S`^(OL*^9eAaM%$PD6PAnap({^Rs54BAy z0xL6(%m#ncSr1!(s|t;=fzb}BJ$?qa-oiK(YQ4K7K&jvcZ}_r@d5o4$f`kBKA#gff zNpfA&lWk#Uaz%e@Z{pD$s-v0w=As{AbcLjh64uLJZ-=$24{g=S)g9dRY5*H!?pD*( z98bm@MjItyr#pys;P1W2g*SJS!l?>OE$=ffSrVN zy>r7+v-f{l0k;+D?@dFIZIWvmN)zF)i( zP6lK@bGTT#@dkpuf%PE3=)4XNGufr2n%@3J8Y*%I1=~=?T${Bj^ctvzr?1fB8{-7n z;8PAr6ae`89j7i_1yJ?`zh%kHEN5{)IZN}o;YNSI#y7Lu^7iB&Q>jbB{T%^}OQKorKMKy;VFhl5k!;-nStWfLI*FdA!7OYB>6=q+fxkUcF8TQ8?ER&; z`c7QwI2;Ksroj;wPEyAJKq4wIazW51^e*Un5>CYRLAUklw?fH^{YraXh;krpuR}$& z7Bs4lE+SVNkp*Tg4N6-xzb=|vu_1$*j3$2_0De%qs-XKF`IQ}Hj$P4f4pXpxytO(i zO{6eG?uA|Ql=1zWhgp?8yZHEc6Mu&~^L!MzE!l3)%yg;(y}@OPwS9}JWQgK-+Vx2O zph)i2UKl425m}r*f#Q>D7>x6>dsdUguh55K-3X2+vHF6SL0>6%;@=vCgH;>fldH{kLsZV+F)32mKX>KEl$hr8^2wr zR;>H1>et!9PA;0pE9TfDO~wSA5UQGw)kfXU2FAnXiA273z1v`2W#!vCsnh^wPn_tB zHvtCXSo^Yjh_qW6!0XSo>G-iRg|&a=fZy@WhP${pm2A&sjp`iZIOwz;{vK$Ju3X5% zTj76={j0Egs_GQ*@%t{kzp+ykiInFxr{Y%V>zeVuKbFkHCXcR2zQ~iO2m)LPlAC&k z(krU9wSKB_JW9{EgLS2l1@@xfla^o~7-o7To`C8mn&-d#$mtp7@coEaLbHE$8i4Bf z5Ft+vWkvAY&HOPd(2(=pc*bSf#B6>81VaJyQ@bjXii%X_%^rIZC)%`b#Hg}D)FL3o zeXy!P>gV4wulZv&R*|+YAEAGnT9v?k6{bEck(b%ErK;=5A7NBlh`{T;|EY6*NA#jV zXHf|Kb5F#1s^;18IRVDWQ+t23y`2}$q;mkWelys9mg#XLRU#Pd8gpF9b7__PLT|;h z645jgQ$({IEoYmLY;&WVvO-tI?6D1k2Nl7bidRPBBbVaE1F}25|Yrk$_65WQDec0TGl8M;Ct<7}Na>ygCSa zeRfnQjBSe}8zZjlrjD*wh+I92?%AO{e}VVdpdXGGr3?E47s)J#ib{5gDg=JSZ3Y+F zi*j7T1pZnH)cL)Ew!_RmK<&8NtmgMoZZ~i)4@AQ9p05t@Ue7OP=(X)$OT9|nQLJS}XKAzz`AKo=$Ze!Wp8FA!3 ze4U1DZc=}e%8ZcBfnVVh)b0Z&`j{mq8m+0g@7Jo0^lT5mXjc&R%R~Yz5^BPR#g60N z+5}Jfdw!%@=Dp0RF!M6pqxxF@Mx-j$A&TmN7ggiD@!adoX`Fxgfiz0ca_rEVm<1)M z`!1kErfHp(QI5ar0?F?|0wYX8o2tnkW^-2V2EM4&nLXH!?zqcrNI9aS&lvSV9=;jW zB#lkVd|8)c)^9(g7K!m@=Vp@$K`j(kM{JKg^y4tav}PnXTVW+Z(gPd%mmc`=OJB%%JtIbd?Kpv|=W3%$F~j_c$ZuKSnAR_TzXqlFJT{(u#itWd z=dMK@fw^_FYO>W+UVJKN8+_~1Mi}EBh}OVrDL^vDPrxMZm8?JjKf&`D%d#FTuFwzC zoQlvr{GZr6A0M{EzA)_?!G*%_Z!RAvfPXVvf%C6qMEQRY_B|M3|DG$HA<9M*K?DB2 z&WAhIFSjmdni$GxuSw>9aP}7MIl1<41K8mB`Z((SZhyz3bv*RW81k11^XAdWfe+w5 z7Nx&+U#8hM(Ho4&hSdC;W-jgYldKO@_Y70-OW|2fpoJ3earCVjaJscwrDn&g<14h0 zrJrxMaSDIEMC0ldYXMQhJb5!O4+Y06Y1=N@h5MZCt5G{bCtn)nqRKtM+y~FNQ_t&V zEd73#C%gF?jXFno7_r`#E?=?-3WQ&N5#CfT8x&c+eVJgGru1M|S{!Wz91)q{5P6CP z!;byZE>JxP9+a&-_ZCyRXuvUVgA62ZlP)GpJlKDXUMa|(fDTO<%_R+xf8Sx|uf&tp z9?Q=pSR%Oc#;;kR{Z|h#(#fEMvWib0E;i7(G6<>ks}rB_(VWFD(9V}t zB^3N>$dHs5&g)^B1|!GAFM9sE3Z~syq$!;7R_`jq%X2_DZG+4s3 z8TB6>2j^iN%lK_-HOm&u)oIYHa)M1l7j**#Nvq(=s9maj6;0;?k5kBkn}Wm77z6F|+=V>z6$SHmle z$vEuaK5t`;1^z9XH8La<&GuBcR+Lf2y2&qtEM=tX`bEV>sHo#FnTF*H0wyD@lS_Zn zw$89sic&wtv2~e4;C6=IIj0Wj{3HQ_lWh}7Kkr^^mi^l7JOeI?ekH{t{=N)-b6B!6 zr%@eOhdU1`*8}-bNT6@qQX=61kqGXH#7vuef4axmvav+glYIqF1SK||ceCUU`-^6p zdV-Uu$Y2pt0z@HYB;@QIjVBbZ$!>oZ2l(wlv+1#=MawQQJa6p!yhtk%HtLYuOdhZ{ zI>Bueg1@u)QCObzh9hI_q*-GZI-7IhQgfKTXShPRJ=3hW0=-n=~vux;)wDwVnC@HsQqvvMYR23=2@14R&t39jBfq$sq<=naWVJ!%$3x0o3vJcf) zhw!&2;Ny^hqL4Uw70oOksx=IYW4_UQcYyP#{n^|7w&aLTms)z$fsZF}O`R(R&{_Al zCT3RQ+7lUXj#mBe>4`d*;EFCUI=7L{ytUcWYD25FOPpA38?M&Ckww z`D<{Ra+7fbil#CEob*u`n0Pf&H#MFO2Wl2xVh2x-GaQ*}Q+(;bo1|2|(*QtcedA zY8B3Q1Rf)Oc}c8 z%%}1e+>_JwvLiVLk~Ox)QbR@Z*$4kuK< zm%R(a7LF~xfY|=x^XZblPQJea_2FM?cf+TLTS9z}0jSD%Ml#ATh4x5>m;MM&1IcPV z=YdV`=e2(&IQWoe5Pe$ewNaXCZG5af3BoOn0jz(hA*4#&IO`rVz%apZdq!M2Ef7Hp zpcZLrBHOTH&1PfW+#D)tI>_nE>PPO(+3%PBS9Ici}dMDE}O7od= zpYo|7{Fj?|v8qkyw3Ych2D{-;!ynn|yvowrr8;~l2+Q*vsq2M{zIWz>)$ic+-7gH{ zzU_Ypg40{Aolsk}!D7~(&hU??F+#(8Y;0Q~8 zKskhcx4QE32rDc-`)UXSCa}ynHx9q$w`LrD(ZWS1qT}qh3>y_rW6naHP_3+H)(Pzw zT_34C;=PYHIpFB=+e>o&@Q+u*CNN{M&ar=BRO}ZHq1hb}ruO*XR4bXV*8 zsR|7`8%3oINgqmxwiwHDL`+djSVSGF&7&No&ybmg6(r|QaQ^tmm6fVv^ZtDlJX3QYy>0x&oeiZ zrb!J{!a>_Qn@41EM`0=l#iGTDiH_1AsB4UR z!QwszWC{5zaPl}qp)s%<+`(q+aUg$pd%2A@g$ZS58pb?gD(3B<_R@w{tZ=}y*lQX( zRJlA2H<3%FL!Wuv3zwsbN=fZ=sjJE4Fz^$KP=#y&_eF=8*CGAK9wYH|5TWSx@+v7I zyJ{BbCKM(>{ZP(DeV5A$=dz}-CcI1z6x)fonC|#u*c}&K|MsYj5;t-v-Y|dKv0RK; zRI?l7%lIK8&uR4{{to|60xL*12tdU$6BWKl0)1#Ln1$R0?F+w}((%c)G=8S}N?i*4 zHg`~Qi~6c_8EMg3MJiA+$2=9*MC2`N9?n_>XdKIQmi%4x@#@MqSF_dt%jx%bX6pz7 z3SL=3)}H|`kb=|6-*GkK`&WO_3dVfADUl{@{kzdgwZCi^RygFgzRVSfQpzwSXjEE5zEVSF(P8`gACuJ=BJ@Z#`7i8@IC?vu9YCZ zm~%1S!j@^cj|rOP0mS{I%~O%9}k=T=VlBk9|$3N->VymvOVPE@}uG`|a%+!;{v0Wp*z7ynihq z{Ts9vlq6>Dtl;>KhDSr_UC^ie;CE#1>cX9yW!ntH+b^e zK5c3T;~qsjG&Ls`TjSCQDt*_o0)Eu+5SIHJOkjv6vtyoijqSV*Ai!G#&ld!Ali%9N z1`G)^=uwGYEXmrhpv-e@emC$0TIbzz2$LEU0$MZmR?2Y)p)ueOSgR;pC%?CtqDKd#IFgLuMh3{d-$&5sg7M zIY@u@?!RM?dc6x)t-o>W=hdCtVId$7j%klWO4Z^IsWar`f+i?#Qn346p|EC&OJHHE zFE@X0sut?$R#LM`MwMRXqy$)I?qTB>dEea;i6xQf$mYIHUsT`^en&UHBlA>R-4SBL zHFrZ#k19oF1(7UsgE?i*tj9>=d#LAAw@}F79h|c!!|JGtJ~+W0JT0=gz^DD72PSJh zlw)Pw-U?+v#N{&DjLm%{-wSKvZTCS$v?zafef(OZ4xBg=NY7T~NkN|Z1qEo0Z@HpJ zH<`v2(|j&?@aN%oH$Hvpv&wUCWw868hUycGe`oC>^zZsjhTP^d-i>h4{>Ze5lCj0= z#j?!~kVfw$2j%yj;H6rH*$(9G&4#z1=~$ZPw zsD-3NLOx9-&Kh=ho^d34W&d1nl$P|3R~yV>cYv2)Yt*zgz8A~7*@@;n4cc^1l|1Y+ zV^DDNn6cZ8w#mHIC9wmlZe1wn#J?*1jlmlk&7jh5ySrHvDUhA`p2;RDubAKF_*ggH z+V%5eqe_|L>G@9H;ka&giK+KHCU$>f>={p1qm6>jy7;6sBDHZO?ZYL>pE9_~4gRs}3-pL-K!vX8E-B z#q9d5hSV!xiNlBhyC>7H3M~H6WLr zwrO#H8P1a@{`d6Y3`2Y8nC^cEsj9l&!D)o;FZV)+W5pTSzyOy2V!X~{`}A^J&AJKR z_pVQu`=x{hLC{0X=;p`>W5msRlPuI^3tB?A!@eodsBvIp*x6_zgBf(;Ty;=O_qwSvLi z;1)zgR?`^2a>A;`ot&R^@03E`6Eq{lFAvN#apJ1!;f?uO@SV&#%YoJ6=i@1X=4Soj z$dg=k9dT9lqvEARWt61}Lar?QmNyoCtgh8w)Nq}WlPu>79`uyu*%UqN4LZB>MX36ZR{e8j;G z{#)@cKiyJgwZMP3906^=^W4x!yMLkz;qbp+Bi z61yJ9jzu1rabSur$eg<9+;)s7>Z~rUT)9b1DglURg>=xD3j|}cvUgVpUwJpG8d081DX^hUm{#+Jgg)LXJ zwZRBm$tM~ZXle-45EblIPn!EHZWP0kyt!i{d58lU%8*l9fFFkP-LH7Z1V`%DmB_Qok5cqj!HGlxeWbx)IaJ3%&JnZtnUPCY}_`$K|=k zUW&J0q`C6towM*LM`06~gZaz-f&RrBMnj~=#$6l%ZG1jq&ZH256}H3*ek2rh7(A~b z*Q`+qint$ccH`N+pUdi&?*H!v1OdX#-^&l*I3v{Msj*O3yY{#7BPdIJ18i$)WxRip zgih`1-yB=~%NhBmYV@a|s;XFRNP77I$B-|JU-ANY1v9g${KaENarMTVrdaYayVxXL z|F+STydCQ%+}|D~WuQz_?3oasdq$N5M0LFN3Rr+Xk`pyc#ET>{OI1NXUiDKxhN8c| zw9}OiaI~JtQM#Z%7<2C2!1Cl&o#20)tdTow)~4L6)8y5IS}0{+7x)&jq#M^TOm$^L z54CqDiwf)28LyrpSX!*Fqu2}ys#7-3blm6Hn5O}S>zETq92YrUE4{9oTGk4^Y_WTw_5x{fp6!!0l$xTr{4DuRX<{9Tu1lz82yv5Oz;%KQs1s_UV6Sq~n20 zPAsmlRq=ko7-J@C)4W1q69vqIUOdP(f;w=10L$PZW~anbvAN;Z-$R|2XycISh_`5 z%s8S7@B4OTtNAEUSaujP2-1JKE`2?6x6k&@+bB)Nb5$#NvJ6dy)NzZ8bhw&yHiO-y zHkO#Y0&opSxrKP$&<6^r-QqQ#jk+3mAs_(DmO=jKiidr?{1U7H;!n|=tj-<}G_jTA zgV9aly>9bmeWF8%;TrT5i^9E9I#c<}!z*9~6}EP35@IQ8pk;jLhjo8&Y>5$JTw_#r z&u$IzYE-9V-muuDpOaF02+`ODUmw!G;4FbgW2Dvq6D|W-i7|hG?gc_Fv@`d{ewa}M z?RMpb5{1v-PvJpwokl@B-l5Apc({$FXv6JcL|0v3 z$7}3N1GV5p7MOo~-8kLUN0sHOXrB8}Z$Hi$KI5Q6@ znk=MDJ^7XFd|<*Cl<_CG@2eCpmKR(aLpdld!Uk?fEvkPpb@6bI2#LtDi+~##L49fw zIxeBC2Sk*K>O=juLKx!bw{I>OHyW;v&zW1=TUsuelMnQgu1l%UX$@u|=N!zC0180$ zzihH)+w#tBM)<>Z3Gi2L6k>vVCjM!dGIfDMNAbI?CGCa&S+e z6;0s=41a$#nKG;9w|Y^jpDJ9}L-${jT?URL!ivzg1LE_|bQO zADb}5P^xtQ7>_!l()zvX6h@=knQ&wi50uIYfO?K-A#-CKa?z8-Vwl%+mQ(4x{ z>`X{B$wHsfOYudX`06KY(fcYOa0jPz`G*}mulRrEh-WU9y^QCe$!r`FSD5Q}0mE;N z<|9}V)6tn_KW`VVwFOxWMWS9Zp*oB_11zf_8Px{npcH!nABg?AD$hifJiQ=w!cLN~ zIvf;t13-Hm2Ki}C@#Zwo+9#T4sVrGQyZW!E#$l3pA02-nM{ zpB8^YsJMt2(7J`_S;En{9BDk2rJRs8Rb@yxc>hq-gLVF%Q{Yau2{soz@BSC-bc7a; zpSxSXxuI|=%}&Ve4!PnOh}4DLy|SQJZtZ|UzUQJtQAJynOTS|p3Yy1w_YdQu;VhEBj7^TJhS_B)O5 zV``d6Xg49xHCKH~WvZ!AA&1??-?Bx8|dG2cl%+$<)jx9eSm*OX-X{%HmJ zK=uwL`%a>ZYjpwTI5zW8)bS$|z-NC??b|)PAKtu5+dcORqRsK8W!u5*nJFZV6*Wg@ z>$3HRta@DqBJfzVFhR6?kl&P5AEGYOs@;sDq%czL!-qS{WrtySPo@(T?yyITAI~lA z$JV|X@nLIU`PPNRU+d)2f_l^HFC6EwjjiS5a7syH6)ewFXm?|t14kGy1<8L0cm8_M zw{-m8F>z0L)&nhC%o5U8cW1*+a97_;VTRGS50OoJV*7&sLg-MhP%U zsC%eB%tt+dm15YtbUZ7NbQg@&Ys!lDhP4+x zM&TD`(9mLMs+ieBgb%w@14XoDjas>B@{+|x@++RF^dyo?Y3ZoB!xX5-0SZ!e@^VBv^|n)9oy-;! zS8lBbFtLESTt6KzLCB%6Fc_}701yZXtpRL}(F%p;FuZ-^^$t*mgIMVfmt|j^p?p>) z!RnL+5xM4Yi_AJClkk7#TL%CNe9NOZID}q*n(G^nq9RSriY?ys*)kZ!fu>84TLAvKt zC{T?a)u#rB&NRu}Nc;?TKh^P-sNCqZX$gle`;BDYU;7?*7|eglR%g!=5QO_-0YaU& zvr28**T@)#9(dtkw{MHvG+gFKzM5T+%n3GW^+qc9`JUM{3 z3H*X%2)CllMcM|RjbL_Yf^-Mi{AJDs8s}hgi~}^eZhgOY2D?&%oodZ=pBEOQtj|jG z=wf^=sLrxeU-5q_Qwh}{+6pNQ9H`QYs$wtu4&t~ zesrigHmtL8KUB}h^g7TO?9;S=eK-F$S@`xRe>JVpgvW90#)bFGQZ^>dS$G;Ix_d}x z5LfeM+_a-$NowE=)lG(E&?DTVveC$AFYo2@jfX_2wTBh( zuD7miSoN)txzqFz?7wpX1$nJtEo(tlq(ggIh3>)emW5ynLWq_V$t zzRniu9F$?@clmw4z}4jM|4*a=(=hyrz65z@cSV0oyA~TKgZeKr7Ac_1CckjOGYov1 zw~Ez>J~LXvdW;$8mb$2dE@JU;7Q>KG+gVufD|z!x0kZnEqC-rHXU}3bhRaljg#Dj}jeCf$YCw zQtZ>z5M~K4f0V)!dz32N^V*a$gy4Q0D>@0wKwMw?L&+jYRj^Imy}dN+3p_y;mUu_$ zHt=VAb_!$rgoKacGXzFzZD~CFDisJ}$8l7v z{I?$$!+%}QYWGJGFCf3HZ0CXPr_New2cqC&#b8>b5Pufqxrt`cqDpnOL%h9@pl^9@ zpe0f(CWf{SJHk5}HTQi(gy$!HW``4-$W4ga#!UfF30uuFXGJvaI@8*zz?d#8 z%LmKt^XNK&AGfMfOhJEO^H*G-p>O<^(QQUfO(3mL z3QGnfno0|#v@qI==eP^ez>BZ!`^bNQ0y)bUvucH0vM~>- zG~6ZIv*ZT}y;e(=pQ4BRK=q4Su)P9DhRQ#vYBmOiNGb}I#>48bG+^RUk!utko2mT@ zzIQ!b5KJB{zvYlyo*i_l?%GlR&95R}htFO1J!#IjkJF)?d~g%RaV1Wj)enE64cE-h zp$jrQsnRWHy->4FCj^liexz}j`;YbybLvbnA=I9V27g*rmD`JzL$$H^xK^T~g#!)p z+@7qVcHN0@Z(AT14=YNA$5Y95_iA!MoW{$u0}ot-K{m+1psCauJJeeSMFq*~;i2yR zx3~nCra>32lF~4$e3dVEz}tTd0|>oAs(A-@oLw>s%(-H}>2E=N1I;)RcBBy05$l;N zoF(X!8KO*~=(d-2qGm*EmT#Usr(<>ki;5%~NS8Pcq~RaG+jVStpm+MgrIA-v!s{f< zUgO#qMpkJQ0_u|!`hK1q7AVR&3P9VyBPL&NYsi8LodWYXJ8~hI5RQMGSuVg#lkNGO zrW~bU35jat&mr`(> zS;5TeUwA7R(=JGpKc=owx^m9;29Bt5zz5CigUdzN%x+6$j-use_E-$zQ|FW?6ns=CQ-u?{!DIUrOO0Y56H7#JL$ly~04)1Ykgc*xah;C!&xXm+qo`^_Pc zF`HetS2{IE&qKY*f@ZGowb@UVq)#~@3W^(Gks|OsqJXOfSvl{i(Hsj2&l*P?TJ-A0~9UmFz$>9O`5-A|3EAe?z8T5lkDYC2xT4z&BeUH{Z@Vvhse zL@k5cDPE3T`mnd(|C}=xspaX<`2LlOnHQ?UrgD%Dd{Te1Fm8CRgXk*&*}Dh^2eeG_N>9nh)m#nm!ac25m8}@ev(Irh&mt$CJJH7?(jK^kcbp!++y$Uj z9SVReST`~L{6v$xDJsaaV8s@M<8>78web6n1jM`Qc z!K~(wM3aA6P5s^Y77`)R@{5;;Gu*!b-*!)v&1NWEJYsZ1e)WIPF-88?6`g~m`i@(k zH%ka7Oh#4u+;#Dc?T;=@OrO$Uz&B+HV)_J75BQUsZ_1NQLUyho`!HE!IBuk2tIrMO! z2Y4vORE~;XjxXH;*Cl&0zd7ESN?~ZsU~>7}CK2!~=pm)ocgUx)U6dGi66=&H=<^L$Kt5V7Vr=a zAQ|WH*t%KQQ`%BwYQ}@WG^a3Z^cpU>ZUOoxhbcKAvN%xD^RhFe2e@A|qk?AK8 zOWLKIww4%9@vNT7H*>r-cej{q?5JM=y|`CbtzzX1vD(l2DmpYG-mW?yl(NKl@AG z>fQR>=UmB+i`w=CkBgEJa?QdmX;6Qc4i_1%{nR+JHB&W&-+)+Dw)o4B_^!A1u3fm6 zemi`RTS-80Wi+pGmYlk<`yi<>bc^=HRr6Nll;a_gXL+08BwUORO&rr#3T5FdnCA6c zs?Sf|6+m;|tW3}Kqw+Yrc5^ZLut*7b#-2m-> zx=ykt`yKVc-2tE+>c3H5&X4y7kkC&2HC9!e-Ezc-u?szxHfo+2?evi3GU8pLNu&>?!gtPOqHHx9E8PU&d55t_3hFY zD>BTTE&L|zQ=tdl)@uSh7&0!&=&J93=dZVQ`BNakTSyv0Qd*2ky0UNsSbI{UooG_M zDNKup2yKDWhEPd&Il3?r!a=W>k&lKSvEo(SQhkYUnGXt;PhxyioN6*#x6GY%|Lqze zX!Gm^Gm^T3-z9&5ukovB&)!{z`Hi>TDJo-<9qLnA$v`e|XgKAP%_Q+ND+7;znUOQF zC1Zw?5x=dDx6Q~wtL3@$Hm*XFr|w-mKP{ZdRM#?Yh* z-j{@rohQeC-0+=mOfZt-y<>OIlF4gpKbkgm+#SPz2QH@PA#iPMuS>E?!jGYXWi|E0A_&i20YoYS zOqJtFYzS^lKgae1;L&n_%?wjb&+4eLO|&mmaroB0snh6_lL9&BHc8Xiv9dN>8Xs7P3db$RqcV*|~E!5&j!H6>S|%-Z?M11_%HjQ36O9%(%Qu zb+^4S**T>4f*0X`KDw=l$Ez$7Jw?l10@p|8ZW0M_;(NgiNT{oJCd{yRqF2V0{ZaF9 zz<5(3l8q|_K?htuEvNa0xfIr6@zosu^NkO+JbgztF%dpY`33<%(U^UV7z!`MRV*bR z(SJ7THS1Z)9o?p5EKuj_1VX942-(z8*XJi6F9jN;%spy<(DS7Sefz#`X((vBwV|HczRUc`!&9wCDd%EAL5 z;ZP_+(euea?ay-RSxTq%E0S|Sb_ALEy94o?_T5@1jE}+uCMSYdaSFw#`1p0kgo`Qn zRNPS8TNwR+Z2vYd@qg+G;aBVufUKgDiGCmoEY5e>+N{rW*LP1UT;iv`e=HPq-P!~= z`(%}EJ|=e_Ln;)UU9X}O+{x)FH+$rGIp*Tup;(IwZ6R{)7h2PLO(4tIE2HZ+8lfRT zGIUdVPwBelq*7T|I(O+1;M~OqeY|y9zDw+;m@6uOrPRIttK~<-S7Y5cNagi6Nw{mMci(-)eO+>~K6K<2 zi*J-|Te`pKMOe?uQ0Z0aJ&mHrD@}fGgy6V*fS0+{3|YByI?V44y-9fX&vmqti7EeLfydXf*61##gRS8Cw@hX&(S# zPO#W7xEMWO&ez^>%pan-85x>(<)iRs##otut`>m$$lo4mZOeE;LR1kEqC48mXUm}Q z@7ZE%7L120r)_Cbcpw>pn(*V42A6S|1Wqubj}cCbxcZ}@Ac?=`wLC1bon3=ik6|$L z9{kLCE54Cy7?bG0xd4Il4K3nUmQxg(?z#la^OH(0As9G8`bMmbJ~pYG0hP@`JXrdF zx$jUA;X|`O_b?A`f~lN7k9Y8)jTP5p3MO!6PYpn`5W5kJT+{1&qZF7w`yVAiC1iKlG z6|NxAJwwc%;uBazUpfo}S^REtLfqzmCo3z+P0{8rj$=Uf#4aNQtQ)2;P8mx;u8o#l z>l@?8Jr!CvNr8!cl24WPDX>(aNmR_EAsH-}Aq&FO-)JKS`h z+1)w@ril_do=y61gGR|0y9vLVIjKIlO*^(kuqw7Hv?ri2mCC>8yr4-Vno`(*|Ls}U zisfPt*Ccy96e+q2B}IDcmhxIQyNGct%uj_D-;v+Gzu)SW-c*RkPf8l*wNUxd4qir0 zBwDask^GW<(w(O8Iv!@B!-#c->cZTuVfq;Du6ahBq}5H^KWHy|EFe817(36nTd0fg zk^A;Ig;$9*E&(|AAHn||GVtYpg=JcQm0VICzqNhIjo1QK5xS9_x1g3EDABj8b_62> zw3yi!b37ftfvHf?x*2(7Vgmbb%-b4YoycezzXa7q%sOx{Hss<0pb}AE+RL5lk|Fb! zkSWVB)OOjq>gJp zcJxPviZ!)7OZ3Y%it^#w`DqGo-8#1^yhW-I6R#}Y*eKXdYA3nmW&if8hy>288e5J=F;p0y`dZ!mwH|s0qO7F1M|zqoBf<91lAeUU z-kwd?4U|&1Po0mjG4#PY`}k%J>-8y)5YzT{LJ`W+=f;j_82is?2tQkU8+OW!d+4f- zrJe14!w^%8bD&>;N%l@lT2{yY4zsP-VF^|Z(2PpgK=&HV;U8n@M@c;v;1r@lM?w~5_! z1@*4l!dt&mc=IXXNR#TPihQJxshy#n15*D&tB!7T&l8bV9Ev{x(Ok zZwA*azH-NZLr3$DMd&3F1~LS69k9W&qR7%lvR(AG>u)L7=1*jI-vdB%YUBABX$yUb z%O3dOdE+4BJ&jUiMGpHh;v;V;q7Bw7LZd`E8djy{{=s?AMyXD$J+; z`;M7^ZMj~#26Vkjd=I{8OgmW)6=)F<@Qftt@I&e7AcoC4vJ546;w3_W7>XwK)~1^e zr&tcjY43MYoig@~B5DE3zx7DS=7zwoAF6w4VZ?Ty-?X*`LAQ6er8TNHB{*6aYWO#{Rsu_a5}QU1r3 z+6=xt{rse5#Jns4o!OTzJDfAk_Z|o!HO}aQV7a^Y7EPFipcTyQk$Q?x z3r2V-w8frQ*pU>GO!qE*UOjVw(knB6^K>dPlDr?mw_hsFQb)@02*~bnP!K6;hxQ;f z4K^4D(-d={=Op-@gh?)56jYv*aZauN5<`a7NiCuv5|BCYcSUhg3BnJsaXjo`N@G`V z=SSGYY3W$`=yFdroBZ4Utr2FTIBGc+pVdVEEf+WR>oS2P<@&B*sHM11OJB=>`2Zhv z6C*C$2!!2ZkNyGSdB9bRP*bUu-$A7@+X{~~fphXr3%{F}VZ^7IsyUJ)+IU6?x;o%eno^PB z9V%cL2BwJxlwYO3#Gz;T3>u8UkZ*S%4{i^m{~em|%*G)bt#m?`o7c#HfZZq!?nOO~ zB2u1IG5IMp3)i|dgIMW`iNzo@OpEqWI4D9sJ$8dia75K~8gFI@aR{R^a;ujfg0Y)t z&Epu_SUHBwzu1G*8@5@ptOk=Ow62sLkLa@+VJc%7`T3p`ia*`Mq0EX~S|wy8alO@E zI0~&3_>JM48K)(OJ;^hFW^r#9Yttg#fyZv;PXNi0(W^UQsjFY=HoYJS7 zD!XrY9})u!r*fr%N}?@H(Z~GBf*J+!LDc zBFoqss!d9%!fceoCrF7rIb6~oWLB(x}UrQ{c7T!-Od=V^7lM1 zf0Phqk*pfs#m#HYVbhunlH}W{&6%cN^f; zD>`#k4EyDo6=ylA5>ItHZ8AWmjHnbqugx|DZK>D8Ro~-(Wu~npAzaA^numpV2>yQk z`v*4mqCs9|Ul>7&Mc|oItAWU_6Wg-Aop5Dp)a2&U*@?XfjUtd*-Ad#qBpYo%m)bt+wBMUT_0yt;gWgr7S6bM1 zJ(r@)-}~)(-U4(^B9j1V%M@>VT)om~kHgU&S0&xF-E-0K;Cq8+OPG zmr}5B4~B^UssU^gN0!FV>#Xd~iFLwNfn`3ROu`Wr($%PQ8Y0Qn%X6Z z)KgI9qe~{Sd6jlRT)j*J$K<$AhtP4AqZ-8quW37sKo&(5g&BF@o!-8LuIbh%7I&J9 zqQjG41i68h=^k=2jIQ8t{j@*BCkyf(`wpa0B^^9)w3}KyCbvt+b)ljBL@iFI32~zQ zqM+%2<~nq<_fHCDZ)W45-9xvv+M!fhhVN&6=YY$)ljOQm;PnP|Y#>cpVD4Ikj*RoR z|DNQpry{q{7>_*BE22kXVjJScoqO7Dk^`TtV@dXD;l8;`_wLFES%VQ7qGV~CocRIP z^)M7H_b3Xuv`;>?XHQ;gKCQ;a&+mI$lOo7}K1=jDA z=X&%zH*YtUruAu4i2~|(vi$xXl^5cF=SLszAD`)les%-2iWC<8>BNJfkJw7XTZ4D) zWqzByqtZAqqgF;(&6k&gZ|odB64Ht(Q}b|M9qgJDF@f~*HbPAipbt_;K!DF*#EWOV;mj*-TjTrwxs)#NrBU9R4bg@W@K;H84KooFdKJ6MbhsS-m%Z^{lt! zv$ZM2plzk@DCM#_XzJTY*cE2)m$7MyzH=hPn!^$BNG!-$5O>PC!$CSLD@sNxw97HjCQQ3h~ zx48j(O#Jib>CEQ^)Ybm+MvWX~#1j?4miVL4-y3n{cLt6RD9VZq=?eCLQd!w3N`oem z31k?RBw(i%$vWf6FcfB~k* z)ytB9@eM@p#6htF1WB&=h>k6Iqt~#=_SrKvX&R#v^L>Y;-?2_*2Ti&4nYicTLl)en zP1Bzzti7KkS-a)vz2RYh^}L^?86xsrVIm;>-5cKwEeCvW6V0xv9CYmpPcuReXL^=~ z8D>Pf!}eVn4dKD|d#O>RU#U&VcEFxYVC6d>96J3$Ir1Cgm;lMsr5ew2P^4rVLRvA& z0uPuvwo_p;ssy6|^fA3Xl3O~Pf#TrQ6#U>H3H=_W{V9SQQwi>Wx6DBVUx$^LnoMNR z{K(J`+z@zRM-=k%VIDKs@ZvxkF;o_l#g-T9LGo_6Z9 zn9RILL43OYv?jg&UBvvr@U9N1{XXeKEb z2V$V{Ln(lN8NB(^h@o0QvguQ0=<9R>Am(h0=3c`r0wt9Ys=wlv>Sa(B-o;z~}E?U8ogW;NpfDpG$Bz7|9XcY{ zXeF#-UPFH}-Stq`W7C@rl#65{^hm5#d?Muy4#1(drj#702Jq$jN<~tkvxA7`f$489 zbB`JQMJ)X>60+FH_AYm9g@JSu{8X*M@43P3n;eR|V{ecr$m8X?dg_v18|2wnC?X47 zHtrN%+{bmGhM@(wfTCJ;ucNk8M+XJtAqCTaF^*|hTY7?Qx%SNpPvLvN02_*?-^|}( znLnCXW>9qCYA25aJwbRRwui~F-H@oT`W&G7)rSLAOg7q%Td>qU_iNCwcgWmcV;4;kDmW;32oUwUT*ymmL;;jyhnn0z$|PR|1Q#qIX24fkEx>IeB?fSXA(C(Zhv396p-z`ZLyT)Ich zX+1?aa2$=z!r+ok*Pw<%U|_!O{YZ9bns-fb1umdZaDG%)a z12hL2vM~dk94 z<$VX6f4gm)p=e!OZ>p6l*c{26+%_^XvR{`L_?9oTt!;${U?MrzP_x&1bOH%nd^tu% zV_jA#lrpA7pz>b7$GNjttO&xNa7T}5o&!8nq+(gCuS-BE67)jgg@y=!^Rz6w7QuBE zGa~mIlE}bMHoyb^m%E9Zh@`}G*_&WT>J;doXIekCxXJs7>t)DNN49Eu*AMqBGw8`4 zM{rYRER3D!*qf0vQ>;(gE-|9DzzIx& z1v2Tt_?-0g33MJFp5JtTNH78vUp^q&8DguUFs&V8)6_P2WZvJz=PY5QwWVL!vhuUxB#kxE!=x#M`z z!oZ1w{2-ivC%D7Tldc@%ft`c;%c=5w&;f?G6VhMba)Q3rCD>^Eb#WBdrXwOgjkf=| zFq`k!LPOyBz{ATF)bV-BZeOKU#MWN`a*)2Bj{fL=V)SN0{W9#lRgHfV7j-UCeaUEP zg&f}*m9RSyhC_QCHd`n@un~a<1d?8W@!Xa`q=8$1)=--gc|T(iL%`0NC9Q~;mlOvf zjN|KVSNu8~Lv`hRBL$Nq4fhtmh~?O*!=nH+i=1w|Pp!{kR$Xz`@<8b3!OUmTP*1b^ zmRI8GhkxDdpw!kVKR9^C;~+vS<>0g_!-smchXiN>{f(ggCB$G$ixVr37=rdA0OsCo>oj(Db-C-)9&F;0K7={g~h=-uXTldD@h!t`xQ5P9*rbVmk~l$+SDrIkJ>PMJW-=}3$3iG z%GaFUaU zsyybn+rt$Z*J7DH`i@pD+EE12MU4UsL;oEU!{~rQ`_!Vv4MMsH@oN~2pi=6Kt{V|d z*#bLL-kB3=&f}WQl67b00RQNJ>6A3M?x!kw6W-L-PSM@@Ia6PL>WA3!0LSXH_A`p9 zkmocORW~Vv7QDUcRbzmBp$S-O;BAA(10;`;=WXOdZ<1QshQeTfN$TazXTi`99Ff4L{ zKh_|FF_;v6J8+f@3cir(?}0{*SP|g*OSUPR$lQ2`5($xSh1y82MTU@i$2pc)F;0$rC{NAFB#Nk z3VAIxD^0x3*iwNJSr)m9(MiMvinD+-bY@N9shCFb>Kn`UJ$I6S=I}byHd~FkM2{lw zh#w)jO1kh@d)Xg-?CzE84FgwQg)qa$n-=Ttp4H%ilVLc9vE3i*X`c=h$7W=#d-{%) z{^c!mj}SWHbBJWRMEqINVs_NmfZ?`_P8-ZkXrx`vq57$7mcsKtX=ZX=h=zRr^IsK? zAkk-FuqeeM_!W+Ss#U(SWe(-hZr@g^SC>&<3_7Qg6z+O}eMQ0e4qeWczsG(X6k8ib zvclqt*-)>CC;HPi6tDLXf}Ed4HdS&iKhVN3Ljjhndnu03TgY*g%uPDDdR#Vl4p!bSwTao42Kg_UF1rjvOc>AShpqHFEVPnfeSAU|wPSnIYeUs#21`%-XNnlsiLt=uXW4@Xk z{z+ayBFdFZeH`s3OXUHz(Z6N+gFq!o__HO&Ns?_2*|=BB4aJ2WiCle;a7|mBTAE3)q{(}ePx;6RbugA;PW+Ej0}`nhIuny z!*kH)7g&F*B|U$e$0St7X-E8jF-r!#?Mj3!vyQ`i*fD_^CA|=f zmN=!Ery;l;@iqq$3iff-pCQJ4*0=M&SQt#d^S)0k6mq6`%p&cxe7`I5S0+T{#6M4S z>f*CX1GsBCkw)mSl#JE7Q~jL1vk9}FVm;e0&5T%$Cp~9T;d$!g%Y)qf)J~#D@t~;* z!2<$+uK%temS2PB+?bBf@O^8Bgnr3*AQK_jp=X10Em8Oim&Ak1{q7Uqxc{k0*9>xL zk)&N{IeNKs5kRmc9fwdrAF>-ofTw|TFdW4z`C+4l(R zgZJRKBLk3paYH74sM<`)%?c<+lo3Gb7;M*nMS|2H!`}^y39fn=BrUpBsqud&(YjVN z8i(>*jkMD!`e|%7J1L(s;X!CVmwRjX$hnCD7FumZHu>2KM?xkz3Qi4Fev=VjwgUt0 zBPfn$=HJyL1Fj!`1aedRCylWSy8wfk{Xa&1q@`Wda*QxX*UCa z%5mrHu#+){Tw5bB!p3fiv_4Vx=0EmlIZFH`GRf{UxvFkzUQ&k{I-7P=v-)tqz`2a- z^~U8(e7hOdF1pM}QEHZw7O=#Mu-!a=`f=0GhzOi)4o;rloMT5I`N&WcM@-4f+$|K` zUDYG>?{>iaodI&cZjV3)_?gvU*JkJ3NE29y{%s@CBr(;@a9a6LDw(yI))$V+!I65l?&gn&Y}=-=_s=@Sx0Uc+G7@ag`#Xx{q*({Te#S(6^=`Cf z6o{b>R{!etC1i;UwleM#`u2}32qcOy!Q;$>ghdfg4Errn2|a>|ZvwBPV^WOcJx%l_7K zNbrPuR~-dG@W&&@+u3UGyHH6%MFOy}==Rk%88p9eAIhBh&@b)fek!EG*pV}Kla?L& z5jlTF05>qa0{_l&BNGpQ{5r=3Ss%SPcnZizGbwSL)h^}eCDvichv+3Z7geI-A!&UX zF#JFa{+_d>)XvtK&#P|(@_P`8JHN`PEde!u=rP4tQSL8qsGV?eNX3%B8i1BBJmPBA zs1P7&ziPS@bp*EB^do>>SZkpk2{7Lm7z{z zhqHs8!M=Jq{*BQWvmj7lwfza+7>cP=R?;j?2lqQp8rFGWSZxC?Z#c2M{qB;nQ_rs2 zjP&5zm#6bf>J}SqNsTuw@cpY!!AZ?ATlK)c6C&@`bAS}1(mI}QUSE;~0nQV_M{ zGq#t_l%RHp&aWxyN6FrFdKzCn0Vu)inkIBfF~G|?OhG_@Gs7S+j93u)eX4QDC+2%P zE8WpApW=bSPgSylUMR5~_!dXf%a@?|ds?KJ@k=nTsg)0AJD9GGzpK^JAJ za+z-^sFh!IRTe=yCceHnI^5w@IUyS|Ecae$Dw`;EAg=m5BmDW?SeL<)hSr!L)JJpp zSb+=@^`kR?;zEJT6Wr~`P2)WT)4-4e`smz9VFFtXy=0n}_#wT@t9<#@P-?}pX0o^$ z(Y)3Reat2?7i9>Qpfb$|uhqk>0JYJEx}2xi$rBk~SzGG6Tu5fm;3GkaNqq_hHGmNic{$!_TlBGNQDK{*C5)b=V>T^*W`HIso}LUs#vHU z9zFQnYo;#+i5@&jacf@fFpEG8{cc#hL1OJ=SLG*cl=0!K8_Hosefx!ieovH=pHJ-N zA^SOhw_b`jA}M}~s~ySb??HC>#T*R`pM1MAd^7*{-$hdpk7#vo*@>j3G?am7x{k+} z3 zzzcBl^PJc^b}~zvkWd>y#?qkp=5qC>bBfM?t%gl@6m9Hq1sr`xPG$k1_w4$hh8x{) zkV8d_bTGauy)m1HCucmsR=XI2-k&(|b+*~D7Ud{cab_oR`6KTK%#U)oZr?GRc-x9F zn$R_~)gD`4c~ivHdh@z9)@!ys*(`2g9^eSI1Gi9);*y={Z7lescxaFsf%z>S0!O2N z^2Wma@7lBqAMjh$Ex)pyU-aOAH``3GeqANBX<2J%!yuP)rxq=K6oHB~((6i}Yk}Ee zX7|YLS*JJT3(uoNqn+zKTMiF&NiJnFO!rL6AIOH^jFLiNaW9w0c#LFjz2U5M2;Wtr z?(iKGrGw?)tBnd?=&!_$Am*!DP72I_6Xc7WScq{|QoT)ACjuWXb`JamkfzBJRQ$Le z(%&aVE2GFxGPa7OvGdGJOGaxS%uaeQjjs=lJRHPuOZ57W=`*3S;Z$~xU~#m6n>kII zffETiBZ!-~vih4&GlFC9rq?seVh@+*EvUKBg%4!t2g+6qZ%iQ zM4f#;sQQ#YTS^(&L{yAqr`Mi-gI0S?JPA0s@T~oZmdUrS7eKK3SyJ49R zYjN@{@SrQ;_cMRJmrcRtS-trMmYyFJ2hsatFo!Zzm`?#<8sQos|5e`TL#UlVCnp8d zUeR{}uYS*`jInw>MCd?m+MJ4iavK31^U?wxmjV=1GBqIY3zc2?RJbx4T$+2tH$`6- zmZJ&+TbH{Nk;UcDmh&7zr7_#+Ow78=uq+(js%EDXZP_niybp#w_J-1Y6A|`ggf%5P zI&^&&Yex^%rn-@qo4=G%E3EPgq<5aNmmp4G@oDzKZEjMP=9eBbl$c}$AtU#6Dpj_RS;j6q z*lkKo*~Y>y7b4`L%^*mBYqkfsNH+j+C#-bysz#v|Z7@O;=~jBdf& zF6y>z+qP}Zwr$&d+qP|Ewr$(C-96jpUTdEmBs=FDNhMX4C-w7x%6*Sd=OFss6(A>9 zrlAK#jttARcC*!O>@XOM)oXzs;Uu6<--G>BzBmbr$B*Xx6jvtHc$!l&nN!qG20r=g z`0tc5j-65d*(BI2GHm-I+C+eTB86V~x-hLp3*;c+0oUYzf$toe-Ln9Md_&P(PbCyK z@wMKne&{R~@4tH9KK_k|-UL}Wzk{Vjj2RdTwE3?bn-3VBx=GIjFW-9Z)B+T*$g`#c7cJ6`TA~~zdlKP`Z|eV3 zzy;l*i7?`!YNJb(28J%)7RSwdCcx()km(|-H4Uf>6v+-N(sL-5LKq)N22mlc7E`IN zSs;_=1pYZ}2RTqQrXpXqk3Q|>|B&}#8FCzHJSh}^pQl%j^*yLbrakGTzx|oPZ`FXM z=PJ@8Mhu?|A=C0D&&4lLqy`74KKF2Nw-cENDUix`+aBPQK%+&)?)4}$2>uM1|EU=T z$c8YA@X(JEh|P;XbonKT1&b?Q?znxeZ3!wPyf}`ed3l<^3m~E$mU8!uun{&h62+at zC`ulG6Ry~^-M@;+;lP(e62uiqz+5G+{~1tD4DleQnvXY^fAGn9b`N-@t+Fd=Q`|t6 zgoZIVf$X8NmcKeX;|YoUXd$)jG?3`xk5;V}Pkhbo(`7R(=5~sW@t0ylajYQJBAuq(6M^DM$)`Jg`9ydoOm$lmyvTr51caeX_<;QqM^V z0jtN6#sl`3(uOeYn zT-~(&OAT?o!(ZfEvzUjA4`GR1X_yi2lR3WS_|wL$`#eLn^?WcmjlwY-{P`#NTE!55 zRL|3J{fFKY`^DOT0fd%3Ir44_w^r2ZUxor}uau#qD3(jbMZ?(Dp4bAwXwP|?jEqIK z;=$W_W|d6Z&QrZ5`0KsfqBn2C=c@*ZFQP<6=%BUtJtGU&W$~M_$QduqL{_1txP&p8 z`J9rKG>MbG0&fWj@g9iPs1`Z>NM{d!XO#YvCWM!);H)&9N|Gtri>1F40Y!xahv%fj zyG()4$JZH|w^e{1Z!Ucz^{c+S$gFgJmD$t_Af25eimJi#EvoT`QB&~vDgV1BcS|8< za5}f!1#GdNJ-e_MYJYjO-yE85E>ky_HHMR|$)I12DV7kKGaMn6lu}JGVtZhJaU>^q z$zBZ=3oK?-S$Qrm=Q%`DuT4(9gLIox>H?N=jbDLRxF~G2=(OLx<;x~?akfCdC~n4- zxFty8$eF)&ZBMt-g0{$-4ANQtJi7qZ_&V>1m&9^YpXA^5LaQuZ7sJy4m!6(3oqP%p zon+1+ydX(=`@+V5#oCrc=%l%S48!p_wYw;BNxir6HLF$ZzhDa5XJT>r(@up(w~w)o815G9b=^)C#l;^gEr^am|E~_5%5y3aq zw)4gW6J2mP2m!p!6*QKA_cKIeRWYWsV0b5m4;s)ImmG97JSobdOnM*YZCR}uNMyzY z-EQf;mI-f^>2Sa2(a#6R)>Dmhk}81ME9JJ#gGeNfPFMaE_nRJ_rz7#_gU3bqsvL8| zKuLZ-E5bd_+lN{P#;Pd>hNEV&HM;Plv&=`69$FlMF<%#~^Dzj2W4?U&2v!|Ky#?A! zsaf^Sl|^mF!}}-Q58v5n=d^@%E))axDFBMNQ`;f|0$Leqf^Eu_SwbWg zzQ__^a3C`#qdeZi`5k6vZ~%kJ^s#`31bhHPnz6cPTVMZwL0cCHKJ0}C#Gzh__u2&U zy@QRlDw=znAyv}itthg{+T`M(2XNv2GQhchNb*$$x{#O9W}Tuq-8DYczWQh`_RbK|U+ zA}YUGE4&4hFS zqzb7`FHM|+1(;qv*hWKhBtD(q1mxH|?dYD*+Yt|QqLDMtSjBC9j^1H(R`gY$*{_Iu&IN%jnsRAF(#~rs zq(4T?B;iPB-`ZXq(2M}`4^hDxP*63)IQD6c7AwDldQ@tr+`OW*>7kk)1Ti3d)?&h` zJ~8lr-MaIly_G>W9BJ7_sQTk&57YoR6d5^4vdV@LX zrYedE%P|5*Y#xXXik-&m-BFxqt!1o5Re2||gwnU#C=>B&#Kjq zzY~vQ<6bN)kQ7~!VRKm13M4u1u$gyopuie`t}9oqaF6P^(aZKZ{~qyA1ya4fMMT)! zZG-bmQ)l-$(nv)O-_NFQyaqLcGG|%Y$1^Mb-lLLAwu4Z z<#Cl8$o>)s6P%zMOCB9>f3P$_=4?DuzB%3Nu$42R0kIQP{mi3bj*MLpeBa)RHQQTF z$JMo8qR$K^e43WsMT77{lp?YX(cM8)fsS-b{DL|P{SbNF(pZm%X*#z~Um1vhT0q1J zu1`sKjw?p>k}IWn#?e3b7E-hdMkLl6i!+??z3^)h^&xO1hpBmOH7E2=t4Eqw#cLJuP@#V13VD2U7^1e!)5e8OuEtp#4wEC&lpuwYAktA z827{bXU@amK|iM4+>A|~-IU;e?f95xRkrFSqJQ+X2}Tfx+reuX@Dp7S{G9`Pbj9wA z`x(NYxmwG>_e}(g*$1187JX29EP=0GHiq5R-3*gEVROJic*5JV-8@~I31xkG*wg2? zT@*1;id*e93To)$bvm^a%2D;VT;vMlzOHK&7zL$!*7z%*xD#N}1B;Y@XWRoQ@;9c` zuPZg)ASBP~Fu4{t`i;WO+qNHGcl&oAU6PABT97~Z)*6+4osYtsE2rVrMwki5!v|aD z@6xT+7U`M!rh!aB`V%9L#M2;;r!ZB%ScPQ&xUbCGpuD;8k)vPfqodT>LIXs`leF^y z`J$ndz&h2VXvFHt&iKfGTIjFfc0uG*Q_-^&-7xo%Sfawt?SYFb>92C~b4v2l<(iEk zW^_%FPsBA}`%uIYEMjhT8}xq4Yig7YEBK@<@H5#Ptep?Bp>KO-mmi1&6_!SkW`n8i z;slAlx?Wh5>9=`TjhR)Jh|(SZSRu~A{eWbl2?Bms`+R`V{gI)6wMSSs`pMfECxjpl_&VZH(b3=v~@udz^)>h@^g0 zwE|n!R}(qTz#8xU2BtOz0_|m{0J3++pc07g4ca#juk+St*17_vwY$=F$vd&@Is!A6 zq>o*zZw6YoD_3-XZM9Z;uXS%vE7Ga!)f3X2Hqxd{*vWI_897UJ4!deCvMW1zgZoAl zr2GfHA^bUn-;4~CM6@zU%Q+`ak>w z0c3DNbJHWK#M+t{;cEq0_&%b9MXa_Nay#{vLw}qQ1S7V8h^a8O$HdAaR;$C60M02y zf&nlloOt_v_5qfh7wTp#xIql)7YtBZup&1nHh6PXnm|GDxK`{ry3iQOmw(t9K|&l~ zDE?j$Kj)->(#$jh(+rS;sO)%$f>QSrDNb5F>OuxS1$J{+A_+r$^B|rZ(#ir)v|4^l z#A!(Jps+n>f{Tw$M-p%u9(*Vx3 z?a`-E*T=XxG++jGR&DZ&mFU52Af2#KpQ3wO*O%{G-J?c>yJ+pODkECVdPD+f1l~lU zh}r|8Ube`*Z62u?-x^awHGVcYK8L5c5$utfk#s(P&L>j}i%a_HGVq4}(K|}Bm+pQn ziN8^E%fa))24ZE|RlG`5r!{ZSD(d5mrre)GeS%62HqL&6{C|eCYD#oB=%>-XOSLlg_ z1Mf$~A08{Ya4xQtHYJMyH$ce0zndsN(7iFu9GZ+e-#mC0Ivk6LiexR;JeS`YC^D82 zWTL(NVMV@zVJh_xDtnW# zt*3lhjo9ocO2#tgc+GO{`KjI5WenBOr0*mE9}0l-pb(;$OP33?sZjfu%~7TeOx z#^rVUh<89m5XqbS!DEctvFcUkKvnZLXO5jcTCg3E70=-GJ4P_&)dJyn#x5eRN=1ur z>2tUBK&dXzbS@PCd&%5p$tvS&1H^`e}ZZ(LCJL#oWmoFRMTqo+~y$xu;1up6fyFBh1NY3|)Q z{*R2gtZ_j#7ijMTX8U^vp>w+?{ne=cEr@g<+}9=t&3c-s^p5&jK^Juc-N3j0$(y~{ ze?J@XW1-x&+&jducnjNsu1rZwmCDVfy2KGsCCvF02pN|mw?88bDFPxa(s!U;>;7;5 z==}H*qy9`jMo;HKjQGLinRRIBQX)BrVNN(!f$F7;0wiCh$h;}t*H7RnPKStrn~xOa z-MK{XB8_gQiFh$4p;ra2ahvTl#W9#;e-JI4MyzwCn*C9a2Ie2<3SEu)ZP|}xCGc+Q zD`i|(*gK;L3z#3eb&^r04bVMP?3)KXG{e|0&k^k_(MTJ3h5qm~01aP}yz)k|-&2gY z*TKi>E>7A@>?&c7dKi1go+WoJE|I~-;RkNs5J0uGf>I`4EjjNQoXZKCw1J!6fAOih z6Xw29!z`e8cY#JNl2X}ttT<2E=6fJ;D}~hydSX7T zAvZ~(bNqQYQhX3iRyWPt>o)WO$&oK}+z^041v+UO8WZ$rhHG3~rwd$Bf0!y6We$^z zIo_g#mmJpVB++dyAQy~$&B{%Be;`%3xUJTqfvx}AKgc4kl(K(Q{(9DLHC>4}NpQ_y z>(#`T=xQhjJ`?)PXkAc8k%>ri%F};3-4cw}gWyv$!cif_1p27$m;0Pn4mk~UYx&Y- z4T)mc3Fp+3t{Oy}&S~S^e*{wfdyl$OTWiYkqkU?kr1@yd8UqzYD2ddwOe$_opG{0n z1>6*V6}f$PJ$F0_0H>>V9@L&3HDQPnVvD z1(cz4U=9<+gf!hHX~{BBiIaQ1X&`X@h%;Xskr9{|TS?(y0@y@bUY8g!gc~foc)5eS zv&7oncpx0)UKbFle++4@aWaU#P>mhVzGuQFHSKSey916^QtSfo8{|{*1~D)9mJ~Y4sRYw6wwt*`Tg#PreopP684!7?sEMs>pfdYoeDe@BLU#|e-Tj{#2(a-Ub@if*Op}~R~j_J0fnY?Hzp6A``YeYY@_kP z>b;_ab(eodHh4v4Bq3v+q$4pENUh(8p!$%ezW>;GKY- zR@05|AL(FJe+D`}XSo3kFlv9pG?xB>(d*^?vaZ*?&@-j5k=!QOvAKuS?uBXFa3|{s zGlS@cC17O_WW0@b*EsSC$+LyT)S9DOa|2ZXj~B-hf2JEvun^%(#+5CKk=}wzF*k*4 zWV2GQN~BI?vbLgPk(S*x-3|OH%@6G+oGXuD(mqK?I&L~N~Hn?(3kpf=D^0xen!-2? z<;&uj)ve7jc$rEzXDpzA-PVqxXU^Te)0$J+QKB;{aW`@$ST}jjxDLc}j6Z}Z3%et$ z&d6xC$UeUjiN8JkB z0W~|^9=(IY8~H*zLyzyxn)?;%;N~wIRLN=Mqn8$?Smp_w0DX5=sHx5TMKQnUPX5N$ns z49tDHEp2^QG!0k_5Qi|B9tmA6e>rAIS02BUMIRw0vmF>Ty=fSig&(%)czV(Y5Crf)CsIqxvR$deaUv|u&e z#}Q-;Qo9Zmzht-8eGqPJu+>K{0d;q^0$(Eowrzq!qgYkE9aJEz%Z5OGy{aAh&^LJRjRe}zNI`MeM@C$j8B*y{C#$U8dWd!g@M32Q_qEcY4 z6(C^x4vZe1$AA8z)IDuB(v`$uibrcOh!v`odEFJ}a9I)!Bpr!je+?Lq_qs)cE$0Qo zfe={NsmupD98;w^?2nGV;8pFx=@nA+KQBgtsA>03tJHd_+JnM{6IP%{`^PJTfFV*e z>TG+@d6Bc^hQRt3lFp+;7oa%UelB);9P71VN*#a>$t%Fzsb$q?ia?7FYPeErGA8yd z?MP1^Kg>J0PFSzse=aG3&0mW8H&zs$DJum1J!A$_{OBl7#+?`I!hFE_lZr{)Y3x13 zG*Sk{E(z?MsSZN1gnTg{i0-R@6H84QOnb%bYEIh^!~{TAv3N&Flxij2;$UWHE-hGI zTP!4)O;k4zk2&r`Ty5JhbvbY5!n ztnxpjDt>d(2(G^Et>K*;%V)ItddJh-O#{5lpK$@+5W}Qo+fp%@8IMsv68Bm87AW7R z>UJ-CQF9uDfBgz+G*3$iEu-8`9b1Jak#w$OL%a@1B{q+8^qew^w&65;2a9cYT=kJaU>>*P1{O|Spfe|Gc$D8&;= zJ|IU=AG?_!k#|#u#`1&Smh#ua{tWpq5KOi1@rwJge**^~k^?0Nl9-EbQdmA;x7aBp zP%F*BzxW1irOJdBIk$aRak7p1tvS@#NC$YKXGUv!`HK2&B&Z)Q(6zdKr z-8{bAe$G;F>l5A!%yLo7*aEwV?-Z!h`Q~k2N)5@Dm1XORGZQaVs7r5+{M*I`ims2Q z0Kv8whJ>a?c1+aEio)w*h5)hJHjDIIZsoXje`1Y_4dHT8dr(wcd{|s#CE#BZ`s#kb z8aXF;k|Zbo`w^^doXM$30y!4b6~6IBW0C4rJv9=qx0Vk{mr|zp<6Lsm~olTZlu|F zsRP6mo-#4WK`Kr55T730ZQa}r&R{-ye-tfSrZL%Gf5&_2pD-cPL}0N!2}=DiIg*z| zjkaKf{x*)IB7G-Eim4>S7g{o)#oNu55RH^G{G%I(B)-MXupN@h=p{mG7p+4IRZP1F zvN)Q(2<>Ef&5lWjLhe6GU@V1Pr|_a)?aP07Gw%#n8fU}b7L24jb3_LMO7JZlf9$_G zAgwJ!&PZOgJG*pZzbeDNqfCTL;3a zS^kyM?H(0e_|9ZPsuFuBGMpU5J7xIOcQ7xe902uxZPRJ0ty`oxK-^PztQ;&F%Ad3~ zSNTbw0ROf2+uZ@GPC-PlS!RNJ>H=}PL=A4bR2*f3?^JirvUc z;mt}Z!b-7tKcL)%8u%s%3oh9=PfMv_Tw9F^Q!B1jty-`Rh#)si1$Z*N3kn^6tB*z%NfWz28CU1m?89UI zTwjb5$!Hpr8jPZdQhYa5uS)SU6y)sNrT zfpO=cKp6)cxGG+iH5R9La?>@6^)Ppb;#zie@=(qb_$q%f3x78WJ+q6R@hk9 zEm|A{fvb*J632W#)3RqXm=3Ic(sevmPgPKSH4CWgsEQJEo3;cR<^Q226g)AYBOMGV z-pO7BL??vaK`jwX2+)RwdzoAqA1Y8H7D5D3Zb|$L=_L(OE==VF9(jJh0Ct#Osir;Z zaBdDS&_WV=dp6NEf1&VSk6hgft@P>RhCi8~rGnmUj_f&lZou7iJqi{Ab+Hx=jPP`( z&oU6-&BSJ2q*XWd90s^*nfN!TQ0fMg*w0evv`5JY(NvNEi#pd_ss3dIt$uGLyEVby z$bKO$(i_L7LKzTd6!wF5G6iPLHcz*i6=KJo|-o*<=9sen#2)ahlLA?joCxY24QsS)X(1`@FX>Q#R4@ zn2h0D#F-?0Qv?!6@r`sZowuO`ObSujD-QWB2~j!AC-kh)fL-rhbmTyP&jNill~CD9 z$|aipC(m?%jD2&zx6GNs<9DDzB}(&22mckSIZOUK#ej zl9Bkn6EXW_fD(NEY=hJ-0iI&6{`3B#?d7RiI>d{~fAvg(?z@V=JrxS+r6y=4SgS)0 ziE|is0Ix`9bXfkF!bl;^G&K_gljl&5n9CZ3oqSP_YQNHxo)!Yp#ClNg+*o6&4>+FL zFYbw&MWsQ5MD5Gu_{1jDuuQ3c=uVTD;9!A4d@L*NuH=_4{xN~A)l7~ELx%#4B0k~M z(`ma+N`nHtNaWPw8Mv?PseYzP(PjLrJTG#KgCvk%s zd5H>6Z(>7=*Gwj$cu0UEuf#CeEYk!iN|7)7C#k$akb6f}m6ZXgYw9;WWaf+?V=1_C zud*M_6sysBL^R%7o{WU$6q)7O+L5F#BR47}SX|ZWc>f3B)0(RgY6e@)-`U<2u?L6hU>d zqti9+_>|ubKF1T1|9DV$hJH%`T2+^HGb#PX%JCtO<>)9v6`ns%0 z@-!=&>qjtH9PP#H>&8K+CT+bq6PbX1)^k4>qJ*0@8*ttz3o&Maq+_rD4*LFVvx;5c zuydPEB-`-zEnoncc`%6pHYR1neXqmywE!zrwe`rzK zh7dc^hLW9x`@7dTd{6K*3^y`3ClRB!F5}aWA8(F36@M;)rC(u;dJIMWfOepXW)e_A z&*Y3ly8Q{D2|J@pV*yT3}YJGsHFv4#x5wY5u|6 z%CtUkl68X?L}ikzwZyeM0jc;)f7Fa(NnVPmmlSWd=cN%9Dt$Vobwul4!ECHNqc5=K$1rSk~`*tGg1jmP5m6_zh*f1@{c*g50w zNF&omWIM-TMGI|%zdP;DNm}rN) z8roSjJm*PM6Ayr~$|iR7`)&{O>f-2*fUuY8KSkP}jC(DJGGIC~N>!JBZCqY;0$M@B zQ#(0fjgh5Y;ZCKij9?|lO{-v6R&=E zTw2g2lT@e~jN&@V&}g13|e8 zL+HSqkvVz{J4K4;P+@q6uPt)4tH?jfdvd%G#EDv8)0>L;wtU}ljC7&lCF=b%YX$37q6M) zY5bsgaBc`)w^5zVmDZUu`ucMm`xiewp=Q!gx$u1`RO&=Jl%uca%^CWAROoEmvp^<@4c6_#NsMB(B?9kTHIPwe@hGi~Cq zqd;J<86-*BlKCB#^$(o{pw9O=NQ= zrEG#>uhQWdkBO_)!C~u4r`Zr=Ym*QaqvW=R~`IsY+KV!i;uN zSY)e^f6p@ypoJnNEsFQp5gjp=h8!|nV7WP>ip!1-J)D1_B$lN)!=`JktzD-!!>)us zd*@x1qiA+o3|}o(9EaG0tECEUmLy2EB|+loI9ZIn7`-fL#d&eD=x@O8N@Wl<69T!D z9a`U}bw*U)juEt1#TvJNsPlFZy_tP3Ze^pWf0kX7dToWBqRS8`7Y+Kku>!*;*NdPd z3NmY)Si>B)X>t%@7sb1;4{v2f{f$sg$3~c;t=>elLds6o^9(|9kcm-1BjZ8czX2)z z24T`#gxr3rCmp_Czc1_7hz5ql`pKVfG(uef)o|8)gk9fbWtb$iC&7~L%UL-Scw$9f zf2T{bmA4PTEvjNXyb9|khoJ%x9QcwD7sxm zqhC@8pmzcFm^6s{yZ(?aj3+<55%i+fJ$~Gh4n$VPSM;{--)w~&-v!(VtFJIGqTLAs zUNt^^nBQ9cuA#Q>_5k33OM4RK+I=R5Ihp$MswW&93N8IsRePTE|M_0~p6f$?e{;Aq z_=Q&g{g~^fTJ!(5SpBA;-MH)nybJ#RJc3C4{;c`S`^)Ttd=rlU#{Q1wm-n$@75xZ~ z{Q`buKVP|j&+hx?yngiN{PlkLzw)2e{J*I`#`0l)-d}rNf4}>_=VX4z_WV=(YCq5R zhPcrDf7#`wU$%B%2K|3q?5EZ-e}2C{`-Fc1Um62~oqLL=6Hjw}OMY8F2BkA^xIgb6 zzgtl!{^`G;YOg*Xw?tpJi@*N-zg+(B`K>+RTS;&>+zj77e@%4&YyRQCpx(dxzi&%Z z9-oB2XNouJe7~P{#pA6`fA5k?X}1Hv zmp{K*h5im#O5az%AO1j!vXD?XY0uoN1i(ND0O0?eLBY^~prD|D=(u2If&M=q>wlJq zrGu@Rh=Zxu9|u!2TSi$cdow#DS1S`2MhORJ4Z~|M!-`#ob~>Q_JCq0|{_j zN0gGTCzK?vY+>jXD1at@e*gm8{0-drhuYS)9nH@c;1|AZGzHy=aeckXQG|_PHG7vG zTrAgj9gSy~S>dHN3ek!W+Tg79*E4fuRM7v|JajaDqj}fda!liannTxm2?|o&sDN^` zi4wXG=DGsij(h7{`=7~>Fv4JO^w+#lK~as#k@V#Ak!j=Bzia#!f7--95l398>s@*e z?Q>r5U#lW`;tOJPI89bz%6VrEO6ugSiuB^o)5a!=lv8K+mMx>kqIE696yfByQi@63j^**5e zR1)f|W)yK-v`94He_!Zq1mEXJRw@g3dHjmBnVEtWztu%Twa=Ns# z{$_JI^CfAH>{?Cjxw1<#gH#v9){h&$~c>6b2+ioraT5jWK>c9W*&YSGhzRGyPKSp#{qhdNd?HTrNcK{auZ-Q2qxu@zVI{ zZ?Q-FTdqd^myOyJ;fULSDN*ViFmF)r&#Uu@$z{AAd)%fw7D1KNo%(NccZ^?XzOXbV zqlsn7U9$BERVu$Hj>6J~z=jEYwHCZObA8a;ZpBt3f6|vdw}PxTxgc)f=>3s1n21}?f9~Fr58%L=P%~YU}pS)A) zf6pI*>=&i|qXYwT`}4|S1LS0j8P$*dqadza?;>J2&!N5V36~kav)_LXk>oBGIo9!8 zG<$EMe+x|U6Y$hGgKIe7tqo=mDDp-?A;8ig7npWc{SyNl5UssVNC-s6G67lg3%}~m zV_R71Tr1;^M}Sqel=t+X5g#MU*AoEDP2a*7qHWaNo`W$mWTy7jn0FAb5>bt?LiM6q zf3QC=^lf+@Z%bDm;AgRl$t0~pX9-H9#Mgv*dkxr|X1YF~vd`4S&Bb&|3k%^+(d5ZB zZ{pGmIi3>)H26K3@zHR=+ThMjo+Ut?DBet*Bx%m^=<}uDr8$Gla=Y6Z_k442g@$M^ z8|T%h5Mg9UMJMp3pIka|ZQHlartxa^e`0l}EE3n~DR^y@JAFLtieZ2a%*Q0%TN=$A zkwHsmm1b#*XIe1wkSR#B`B`PT_h?B>>+%{L}sKypMML4S8ls~ky@eeGZZMwKQ!{VKVY^q}Ve`tpv zSMiN?4w5NMy+%t45ZuZRjD%Yl!e02CtX+4TZ&zGymbT?B09m>_>d1$~Fj}0Mhk1mY zckIE291L%JCz{QnvfF=J%WefO@W-QizrR|mMGJ1(`WZp_im#)Om4e_0yPnrtz+q#e z$&JS+JjYD;vil$BUor?}lvnz@f9rMj?f8rec^|Pb`oEE44Cg}nFg|XUgSb$2676cX zr`R+!z&kyT8k|90dccSvbL#_oINN`y#-|PlT%9c7xBnVP!@SDW=e0v}M(}7cmr2Op}a0=>Y`>S0jS5}dSe>uH6eMNK* z>Vs#CCx!MBIQ#>k@;+<7UFxJ`yy>|nrTC)IO83^_c;ejh5&h+pmGvQ@KLXoKev>{^ zf*y%~Mo+7gjDACxAGchh^CugXd@xH{_S@=wLH2>dX?Da!&1G=hBXB8kCiX2LYwU34 zBP0Q;&K(131*@xZ);sqFf2|v^ZzrAb;iRL?6jZtz9!}AnA zy+jFF?8o-s=rbHFZaG6sK;E=;h8(f%RqF=*^e{59{5+#w##eF5ouW_+DuxU*w)6}K z0bb$6_mhK;z&Wz`I_Sbbr zK@-ao9q-}{=wTF3e<%w0<{gKBztJoIQ}2iT;YK6fO``oY4xv*A9P*>#b`R_G&O~Sa zSNH+*n*QBh96;_ld#P|T-#sBc`mgK*nZQxqx$0rHWhVav`aw(+&=f-*>#LoKB zF&L`{dO&@U@OxRB^UlZ-eXrmT{9ke8EeGEq!GM5xaQ`Q9fBxr$^8fFQ_Krib1d{)) zLE!jQt|`+ev{TRTV~d)-2pMMkIV(OMO=AV(pe#8iI`d+X!0}RT$+3rI@LII%xZeH zK5>OI?XbzN9W}JVJ_jW0@-ttbE(xKr4-QsfKb`?~f5TN%;&^s{?E+%czVqUUcOarG z-U>gKj=1r2)ii)!F|-nntJ${XX8tIeE*zj@bKjNM<`=SFk7&xz2=4D@1f#YjWR%m?$$2}&>t=&j`*3}SPSo0 zMcIJEe=}C8?O;`yUBN5xTiloPu8f@hy07OJ3#6Z$Ubr;+g6I5E4bjr8y*Y#$UM@+G zqdZ$Ka3Bs$KK{YRN@F?&X>gP{RPRkM*J~#ophaAZ5^oPGLQ~wHxOFB1w8@MG_j7Z6 zF{JFRC?mB!cI`d!F5T3kN2dZ9!LQCe`~v_Me}o4fB8;54%Jv+k``+=D=xnae0)?RW zKNt3*0>*8`MbbV+8~U_qR8|Hsi-|8{aKn$~-IRobK6L{=cT6K0@;21uMElmjr8{`H zD{*}~l?v>4Dt+5jvQCmusdOXg+ETTRXn-TSP>v-ui2X{03neAtWUIiD+#IR8No9h( zf9S*0V{!+3Tt_8Ew1dL=^Q!~Bf z(RCSX3Zv`&TW|?~Ac%(RRiVoz#l_+4e=Q@!?8(|`%sxC(9NXL5D1n`7Edm`r2`uzs zF|hjD0{ar1wD9^%+wZXXY4FkoG@HdlIp69gw*?3Q2Qij{uRxdU^b7HQr&f5ahCs!b za70@VWbErkZ!G{=+_Q}$S<6B^W**Q-CfvOn;+K>vpJ`~Mu zcwYg!JEKR;qI?^J^&r{0na$r_e+ch3;2y+z?|}9cN$_~Nugj>=od6F=2)^mHi?gaW zy^Wi~Ume)(&?P>qGW++0xgPB_%Hd^xn%w-CP*$cVZ2$DJZ+!~C!|M^U^pjwLV}9+b zGheo4nKMcNbF+$|oZBAp%`4MC)EQ7g5+wcUmv3#BmZt$lTFVQGfWX{0e`IK|^9usU zt6_z=bT}e(P?`z$yOu?M7`W?sMC|z`D#s;OLa&!bP2=9W*>`KL-u9HIih|ND2Qmov zeaR9*6n=Q1wwdozt|3BaLE_2RC7B9z#8PczC(i3|_tUee#PhSsKD!Ub9@%p*Xg}(R z(QftmdHAou+*jha?)?2df7dOK>~j8EdZNlE=1retxpWXWwG%Nlb{?ex{PlapSrm%* z+P)#h-*8Z#6w%+(>5I?aDi+`NU zyJBBsu$j6+b&VnIbMAd$3=CNe9~K&sbe)9O?@LiF`}4xJZ!g=&{#2aJEF^)tW=F0= zkj&}jZBgvfYgaY?fAF17#3+YMVD>@ISXEv8hsv*8E@;JMiw(zwdetS?IJ+OMBU!6g z-y_+OzXOItfZ=x!BJ}$CH+?K%31FpRC`a2e<6~ zOrX3)^6psP_V(t|e-rV;_bQ+0(DV#DD}5w`q1R_m&J0D^bk@J*VqL$+SBNmNk;w`d zh#~S0;_FC%fBkQXJ|}VnCxmyTAkJN!z9zAK>p#Ix2^3Kzw;{Z1zWquOX>Dld>PTM4 z+#||pg;){xoFKHzBe-4V40B&zi}63vE}(9-D^Y~I0CiNVS7jC0AM;YdEw79+3I`jqf5ZhkIDM&F>6FYFa??_&ntNbhzn;ZomoTh`)1X<0Atd#Z57~)1{~``CBVy( z)TMd9e>quhkC17e+S(Ki9IJyF#?fbRHZCO8!?^}>i5+P^yyL~nAwqWnE&KPf9Zhc&Zs2S+VH>c8T<1CFWbFB9Qen6 z-Dc+5IC)6@{POgFcN>ViI5MaR&uteEx~(_KR|PuVUSGFv&kcOvvi;yEFA3lG!A%lR zm1LWemH6T2X-_e-VFWs zVT*&twEWv94~W3!O{S_`w`5{;SIm0ed-sU_INLH&b?@2NoPVskX$t|!K}}2x`)q`# zc~wb`EF94^=dR0TLq(5n|ouWA^s;bKvc$co8P zt5}{`sxA#?LvXbxZpC-pe=M-=br9a-RLM`ca`;fW?6;Tyi$ktVN?{avpEbthO`Of%S3&LO|RJ&*(hfe)~k;) zlUKZkdfN&WsiRg!#4+r6!4RBgf&$LIy8Q~dXT`BaG%hpRH5Tm?)c3|rDqA0npt9wp z!@YfY>5QwAWQj+8e=}5LOp!pQsM1&bfan(a+qWnXbiDxQt;+>G6bR_E8jpE?#|nN8 zoUf49#<=f#W=T8h+m)*qxD?wv6_Y^Sd!C)>;4?j6_j&+lN-?Z%Y~PRItcyNJ$0GfH z>Gvp2Q{ip(JzV#yV!jKrx9Waw9f`D`@4d>tSSUJE_w}C8e|f3^DUSvWi5p{x`ZZWA zw~zy%5-Ypt8XiN7fzUy}27TIkuWwc5EtbhCO;iYNQglaqtV$YV9DZ*9ww=K+9rO1$ zIO48dU%VvmDW8-~6QALX1zQyOv%)QiMed(3bZviq=L)u({t@^bg8te3oEhBV6}`7i z@CWyggvDkZe{J0b7_3Jt$J#Bz5G-1UqCA#ZMd4O}u||F{=NsiwV2i z=v)73Ic4-69sih^jJ}hDx!YeOQysNgV?gM7qJ}t(2lyp;0YwA;GcU9s5UTM5V5QiI zHU3!PKHkeabYYj&28-AxojuHiy^ww2DO8-}*)DnM_~#n<20S&Pej*P=S6llL`uCwVMcIdC~S0 zOJ4#})~2gW0WDg5MO}y*8beUE*^p_255k04f5{0^-$RWt)v?YyxvAd>hz_OGn0X)C zFp+WstGlb^_7A7A{lKZE#Rko+S$F`qBJm2&y?klAG|4{J6eGQX93LG4rXO%5l6dGq6HIn%%wJ|^2L(HkCJ$z%D!0l-da**^);BW2Zu&A}V@-UG&eU6E)=`^z4EZ1l7Ic-m{VE=K;|sp!W;1X?6BuC(JGQ zM&*SSwqv=#r7r32auaXLX4$b=U5LF>x0Uo1^bx5#_j4{Dbq22i616O-1O63kf4-&b zn`aQ}u(lL0iUwi6^bgi%8(ZE@G=Df6<-t^ywr=V+GA~C~4RO1Hw(2}Mj8=rkVgt~? zJP>wo+xhhTn$BV&sjd&2k7#f4o_zKBEe=VrnOQ7U-f*9hPrG|IvEhyaKBtLgSlxU- zdVqLgMIB=rT~^dCVQ6qRHc}vTe>GRGy>eXsU{5jU%;FGL?TybsEbf}Fwk|FXx408$ z2ZrV-zKUJCDodx5r6;6sgKuILkmRj~ucr)9aPI^P-FWqTr-&utd&*ClE$E>dq%^lV zcx$itKJ(GMA7Fnl^wGGVWvCQU0f3Gh_9MJW_Il_VnZ-FBTgyqGab;cGi+&VXGE~+e3lsSu| z_aggTI}Th@!gqI;MXyn!AC$Q>iYXA)(RT7_*hQNv$H4J+I%ssbQ;QbKq-r-UmCsmR9oVJ~Jjak0FVXoO~X7=VXj7qjd@ zO*iX8=Gw+rHjQsjf4*R6!?QU@No8Zsb=(T6TH-p+E?r|FVG#32xd}oVGlt5w=}dm# zP0vvSqG*2k@tP95P_BP`Ai&O4*ZA86Nol-uiD+X4b@`GmXK?Z7{NihcM0u3fztVzx ztDSbACRnFLvzDBNV1V!E=|oz8;<$=K-{#Kq-Yz>~%rbD7e`zoW!4-ECtU+*pMcN3d z<^7W-6ls2a??yBtIDqUB+#mg6=QC${UtU&v#BoswFVMFRRSO5~GY9CKa4eVc%u9!! z{@t%aj4Tn7x!?66XjjKgFs}=7$U#h{baz&k2|m{`3gC#O{?rLvyzL9oGzGRROXHfg{U(CSDf9m&|0!ZYGsFM(BvtefS2VciR zSDS-~=E*>t1vA0#^{XeWRoL};W>onBqQ8&sFW3NFtrU&jfuObC$AV5cffTT0G9c3rxWT11D{(z0uP_Zw(T$Ye1|sxJnP{-BLg^ajmj;5Zzsk0{XY!{HJGfb>h+UY z>E>+Vf1r{fufgK#D)xD3yr(1j-T`HX8)xRx8^ir@_5q^ip37;n#yBaPT*#DxbJ}Wn z=-p6#h!!A`|9DCl&zFS^eb+s5`_Q$WThaacI~x{_X)^5n?GO5B|K<<$|Kbn-V>0~T z-~Ba*G|iY*c9fB=Cq?1x6cr-E<~;Q116QY2IyXEX?*0y zf30Cf4ch|Mn47HGI!6Dxd3=vm<~GF;m+{DJy)plUgf*W;1~?JDjbBtbW#|XQj3U;Q zuG6el!BFXmWpV{ddsx%YA4BTjM?Q*b0)nwvp%8~E6ajJ)vrpxYYd?qE3F#MpI`B3jd9PVah zt`mFYR`kebt^aJoREhzu#_9~UP%g&DOULB>Oj{1z=-jlCQ?I-oirW~C*GSa%e^!)4 zW&k9z9o-YMjy2TOFYf}Fr>SqjwK8G?^%)jDS2*AJphU4y%~Kg(njqmd2cCxaj$No2oeCh=LR*>)3`=*K;zkdV9&xZP>5@l^&f35!K7K!}v zHIh2CH4Q2Lktb0g`M4z$6cY)k1NB>yvDy%>nj6$%Tg{4n)Z{R0?MmO`DA_R@>9uwl z&jV){7#2FrA?f`(7#y3y>Pg(zUtmAiQS0yP0%EtR#}$DEJy3f9aj@|7fn)Uv|Ez1UbbW)N27By)f^)p_$N{Gwb^dgy0QL zVn`Mtm5l@BN(5YFnt@a8*uqlhkp?k6aJV7@@+cs>P8-tR;*$XR0w`%`IuyYpy^$1g zj=*~t;$f%)zi^X;sES)0xVKaBd7<;rV=D(g)Z`^QzYp!#C=7;qe*ht5fBp`UjTYdN zs=#k)^guw!Zd%lFMFess8oZ4J&DG4c-^U;fHI;|bnjGL#I``)u21<5Ua!{WFh3i(4 z@EAE?vY@**@u5-hpuMh9Y}atZ6prTbf+_4!vgl}6SC8J7bdJ|S2f0a{HPZop35M04 zEKQipEwltSN3U%|e@WxKlZGocZ!n3VtcRZ5Gb!O}B(xX4t@n%`3tYLcSI|Fhgd1;R z#rV5vNW}d&H)8x3Hxe^;`r|}`=K6no2T@xGL*sw^NY&bQmmT5Lr>9@C=UkFxIXo*R zqIS+_8J=8L!~DvJA4>MrT6}r1)5`ZFDvKQeO+d20A;Lr0&N`2ZIe!}_`-T~Q!0pz! zWnwl&wTa@#G7(%e0{!8EAd0%x$K4YfS7Wy{`2(4dW?gJdok$(>cQm>bG>?5E&&0X| zFj)j7)il-s+n(f(<$eg_ehQ*gbqE6#XDc4bws!oOmbI#ehs^r1VY*>An2Z*>rw%O? zxe^=+6cNLZg>+e_#D56xn5ul5)?f?uBsuP8yj!DBqhyy1+PcOX?J7sR9c-P%A0kH} zZ#VAs5mm2CoMmp)pA9GgKY_hSmI#m9)K)5ltyc$mCi1jM9SMEU+{khU&d;X+ualG& z7R=RY4K34tN}lt^A%^gMd}0QaQJ5iW`u1T>0*DX;NV5!x>VMsPy*gp@rWhOFv49rI z7;$GsHk=ss&3kalo4!;BK!oL^ZR#)R?GJpi=7C4Z5C+Toy{KQAu>v)%w1v*MkMV7s zT=0FdX}PNP==>_CS{m9FHcuA3EpIqersD^|*X@^$4&TWx58OZj3gR@ZL9sGw$(>#f z(}s5aVh{#qF@MB57G+r9-J(40BRK!S?%VVNzc*i*UEoU z5EXXAxSWmJ_WAh&(F1rCz6PG1iZ@T`vcQrd8tWfKehEt?x0%0&@JlQktJpQ-f-TYZ zcZhL!4$BbA?uI-X&?x{9(tZ{x@sy|qCta4Rg%9LC&wuTadZ>{3KuDvOq3rv~!&o#U ziy)m&8LZ_lY42$maUlQ*NV^N_NeTnVI}Krs2U6fUTXU)$#PdV=>iunhl@ z)Z*cU8U^Rq}p#ynO84dg^QX6g+2Fdr~L5 ztG&=;C2tnJ%e=kX9l&dm-v&5hT$B5e%y!Z!#8qWPPVERfO@MAS0u{K)!2gq1M1a>j z?E1b^|K=42?iTFc;0`7C>^`7r9uomG&H#Dwd4DL4yomvuYIN9ytNwsvLl=LyMSj~1*m`+O6$x424m}l&X;%cO2Uw>ZGK%9)IW>UEbA7x_Typ1&+o7*Ux3CY3; zPTRte(22w1QV4a#+dAtjCru1(a2gQ8jgbXu)H+?-R*SiN`1ZvE32N_Y@M4fq?pR>$ zb@pKj6e4!BgWb|a8{SOJ7FHB0y~btaCgkSj+_W|;;L2B?rKO~2Ib0Dp|2 zS_(P$X%3_eG0Q|MS~qYaj9K<>Q=*sl=O?GkZ~=5F^E)G<bt3uWDS)gWx_J7x?S|2bcox5Z1dLP=_;Us>&Yh=w=JGcWb8f`Vo zZ#t7769B-^>6d*9*T*jplt%>$TK#PZo4wamGvu4ST&R}=Hepa^)4%vt1+|;nlotl& zm*M#!9w(Wr+2SAuzeyqmVlhfyT&d)sXN+SU*?;zneaLyLKnq8<_5I~nZtxA!48yn zRqMs0c`LT8KNGoMqvR-TB!925#`*yGbAxckuP8pXmU~u=Y$T|}w4w~;D6<0T7GR`E zj}+O`E(B#8)(bfaW&@2BTmAIXblf)K0n z6y_O z7s!nFks8~NK;PCqxt_mWL#F-W%b%%&<-bl9DE=pq0)|e``cAeEj`WKEu&7{cV(egS z^WP9E%iCr!Aoy(6)PJt0s6gof!%2WDtqx=}mCd!|^9K;>0GbX%n)`lC!Oa+jb1IMH zp`mQOuy1AcyjksrdTZz5s#e9y1e8fJ>`qD^=2IfSf1Lba9)LGrzm!}E*Q!B2f2+P~ zXdgD46lwcaOX2jPZY0Ci*D>voqZa^?9vl{oArMe3bFFbU*?)E9tbOF-Ppy3N5`+Lx z^hEdcCdo3Lf^*`<`*g0EIZR3=tW4S(2Rl-_D9L*VLSJF^z%8BCtrSsJQ_zgsdW~yq zlpQ0B5K~hx6R?)ECVhka22TkPMM_giIpJ$Lqz^tNt4IBIY za+-ew;f?DmB7TjmXC_g@tXi}qOBo1+;SR^{m5cOU3V+uQjut@w(QOWd)qWZ97Br*Q zGLM%>b_c@?a8sUP%a0F&!3X001mbm)=I7B$J^d?20yQJr45z8p;AxSE6Uu!0AW zjvhh)8fb$&mi~Dl%Okvi_{kQ6Yun=MX=l;Z10js(szvvb&|T>5RJ!g@Q7#dcA5e$T zb^BEFc7HDgwg}z6YZ0o;groyXJxa-h=eAwIq_uVltrT~aHEyZ zt{D}CztAZs==2l5uKiZ|yn5#4dj7863_s=^e1Cud07N1FP1AJ$s%dFkS7~Dx0yrgHdXN!ZqkMX|}a=vGk_Q}hN`gDKoJi=Ib5R81pn>kHSEN{@myikHc4 zq<_6uSukiZYm%W#@ND!*u&DapceDMWWLh=0zwQ0h=MwLf-tUv2Q(1y^$C zAnXd5ojG(>xxd*>#SPn^r?s$4Q7PTF%i2?Ggvgf^y6I77FTL#Qf5+9N9vWVXJHygi z4r$7#c>Jwx+FRv_juB_NmAH?RZGaJ+_xvo~VV@GJQOK?J>Kpcpwat%Ok0uKFha|g9k1=vfcR4!Hb1$^N|W;v5+2%K2U6p_uTQ5_XFsU$ZM-Q#KM1z{NP_j{%0$r z>|}0b?qqKK=dkfVqhBR+>%UVTMRyxRGY4B6a}Q&OKLT(1U)G(OBKq69CH~90%{4mk z`NIfxqOvf_Nj@I9xDZIKn}5qJ(ErN&?U|kHIU&mPq%UGXjzzQ0Yd=`UPl;+!E4n>xN%f%q;m<-im;kEPu%qsZp?qJbtZ! zaxlN`!J`h)(w4mmC9cm!wrJrj8Q@V#!-{F+YYja~x66kL&XZg#%>Gm1I;w@zYL@tt z1H6e+(gqIBcH41kii^~*Qxv_vD$#~%9Yyr+12zkxb)6lI;YWZ9<|h=dhF@4crw=mKDD}adjaiwQQ!eNP)=mQBwQ|KfGI^4pUwlo+QJ zX$o^OntwD#P1AQ#r+*v?ID6E_u0L~HjQ0g!mc|;pI|R5j{$!)H@wIUjnLg(u0p?Yy z4O&YCHN`ef$jGI4AHmosqfg~s_5#jkwmC5S`4wOF$Hm?8EnZ?B;IErD0ZvqoK@jqJQtEzPqTdFjqc_)R16H1{#PX3OT}& zrMC-0wow6dWOkAXq87utjR0Ou?>{ZRO6B8eSg-}FwW0L5G=S&$DDV!Nu#MzPjyMJ5 zNWTYui=K1i%9q7XB03&N64DmO@>szhdG)Dn%hrHoli=%Y-;LC_oSNgNtR~Z$B6w;wwf-5#YHgXymp$f<)iMlXRqDJT{fD$MNhThw%oclIthjk=7;ZjR26zRw&kGt9?xT$nA=mJoP5yj_khoZU{pf z5`bn(yJ@w)Re(rYxA)DubRdB56!CUJJ|h`jrEQG$qxU~nm%c2 zEz{M8@)-B}S>taH))y#uORMZw>hej}%@snM>Z+RM2CD^(FE|CxR9QwQ2dPK_l1<+m(#IEnBOMrV zNie`(p@@{<)&s#z=N*zFZ1)_;3hBe)Za7FfSZ%fzIG#Q588EwZ8=DQ^TUKzjPgW`| zj4Wz3#}1IEcY708;5L2Pm9Ge?Mt`N&4XnXvjs0f6n!n5;z+L~d1LcWNm4h7o5uX;6 z{qPz>krF-9MKonRcdhg7TcdV&?rzFh$=OQH)G`M^d%%&5ZgZ!seHOGVTg%j7NDtN( zLE1z>1d1;h?qt6k4lwxSxqaj8{7F*Ps9@tdfiYx49R#&hC6yGE!lOFT(tnKzS#GQV z)uxXqu@iX+n@EE=^oS6%`JzI4j*>VoWbxVzI6)PAN0^ib%Fy4o_ zK{IYmt19~^pqu}>%5n@hZ6|^ra7FT*7ouPES8}ztF}81)K$c?|_|0-|fK^bjdWwUv z;|gm(#a%knjH#2X8{Kx0h%Vu~TT6*tE!N1d^5-EX`fE`(qCe331geAGwm=#6AuKhG}V&0OJoptYD&e*(IsT-%+>9Vl^} z%OnkmSZ{Zq2HdYTBWu3%x^A=p#O~v?EfPd zst)E(#{c-YRLm*^LidxZ+F?EQ&Y-=xpK^SX$1!CRRg?0fA%UzNTMcJO?b{g_Dj*gXN6;x#vyA# z;_7xgoBJ|)z6Yo2F-?lp8uyTVY=Jb2NLWStE=H5&FFEeP3Lm`Tl;ts%FQL2D&uw zDm%2I@MBny1S|0DQ13IFL(Mv={pGWr9lKqU;+Ahy;x4e~{CMD>m-vTE^VwcSN!NqiacH2g|<^+d<#L*zk8|`8%Q%Gqy2y_>*A%dw=m;@t@tg`fa)z zWq*(owZLT%NyTM3sVr4%@DPKLIzs(8$Y#DDQ&Z42hEaOfko~SMblrE3@F|9NJ?W&S zdPGO+r-o~d3GV3ca1(bU?O8trp=SZun zQlO^e(<@^mX!Wrd9$}A+KZCdH$)oJ0aduqvx{$11w9m@UlB|;(1 zNA9@Z=z z)CoX!wbxqEyzbqArxMXoUZ1HaW+C`1K`#p8l%vo*IJ}wzWQ@pQ&_r^T^qoQiWw~*J zXvRW;o#SoCK*8}X<~Hulm#ZBu+3~O*Eb>IV)+tVhe{42w!YnvE(H5c+wRO+Y*?ht- zCl%FvoQGM(g@DI1@5P6kXip=-^?#2{@m@dDeakdVqmb)JfC2a(@DfBe(VMY>DxL?8K9Rbt}N2^?#y6cy8(4aAEa+uWGka&QWPyn+gW7 zP5c>neDMpbJZ|YACmYedUBo@O)}w|!s*uhoR~1^#8l2nOuP5SO8MHfmJb!I7(QnzG zjkKsKSJ*K*^F`)FO%uWeupryvxDu6gN0fBIff@n#4COHzT_HQG^KrIZUwJ*riuCM! zY3IV2Z%n~lxG$2N0sn>(**~ZonWz78aU-**7t*>Sd+bP9QFtPtP(xG2np|DzdqGh? zMjgwqsB%k;kI}yMRbG5jr?OY$pkk(m-3X7I2T%1LcOJvyP&1O%0 z89Hcee-{i*Df3&MVWByne`h}vp8a#`zyJUjNdJZ}`hVbSW@}|+?7%O;|6f5Z`Zt~4 zSHJ5~a1yJk10jWe5r6M}xMb3*5C89Kv?Nh#2+^UtRTti1B+zJPz6iQgM?Ro6l_rhE zcPGjI>o*d zpY!##YvnUskbeaE@5$TKcA`IK&Q$P&HmX=Xcy(8zD}^UvCC_tT#q$pDizWcgaAu+S z>vZu0xvJT+Q{vbHY=Qu!190fm7Xdhv7d}$G<6O~dcdSF%-xWL4#ceNZPeawCr@Lou zLf*M+Lw^#>NsVoH=1TP|0>)_FqprKEV!y(mioTL$r=G&;6j#nSZ2&KM3h)P#CaA@h z$C`VRtuuHo3SH}EeTxNKwq`en*z%_}0x;|er+q0I&kO~g`nG~hi?WpddU@(x7<%>N zzV}U6!qsaYx>!-9^TwgI_iMTPEfCEv)D|KSGJj#^n?5UepWRuoLj_E9^VoKIvfbAG z*!7jBpbDhO=a7G;&viEU*ERGX@iV=T-n9O%T{Zt2$WZ=6{KgIrwhsTjJ#+X+`DTeJ zMqs)|<6x!?X(vKC$I_;&K7N3h3(tbq_7dIQ)GI__idgV0kfXxXRp=L|nZ%u#yjJrd zRe$R8x7^T-jMkBAtdpkP8KJ)m6a6p%Uu4LEM>MM!85#most%vs97+M`-d!+2is9pd z$K=YPV>fJFl+{8>7#u^uMFZ0yG-2{na?^^{M3m*>(7J=wTC?63=e|$I_4$n&0c1e0 zg4~T6yBMQfJc6nFFawoH9A7%6R#dltR%Z$A5SA>BhXp&4Lw^Tm z6w@~{WZSU~sjjvBY3 zy74HLuS7j|Tnh}Z@{WM){W6xe)X`yDEs49b0G!Spow(E??d@0M6-f{}RDY`UH1pDy z4w_P9?xZp76K_F&8S?6jkmL>sZ|T3invdq}1o`WPmk5^?h!+$-TAzN#cN66H#fwC$ zv!)m;B3DnSm_ulcz9EhIwHo(Hs#Fr9QTd6Qay9OU$~s=+Ib8nATuN3lS`zi>u=i0B zx~I$RSekg5w`AY49ES1k(|@*J`1rNd<+B=f-+)!$LcURg|B#Pt00u0HdNVw}JDA0$ zQ{Fin~Sq=V+G+Dj|GJ=Lf~4E&U<&6G#& zD1AKcT_0N#B=k9=BK?tc_HsP`H#Rm>*ngLE{H{Bx|3B)E zl7q92;dgTzm;cj=c*$Q#YH%|`a&+HwPr!e&8aK@D{&ON8VTObZvT(u78itL4Kc@uOFg5#W^5Fp}HE^v}0pcbGmx4Kd<_XGxk@I)|G?K zW)>8QJr38aDmNbO_u)J4K4WF3NDInxuHTVvn02Z$6{u?>9Zp6C9ci-%<7Ooj4`F9k*D1D zX@(0p#!qj=FZMF1dh-G_+(JWAZREqH?s#1 z^qTh|-Gx{; zdY7N8`T@OuwEVpg1S{h6#+p>KqxwBRFzLF(M~ zE zkAKVtnA^k|idc&T)D0T-xOK(d!dCM%YB<)ss#_pk;(id}zaWZkcUd5H#yYs4uxCsT zZ@RhAI)t`YpZRGTI<(QcIlmG^qqbl zGsTrtCuQ2l<<}HIY!Xpbx;yO{NJ<%sm!~WkUFU-vV4o67BIz^s|K#aO?#gP?q#g|| zV_M%J-fozf96yGM)pnS;DaI1jPY9&x`jJ>epS`v;hKwsuwCJKxVaqZli#)Zt+JBRv zO4#0~_(S&{w}M%<2QD1(p?oZRyJ$Z?JWHnr3J!?s4#DxZmFn1$jL{F6`+@bvbY#E(Xr#(plO`yFt=4GVejyvJoBo|)3K9DX~_g+1QW!Q2graZ7ny zP!6PrXW)F%2ql{9J7LcsJi|jc>3@}xkX4R3 zuXf{#b;DmoRuh|9&|!;%TBQVh`iwwEn^_zd3Z|LlHby2qL)?iaq}mWAJyGr! zKI|quuM*r(S8f<0bb7r8?wGtGpFW1A<7E9!YLG3IR%NLk?Du=hnLRykg|=8suF}2E z^ly%^o*gDD9;7S?F1IpRwST4;LZCTu9!q?3i&yn*%VDD{!d06XzVgWQQffzi-N?`2 z-$ihJUt#~ilv_z#3;7!+vVVmM|36`}75#hi($MzLxp1d{)-8)Es=g#sNJ!a-+!%tPGJ%YW!Cc_fbZwS7zt zd7Zj?h`OQ-j9CMf;Yx9#_lvVG)dtTRvn zz2CdsxFzNL>uCl>)PKK6QuU3CVeOiuP2#PU{{pep|E97x4ihqiN;}4W3Fgnk`2&rx z+J}x<)^*i45ynk=Ct12J)7UDHmdL#Eu>)7AEzCrko6^^sdu`Ty1E81MO-V^&^bX-D zZrjSy8dmzb>=rCjf}R5IhP<=@lHV%$DmQ#3k<5daw*@sTJb&JjMS|bFpJAAo7&pcs zU1={ab2QMYuQ#-Ed5!nmI4SVt-Rz((C`x%#QvHkiij|DN#@gmi- zKp=0;0C$Gbe_C?2LQ1CzgG$0f8;mq%N*iG_%s4jJO)?u19?#$$ULe7!^H?5G_W)qUf=9*|RqW;vjGLlLV0EEs#CyJ0~ zV}ID0>~LqMuDz6&WyqReYb6*4TJ4!I;yrqn;uyjLBP7K)B%zd>nPMDyR&0XNq`*Q? zGd#|u-361+xF69}Mc7Q5T8mqeLBoaR&(|!;#%SYft=LEQnga{Yo_sA?CR8oi&B$8j z;1R|(mA6tzO{eSJNtk2rGCT_~^SfTHb$=o%M^-37b@!Ao1L?}(6Qo82)MNMpV$uS& zltlkPD=Y!&%Bry%QK?4+8+TN@mr#>1LX}9Y>y#l<9#Q>Mtw`DT!b0#TV6gZ*{VB^E zfmKi0E*!2w#skkF#Wm$Ox6HrbeMe5CkEhKIg&V3Gn7zwdjdn|y6h{4rmU)LVyMJ?_ z-V~6Xs;*Y`+{|{$SYy*%snJ~p&u7!coM&NE% zjc2h#0On|zL{)!0Jb@m=yGRe0oO_G}>@1YN30@w`cYjU~1^D|Aa!_aTZH{u=nS4am z2@Lz99w@=n&+%=#7KKeOo0B45_J4t8$>tQHyU=^t^c=P(mfOZ%(x1@XMnp+=XZg0< zf42H;rLpk>i8V#p2=Yb7HD|96dTwMM8@T*pbPr+kfS4wWA~H z(8{DJFZfTTpMAO|`}2RdJ#*L2zcPRT0Qw>SP2_)u3yxOO<^~S>4(@^uwyuu9#qDNo zb)o&HxXzCBx#1gZ;lrM5llla_9JGNDkHdka(5rK5VQVR6Xla7N{VNl{cU{+aBYrEU z?+)m3N(l%rX3;{T>gvp9{C_qh2j7&e&9r$S_@ViiO`}DSdOJhwH+Rju^_v~}izCI0 zs8KQ2CUhgoEX@qY)_PGI&cMJc(-y&0;v2Uzx-!I!4M)<;_IZmZ(I&+xgj*9MsE&Bh!Ah_0|RBsSK0zj{Spn34h#@G){8{F}a)! zMOTk>m3H;-ah>eyIumKi?VZ0bvbl7FJx7n9Cpx*T!O_X4ic!$uT=Tf()_~bp@cO@8 z@wmvlEw$NIH?w#b$S#J*qBqIik$k|v#7%4Hn%G8B$6K0TFr z;x&;bus)P&zRERnW1@GzujSFg zQLa(QVRCpPgkvxh`4+yoLlDaD**7&&JM@LIC2fEPy+Z2Pq<_KJ^V%O1R_0CA`WO-2 zgbd1?o@NP+>;=f%ThJyi_A)1}FAdC{54GQaSX~~t>t%iLaTJtpRSi ziRTiPRHu$Mqkj$VbKM1fNR4U^`T}<&N-0secj2arERIZvWR1t)T|!P;4t|I1clpJJ zLWyi+hBd9+2zS)Hg)39^dN8T6DCoh4`YnAl5W|#(i5>>IM*5d{E`g^JkqkGiXkQ2$ z|G61!Fc)2dEYu&chk-2b6HXMtE|Z-vsG;4cv-GMuIDb&kGqp`Hu#NzATxN)K=B^MY z57(uxNv!e;-_0Pq{2|$RJPUqkM06Y z9awFkvLwv80H!u;V|rJ}3i%Ry-8(VusDg8VSsTdf^@r?f@rr3+srO0TLQ09`r%we$ z@}FG{BY$krrwoi{PnsD^kE>CX#D`pP6k+ZL1{Y#KvovAM{LYNo>(b=BIZDPOEtxf+ zG$6i{RDuA|;NE5GkEqLW(!!84W}m~TW__7!yD~gEM(NLBqp1sx5%5C2`LBYx&oL-8 z*A?omT1sljt=rdQGH`U5jv-^cAzcZEtBYAg!hcB_I;x)b-}00(pA!7w>P_kz!Sna9 z&V7!2V?kwR)K9+7CCku&JLXh$;x@PhHdL9L>?L~k4Vo*O+U~-*MTsoOY~G9Y5@nKQ z@={NsJ3-rj;dtI_(TwB0*V-305xWkWv3?S?IKJ&5JP7kiRHfRYa5@M25>F;Tr?W5a z2Y*H^z{$Bv;F{9N8v;nL5@4;=}UN{YJt z!3ZR3$=??*Fj~(*B&7lUd&Ce>Ty8OjGb><_-B730&d_c1r-`G=IU zn*^%aaZQ0r?%=9gqgw7Q^J@gEc&D#cWw!z?g{ml}Ds$+Py4}^_C_l^Iv$bD&1b^rY zTA1B%-WL%JOKO1)gl-!h@AMp(j8%GXlVTD+%e*pEuI&YLt&9CFm`94$E-yRNh)*Va zYq~YIn|;J{7C)7PE&~hdNu24{r}ryV;|mm2Q%WebCji*JL(-?Pm(o+QC*l zr0wp?XtDXL!cF__zjJGr>1r=r*T%`(7lFdUg!0r_57F4>c4=mlya)}nq*dN;U^|Uj zQHufiQi*LF*B=&L=qqbqzD(J8>%!zM?ge6NUtF@fq&3Mnjq4f z2qF)WjzKzt0)jURNE4()RFvMLAVr#VX;FB3-~8`Qa=~~1FPX_qW_EvPH)VHczjMyl zO{W!)L%JMTR`y5PwKeIvd$!S@n~}_48wgH|Ph6g;)#IHCAq%&4dT&=hOWVupW~A8V z=nqng(hZ}Ur}aUjP&1malz(z%1VbTWP~{uBnqHHZMM=@WGEE$DrZ=3Jy^HQ~|Gw{6 z>rvHXcB@XRdQ$b7%fU%TmT*`!#X9SOVLwOpi!M{nmAT*JjDwicG}o96W&QFl!Al*p zrqR319GEC*X8yyoiCd##>gU7#MNAoOHIpW5m)0Y;AzU<5l8vC8uw)~@6%IZ+B-cX z@_iFA5GaN2Rv&}1{C^HI3$yH5j7Rz!=o?gKQz^h2*n&$%nyK~#cNX$^w-d%K__tw} zO|TR@b5O@ZT@HE|PHxL1TB)X(U&&7UVO6$WU%+Rj-Q)(Rh1wD!@TU@QZsIDRW| z6zOaH-D6qzmS13uiX^KV6Mj`rRz45D>(mzvn5V2`y^9#Tbbl4dgr6*s9w@0-3deOD2UMey3ysHAbS1yF<}EM>=M@?9129DhU3$fa6d zxLT4V<|!x1l7G(A^B~1n5#j~s`*1SPq}*VQpDvx^Y%2|ef`Svd9iqA@y`jQn*C>q( zQ^RHUG8y4pknnQlb#w}iVM8}gi zmG?l~lcD`JvfHio{&axmTZ2jt)201_CEEx*f_IyI{&{!O#0he=d8eJ*$Yti`=+s96 zzdgg}TylV~R=Hyr?YDaa2Ve#w>4-ZM-_PIF&MDTQrcYw!RO`;jc<{&3QvF;Iz`d*kHTd(?t;=tfuK%?dAWp`qk1+EdRP3kPJAA!%c~ z{3)?`%8pJ}AH~tA+Lr~rQ4Fwci-63ls*0) zyrY@=nj(e9Qr-NSzO2*N(Ckb4K&H;(@3p+#YJtiQ4+rsYq_U3h0tW`)rZGO=s6eY( zy3h8kU`_<9!2Ch%N_5HNin#P<0mIL(zr7I$xtg-cEA`^rpJKVTbT9ixG=>Oqij63} zzJGCr<#X}cN$NYEWoD8%ppXl;Z7&B(y#_faoSCh| z5j)>>9^dZ|EO!n*p==xQSbpP_16QzA!hcunZE}kN6NZ(Y-&~8YS2vHYIXe+-lGc(ByNIhm*-zF=RH2ddem^|HP(! zIt$qPyy%lU2}eMcY70wjaF-4=x>D*M1+!$*4)DQQ+Y@xC)^xh)f6aj-F5dNr_=iTP z`7I{RorBA?LHVIFv}mBcX)CV7T7Qle8sryrzalEq*?AdoFj~7GJ%QL!s7+7b%%}ij zr9;c$jvVE;!>6*F$ML0mvA0|plQ1<#s|n_4$!^_rw4{-dW)>`4DmaEJBG=24@`Vap z$PEQd=)6OC!GQxG57OgGQe&}=tF*W`75utSj@9mZKqYFX+j;rZS9e^?tAF6={p;qO z3*WBmH6Vloz6sQCNod|aWB$D-aOfigONP|+@f>3t%mt2*ZRj_vZ^v>IMLd(A4RMc- zkaKMoUEZcE&o-hQ;)=?B*kuF-q|{hXzW zT-$V&@{WD3^K28y4Q= zzbX4#y?YtjSM-jY(NX1H_c8aAL1IDlgSmPdj%mKfD=-mqqfr{JD}Of3#yvBQM)FeY zCB-S^Jd)B}bFDn~8wD37PRbO@?DFz(21wH{g8Q{8D~(|zQ;}v91u#gZ9I$s7>I{oC zZl1(6-~DJWG5&FzZ8WyHzt@eQF>mu>o5h*x`p>IW_deWWN}2&q%bT6^VB}mBle&;I z4}n}PD8&j=n&YQ`EOa z`caDy8OSAUou(9%ElRE4vSj2$;TI@rSlJFJPsdI;1hm~KV}FqU!sk7VIfa7_uYdDzO}!g)F@D8RD;#^QtXA#2 zO(u=*Yq_~n2kR{0WL;15B-->KYc5uGQwYOv_~b^6$O@Zfl%?K`%;ghy7iDKlM38hc zoPKEdRSV{9ohGB9Vg-L+^taKS_>kC+eyrwM@)pS#RShvy;;+@O9{}TInUsW+xE27{ z(>K>WlYfpgJ$P$aCt;xOO)lq9LCvJxegU+QsuzO4zDi3 z3S1i-{+I=bo78~jt8Ix_R(U}eiu&B2b+yOQab*w5-Z$Gb=i!>$w6#=|HvgDrt?c|(jiMi_U(>tuL|2U7Ft{#L$hGs7s7_)8Bd;DFBe0pWfbY~p-+wLWc^|L_5Z5z}MyM07*Xv`IvM#MjG6T7)Q(vl>0vThUFWmFCu!rVjd(Adx3xqxBP zcgamYeHWH_wdb-!8Sc5DYtr_uYJZM!8#^=-x4-rkmqAyiUgvHm_7t23my5Z-pq)RF zP7za0GkFK(Ubo-NzNBPUy2Pu(y_Iuk2)*VNy-_U$ z9ay1K;?gxC&ZfxZ2^t8zNg~=r7p?tSOg2$;9nn-0Kl^Gl7WLj(y!1sZ`86q1jie?^=c=cW~W4xY$(MCL@D z-lyk}zn_@DzW$kr?;qJe|AjZJvesLizh?NkpOK+(IdC(t3&RzDox)lFHhkS#FYmEq zBNs!@T;<=%0bkdDz3($wR%nV!>YqJ=Gg>^4)Jf$je)53al>vbL|*^!uNjOhl)%^HuggG zE1s9#Jp2E`+w7Y$nMTo!3|~S|Fvz%A>{jbqeES=}b7M%?E1~+DvwxaX>U%io`-(+Ivlvd*I&D|pTJFOn0R ztez_DX4hF?-~O{~!GCwFnNz$aPAmVr9AVY;FSBNfh}VqFB;_WjIga~JeE<8l!%IL} z(avOkk!{cCbh$1OmyC?*%1m!}HUE3g!?luYVeyPskEPeROQwX*6LEUcn4;8_P~*@Z z)#u6CGEe`}*$F$itWH^aR*5>jC{^4ysdE>b)gc|XQwlN{U7sr@ePL<-H`~2U#Lc3} ztLBh6FZpPek{`!pMB(tcPj6dcAe@W!d-jr@m|AAUqk{*q%@~ZPJYy|Q)j2K zvKez(%DUC{udaP~&!#i`)yAy~|4!~T`t;{OrchFVX_5QQrfX^e$Ha_hebzj?blI!Q zCES69UxFVwmP~FE6u-Bp+xg;}Yu;yFMb5zUbS=WD;=y>4vWKmDVMTc7w(nO%G; z{8NMPd!@M=X&?XJ_7Cu8WMW`|1qQb_Q_|jTDU1vZlXYg%~z#xpGV`t&y&9fEjLB_71Y&BOA zsAvLE5jTn=>0$Gi*tN3lZq0HDxHe*%ZpQs^oj~#MzI5xgA&bT{y8$tNgN!L_2wumqNE+5yHrrz eRIkl3*?6X^Sb#Sx8%Tl+2+sk7e7Oz>kOu&_FvM5@ diff --git a/toolbox/WBToolboxLibrary_repository.mdl b/toolbox/WBToolboxLibrary_repository.mdl index 5bc9551fe..b5034389e 100644 --- a/toolbox/WBToolboxLibrary_repository.mdl +++ b/toolbox/WBToolboxLibrary_repository.mdl @@ -23,7 +23,7 @@ Library { $ObjectID 2 $ClassName "Simulink.WindowInfo" IsActive [1] - Location [173.0, 232.0, 1280.0, 721.0] + Location [447.0, 302.0, 1280.0, 721.0] Object { $PropName "ModelBrowserInfo" $ObjectID 3 @@ -48,8 +48,8 @@ Library { ViewObjType "SimulinkSubsys" LoadSaveID "192" Extents [1226.0, 537.0] - ZoomFactor [1.66] - Offset [0.0, 0.0] + ZoomFactor [1.75] + Offset [10.634251290877842, 6.0] } Object { $PropName "DockComponentsInfo" @@ -76,15 +76,15 @@ Library { "////wAAAAAA/////wAAAAAAAAAA/////wAAAAAA/////wAAAAAAAAAA" } } - Created "Thu Feb 06 02:21:39 2014" + Created "Thu Feb 06 01:21:39 2014" Creator "jorhabib" UpdateHistory "UpdateHistoryNever" ModifiedByFormat "%" LastModifiedBy "icub" ModifiedDateFormat "%" - LastModifiedDate "Fri Aug 11 06:58:36 2017" - RTWModifiedTimeStamp 424335513 - ModelVersionFormat "1.%" + LastModifiedDate "Fri Aug 11 12:50:36 2017" + RTWModifiedTimeStamp 424356590 + ModelVersionFormat "1.%" ConfigurationManager "none" SampleTimeColors off SampleTimeAnnotations off @@ -1031,7 +1031,7 @@ Library { } System { Name "WBToolboxLibrary_repository" - Location [173, 232, 1453, 953] + Location [123, 132, 1403, 853] Open off ModelBrowserVisibility off ModelBrowserWidth 200 @@ -1065,7 +1065,7 @@ Library { } System { Name "Utilities" - Location [173, 232, 1453, 953] + Location [447, 302, 1727, 1023] Open on ModelBrowserVisibility off ModelBrowserWidth 200 @@ -1077,7 +1077,7 @@ Library { TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] TiledPageScale 1 ShowPageBoundaries off - ZoomFactor "166" + ZoomFactor "175" Block { BlockType SubSystem Name "DampPinv" @@ -1163,7 +1163,7 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "1619" + SIDHighWatermark "1628" Block { BlockType Inport Name "mat" @@ -1184,20 +1184,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "107::1618" + SID "107::1627" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 98 + ZOrder 107 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "107::1617" + SID "107::1626" Tag "Stateflow S-Function WBToolboxLibrary_repository 6" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 97 + ZOrder 106 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -1213,9 +1213,9 @@ Library { Block { BlockType Terminator Name " Terminator " - SID "107::1619" + SID "107::1628" Position [460, 241, 480, 259] - ZOrder 99 + ZOrder 108 } Block { BlockType Outport @@ -1226,7 +1226,7 @@ Library { IconDisplay "Port number" } Line { - ZOrder 61 + ZOrder 76 SrcBlock "mat" SrcPort 1 Points [120, 0] @@ -1234,7 +1234,7 @@ Library { DstPort 1 } Line { - ZOrder 62 + ZOrder 77 SrcBlock "sigma" SrcPort 1 DstBlock " SFunction " @@ -1242,7 +1242,7 @@ Library { } Line { Name "DPinv" - ZOrder 63 + ZOrder 78 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 @@ -1250,14 +1250,14 @@ Library { DstPort 1 } Line { - ZOrder 64 + ZOrder 79 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 65 + ZOrder 80 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -1297,29 +1297,222 @@ Library { } } Block { - BlockType Reference + BlockType S-Function Name "DiscreteFilter" SID "1772" Ports [1, 1] - Position [440, 260, 500, 290] - ZOrder 83 + Position [400, 245, 460, 275] + ZOrder 82 BackgroundColor "yellow" - LibraryVersion "1.386" - SourceBlock "WBToolboxLibrary/Utilities/DiscreteFilter" - SourceType "Discrete Filter" - filterType "Generic" - numCoeffs "[0]" - denCoeffs "[0]" - Fc "0" - Ts "0" - orderMedianFilter "0" + FunctionName "WBToolbox" + Parameters "'DiscreteFilter',filterType,numCoeffs,denCoeffs,Fc,Ts,orderMedianFilter,y0,u0" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 23 + $ClassName "Simulink.Mask" + Type "Discrete Filter" + Description "This block wraps the Filter, FirstOrderLowPassFilter, and MedianFilter from iCub::ctrl." + Initialization "filterType = get_param(gcb, 'filterType');\nnumCoeffs = mat2str(numCoeffs);\ndenCoeffs = ma" + "t2str(denCoeffs);\n\ninitStatus = get_param(gcb, 'initStatus');\n\nif (strcmp(initStatus,'on'))\n y0 = mat2str" + "(y0);\n u0 = mat2str(u0);\nelse\n y0 = 'none';\n u0 = 'none';\nend\n\nclear initStatus" + Display "disp('Filter')" + Array { + Type "Simulink.MaskParameter" + Dimension 9 + Object { + $ObjectID 24 + Type "popup" + Array { + Type "Cell" + Dimension 3 + Cell "Generic" + Cell "FirstOrderLowPassFilter" + Cell "MedianFilter" + PropName "TypeOptions" + } + Name "filterType" + Prompt "Type of the filter" + Value "Generic" + Callback "% From: https://it.mathworks.com/help/simulink/slref/simulink.mask-class.html\nfilterType = get_param(gcb" + ", 'filterType');\ninitStatus = get_param(gcb, 'initStatus');\np = Simulink.Mask.get(gcbh);\nhowToCoeffs = p.getDialo" + "gControl('howToCoeffs');\n\n%set_param(gcb, 'initStatus','off');\nif (strcmp(initStatus,'on'))\n vis_init = 'on';" + "\nelse\n vis_init = 'off';\nend\n\nif(strcmp(filterType, 'Generic'))\n set_param(gcb, 'MaskVisibilities',{'on'" + ",'on','on','off','off','off','on',vis_init,vis_init});\n howToCoeffs.Visible = 'on';\nelseif(strcmp(filterType, '" + "FirstOrderLowPassFilter'))\n set_param(gcb, 'MaskVisibilities',{'on','off','off','on','on','off','on',vis_init,'o" + "ff'});\n howToCoeffs.Visible = 'off';\nelseif(strcmp(filterType, 'MedianFilter'))\n set_param(gcb, 'MaskVisibi" + "lities',{'on','off','off','off','off','on','on',vis_init,'off'});\n howToCoeffs.Visible = 'off';\nend\n\nclear fi" + "lterType initStatus p howToCoeffs vis_init;" + } + Object { + $ObjectID 25 + Type "edit" + Name "numCoeffs" + Prompt "Numerator Coefficients*" + Value "[0]" + } + Object { + $ObjectID 26 + Type "edit" + Name "denCoeffs" + Prompt "Denominator Coefficients*" + Value "[0]" + } + Object { + $ObjectID 27 + Type "edit" + Name "Fc" + Prompt "Cut Frequency (Hz)" + Value "0" + Visible "off" + } + Object { + $ObjectID 28 + Type "edit" + Name "Ts" + Prompt "Sampling time (s)" + Value "0" + Visible "off" + } + Object { + $ObjectID 29 + Type "edit" + Name "orderMedianFilter" + Prompt "Order" + Value "0" + Visible "off" + } + Object { + $ObjectID 30 + Type "checkbox" + Name "initStatus" + Prompt "Define initial conditions" + Value "off" + Callback "initStatus = get_param(gcb, 'initStatus');\nvisibilities = get_param(gcb, 'MaskVisibilities');\nfilterT" + "ype = get_param(gcb, 'filterType');\n\nif (strcmp(initStatus,'off'))\n visibilities{8} = 'off';\n visibiliti" + "es{9} = 'off';\nelseif (strcmp(initStatus,'on'))\n visibilities{8} = 'on';\n if (strcmp(filterType,'Generic'))" + "\n visibilities{9} = 'on';\n end\nend\n\nset_param(gcb, 'MaskVisibilities', visibilities);\n\nclear initSt" + "atus visibilities filterType;" + } + Object { + $ObjectID 31 + Type "edit" + Name "y0" + Prompt "Output y0" + Value "[0]" + Visible "off" + } + Object { + $ObjectID 32 + Type "edit" + Name "u0" + Prompt "Input u0" + Value "[0]" + Visible "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 33 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 34 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 35 + Prompt "Simulink:studio:ToolBarParametersMenu" + Array { + Type "Simulink.dialog.Control" + Dimension 8 + Object { + $ObjectID 36 + $ClassName "Simulink.dialog.parameter.Popup" + Name "filterType" + } + Object { + $ObjectID 37 + $ClassName "Simulink.dialog.parameter.Edit" + Name "numCoeffs" + } + Object { + $ObjectID 38 + $ClassName "Simulink.dialog.parameter.Edit" + Name "denCoeffs" + } + Object { + $ObjectID 39 + $ClassName "Simulink.dialog.Text" + Prompt "* The coefficients are ordered in increasing power of z^-1" + Name "howToCoeffs" + } + Object { + $ObjectID 40 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "Fc" + } + Object { + $ObjectID 41 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "Ts" + } + Object { + $ObjectID 42 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "orderMedianFilter" + } + Object { + $ObjectID 43 + $ClassName "Simulink.dialog.Group" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 3 + Object { + $ObjectID 44 + $ClassName "Simulink.dialog.parameter.CheckBox" + Name "initStatus" + } + Object { + $ObjectID 45 + $ClassName "Simulink.dialog.parameter.Edit" + Name "y0" + } + Object { + $ObjectID 46 + $ClassName "Simulink.dialog.parameter.Edit" + Name "u0" + } + PropName "DialogControls" + } + Name "Container3" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } } Block { BlockType S-Function Name "DoFs converter" SID "1771" Ports [1, 5] - Position [240, 241, 385, 309] + Position [160, 226, 305, 294] ZOrder 81 InitFcn "if ~exist('WBT_robotName','var')\n WBT_robotName = '';\nend\nif ~exist('WBT_modelName','var')\n W" "BT_modelName = 'WBT_simulink';\nend\nif ~exist('WBT_wbiFilename','var')\n WBT_wbiFilename = 'yarpWholeBodyInterf" @@ -1331,7 +1524,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 23 + $ObjectID 47 $ClassName "Simulink.Mask" Type "DoFs converter" Description "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on" @@ -1350,7 +1543,7 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 24 + $ObjectID 48 Type "popup" Array { Type "Cell" @@ -1364,28 +1557,28 @@ Library { Value "From YARP to WBI" } Object { - $ObjectID 25 + $ObjectID 49 Type "edit" Name "robotName" Prompt "Robot Port Name" Value "WBT_robotName" } Object { - $ObjectID 26 + $ObjectID 50 Type "edit" Name "localName" Prompt "Model Name" Value "WBT_modelName" } Object { - $ObjectID 27 + $ObjectID 51 Type "edit" Name "wbiFile" Prompt "WBI filename" Value "WBT_wbiFilename" } Object { - $ObjectID 28 + $ObjectID 52 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -1397,11 +1590,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 29 + $ObjectID 53 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 30 + $ObjectID 54 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1409,46 +1602,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 31 + $ObjectID 55 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 32 + $ObjectID 56 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 33 + $ObjectID 57 Prompt "Block Parameters" Object { $PropName "DialogControls" - $ObjectID 34 + $ObjectID 58 $ClassName "Simulink.dialog.parameter.Popup" Name "yarp2WBIOption" } Name "Container4" } Object { - $ObjectID 35 + $ObjectID 59 Prompt "WBI Parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 36 + $ObjectID 60 Name "robotName" } Object { - $ObjectID 37 + $ObjectID 61 Name "localName" } Object { - $ObjectID 38 + $ObjectID 62 Name "wbiFile" } Object { - $ObjectID 39 + $ObjectID 63 Name "wbiList" } PropName "DialogControls" @@ -1480,7 +1673,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 40 + $ObjectID 64 $ClassName "Simulink.Mask" Type "Minimum Jerk Trajectory Generator" Description "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk " @@ -1503,7 +1696,7 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 41 + $ObjectID 65 Type "checkbox" Name "externalSettlingTime" Prompt "External Settling Time" @@ -1514,42 +1707,43 @@ Library { "SettlingTime" } Object { - $ObjectID 42 + $ObjectID 66 Type "edit" Name "settlingTime" Prompt "Settling Time" Value "3" } Object { - $ObjectID 43 + $ObjectID 67 Type "edit" Name "sampleTime" Prompt "Sample Time" Value "0.01" } Object { - $ObjectID 44 + $ObjectID 68 Type "checkbox" Name "resetOnSettlingTime" Prompt "Reset on Settling Time Changes" Value "off" + Visible "off" } Object { - $ObjectID 45 + $ObjectID 69 Type "checkbox" Name "firstDerivatives" Prompt "Output First Derivative" Value "on" } Object { - $ObjectID 46 + $ObjectID 70 Type "checkbox" Name "secondDerivatives" Prompt "Output Second Derivative" Value "on" } Object { - $ObjectID 47 + $ObjectID 71 Type "checkbox" Name "explicitInitialValue" Prompt "Explicit Initial Value" @@ -1562,11 +1756,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 48 + $ObjectID 72 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 49 + $ObjectID 73 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1574,38 +1768,38 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 50 + $ObjectID 74 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 51 + $ObjectID 75 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 52 + $ObjectID 76 Prompt "Trajectory Parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 4 Object { - $ObjectID 53 + $ObjectID 77 $ClassName "Simulink.dialog.parameter.CheckBox" Name "externalSettlingTime" } Object { - $ObjectID 54 + $ObjectID 78 $ClassName "Simulink.dialog.parameter.Edit" Name "settlingTime" } Object { - $ObjectID 55 + $ObjectID 79 $ClassName "Simulink.dialog.parameter.Edit" Name "sampleTime" } Object { - $ObjectID 56 + $ObjectID 80 $ClassName "Simulink.dialog.parameter.CheckBox" Name "resetOnSettlingTime" } @@ -1614,21 +1808,21 @@ Library { Name "Tab1" } Object { - $ObjectID 57 + $ObjectID 81 Prompt "Input/Output" Array { Type "Simulink.dialog.parameter.CheckBox" Dimension 3 Object { - $ObjectID 58 + $ObjectID 82 Name "firstDerivatives" } Object { - $ObjectID 59 + $ObjectID 83 Name "secondDerivatives" } Object { - $ObjectID 60 + $ObjectID 84 Name "explicitInitialValue" } PropName "DialogControls" @@ -1662,7 +1856,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 61 + $ObjectID 85 $ClassName "Simulink.Mask" Type "Real Time Synchronizer" Description "This block slows down the simulation trying to match the period specified \nas parameter (in se" @@ -1670,7 +1864,7 @@ Library { Display "disp('Real Time Synchronizer')" Object { $PropName "Parameters" - $ObjectID 62 + $ObjectID 86 $ClassName "Simulink.MaskParameter" Type "edit" Name "period" @@ -1695,7 +1889,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 63 + $ObjectID 87 $ClassName "Simulink.Mask" Type "Simulator Synchronizer" Description "This block synchronizes with the external simulation on a simulator \n(only Gazebo is supported" @@ -1705,21 +1899,21 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 64 + $ObjectID 88 Type "edit" Name "period" Prompt "Controller Period (in seconds)" Value "0.01" } Object { - $ObjectID 65 + $ObjectID 89 Type "edit" Name "serverPortName" Prompt "Server Port Name" Value "'/clock/rpc'" } Object { - $ObjectID 66 + $ObjectID 90 Type "edit" Name "clientPortName" Prompt "Client Port Name" @@ -1741,11 +1935,11 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 67 + $ObjectID 91 $ClassName "Simulink.Mask" Object { $PropName "Parameters" - $ObjectID 68 + $ObjectID 92 $ClassName "Simulink.MaskParameter" Type "edit" Name "tol" @@ -1814,7 +2008,7 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "1610" + SIDHighWatermark "1619" Block { BlockType Inport Name "mat" @@ -1835,20 +2029,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "112::1609" + SID "112::1618" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 98 + ZOrder 107 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "112::1608" + SID "112::1617" Tag "Stateflow S-Function WBToolboxLibrary_repository 7" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 97 + ZOrder 106 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -1864,9 +2058,9 @@ Library { Block { BlockType Terminator Name " Terminator " - SID "112::1610" + SID "112::1619" Position [460, 241, 480, 259] - ZOrder 99 + ZOrder 108 } Block { BlockType Outport @@ -1877,7 +2071,7 @@ Library { IconDisplay "Port number" } Line { - ZOrder 61 + ZOrder 76 SrcBlock "mat" SrcPort 1 Points [120, 0] @@ -1885,7 +2079,7 @@ Library { DstPort 1 } Line { - ZOrder 62 + ZOrder 77 SrcBlock "tol" SrcPort 1 DstBlock " SFunction " @@ -1893,7 +2087,7 @@ Library { } Line { Name "TPinv" - ZOrder 63 + ZOrder 78 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 @@ -1901,14 +2095,14 @@ Library { DstPort 1 } Line { - ZOrder 64 + ZOrder 79 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 65 + ZOrder 80 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -1962,7 +2156,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 69 + $ObjectID 93 $ClassName "Simulink.Mask" Type "YARP Read" Description "This block behaves as the command 'yarp read'. \nBy default it has the option 'Autoconnect' act" @@ -1980,35 +2174,35 @@ Library { Type "Simulink.MaskParameter" Dimension 6 Object { - $ObjectID 70 + $ObjectID 94 Type "edit" Name "portName" Prompt "Source Port Name" Value "'/portname'" } Object { - $ObjectID 71 + $ObjectID 95 Type "edit" Name "signalSize" Prompt "Port Size" Value "1" } Object { - $ObjectID 72 + $ObjectID 96 Type "checkbox" Name "blocking" Prompt "Blocking Read" Value "off" } Object { - $ObjectID 73 + $ObjectID 97 Type "checkbox" Name "timestamp" Prompt "Read Timestamp" Value "on" } Object { - $ObjectID 74 + $ObjectID 98 Type "checkbox" Name "autoconnect" Prompt "Autoconnect" @@ -2020,7 +2214,7 @@ Library { "t_string" } Object { - $ObjectID 75 + $ObjectID 99 Type "checkbox" Name "errorOnConnection" Prompt "Error on missing connection" @@ -2045,7 +2239,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 76 + $ObjectID 100 $ClassName "Simulink.Mask" Type "YARP Write" Description "This block behaves as the command 'yarp write'. \n\nBy default this block opens a port names as" @@ -2058,14 +2252,14 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 77 + $ObjectID 101 Type "edit" Name "portName" Prompt "Opened Port Name" Value "'/portname'" } Object { - $ObjectID 78 + $ObjectID 102 Type "checkbox" Name "autoconnect" Prompt "Autoconnect" @@ -2076,7 +2270,7 @@ Library { "';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val prompt_string" } Object { - $ObjectID 79 + $ObjectID 103 Type "checkbox" Name "errorOnConnection" Prompt "Error on missing connection" @@ -2099,7 +2293,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 80 + $ObjectID 104 $ClassName "Simulink.Mask" Type "Errors" Description "Computes two kinds of errors. The first is just the difference between x\nand y while the secon" @@ -2242,7 +2436,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 81 + $ObjectID 105 $ClassName "Simulink.Mask" Type "Holder" Description "This block holds the first input value during the simulation." @@ -2322,7 +2516,7 @@ Library { TiledPageScale 1 ShowPageBoundaries off ZoomFactor "100" - SIDHighWatermark "1610" + SIDHighWatermark "1619" Block { BlockType Inport Name "s" @@ -2343,20 +2537,20 @@ Library { Block { BlockType Demux Name " Demux " - SID "1300::1609" + SID "1300::1618" Ports [1, 1] Position [270, 230, 320, 270] - ZOrder 86 + ZOrder 95 Outputs "1" } Block { BlockType S-Function Name " SFunction " - SID "1300::1608" + SID "1300::1617" Tag "Stateflow S-Function WBToolboxLibrary_repository 1" Ports [2, 2] Position [180, 100, 230, 160] - ZOrder 85 + ZOrder 94 FunctionName "sf_sfun" PortCounts "[2 2]" SFunctionDeploymentMode off @@ -2372,9 +2566,9 @@ Library { Block { BlockType Terminator Name " Terminator " - SID "1300::1610" + SID "1300::1619" Position [460, 241, 480, 259] - ZOrder 87 + ZOrder 96 } Block { BlockType Outport @@ -2385,7 +2579,7 @@ Library { IconDisplay "Port number" } Line { - ZOrder 61 + ZOrder 76 SrcBlock "s" SrcPort 1 Points [120, 0] @@ -2393,7 +2587,7 @@ Library { DstPort 1 } Line { - ZOrder 62 + ZOrder 77 SrcBlock "unused" SrcPort 1 DstBlock " SFunction " @@ -2401,7 +2595,7 @@ Library { } Line { Name "s0" - ZOrder 63 + ZOrder 78 Labels [0, 0] SrcBlock " SFunction " SrcPort 2 @@ -2409,14 +2603,14 @@ Library { DstPort 1 } Line { - ZOrder 64 + ZOrder 79 SrcBlock " Demux " SrcPort 1 DstBlock " Terminator " DstPort 1 } Line { - ZOrder 65 + ZOrder 80 SrcBlock " SFunction " SrcPort 1 DstBlock " Demux " @@ -2477,7 +2671,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 82 + $ObjectID 106 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyActuators.png'),'center')" } @@ -2511,7 +2705,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 83 + $ObjectID 107 $ClassName "Simulink.Mask" Type "Set Low Level PIDs" Description "This block sets the low level PID values for the robot actuators.\n\nIf only one gain file is s" @@ -2530,7 +2724,7 @@ Library { Type "Simulink.MaskParameter" Dimension 6 Object { - $ObjectID 84 + $ObjectID 108 Type "edit" Name "pidParameters" Prompt "PID parameter" @@ -2538,7 +2732,7 @@ Library { Tunable "off" } Object { - $ObjectID 85 + $ObjectID 109 Type "popup" Array { Type "Cell" @@ -2558,7 +2752,7 @@ Library { "kStr, 'Torque')\n set_param(gcb,'BackgroundColor', '[0.8275, 0.5765, 0.6039, 1.0]');\nend\nclear maskStr" } Object { - $ObjectID 86 + $ObjectID 110 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -2566,7 +2760,7 @@ Library { Tunable "off" } Object { - $ObjectID 87 + $ObjectID 111 Type "edit" Name "localName" Prompt "Model Name" @@ -2574,7 +2768,7 @@ Library { Tunable "off" } Object { - $ObjectID 88 + $ObjectID 112 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -2582,7 +2776,7 @@ Library { Tunable "off" } Object { - $ObjectID 89 + $ObjectID 113 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -2595,11 +2789,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 90 + $ObjectID 114 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 91 + $ObjectID 115 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -2607,29 +2801,29 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 92 + $ObjectID 116 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 93 + $ObjectID 117 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 94 + $ObjectID 118 Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 2 Object { - $ObjectID 95 + $ObjectID 119 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "pidParameters" } Object { - $ObjectID 96 + $ObjectID 120 $ClassName "Simulink.dialog.parameter.Popup" Name "pidType" } @@ -2638,25 +2832,25 @@ Library { Name "Container8" } Object { - $ObjectID 97 + $ObjectID 121 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 98 + $ObjectID 122 Name "robotName" } Object { - $ObjectID 99 + $ObjectID 123 Name "localName" } Object { - $ObjectID 100 + $ObjectID 124 Name "wbiFile" } Object { - $ObjectID 101 + $ObjectID 125 Name "wbiList" } PropName "DialogControls" @@ -2717,7 +2911,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 102 + $ObjectID 126 $ClassName "Simulink.Mask" Type "Set References" Description "This block sets the references for the robot actuators.\nThe type of control mode is specified " @@ -2734,7 +2928,7 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 103 + $ObjectID 127 Type "popup" Array { Type "Cell" @@ -2758,7 +2952,7 @@ Library { "'Open Loop')\n set_param(gcb,'BackgroundColor', '[0.98, 0.98, 0.98, 1.0]');\nend\nclear maskStr" } Object { - $ObjectID 104 + $ObjectID 128 Type "popup" Array { Type "Cell" @@ -2775,7 +2969,7 @@ Library { ";'on';'on';'on';'on'});\nend\nclear subOrFull " } Object { - $ObjectID 105 + $ObjectID 129 Type "edit" Name "controlledJoints" Prompt "Controlled Joint List" @@ -2783,7 +2977,7 @@ Library { Visible "off" } Object { - $ObjectID 106 + $ObjectID 130 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -2791,7 +2985,7 @@ Library { Tunable "off" } Object { - $ObjectID 107 + $ObjectID 131 Type "edit" Name "localName" Prompt "Model Name" @@ -2799,7 +2993,7 @@ Library { Tunable "off" } Object { - $ObjectID 108 + $ObjectID 132 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -2807,7 +3001,7 @@ Library { Tunable "off" } Object { - $ObjectID 109 + $ObjectID 133 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -2820,11 +3014,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 110 + $ObjectID 134 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 111 + $ObjectID 135 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -2832,33 +3026,33 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 112 + $ObjectID 136 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 113 + $ObjectID 137 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 114 + $ObjectID 138 Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 115 + $ObjectID 139 $ClassName "Simulink.dialog.parameter.Popup" Name "controlType" } Object { - $ObjectID 116 + $ObjectID 140 $ClassName "Simulink.dialog.parameter.Popup" Name "fullOrSubControl" } Object { - $ObjectID 117 + $ObjectID 141 $ClassName "Simulink.dialog.parameter.Edit" Name "controlledJoints" } @@ -2867,25 +3061,25 @@ Library { Name "Container8" } Object { - $ObjectID 118 + $ObjectID 142 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 119 + $ObjectID 143 Name "robotName" } Object { - $ObjectID 120 + $ObjectID 144 Name "localName" } Object { - $ObjectID 121 + $ObjectID 145 Name "wbiFile" } Object { - $ObjectID 122 + $ObjectID 146 Name "wbiList" } PropName "DialogControls" @@ -2962,7 +3156,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 123 + $ObjectID 147 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyModel.png'),'center')" } @@ -2993,7 +3187,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 124 + $ObjectID 148 $ClassName "Simulink.Mask" Display "image(imread('Dynamics.png'))" } @@ -3027,7 +3221,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 125 + $ObjectID 149 $ClassName "Simulink.Mask" Type "Centroidal Momentum" Description "This block computed the 6 element centroidal momentum, as defined in:\n\"Centroidal dynamics of a huma" @@ -3046,7 +3240,7 @@ Library { Type "Simulink.MaskParameter" Dimension 4 Object { - $ObjectID 126 + $ObjectID 150 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -3054,7 +3248,7 @@ Library { Tunable "off" } Object { - $ObjectID 127 + $ObjectID 151 Type "edit" Name "localName" Prompt "Model Name" @@ -3062,7 +3256,7 @@ Library { Tunable "off" } Object { - $ObjectID 128 + $ObjectID 152 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -3070,7 +3264,7 @@ Library { Tunable "off" } Object { - $ObjectID 129 + $ObjectID 153 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -3203,7 +3397,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 130 + $ObjectID 154 $ClassName "Simulink.Mask" Type "Get Generalized Bias Forces" Description "This block retrieves the generalied bias forces of the robot.\n\nParameter:\n- Explicit Gravity. If Tr" @@ -3228,7 +3422,7 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 131 + $ObjectID 155 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -3236,7 +3430,7 @@ Library { Tunable "off" } Object { - $ObjectID 132 + $ObjectID 156 Type "edit" Name "localName" Prompt "Model Name" @@ -3244,7 +3438,7 @@ Library { Tunable "off" } Object { - $ObjectID 133 + $ObjectID 157 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -3252,7 +3446,7 @@ Library { Tunable "off" } Object { - $ObjectID 134 + $ObjectID 158 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -3260,7 +3454,7 @@ Library { Tunable "off" } Object { - $ObjectID 135 + $ObjectID 159 Type "checkbox" Name "explicitGravity" Prompt "Explicit Gravity" @@ -3438,7 +3632,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 136 + $ObjectID 160 $ClassName "Simulink.Mask" Type "Gravity bias" Description "This block compute the generalized bias forces due to the gravity\n\nParameter:\n- Explicit Gravity. I" @@ -3461,7 +3655,7 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 137 + $ObjectID 161 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -3469,7 +3663,7 @@ Library { Tunable "off" } Object { - $ObjectID 138 + $ObjectID 162 Type "edit" Name "localName" Prompt "Model Name" @@ -3477,7 +3671,7 @@ Library { Tunable "off" } Object { - $ObjectID 139 + $ObjectID 163 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -3485,7 +3679,7 @@ Library { Tunable "off" } Object { - $ObjectID 140 + $ObjectID 164 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -3493,7 +3687,7 @@ Library { Tunable "off" } Object { - $ObjectID 141 + $ObjectID 165 Type "checkbox" Name "explicitGravity" Prompt "Explicit Gravity" @@ -3658,7 +3852,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 142 + $ObjectID 166 $ClassName "Simulink.Mask" Type "Inverse Dynamics" Description "This block compute the inverse dynamics of the robot.\n\nParameter:\n- Explicit Gravity. If True, an a" @@ -3684,35 +3878,35 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 143 + $ObjectID 167 Type "edit" Name "robotName" Prompt "Robot Port Name" Value "WBT_robotName" } Object { - $ObjectID 144 + $ObjectID 168 Type "edit" Name "localName" Prompt "Model Name" Value "WBT_modelName" } Object { - $ObjectID 145 + $ObjectID 169 Type "edit" Name "wbiFile" Prompt "WBI filename" Value "WBT_wbiFilename" } Object { - $ObjectID 146 + $ObjectID 170 Type "edit" Name "wbiList" Prompt "WBI list name" Value "WBT_wbiList" } Object { - $ObjectID 147 + $ObjectID 171 Type "checkbox" Name "explicitGravity" Prompt "Explicit Gravity" @@ -3737,7 +3931,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 148 + $ObjectID 172 $ClassName "Simulink.Mask" Type "Mass Matrix" Description "This block retrieves the robot mass matrix.\n\nAssuming DoFs is the number of degrees of freedom of th" @@ -3753,7 +3947,7 @@ Library { Type "Simulink.MaskParameter" Dimension 4 Object { - $ObjectID 149 + $ObjectID 173 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -3761,7 +3955,7 @@ Library { Tunable "off" } Object { - $ObjectID 150 + $ObjectID 174 Type "edit" Name "localName" Prompt "Model Name" @@ -3769,7 +3963,7 @@ Library { Tunable "off" } Object { - $ObjectID 151 + $ObjectID 175 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -3777,7 +3971,7 @@ Library { Tunable "off" } Object { - $ObjectID 152 + $ObjectID 176 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -3879,7 +4073,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 153 + $ObjectID 177 $ClassName "Simulink.Mask" Display "image(imread('jacobian.png'))" } @@ -3913,7 +4107,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 154 + $ObjectID 178 $ClassName "Simulink.Mask" Type "DotJ Nu" Description "This block computes the product between the time derivative of the\n Jacobian of the specified" @@ -3937,14 +4131,14 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 155 + $ObjectID 179 Type "edit" Name "frameName" Prompt "Frame name" Value "'frame'" } Object { - $ObjectID 156 + $ObjectID 180 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -3952,7 +4146,7 @@ Library { Tunable "off" } Object { - $ObjectID 157 + $ObjectID 181 Type "edit" Name "localName" Prompt "Model Name" @@ -3960,7 +4154,7 @@ Library { Tunable "off" } Object { - $ObjectID 158 + $ObjectID 182 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -3968,7 +4162,7 @@ Library { Tunable "off" } Object { - $ObjectID 159 + $ObjectID 183 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -3981,11 +4175,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 160 + $ObjectID 184 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 161 + $ObjectID 185 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -3993,46 +4187,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 162 + $ObjectID 186 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 163 + $ObjectID 187 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 164 + $ObjectID 188 Prompt "Block parameters" Object { $PropName "DialogControls" - $ObjectID 165 + $ObjectID 189 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } Name "Container8" } Object { - $ObjectID 166 + $ObjectID 190 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 167 + $ObjectID 191 Name "robotName" } Object { - $ObjectID 168 + $ObjectID 192 Name "localName" } Object { - $ObjectID 169 + $ObjectID 193 Name "wbiFile" } Object { - $ObjectID 170 + $ObjectID 194 Name "wbiList" } PropName "DialogControls" @@ -4172,7 +4366,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 171 + $ObjectID 195 $ClassName "Simulink.Mask" Type "Jacobian" Description "This block retrieves the Jacobian of the specified frame.\n\nAssuming DoFs is the number of degrees of" @@ -4192,14 +4386,14 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 172 + $ObjectID 196 Type "edit" Name "frameName" Prompt "Frame name" Value "'frame'" } Object { - $ObjectID 173 + $ObjectID 197 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -4207,7 +4401,7 @@ Library { Tunable "off" } Object { - $ObjectID 174 + $ObjectID 198 Type "edit" Name "localName" Prompt "Model Name" @@ -4215,7 +4409,7 @@ Library { Tunable "off" } Object { - $ObjectID 175 + $ObjectID 199 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -4223,7 +4417,7 @@ Library { Tunable "off" } Object { - $ObjectID 176 + $ObjectID 200 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -4236,11 +4430,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 177 + $ObjectID 201 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 178 + $ObjectID 202 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4248,46 +4442,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 179 + $ObjectID 203 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 180 + $ObjectID 204 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 181 + $ObjectID 205 Prompt "Block parameters" Object { $PropName "DialogControls" - $ObjectID 182 + $ObjectID 206 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } Name "Container8" } Object { - $ObjectID 183 + $ObjectID 207 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 184 + $ObjectID 208 Name "robotName" } Object { - $ObjectID 185 + $ObjectID 209 Name "localName" } Object { - $ObjectID 186 + $ObjectID 210 Name "wbiFile" } Object { - $ObjectID 187 + $ObjectID 211 Name "wbiList" } PropName "DialogControls" @@ -4395,7 +4589,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 188 + $ObjectID 212 $ClassName "Simulink.Mask" Display "image(imread('forwardKinematics.png'))" } @@ -4429,7 +4623,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 189 + $ObjectID 213 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4449,14 +4643,14 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 190 + $ObjectID 214 Type "edit" Name "frameName" Prompt "Frame name" Value "'frame'" } Object { - $ObjectID 191 + $ObjectID 215 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -4464,7 +4658,7 @@ Library { Tunable "off" } Object { - $ObjectID 192 + $ObjectID 216 Type "edit" Name "localName" Prompt "Model Name" @@ -4472,7 +4666,7 @@ Library { Tunable "off" } Object { - $ObjectID 193 + $ObjectID 217 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -4480,7 +4674,7 @@ Library { Tunable "off" } Object { - $ObjectID 194 + $ObjectID 218 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -4493,11 +4687,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 195 + $ObjectID 219 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 196 + $ObjectID 220 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4505,46 +4699,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 197 + $ObjectID 221 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 198 + $ObjectID 222 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 199 + $ObjectID 223 Prompt "Block parameters" Object { $PropName "DialogControls" - $ObjectID 200 + $ObjectID 224 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } Name "Container8" } Object { - $ObjectID 201 + $ObjectID 225 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 202 + $ObjectID 226 Name "robotName" } Object { - $ObjectID 203 + $ObjectID 227 Name "localName" } Object { - $ObjectID 204 + $ObjectID 228 Name "wbiFile" } Object { - $ObjectID 205 + $ObjectID 229 Name "wbiList" } PropName "DialogControls" @@ -4653,7 +4847,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 206 + $ObjectID 230 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4677,21 +4871,21 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 207 + $ObjectID 231 Type "edit" Name "baseFrame" Prompt "Base Frame" Value "'root_link'" } Object { - $ObjectID 208 + $ObjectID 232 Type "edit" Name "endEffFrame" Prompt "End Effector frame" Value "'l_sole'" } Object { - $ObjectID 209 + $ObjectID 233 Type "popup" Array { Type "Cell" @@ -4705,7 +4899,7 @@ Library { Value "Full Constraint (Position and Orientation)" } Object { - $ObjectID 210 + $ObjectID 234 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -4713,7 +4907,7 @@ Library { Tunable "off" } Object { - $ObjectID 211 + $ObjectID 235 Type "edit" Name "localName" Prompt "Model Name" @@ -4721,7 +4915,7 @@ Library { Tunable "off" } Object { - $ObjectID 212 + $ObjectID 236 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -4729,7 +4923,7 @@ Library { Tunable "off" } Object { - $ObjectID 213 + $ObjectID 237 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -4742,11 +4936,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 214 + $ObjectID 238 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 215 + $ObjectID 239 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4754,34 +4948,34 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 216 + $ObjectID 240 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 217 + $ObjectID 241 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 218 + $ObjectID 242 Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 219 + $ObjectID 243 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "baseFrame" } Object { - $ObjectID 220 + $ObjectID 244 $ClassName "Simulink.dialog.parameter.Edit" Name "endEffFrame" } Object { - $ObjectID 221 + $ObjectID 245 $ClassName "Simulink.dialog.parameter.Popup" Name "optOption" } @@ -4790,25 +4984,25 @@ Library { Name "Container8" } Object { - $ObjectID 222 + $ObjectID 246 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 223 + $ObjectID 247 Name "robotName" } Object { - $ObjectID 224 + $ObjectID 248 Name "localName" } Object { - $ObjectID 225 + $ObjectID 249 Name "wbiFile" } Object { - $ObjectID 226 + $ObjectID 250 Name "wbiList" } PropName "DialogControls" @@ -4947,7 +5141,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 227 + $ObjectID 251 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4973,14 +5167,14 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 228 + $ObjectID 252 Type "edit" Name "solverName" Prompt "Solver Name" Value "'/cartesianSolver'" } Object { - $ObjectID 229 + $ObjectID 253 Type "edit" Name "dofs" Prompt "#Dofs" @@ -4988,7 +5182,7 @@ Library { Tunable "off" } Object { - $ObjectID 230 + $ObjectID 254 Type "popup" Array { Type "Cell" @@ -5007,11 +5201,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 231 + $ObjectID 255 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 232 + $ObjectID 256 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5019,33 +5213,33 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 233 + $ObjectID 257 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 234 + $ObjectID 258 $ClassName "Simulink.dialog.TabContainer" Object { $PropName "DialogControls" - $ObjectID 235 + $ObjectID 259 $ClassName "Simulink.dialog.Tab" Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 236 + $ObjectID 260 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "solverName" } Object { - $ObjectID 237 + $ObjectID 261 $ClassName "Simulink.dialog.parameter.Edit" Name "dofs" } Object { - $ObjectID 238 + $ObjectID 262 $ClassName "Simulink.dialog.parameter.Popup" Name "optOption" } @@ -5153,7 +5347,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 239 + $ObjectID 263 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyStates.png'),'center');" } @@ -5187,7 +5381,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 240 + $ObjectID 264 $ClassName "Simulink.Mask" Type "Get Estimate" Description "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of " @@ -5202,7 +5396,7 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 241 + $ObjectID 265 Type "popup" Array { Type "Cell" @@ -5225,7 +5419,7 @@ Library { "');\nend\nclear maskStr" } Object { - $ObjectID 242 + $ObjectID 266 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -5233,7 +5427,7 @@ Library { Tunable "off" } Object { - $ObjectID 243 + $ObjectID 267 Type "edit" Name "localName" Prompt "Model Name" @@ -5241,7 +5435,7 @@ Library { Tunable "off" } Object { - $ObjectID 244 + $ObjectID 268 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -5249,7 +5443,7 @@ Library { Tunable "off" } Object { - $ObjectID 245 + $ObjectID 269 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -5262,11 +5456,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 246 + $ObjectID 270 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 247 + $ObjectID 271 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5274,46 +5468,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 248 + $ObjectID 272 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 249 + $ObjectID 273 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 250 + $ObjectID 274 Prompt "Block parameters" Object { $PropName "DialogControls" - $ObjectID 251 + $ObjectID 275 $ClassName "Simulink.dialog.parameter.Popup" Name "estimateType" } Name "Container8" } Object { - $ObjectID 252 + $ObjectID 276 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 253 + $ObjectID 277 Name "robotName" } Object { - $ObjectID 254 + $ObjectID 278 Name "localName" } Object { - $ObjectID 255 + $ObjectID 279 Name "wbiFile" } Object { - $ObjectID 256 + $ObjectID 280 Name "wbiList" } PropName "DialogControls" @@ -5389,7 +5583,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 257 + $ObjectID 281 $ClassName "Simulink.Mask" Type "Get Estimate" Description "This block get the estimate of the specified type\n\nAssuming DoFs is the number of degrees of " @@ -5404,7 +5598,7 @@ Library { Type "Simulink.MaskParameter" Dimension 5 Object { - $ObjectID 258 + $ObjectID 282 Type "popup" Array { Type "Cell" @@ -5424,7 +5618,7 @@ Library { ";\nend\nclear maskStr" } Object { - $ObjectID 259 + $ObjectID 283 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -5432,7 +5626,7 @@ Library { Tunable "off" } Object { - $ObjectID 260 + $ObjectID 284 Type "edit" Name "localName" Prompt "Model Name" @@ -5440,7 +5634,7 @@ Library { Tunable "off" } Object { - $ObjectID 261 + $ObjectID 285 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -5448,7 +5642,7 @@ Library { Tunable "off" } Object { - $ObjectID 262 + $ObjectID 286 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -5461,11 +5655,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 263 + $ObjectID 287 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 264 + $ObjectID 288 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5473,46 +5667,46 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 265 + $ObjectID 289 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 266 + $ObjectID 290 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 267 + $ObjectID 291 Prompt "Block parameters" Object { $PropName "DialogControls" - $ObjectID 268 + $ObjectID 292 $ClassName "Simulink.dialog.parameter.Popup" Name "limitsType" } Name "Container8" } Object { - $ObjectID 269 + $ObjectID 293 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 270 + $ObjectID 294 Name "robotName" } Object { - $ObjectID 271 + $ObjectID 295 Name "localName" } Object { - $ObjectID 272 + $ObjectID 296 Name "wbiFile" } Object { - $ObjectID 273 + $ObjectID 297 Name "wbiList" } PropName "DialogControls" From 4791efe8bfdd3331d51d024c0593ab9ac4a9faa6 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 12:54:42 +0000 Subject: [PATCH 89/92] DiscreteFilter: improved behavior of optional parameters Now it works as expected when the initial state vector is set but is not enabled --- toolbox/src/DiscreteFilter.cpp | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp index 0950dc573..8c466ba6d 100644 --- a/toolbox/src/DiscreteFilter.cpp +++ b/toolbox/src/DiscreteFilter.cpp @@ -123,8 +123,15 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) yarp::sig::Vector den(0); stringToYarpVector(num_coeff_str, num); stringToYarpVector(den_coeff_str, den); - stringToYarpVector(y0_str, *y0); - stringToYarpVector(u0_str, *u0); + + // y0 and u0 are none if they are not defined + if (y0_str != "none") { + stringToYarpVector(y0_str, *y0); + } + + if (u0_str != "nome") { + stringToYarpVector(u0_str, *u0); + } // Create the filter object // ======================== @@ -173,6 +180,9 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) return false; } + // Initialize the other data + // ========================= + // Get the width of the input vector inputSignalWidth = blockInfo->getInputPortWidth(INPUT_IDX_SIGNAL); @@ -181,14 +191,14 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) unsigned y0Width = y0->length(); unsigned u0Width = u0->length(); - if (y0Width != outputSignalWidth) { + if ((y0_str != "none") && (y0Width != outputSignalWidth)) { if (error) { error->message = ClassName + " y0 and output signal sizes don't match"; } return false; } - if ((filter_type == "Generic") && (u0Width != inputSignalWidth)) { + if ((u0_str != "none") && (filter_type == "Generic") && (u0Width != inputSignalWidth)) { if (error) { error->message = ClassName + " (Generic) u0 and input signal sizes don't match"; } @@ -236,7 +246,7 @@ bool DiscreteFilter::initializeInitialConditions(BlockInformation* blockInfo, wb // If the initial conditions for the output are not set, allocate a properly // sized vector - if (*y0 == Vector(1, 0.0)) { + if (*y0 == Vector(0)) { y0 = new Vector(inputSignalWidth, 0.0); } From 189df02d89954a34e914033b91d7a0ced60a0b99 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 13:49:33 +0000 Subject: [PATCH 90/92] Reduced memory allocations --- toolbox/src/DiscreteFilter.cpp | 27 +++++++++++++++++---------- 1 file changed, 17 insertions(+), 10 deletions(-) diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp index 8c466ba6d..be74d7c70 100644 --- a/toolbox/src/DiscreteFilter.cpp +++ b/toolbox/src/DiscreteFilter.cpp @@ -33,10 +33,9 @@ using namespace yarp::sig; std::string DiscreteFilter::ClassName = "DiscreteFilter"; -DiscreteFilter::DiscreteFilter() : filter(nullptr), inputSignalVector(nullptr) +DiscreteFilter::DiscreteFilter() + : filter(nullptr), y0(nullptr), u0(nullptr), inputSignalVector(nullptr) { - y0 = new Vector(0); - u0 = new Vector(0); } unsigned DiscreteFilter::numberOfParameters() @@ -125,12 +124,18 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) stringToYarpVector(den_coeff_str, den); // y0 and u0 are none if they are not defined + unsigned y0Width, u0Width; + if (y0_str != "none") { + y0 = new Vector(0); stringToYarpVector(y0_str, *y0); + y0Width = y0->length(); } - if (u0_str != "nome") { + if (u0_str != "none") { + u0 = new Vector(0); stringToYarpVector(u0_str, *u0); + u0Width = u0->length(); } // Create the filter object @@ -188,17 +193,15 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) // Check the initial conditions are properly sized unsigned outputSignalWidth = blockInfo->getInputPortWidth(OUTPUT_IDX_SIGNAL); - unsigned y0Width = y0->length(); - unsigned u0Width = u0->length(); - if ((y0_str != "none") && (y0Width != outputSignalWidth)) { + if ((y0 != nullptr) && (y0Width != outputSignalWidth)) { if (error) { error->message = ClassName + " y0 and output signal sizes don't match"; } return false; } - if ((u0_str != "none") && (filter_type == "Generic") && (u0Width != inputSignalWidth)) { + if ((u0 != nullptr) && (filter_type == "Generic") && (u0Width != inputSignalWidth)) { if (error) { error->message = ClassName + " (Generic) u0 and input signal sizes don't match"; } @@ -246,8 +249,12 @@ bool DiscreteFilter::initializeInitialConditions(BlockInformation* blockInfo, wb // If the initial conditions for the output are not set, allocate a properly // sized vector - if (*y0 == Vector(0)) { - y0 = new Vector(inputSignalWidth, 0.0); + if (y0 == nullptr) { + unsigned outputSignalWidth = blockInfo->getInputPortWidth(OUTPUT_IDX_SIGNAL); + y0 = new Vector(outputSignalWidth, 0.0); + } + if (u0 == nullptr) { + u0 = new Vector(inputSignalWidth, 0.0); } // Initialize the filter. This is required because if the signal is not 1D, From fafaaf1644d856fc82258de5193f9fd6de3f4857 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Fri, 11 Aug 2017 14:18:26 +0000 Subject: [PATCH 91/92] DiscreteFilter: uploaded test model --- tests/models/DiscreteFilter2014b.mdl | 1086 ++++++++++++++++++++++++++ 1 file changed, 1086 insertions(+) create mode 100644 tests/models/DiscreteFilter2014b.mdl diff --git a/tests/models/DiscreteFilter2014b.mdl b/tests/models/DiscreteFilter2014b.mdl new file mode 100644 index 000000000..d328aa757 --- /dev/null +++ b/tests/models/DiscreteFilter2014b.mdl @@ -0,0 +1,1086 @@ +Model { + Name "DiscreteFilter2014b" + Version 8.4 + SavedCharacterEncoding "US-ASCII" + GraphicalInterface { + NumRootInports 0 + NumRootOutports 0 + ParameterArgumentNames "" + ComputedModelVersion "1.64" + NumModelReferences 0 + NumTestPointedSignals 0 + } + ScopeRefreshTime 0.035000 + OverrideScopeRefreshTime on + DisableAllScopes off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + MinMaxOverflowArchiveMode "Overwrite" + FPTRunName "Run 1" + MaxMDLFileLineLength 120 + Object { + $PropName "BdWindowsInfo" + $ObjectID 1 + $ClassName "Simulink.BDWindowsInfo" + Object { + $PropName "WindowsInfo" + $ObjectID 2 + $ClassName "Simulink.WindowInfo" + IsActive [1] + Location [151.0, 32.0, 1185.0, 779.0] + Object { + $PropName "ModelBrowserInfo" + $ObjectID 3 + $ClassName "Simulink.ModelBrowserInfo" + Visible [0] + DockPosition "Left" + Width [50] + Height [50] + Filter [9] + } + Object { + $PropName "ExplorerBarInfo" + $ObjectID 4 + $ClassName "Simulink.ExplorerBarInfo" + Visible [1] + } + Object { + $PropName "EditorsInfo" + $ObjectID 5 + $ClassName "Simulink.EditorInfo" + IsActive [1] + ViewObjType "SimulinkTopLevel" + LoadSaveID "0" + Extents [1131.0, 586.0] + ZoomFactor [2.1817619879155012] + Offset [138.17691806436989, 8.7048744900272084] + } + } + } + Created "Tue Aug 08 11:48:28 2017" + Creator "icub" + UpdateHistory "UpdateHistoryNever" + ModifiedByFormat "%" + LastModifiedBy "icub" + ModifiedDateFormat "%" + LastModifiedDate "Fri Aug 11 14:16:58 2017" + RTWModifiedTimeStamp 424361818 + ModelVersionFormat "1.%" + ConfigurationManager "none" + SampleTimeColors off + SampleTimeAnnotations off + LibraryLinkDisplay "disabled" + WideLines on + ShowLineDimensions on + ShowPortDataTypes off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder on + ExecutionContextIcon off + ShowLinearizationAnnotations on + ShowMarkup on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks off + BrowserLookUnderMasks off + SimulationMode "normal" + PauseTimes "5" + NumberOfSteps 1 + SnapshotBufferSize 10 + SnapshotInterval 10 + NumberOfLastSnapshots 0 + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + AccelSystemTargetFile "accel.tlc" + AccelTemplateMakefile "accel_default_tmf" + AccelMakeCommand "make_rtw" + TryForcingSFcnDF off + Object { + $PropName "DataLoggingOverride" + $ObjectID 7 + $ClassName "Simulink.SimulationData.ModelLoggingInfo" + model_ "DiscreteFilter2014b" + overrideMode_ [0.0] + Array { + Type "Cell" + Dimension 1 + Cell "DiscreteFilter2014b" + PropName "logAsSpecifiedByModels_" + } + Array { + Type "Cell" + Dimension 1 + Cell [] + PropName "logAsSpecifiedByModelsSSIDs_" + } + } + RecordCoverage off + CovPath "/" + CovSaveName "covdata" + CovMetricSettings "dwe" + CovNameIncrementing off + CovHtmlReporting off + CovForceBlockReductionOff on + CovEnableCumulative on + covSaveCumulativeToWorkspaceVar off + CovSaveSingleToWorkspaceVar off + CovCumulativeVarName "covCumulativeData" + CovCumulativeReport off + CovReportOnPause on + CovModelRefEnable "Off" + CovExternalEMLEnable on + CovSFcnEnable on + CovBoundaryAbsTol 0.000010 + CovBoundaryRelTol 0.010000 + CovUseTimeInterval off + CovStartTime 0 + CovStopTime 0 + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 8 + Version "1.14.3" + Array { + Type "Handle" + Dimension 8 + Simulink.SolverCC { + $ObjectID 9 + Version "1.14.3" + StartTime "0.0" + StopTime "10.0" + AbsTol "auto" + FixedStep "0.01" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + SolverMode "SingleTasking" + EnableConcurrentExecution off + ConcurrentTasks off + Solver "ode3" + SolverName "ode3" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + } + Simulink.DataIOCC { + $ObjectID 10 + Version "1.14.3" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints off + MaxDataPoints "1000" + LoadExternalInput off + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "StructureWithTime" + SignalLoggingSaveFormat "Dataset" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + VisualizeSimOutput on + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + } + Simulink.OptimizationCC { + $ObjectID 11 + Version "1.14.3" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + InlineParams off + UseDivisionForNetSlopeComputation "Off" + UseFloatMulNetSlope off + DefaultUnderspecifiedDataType "double" + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + CachingGlobalReferences off + GlobalBufferReuse on + StrengthReduction off + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + ExpressionDepthLimit 128 + LocalBlockOutputs on + RollThreshold 5 + StateBitsets off + DataBitsets off + ActiveStateOutputEnumStorageType "Native Integer" + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + OptimizeModelRefInitCode off + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "Off" + AccelVerboseBuild off + } + Simulink.DebuggingCC { + $ObjectID 12 + Version "1.14.3" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "none" + SignalRangeChecking "none" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Simplified" + MergeDetectMultiDrivingBlocksExec "error" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "none" + InheritedTsInSrcMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "error" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "none" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "none" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "EnableAllAsError" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "error" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "none" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "error" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "error" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnconditionalTransitionShadowingDiag "warning" + SFUndirectedBroadcastEventsDiag "warning" + SFTransitionActionBeforeConditionDiag "warning" + IntegerSaturationMsg "warning" + ModelReferenceCSMismatchMessage "none" + } + Simulink.HardwareCC { + $ObjectID 13 + Version "1.14.3" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerLongLong 64 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 64 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "Float" + ProdIntDivRoundTo "Zero" + ProdEndianess "LittleEndian" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdLongLongMode off + ProdHWDeviceType "Specified" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerLongLong 64 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetLongLongMode off + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + } + Simulink.ModelReferenceCC { + $ObjectID 14 + Version "1.14.3" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel on + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 15 + Version "1.14.3" + SFSimEcho on + SimCtrlC on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + SimGenImportedTypeDefs off + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 16 + Version "1.14.3" + Array { + Type "Cell" + Dimension 13 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "PortableWordSizes" + Cell "GenerateWebview" + Cell "GenerateCodeMetricsReport" + Cell "GenerateCodeReplacementReport" + Cell "GenerateMissedCodeReplacementReport" + Cell "GenerateErtSFunction" + Cell "CreateSILPILBlock" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + TLCOptions "" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + PackageGeneratedCodeAndArtifacts off + TemplateMakefile "grt_default_tmf" + PostCodeGenCommand "" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + Toolchain "Automatically locate an installed toolchain" + BuildConfiguration "Faster Builds" + IncludeHyperlinkInReport off + LaunchReport off + PortableWordSizes off + CreateSILPILBlock "None" + CodeExecutionProfiling off + CodeExecutionProfileVariable "executionProfile" + CodeProfilingSaveOptions "SummaryOnly" + CodeProfilingInstrumentation off + SILDebugging off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateWebview off + GenerateCodeMetricsReport off + GenerateCodeReplacementReport off + RTWCompilerOptimization "Off" + RTWCustomCompilerOptimizations "" + CheckMdlBeforeBuild "Off" + SharedConstantsCachingThreshold 1024 + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 17 + Version "1.14.3" + Array { + Type "Cell" + Dimension 25 + Cell "IgnoreCustomStorageClasses" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InternalIdentifier" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrModelFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "CustomSymbolStrUtil" + Cell "CustomUserTokenString" + Cell "ReqsInCode" + PropName "DisabledProps" + } + ForceParamTrailComments off + GenerateComments on + CommentStyle "Auto" + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + OperatorAnnotations off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M_T" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + CustomSymbolStrUtil "$N$C" + DefineNamingRule "None" + ParamNamingRule "None" + SignalNamingRule "None" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InternalIdentifier "Shortened" + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 18 + Version "1.14.3" + Array { + Type "Cell" + Dimension 15 + Cell "IncludeMdlTerminateFcn" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "ExistingSharedCode" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "GenerateAllocFcn" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + Cell "SupportNonInlinedSFcns" + Cell "RemoveDisableFunc" + Cell "RemoveResetFunc" + PropName "DisabledProps" + } + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + GenFloatMathFcnCalls "NOT IN USE" + TargetLangStandard "C99 (ISO)" + CodeReplacementLibrary "None" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + GenerateSampleERTMain off + GenerateTestInterfaces off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Use local settings" + CombineOutputUpdateFcns on + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + CodeInterfacePackaging "Nonreusable function" + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + SupportVariableSizeSignals off + ParenthesesLevel "Nominal" + CastingMode "Nominal" + MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant on + AutosarCompliant off + GRTInterface off + GenerateAllocFcn off + GenerateSharedConstants on + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + MultiInstanceErrorCode "Error" + } + PropName "Components" + } + } + PropName "Components" + } + Name "Configuration" + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 376, 270, 1266, 1010 ] + } + PropName "ConfigurationSets" + } + Simulink.ConfigSet { + $PropName "ActiveConfigurationSet" + $ObjectID 8 + } + Object { + $PropName "DataTransfer" + $ObjectID 20 + $ClassName "Simulink.GlobalDataTransfer" + DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)" + DefaultTransitionBetweenAsyncTasks "Ensure data integrity only" + DefaultTransitionBetweenContTasks "Ensure deterministic transfer (minimum delay)" + DefaultExtrapolationMethodBetweenContTasks "None" + AutoInsertRateTranBlk [0] + } + ExplicitPartitioning off + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + MaskDefaults { + SelfModifiable "off" + IconFrame "on" + IconOpaque "on" + RunInitForIconRedraw "off" + IconRotate "none" + PortRotate "default" + IconUnits "autoscale" + } + MaskParameterDefaults { + Evaluate "on" + Tunable "on" + NeverSave "off" + Internal "off" + ReadOnly "off" + Enabled "on" + Visible "on" + ToolTip "on" + } + BlockParameterDefaults { + Block { + BlockType Constant + Value "1" + VectorParams1D on + SamplingMode "Sample based" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit from 'Constant value'" + LockScale off + SampleTime "inf" + FramePeriod "inf" + PreserveConstantTs off + } + Block { + BlockType Mux + Inputs "4" + DisplayOption "none" + UseBusObject off + BusObject "BusObject" + NonVirtualBus off + } + Block { + BlockType Scope + Floating off + } + Block { + BlockType Sin + SineType "Time based" + TimeSource "Use simulation time" + Amplitude "1" + Bias "0" + Frequency "1" + Phase "0" + Samples "10" + Offset "0" + SampleTime "-1" + VectorParams1D on + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + } + System { + Name "DiscreteFilter2014b" + Location [151, 32, 1336, 811] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "218" + ReportName "simulink-default.rpt" + SIDHighWatermark "51" + Block { + BlockType Constant + Name "Constant" + SID "16" + Position [155, 190, 185, 220] + ZOrder 14 + } + Block { + BlockType Reference + Name "DiscreteFilter1" + SID "47" + Ports [1, 1] + Position [440, 110, 500, 140] + ZOrder 99 + BackgroundColor "yellow" + LibraryVersion "1.395" + SourceBlock "WBToolboxLibrary/Utilities/DiscreteFilter" + SourceType "Discrete Filter" + filterType "FirstOrderLowPassFilter" + numCoeffs "[0]" + denCoeffs "[0]" + Fc "1" + Ts "0.01" + orderMedianFilter "0" + initStatus on + y0 "[0 1]" + u0 "[0]" + Port { + PortNumber 1 + Name "filtered_signals" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Mux + Name "Mux" + SID "23" + Ports [2, 1] + Position [395, 106, 400, 144] + ZOrder 20 + ShowName off + Inputs "2" + DisplayOption "bar" + } + Block { + BlockType Mux + Name "Mux1" + SID "50" + Ports [3, 1] + Position [590, 50, 595, 140] + ZOrder 102 + ShowName off + Inputs "3" + DisplayOption "bar" + } + Block { + BlockType Scope + Name "Scope" + SID "51" + Ports [1] + Position [620, 79, 650, 111] + ZOrder 103 + NumInputPorts "1" + Open off + TimeRange auto + TickLabels OneTimeTick + ShowLegends on + LimitDataPoints off + MaxDataPoints 5000 + SaveToWorkspace off + SaveName ScopeData + YMin -1.6103 + YMax 2.6103 + SampleInput off + SampleTime -1 + ZoomMode on + Grid on + DataFormat StructureWithTime + Decimation 1 + List { + ListType AxesTitles + axes1 "%" + } + List { + ListType ScopeGraphics + FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" + AxesColor "[0 0 0]" + AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + Location [675 361 1245 811] + } + Block { + BlockType Sin + Name "Sine 0.5Hz" + SID "6" + Ports [0, 1] + Position [155, 70, 185, 100] + ZOrder 6 + Frequency "2*pi*0.5" + SampleTime "0" + } + Block { + BlockType Sin + Name "Sine 10Hz" + SID "13" + Ports [0, 1] + Position [155, 130, 185, 160] + ZOrder 11 + Amplitude "0.2" + Frequency "2*pi*10" + SampleTime "0" + } + Block { + BlockType Sum + Name "Sum" + SID "12" + Ports [2, 1] + Position [235, 105, 255, 125] + ZOrder 10 + ShowName off + IconShape "round" + Inputs "+|+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "signal1" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum1" + SID "15" + Ports [2, 1] + Position [295, 125, 315, 145] + ZOrder 13 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "signal2" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Line { + Name "filtered_signals" + ZOrder 258 + Labels [-1, 1] + SrcBlock "DiscreteFilter1" + SrcPort 1 + DstBlock "Mux1" + DstPort 3 + } + Line { + Name "signal1" + ZOrder 19 + SrcBlock "Sum" + SrcPort 1 + Points [12, 0] + Branch { + ZOrder 73 + Points [47, 0] + Branch { + ZOrder 257 + Labels [-1, 1] + Points [0, -50] + DstBlock "Mux1" + DstPort 1 + } + Branch { + ZOrder 70 + Labels [-1, 1] + DstBlock "Mux" + DstPort 1 + } + } + Branch { + ZOrder 32 + Points [0, 20] + DstBlock "Sum1" + DstPort 1 + } + } + Line { + ZOrder 20 + SrcBlock "Sine 0.5Hz" + SrcPort 1 + Points [55, 0] + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 21 + SrcBlock "Sine 10Hz" + SrcPort 1 + Points [55, 0] + DstBlock "Sum" + DstPort 2 + } + Line { + Name "signal2" + ZOrder 41 + SrcBlock "Sum1" + SrcPort 1 + Points [16, 0] + Branch { + ZOrder 256 + Labels [-1, 1] + Points [0, -40] + DstBlock "Mux1" + DstPort 2 + } + Branch { + ZOrder 71 + Labels [-1, 1] + DstBlock "Mux" + DstPort 2 + } + } + Line { + ZOrder 33 + SrcBlock "Constant" + SrcPort 1 + Points [115, 0] + DstBlock "Sum1" + DstPort 2 + } + Line { + ZOrder 227 + SrcBlock "Mux" + SrcPort 1 + DstBlock "DiscreteFilter1" + DstPort 1 + } + Line { + ZOrder 259 + SrcBlock "Mux1" + SrcPort 1 + DstBlock "Scope" + DstPort 1 + } + } +} From 580e4300f94532bcd6c588e00a1d173a0eb9cea1 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 6 Dec 2017 10:11:12 +0000 Subject: [PATCH 92/92] Rebased DiscreteFilter block on WB3.0 --- toolbox/CMakeLists.txt | 1 + toolbox/include/DiscreteFilter.h | 43 +- .../library/WBToolboxLibrary_repository.mdl | 575 ++++++++++++------ .../library/exported/WBToolboxLibrary.slx | Bin 534789 -> 537123 bytes toolbox/src/DiscreteFilter.cpp | 177 +++--- 5 files changed, 494 insertions(+), 302 deletions(-) diff --git a/toolbox/CMakeLists.txt b/toolbox/CMakeLists.txt index b4c538673..fa353fa7a 100755 --- a/toolbox/CMakeLists.txt +++ b/toolbox/CMakeLists.txt @@ -94,6 +94,7 @@ if (WBT_USES_ICUB) # # include_directories(SYSTEM ${iKin_INCLUDE_DIRS}) # endif() + configure_block(BLOCK_NAME "Discrete Filter" GROUP "Utilities" LIST_PREFIX WBT diff --git a/toolbox/include/DiscreteFilter.h b/toolbox/include/DiscreteFilter.h index 098ca3966..65915f3a1 100644 --- a/toolbox/include/DiscreteFilter.h +++ b/toolbox/include/DiscreteFilter.h @@ -1,6 +1,7 @@ #include "Block.h" #include #include +#include #ifndef WBT_FILTER_H #define WBT_FILTER_H @@ -24,25 +25,41 @@ namespace yarp { class wbt::DiscreteFilter : public wbt::Block { private: unsigned inputSignalWidth; - iCub::ctrl::IFilter* filter; - yarp::sig::Vector* y0; - yarp::sig::Vector* u0; - yarp::sig::Vector* inputSignalVector; + std::unique_ptr filter; + std::unique_ptr y0; + std::unique_ptr u0; + std::unique_ptr inputSignalVector; static void stringToYarpVector(const std::string s, yarp::sig::Vector& v); + // Parameters + static const unsigned PARAM_IDX_FLT_TYPE; + static const unsigned PARAM_IDX_NUMCOEFF; + static const unsigned PARAM_IDX_DENCOEFF; + static const unsigned PARAM_IDX_1LOWP_FC; + static const unsigned PARAM_IDX_1LOWP_TS; + static const unsigned PARAM_IDX_MD_ORDER; + static const unsigned PARAM_IDX_INIT_Y0; + static const unsigned PARAM_IDX_INIT_U0; + // Inputs + static const unsigned INPUT_IDX_SIGNAL; + // Outputs + static const unsigned OUTPUT_IDX_SIGNAL; + // Other defines + static const int SIGNAL_DYNAMIC_SIZE; + public: - static std::string ClassName; + static const std::string ClassName; DiscreteFilter(); - ~DiscreteFilter() = default; - - virtual unsigned numberOfParameters(); - virtual bool configureSizeAndPorts(BlockInformation* blockInfo, wbt::Error* error); - virtual bool initialize(BlockInformation* blockInfo, wbt::Error* error); - virtual bool initializeInitialConditions(BlockInformation *blockInfo, wbt::Error *error); - virtual bool terminate(BlockInformation* blockInfo, wbt::Error* error); - virtual bool output(BlockInformation* blockInfo, wbt::Error* error); + ~DiscreteFilter() override = default; + + unsigned numberOfParameters() override; + bool configureSizeAndPorts(BlockInformation* blockInfo) override; + bool initialize(const BlockInformation* blockInfo) override; + bool initializeInitialConditions(const BlockInformation* blockInfo) override; + bool terminate(const BlockInformation* blockInfo) override; + bool output(const BlockInformation* blockInfo) override; }; #endif // WBT_FILTER_H diff --git a/toolbox/matlab/library/WBToolboxLibrary_repository.mdl b/toolbox/matlab/library/WBToolboxLibrary_repository.mdl index 0ae80c40b..1083107e5 100644 --- a/toolbox/matlab/library/WBToolboxLibrary_repository.mdl +++ b/toolbox/matlab/library/WBToolboxLibrary_repository.mdl @@ -61,7 +61,7 @@ Library { LoadSaveID "192" Extents [1557.0, 726.0] ZoomFactor [2.13] - Offset [0.0, 0.0] + Offset [-46.444835680751169, 21.953051643192453] } PropName "EditorsInfo" } @@ -97,9 +97,9 @@ Library { ModifiedByFormat "%" LastModifiedBy "dferigo" ModifiedDateFormat "%" - LastModifiedDate "Thu Nov 30 14:54:35 2017" - RTWModifiedTimeStamp 433954470 - ModelVersionFormat "1.%" + LastModifiedDate "Wed Dec 06 10:03:50 2017" + RTWModifiedTimeStamp 434455429 + ModelVersionFormat "1.%" ConfigurationManager "none" SampleTimeColors off SampleTimeAnnotations off @@ -1080,7 +1080,7 @@ Library { ShowPageBoundaries off ZoomFactor "343" ReportName "simulink-default.rpt" - SIDHighWatermark "1789" + SIDHighWatermark "1790" Block { BlockType SubSystem Name "Utilities" @@ -1573,6 +1573,217 @@ Library { } } } + Block { + BlockType S-Function + Name "DiscreteFilter" + SID "1790" + Ports [1, 1] + Position [125, 260, 185, 290] + ZOrder 96 + BackgroundColor "yellow" + FunctionName "WBToolbox" + Parameters "'DiscreteFilter',filterType,numCoeffs,denCoeffs,Fc,Ts,orderMedianFilter,y0,u0" + SFunctionDeploymentMode off + EnableBusSupport off + SFcnIsStateOwnerBlock off + Object { + $PropName "MaskObject" + $ObjectID 47 + $ClassName "Simulink.Mask" + Type "Discrete Filter" + Description "This block wraps the Filter, FirstOrderLowPassFilter, and MedianFilter from iCub::ctrl." + Initialization "filterType = get_param(gcb, 'filterType');\nnumCoeffs = mat2str(numCoeffs);\ndenCoeffs = ma" + "t2str(denCoeffs);\n\ninitStatus = get_param(gcb, 'initStatus');\n\nif (strcmp(initStatus,'on'))\n y0 = mat2str" + "(y0);\n u0 = mat2str(u0);\nelse\n y0 = 'none';\n u0 = 'none';\nend\n\nclear initStatus" + Display "disp('Filter')" + Array { + Type "Simulink.MaskParameter" + Dimension 9 + Object { + $ObjectID 48 + Type "popup" + Array { + Type "Cell" + Dimension 3 + Cell "Generic" + Cell "FirstOrderLowPassFilter" + Cell "MedianFilter" + PropName "TypeOptions" + } + Name "filterType" + Prompt "Type of the filter" + Value "Generic" + Callback "% From: https://it.mathworks.com/help/simulink/slref/simulink.mask-class.html\nfilterType = get_param(gcb" + ", 'filterType');\ninitStatus = get_param(gcb, 'initStatus');\np = Simulink.Mask.get(gcbh);\nhowToCoeffs = p.getDialo" + "gControl('howToCoeffs');\n\n%set_param(gcb, 'initStatus','off');\nif (strcmp(initStatus,'on'))\n vis_init = 'on';" + "\nelse\n vis_init = 'off';\nend\n\nif(strcmp(filterType, 'Generic'))\n set_param(gcb, 'MaskVisibilities',{'on'" + ",'on','on','off','off','off','on',vis_init,vis_init});\n howToCoeffs.Visible = 'on';\nelseif(strcmp(filterType, '" + "FirstOrderLowPassFilter'))\n set_param(gcb, 'MaskVisibilities',{'on','off','off','on','on','off','on',vis_init,'o" + "ff'});\n howToCoeffs.Visible = 'off';\nelseif(strcmp(filterType, 'MedianFilter'))\n set_param(gcb, 'MaskVisibi" + "lities',{'on','off','off','off','off','on','on',vis_init,'off'});\n howToCoeffs.Visible = 'off';\nend\n\nclear fi" + "lterType initStatus p howToCoeffs vis_init;" + } + Object { + $ObjectID 49 + Type "edit" + Name "numCoeffs" + Prompt "Numerator Coefficients*" + Value "[0]" + } + Object { + $ObjectID 50 + Type "edit" + Name "denCoeffs" + Prompt "Denominator Coefficients*" + Value "[0]" + } + Object { + $ObjectID 51 + Type "edit" + Name "Fc" + Prompt "Cut Frequency (Hz)" + Value "0" + Visible "off" + } + Object { + $ObjectID 52 + Type "edit" + Name "Ts" + Prompt "Sampling time (s)" + Value "0" + Visible "off" + } + Object { + $ObjectID 53 + Type "edit" + Name "orderMedianFilter" + Prompt "Order" + Value "0" + Visible "off" + } + Object { + $ObjectID 54 + Type "checkbox" + Name "initStatus" + Prompt "Define initial conditions" + Value "off" + Callback "initStatus = get_param(gcb, 'initStatus');\nvisibilities = get_param(gcb, 'MaskVisibilities');\nfilterT" + "ype = get_param(gcb, 'filterType');\n\nif (strcmp(initStatus,'off'))\n visibilities{8} = 'off';\n visibiliti" + "es{9} = 'off';\nelseif (strcmp(initStatus,'on'))\n visibilities{8} = 'on';\n if (strcmp(filterType,'Generic'))" + "\n visibilities{9} = 'on';\n end\nend\n\nset_param(gcb, 'MaskVisibilities', visibilities);\n\nclear initSt" + "atus visibilities filterType;" + } + Object { + $ObjectID 55 + Type "edit" + Name "y0" + Prompt "Output y0" + Value "[0]" + Visible "off" + } + Object { + $ObjectID 56 + Type "edit" + Name "u0" + Prompt "Input u0" + Value "[0]" + Visible "off" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 57 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 58 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 59 + Prompt "Simulink:studio:ToolBarParametersMenu" + Array { + Type "Simulink.dialog.Control" + Dimension 8 + Object { + $ObjectID 60 + $ClassName "Simulink.dialog.parameter.Popup" + Name "filterType" + } + Object { + $ObjectID 61 + $ClassName "Simulink.dialog.parameter.Edit" + Name "numCoeffs" + } + Object { + $ObjectID 62 + $ClassName "Simulink.dialog.parameter.Edit" + Name "denCoeffs" + } + Object { + $ObjectID 63 + $ClassName "Simulink.dialog.Text" + Prompt "* The coefficients are ordered in increasing power of z^-1" + Name "howToCoeffs" + } + Object { + $ObjectID 64 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "Fc" + } + Object { + $ObjectID 65 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "Ts" + } + Object { + $ObjectID 66 + $ClassName "Simulink.dialog.parameter.Edit" + PromptLocation "left" + Name "orderMedianFilter" + } + Object { + $ObjectID 67 + $ClassName "Simulink.dialog.Group" + Array { + Type "Simulink.dialog.parameter.Control" + Dimension 3 + Object { + $ObjectID 68 + $ClassName "Simulink.dialog.parameter.CheckBox" + Name "initStatus" + } + Object { + $ObjectID 69 + $ClassName "Simulink.dialog.parameter.Edit" + Name "y0" + } + Object { + $ObjectID 70 + $ClassName "Simulink.dialog.parameter.Edit" + Name "u0" + } + PropName "DialogControls" + } + Name "Container3" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + } Block { BlockType S-Function Name "DoFs converter" @@ -1587,7 +1798,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 47 + $ObjectID 71 $ClassName "Simulink.Mask" Type "DoFs converter" Description "This block converts from a DoFs serialization to a YARP serialization or viceversa depending on" @@ -1604,7 +1815,7 @@ Library { RunInitForIconRedraw "off" Object { $PropName "Parameters" - $ObjectID 48 + $ObjectID 72 $ClassName "Simulink.MaskParameter" Type "popup" Array { @@ -1622,11 +1833,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 49 + $ObjectID 73 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 50 + $ObjectID 74 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1634,22 +1845,22 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 51 + $ObjectID 75 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 52 + $ObjectID 76 $ClassName "Simulink.dialog.parameter.Popup" Name "yarp2WBIOption" } Object { - $ObjectID 53 + $ObjectID 77 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 54 + $ObjectID 78 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -1683,7 +1894,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 55 + $ObjectID 79 $ClassName "Simulink.Mask" Type "Minimum Jerk Trajectory Generator" Description "This block wraps the minJerkTrajGen class from iCub::ctrl::minJerkTrajGen.\n\nThe Minimum Jerk " @@ -1706,7 +1917,7 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 56 + $ObjectID 80 Type "checkbox" Name "externalSettlingTime" Prompt "External Settling Time" @@ -1717,42 +1928,42 @@ Library { "SettlingTime" } Object { - $ObjectID 57 + $ObjectID 81 Type "edit" Name "settlingTime" Prompt "Settling Time" Value "3" } Object { - $ObjectID 58 + $ObjectID 82 Type "edit" Name "sampleTime" Prompt "Sample Time" Value "0.01" } Object { - $ObjectID 59 + $ObjectID 83 Type "checkbox" Name "resetOnSettlingTime" Prompt "Reset on Settling Time Changes" Value "off" } Object { - $ObjectID 60 + $ObjectID 84 Type "checkbox" Name "firstDerivatives" Prompt "Output First Derivative" Value "on" } Object { - $ObjectID 61 + $ObjectID 85 Type "checkbox" Name "secondDerivatives" Prompt "Output Second Derivative" Value "on" } Object { - $ObjectID 62 + $ObjectID 86 Type "checkbox" Name "explicitInitialValue" Prompt "Explicit Initial Value" @@ -1765,11 +1976,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 63 + $ObjectID 87 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 64 + $ObjectID 88 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -1777,38 +1988,38 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 65 + $ObjectID 89 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 66 + $ObjectID 90 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 67 + $ObjectID 91 Prompt "Trajectory Parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 4 Object { - $ObjectID 68 + $ObjectID 92 $ClassName "Simulink.dialog.parameter.CheckBox" Name "externalSettlingTime" } Object { - $ObjectID 69 + $ObjectID 93 $ClassName "Simulink.dialog.parameter.Edit" Name "settlingTime" } Object { - $ObjectID 70 + $ObjectID 94 $ClassName "Simulink.dialog.parameter.Edit" Name "sampleTime" } Object { - $ObjectID 71 + $ObjectID 95 $ClassName "Simulink.dialog.parameter.CheckBox" Name "resetOnSettlingTime" } @@ -1817,21 +2028,21 @@ Library { Name "Tab1" } Object { - $ObjectID 72 + $ObjectID 96 Prompt "Input/Output" Array { Type "Simulink.dialog.parameter.CheckBox" Dimension 3 Object { - $ObjectID 73 + $ObjectID 97 Name "firstDerivatives" } Object { - $ObjectID 74 + $ObjectID 98 Name "secondDerivatives" } Object { - $ObjectID 75 + $ObjectID 99 Name "explicitInitialValue" } PropName "DialogControls" @@ -1865,7 +2076,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 76 + $ObjectID 100 $ClassName "Simulink.Mask" Type "Real Time Synchronizer" Description "This block slows down the simulation trying to match the period specified \nas parameter (in se" @@ -1873,7 +2084,7 @@ Library { Display "disp('Real Time Synchronizer')" Object { $PropName "Parameters" - $ObjectID 77 + $ObjectID 101 $ClassName "Simulink.MaskParameter" Type "edit" Name "period" @@ -1898,7 +2109,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 78 + $ObjectID 102 $ClassName "Simulink.Mask" Type "Simulator Synchronizer" Description "This block synchronizes with the external simulation on a simulator \n(only Gazebo is supported" @@ -1908,21 +2119,21 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 79 + $ObjectID 103 Type "edit" Name "period" Prompt "Controller Period (in seconds)" Value "0.01" } Object { - $ObjectID 80 + $ObjectID 104 Type "edit" Name "serverPortName" Prompt "Server Port Name" Value "'/clock/rpc'" } Object { - $ObjectID 81 + $ObjectID 105 Type "edit" Name "clientPortName" Prompt "Client Port Name" @@ -1944,11 +2155,11 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 82 + $ObjectID 106 $ClassName "Simulink.Mask" Object { $PropName "Parameters" - $ObjectID 83 + $ObjectID 107 $ClassName "Simulink.MaskParameter" Type "edit" Name "tol" @@ -2165,7 +2376,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 84 + $ObjectID 108 $ClassName "Simulink.Mask" Type "YARP Clock" Description "This block outputs the current YARP Time.\nIn a nutshell, this block outputs the equivalent of " @@ -2189,7 +2400,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 85 + $ObjectID 109 $ClassName "Simulink.Mask" Type "YARP Read" Description "This block behaves as the command 'yarp read'. \nBy default it has the option 'Autoconnect' act" @@ -2207,35 +2418,35 @@ Library { Type "Simulink.MaskParameter" Dimension 6 Object { - $ObjectID 86 + $ObjectID 110 Type "edit" Name "portName" Prompt "Source Port Name" Value "'/portname'" } Object { - $ObjectID 87 + $ObjectID 111 Type "edit" Name "signalSize" Prompt "Port Size" Value "1" } Object { - $ObjectID 88 + $ObjectID 112 Type "checkbox" Name "blocking" Prompt "Blocking Read" Value "off" } Object { - $ObjectID 89 + $ObjectID 113 Type "checkbox" Name "timestamp" Prompt "Read Timestamp" Value "on" } Object { - $ObjectID 90 + $ObjectID 114 Type "checkbox" Name "autoconnect" Prompt "Autoconnect" @@ -2247,7 +2458,7 @@ Library { "t_string" } Object { - $ObjectID 91 + $ObjectID 115 Type "checkbox" Name "errorOnConnection" Prompt "Error on missing connection" @@ -2272,7 +2483,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 92 + $ObjectID 116 $ClassName "Simulink.Mask" Type "YARP Write" Description "This block behaves as the command 'yarp write'. \n\nBy default this block opens a port names as" @@ -2285,14 +2496,14 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 93 + $ObjectID 117 Type "edit" Name "portName" Prompt "Opened Port Name" Value "'/portname'" } Object { - $ObjectID 94 + $ObjectID 118 Type "checkbox" Name "autoconnect" Prompt "Autoconnect" @@ -2303,7 +2514,7 @@ Library { "';'off'});\nend\nset_param(gcb, 'MaskPrompts', prompt_string);\nclear autoconnect_val prompt_string" } Object { - $ObjectID 95 + $ObjectID 119 Type "checkbox" Name "errorOnConnection" Prompt "Error on missing connection" @@ -2326,7 +2537,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 96 + $ObjectID 120 $ClassName "Simulink.Mask" Type "Errors" Description "Computes two kinds of errors. The first is just the difference between x\nand y while the secon" @@ -2470,7 +2681,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 97 + $ObjectID 121 $ClassName "Simulink.Mask" Type "Holder" Description "This block holds the first input value during the simulation." @@ -2707,7 +2918,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 98 + $ObjectID 122 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyActuators.png'),'center')" } @@ -2739,7 +2950,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 99 + $ObjectID 123 $ClassName "Simulink.Mask" Type "Set Low Level PIDs" Description "This block sets the low level PID values for the robot actuators.\n\nThe PIDs can be stored in " @@ -2761,7 +2972,7 @@ Library { Type "Simulink.MaskParameter" Dimension 2 Object { - $ObjectID 100 + $ObjectID 124 Type "edit" Name "WBTPIDConfigObjectName" Prompt "WBTPIDConfig Object Name" @@ -2769,7 +2980,7 @@ Library { Tunable "off" } Object { - $ObjectID 101 + $ObjectID 125 Type "popup" Array { Type "Cell" @@ -2795,11 +3006,11 @@ Library { Type "Simulink.dialog.Group" Dimension 3 Object { - $ObjectID 102 + $ObjectID 126 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 103 + $ObjectID 127 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -2807,19 +3018,19 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 104 + $ObjectID 128 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.parameter.Control" Dimension 2 Object { - $ObjectID 105 + $ObjectID 129 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "WBTPIDConfigObjectName" } Object { - $ObjectID 106 + $ObjectID 130 $ClassName "Simulink.dialog.parameter.Popup" Name "pidType" } @@ -2828,10 +3039,10 @@ Library { Name "ParameterGroupVar" } Object { - $ObjectID 107 + $ObjectID 131 Object { $PropName "DialogControls" - $ObjectID 108 + $ObjectID 132 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" @@ -2888,7 +3099,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 109 + $ObjectID 133 $ClassName "Simulink.Mask" Type "Set References" Description "This block sets the references for the robot actuators.\nThe type of control mode is specified " @@ -2905,7 +3116,7 @@ Library { Type "Simulink.MaskParameter" Dimension 2 Object { - $ObjectID 110 + $ObjectID 134 Type "popup" Array { Type "Cell" @@ -2937,7 +3148,7 @@ Library { " maskStr" } Object { - $ObjectID 111 + $ObjectID 135 Type "edit" Name "refSpeed" Prompt "Reference Speed" @@ -2949,11 +3160,11 @@ Library { Type "Simulink.dialog.Group" Dimension 3 Object { - $ObjectID 112 + $ObjectID 136 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 113 + $ObjectID 137 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -2961,18 +3172,18 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 114 + $ObjectID 138 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.parameter.Control" Dimension 2 Object { - $ObjectID 115 + $ObjectID 139 $ClassName "Simulink.dialog.parameter.Popup" Name "controlType" } Object { - $ObjectID 116 + $ObjectID 140 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "refSpeed" @@ -2982,10 +3193,10 @@ Library { Name "ParameterGroupVar" } Object { - $ObjectID 117 + $ObjectID 141 Object { $PropName "DialogControls" - $ObjectID 118 + $ObjectID 142 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" @@ -3060,7 +3271,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 119 + $ObjectID 143 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyModel.png'),'center')" } @@ -3092,7 +3303,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 120 + $ObjectID 144 $ClassName "Simulink.Mask" Display "image(imread('Dynamics.png'))" } @@ -3123,7 +3334,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 121 + $ObjectID 145 $ClassName "Simulink.Mask" Type "Centroidal Momentum" Description "This block computed the 6 element centroidal momentum, as defined in:\n\"Centroidal dynamics of a huma" @@ -3139,24 +3350,24 @@ Library { RunInitForIconRedraw "on" Object { $PropName "DialogControls" - $ObjectID 122 + $ObjectID 146 $ClassName "Simulink.dialog.Group" Prompt "%" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 123 + $ObjectID 147 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" } Object { - $ObjectID 124 + $ObjectID 148 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 125 + $ObjectID 149 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -3292,7 +3503,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 126 + $ObjectID 150 $ClassName "Simulink.Mask" Type "Get Generalized Bias Forces" Description "This block retrieves the generalied bias forces of the robot.\n\nAssuming DoFs is the number of degree" @@ -3307,24 +3518,24 @@ Library { RunInitForIconRedraw "on" Object { $PropName "DialogControls" - $ObjectID 127 + $ObjectID 151 $ClassName "Simulink.dialog.Group" Prompt "%" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 128 + $ObjectID 152 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" } Object { - $ObjectID 129 + $ObjectID 153 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 130 + $ObjectID 154 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -3505,7 +3716,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 131 + $ObjectID 155 $ClassName "Simulink.Mask" Type "Gravity bias" Description "This block compute the generalized bias forces due to the gravity\n\nAssuming DoFs is the number of de" @@ -3518,24 +3729,24 @@ Library { RunInitForIconRedraw "off" Object { $PropName "DialogControls" - $ObjectID 132 + $ObjectID 156 $ClassName "Simulink.dialog.Group" Prompt "%" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 133 + $ObjectID 157 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" } Object { - $ObjectID 134 + $ObjectID 158 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 135 + $ObjectID 159 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -3707,7 +3918,7 @@ Library { SFcnIsStateOwnerBlock off Object { $PropName "MaskObject" - $ObjectID 136 + $ObjectID 160 $ClassName "Simulink.Mask" Type "Inverse Dynamics" Description "This block compute the inverse dynamics of the robot.\n\nAssuming DoFs is the number of degrees of fre" @@ -3727,24 +3938,24 @@ Library { RunInitForIconRedraw "on" Object { $PropName "DialogControls" - $ObjectID 137 + $ObjectID 161 $ClassName "Simulink.dialog.Group" Prompt "%" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 138 + $ObjectID 162 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" } Object { - $ObjectID 139 + $ObjectID 163 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 140 + $ObjectID 164 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -3772,7 +3983,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 141 + $ObjectID 165 $ClassName "Simulink.Mask" Type "Mass Matrix" Description "This block retrieves the robot mass matrix.\n\nAssuming DoFs is the number of degrees of freedom of th" @@ -3785,24 +3996,24 @@ Library { RunInitForIconRedraw "on" Object { $PropName "DialogControls" - $ObjectID 142 + $ObjectID 166 $ClassName "Simulink.dialog.Group" Prompt "%" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 143 + $ObjectID 167 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" } Object { - $ObjectID 144 + $ObjectID 168 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 145 + $ObjectID 169 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -3911,7 +4122,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 146 + $ObjectID 170 $ClassName "Simulink.Mask" Display "image(imread('jacobian.png'))" } @@ -3942,7 +4153,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 147 + $ObjectID 171 $ClassName "Simulink.Mask" Type "DotJ Nu" Description "This block computes the product between the time derivative of the Jacobian of the specified frame and" @@ -3963,7 +4174,7 @@ Library { RunInitForIconRedraw "on" Object { $PropName "Parameters" - $ObjectID 148 + $ObjectID 172 $ClassName "Simulink.MaskParameter" Type "edit" Name "frameName" @@ -3974,11 +4185,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 149 + $ObjectID 173 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 150 + $ObjectID 174 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -3986,22 +4197,22 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 151 + $ObjectID 175 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 152 + $ObjectID 176 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } Object { - $ObjectID 153 + $ObjectID 177 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 154 + $ObjectID 178 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -4139,7 +4350,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 155 + $ObjectID 179 $ClassName "Simulink.Mask" Type "Jacobian" Description "This block retrieves the Jacobian of the specified frame.\n\nAssuming DoFs is the number of degrees of" @@ -4156,7 +4367,7 @@ Library { RunInitForIconRedraw "on" Object { $PropName "Parameters" - $ObjectID 156 + $ObjectID 180 $ClassName "Simulink.MaskParameter" Type "edit" Name "frameName" @@ -4167,11 +4378,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 157 + $ObjectID 181 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 158 + $ObjectID 182 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4179,22 +4390,22 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 159 + $ObjectID 183 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 160 + $ObjectID 184 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } Object { - $ObjectID 161 + $ObjectID 185 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 162 + $ObjectID 186 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -4305,7 +4516,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 163 + $ObjectID 187 $ClassName "Simulink.Mask" Display "image(imread('forwardKinematics.png'))" } @@ -4336,7 +4547,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 164 + $ObjectID 188 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4353,7 +4564,7 @@ Library { "', 2, 'Joint configuration')\n\nclear escapedFrameName;" Object { $PropName "Parameters" - $ObjectID 165 + $ObjectID 189 $ClassName "Simulink.MaskParameter" Type "edit" Name "frameName" @@ -4364,11 +4575,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 166 + $ObjectID 190 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 167 + $ObjectID 191 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4376,22 +4587,22 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 168 + $ObjectID 192 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.Control" Dimension 2 Object { - $ObjectID 169 + $ObjectID 193 $ClassName "Simulink.dialog.parameter.Edit" Name "frameName" } Object { - $ObjectID 170 + $ObjectID 194 $ClassName "Simulink.dialog.Group" Object { $PropName "DialogControls" - $ObjectID 171 + $ObjectID 195 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(conf" @@ -4504,7 +4715,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 172 + $ObjectID 196 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4528,21 +4739,21 @@ Library { Type "Simulink.MaskParameter" Dimension 7 Object { - $ObjectID 173 + $ObjectID 197 Type "edit" Name "baseFrame" Prompt "Base Frame" Value "'root_link'" } Object { - $ObjectID 174 + $ObjectID 198 Type "edit" Name "endEffFrame" Prompt "End Effector frame" Value "'l_sole'" } Object { - $ObjectID 175 + $ObjectID 199 Type "popup" Array { Type "Cell" @@ -4556,7 +4767,7 @@ Library { Value "Full Constraint (Position and Orientation)" } Object { - $ObjectID 176 + $ObjectID 200 Type "edit" Name "robotName" Prompt "Robot Port Name" @@ -4564,7 +4775,7 @@ Library { Tunable "off" } Object { - $ObjectID 177 + $ObjectID 201 Type "edit" Name "localName" Prompt "Model Name" @@ -4572,7 +4783,7 @@ Library { Tunable "off" } Object { - $ObjectID 178 + $ObjectID 202 Type "edit" Name "wbiFile" Prompt "WBI filename" @@ -4580,7 +4791,7 @@ Library { Tunable "off" } Object { - $ObjectID 179 + $ObjectID 203 Type "edit" Name "wbiList" Prompt "WBI list name" @@ -4593,11 +4804,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 180 + $ObjectID 204 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 181 + $ObjectID 205 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4605,34 +4816,34 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 182 + $ObjectID 206 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 183 + $ObjectID 207 $ClassName "Simulink.dialog.TabContainer" Array { Type "Simulink.dialog.Tab" Dimension 2 Object { - $ObjectID 184 + $ObjectID 208 Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 185 + $ObjectID 209 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "baseFrame" } Object { - $ObjectID 186 + $ObjectID 210 $ClassName "Simulink.dialog.parameter.Edit" Name "endEffFrame" } Object { - $ObjectID 187 + $ObjectID 211 $ClassName "Simulink.dialog.parameter.Popup" Name "optOption" } @@ -4641,25 +4852,25 @@ Library { Name "Container8" } Object { - $ObjectID 188 + $ObjectID 212 Prompt "WBI parameters" Array { Type "Simulink.dialog.parameter.Edit" Dimension 4 Object { - $ObjectID 189 + $ObjectID 213 Name "robotName" } Object { - $ObjectID 190 + $ObjectID 214 Name "localName" } Object { - $ObjectID 191 + $ObjectID 215 Name "wbiFile" } Object { - $ObjectID 192 + $ObjectID 216 Name "wbiList" } PropName "DialogControls" @@ -4800,7 +5011,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 193 + $ObjectID 217 $ClassName "Simulink.Mask" Type "Forward Kinematics" Description "This block retrieves the forward kinematics of the specified frame.\n\nAssuming DoFs is the number of " @@ -4826,14 +5037,14 @@ Library { Type "Simulink.MaskParameter" Dimension 3 Object { - $ObjectID 194 + $ObjectID 218 Type "edit" Name "solverName" Prompt "Solver Name" Value "'/cartesianSolver'" } Object { - $ObjectID 195 + $ObjectID 219 Type "edit" Name "dofs" Prompt "#Dofs" @@ -4841,7 +5052,7 @@ Library { Tunable "off" } Object { - $ObjectID 196 + $ObjectID 220 Type "popup" Array { Type "Cell" @@ -4860,11 +5071,11 @@ Library { Type "Simulink.dialog.Group" Dimension 2 Object { - $ObjectID 197 + $ObjectID 221 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 198 + $ObjectID 222 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -4872,33 +5083,33 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 199 + $ObjectID 223 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 200 + $ObjectID 224 $ClassName "Simulink.dialog.TabContainer" Object { $PropName "DialogControls" - $ObjectID 201 + $ObjectID 225 $ClassName "Simulink.dialog.Tab" Prompt "Block parameters" Array { Type "Simulink.dialog.parameter.Control" Dimension 3 Object { - $ObjectID 202 + $ObjectID 226 $ClassName "Simulink.dialog.parameter.Edit" PromptLocation "left" Name "solverName" } Object { - $ObjectID 203 + $ObjectID 227 $ClassName "Simulink.dialog.parameter.Edit" Name "dofs" } Object { - $ObjectID 204 + $ObjectID 228 $ClassName "Simulink.dialog.parameter.Popup" Name "optOption" } @@ -5007,7 +5218,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 205 + $ObjectID 229 $ClassName "Simulink.Mask" Display "image(imread('wholeBodyStates.png'),'center');" } @@ -5039,7 +5250,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 206 + $ObjectID 230 $ClassName "Simulink.Mask" Type "Get Limits" Description "This block provides the joint limits gathering data from either the Robot's Control Board or UR" @@ -5063,7 +5274,7 @@ Library { Type "Simulink.MaskParameter" Dimension 2 Object { - $ObjectID 207 + $ObjectID 231 Type "popup" Array { Type "Cell" @@ -5083,7 +5294,7 @@ Library { "imit blockParameters limitsTypeBlockParam" } Object { - $ObjectID 208 + $ObjectID 232 Type "popup" Array { Type "Cell" @@ -5108,11 +5319,11 @@ Library { Type "Simulink.dialog.Group" Dimension 3 Object { - $ObjectID 209 + $ObjectID 233 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 210 + $ObjectID 234 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5120,17 +5331,17 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 211 + $ObjectID 235 Prompt "Simulink:studio:ToolBarParametersMenu" Array { Type "Simulink.dialog.parameter.Popup" Dimension 2 Object { - $ObjectID 212 + $ObjectID 236 Name "limitsSource" } Object { - $ObjectID 213 + $ObjectID 237 Name "limitsType" } PropName "DialogControls" @@ -5138,10 +5349,10 @@ Library { Name "ParameterGroupVar" } Object { - $ObjectID 214 + $ObjectID 238 Object { $PropName "DialogControls" - $ObjectID 215 + $ObjectID 239 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" @@ -5230,7 +5441,7 @@ Library { Variant off Object { $PropName "MaskObject" - $ObjectID 216 + $ObjectID 240 $ClassName "Simulink.Mask" Type "Get Measurement" Description "This block gathers the measurement of the specified type.\n\nAssuming DoFs is the number of deg" @@ -5243,7 +5454,7 @@ Library { RunInitForIconRedraw "off" Object { $PropName "Parameters" - $ObjectID 217 + $ObjectID 241 $ClassName "Simulink.MaskParameter" Type "popup" Array { @@ -5270,11 +5481,11 @@ Library { Type "Simulink.dialog.Group" Dimension 3 Object { - $ObjectID 218 + $ObjectID 242 Prompt "%" Object { $PropName "DialogControls" - $ObjectID 219 + $ObjectID 243 $ClassName "Simulink.dialog.Text" Prompt "%" Name "DescTextVar" @@ -5282,21 +5493,21 @@ Library { Name "DescGroupVar" } Object { - $ObjectID 220 + $ObjectID 244 Prompt "Simulink:studio:ToolBarParametersMenu" Object { $PropName "DialogControls" - $ObjectID 221 + $ObjectID 245 $ClassName "Simulink.dialog.parameter.Popup" Name "measuredType" } Name "ParameterGroupVar" } Object { - $ObjectID 222 + $ObjectID 246 Object { $PropName "DialogControls" - $ObjectID 223 + $ObjectID 247 $ClassName "Simulink.dialog.Button" Prompt "Toggle Config Block Highlighting" Callback "[configBlock, ~] = WBToolbox.BlockInitialization(gcb, gcs);\n\ntry\n if (strcmp(get_param(configBl" diff --git a/toolbox/matlab/library/exported/WBToolboxLibrary.slx b/toolbox/matlab/library/exported/WBToolboxLibrary.slx index d2f615da634fff6b1190c48dde0c38cbd266a766..da72a0ac43c624105bff87a15e3398dbb97d435f 100644 GIT binary patch delta 81022 zcmV)MK)An!(jcScARACi0|XQR000O8h){-0w189TWdQ&HzybgO8<$Kb2p)fZQqfMs zAQb(ThW8femQ6|5C2IDxB}Qj7zEOJDp)E9ktNnXhw$`~UzQH+%bI-lpWcgi{!2yhw zS}hQb2ns+6ol8|L(93oe-k`ubu5w;#1q;-IMZq#nM9qXY@Mv@m#!0Y2XQV6>^#bjk zs~N^t?4jZ|>J+LYciL3kbyt5=;F^n1UI2~>nc)f?&$;8cHw^315uGe^F>k z6X(>Oc>df9p{emp8syEEVSl`SXJ7l4e~+KxuM6Y7H77r953L(AKAc&;H42G;%)8!x z^I`aMe|UI$`uf#H4ubb{b-y6nZw?%9^qGGnXi9%{KL=MHZ?pZzbBpbUBX2=2$;2nY z?8=@)zs*Lo-EB6T#kS{w4BsA;B8;f#BRjCJ9kTB@w0!`rCX-^blYfh=%cYB-x8J}A z!z?yAv+mB0-ksPEffbQ=#GQt-?KfsCHO2Gmf00pWT=?FC!5oY~+V0r94RB|+4fgx# z5p2q~ap+hh^XAX1CYb-7$a%44SF`m}Y){MVb)p zV6XZPnqOoG&E3`tJJ@d(n5F&>n(gX)_OjD!bUK|uyW1Ny`(4xQ!KSs$#%{OW?3%q! z8`jh5w#zr|^(%Uk<4Y^kAotgy=T7YDndMqj;txp}f`7;n#E{XHKP<*pNZ#53tQG`^ z%%ATGhykfNCD$~_FB6-L5AIK>EVTXR*%<&J#{ZFcUm^O=PiPB_t^L0c%{Y3G`pF)a2X!hW7`LMhFMxp`Lc$v zL9lc5>?s>wks!SA;Br45vGoh*K)Zw`SEQ0K1oDAn$ zi(ux32g}I>P+DGR|4ugca&3^biMPnNc>St)h+ao{Ld*)T zv=F~Pu)@)du|4VCM;kI6o;aSRqJMDS_{z7ZOjS0w+@+Y8rka+q-Bi;HN^L^Enre0I z&@;RJ#&YjVnjS5Err3F7N;Xi?I6;F2GHeOZThAHOGhW&|p#o)Tvq%Wre&gE#%%Y_I zJ9srX>TdV_(F_i=4jpiz{oEyRdCLzzZw)PBx*uo6-S_9EU602@xD)NWD}Rr%A7$&0 zz8#{9lZqaN$bD5jy00VtNPObLbt@HSP?F3vrMC@#fhmPn0odtzUdU2SgFkWkA%WlGVe2H@iY_y)!hbC&Ne0_#y}#LMNK~h6Oc*SyHY-kTz5t2HEt%79UNuvg z*RJNghMoh$&Ea9L!>l+RUkZ()iZ0VKx*N=rmeEa@V_=1LC-xl~qc~gM^whOO+j8_8 zpILVxww~E87nNTY6<68T{DoH3(4`ecqpKO3Mu6j%&j9ElpwGG+@_&!R0H+aM=VtQ< zvo-hu=2bGMY!`(qqyPfP+P4-SlY;qzIw}Ar*}o^ZAv|`0B}A{tGGuA)0mHu5W~G)I zgDGbbBa^%=YUncWZzO+q_3W3-gA2o+J6ig{f5P}(p66?#&E_yy#iyfmR?uurI!cmb z4cWUxv+>`pk#}udE`K~kX5JW83ck)s9L}r-xd8G8A(F&UiLFn0Fo^FR`d$#ka3GVS zP0NWmxEA!jGxgxwoxxT9-gB+7wLp4MvKePe;C*k8P|Xw}^~zrc;U$^cnR`-#txH&N z$WXQY<^*22DiCJEx&buVIMI8dTBkTkD$@X7!%Mi8uYAiraDP6RlSoR(=mv1GZIn1a zxTEN=j83os&Ii0YV5E;y2C8?B1>hO2N=2=AC9SIU*x_9*M^# zjE%}Gr|x12Ncc6}F_uMze&$+n@umQDv!ioIztFl}00!FgKUEO#?72;~rBu0?*S!^* z1CvWPF5~5B3xCNiyM$m6BD;!G3cDc*qO_W$^x}|^gW2;6199a%m4}p#sS*}M-6`;m zG$a)b5ry!ZlAj>Z`7&fUQ?mfnP3SElJ*%>AkA`QOE#Z_d;9SMMm){(}*a5tF?cWJt zUw@GWXAVKTOA;=9H&)TG&NZ$w#9yKuyYrSx7D^2}aewQuq&1sF(*C}reP){&hyz$H zflBs^fsBK>*1XOajCa9%1=unBj;e3VLAjRqS0xt{?+6zL)DvV=654BZ`Mjyg=Mf8Y zuJILd`}_-tixgx0CVm7R5_s5VpFo2`SNH^kc3Io-f#*5Ia)bTgzz!!iamIjtY^DW$ z0iQ3)GJoL6-S?-^(Q5GV8=*osC<4Wgax(Y)`~8qU%a)6Zy-+RSO1<#?B+*kG@03IM zT%n8i9=z)o;gNlFaF3IMtqz$|sX`|pLJomBQgbl83E=(|1Lut7@z)s>RICm!zy%=F=2q_aBpf>4g5JiJhc^tr8OsqA5iM6M zapQ35W>Xs(J-=m5kKLK&j>!1H8ht*2!!0n_6p6zc&7j@Sj(2S(O0Dw6Fn|h^8-_mh zoqtSIxq67>y9ID5Mo-aVbk0SZ&6W-lwZvB;K3IH4H%pL!KV6kS#DRs47WbucHEoqr z%=DBh47OD&jr zj+0uSS_Od87~nl18loE>W!<*SA&hp8ZW1=BvXg7SA<40dLL#PlBF z_)L|{lU>{8??!t9T-t*5*sii6Rr~?_V?G6^?u__$XiR)>Zom#qiBcdWF3}B4ALx=;;{!7B zd}d^$ULsZWh0HWJ0Vc32JkF#tcz;IcNTF{n-_06I1$z>r{oJ;kTHyEs{%D7@=a z;KHBN-PJ`0zX8ekDmZnA{zx11NWo|)IvSp7q9cO9=Oz;0@Lm^@5oBa~(1hb2TLr+f z{ifzGWHv+iGonpxMrBX&xqo=<1|Wzh_K!+j>dXp#`wpkSbgX#rvT1Xn731J0j(4k1 z0b#p!+!2V0r<&A$1NZRwWaJ)Nj)TredW6IQPTj>Rh^1q~Z$Apmp6vUMvmboaI_apV zx2}nEW(RZXC8&q65p$J7aU!~FHOMIim%5~@0itWOHYY<=!NUb^WJddXROnNt=^;tr z8=}xb=?;Bx?SC(+4}U*C&Gm@zU>UHNPG&o_mU-!URCMzE@RIy{Y5OGZOiwBf&`4cN z_{lnoou2DSBN-riHv%PxsMvc?-9xE!9#sX=%OqGbi9qL~&2-Hli!p8E8K07>6NFV& z?cjs^*@Zg=C6d{2sr|mlj?0a#_>PSSuH4D+etzva_)GmhsDDG#dk@bbYJvkD!6h>K zPmAWI z>V=aJ?lNGPDt}Dx_y+wZu>(ye{J|x63(CAvZ4b0WH53&(;5Q|`Yv?3K$eT}HOzsfk zhE?e6y+<#T$XvvYD^#?mUsdQT0RrxeH}QKbT>6#+LKk4D5`t1QN_rj6tg&}n4OJip zQO|L}weMMDlxi#QS2BZrsvBThqS(f!-4hq*hZHN79)HCd_H#JY3OP%)9|}+(-Y-GQA+h z1K)j7P>2xV?Z+c>V~@D8soi>cZHLCs#3jC3b$CTh6WS*w-CXOeqyaQeOS-wvdC9le zIWcJ%tuvDb&^tA02+ecDKkFSO z;E8!=-J$7sXzP+}7Vd*KT=v`!^_Rt;GFr^x_}>ghxU1UNb4T-f&PfT1OPU2@W!tlv z!X}?iKzci$V2X@$KXO2@95@T^wA_>->NFNpN*^0cU4u$G$01HGGz$%;M=aVz$C)TzQcC9* zP{O0Vmz%1V3)JuA9{2W~QQYA&0B$VzGk?%NdtKddwiEOTP(`z0gX7Vx)L{bq34P~K zqaD4c(3qgnHd11hVI~U&haeyskg{>;DP{LkF!^Lhi3BX?(>4B50u6%G>3l(RlOSV; z$Ebvo)EkJ;>g9sFZN__adG!%?D80Kq&D~{?g^Aa7A%+K6zAr=MYI^F9oaLCjg@1m0 zoX4rl(h5}YR;7|CGnI`9W>c#RyV}SMdg!bOKUod_cwT1$AIbHNO>S#I;*nu_H-g&e z!#)7mfkogss@xBz4nU%eq_HYq>wcHRc8|Qb_^SNvUIEZT^~}d-thF@#pye$ zv#aNJJ-iP>!f%Nan&@TfhmFutKY!NV9kQSb;6|!;KV!`Nn4G)LeJOW6vp%Dz^xSgC zm@wiq`Q(SUC7rX~fVMnEO^EI;#_>Rw-_yb%S{aO4|YF=KgjXaYmNyLi-az`k&(RSbv%zAdGS} zzB{D;cRCGa8Gl4=nUzWh12yh`28FVSJ`ASEg0pJ7ETkDjC`TB7U^tjYmKc@`LMq6< zAXSfzFlwx}2H4b1JIR{Bf?+}QWv>CXwpDz4mV2IBz@28AjSKv>+*K>j$jaXki2m5Q zi;zQ3fG;3_NyS1fk7dAB?7^z3 z?s#Wm(?bpVI9LX6Z8&uPXm)=ZoqxJ7@z-ZoAtzj+w}PNm4MLOJghEv!Vbo>+t~kq?-LWb7~l688Wv8E**E4}V_XRBI3hJa{J+ zcwshMLY-*M6fZ5&+obp~?rZ0t0jXoL5ImoRlhl1ewfe&T#Lp<|e#tg1ot{%J3oARq z#GMNoE?*U#=01p1Pu7CI@SOW0M%|)NMXJwXc!Ks~*vA?(V7jl9ky`^cqKEpUA5ncZ zPzg}~<QYJaBM;M8xhHZ+SK1frfZOMOLfPP)`{Wf=OaL9-~nU#u0o!IQaK z4<{Idw_+C~=?hZ3gMELxS|10_=hO2QkvU(iydh`S$d_t&BwbvRf1}rkB8pl97{$7s zjxkB-#3rjw9@V%j@8*ZlmMVCZJ-}1Pzw$m4o(FifSsc&rR)0Sn(1{Wq5;X_?DUuv$ z)>X>5K!mfM=*EyqMj6;dwu*s7FSQH|Z#xX{9eGx(421k<))_B<9cwKNr2dq+e=0X9 zWuVTiyVG%02&OIaV9PX*@>StqTK%U1cuW+{H+1&VLhna3x7uQU3r>jM@gB6xG4qZSc6+2nw;?}P0(?`+I_>4+4Z8OTI})0!pI>0YwSW{lq{ zRwuTx(qEKzR&IjNnp$=9)&6{W6~nJpV_=FBH_;yDrYi1S1UusSsgyd^AO2L+cs6#f zh|ezS>VL8>cX)tf%Bcl|c`85up%csyLfv6lBIb%c9A93s(?QjwmJ5ig+C_w27D@>n zo>4PEtv*oti-RMoPK3TXFxogWM`9KYkB7Tq><`T=i1~i13iB5i^lv60)#^gqZYzUd z`oy{Co{TkKc%0l=W<^Pgt1{sIYZ^#Sqh;$3kAF2NmfkX`(MLoh=w~&me&8<2+{022 z0SS>ls-BZOJHTkMNPSy*1K9AKyQwFj^BCk7?~(h?zQzgxf&D3*IG-queG2EdjkzUC zlp^Q@I$#Owg}QD5z=cm!f&pAyPqGve_KxKRv%(pV?}VG`{rQz~`ri03Jl32l$mhW2 zFn^~D$hwDv-B*XZP2>6g`{C(}^4Dy}st^}7)sd4>$j+%-;wbkRCbVq}Nt4tNXa zp1VN7X`oIEhTLU0(?tv)Jxp57j>x$@k8pZePL_`ImRKx-aH*UnWaX6<3|R)Q_v*^} zxke0DXTBgS!z~Q3+_GE&6dRu}LK?zW5r43dxVsX(SbC_kJ2EjQ&ZBKu!bIBn^#??DoijZ*jIpzTsnp{{jxGK zWp_r~G_)a|k>}bf2N^E&g6$hDw7--0D zaeNbIT54SoT5`P}1q-Bko$Wz>5r0^IwZUMm@oA~T<0B!r(&d};EzlY7LqN_f97~S{ zv*JHh+9HFuNBdQWKsiF;9#k??RFAOP6z9Jej_89F&0I}%LC(k>^DZQJ;ir)|pKHPa zMfekbMx`*}pig!VWlyI`yw`5WLVULC~m^^Gc+;Kit1)>4}G#n|}&r2FAmW zCBa8>MVIhhr5ifZDk(@Y8#^PIm%p?d_;IAFM-kU4-G1}-=$(P<@r@B>iN+}H9tnSO zCm)qd5i?80J?S_PL1X5JN$FRiWz&mnFzPvP<1ARl*DLEfd&e-_UHE6vfsg%O*T^Q@&o3b} z{ir;2zS!7n!6QRjEbaIX?xT?%!buP5#0q?q4x{exHG7ltbP>ftF02Ld&wV>_@^s)G z9*nGoxa=x6j}XPK3|Wyu+LWhk4jh=2xH>p(_5q~C05iyrW|{H_iGQBJM%6JkJp)<8 zM!D5^9SkM@|o z{l!IgM?OJu#=-K}*N%nZ6!GSZw)Qo*`bf4LUGb@wwGk=TXGtrO*~eT zNm@A^)6MZVJV;8`6~C77h70hbNFl6<9g46dHKz=7$2XR5$ek-Cr>E-1Wq1hV#)^UY3tTkzFR-nJib*L3jOjMno6S5bJm8aag$nvu zXT#L># z3Hwgm>pQ?0m#n0_kR<3WRt`v57ENgh6T$L|(pIUmlXQYtMM14>XOGByc_-S|xX4CF zLQIV0qFP>s1YgNrxeS15vZUq0Qr2Zt{F$0;iXF4>C3Ht0+4zj$^v-LKzr3{r^8Eia zeptScpnnu8RY_T_g^IRl3o&(JdS}DJWEhKFA+m?3Y>lyX==ahcW8Kf~Hz$sl(^sTu zoMwo}8^xj@Y*Py5Wh?Ckrj2Fw zcmigyQnW>6#Hx^DY3CF__qn1zo@T`zOShr=J%9EXmM=BS{1qs{oPr1UM+6uTH0Mbi z*%*qIQ!tuD285{-LdMs$8jD2pn3X4JS?I!*Uq+HVxo;hsd?K?iPG-z4^L&!2+rh=0 zBlyCbsyGUk432#Mw%^Q%BavV-z2~;Hl)x}~7u^R@zwF*_iHB8QjEx^8*CIS~9cvK~ zUVjkWag1@i$7%?m1u41Hsp7SCbS1wS9{fI>pbdU)w<6Y@+JH-O_%gcLL^Klp#$Mn7 zRi{a25H*FJUplA>Wb&^{3cjFb<|Q@QRU_-+@|x-PM3bg!N$8rT;sW^tBy{{6AFPsz zpg&5$84 zd;AIiQA5#sDP&>cp~54sI-XY_&j2B0gs{kY(N!r|jIEfRP7Kb=mDYg9Nv4e1wSV9f zEk`ZzSldux{GmPn#U?bbHBCvWQZaB&i>%GJk)o8v38ZlQ3%H_4fSEwy=)GUgFRei^efbO(KZEN)ir`KIIwQLaVw+K9na zK%7ne?0d@v8Ka02bpvP-btK`a9Df5aZOomK=*z0T=!Z)ogGWX_oLPuD%!qEWT0{!b z0VevlziphrvJcE%^8AlZ+>LD+Hb2OQzjP#b(pM(>Y>Gl4azjPKj0lGRA=ApT`!I$~ zp@NIdzqXo#-i|TY-7(s|fw^PscDq7r>-mBd{GH+-|KWM_6Kh0g+3vK(3V&=l&=Q^#(Zv{JCpV_;D4ok(#|)gBtD$cj969uGfIj3N2renXz9B4?i%qY z*0zPzOMBow0|0TyTU!YPwrJ(R5CW$@a){+eb7HfX`eFKwlJf?Jv=I7{?d z^KtettMfmK8Ne96eSe!>K`-wltva1HqJVEwLjUT*BLhEj&*1bxt`;}S`RIRB1%MRJh5S$_5 z^;n*nBqb>2pCP&XRUjylv0WMqFBK}-$hCwD{3+rBo_|(1BB6rczz0`sK9}CL7YfWt zB2;h}!JOD!9&!_T?o|eq3O83XJ1{Ul23fr^VmZTaXI2<^=%|<$LIC2qru6bc!jXLv zE`68LV!f+s#cQhe6}2V5pH@FP-N!mPlt%IUTE~V$8#>_f<6@7N*NQ_@32nW{LfZ#_ zJUJ0(ZhtSw8Uh;;haO!>ch67`V#cc`E06k3imuq1THDm0V#gv*2F8?&Bwyp&%Sj7 z?=$9VUkh`*2Scw55%zvMO_e=LWTJ*QyuL z76k^Eq3zjUosi0EIGevtB_fSTr<`9-Y9bQ7GG8GEWXW`zdUH)hYb&O#ra0^aXYz}% z{C})!zjb=1yD00r(h)4tK?@NTVSFzLmt))8Lvi=O@{{-C8F82E*yxUWqpfR%vTT?5 zvJJ0yNH8>APfISusaWXN!R(1#3%$~U7SYx;cuVc&NtW1C?o2Y=1sW`rov*CrkGoNv zC&fzonkzXT+cLINSP0wO*esk~63QqgOMh8eNuiGuh4rO;CU8zlD7I_@f(?-+dCg2l zczV#2=V4C|C4%hH5kD0b>l2HL(ltI56_q{M<34H~tBzQ-d-PS7ysuYWq*x+)^hIjE zgjZaw`i^+)#g;!jS6r@GFnaXmmc92@T%}mE{^+aJd7tU8bk#ep$KBc zPna`K;WFA6wwI>`h#c4EOnOVX*zNU1DpQdgT?>8Z(20)zPohQ0yU`8AiRN;u3Ss`c zoEx!xl__`PNOhC?Cbd$bW0YW}yMO2}h#9s__@^VJ4AD}nECSP-X!Kcvy`eus_hGt= z|K%;iy^{7vK^V0k{Fm(to3oTF`Qs+=KP|3I!_)J~nlCPF_a@qxW~q-S`Xg8H^EA6{ zBv1Ub+t={(d|AXn+@_F4=+|ar&>8S7US@01>QLZ@j* z#8jt}XL!~(Q9+JXG_0x%CiKMFW7Y4qE6*W5Zh#Jl%7U8YrLbbE_*Po=uA)B6K+iyL za8q?UU-G6h#W$5K=L7FyZiVrI7pbR2rfDe}{$6*3HW zIlmTXu++VNvP%u@>D-DJD}Q>P%ND!K7i%`PSKBHfdz#9iq|rm5M9B8Z*tiJDa_kwW z?hUXK5@V@E0#V%qGK89V1GINhVnLL)%0Oe3iq3WVSh6Y(JTEJp2Vnkc2%0sPMhnn1 zw-{5^pqYO$Z$%@FK9#IY8T_2EXGskYEPsu+aiU7tu6Os* zmSQfN-Liy}nk|&)kRJLNBh&A<#blw$PqVAk;i(yja=w}!pcpvTYl(@k8b|K$?a5S0 zvUh;lGy#+N!Q7RhP@g?#+E(C46i&>Oba0Sm)qn+wzmftC?H)%%S9mK+&|qqyLB+ct z4PPwz7$3->e;FCF>3_8}D2MTHQ_8=k81AFw(}sWA^zGS~JUYcVZfYPo&Y>nvhh7C+ zsgxcO%Hr%Cd9=wC)Cr%qrl}jlNcv8^(fM6u^z^8SU!tvQn_x1LB-#nHS8WqyTrJf& zm+NHmDVQu}RRnTNij$bMw3Zd`#t~UK-aR_VmlYRCU*y!c6@Rnkv8owmV9-RW!%HvX zJw2|fvz~wbyg9-rw0!7Svau_Xb5X5gBwyv}SsKSBdZ%M3W~+lY2ohJTTjdHdo6;+< z%HpB~V3B;9(MiCPs@w#0J?ustRKF56PVX97yjbrfoLNs}W=sJ^X+WWW${~)G+6G|^ z)hHUMVp^++aevD6R&3?6^;KGUzskZ}UEP%z*C8k6Ro0=!BMOU_6?jWa(mb)#ubLZ| zq7GazqDe!bNzl}NguULaxD0JN&+K;V;a4Iw38+@mthExe&Pqi3WA?qKLP5!{b=CSU z)am!zc;mo_fwq>VmDp3QrB7z>!ZvEICLs0&ug}ZvLU6`7RSa1zJ%a4Rg@d&ZAM3BINd! zd*Z-jM-GsED#Q;V#q3kr)R^0N7EjzKe?tF2)b7C9J@m+A66}mon?paHjCQVq9S;|D zM#i?~GJoKm`{vG4P(rBIbED!jL)-8paWGV8!4Mc`BD@)F?J9dgy4+OGOgQNV@qd>z0|HEn)ghIQo3zN}O?b{@7L%WM zvhlDlSUlo=Gd1*mlZRF>)88)fTZ}+Y09Y58DLx&FyA=PFin~o_qa=&6{3z)o`H=Zh zL@tm5=cMYvOb?JBMdk-4t5$ATEi*1Tbyah$q>ks>bFCz2uuMfRw)5ig=0VXD8S~0? zBY!ga#@JPZO5>5yQ+dyrh2bLDd-ci=v0VD>7PFi*M&A6@j5v!|Q3|f690?^JATAmhiG?fzAvf<`!i@ zz-8z&!5cgHgl$Ag10udxY?EYLpd8MgM1RAjgaqD}(?n)a;kxvaZR}|M8O=}k?+83v zY5XBhxRLBngU8`ZFs8zVgpaHnH@d6UgD&7E*G>yXDS|1%QJPCWHezZbZe5s3goPCI zO0lFxx~KS5t{&vsd9={jSOTndNzn|-RIyGwu}4_=!c^CXxRX*@L>%(I3_%t_j}CWqZ#;kdyGYV5MOCS@LbZf0l`t$e zH9Y`^uj&yL68Sw<*P$*^~8`h5nRxy)WSCvI=(g>SI;Rmnvv0Gk+Q2C&&v0C zIf9SK#CF+j4dOl43+HL*>ma>;PJgGAv|vfYo)B@m?up%8(@YYhlQsUQ4 z{7i`l{$uc`Ebm*U*{-k|&nH;neIy<@lZh?WVM?NvKY)~T&Gd{yAr%a(h`*V>ll)aF z;>c`xGUe4}$?l`2v$`*3O=3<+-IwOSj}Dz5ZM+^~hG7VnmkKp}5Xob1lh5R#IrIw_G@DNxh0{ zi9}Y>Z`7ExI+M~G=3J&+s4?euU5-+ARDLk7W(0)mM2TToJ~8MUiDeG8-H}hM0H2l% z@0R#z)cE~>6+ZQ9wiO!I%iVVEnOw-zn1Q##)>78l^eEVsV<|&igmLuec2W3 zDi>-XK%KOS$xYHJKTHZORlX3x3e<8@YA{qf9C&w%-d9vT=xl*x5xeWkomJ~8R)6As zT?u2QiA&!qdJ`|nVxk&3&LblBt}7e8rkB7YWf`gKp68ulI&utrO@F)R_4DQek$avX zNKxqC+KIv{+UTCwZVJK>3hsG={2c4_wnKk62fhyJBx8TOIJbNPu`{AyP$ceO)1$F- zZ~2SX$Ai<&cCqX0mWs>FLF8hWp^=q6?08QBbCL$#2d~CJ^22A_Af7T-+R7+ zb!0J0+cL&vLEJG)oqzC)9nvW#rHdL{D7N}EgSrcoGhqDC`b=0&BkFWR+#B2XT-+Sv z1|xdWNQ|R?x;#HPzxwok|LnN2wUyAq-qzMj%#nY?qO6Uvjpat+)1DD5$jF}DqgL|X zTN<|(^a-orYh`271;Lj%HqUD>T6}tujjh@~gwKqR2aEw^n}2ORGky~OXKO3;@99v# z3TWPl&&F@YPpQf?v{7~hrY)V0f)}YmIfA3b`eEOqlTJjTNsDx)nz-qYTOg8+W>Hat z{883jZfe~Dt6C$}qDN<)xx{geGMknakjTj-y}i(weH(9E)CVj$^q1sEAvpdH(AbL{ zd}28PhxdSt{C`_JAc%7AyTU8W~k{aY5>;FP$PHpTx$tDk*j8I;}njT5`W+n?aP3r(w9<5&KzEKoP;b9 zf5hyMqMcWFBT}>%5hRGhkjQ_Jtt0Q(NqzkgI`V!=n(HSWxxS9PUt%HLY#q5YhP$}V z^(5e4k)^12M>6x3bT?Iwm0HDeuna?dwaMS-YM*v*I(4EtQtahvU~(7-i;aM&u73KL zI9jB|(tjP}Kb7RrShh{M4J6V_x?^_fzePhm*>^`Iz>+9j7TL*%o1}aTW)$L6Km+Fl zJx*+Q97{t85Q{20(5WF4Cj}-4)4wp86PI3oeHQEuXWs2$(#c+g(cg>{%f_-ka1kwh z4^|gFoA~1lpGtd1Ec(#;TuDDKG9I(3AN2NBaDSXaN-&xvQmPwLDVpg(jJ(Sd%6^A> zpflSAPB1tAPW;ctm2drv<{Z8^s3%P(VQD9CL|;KQ)WQ6682Q|5vg}tHnxTF%A;4NS zLktm!hXf5V7WlCU(3O&0+4v#|NEo79CHrfF;RZ+Wp1%PWbVCCC9Uap$Uy-|oV~^~R zvwtfpGUB%|57%;r=?;AY{hzz(?>1cPB+-6X);g6^VN~27ik%VLYle8WBt%%G7AlbkO4rjkY7WvX?N2 z#uhc|&VdOU*7(K(b~q)*tsTw`Ah-qYGuKmLn&za8Yjr*|y2zRG2@)l|;r~=OQ441Im2Od*wGO75tjFlPi3rjUFtbZ`H zMu6lU<3r;|<2@{9$2h@HR%khJY~I1=GdLdBj`1^m99pOowDFG}pb!`*a2-gD?A`Re1zWf(%KU& z0j=PtZU_%odx}~;T16tD8^QwV1ApWB>E-$G1?GJ;o5tz!@$sw6;om6`oOzrJObl;q zjzpLn?5yX&B3uvtSu7f6uQzyU_WB)+bAQ=t8Rw(0LHpYpd-k4THXEkd+X$32MHGrd0K zy%hlxb=WiNxfg69$31n&a5bX4Lm(blM^%SrXorS?NyB z!IjIa>QUk;MbI1{Mj9b;KY!8Wlh1!M%tDZ&6npELVbraWLbBEjpYc?CMZ|mbhXUq@ z_7s*84G|OEMRpt0(RPfOb=R34wv`EEG!n{AuTeM&!I$x>li9_s>P@dWNU|aLi(tYO z>q4u>nxg21NqYbu}V}FPE`^xbTYQ`cV z=48A-TIJyk_kVOm0Rrg=ZBcKoMrYah(<)I0Nr!+0_6pagtttw`!J~x>2CE*4l}~~s z*HRU1JzD5r^6;!50!V6Os@aevudRfv>S253}A|5m-~|hGy0)iN z_#p*L{aVm@WZ`?)G_+|ea@mNGV~i}<@CkJT32?D65Oo5vLv`R$Y07Ld61g>Ig}@23 zsR(L&)Y`t1Ly*zKBpEkv)c;&Z`lK3e8Z1%Fq50KWVf=2Ej+-Nskj6rW}yHI4Du zg+Z%L>2xAO8zb9SBRqSr`~}bAxCTT%TAIWX?yG~yL)yh!5DAygrxXkG5vO}z4Xm#D zX_&9Ye&xemlqsN=S2Gku2yyLoxfs!HV_9VUw5tOvqCqki4#rWi~lvax`t9L$(4!kLH$`qYu z3>(6;j7#om*GnuZl(&X@i6sjS(YnT$Dt|H!%9gszmkMV}cdaFr4pmj$9~2>Cu217) zE&{R~d#5zup2T<(x+Lh`12UAFcmuR|F%|=n+A0H$kt#aX=|jotp8vuU2Eb`(v`a92 zjA5H6BR5r1y>SIxCjeodG{Wdp$;zcIA&|7(sMN0?%2p)h68e9Nr@8o`0@< zVuky`e(25Z(FYeTfMw|pYTRBK_~A)R9NTZs_OIUU9~jY_w2bpA?mpU5%tNzVmhe#% zh^WJ&5P>w>{k|ZEF$b;UrrA~MaMTP$IakdNaC(F>v>$<3{JG`BwQcrHsbQgnP0g(^ zIevS4GA9Pn(Q3sN$Ez0{*Qofr#(#q26gVI+Mg*%0_mWM~wOPhFv{YMWp(ktEs)vsY~sG|GZ!m4BzfK%1uDm!|uaD z^$W3Bp}Np^jVxYVnOr!to`1&7Sc!5<1Bxo;ImFrQ%$ms5b+`$uZ5}aBS%q`9a@qPS zEnI`4CJS$=>a&-uLr%)8tV4@O6c$}fxKU{P4nsr(rj5|qxD<8Zf)Py`0!@OZ?j!8= zZpCG^YVCIW;aAevxM~F(QgtP*IxBhoN}}n~RVd`y^&-u#h4v|tJb&5hvOF{`bQ>CI zYgxJvu0WAst#J31yt3KuHWm9?*i+eVig!|Xq9qEEhzu)CRC<6`o2VozG&fPzNfBaH zw0_YfU?VEH0~OwMcCJvxUqwocJu!i5Gi;y63dN(e~) zy|iyE2Vp&yZRqfCe={c0vv*`U4o#B0x90_Wd)V{dp6lH{7rH*gTSlA-?2$d8dB1hy zBK7?-;uS_&FN&MGK1VEizAuS2j(xA%dDV;PcnhAzQe`>KIe*maN|fbACST-o8+*JF zagj4sN^DdraLP1xO9C*W6#JaMx zQ3^-gt;`{=$;`UJ{A8R-c=I{t%}SDq8-Bb+4P)!z-WZdKwRA$m4viUyV#&ri(0;N( z>AtiESG!2BJ46CzOjX_u+&>C%H)qfxv-3gcs<@M+M(4(>g$c^6i2|Fj*S*J|_~bWv2-?3EgAGS3fHKodldoxYT%k?k{2~ zSb#-HZ|OWHr-}hQ2aC2U>VMbiR!zBnpNP&RFY)+Hcv99Y!w9A6hUFijV#qX)aI!~M zHdxYDhC(4BW!0$jbkXb*XFbP6K;+P6y&kXy>@P}=cV z*cc4ym%GB6*-)AW4Z0DYeWzlZSXo!QocY6Rt_;0y(C2gNs2*!t>a%3h^ZCYhcw~2^ z<$VyW7nNq-O&bn=VC3YXP?hKd`!cb-UyTTa z1~)Kz3^4?)gi&|jr`ykg^0(k*kv}&+1OGM$h7=0VQC@X-@}V^Z?1qjdcL~DH&LW2X zZ4SX>rdNx~Lii}8_lTH(E93ED0;9OEKHUilL^RsPdpzkO+Am#M1mLD1ixu#W$*TH4 z;xMaMeear6@GgR{Z;qwOaqhi=xJ3U{FqGI4e8!oiS8lTZ3F2@yL0*|GMEgPZP6&%mh?Q$w#m2+N_+nOtQ z5z7cC7x=vIEKptT74Zs??^wT0gzdqe2?&g4AMs7>kVSB5Q$Wdlj86;$r?gcsRXZY( zugr9tv^?#&bO&T?Pl_$g4Hy*6{A31=5m!?ZfA$~Ga6jRFT={pNxkpedDc)+NFF^|o zm#`hwi(EM5BqPl56Q(Bfd4tE2<5rJ~7VaDeCH3{{HMJG(JbCZ7FHm=Bng4=SILN4k z`yBm|_r=VDKxrMQ(4Za#q-(dzlh%aDOU2pG8xWS2UhdT@(ZB-L$ovU+FhPu%2~_v` z3_QKlixThu=i`BgdyMW>t{IeiHq^S$fx|ZC5Bc%XefbECM2N2xHhs$%Qs$iu;_1!U z_`MI?O&|L&{3(D8v-D@6Mou`?gm|}!tCyY(RBbXDy&Wb0AfPP_NT2Z;ixrS)5xKIi zVQ_jg8{=J?FrI~+8xwjr(!hc^eEDk_j1xeLN&#KEZ<3ygrtJt#p?T9j5_g7$3sJuAfhQ` z#86t7+C)m@k5&*BP=#kk@pXDu76YoT+9vbSoYBZ>*;KJx>}~K* ztEHz>I^L;dH`|d-Wk{74(9RWE=uWPv`Nr|t)rn%RF7Xm{b#^9K%w{Z?sPj%`?4u1g z_;m2u$++RhI$)vJIcg}2&W}G7$K4q3Idv*U+Su1M`-@|x{D?hc6kg*==(H$CdIuZX zgu=u9lMQt2RGWOjqWO7ZMCBO~`ZB}Xc_Do@f{E4%IdRT-ZSJw@?C5Ljna#x{#OGYx zoN8mMT*k%3t~!>Mq&Xr&<)y+B)|*buFbAkxmoD9WmRc_~wyW(?vFqld+W@$#(^Z?0 zqjf<}W&A)JtjtjBjuMu210kbyyzHt{)5@KkY5=Y=1hSp7JlrKTx)ue`OGv&zu@?!d zEg$_zy{~L6HyMhV8ts!+8-kI0YB*J0O3!23qFMSSqUX+g_iO!e@ae6^ElD2py*^k0E!N(y`*x5koE+KdI39B!Sqxe&@szpvr2hdt9 zy9JE?3kdt68NSha>>^HE(BcKCwlGlt#3YgJb!GXQ?9dNkN44DX(B|) z#zcJ(lAr&sh6pJ?rt)usT76i~i zSb~!bKsEslwV}6F|4X~a&>71fWEJLjVk+NblP+Fb+Fg`*!{rPL)ROeB{z{$uJG~hA z2j1UhW_c0L2`kYW4pW@o96SCmr+yE4U~lht?|;;*eA$(FMTU|e;>`{Urj*&%3nkUZT_Mu)njVr#xI)OEW{!vakkvRw z;_Wy;o^5fbsDP1bv4hYEySTM_TZPLPg!bIW zH5Hbj2aEsmc#=j(>8VJz4TF$}E+=ZdsJdxP#5&)g(w|A<)X^GUm}HHBFJRuBSQstj8^htlD>0Owx>oSh3%Q6AYLG?9nOuii~w&Q=-=h=&qwcs zQWL;o`?Q=|P*AW1O&UvR+w#s76#^hR&RN2Zez$bNeEk7V`NI}E`Y^X5@39Lh*0Cs! zz$hZB7Z_+HQvG_>-`ONdAZ57LlA~(DTwkRrcc5|AGon&mB_9nHtfDZ6|KCPXtEW zs$2no%U@$x;#do?P5fg)=eVF-#7(+bmEmR8` zG!pe4O`9;^H1aon+~AUoihqq&9Vhc)3zD*20on0L?>`ccpqa2cW?$p~!>M3U)V_l1 zjqqtIleri1nqnUSWN}0vH&BHtRTC}4zK%U@Dbgupj)AyA&lrjuwYfuK7tw4>?wOa8 z&^#Q*x9_HKc(3ZxAkPn)HC&k<%^_0MUZ~MC>Jr^5@y4EySwN48w%;e}_@x3D!8y8kFbZCS{S<4pp$d^i4gAorl_#tM`7v-epu?Dkh zq;S<$#zsChHJL|aHTEW%>wH*!xGf;u?oVXGCV_~u{nNF)pwyY8VlBKy*gApb1R?)X6WL=de1Slu2$_{-d<*4&`j z9wOO2>_%B+dA>nx3`fVfMPuFLiC-fZXaP(V&;)! zo}^bo36mshM7d=*m$dc9m|>D4X_AgL0yvbR3zJRACt$io&cwq!3Wj|-r~66IbmLW) z6{#^lodOZ4t+X_G1RZTHV(el(o;moN(vEi2G3rk^7%biVWTZYnz{dR7j1GcQ8-Ray zQ@GjRnE*qk(}r|Dp0+&5!)vz@N&u+6+D>nsfT&;@=zOV8CF_y~b+%MpZD zYHh;WJo=Gebtg^VyMSfKHHD^i4!p81L4Yk_DH*U8s`<%TYT$iwjHlOKf!OxvpD!cU z`XnAhOBOZ!Wdh{WNC1Gfw@<^K18BIynu~1Rd(reqsge>lMO6IfhIK?LE~XL33|)Da zRL8?L%i2T5B7bK`2EJB)4a9Hrc%td4Xm%v3sGA)XPa|+QQJAjcia3X=$C{-A>f6?6A8>p z!Lg+kwubkF#)WG&cti9_(JK|BLy?NG9BNr*?t$8|W=ydKy-nNY{0-qu@r8MxvZ_u4 zV>MF?2Xs$4RC}tesXiGuyo#7$^7bN{Deo-Fl}Nx-4S&;gf2bSX@7mqQZa1;VYp_-~ zx`V5Wb5{?oMk2ZL#e~8o2H>=BH^tF-*^2d;)2!v3TQiuC*&)d^G5q6S*_`hsjl&QV zY-nD1EfAaL-(-{$>v|?~b0CqT5m?Oc)7pmS0kTvTbo@K?kYvDED&tWyydX0*IT6#x z>`xxfNuRY1mdB`^&TT9Z*T@~f9wF)V9#--y)S*`^;92-)@y*);i^JVY{>2hL@@0K<4eK&JcfUOQqGdqF)NK_ zF%do!_)BzBpM@O}0f&cT$9cCb*bf+!(~@4@F{QkwjyoeIZ-S%P469wDqsTn)rq(*( zAYNZ?4h95wdDiYz%o}GE$bbdoES`?&--@n-*@063o~Ww}8P>;2z=d>M5=J6_Q9yiJ z#P7PIL>ynsHSjV`(0;tlRo6nev!zB#leP*Ig?xS*8#qG-AcAGWuQmyOM-_l>;;TJj z#nNK<5f5-S3dq)Wvp!jsPkN-2L{RHuG3Fw!qA~Wnfs{VVP+g_6#Tj_Vt2r-zJj`|~e)rU>_)o?_6}XQvHXlL2P`7J^t! zM%;PrTRJEO^k-lZ=ueJZ|B0{2Ec{C#E;J`s_Oy*jXvHrfcBMj81dnzcchdMks+*t| z609Q32Y>-xJwQ8Qt^UnZoF5_B;IY5Nn$OiXJp93&hO<&S`)e#|8pI;2JG*kOS_V=O z=h6}Wz{ook0LkPbBB5|BZQ626N?ctxNEbwep*7wGtbxZcrJwdt0ffR19g9{;(ba+o{`Vh>)#hsl}o#S_0}weCH0uLhY8Id?U3S5R&DikG6u z{t*sI{d`YcJpYG>w$=W%jNtV4M8+z#+T;~4gf+cul=(+a7lI)2Z-zYm-hV&K!Pnp- z(WeyNfZH&4!c~@Cc?bFF*Epy7sLdPJXX$p*x7T*jFU9l@`jsYK|2kjNf`xc-vST;@ zHl{jwqrGyrl8$4s9*`Tbb0V?lftys2Gzu@~jMLy-i%Z4LXB!AfB=kJvkEg9E!0E`V z?9&v*Q|}Eg84{dGpEdxo2ji+%T|RhOqMa$DfriKi->);>vLneA2IHvrBp+tF9QP#Y zXH!za$Ng*8l7EkQJFkV(mV0ZgaL!(-*FvVw42(7#rbxJ=M&$|>^30;&b;)%at63_GdoZMb`>p+C0es z+3lR)*3;)xjvfEtSe>a-K*9#B{A`GXWI+Cxu@!a&IpxJ$JTFoW*XtX6#{D~SW(qZ5 z`mEuvRKzS62Rx}m<2YT>>>AJOlVwRhy+=VU?kXHAV&#A z1o)Pt1Y2o#p1u5mQH1!AS-PP!Xjc(tyT_Y)8LYZ)l=f;|TtL7gh6(^VZ#WSdjH#c(26DLE>xlj(Yb>{Dg2%m|7%2BmpSFH^^|u)!}%ns zoEKg1O+sU9Rby-X!KGJp{+WQ-3@H{7OL)~AhS-xajV~*PAZ|F9KzJ2LY*!H-ARKxZ zjm$A{fy?pbyGBwb3v5b0s#sQ@GKA1=~(#hp4P`GYIAI{+=CYl6Q|y%dw>70nPx-FWt#MDeb)d%|KOP_O&0H0i*FZVe zZN!E?Ty*sKR$cUXf~7MS(g)&&KZPbJW3k^Ki*w{pp-qWAj7g_+zDXv)Uml7sVX5sz z)E6*jTKsbkS)R%iGC2PNh>Bu|sq1@2f$>6A6{mAY$A)p0g)e)|y#~HF88?4Lnw$GN+ z8{@+k@r!|12jbWdK*gq!7_6qPx9q-0F9n0Q&>#tfwJZLh3qcPfJ`W@Bf=!%4%8QBH=R{fdt)rbpT?R99? zTqpI?3AMq8l*X5MkjoyvW7ehf(jm`=mAXTgxZPw4f^Z`pj9$cC1!IvBs z$xIpC%%Xh`lULWM;<$9}lLzf%cCKzU#z@ThSJ)NiqxK7vj$jZ^lys2=^RIR`5Tv=G ztSXGK>jz#RU@vJ|Dol6f{jS$J8H$a~->Kz^62xZ9JBdIjXme}VhVxA*?ucF&C7+cG z^OYZsXz3=4IvjGcl)H-YYE17 zy)$v(Mc?=3cvyQ=>j;t_KMHug_}b-tta(^la|dP^^%6Q^b2+GcgEZ`)Sk^TtM%!M6 zqbXX(KE+{wZn$?xUU3`v)`117m%q%I;CUr7%t%!)BwP=JwLbN0a&RfSZKY`JS)E+I zWLL~xMOo}&cX8?VI?lq~PG=Y3$J%Xym~6#L{v)XEJigKw5`Tn%4>V3XndcaGmtQ!4 zCIrs;c1yn3rDn_?dM@yLEG~STUy2L6q?pegcM{0(&)$zPkv>`8rxY|*R_va#d-%|jjUpgezZ@np`JcK+Kn#Rw?tr^eP}3{94lj@}^bx~61Sa=jm;y!uMdn(nrXJwV;% zq0#j7)kO(Y%(;4gIBQ!U&AN?;G&Opy!&ghLHoIA@wsfDuc~0_W*R zYcDVN93l>pYehBcv!(?6jE3eDas2O>t@WSc-5Gk&G{cbp2T zX6$ju?ju`M09g}&?WVVlc%v@SYe3Ja13W%G6J~V2f71t zBii^>)K;ysgzCW(U0Pz?-GaWGnGdR{Q@o^d&m`q|($QA}lR#;jw_>>OeoC5xqpFcw z)AXe2$3~2*S;wvEsV&N8{oz>I4X%>T5Y|sb`K_SGZ%b9_DtundL{nd($)4x~Nqbg>QZ` zhu~^rW9nVKfjg!6EOmhw(85^vkC0_=*V%_nR?j<#ocn{_u}{=&~Qrw)O*+JCIrcgcAtiWJOA8L7Y=8l`ewm8w(1<* zb6t6tz4xwv#pCZ8MD~FF#@gMiCc^nZBmV6t{$?%Y8nx7I?EnYHpLFFAgUW?}fZ>xXm!8RXR}=c#V11aNo%?d2E`x_vKcth@ zP)9~l^FHYW88(Y;0#oq*RJFYG@cKs;*y}G`B`8UOD5PTluX|7YVKEW9#KMrE1UDe43Ws zbTSvVPIC;6?Weo+3dyUZ;Gs=AaVD=Bjq{gfR&CZ@MXu^LKug{F|6H+s>*fVCEpr$e zzdP5xy9H$`YaVS)_pip3*Ge(q9*s+j4#JELpWRGK`A5#0a%7uWD_ztN4c?6F7;(PZ zCc>%Ks#>L})}mc|cEhOvJ#$cL*1YX8CUqufzKRKz$#HaalT0>Ekpdsa5cU2Ni@@P5LeW)#{!2~?v#+u6nU<=c%1$ioK&x_EqE z&TUO8Z0RAYkoz)Hjp~Gzza)g+3Rw!9I@~~xC)G7S7o@X9XgtqyPB0!{#baR>)vb7~ zp1i4s&^UtS^^DQ}b8Lcv(&)mL>iTv3lg*D)ZO8e34#okStp8Z$z8h### z&j=o0kjlRs$Z0sO|eaUh}L`{ze8X#w3#D(0knrb!5(D`P{un zhyP)eCfEHy!};-(@wr>@qg=Q;)R}Y;en`A67)FOfJ&v#>NlUya+5q1;lEDthDeFbG zFB`1+<4?ta;^{FHbJNIb)plR*;@J>_I<&62VnKeUE4HHo)YhGT;2!iO-o+%V&PyOE zhs(pfIQ=yaIFA9@iLuK)PYzg1-%>OnZBr*|EvQ+8sZ8U%Hpc0-B5Z1t)PZj0u-50& zqp{yES0=XXCfbXLmae458_5nxfzon)gRdFr*TuKgI&_v0lYjZ0GLY2_gBxs_ zKoBt1smEx*R&6R9%%Vt#G{HJcE8+D6e?V~`UUT^uisPsQzE3H>vT$S;K zm%qYS(qjM}>|zaW8@lF|I1SUnk6n;8%Wv7+*yC;PO%9 zC{j(5q>xVY!Dw4_){H8J()S z1wu;oi4!ZI?y-JsM8_DIzk3>RX-P-6>&wnZPl>}y3H$YXP|=2?hX<<&Nly~X#sBIO zQ@!YJvZARtUc&Ar(J+{zJVDt+fb6|2EjAkBAr&Dg-ZnX77!qlrZp>r)^lGmq2XnaF z+ofEPV2MS+gOIn=BU!L~kwvC8F`s`7jk|l5VQGkH-#4i3jy4MzvB= zcGYc%ghs(X|1R`)%`fKKF2PlWgP&otd1{gU zAl;SlGf|5m1_kqZ{sngtFJnLPeJcFg8H=*O?g)@+TD%7mH*F_Dy-3V0AsLOxei?*G zRAt0XcMZ}W&Rs3Qk!b;$Cn(drNLesgIQZj~I)polLW^9z*l+MFEhW*rPq3~}!?q9< zSUA4RIMC2i%QWdcIgOidVE+G?_Z|y}(etCnHaCf@emypT{nOAUj?+Q?EUYol9~_v0 zZbzOr+1J0Gh**g3(nrM*(P3bKJN--WvzP&lI{F`NL~q!xy*^mm3*FXlghh8#Zygo^ z=O3J;lhlMHcO5VJWV75-VT-pxV7}uMh|h6p6Jmpl5;1a8Rbi_{dEaxQ(zdhKKXjw~ zsN+DgVJpTsB>pyxd(P0(>tmlGE)4?DfP@yp5zKTPI;QGx*F=+*o(4Dyq(aIeet%)t*3+TBk`_t+gQKzJc@nd<)A$kO-6Xc3 z&m;$!A@->JT&0(Z>%ixy76i4N_lI#&Qqi#lxDdvdad33jFYRSi9>D5cy0-$Ms;v?K zj#1}Gk9eyHBn2{=HgL?Kj`YuJ%GGzW*e3a;?e)OfCh?cjP~8MtIS95`UjD>C`CWR8 zd@j|9jMkCMCjYnY$7FLNY-_d3Q;RE=@jddn*r$Jc#u@Q&CbqF|z(`QH(Y8ygk$3$h zP+G598Z!@?57Ke1A`?urZ^aBar?Y%N)+KJsw}B|_kAN+^aN@>Elf<$P-dOx~5HWm+ ze}HG+Vz41z#o0FvC$;aLgxJkw|9HNG;do1gmE`xO^fG!bNwPazM|g8Zovlzz@~vSh zHxFR5zKP@BCzSsOwOkO1j{9-RzqT%IRR43xW*>9$(>~*-gAL8M4s>s3u$#GS#B=Fhl5iNpVO zx$hkO2B67TF?BF711W%BH2OUY+A~;PZbmV!)OapJECj3dERDjVF}xguzs>)Zk7nTa z4_=uAPPO}^RrT!=QyjMQjFOJb_~Xcy$}5Q@+0JaIn6FBnRuS(WM?DtCD|vgyGAF=D zx3gKw{H(K3=`~(!D8{IdZTA62%N@T|c{ujsUv*OC#E3~q=*59*ZD)lth#f_OWEd#L zaTp|hrA}8Ut0%Ed5f`VVu`b*wjh3P$RoJTuZ$=gHP`}W}V3|Fv?XCLoBIntcm1iL1 z{2fmV`$xLMM*P5s5=N#a$|6Gh4tff{C=#Ohb!G!i^MHwnxA35FHGOZMfyR0D+eAcb z0A96B##aTbzj?rJ3RsGGG23wWDq_T-`4NSn_Sdm|3_FF{i{q=4e5XjBlgQk(orE|p zmy0baByR!PVkNsFHYhreXXrvZ(AcKVR&%)V|U(Pv#@MK&> zm2<`BN!-KvhJCnO_z8Vr#7j<#7GfZagwQCJK)FpWvQA*`FZwO4470N~nu-;Ep>6(H zQv|vgP*55o2ky{O$126hzqEg4@fjLcZX%?rq2nZku*falrD`YBxd<^ESlwKL*>AcA znRMA_n_V19kPYqq#vdL!9t;=o71aYb7;VDwto}z4M663>BVqj3zhm09x+xZ_A!|P;@J|s{f^njqw zlb(oFKma1g`3)inAg@bC4_Brz2I>|^uCGk#4zY- z`w(>slx669mt9Wh41K~}%h$1hx*XN5ox0M>(=eqY)<->@-yb<1ynN}#tC_Lna*%DG5<>KjdpH+BNn@LH|U`0+;9T|^URXfl+K0;*5u>XAb7 zE$6AD$w~*2=1YwW5J}EM=Ww1@ysnbpL@ccE6ms1lkY>pV{XmNS?Y}&%O4NUNSgIe85V=CGZQlYn zZg$;R)d!g`=}y)Et8a7Fa6j#R(su!UqTd~aSnAzgG>gNBF=XaQJIAMf5MeYWRu-Ni ziE87^Q6eKhSaz^?;TB%k*zKlfIOU~o+o+g=!ik^g3- zW(WfRZC$=&CRY#UGs5_L3%0xtJlS>%@!z;jjCcJIF%>1uDQ)X@4~{;&VOlWhy+3F z55Ihgb(Lv1Gf-GBkDV|tUUhEP+aZ;jF~SEtX-++XiTZ0L>5Rdf^{%fS4|@X(x7UUn z?A;W@oH4KJbmHk7nx%VfxXxCkA&&Ek$kWCCU#7JmWQA9kQacQZDV`I>1k2q~GK}C` zM%X##^eZ%R%sXU=_MvWiTl=TKMTFBUg!HJDapg1|r|!tS^4v5Tk^#!H%;#i08ZZd} z*ssB(!lt#>^3s9Mw#YPzz5Pi)P|qy)gHkxYM%fBw)yW-UM2=rtM8QBXG2flTYAW4^ zf4)wo;VE(16Jkio;9?|iPX^z|5#y`KMle9+zDVv@no}!nGD+#@;S8cc78=|89Iqlqd`q*8J?v0+V6>$w)SzA^crt`R8KU=v8@dCGZaJ=JVBM z$HZXht?I1y-Ps$u{(z<4`e9bFS|R~X^xD@xoi1El*ck0cT}kK$GH`^>LBxyF%Pp-J&Gc+hJ2Z_- zR+SgFuqOz~yIcSShUKdDW?EWQxT=J&P0zmmS0tGihW~6k6bJ|zI|vBYcQl!kg^i1~ zMg1>}1t{=f#o&4zdp%I_?|`y;PX`H5q=@gNGCv6-qS$C?5cBkeDMwcDaK+$22&ZNU zCs23T|2#AUy+NJUz`r}2AJoCtuK#;CCkc*J4s>RMt1&fNYqI%oIT=z@H`(xV*V<$N zBfB;VxK7lq7IIBFmfJ0T8vkIym#+@WQ=Wg%YrudDLF1|)2ieLmYNPmuj5j_%7W?_A zo_P)N`<(d)=op?l=on<5o>RWE0~a|pM8>KDVM)c2e4*LfQZ%~~B*MzL?@WRS=zs?r z9!<|?R{Uq;%s<=GH@OMb;thmh&-;oB&kQ-ICr(b}SE2VP2E&q+-7u$K@K!f<&7K|p zB5-oqLM4+HmF1K!%^Hm*q2f=W>Ee>5*!|Q9)V+AWlnv`?;mu)i1BiAT_f1B6_VQ3$ zemVCw0b`d!KKM_#k)kh^mAs!+*MPyV2-y<@(&=ol;oRA|di7~`A-RS_ZM0^&!rFqc zaB9a$3G`H}Zzz@uTCy2@D~8>KTl@Z)#^k1MPtz5BN`4@`Sl$k5;e@_}K1koe6Vs{M z3eL)zr`=mR?9BoDr?*lHMGQTEX<^jIxIoKPI8V-?1Y5g#NMI{VLWm047J*mRe@bCc z^Veo zRLwS+96=XmjKeuwC3r|K##DPI1`pyp=QP{LXQWCUn#7FG^ky`F5GVz$MlaMX`H|4G(3!VyyxlJ#DzTX4=dTZYU1jA=6Isirf0fk?8bN z3|&TBX7=~VOq)?U0HBP}58-rBl@)ehKd2%U*3}1Cd|r4Q)2&U*;%v-<{VVnUfxV_kC%o zhFKMrj-qENRnP8488bn&H}*@mmpJ<gk_KiPd<1!XbCW*}I*hFRKaVTrhfM?C>j z>cj+jA4WRmdlu{niV01uoD9)e_aB6lSRG~V0W049d{PD`;)l>=t_iW=n~{64a_%wE zYDGTS+g_dl=rN!{u`C$f5gEM_8nw)!JpA6luLLHhxGZT+1vZ3u?rTy5V0<@sjc`n{ z0@GJAo>wegOUm*SI36%N4kRZPZ|yeJF>P42N(a_cz>2i#_vMGmefujhUBgvnJP5=O zR71;y5kV&9OGuD2?@hglg-mPvwS7oloO&lB0UFTyStz2l^v+cKSX6+N7pw!Jg>g&& zFh@UyS3GZ0IM~XIMBs|h9Se4`O3b`MQP9g{^p0eT(t|s8&nQr^qMxo@)R-boh zL_u`NoC!WoPQ6~`c^0w}xrr;JbPG+7DG{aT1>o(csHqjDtfjLelxBdOiz?+OcaRQh;FqCbx|u3F2X#m5)1kpPk=}dr8_(3 zrxD}eIvN*Yl{e6%xM-cT|E+Q-CvSh@H2W|9KvrZ%9Y@^rXjv#~L5N(Vo&BfW>l=lJ zdOp@d=Yi7a@Z|=v;WrV{)>=RGXKdgM)iQvGh|f-oet}z+MchqMAaKcY(927Bpsfr8 z!WP`Y^icy*t%@Zu(xBXnA`n?OAe&X43~=QfiR9?;h6!|+)=seB846o53kE#aKW@RO zBQs?-autkh69z0E$D6QT9)L|JN2qpHhW$fp$s&gmHo)&slomH`xjg^PETxq7fV#0J z$mdoSPJ%nVRiVzNO#%V68CMy;5lGFF4h_P4;CcJ}aTq^MI8dDHczkZEP(DSVkmvst z!4G=f2?Q~R`siQmw#&<0&Pk#nc}51ufE z3BK3PVn2i{X|EjCGe@OCQOnRWLqpd8m&Vi%?t;$rm)7G6A=`(1W z;=Va!k!q~;t(T4$rJ(Q5@`*N-g=YOj>O#=bzQ%*9GPwmd6Ofv;C`io`%9M7SoQb%z zkwJ^YYj|w4SGqq%CVlvoWNGWL>`m`=9=s*V92nf(Y{CxXcGO(rngU;^uQTHvgB*7( z!3%5(Tf_N7c$_Gv=CN1W4P7UTC%n;0#wyeCd3J_i2PcddY)IyfZOC0AQHc}& zcG}Wpn5{n<^GByY9i?HKlUKj`=jN`AXUbddZv-Zl{J#_X40Q$t9NC>Sx=H##q<}1E z(I8-GaSm*2s0oha6I#`wChf8g5AVNNzbX zQj%g}N`;kb5t2sY&W}vBcHl^L{-8NLhMq6VNf`H8i$7nqlOMAShby1J@5J?64?Akg z^=jMGP^kxXCs>ua4mvXVRwsHJktl*jq0CjtA9}r@it{^j1}^*_RGx2mK_7Ul^q#og;Q;zNtt_PPiERt`yXjLJ8zH-iaGqJUyU=(i%p&>9*f zV;jRJ^Fcg*LE^;@bXa$Y7r6Eet^HtAMi`yA1HYa+!VC4yy=am+D%U z&5-ihF<1e~VKbjaiz!teiuYW9G&nti_5#sD#k9x+YKt^h;hgX)DMOEYCYIZ7!Vk4w zN+tk!2dqvWH6fh5EpS@shZ(`)vUGO_Pf%3Fz;Y>+h=sokoJ5|>k&2g)gM#-bEiwOn zw=%mlvSE&?7-vuaa)C;IzdR@k0^FelFFUqTs1Ncg^*_wOL$)K(vTTCXUY)=%(|Oa* zI&}BgWA}`#sWdIK&ET!d#gZ;Y{{X6I_?dUF^i_SSCONAb8=z(*?jMj(?Y|cpwq}QS zHZdpQ5<7`^0%-Q-QW516$k70qHGbj&*`lrJE!`A>pF$$-1`n*KBz%C>cpIDyCs&va zdOt&wd9EGyxhWj$Kr!`|Iv0xe6b2XUTwuU;Z=J#)qa;X!*h_s1k-LGCtS_VDk+n+ikp1^s1@FBFP#I{MH6i-Nhva1}H z7SM#i8LD3;jIHyA%~xY)vq{?jwAKl24F9fJ(!OsU)JgJo-*X+Dkgi2hx(3N}nTO=` zUUR91Hqg(xg2I0w*d|>9Ci@%%T)E#y*UX6dpIp-e4@0+zLLVNS%0}cQxKbXHDQ_+G*rD>4 zt(vz{%n$JR3NaA7oAvN17!?Y+Q}1t_die3Tus}gd3I0kkWaKh|Zb&C+29iofC=DL^ zaK+bmI0E{9>eHMi19@rVit)v8>!u`+%v;fCaIfQ+GIwvZW$-Q2%*8t6Ih8 zrscRXgB*$CO|p>WIlpnF&+lx*74Y9A*ol94%KS3dWiX#N@<$N#`Sh%pITr((Apnw z(;)NH6zG)(@FEyigi40Yfv6D|4F3qHWCcF&AB9fMAbOc9PHJBW%#Wh!5@D%KWwYLl zmC;2yGp<-VLD_pNkBX{gQbTLM^Jne)TB2eY!UZST+5x7Rn>jHVhT2wpVC2WBeH(uVvZEu8H3dpILJ5T^ z%z|b~mtq74K>;Rkk`e|6LBQ5J#qg`4@KD$q`yjJuStKw0$EN-jh(#>i<^?s22Co6v z?XQkh@6jr!z~;+&NCiGhj--@jFbG26-E?~F+o)vlqTpmWm3QquO^B`{@Fob++k0N; zz@hJEZ89zne5Czu%ZZmqc}seo?)iQ`j8k@{n{vV4PrK>96^PF^Ad5CV2OZt_p-3rKfy{3B z=0;2bZiMcCaki7K&i0i+-Eq<=o?O?~Y^rR`kXT_%^u`bC63Vu2CNFEZKh{v}vIY}n z(_)|L*qzO+_eirzqr&1MkGeR4F5uiqMdr6JNwSxHdUga`cIw@ZCuBh_kfH-1l|w>X z`fw2bX%bl%h1M};D#*xIDN3Cc#}HZh3i_@GWUtUhNL2s){8@hgO$^e&r?_ zBM6&KztFL^V;e+gI`n=;U<&Z7FE}=X~#)fsOg#3*E7;!2uu=S zj}rUlmM%IpzFUxMyxyx&4&=|F&MFx+7&*K7_fdf#3JH1Z?7QH+De@uO1f95w1x8!J zlNP5~(rxh4rsamy=pqmU<=&P1UbAX5K(0I(E`-ru>qbaBE+%B>UR4=o{$wjustTR4 z1pLw|e!E+7svLCRKdy=c;>^Z+$9QpoG5h9@!g7jhB+^~QK{k)dov?Rg8U~vqPo@@47yyPmkd;Fl7 zaElFX{o5Uu!zkcSY|jQ)U9rnVHid`|w@VPPTcw&?(Q(#-!49VeIU(0dAc(*$5WHoM zb#-GIAn?|l?ed@vY?V(bgc@0kF6oWoZVGi0C#ds`aNF`-YYr*J{T#qXzKunKC;^{O z?bjp)_b(BX#5k`4Ax!Y?^HQiyQyTG|ED^1X+3|19W*O2fBB!;7-w<@H073>#@C-Oh zgHsg`U;m{$_V1N!&!dHeim)L`wlk9bxozcSi#9BHRPulhRAO)Hudbr3`O|?5aWl4l z@&5pKK#0E_7tEVzIM;cHPV3zIHz*A12p0Y>-pUIvWQdSQX?2ODe%+KZh}LyvxYSSZ zGmaoZq5s|Sw(eY~0wNj3A3n@kVw%4^JPM1nU^XD1TPJ*%_Ot6SdjRPfnFKo9QdLgXA-Wiz}~FgU&CXJW)6X1p8OZa$3dO^xLGYK{VGhJ^(3P-fbr~!y|Y3fIc&t0!neHXlOZkHTTwJu z=7)?Uq6r}956CwjibG3-83(_lpbhOfzI8$!;;k4+-PEr_n{fD|x4gpxV0G5`alUJN z-CuuU{!Lf+)5>REM^e~*$sr}fCFf;`5`;eDL?KbrE-ygpY7g%>f5vmUc~6v%fJ?GL z2aj)>r9r; zqV_G|0I32cw8kd2aA?&;3QhjO@4maCx#NGaA}wWr)r7=I3iOr6B(fKK73H-=Q@m&| zaWkIinZvzj`$D(7;@RaX34u|Fdn#l&N71{hNH|h7#p)gD&$P}wQ#T)2#JPX9$RAXK zT_PA><OZN?<8gcJuX9&>i$jLywaB;xZBh$*;TMlIf!UJ*v}Bd+$sO~He4Az7%8TFZ{D$uTz# z)}Xxv!)bOqNqUqw(`<*dL+vr%G8DLoge1OXhKdb1>o1JM>ZsJWnmi^LLZMU?wLLKl z4nFs3Hd|lw#fGr2@SCSgutgO+xk@q{K!c6aig2Unco~kKhpytyp7DsTMihUyXCJc~ zpXJJJ>{QhBkNEdt?~^swlzd07gq!H06aH%gLsz~WnNLm}!Bi+9G@s~GEeO>t| zNyC=#`{!(24fw(e#ikJ+Zk6&7gU|24tNYAgM$%T`fMQL56Cro1q?Ugd!FR1v=zPjc zNtq@>ZIoCI>)jH10$+U#I1Zuh%z5G&xg4wTm}O0VY7&%v)>24PGVMCEDh&rQ`jh=b zf)kn%gY}T$2o+UBJ*75?~41N-h6! zeJ64`ZJQSL;K9U|o@jqweDncy^p6)lGni_ra{J}g^Fw8jP`1BRXjjeFr6Xa^@{DXf z8Qs}R)+poFHM*J@_^@ARBO_kCW0>^Pg>7~%bjtmn*uM#U9ZbGqXCLvIT(p;~!i{s=NS)8;Mb5^TpV^6Nii%tcA&g9 zxAnKQSR81Lf?j`Ak5oT>Y*lMM&&{*S0YR4snI^gtu<#WzFN3&nLF=4|o&avF9hxHc zlX@uc{i)xg-{P*H+^FZbH>G(-QRAN-MdkEsyDMPkHB?*_>^amGh?!0HF4@nh`vmP0 zp|odNhT1K(LPLFXe6b-X#>l{&>O`_1PXRZlJY(B^xLtpxS+(w2-DsVU*iWRe->w6s z#xU%2Ha;^6UERLgJgUy74E%}t1tIXmfpEl z@*qD0n2WeOlaDSBl`fXC!iXhVB&B^9q>zusLac+Lz|M2h6HGu!G}v6cfB{Jz&tScI zylP~k5o+ty+jgwMbOl2;{i>s@>+2KdX|Fl(C;fjCd1F_XLta+gO$jRThsaW&Q`*vY zmV4GKCwNdNEbx_?{@m3~<|gyj0v{zYF0*cNYymam7=+1Gpq_ec=Q>jy+RQ`hnZ{l3 zRlusUartIZB)9;<@QQ&{DZb&!Rauw%#Q9f6O)3jR22uEAH{Iwf( z&dti$PCn|p<2Suw9Zn`tfdNS176akHeR~=Oyd1Vu3RMZ@wj^EF9we&Wv?Wc4+TZ@U z$<1^CAw{ZQuX0Zr-kX>SH8S(J23i(Wb==i;Y19V$K^3pVhyEpQY*T-5y^$G6Ci8z6 zGXrE+V=J<+1O}5FDjPQZf>0>Z{U;Us&i+0W64W z15uQT!)7b%H2D>ITIH))d!&HCr7sg0c?*b0Ok`Q(Uer+Bz+3I(B!r)cS_X|p~ zVJ7=LHWv0zND-(!)=5Ukjdu3e19nJJ5fWs-ZnJ7EezrxUJQtr8h~jLj!8DM5F=&ly zwx3^VgxY-dh-6O~rW8tMP1??~#uZFF@wWU^q$0}KB#iu`eL3V``d0p(ax{PQ`qeg< z{d@vEL{oIh{7nS#6cFwC3CE27t6VquEM?b>5 z2C){EUF2PN&GH}g4H!}2i(kixiA>nVOHn#e#IgsgkhP6$pt3fiyT_YISz{z5vHEtD zgF>RKqP@V&XPRE<=`2_w7%P8Y;x`YWA5{wUKjc|e7jOK1I9)MTzNTwoPLc?*shIKV zBgvvC4`c$V!ZCC`lJTkjC1K`Bb8jb8ZJDB7Ehu? z@-HVa@J9_aB1BYL@yn3x9M+NbD#qhT8b_qa z$m$22*we$nmir}Zd`y?>_6t4^cBFfd_)F^|axOg2ugRScN)3O1Ds}i3(NQK`*A=_5 z4o~Ylzl$C9!Zy48RdH^?HKdvEW|;a1bWOif%zfDP&}s;y(%x70A1B4s0E>Ff6 z)<(5jSEX-TuZ~h_%m*(cQseY=)wg;t=}NJu|A(w#&!UiUmF|uSLRul{xn9?k(5h-j zcvr3Q%|}`Hx)T-e%>_s-rarG#T6&NHqXdr57<+wj+Ix@uws)1JyXROraF?DHJR#vk z9pAb}MHzoLHQP7+;21lN=lZzO#5D#0CSLYH9?^$dtt}q%m9r&p8}Z_x>Dz_3HchN$ zeRmH6U+jKgd5B!b^3UC!T;yu%49SC0R6d;G#$G>&z|81n(dA_v(%qXK)>?D|#ck}Z zQy>ZQltzhbX>7P-3fR5B;5!^oqyg5(22YIN&6M}bD#q>LJbdR zvx)$Y{V`Sb`%Ve&k#Y<25QF|OkM)SGDQZ%lS3P(uzjAn;*`Qu|H0<3)8ojD<4ot1+ z0a;h`n9AwTNhr7^|3#~}iBdkqNs1a&YwMNLKao`5tfg}p9$*US^qX9L3o#MO zE>sU^9+k9OU$e0c1jI?i7qbQ4dpDMl@*a@q(_2ADo4?Rx5SK{gKzY&sJVAgV;DU3< zw;PJC@dk6L7YW#nf-FX@hA>`bhgcQW3)w=o(q5r`X_L8Wr z_Alb@2?)`%U3ke#+ugUD%)>$E)({m0)2BK(?miXo6SU+`vOf^BF|dhk+ophUwxk%~ zWJA6~7YyQ#5hytr=m_F~K2jeh-$%dkmcM-q;6Wrp{1%kq1qUB79WIg?DEk<4dM1A_ zdzw(uK2sPmndtATYKC)j8nd~@HtL9A;9uLeyVxZ>`^0#s9E8poP^S%xWb0Rw!4{h^rD^5m>%OEH0Y zuOhtaf@c%caHqds?q*{oHx|O)6-a;Gu`PrzLA~<{iilN@aud0im<%Hq_sR)3@8`*Y z{Q4#})B6+`RQr%{^y}fc0%ntijL;Aw^sZm1ckdJ4Nn{+q-xZV9+A^1n)tE3QhW2Bw zZ5{Wpb8NYU_R+HGw##4Ah!$Y-`$??s#L@+cxAv+ZK8$?p)s7Bwu&Qj^tk`V zm{uR4kMCpn?C%h5N2NsMrX3pQ9~YKY>|t#ENuHO!7z7=EU$Ea0!bHv*|C7}91`H@L z&vL&1M^f|$Il`*k!Yk?c)=yRy?Lx66$(yH>FGJNUWa8*1xgz`ZUz@+e$6z~-$L`7B zWp=xx_!Ejt3l;M`8qTapf1kOouA~m{u?k`-l>!T-uK<;ct(nA8ywXIotug;c40(W~ z*WJgYOifXjS{Vc@6l_fKo=0sG-hbdoo@(b3Nu;F{3744}1R{UgKG-b+SeI6n#o4Wi z-(ThX?<{;^PZ`lCa_G}qcw?ltccDGv&ZqD|@)XRCB zw$N3Uo1Lc*PCHjDiC1#?_UDo9P%!c-EEob;G7HD42J|D`^CoT9Ga*w)f1o`1jSCoo z+Y>AJek$Z*MLCx`8U#Uq_UB4hiPtKV@;J>c9XYswUs7TT7ufz`nyjGeRi%mi zZ1>ARa!aPh%lvu_Nqb%osvwB$zyub1#*EXy!S@&v0z6yK1$u>4d$?QCF{dkSJY-DW zC}p#As`PZ;3nE!8FcTb2T#u^{XaiF+Ov5L$lw!h&(NqgBU~E!<@abiSFliqu>P(fv zQh&HXNNVc%0bL&APa}-A zl=8}xw_6O#Y=j{6@~Q*tA&F!GHe5N2^0c&~*|=D@ZQOa=fE}viQvEY;hMemHAJYSgxNzx58B**tS8v;Ono-| zViQ6zygJ|k8gTO#`llCv^QWJbIgh(vW^{h_Mv#Hhi@@FJ%rJnPzx9(UATo0ae^GP8 zrshy2SPy3tBRVQcs=`_5+iw)JU!A+zC3sMjXN%y!nRmf|nrSDiXO@&l;Jv$5n!*KH z0#cDVf^0U zh{(H~)a|5y$mPKEsScfvatg9F)3GlPDP(Sw;HDx#B{Imo=Dw@R3QT-+Y$Zxlu=x`= z4#-})!CRNx5P9|{$0Ek|yRJXJywQ?S_po&qMFd`K{Sj10?Rq&T9D z=E!b;G&_=orcnoP#%RcgUB26tLcNz_OQswS%kXBru1Cmeew=f0Z~~(Sk7vR8p1RWE z3KS|WRg|9%)a#XReLPAuwVC{tjw0`5m!1f9nM_-VJbeUma+~dLo1cI(KwB5&WAw7! zfsak-_*~J&j({z#N_6oGIrc~5ifgqW)Wu~q{v5kgG{KC1Z!x?sh#kkr_e^n!37<@a z8xv_4!%Y-QX5TvEozy%V%SbR>oR+t9zh-?hmna?tCl_{?wwDeC}akNIGyb z0^#I2mU(W0t<`4kPzgc?*z4nEe14l?hk*Yd-7*vb;8bpLtBzh=0{Y~i%$MvQ1So%m z6pqr_KzjeDO^-N+{`1fkCu^*eV%$fL*9`hCn}7Ys2jrBif-DnE~H)AE|^da7(pm5=@+9-bWug!f%P1TjS}%8NqjYY9FUzeoF<_ zZJ^KSSTWI(JrC^-d<7QL474HId4YfB#L{geR7N{k*vtq@!7CD+BEA+8XjqaejXwh@ zSNO>T1nJ5ksW2IVi4b(;HtMj1tMJ_9g zVcG37E;q##It5f^b}8Q~LLxr6!t9C4Zwls}qq%p&ShhKla`L(gR zqUA53d(rd2&CG1cn8S)Pdxe>j!wq6Sw<7Jh{OLM z`X~Ie$Z>}74iXvu6_*M|m~MlVGb1372B1CKHD1lONEi$UQ&G`TE$m*BADYy%JT@C^SAYU@ZA~87nhodls0`7*8s43)XEZ zym9Ze`Wr8_jVK`pT&}{m35-!vwVv}XTd=*ew?3F<_VBuUk&((_0z(t;+z>CGlL&Jp zR+aP-@*ZKCw7-`lAp|6Uacj{UOz;C9ibUwHD=?SIiZb57AClBG@RW-fQo+|+=)w1= zhX>TNj|wj@wx)-c_%)1cDo872v9KLNNLC+sF!rA&r5q{!^_2r<>>}gd)MQQ<^TXPL z=u{th>{o60N{z&%Fn{C{K+IIEZp09{a&HKx*H{h9!KCJD-n1EiYTBr9-72kw2>QaQ za11kb(cn{0*NsODMwWukLeuy1)O^^XA~p=4orp6OMFs8nfgFcAFIEK>`cO;hJxCl^ zHj9pSgbM-#j+si_bd5{z$cR{Tr_MbIk+O*meLk`qh?hB(j^{-Psk!&UtwzO!JXsJO zZdE~@3;P0QN7f^MgN%h+ZARh$}YL@u>94P#mQJ(7%d5s5JAta)_njXr^A#Jwy? z?=oiwn;NPagT0qD!k*GU43yJ`9U{Win@a@r6~u=jjE-%?o;%yE>cq$v)*JD4A{3WC z9j)&}+%tso55jlc;7z8r7v&Day>}CVG)1+%tW&+f zzOB~~U4mIQh`v@u3MN-}LUGnmGsGo&c?K<*iC;0EOwm)6mr`|i+)T`YKz2UT={(PN zv9Kq3`kL&2c_SA=-iQf>e3PJa4o%$^!O{b>2h#HJV@|Y^$7kD}T^G&w#Q1CJ;1TW0 zuN4wwlMbM*P<9R9PAvR9u|Ts+hIU5{b?|g!05OMJG~3W}%Ktc#t8X%*&o?F08mXAf zn_2U+3$txfg>=1>yw}>o#IGMx!N{tbbo(8VEeEQ9-_nu)$yJ|GFhB@aMYk<(}SUyi;chJJL23+ zR^^4&5!EJiAdf?xTmD95y>^lO)sQJN20;teP3?ADqov82bYmsT`Inj`1STk&V0(m) z0E828z9x*nA6qiusoBA~$&<|BjxFWr61v3Y`)+y7F`MC+=p+O+55|@Hlr$*VA@!mb z(#A?GmneZF9rnfj2 zL?n7mY0@^4*RR*^-$$M6FC+$khn;}-jj3)1hsF%)-Gkns#GQ^VAowbW4K%RETtVdK zKnkHpsHVngEm&<36^I!4A|t`Jj5Ewt@oQ{f?4F`HV}%H_sgD4D*7daXaYPx`^`wxc zaO0>IJaM&Hp`3HBWOuk>30$OWe9#8AYH%MBIw3JUjhCi|jSm(ikvBJg?L)q6`>=(U zBr9X3j_q_xzO7z6dGX7wemLyc=1E%kmN}=QwsjK^yi9ts026K)2l3Qs z6~r)Thy?2{D>+O0AB>7zy`d~4qMPi4rsN%bUDCOla zadDfrkj1bA;@SmFD9HDj7+ZInK%IWK?2~`8-ljmU^%4c!=%L=QI=)v_FOwObBmb+< zpE~IA(ZAR7fec@N@?L&zzGYkPw~!n7O8Y8Xi|@VBW$vs^lKqju&y7c~sMUlq6ERaE z#sX+pL(E#i7vS5u21gVbXfFiu@sbLvRQu;HKd{B8Pw(|HxH!ni3yk$pvhurWyw zMK{ta-#=)V5+PaoPR1K|mhsLE_fCnQ;DdAoP^p#ULxTm&OD4kaUVi85OT5`os(l&Z z*_}>S6FQ{Ja)Fu2waD-yxeg$ub0Ld5OSZ5nG&mv5N{?{^)+sk%Obuz$pc zZ@_*(IMyXQPn37z6c)onq`nT-aEewMN(K6MNMSn50-vX_7ZoUwO8V*YL3zRnG2cJ# z6Vy)W!&Jb7TIQOW1S^lIV6(M~@@OMD_G`*_n&=#VX{WO31}=fb$Kj3Gq{OnM&S|04 zEZ4NV>hon~Sg)s_{IE1zhPg&a1G~3TrbkNjsXh11YumX@HUeO9C!1aIIZ3Mh6*o~( zY6g5*v;+GX*znNChHlTmVhP5wTlQrXvH0iwQHp~sW~I^IntISnkXbeHi>IJ%i@rz9 z+?U{g5Eq1J8fwczK*a-@jUwDe`eiRF{%#b{T{!IHJu!Q zJLEJO#|ywWlG4nLUc4p8JwZf=Lak>OddyyC`WVnPt+~UfBZaiRv2mr!_;L{O9X!@- zg@Yswn>M?%GxuK`ABF19v%Wk1F!3u*ObOe6cvdOCU5|JNzk4{lEjJ7U^#Z>`q7C== ze!;5yf3q-8Uhe`e^jWnhb$%C)1HV7Kfs6Zpe$Jjvz2QFcCw@nNADZ7qiz|NhOD6IU z@9=*lA6^k&?|6Q$<`o|Vud06Dn7`j$@B0JnWnb@pU-Hp^#_I+Dm0kUOu>TQ#xJqz; zmT9v1egLcy?zv+NjvDs=)PDJYG7jhKv!ZFUd;@5ARsn(9TaDO1A1j=;jbH8Guhn(l zc|RZFU+sY3`m?#>$v{6}xT|EiJr})?Gp)%kwzK}>-=I9+uY`OJfrQ_;{GI2Xr)QY= zdV2A%LgC*{5k<={hn@VXRepHt7Za?1r>`|a-=x~3M@!{&#REh6-?fRa0KeDEyWgi@ zASGEysA$B?2meDLAW8<{|7K7yG$1G_D4-an2w9;2Q565RrB!*+%SjFD(TAqdTlF(PVz3WfbA z5E<6t%KkJL@lE;O25@$Za=FdMFv{rb`1sDdr{Ljnz#deKY1L7aJhMBrM2-Gra=Uv> zpx^H?-MxRhTQ?4%XZZ>ZGD%hnjU8UXcI>KE;bABaw5x-?4&U-yvQv>+7))7EA~*p# z)v6nVfDL$)z2$$Da#R>WJ&*nqf8>M_n%pt-Z+{%Ux#@ zGX1cWN&~U@0&Ygd&J@2D9cjp;Ce551Tv(uuhJ*Sxz#eu~;Y*Mlk}v%}s)1ZH#PP4Z zaWcUr!7CBxXv~$QuH*Gt2d^azkXI|sW?gcXw6m(!=O{6+Hl_;)3x|e%;YRzTS$lv2?>cPSY=8&Uo1i*KeC~4|m z{7}s*Kefftqy>ITu+Kz5$g)QC6|L^!>0FRL@~1aHK6$&nw*?pcnw)%qEi?kj=#TCG zg{;k+qx_-MCg!k{NNS{i1%?@h0nFz)n6J<(XK`Py8PLf9Kh%96?2A>%w+(Wtb0glS zfW(Q&Ho)?S`&MDd5NjLZ3cOQxlG?k{_y+G}kZRgyC&h$gH=Kk#aCrAb<0>{KqfgoZ z2l05tu3i%4&v!405V`J+n)opII=3NX02di6%CnMm%H)@Z(IEiidc@(}TdD9_xIS z%EdN9q$uEeZ{v7x>%i|>3WY)<9ksSrBEJ{sx7j)VPS(&I_oQO-jMj>OSgILDBU8?4 z(JnYg`GS4i{(h`@%Tv@k(Q-2;*O3gw##(4tGaZ?;YJW(7Gn7%pbz0H<+;wYB<&cC^ z#V1~wK`_nnkFr#rZ0B@qHE#cT(sBc^h(|(uaZ|3`8U96zMzF<@%=yJehEiuo@g+EG zr{NXrOkM_$d!?2iL3X=k8&Pw##p@j#4Q2GyG}W+&e7|w!j(7a@N|Em^{8oYOGl%3K zkDYK~x?1LcUCMI?w3}9(UT9TF9?gw4;btJE-BM-FWL(cG8w z71sW9XB3A5v;eaw32iMAl82CQKRI5NjF2y9v>0{(54r2cHStzLfbcAR+X@RT@I18l za-lTFgK$+;VksVmQrxOioj;xDL7VCDvO8!^{4@oBd$fP)-oX&%eRC$E5zE4xm@PuZ zpxdi`0wVTjL*V+EoO!*G?_9L$Hdc)bSOz2)dJ%dy+^-|S&n$?uSYmHu#3U&}0aV~C zY(VlC=+z3+bH?gB2%vMJ3iMYScr!&QL1&rqBLJhcnBv-AX;zIn2se^Og0=vN(u2=* zw4j@RoRlo0aV{j-*HSj`pYBIp46_cEyT|ULsWp^#q)IN-=-R*2-H7&#Pib`;%VZ3a zNOuwmy)u|C#t(!o&b`$`Xa%Wg{i^Y8Bry!@-E$53ryBuLqlHCfvYx-$9{3&i>q4R) zR&zJtWlIKYNbp*7hx}ZbfAiN&VNC7_z~tKz~V~eUuu^>maOK# z-Pnu>Qz4A^JwWpvGWS{AB|pD4JDlFpUozAKbW2&fePBsLc042s3tp5CIY~{sVuPD< zgMQcq!17}eQzdddULM|r4loGczsp!!Vom)zP#tMt4+NmyhWu%LvU&- zevJoDIo^S-=RH69w+OGlsGt`CxKab>x8PIoJU;WD$@in%ls*n}ZDnJJWE$r~pIKUk ziqQG}KEAAkZ@&CrkC6Y@y(<0?FnUlRpfkk(%{~18>7Kl!nYkUKthIx=y|J6M>HqVt zrCT#)cs-5cO_RpPpbRv5U%y@k^*-W%9!MC;@qX9$>q9(U%?4oSXlEye$T|T_;%MM{ z%bh=I_5%pa)&HEzn~`OI?*E4Q1^)nK)F?)@T*mGN`1>B_R~r7V?frCJk1|T8)txx@ z7tI@5!3=iYt{MKTq4@_8+}W(YHi~>|H!L(PFf_vY@&5UkVwLRwda>=SJL(UA-FLLS>t?tclZC?)Q>WHue9}lZzB4?Trp1ZAj-dN z)jQ*o&k#EPekH63r2IaAKlQXKX4uVr5X=8=TwpWG7Cp2ZW?09bUJLHjM_xipeSJxN zex^$6#sv}-=L`P|-1XNPV-=Tw=+y6>eVX$Bc6ABojxyOHy6Q16-8+KdeRzC#} z1%~9+?-~ByWL;aP8!qkztmMD;TPcG5S_Obq2?w&xGrk7)cJs@w8vnSapUsU5Vu1X& zuF*q#f0=gQ*G;{kZ({&OWuA7xZox0lReqA-H?}uL*m+>v+!N+a=da{{=XQS};bTHl z-c�cRon#%+2o?VSmD}W8lbDpisZyPviYB)RbYxZyOa!pvaFZnsL+@>dPyT$uElJ zbw0e<&vo)w0_=4^W7GQY!Gy^#^2XQe_%DI>+pm`1Z(goqM?oMo;j`q^US{rc|E!Ei zphy4(*<@fF)8q8p_HVH}c)@QVbIH%mZ+G@@R{Jln+sIbe59Yvvx-G}=)6d=A=B0JO zC;EF}1pW`B(bexa-p~I50YLu0Oi+KfGBgDKKL!8>K>5Ffw>ESH1waM>20;10aJNCU z1O-3_02e^$zgo9U^aLC&1By_Fw`(B<_YwvG2|)J0Q@3a|1qeU}00}_$zvQ=ebOi`N z1^@{__P^b?gtP?+Kn4H-K>okJr;_vqKn4H_K=!||x0o~r2tWn^7eMI0y0@lu2Dc6a zicp5PV1ou+F$MquK>ok9r^2)bKn4I4Ke#leiEVpg+qP|+6DJefwlUEY+qUiG+3#9w*SB}oSGBsTtNOlw^`G;o^J@9% zUz=KM$D(2UEw~WT1c(LnyGOF=827dZy9>8lqrIDPpS&iI?VDU@DCCNMcj0ex!EV5w zo7XarB_{M2DyEH1Ew?aiEVrkBE5U}X(N11G0-*XhcX?|5pclkn=m0~7hJW37Bne0s zT11mj=+kKJQ`vmOO8ZmU+vQx+Xu>&61U;-Fyp+O7SpS*Y<32#+tpw?d@KmW~zxy37 z#6hr(NjCJOxj-)33Q&$B?K{Ui=k3(Z)@W7aL-EA4e<{pPmYmLT&%SbhH4%c}7RmSW zmHiZJv*gCVbnBdEEH@2iO_56AX{rhn2Ly>a<5%wzoWK(mCZ#xk?$hqQMKzkFlL5-m%NGq^^b$Qs$IP_ zEfhc9DYE1VJGQKB-7|Jt#bg^D-WiRU&3@~EL$T=CJfpo^aq=UqW5hr;5vuKumCt)D&bwDEDg%+-V zV)U?H{vEG-H!a?O#wtp^GiC*TsTzp``q#ikHa zs)g=o|1K+uBDTJy861PQw15Qi`)0aMo+b+g!@4_*|i5O)ge|gO@ z`c6W+{NGwAOqX;(yW$_K1{j&%?gXIEr_|&iQQaCVvSZDE;AyaE4|{og=1J%aGyY;X;bFe)`;MGf#CcBiQ&e6$|LhDC6IF-77Kc=7tqq1j-%(oM(;6OVvX zH&Cow&!(tEoUQUm63Ty_T4nQ2%*PCYPIiN%*;?TuR&_O2=mJWpB@DaRomYCKKAE#Z zeVbW-h(DA;rkUdHkrEkEO>rE!_+9D_cbFT7J4He~^*o^*!&tB?LTRmvm`qBFmGf)P zK1Ew5Dl(dkt(1o!zO#1zAx_t9slnLbji8@pvQBZaI*=&~JcHW}!E_7QJqKo=Z$q2| zzSe!Y_7Hp*c|N-5xCYF zQjvuzN}7+eqwTyhOaBv%2XdrXok5F$b=?hVfn&a$T^`#frfj=C&nvlYV(jn`NIh@@ zZDLUGedP&sc`T7*rr>p&P8@Bd!~syS-qdWJ_E0q3xpr-;jFu;qqq^ItLfw!AC}smbX`&{^CA&;>qGD;t?jqSLsAW1VIk zUi>)tt(jD7>Sr$|!-9WuWjouq}3IUM$YiQzSue?|AXN0q1ZT@+EGl zuf=ZJ|9c8kRWLCBU;gQqR>rz?E&AXL$!D;grlN(s>v++rvcvWkvA}ZD+cdiKYJ1i z%LS0}NOnSGlqWkJ@K0fUYKMf3t@abP9(mUD2ad$2YqKf9x}{ikzOA*#@>H0_;tuF2 z{r(DmSE5Lf#|Sd1xaK9o0*MG5nKwj^EB1j5Cm<^8*SetrEipsRA#(`g;(7%F|B!S= zlL$ubAvJdj>f_VB9HU`>p*Hs#ScDysnnVf78rivdYsMx()*u$XU~tYrVh<6^I@14& zR4Btj(w!wzcSI1e=LqvA$Bg|cITk`u;Hu2 zv=bS2!H@qgHd#sPOL2^1J4~2ov`ABiP~Z)2>?W`u$jES|y_xWT1|NN)bgIr3igEMD z*V+_bMmSgu7dEFkX~M&2u10|W0ETK&_=n)c_!oA?XK))@gU*`61ImO-mdN=}~lRa#H=LXtxrEVlEnu1BWP)8vet= zt&xq{wC2D2^SAWEr?!s*v(OGXN9MUxpHQSRj*1L8o~bg*dBZL zL^L|Ekz|{(JGfTI&8t&qa50KIXtvNxc&QXi>~^)Jq{!aF;C5jgNMQ%tS;&aa$7NYKl7CV( z3Hw|zm$;G1GK7&XEx0%JkKabp>LL}&h=(V4Nx+Jj51XFu#}#&=EY)3rCt{pu+Nwn7<{gi45_yzww5BCC{KC^JTPW_g z|7sX2s11I`b7fW0nLA)vTn6=pu>1&rHY@RFV+5?_Nw>DxCy+eLh(+t;h@V<(Xd;*X zxG!5>QMhDBrtooUTb7e1B1c{bnTWt3@KxG}?sA}C?3(sj(^F8od*jQA;|lE0Uv9rm zdZ7uA=PTC76nYfNIl4|9#xQN89X*jWWb)J!0n6SiED_{#a+CW$bLIJ%G883$7;P26 z;;n0i5|5GXawge`jY=IkS@l6*fqa9RxA**dm?r5Dh$)RU5|@(C#Y5i2InQMDJBF-A zL7X{fvS3&mF##!razw=qM|Y{>Mb`yITbF4`SD`nXucT&QBMNX+O&>^#gULYODA$43 zK2H88kq%kx{bAcxpHmg{n)FwHyZ`wVI4Hh!7L` zv~+VTle`Nje}y^wn7p(%spsUa*BxOE>;}#T88rak*F-wkdhvkrrDeWPLOe>xFx|?kfB2r>5V>MTyMS@)5;#D+Oz2+=Qi>+|2nZ*KO5C>4k%$@f~wY za-Ngn5Rt+|G4P)Ru9*ZZ7!M?8a3ucxa5?lJYWx~fs~y=xv8;B~%O7xi$Mo~8AwWMh zPEwf2T~=oYt2jK}_Z=R8MzN{mnV4GyVoD`Gr+de*nSE$yK8Rz{%gk|%d7o$INyP-T zBWNY#s|fI~RYa6)s_iN{3$eLUvTaCGTaoczzxYF3NO<7}WAfUF6uLnZmEOt|i6E4j zoe~a#lDtP3!%}TdVM;G?qbl8cClW{;2pJyxyi1ZK!6YtfOtSHR0>e{KLOb(cBl0H14D_Ns8BYZ4^WkbuTjtQ_8*6@_^(C(lwua?HlI8ci6bf6#$2 zpb%Urg8@0>j`o6o5_pE`O?Q(*n-=+AJY$0lWKbru#QIsRZmAfVkSV4ey^xHRWlOq& zT`)qFk(I`lq$py|h|hw*{{2bc#Epq{{5oY^BLu@mbY2$uscVT-AEC1$r5OZjr zY0PN-Tu5iFvrw{69Z@XmgQz1tOqV_{pUD-9{pcAwGSbI?+4Dy!SXv;!m>&`s0&fPm`V(t)fTcy~1y{W0&m!lOiYk;YP1w9j&+ ziYuEAd%}72F0Wavr7o?Lgsq7gI`5h3jc^TEU;?R((-y{oYNE@~=X7~^kK>Ehxq8C< z0woe&GE%|!yL*$Uo|joh5XSVmCQxYSvL$^5Y3(b2DCLvecUwM1F|bpJVw6$C13q{c zd)I?PH}3xk($NXLOGiWX{nZ;$x&te;ky$+uIIlfflM zE5J*8CtrSs!q@>Mnox-RRenF=&!I<)kiU7zQ-B8|di@Vus6$4*nMT<7s7UwQ!XlCC zIgc)XjbX*u{Zl>~f_dD>MCY7&diDwi(oMO1h9^-UZOzr*t>E8hwn1E&l$jO3&ah;M zp%^&v%FiY>^=(02}<$TR??fm=V_%0fcMqvKDh z>!@-PM=qIA2g289_1(HJf|vV2{Y$WfP^3S9{ogit+akyrSykq5j!dq-Z%36)u3@3i z`wr$Yj&eS;VDfCfBqT`}UiFx^R5}RMVD^*65l~hAv+aKF>;)-lD%b!c>`&zW+|v3} zk;dQN0mecVxHG_by~IP(JziB{5U>8JgEvbk+l|n6H&v2oa)wf zU6Pvj;Ovrlp0+9>@6}+53-O$9NPq@O!tX(bG!qIB=!)OeSV3O;M*&ieR67v3udRd0 zvO4S2<9ruGZwd(Y_kJ##KG|V|jpRyyo7>=pD;|3kF8(?EDbvh1N*N-!#)RQPL(6^#Lye3$c zLuJ1M2xJ1R7GkCzbFl3cgBB-$Fc>$bjKKg$K)AmO{5;;?P7~5aUhr}#8$PVFmbgcg zqLckTOZKC@WHrNLv09F(?+uz&Sq%e@etrA9%bJ6x6Z7k_QD9CW8pibR0MctdoDu%q zJZ@mq4O?-&u{=;3Vh>>^M_?hj##GJHy;Yt7jx zASsQo?<6Ww^a;8oNC^&vuUIi9+FW7td zKIvPd*%hju{LwQSyEK944#!k#`9bU}OuVY7E_n4zaa}t~$gmBVE&@C28!A)peSPO)E{CW9aXastZ3!d)yi3V zV(>LWm<(A+Jx!H_kh{ONT^ToaDx&oc`!#p}C0bo}Q>A^DO$RMV`lIRLf|HwA%a@xI zVp(|E7ZUWED#XI6h^op8R{Vtq28993x8r1zyRNtoUxtcH*?&;hf9sVa?#sIyjdY$+ z{CB`F4HDPS4?xC&QfJUSa|;-H-o3Nw$}K1bJO)C2F84u3{E<8&Y>FSfaXQ{qvSqMz zp`(!u0-&Iovf-fbW@ca}K#xa9B+W0|i84TgaDaHXu$Tc^>9wIs4#(%!vaOE%L4H}h z+}XHN{oANu<#8SLe*iNb!3e+-?5KQdPI^6j$GC@t-VPr+m70Qkh3s#PDkKh>A+4;) ziUfkC!?RAXvLIo!xVV8&wH1xJg0+QlSWcF{thum9@2W&>;4}}4kH_%qVq%qOgi9~j z>9Pq*IK;%Z>csSw$%Om-LnuB8lXuJCQr_IpXcdWJ?XBT&e-nCbo7Kq&B@pIxH#L0< z5|0LhGO5zC`oN@%ty4t?m%v= zrlVn^+PBP+?8YUQ|M?p6W4i@j-vCw9GR3AShrvb|+(*G6H-?*yyIXtRF{Qx}WF%0gB^3b*`Ce^J#-fN_V#b`Hids@q>fTcl5b zCoB$HyrW=fVv*&sHiEYPq;}aboQ6kl*x01|NxfsE)mS%Pw8sGzH}70f-C(l|AXn=I zoh)SW8aM=N7>(m01An7-k}!mS*Qw$gAV410k!oi~jI&?c2q#!>IbDgld%frL!h8jr z4f|s%e=eJ{(nt?ex;g0H*6QG!5GB7hV-`sGx!s{TGBW;45yB~wiH*RkQJ7+~_B6GYKa{l`o zji1!YcRHiVP4kIf;p-)sj|ES#Ts1Hyh;P1tf3~jmU4t=9-_rnoqGaL0hZ&!apeyat z@JNYokPpLpxs><@kI%#{-;|Q?W|DLREu8p{SZtv_j7L9*szym7K#K|U=J+ubGjoAX;E_@DLYBTfb*#~q&M)?Xl*1Wfh$!Tu?N@Szt}k2- zf0#Z1`)jTXh)p=K*_Yd!Rw`VLf)D+55~NUGujhkIQ&poITokKq?7*tq^z#P&@!`2N zhLRmTgO|c@p;_+&xrNTj2$u2dCK&6`0kaZvhm(a!ck=U1yBmOf2CCb0UXht%#QzK4 zAq1j!2<@HgG3iJJ$AZlI{(kcq%Q?-zf4?6sGmUm)qP>F^xA>2Q&yl#PBDJwpC-{8f z82yYm>aM9kPh;(&}YnOxBClA=v`m~B#(QI%n& ze(3Nn4f8BaUL_@ey$*hGf9Av?ZDT3-41ebp6-(!|?vORkJ(=9>z3VMsw?gnkZ+9mB z4bhv)k$Tu{u@uf|Wme5-p+78eSdp2j~B`>25c_O5`7SiAp-|dtk2sPf5=Y4{X~V({3577 zC<5P?b+~tzcFo?uD|$}SJYF1+!aC?u_}$&NpC{b=JmE+ z!?IGsbqTZ?Zdwd9_K~hMdfkj)yfD+HZ8*X?Oc#(FDxCZAO|KJhx}AM2^z!F>-hsxM zLr6U*r^l?8QKw4v8YYb85kzXp;}HlJ7?r1L0rw5=_!)E4f4{jj2V6uR#uNy!Y5Nfo zwV8)9V1;4AZl-R8X)=+3e_zMJHd>BmQt@yX4<#gJ`wjn$I*>=CSo3L!j(>Q^%$TOe zYAyH+=G*V`gl}Gw?~LJ6OGGmm)m7jx#e~nQ>JnOeO)R-JSJO~Y;4RZycX#CSfg7QE z%!`u@Gn|nae^Y`nHp!|c7jumYlf-w^HzsbZoCr8bHYTH3*2xf6$>2~x;zi|a z5*6cYhyGMhl&A+P$wGh+@c3JVDKBKYGiol zBH6gE!F}Kh9)`>fuyWA*zKRZHInB>FM7AubGpA^4oq>n9YTK-7>f?+<=H3szUY=Q z)6?21ReWMw3S&d9SQk)vaJ-}pMP%~o*34hvjYNA3MNn<;?ffTTh*;y0`cG-f4Zzn} z)BiMWf0QLgD^Aj*V(yw*9=rejysj_y)-3KEPNf=mgwM^@-!g$>MZp?$ws|%JNcue@ z_;BGd2l}>Rp|?bbG-IZXHWd&KA^f4=oqZSc&||vwE&oSKXR|?F8aQH{>ZJBko5{qGD{8l0q-!>j4q z-4kKN_&dE316fZ`x-cO)=Nn+HfI{_=gT|mRhN=j&y9IlV=H)MSbM?=fMI#@UXTwmVbFC0>%mF`yp1)bJnyH{hUU5(jg-tQGM9UVQ8sUNuc<` zp=lq)(Xp#<)Lla8P@-wl1{iYMnZsM9=UfEY(r_rG`Tp`5a}HX?iwJ6%A4@ zpFHmUkWInBk9;oAfk}uFu}wF-VZWIHe?MMGp= zlO8Lp2OR?_ccQ(nEfr;So^Q;|=8zy581jmbQ-u?i-A?LMxF=mEqC{+hwW6Q($`P@6 zcHD*Y8b>thm|0(ih|!T#2(2odf2ihzPTCY(v>-@4Cz>ttJMZ*Y%WDiRiuoUI zoLYQUHylx$P>75-$k#3Z-7!1T>&tzeACWEz- zPwu-IAl?Gc11>?veMVWqe?*!Z5~ZmqsA(a95$ZNSqox%So~PGW;E%I$E5nWe2bCTM6IpZ&*x2UaUmGP zK5q;U>qXN{Oe|$4g^?`msAoe>HdnSaeRC1Yxyyy0uHzQ1^({T^E2cDP9>Vp_$_T&n zMaHs(sI%00W!~siWc?plT+*kQ(JOn&6tsJTNR*PK%J4Gkf5iQ75?SUvFrj9QwYE+r ztZtLu**`B@+iptlO4q(GgC81?SfM5^18^5(uPFwTopXffQM)cO;9dXju=w%D3ItYe zDZfp!J^Vt-x59}bw6F^TA5vszT5u9cK|tFVkJ^nVno!juAxf~R;>8ITfb6FugIY91 zhz8}ET_TQUe+4{TKaeIrM-Uw#YbRkZR%0cJx^r1KmaIt9e?_7eDF?D%xLA&pW z?s$Bs4(CJ)Yt-?!1EUUadkhTFh3-dzTHD8ByJ3Uyz0pw zyEcFOe^I$lF!W1D|Kk{=HM-B6L=&L~VOr=_W@GIdV$VV{fXTsJb~syr%chdJO>+It zlS_UC9X<`KZA}zvrWWP})7wZpi{X|E4Qhb6+f_)1B?^m90~|=PG=xi1ncSyVt>lDF~lT!3O3?sKgE9Znumjhf1CA|xhf#SIKJUr(l~{v2C{Nhk^UJS zDXI)VRp5(yCH)G%m7^aT*;ly!Pycr@!Tg&)QkJ&?F>xJ!>u&*)a|6;EY`F?+k_;1? zMR3YO@7U@Q7}~z$Gh@!TSD!|us2@h<3f7N#OShVpe2|c6YHattD=^H>(&QJZj$})M zf9hycK2-*Ohf2nMOR$IuO#9+mJ&;z+Fb%NUlBYu1hsG_`m5Qn~+VqAAq zNN4VE4I?^ZF=l@s&!3I@)tMmk+U^pce@YodEzFs*+u9lqD)QC-iWVzN+`V(Ps=d_G zYhOoFkT}N*yI!ZXr!=k|&RM^)fLO{qcp9E&OL>b zq23SV5OFw5N+E)e9iAP^jIb4OKBms2JuRvVzl;=4CsPlHjZX<$fBC0On(rVX0)B5y#Xu(fhhcRe`B4f&TAgI_ zU!L%4GRR@HDdk`rC@}qu0nv$wfEKww^gURxFivqj)J8x|g-v3(xMFwYHNiM`{()Nj za2_tN2g6OX5=nHFhOOh`q$|EJfA0y|s;!DWo4@b+pC0|xP4{0mTO zH^kyMvE-o4Qgk$uzPolW9mNn(&rU_&(%b*6lzG1W03z3#jZJGZ1rQICH4lDE3k2gn!e~(+eltB zOUkX@G8z8Ts#=!m!~d%R^M+O?zFm{Tvj67zQ{Y~>g83(8cYRpn zdz;lDPS75as<_MJe;FGWriQ_)sW77fIo!bU`pG&%f-UXzJ;x|A=fucg(gaOCj9XdN-T) zr9y4lCFXf7t9pa6`jxOb73WBTx`RTM(xbh($ZRZS%<}lMg9hr%7Uc*mSNqowEKdMt zb9{?sGhhCsth3Gip0kLE4iH6fyEGv{~8teV}2cZDue{d~yyvA!!!R0#|&{@-Lz|R*( z84235s;2|1yyI-W0xIUa66UaegLoFTtMH^(^|T99~}6bA8UBB%YKGncT(;3ce% zw5(=nE;#R=U4AozR#J@D=EDFaGu z33&RpI~!;X6g&m;|Ge_d_Ful&1NtL@&3za3LK46?)j=WPPR30?upOv<4t)Epe^_+~ ze}4JmL>}DskN%nn*xWRDyX{}G$K5>04+L_Z?Ir?g-=tpgW9YMf-aWepV1QJxe<_dv}{jA<>|11;$H$-lOf4;gSfm$y&*K*Dn!ToMRMO%6qbfBjAg#TY_1)jfnbbz@7B>hpVNy<35D6f9fjfb^412cBHZ_`G(Mdavpjc<(BAMDNxg0Q7XWc%dVmG?sk~56bcWBT|S%fui`+pd$(psM#qmzvmV&eK+q*t4gMu z5mHy;C+v8&XUpjFmYXYgCNz7)f;ilU1@sro0<6~SB2Rkf6ish1x9`m?uBpIVv;2dW zG*0qwrqJ>O5!MJ<@-wc+e{FQ@3`omSVgNf1I-MZNMlWbyAN=fVx^nE@{*n>b#hvw? zB_u0j_nMFFw8VZQ&$8Vie1jfld1oya>j5${Nzh@d+@p*&OIevX|IBRdw6ZVVcG zp_Cj5TBn63NkIPN_KI?c>I!&ZMwa5`f7>rc?5dT*e+HE+ z0Ze;$Ii9od8n(PNxE=%|94iEk2HC8LFA6rF+!(v+oLIW0j6}Up(>C&c01h*n03||T zZXna!Y?aEowoVkmhHK*^FoqbtdWYye>#m%;Q)+LY#E^w0g~SLE$1D= zgdA#Ug2BANp(sgDBZ^VpaYP0(sLT#AILlUo02ePg)ZFbUgfKe-NSWfValez7KUuMO zZci~cxY!``@sL56+B@zmAd&>gF$1_?maGhKJfzGWeQUz}f8kT*23~4YkPFvgoQcIi zeXh)WX9%q)@C6{PB8Vi^6&v?^R-bFbS%nwxePMY@m#G>Evx_e1fJv;s@Q0!Cx20R= zSGHd66FV<$-EZF&*=?4D03Y3_Zed{BN#I$>Q_YuQ$urNt{KnINyYQO_yT91k)%!6w z_!Im*bdSXDe;t3Uo%}nAQK^xNh)?=1-@IO+_e$oPXxSQfI2Cfyk%nJ`=Yp|4PtJJv zpl6>3R=aRrin37;4-Q8Ske(QgQ;0v>9DXjgeO>^8|0Tr^hY9NhI0%R;Hpu@X1?B%O zg^aPOqlvY#gX{k}{l7LOZ2pf8TNw}yW(MN=Sn1$Te}yn$*feu5;AS}stktpP6B$>l zmeTrm*Lcz4&uzB&D+oLoJp8T};@&UkNu^fQ02xg0s7iU}Kkrpq)%>vc{lG8d_qRnq zjcc?P&C3tckpxHhRRC)oQHczZO~*tl;c9u8ZTZp9>j8>M2ux94sCW=+O_C;QK*i!aNhTg$-YgnMH9MlS!4X<<6=SRv?twX8 zEm3#b@`p?#u5H>TM#OmTRP1vXF~sA9dJC-cvps&A%N(#(31ke-;rH~PYBl>B`4VdT z6@ll%HE}xiK(0&opT9nq&)^{2U2zYzjFa>uf7)sp7k9x5Fn-g|-&5(XKjC@9&vBOyc<7xwVu_W5sn4zaT6UE|hi^t0`aO z_>tTuqPOlfKb1)0dnyps{_PvZ0G&cc0F zKJ@MG{_bFl`DmG7!PAS)>5*NC~j8P)L5*Fal66tdQiA-%wZuZGyafu18efX=(KN)e|qk1 z`j{r&1adBN0u?|Vr9rWT!w;+mt(mgCBZ3MwTg(X{d+>`vJgN2c^1)Jj^1$=1JBQ4% zok09M!$5wLK=g!)NM3Po&0W0?ca;BgZHPO^IFJN3=N(H#qY;mBiTgwVO-hE6kylLc zfaHb%&FHnv}E<3CEMWmfINZ3{5IUA2WE|LcFh-TOZ7Q@k2@e-6z0+`{tu zfpn^xuNpT^v%@cEEF8Y`A83X&>t=Yet@xC~u3MQ-LSK%<8B4_X<(caalkYo+?|xVB zHv8H9?>cdBsd~2XA0*WOS0t$aHzdRz-DLi&N+`JhHxt_br$S5u7>y=+&P1WovDYGt zv^s?Ur$ZD=rtAIgv-_#-f1h*QAf=>DPq~q4$XVko!ZnxzWU&nwvc9`%m0MBAvQ9M5 zks-AuO<}#WPG}T9pArjgZhf%lrgmd)Py;SVTlDr}@;@$H!->qAd@4j^p%P{@tJW!9 zfILEBSduu&!X%{h5Nu}VRsw3vCjtCBx34pKJl>6Xs&V%?5e{8jf5ZzEzJ9gjsG@Q1 z)f~AsN`FhNt<1ft7}PW*erUvO^CV-XR9kXd(PUp+W9{Mej}$E4UDiE9?vKbe!ZhAr zIcd$xf9m-`xlis=)D%0VQ{sE0mkOSH#%#yA=E*AiF5ahn5;QH_2|>22qMBG|V%@E3 zi>suOh{s`uHHCzRf6Q#KS`cat3*#(6icm!ha2@h+1bX}0bM@4`jRD+HrP`xjytwsc zDW!3MbMfmVE)EGW*9tJcJT@HE7z<9=vu2Y=kZCaTf{)*cR#0HAM4h1vZPG$p=leoG zI5m7VLQD**N1JxS0 zWcP1~6_vrSl@Z+-wh9LO)zyYcuDZ2wO)yVw#$Of*7oKnX{^j3 zBi6F=f5UZfNrL9<*<)0IgSdn3F3P<*B7J=-5`(#^;NXV{X^tV;mnxWNqAKxCJy@DE z-x_&)?NvYdlM!q&ece8i>A$e}zc$IKw@nV5G5TtBbajiwCRZ8bfX;L=_6vYk;8fOp z;t3dXhjhoi8i9P2CccN(ozflB=38EA!?vt0e`-`k7@r_J0KVkn&eA>t_m~#|z*FV* z%d^w+=h;Vm0D}w$%+eOVDA8z6huI&^B_C{nC1|uvoQ>MmuKj}y(FhQ1~iyU5xn7f z7a+OH7om7Gej9t~KUD{K3D5tnd84tI-v|0%jMeGfQ@KEZfM^r_Z;a9Y-;9ZSI~d#l z*GwdD?CSboipd+hxmbJsw`7`|4hPIAfBw7m4O@APRS! z*efggtExsV*uBzCs=%`DQd?N_be;C>! zS5mC@h(?3@=hoT`eh&IYc0{di=gw`j8ZX`x=^Gl%kfux*$Z~BTjzogf6#g9sr{aKggI^8vvZY)qVijQh6x)gPY%+4o# zsIbO~N9S5T9*x~<(~VQ{d?8Sh&fndqLhA5?xRzEa7hPv5ZTlBqC2_D$&^yJ}F#O1Ns}P8%$#XU$h@FU|Yuf^RaF9aK zGsRZ)GH760g<{GZBctWTf6C7Q??P>^f>&QyeP3RqZi)e5&W>a@G^nj#UC&EwK%Bhf zogHO&nS)A}bjG0PXxYM^Q$TDk-fG=(k(2u${(4?x^?*R!NsZsP6q&jbNpF=9$=#z$K$$0{F3^A@rum z_wfMzUnz7R2F5b}r%dP}|8FT|{a;cjX71qT;%IGVZ1>+;bhQ7^x4ZrSj33(xIlL%+ zLW;)Tjyk`n){MZalVk)`n5xvOmR>;DM$ER4siFVo-z?@ge-5&nybu^1DK*=^{$yUijsg7u1 z9J{Q`hdhsvX^(aMSf;2ISpv0X1`eSZC*lASRI6sWXA=1Rku0f~W~9qZhqI%uIE3d^ zAU#zwF}w`b{G;AQw4H%cQjC66x4uqgy#?lR{R24Df5w*@5a{fln}*oiLVfMES`|%X zWbz``!#J~Lhs$4BOh!Dzef9*d3&Mrp$Ldjrrr%|FLI#&{Pkl4#Y z`p4%QIpm`r>P3!b9axjH1%1X(H^2)c@={ae+^l?YHC3wULG7T+nz}}pRmn zD4l)88hWp{6Gf{$cUA1z;OE-&XabwN}1aN6B)m*eWG%_KGNgE$&3%`!U`sAp)x$g(-T;n`9E4!Ng z;nK^RIb*%kALZw_%F`RGWgA-0b`|5RkF$m7uj|5?faWT`zfm_ z0%?5yL(`@%4*F}OIuyGdAw;iY86dZ566d(0T357sm$gW>q$1?9M_0&vfT=TMRS)1h z>j~h2Y#)z@1y3<}4Z&e&1HA~q^o4r2)3c03br>&01muK=j}ItWp#017_Lw{&e+(|2 z1F#V2wddtV#G@ukb+Q&2=Ci^+{o*cpHPF!fNjp#XQe+pkETCyNv*#{sPBN&&KB1Y<9<^jVHiBTRq-ipkK znPU+BbSLYBaWKVu*|?-(%Qyk0Il5Y(DDptRM*4bDY@_q7qV;gbOU2s2I*t0o6kk1a zYpHLXF`ws##HZ3*7`K>_M!sI+@!qlKCblF6%Y_?O5!;+zOy}vaxl%QHf9A-gm8D_! z+lZT_^h|osrghSwcIqx&5vRe#O`!}`>VyG}V&?N#{%Hvym5@Gf4sa2?}&ekvaFJB!9$Y0T7s<|9l3DOm*NaI1VA#86f9aFGx^la^Zy zQ~qNargQ*E6>eRqo^}QvehdcxL;AGair2QWh|q2b!te;B@5p4QOwHD349&u5%VTu)Et?5-jHDrzM7ekt!UW6bulD{9PU z?ZFho(@kvT8+RJ4);@!WfE+veYuv!1n~Xgp=vn`;0`5&{)@ykZepriw&y{Rf*vE#+ zn4Xl8k6d+pB6P*qba^`iA_<^0;?bs*>+_=lyH7n`)m5I9e@S6{+$WfOo>A5Aw`xf6 z_dkdN$;U2upcqL&?TK9Xjb;aPRo$Zw*lL#Tq9*>7Q7-o_jFcUr7GG(x_S~z#he4r5 z?Ds#Yfkz7U`vD(2DQq2*CJr&)&*MqZS3&`W=fV*%zVvAbWecwD=K|F?+uT zrudhi19$UF1>#)q`RV?lF#m-T2rU!$it_|gH(ystWnJ}99*NFq@%R)l?>w-ghg=kK z&?J^Tk2E~GF~>zNxJ!|TUgefS&p00nD>sdB@d1P%e-3oFyr3Lh9F$pPF&}izi)@x$k7N|uXZ;85{LQrz6r73dzW#$ONCAxN z_^c2A>h;~om%f@&oRvQLy+|QsF^fo9_(vTku_TQ9<`hFuR+t3g56UeJnDY%VWHv{y zT|-Hcf1D%7LpJYV2_qv{=o(42-4CxD+xIdV?vE4nFBfu`%A=$B>=5E{|ILLM{>6pF zjGew5NYGsWuSP-C*1^#DKU))B+dOsz-_Gy)&2+5_1gwi7r7;Qj`uMUO<^}C90L%=t zsz4le@25V`*x1s7Sa<%ZmTAJn5#WPN?_<&Wf9Xd_ZYR1tVVfAEwe+K29jjdEo)DO_|%y(1uremVqy+rsdR z&W*atQ#g6Ka%)^^=GvesvpPi-9H@5V+Vja8-9B0s#uAxY)atJ_4^~JyV4xil)Ke-e zfAvCQ@EMBhkHh7(u0u&{maQMw4_ge&)uL^csLoU)Il)-?u=*u=d+M8n1mON7YjcR2a}6;5z6W@G@oloL>#HB`zls*se2-^e+ME?GCSx>N4`6B*ut2h8BU zX#ncwa@6=|>mIl^qCzXHM2RcPE%Oi5e;%=?$s`d~m@2j>T`Y%!(0Od)duBusT^`7} z+-}v@Ai~Tuqw<&c{q@Kt(Ax$XeY{lF|0=c~6 zIK7R>Sa0TLmm%Um+AGTK@PLq>zr6T4Gd}^nPT2Blv;(!(9Cvxr_>9$dwlFS4O$d!~e`E^@*K&A+fk6 zSF8p2o1p&$7L`;Jq8*`DJIY_tn4=jCv$O{R@BK1MTe+WQM8M<*A z*%!t%g@$h@Ni!E&g&XiIx0?+WsRVi;z{`$Lr2^nEo@;hHAx`egPN4@gY$<~u zx#|HKo^d?)%KOP^nUrkefYHr@rpz8{s?!L217hpd=+vGGe!pneVk_znl?}yA<``^A zVLGLw_0YWinti@cM7BN6u2|i#bbeVvp2KTE-DfZ{|JPu`{6AZQf0%>5i@B5g|KJ@t_!ZX75`CMiyn2Qc=FW_GJltn_f4ww5Zh;G+OPbdf0i6=W z9v+W!BDG9-$+AENQJ9x){?oS$BNCur6d>757)xOCW^0Y+Nf>o{+a5+T<0lgi`>-AT zo;?T7Vf*S40Z{ItfGbz2h<2x;J4~cTPSwCFrN{PC`7$+_Mg23J3UrE&PBMb(NARhC z^2F%#kU{KsfB1NE$Qc{#eykj4(D~-<05qeD&06wQ_Nc*fXFKgF|Isv*fGU&v2v&_V6mbIC(dc;j^0pi{ zVKd!Pe_If5lRc?z*8y@o2B^)?Ht$znYwj+v*v6a3)7#tii_8;tkg{`C5G%f_&&TP= zh41+Fi=Dywv#oyDm!c(N2Z_{`Fx!Km-_~Z*$o#Nu281F)OfJa_|(m}x|PKDrA8+R_-E=*HCp~-co6=-sqx!?SEGQTle4~) zt%D<-;@?74Fg7uEFt+(G1uE;>rqLt#ZWMhf5K8Zzodi|R9Nu#zU-E<(05aH(g`G)O zfBfah)#V47)NF~yeRcNZ_~6s|YipLwb#)c!GQ*t1QvRYVq-eSNus@q}SSO#iy~!h? z)UtLEr_P~sSiodtuDRR-Mg?ZoJeG=lQXe2oA+G6~Y4djm0gy2wVd4k^p_xLrio5;w zo0dw)*2#p@Yaqd&;5nX2FYTLSH>6^|f4o_q_cY_bpc1rxqOkqe$EepBHci|v7*d_+ zojtO=tGRQYRrvwEQX`7ie+Y85NV$>U^wvCv%2o3bgR`mDgQTxm39`YSwhF?t%Tp;} zbB(${$GRamVedSC2ykeTz-CRMoUzTh5O!hv2I)5#O9M4oRNe}YDw z59!v!-IS|gT7jdSTHq-B@^@d^?|ePuG*T1%XfnVM7!xEs(+F~b2sGJOGTgifpaE5E zTL|D|!gEMLO;Q_MtIJkCU}vGzi#94ro3w2~MT^Q5tTPufc8KhKj?MRrcnDhOE{-~Y zz@;4t}*!pS1yL$=!L5niW;!njh`F!t&oW$L>AM z-sRTSZ={yYivC#A>UC^N6*|B+@;!rXy)@GJ2H`#%B_E^fW9A-f-8NKqf4=6iL4egs zqe9Os6`sem*ja1_Y(CatD|*gtG|Iuc*`ipcEO$eFBLV3=m2X&`{pChB@WPy3WI7ZS zht)KB<>pbUuu(k!S!3bwi9z2w#r0hv(_TZsXWzG8GQ6Kbzo5qK^9=F@0ss($_&2C& z{}pO!TUTjg7vsMsVsa9~e}AK`vSss$_Iu|i+I$r#U5liFP{qtLab(5{`8M$U{t|6K z;}OWyyl>-`!@o#1RZHSj5O_E2JGgw`*<;twQ?aa@j{~ikaGpVk*J+I?mW_iueVz_w zF0C_NR!EOUN>nimXUP#mQ^E33(MJ=4m1DmfSjcF0zdSf3>H9;3e<7o28-idi)AmwT zEU*boKD2Kz>6RMvLlOc8y3n$|J}1$$5-@OG5z|#7UfG-OEL@wAD_|{_YNM z8FOMlcpEUrHtVRCf6?d);8ah!T=}bX*iO-m)Fo-_XP5OLmAJ|8Y{uR!0kIi&dqbzl z!oEllp3IG(Wuh+UOJs0)hbfMSaoeC~l~wZ2@6|u0s$E zeCsAcDCw*oJit2nyS<=DZJAUkCTDJ}x1&XOljq9;uGHi7#Vwv8Gz{9Q%fP#$jkanElQ)keZ+ z9A+Iey;Jae893ggnrF%)#1@l92II;(InX&=5Ett%+lVe0zXays>-Rz|!j_jj76L1M z1?jVmOOvl%f6R~Z6n$|*AnQ_LJgILnGXfhfR-NRKsMV>~?dyY#LrR3xA6# z&VWvL3BM5Il94;y@VgqyE{7ReNf=$_I)2p=AH8MN2)nEq>sy}1|8$| zK799w+oG$OixxHc5zNe+DVmd_5fV`1?1soCc;9gNf64d+-|5P|AAZE^+Fu*wGCC~C zkWa)9{}u7C)r+!|xs|z-xv?Xig7M!2UL|wuzot5h?ly*I4z@Pt9>xw|c-Jehed3MM zv7xATE<*)c?H7X&nBY=VCY?He4hX@}7hc1(6Il1X(-1s2e~eZ6%xLST_lhHnFG|M4 z*9>Hte`(Eulu6p#A2F^#!(QF=ac~FSHtgc2Zf&7>hpKkmF8(o)L}Es-&ZJETTTSGR zJ*vWVLj6Gyp3R8(nnIgijp>fTa-HWBF znakEk3HxMCAZbqmHRy)NN)H*&JkMZugUIk$Tp8OYhuA>|&=2iA=p_|NHcT6+yr-?i zC zAO}cuW7-a8X-J6-x_kJUAEucl30Gc$U^S~=b_RKk#eM$4v5vKGVzM)EGrNmc>+XUs z1&y0E)uX=w2NfFomg!~qVQ67ZR2+!n67@aFSysCU1VB;uAKe|z>8V|7NYT29iR})< z@xCPKD&CCWh1AgPccpNG?VC9BCX$uCqz0lNLl{N9u$yN$49r8Lo!oVWShAtM&MiN; z5Acn_IiBY4f8)cQ{T2^jz7gu`lCV6Tz->Qb)}MmX3SP;uY(Nq(c=oH=Tm=tA7q;YD z{}cenh&bWpruwem-SD}BJVz>&o(kD@SuN0iA!1rnj6{MY&zAo_Iz8*BXU2%E@vQ@*jI4Yhkh-0$}5+sSx@s(i-{C+Ih_zM`kPk)KF7}MkmJcWTawAO7@tyE_R3%;)rO1Y6X zK6m|M6H4#hL7=#CGH)fr(bR-N(i>)qaF63A5xnC5(jSG|2Hcg$XUcWpFW=d0jA;N$ zL>g83xv27kRWPoM3kScyp8T}Q!x@tv(l7x^tQJr50GNM;-9=qWm1ebW34r_>*h7tJ zGbl^eKk_FfV7V~EEhgwFK)K~6KN|AKIN{fm+#0V7OJC)$SIYE(Yr}yrw-r9ONl5jQwG(*gcp9=>M{7)KIWpx!;6(26 z`%v$%4Q{wFKDE`TWueNP@(2!3L)uBPQ{&K{2YHz6MXPJx+Jru71$++`ZMC|C^*NwC zYBUlr$iREa%j-NR`4&_f88R0!*h8*g;m|U0X3Uw{NOyL1XP(qd+EPy+=nFGwWQeN} zP?p&YW{CQrNyJFj`?g-%oLJ|qX=}d!TcPbhfo>U>o??rII+Zk9XFsn~dmzo-Z_iGYkrs-6ENiX8e2U4Q-;$rCs+4Jhm}8;F{M6Nq{FK|5HF z?!FVc=ouGHG;_wxoVElH;zQ~<)O_bezR+s*rw)QO9b1=8lS=xW*%Bu#H2*alCB1%Z zabgk*2iQyx&Yj#tTw{gJ#KP-Jldoj~cVYyo4*t zAMTi6=~zFPC4C-40zo4rEoX?`MZ!Eo#MBjwXmQFxmD4Y|35(V+ZZ1pq>+{66hnqgh49CL{(nmx!Ag&IyzA8ST z|GS)TPx55ATf-h>(;KO9#=E=9vP+RRv zYSyFI1c}Wesz%yv$~y$DP#@YCo3*~8FojQ{jsU-0{S8}ecu81ULQ`2%lx{OqjY&T; z-eLqsx#lh68(#wS&7pP*R6T6*qKDT(7l?~-Lhbg%n1Lo z(>+~`#EXuG{yG68QQxV?%o~V9?_i+@!NKM zWt=sfH>vK`N03)@cX(^`k4Es71y4JMMQ`y--bN67n9?{;ne7N6OEJ4}BE?&n{f4hV z_@Rd?Y@p+C-cs2DI+ap%7S2`fogf3ryuPw2NC%7jtz`CC_S?n^U(f>xs9@_4(0wk` zipXb}{j@tc@ol0B)X&I)N4aXo(Oaax5xUG99bbACjB%|!iYo)EvjoJyo4!uaewdPy zWogIBUQi-o{5S(HRa@ZAaLr8KiJzuf4TJ*lsQ|VtA5Bn04lX_Z9(&r`CiG1NbdURQ zG33^O?gH|+2gQjy$@D_5H@96DA_O}mqZAiET{fJ!)v)HOv6s!8@~wX7q;-LA3V)X< zza{%|XPITtaCSOh0_lwrXg4{G?-lXz9hw3opBj9v-7Q81#HzP0cyH(uppQL~U~ga4 zaDWE18`VKiwchx%8U_JYZUr?6#r&g9UbCptB31ZE*^jH(#Ny-mRXldmlmH&oLgzIm zESL$6mpGAx_Vy@_RiwF+bb0(~`*(DSHW8zWhGUET!=q4#Wt5t@*Pn5gKZ!aZ>2)p% zwX4o|3`mnzp=tfXyEvdZoy6!O3hMYJ6#*?F2-L>buaKe#F>qvgkmyV}j3rr-_xloP zw+E<0UN6c*wd>X$v#2xhvg9e4c+QEwzm4j0T|FYF;=KIxg)x%K^&F9_K}A?-I#ow5 zq#d^$FHIjtobyeAXgwMfUn%F9&QRZ3`BQ1ZsF`P6}ERpZ8Z1WSx6q>@&GN{ zy5N_h^Rv)g;;FTVh}ap7;YsNTq(qp1ILk-!cW&m6dNn~fCC%ccGFcl@V=$WUB#H3L zQLLE0f6ijoOG$gVP$6zNHs3Tu>fFe{W}pptK(CkxiCsxmFx8=Rh816% zS7uN99Ah+8c5SvG?;rRv4c+m`tsqVlCEZZ>$cfF92q1Lv3GIhM=D~Q;vkOb2x9><0 zoK3f}>9j0rmvsIK;Co$EoP2>3=jLNXyO*_WCqJ^MrU_Na^Q7i$B8FKtIe;%`eCfpP zaML57AG}2L`*(;fy?cY%(S^Ar+;dUZb1NMIJI=&huA&1?MU&QpD`ouN<%CkdmNT50 zHx%?9)=(0=lF7AlS0xr;>-I~|c{65Rc@SWe`*n13{BWU(^s#S=1m^1wP8)ywSv0A-Pd<{t#Ak5FbI)(#YKwOo1@KS7Ox#es5fD(TXA0#P}X zhJIF37EukjmKf?Yoo#tszpk)plBwNBA^N|tKS=%|>)eW+S+!hts{(ct#frP2aU(#O zUWGTx*0MRN(VwmdeY`5t75_?bgvF{bbxVBITAv4wX!CZ(C#Hv)4J0M)`+__|eMq0z zAsh-0IM;r^dV^Kes01Rt6vByqII9M;PQe)Z9U+aj7GWtEPm!JK`pX%L^7D8cZ4wQ9uIVmSOuSvQ*uS6laHX}u#r5tJUeA%m35IHFVS3WvYA=+|)O zE16Is8Tf}vn~Kt}wj_9$nNqGUj_BEAg-j03-du`#2HtpQu^(`Sd2^B>xF4L9vpu61 ztiW7qdjGx*?rPLWY!F{RQ(~qQFUaRXV)j+ymG|ewAs?SKs`%|)5eJWI(!2%fHWB%Q z|ECp33vO@98{VSx3Moba^y3usro!vvo7=Uqys!0DoKLR{_b}#5_Bb{X@I3krzzlen?YCl&nS zB$oY-Se4e~X@1!^O?H%lx+J^nced%R17&`Rcw5V+oj*XIB6Tz?A)j7)>qC)-OQM#P z-tbLQG? z{EfDeF@v7y$&i2!fHxbMdHq<)GniZ*UfrXM`4X^eZ80d3^1gX3GSDi7XrM&b0ZmYq zOo;2#F9cAD^5Ipb%AldwCSM%<^=ZS6f45~t^mfseHoRbGe7 z;#NDRv^d4;AF1r7xjafw*X1vg^p>?9-OqmFY_L;EU2B6WtT0Hl$r9#N=sO-8MAIS4 z0`JFA-l4h;K0?vbrSN0bh~?F=n#MaAUhq-j`}h4NHQ`6;Vp6KdG8q54R+6%z_6WwY z&jwR+4UUj}2i$H2CT6nvWnxsAD|;Z*ztf7%x#HD4nKn<(9_+=+lNUXelj3>`T)BfZ zC2h-RA<8qcGnbM$a*25y!QJ&I!`>VJmVL4xUS=S|#6Q zO>BlS8t_c|1|lAc>CNZ`iyi069mkzHp%0+5lMIN`3afiAUU*3jZ7llf{$|CPUk$qWP-G^ za%^hf>!slvJ#JC7T`V@9c#2G!ToYBc5ZhMk9pF~FLvc}z;`RCUwsfR&{Pq}~*eu@KPTeOe zdf(0Qa(`fVBiGSco<8$JO`z5_q@SExMO5!Yp!_Tvb{Wu=W1&ckw3|H6Jb`MY4OS;J zBE4WHFnk1vvNqIB!sOKBbh9kDEj+7O%{Y0{<**#~m5`EoD)3=ddT%=gJ)Ki~qaE_U zWpbwHlPQ=}zF(E3-I*2WHelc&S)?DCL33Xu#%y|YWMKqfN zgsH=NDDS?}2^uAN&-O&k5dc_NJtz%s-UZ(+&I(uZx-a}jtRK{!pr6du(}z)xgiBBc zp0mtNt|Rs?HsE;7nBEoc{u;8FMo#BtvNNt1{_YUj5=^Km&OGuYCRQ^YK2FniV-JOi zis6D2>TKJ@5B+K3*Lb0u@6$2X;w@U4Zw~8TWjPVpFJ|xa6~^c2xc*Yo2`v?RKHiu?_@veUffpTzTB44-M%#r9-lo>`s|g zD+{wF9>j$^V>v9xsFM{7aLl) z_ZDfOoaEyeY(nTv)fsqwq4Z+Sc0|W$=79>UM@MHBj`R8A5BOKcCVY7PXq|^Br3t94?OKOI_ih}~ z!De1%j-52$PiB_hJP3ffPewQ*!5PL~ta6H3HyFZ3E$>?>2aEKhNxa z_>SqGPjngB1XeItHrH+HSuL_~0nx#P`@cW;t7TrYop0u>TS{d~ zVbulAkT4iCI22Y38~8_gUM_M^mrv_#p5x-I1DAsndJnr^xk9%y;iIZSc$W-~72#)b zP@=-hOQn1p*F8{q)y7piwh6b$#7leb0-GN*QEkQZAb3We_Q-~$)>&lE78vZe)aeAX z#%^6Z9{le|Wyygya+My!th!>?tmlO9?dJjIxq3*JFX+p)y`}oQ3HZn9OnA*8_-vky z1DuWJ2G_>FKt1}!Upbq_#yRsh?(TYWM)jYnML4Txi&!9D1(B4=05?EqG=2qTmm;@1 zZmTrD2iM70eQf=B=3e7ZtpL=x&?%RvbDhWQOi|#_9$LT+yhh_IITA5xeR9 zf=$OJX*^absQj|%YUS7_3yUbL`DMwY`Gc$x7Z1o!c1EopR>H#%Grmx-CwlOn7KOCp zYEQ0O#Pzx~R;<#g?z9`is)*yB-TyqUocdr58-tvz<+bZcuB~F&d{i^9axw7|M&9)?j^wcha9%kk3@lo@~9 zaRyiqT{H6<`qh5~My|YF6)j5hslT5=-|cbGZe(ya1*`EfvMQ-Canp_{3U%T;&b`lx zUTqsky43I(L{z#NaJGr23{4&HSs>Hpvz40E=rS1{doksSeCv70euCjie}Qv10;a$u zL!y5@TiLyR8v1;~@rcrz8uD(B+X%)jSq(_IR#eQ@bT#I)kvK&^EmSKSZ#A6F2H-fv zpYURp2L-oHdewZ+fDknZ;WI0)>|K|uf~Q+#VHrg&#Az~X@`!PY^VQQNbBPN)J4D7c z&4uK@fjGEV99WYa(!*Z(fp#5t;joij-CRgV55nROb9CUjBJ$-i1@bScKn)=UDFUYt zmn`K7V8yaK{hajvBZ1+>;Wi4+c&eW17&5K;Xb$qf!yZEmhcBa*q=RMTQp^_RQ8JSC ztwccdit4j!pMxBPLClZ!%So1w@Eti1`Lwg;T9apA4Tu`)heSigOmJ+cpg!oAY^XIih z^XCRM&27h@Z>hNuN~#3M7F&g6X}?ewZSVbG+51ci(bJP$(2Kmrhs5UWvkLC4{E(OV z6c*JDvDDD1AGa$>KZZR`J-VM(+&M{=+~f8dcZ)uR(D5mtt?=$9B3mY0C>qe&42~W(3p@)UjZ`9}hTc^5 zg7CL*1W++{r;-iA($o2sm^J3zo2{I`3KQbwGmjRBGnzeh4MFu4D1ZW%T18x_5W|rD zBkBW@H(!6qW25^idXL5mUG^I*+p4lP$MfXT!QB@qaC47QXES*ln}jr-lRV4L-*$yvTr3Qk?4*L*kjU9e@)Z>+H~7>A zvV};5{W71b=7@|}WB@*hEcAD1$?RkY`2M64JD05ypZku1%$FJH4gTo5h!?}|mOblZ zSxW=|`qs>l{aEdXpvE-)BV>B28TBOpSE^^3X{cyUwUyO}Rfxl$J9k(`PmfBA4g39f z>tI8N_ul^P*^bS4#lM;*0m>4O2eD(*O&Y^iZmz4&`bd>7G{CX58e3-AzWGE&H_Gm2 zo}YCN=%aSyL^KK!oddQz`PL1Pq#1T^N3;CZ@NaFftlmqfrq-{b#E|LBr&GM-X{m}s z{y{tAi40&UdC0oRH%f>{5=CanP-oed_d8UHN-2Uw5o<9&c%Fs*-Oi!=BD&~$l@v7> z3&@ms?~08#2!MIe?zpynzIq*RM8Q1s<;x72qxkpvE$^FGX#4F3iTwn1vD0gFR~nxU z8~5AnZCVxI=D!s{D5C7Bo@ap~a8T{Ph>3Exke&RU&xvm*6jLJ^W)QM9o zm}>$bKXpGnJ0xa9LT+11`W$(Pus`mKy*bYDcmMWHHUJE99ZmB}jVf`VzF$~Ct_v-a zS2;Pn^b9`kbXLxCdO{_Bi})`3P-RZ>fZ-h>7*Ff_48>`XJ|VO7%It*UCaU*$f%E#wXifFJNF>qZ`KxjUOm+-;MHVpHYufzL{BatmLH}mf_ns$A8$p7lXP#{Qyd4+P)Xw z70^PW{K$C1_yF2uVP7w=t40^D+BP?8Xt>xP2sr3UcC!V^1;0jw%Tmt;!JwZ0(A1}N zFO|y7C8S6$+M_$|!ubidz%E+EsW!1UcTg9FL6H(T^$h_Br--I;;fBWdKo{AvIFwRD z*wci^+Nece9VKUuzmZcJQ+DDuVdY(tP78R@J&Au0$*-u`@Z#M0I7s069iNknc^+n} z2%sxSLj8ibIO~0%_C{)Wu@K1lM!fyNpLW!xjSS1osqwq%Vz>JHXL?KAvYL2;a$VeE zk9Q_Y30+7wXcqLYV%Lc7cD^GOlz?R{8#6BZg<hme&wcybVZ4`(p1HFqE`jpufPGr@;JTW{8!hX z2s!W@8EAWW@CFh&yeYi*y%!gLm3{EdCEc@G*oqP!8etQEON!eXisP|ZW4(x6M?DiS zJ39;ysr=(kr(5-aE!0BfZSjD}NZ{UR==*~bOFADeFE$@ebcPj*3+FYz+Vfft^ z^n z8|oA~tq*t_P%E?Ig8kK7<06FFdmrZvk25JGssVKIYzgPEP%D=nogEphl7PfRtIv2a zKBhICSgh}1OX`xEn2mUXW13|N3|L${-sF%7n(?Hrk;y=cl)CY9NDX#GlI#4UA9Bm`%E4G6NN$jLqYx~d|BCY49tUGkm zBQUlw&g>3bVO2ozty{q?`+=g6A?);igsv-UDYj*bFjIH)4Uz?SeI)uIOc}HjO?a|J z0$GW$h3KKzoG_W0+5zEfP=oGKn{FS872`0AA!dRO_{zSb`PE)pj1av@30N}s$XC20 zb`xZO11k{W!3{!vmNZe@z^F>Z=kgqFVW(eS%$#6dEAk;7-@BUypMhy)MjmtcZSbSj z`X4U5$zVlwb6roaGQ!xgc=(-uYBbN}vVq*HLH*ENkSKa%oV#1!TKF>aFa^2&219ja z8D?9MgNa^o@%+1Sv@7`&^sm}Z^x{uIjzHmv#B_Z-#on*W-t;24;&q?_{M-j+LPF%~X7eMSG*dq2@A(c5$*)&qvcDR#^SCzrmAlhac>RpW zhla2lcCD4F9HuE6q6x=xi<+C699MpR`yg6g{##3=ip%lE`sZJLHn^L)gOGZfn28Y`*hb znF5LyiHNz>IZ%Z(5b9J>vzJ&=Bt%xR3B{X>Ahvu%uj(dpMsB763qRHYWE}gbd{LfF z?CTB8KI?W$!$9YsX(eIsTQKR9HSb??U7(u8P_Uno-SJV=A*|yYco$rPi=Z2Vdxwy; zL@N+aqMulQ82mmlR5FFlo<1_D7j*dj&i8JEgQYBP# z=5t}5{2QXQGK141H&@fbEesA}(Wq1ygCP!mMEm9Ec3>=w!t2zKPc!GQ!T4aZ zNwTy-fB^6~=DPjuL(6T)<=L*D%_pX{P)L{16UIdf-nHkeR7Tlvnly94T~Pz;ah44> zO3bukz5WP2)x3PR<9oXI+N>r8$qXD(abY`#@GTt%^;%*ln%&t2{4Qn((Q$N<7mL}= z}f-!b%$eaARb|@}cOFYaG{Y$FLi-&@)Zp4#?HR ze7gE#9y|EM9e@5oug878OMB)@R*Op6psVqjvh<{OG*jz)+8+y|TiIJ) zmAnn6$y&GlwVk?a_7wQQXHd-^w`bciooS=npvXJZ#+d1#SPAa9E~3Gp^N$Kaw@RV` zB;iBARX?ftL~}e8zwqsBpFm;H7jF_=m-MBhWGBv5c$WXV=Ob}A+rDI@h$w`M49WRp zvWZHux&8g_DOV3yg?Tj?0b8_PUYz=5f3=ee;RbWU2x?Nw21q^Igu3mnN_FV3$HC91>Kf?)-O0Irw zf7b(NRsAC$(=XJb$#P2>-7s>8d^OetwNF%<8|r-@0AKOSS+BKO@2*By8&*5|tyHtw zyz~voI-V`kmvV2A;{PFjRJdjlIju%6tWG>&6wRKw?f3fGwPG1iJ_*(kg7DA?q~Q;I z?9}>xw|9`ARLCZH%${`k`ZOUtsxMOt^Waxj=Br40*Y#%&kAJTg_Mp-yZttH!7Tz9o z1Y+jg0-`S>5sr5LrGK%ZY*lJaa`kY=7>KqygQmKw8j8}9-uOrwYVeVxG?~y$jT^Y* zXt!pNinltL?XA_AIV~QKocPuG zB3b!TQq;i5WMb57-h2AY)w;e6e#f0yskZc3P^*A^yi#(~c8#UAui4-FN7LuT7%}R{ z&oT>ZzJS|5`Sl-a@s&fEY$Z#r5|7MR#fmiCovz)pwo#B@k~&j|_Pk!azy$V1#>Yu< zz-7|$y$cd!5GJBJj)siI0_A$gm58(A{)8@7nTbtP$DZ867>%S3bCoa~Ec4h{;fo7* zWmK(1oRGlyvSH-;wu*Czr)5Pe7C3n)YIl*r_+p9;`un^my|oq=pFlu~1{(OH67L6X zkVOUE-;4}W)3r7m!~Ak`;2-=d^+hNfbbT^OXi+h|4sp)oX%3V=4N~gK|2dS!=m+Ue zG6|F=uR$s}7BViax&R$xTK0%Gx`N(`aBrWw(QFn!68X-y%6qIhBEg=j%gv@E;?~-r zyOel)%n<=-E}%i7#wv%l9bzA*zIX32pkhqhqoVf*vy~V^eHVHH5Dp7XO|L?IleTdr)(rse2GoPVa&9c2aF(cuP#wqOf13X z+Po`A;>ng_f^+um>56GSZ@b}jNgdwW5DX>%<(Bn4db>D5UrZD9?g2W!9(%Sk{A0WD ztBa-(@gE5`AqngO0|Ft2ovHP6`L{urV%WRF1~h8q-+>I*(^hk)ogONh`O=)-!<`?} z6U#q9&agsEccmki43>u4f#2R~sxI?ub2TVPlqk4O+hS&RSn)GcQ}Vf>3z|v&iC5M| z5^uS}7fw+VKC#1itKK?yzq{10I64jV4$cy$a=>OplpA(3fv~t!lj{o>HDN)D1 z040;x>qT3UzT&aeERol?|^clxK zTsx;e`PP=n;UU9rT2-{0nFfqwsH%?wHHoycu zd+f;-O>Jn0q)D;M-h571FqS%zFuK-!-@9e7Zo85JWMnFOo9_?#gicNS9w^OVpYJZk=>{>Xj$huC7=SiBG)mm zad-sfRAK8zD3qx1tZ6q>)Gn{6`(?Mttk>&RZ&vEsCB}~O)Tql~cZRefHb^?f09##B zxi}SwsDpcDWnUeVJIaePeP)>K%abFwmQQJAu!Vo|G9#nMD8N2Zr$G<(xv*$&kZ_@r zvk3mf>Pch8zzTsDFm)0jcEuJY&xv{76*FOdUKJX|dNM%6b+IsX7LQ?@eY&XEm}=py zvwt|)N@Pw>xi)|-k|&yAPf!3p`<_QE7MlVP&K@Iml7bsGUqZ(=@bIm8_`~F!%jL@i zR}+1i3#1ys61h!VLlA*8n`lo$-Xn(JEA*X;WD3!{j7xh8wTe6ckt=ek8m{d~Zl*oF zDOmjlE2G^-ZJvG^KWdTQ#A(T&326n(Ln%t-J2J&x#aKpEj0$3-XkU`ZU+Kgw!|Vj8 zV=L;xC^yB&m4iGCPT84@va+Wk9aClNU{Y@HD;1LD${mU*&wTwZn6SgOO;_^Q2?y!= zjD))->tk&^Zpuardpcxh)N;|0doU}x(%%iHp|(2mR}z&@40_oBC7t?CN6kXRiJ_Sv zQywz%{ElEs=_14tpm`JLKw|Pnp|lBX29^B9qOR*iZ7_@zI>3)(SxV1@Le!b?jR=I4 z7?znnGRGv>^b@Ucj_&uhzLu?8MZvm9vBA{K4w5GCN{eMp{)F`qznGIdTp9IMB0=iZ z?}r?MKC`4&$**;`e{14y_H&bxCjbo!qZQ8yj`#O=!=@kHHtaV|!cp6yXsw{8cecb3Xf z{gM~ia#x~~#VK6;Jh=E4I%fy?(JdD!37zFOG_=|G9sbC<<$YtFR`|JB(}r1c=d8GM z3i&s?ec_psvtmUpc}CHR%gQ+hv-#en^OY(m@0FW@Ps-idq*fg-*Q#0@8-7Z9G_#qy zI%(%+;Uk$*=lTWjm)I{lP-)s2)5q%+S_kl8b9hqDsh^b?Mwj%e`Fy1oJ85<|8D7;L`Ud2_)lMSYO?Pucu&xU)GF>CTBMEaL7A^rf!n%^ZvoBZr=*;6^fn4F*&8oFxUcGi(_Bs$9POwM$ke=pJ*o+)daV!e5 zol=OAI(SP$m?tR*#2w5^t!abj+_GW;rBs5u<(#LCQ`DPYO!ZV~Ei7CVCXYDq8Pqz? zpnH4slOo^g1=|-uV|w0pPV#L@%*w#-FWr8c#CckNn#ZdA(!dpUATp}A(k_~&Sy#Jbev*x*j@D6tPq1xv1PB;o zOaf~VTXw2H7~59yA#>T)^ik~1AR}+{lU{ivm~rDq^r{|UM`gFI6g2h=gwi0!o*4xE zjA92$fBud9MB@g{H(<8L_|v_jA4BqRc&}xW!z~h;&-@}qcSwd;Cf1p}w^>=lW&gU4 zv^=Q(P`>eC!PJYXO&RS_@^}yI%~IA-cykNEpw}=n)nnC9xZ7~{>O0zrc6;A{4c#kH-omV+F7F?(?48WPvHV*qFlD|8=HY#Xroi(&&zzp-n<5!5$;PZSN)wL@nsT6{2)QwZ0&{HK}V7n2M zKYaw8z#){zVRWk4qh`v#Deg({n#EcRh?~QpfI9JteMu54#0N~D&yu;9iHTNGP>CRa z7dgiK!JKF-q|5crX$b{!8xD#ep#ZIICxXgi3OjbFq?{ZcTv=eqT7zu=>2vozn@2S} zz}9n7!cn$_V(GcqVTY3IgVT8FAftg>Ba(&$xddk2JSBkY1v+*ZOZk7%Y) zj8cRfbu>sC9YS}4bh+kez5Vgb><1*Oj#J=ZiSs!l=%@`N+>nU-z1@+huj`LNg+&cn z93MglVN#te+sP0*SzL$5Y0m$RAju7Z|eK4CFMx05Stui4KB2mnrfL} z)+SV&=uIB0qYPd%Oa|`OX)lBqZ?2ugnVaKzGMo`3Y_TB*SXpYM|Hzkwp#Y*#$@0`J zvLzp*gN*tP&s``WJL5zYlXio3Bfa?Ad1$A^%jo&>-=CE!Np2Un5r{VHiafdF&Ff1wq2Md%u0`964QH zuFNUZCl5cTr;4_+9s<7XPQedkE(rH^w#Likab#w_m^G1UoO{A2J9o{i<}3NzykFn- z9Yu9yJo`&TFC}DoZEF5Xjx>K5c7_xY1d3#zI6^D4fXj+xVVaf=Y)4*M7DlHE!EX@TB2-j15`jTe)8 z|8Y;B&DX)%!Af`A`a$mcJxnmI6wfg&cK*hWq1RXp^Meg8X3{F^%oB|zZCMM^EWS7v z4O|HG^Vj#=74<>%J`O-g_*J4X0e2A2teyn5svwR>Qk=1TY_0}-DV^IRdIigZicyW_O{IETiV?rh76g|a4$aL-$GAKaHZe|mxoCgy9Ex29 zJh*rX297S#>To?=FXF2UWAey(7$m$8v*iC53{boqMX zDRneqR)$f81UeYYG5ZgVzyG$3uOjV4)uwWmF;0!PrlHS}(ci0C5e^Y~lbpCdjLk$; zm*St>>2;V3-oqlIjh#={sM&PhTX9}@GuP_S8{SEj#R87IIJwIr#cKWY(l!gr+`g+) z9MunM`z}leN!|@9#23C@FU40VXbP+3+;t2BJnQj0K2=vf$^Rg=_6ZY@znH~UD`|A@ zzE_GO$*6!_m+f^eT-O~T-{R7&B|989Z$uB+Ft6nZBhTR8bnCS~gjw(vm*rW~A5n~# zms=kmHUW^N^tq3b^@dZ7jQSb7=x1Tv+ev)fECQOZ@^T*>I~BF14dStNl4qPG`z;i} z*D(c4HjyZwR(+plxkk#$CH)F?pT{{FU(L(W$#@#e#?RNDdV!}^)sx3nk{;cX@{6~y z2qoz0W5J3UZISzx(weH+RSNqDp8fPWVueau8sM+kXDZZ-N-Ws;VxMN|uh36;n`(-5 zGBQR}jf}K;(71eeh4rpq3pcx7{xPCFurX(_jBuX>g zUZY~7&Jquu-A?6tl1Pj&mH4Nz-=Bk+3I!VS<+4M4Q798 zgjOE>g!zgW!=~$k7JAdQZnu;Ha^iLvK!CpZ_#v1$!`0TdeGlV?TV+{FLlH>dE*CAe z)4W3oa2Nh~bUA-xfnsO~__LRa;Q=;0sl&q`mMNGd@YYQxm*kR9d2k@OaV(5?i2wr)+9JYFt; z5;Hu$Oc|K^^1+B4zennAT7_;R${n_JZMZ$vNts>UNIa>9#wwu2s&GnNTx|^xShjcND@eNF{F5jOc66!*}sZ8XsU?<(eYzt!GQL?{b3{$!PHo(D{ zu}agLn(Mx(uyd7s{5C7|^6YojVzbcJ z{h4CU;V-q1POU2Gq1ve3u5lpP&CGAKprj}Mmyn{-sBhdt^VZoi(4?q3%Q`qEn#WnM z`D;DAt|;d>3+ZmM_N9(zmCk6XtCFWe8Y(>&Ys+ye6AYZ8^l#k#+f3P6MGI}hS)L?lIU@yGXUC@_@^Ep<7 zt77eN%OXtt<0g$lUltC`W{dl#hE8qc4yHA)=FSF`Z0i^f5cy;q$G50IeHS|I7|ae} z@xslUh0}4!Jo{madS-1iHFthwhgTIsbhL3TZb;&fDdVGG7n+y3uif4>4^Xgn;iya)Y1t>j+Uu%+AKj3>m zxS)avjMv|F3wdEcq_{*tTu@LNhC>PkS6jb$Aw37?_n%OqKoBy-KDF7uT0RC=P>=#P zvtkY|wkN+yf(mP(f%S?EuMwWMju|R;I*EqC7mI=tYlDEq=P6{D^Iy(<0k9NE|Bwx) zg)f1zYKP{A93;S9fj5Y;DFFy|sQeRe4J9Q#DZ+>g*3@7HAHO9?Zyy2}bx2z@BLC)$ zTwkPW^q5tSzF%=dcf1g$Mvn@gp^z+wA zn%dy!(jcx*J`}FVIL>oiqt>d%ax#cQ{NLdxKibk;c+bq{RJ?b=OV{uZqH^#{M!OM) zSFxl^*f*dwVDFOJZlnMoX6qdMP4R-Ub6}kU>XWze;pp&v?P?UM-t#0V9}zSwPe^Za zm1LO_6dZ*e4dQL3THvyTZ~V<< zvqE(Zby=76HbLARJw}d&u(MCM4D>U&D>^iw6-p-3z|HehWKr# zEHmhH_maJ5#FH}0yJ`X~^UsO6>1Y3UBcl8+&pA}x&Z&^Nadu25eENvnd(Ccg9nxan!5L|PPL?jK_U8& zD0VN!G3}q3`G1A-U-{1g`rmVI>MkV=2k}3fazY7RbKmViKvbN-L2&+i^Z$$dz?0I! z@lutkU=aT6#E9yj6Hcd8e<~Pq;vfIIUbw^@u>3Qa4h{l>_CH-IJX3qAU`YP!pf-s& zo8+G={+|l|e^lXKsi4#_IKe71|j%=s{dQfd8hJH!_blZXRs{2 wQ8H5hrV>UC0)qKJsw`-j)F0F^WdC_isa4efMvBFlIz|n{2_?h?^H2GI05Ls4AOHXW delta 78666 zcmV)6K*+zN?*XOR;qe_c<*AQb&84eu?`eJSa> zM9rSI#AuDiH%9L|w1oz6wf|n)ZFMe-Z*b1x+;cBCS$tPzum@wMR&zunf&x%N=Ta4O z^pY*Z8x&Z_RnAMTV2)a_C|IP4sF~0P9*wTSI0-iJM#?f#&(Y4gnqh3k4k~UVuTY-c zYEyCNucp8?e;1#;02~uC#T7W7bH{OK7}kR$I$Gvpu&lpK*&E~nLkSfqXEBW^{?%5} zwKZIQaU##u4oqdQihE{Iep@-Hnx=`GQLpp)DSlh8p8Hlqsk%`KK!^Eo2Zc6mx{@2i zO`G6zFgX@y!hpx}z?Wc$=qKiNbpMboQ5q9E4oMu6e`!Wy7E?C5eNXVk`_Axi)+YVX zX2&;j)2Rlq%T#jf*8X?567st?&9`7=q5EVP)R3<_V*dx6h13V68JV%kgvI16;K`s5 zU|=u1T}x>+o=y6~1Jv=yRZO3{rZ+u*f)4ZhvvlbXP)h>@6aWAK2mt6lflG0sylln* z002h;lePi#1L!`1ldJ;Sf95`cOA=&mWoTsp0DDIR02u%P0CQ<=b!=&FYcFDKZ)0m@ zX<=t_VQnsWZEWqmYj@kWvM~JJzkFJwS7a0iN&(*`6Z0{Y|?)WqRM9`Fe>3sID zT;67T&vo+cMq_tQe=f#rPerx6SBSc zj!Xg>*hk9*e}V|xTTak!ZSQrZqr4^7^d?Ym4}=HjGuwWcM(Znvv?4?w-_LE=Bi@0L z!*fTB=PX1uH0xzE-1j`=AvrF@Z~+ca}5(Y@99yde}i^!D2F<}4~P@^`Gco-yL~)r zywdVKr%@E`JTW%pO{m84}*X* zv50x_a6*Nh?Y(C|*um@lMd1E04PF<496|TWK$lk^LpT&KMu9P#Z|`;5ou=OHx0;f1 zh|LABa2&l6jdbdaJpxQC*zNSYsbSx|DnQs9f5!EsSRBE`Y=UzytmeaCSF zdWp+hbAb)THxQ!cwgEe2GHJ>bwTJtUN=60a-?(?!BI4Y|O)p$8fE_dNkQTQ*BEB_s zE)8c|HoEK1{d4Eo^Wgj><;5gFnL2RW9ayI20X@Sk4ZD0dJNP14BwLz!-vsU(kSys0>xnnUa$Ue{T=8`uT$cJ9TFG+177fiFm>rdUsLe%b7*g z1ew+Lo`Y=47ER;ASooA#z}Q_;gZGQsHSx|Tqkzo)^lcjt=NNPU#tjY@lL?@}`V)rK zg}gItc?v}5-O}q@*e)FPo#6)|jGva)5-co1nP>hKm+KJWVm)_a;e9CC6G~$re_ijh zKR3o?fOz4@rB<6zh zQjkIl0FE8JT@DuvcekXVDIy?le|Y6aoA8VLAabw~%-U85iAP~;F2W3JaqiHwQ_v?B z6fVhxEqHtHT-qZFj2_$r$7k=t#sySyGIq*a9k>g}1TM6H?O(YzRkfg8E<8br=9k0{ zo9oS_W+vVI17jNTF)o;HV0Zyn_eh(#^K6SZukwfJO^7GNtl&xu@bd#Be;D5|wkN&& zXhVj>6WcY4D4aLG@~kP-h0P3SA?Brtre$n5(e#2+n~<+2S{>W;%x>=)&O=GlqlL#b zH+#Bd0|kv^G#DVmmH@qVZIhny(%uObC`+4#LfH16XZbLTlJ@W5)nFHQyYG!};4rJu z0Tf6x!rT5k=KL6 z#p&o$XykQpsg~j0pqI1^Z@LTv%e6bP?um)wY|R@j z0}qiK*F=?qr*aZUH^!V?0C|HDNg}A&m{)i(i02-9uJ1>1Ad{le$__cW67;@3b>Z5* zfvfzz>lmgnM|vn^Gxn6g``#L(nkhu;mACMNOER@m_oM_{m$2Y~p=x{Y1YWpBAk0Q} z3uv-%q7Oo~e@=dqRHgyE2A6OvUwMXeV1F(rk%W%X@!?=wC~WdSC?1zEHY%^2I`ah};n!eC zTjVwNscXf-n*z|yj?O*(K9GG0PaTza1V@GD$ zB?N;I=~a|c*e!_>rPLgy7n=ke%$ijgh%4u*JXF}2Dq%s?odVxTLQ>HXQ3&4^@)HC) zUjz(i#Vi1I6KYFH&Z?~2qtTgSOE{%-I9E~crVpMS6^h#TSL(9k^~FS ziBvSKe{+Sa4DlB$$L`%lAq%C3ov3wC(wa>oZvRlyKDA8@#0IREK*jsTKumw8G_UhH z<6ZDx0d~wjqw3poP_E_uwUCR6cZ3TA#S>&x5*lPx`Mj>k=Mf7tuJILd`|Jydixeh) z5B|WZ`qx!h!yFn)2F+|?>6i>Hr_Qb6!5fC(jO7RliI%ICxN*32v#E`Yp5L;j z$Igx6jEQ+*j6a{i;T9Nd^2A|`Z=l^zf3|yV#7eF5#V~*hlN$vdb&gC@dGQd(_jBM< zjGn^9sGN%=n=KtAY>BTze6V*hK zF^{fo|H{R_O4lvF%F55!WMYji;sliOwqV+ahF|`Ui@?qdkeJ>h9G_|7@?_U``Mc4Y z0GBpkJ(g40kShLw{V|_{Q|E?we^#JPJa?wS4opd*KpJy1Jldg!vy`z}GrZ(1n|Mhv zv-GyxACIY9*tP4EgN231MuY`rS-7RD^B~s?`j9A6dt6>!0F$xcE+ps`Ri;F?`~cX| z!{H4Xf2NE&<57`cJc>gU!@fEYyJ%0H$$P`83U!HYVCq1Z#4r!Y#Pyhwe~o&HRM8hQ z)7%7@z_Rc-lgi*Jog;<5Gdw44C>88UfcA6Cuxo+i3;3fI+=Oo@>dsUZIP%(p^INS4 zy0@bd*Df*sPhpEsZ(4BV(EJD=k%*1bgJg}1FL~fE3`SdUNKA$5qk4SlsTTx~JUCg3MeMg!-|X zzc2g%-5*5WUHMV6RxAot%JgGJ+^Xye`Whk&0olDM(}4y zo63yJn&NZu*zrLSkL@3oxYU^uc-B2me_Fm0odSY(>&m6_9c<05 zDqO^g(FtS>LZRBGL}00Ts)JE}9Kn_0Bmx5_Ii{+IcdoB|Wkk?d3wX>~Hta+da4K|D z!&kLQ$8aeese|Pge_IAiCpgNgM-)LFGKO~~NWusgJfKd8lTjJ$F9btU7`Y=56HgVX z{TA+F^JMHC8n%tjM{0z`0ZyIyDTt*e;kO?JW>5Bg+urv-DxGxH(;L^sKC}E8^%7J= z*qFIWp*RuVwF=~vfJ!5UpJ~-AN z3+lsxM3CgdhgQ9Bs3Rs z;|dk6=|>g1ih+Rp;!XVC2o|1UgU|&Ss)V4#jN)ELH-_onRYMhsLDX{`aP7He@}G-OiL8m*pz$X;{1qWrP8A~#eNP)YW!DOjo4OHBfd2}6J|?_w1^-lm(gZGc7k|h&qkLl+worQ`ex9f6lgvoe9lCgK4=(fEbuQKh7O4IA6GKHeOA! zpE%GP*{Y>*($nzo7qjqb@9*2Tdq>ReJ^JD=p{2Pog$?<|@Io^;bjXa{*VNjiS&lZt zq15L>eNJ2qv`2T3gNNvgQs0&|N-SsJo}$_Ce9WRvRGf*TB_(ujJ|#Tbd%3A zPUdlM%^1ZUE_~p|az6v*v)5G(XFEZkfTCzNY;ZijDRr2@ege-vRA@)>7vbUK^U+$6}D;V~+qq~Z<4XZ2#v z-8Q2=y1e=bJCxkrp5pE@$lS#1f4UIEgDcyYCUP}Bb;kC>ByXV~59e{}u(Sddyj7_r z%1mWrg6Y!g!Y(&5gC5yS!cUfiKc3Z@z(;a@YmvJeka%QR-VMJt`mhfGwqX%?jw<(q zsRNKGLussv7kM~`Gt2jhx$I2B-i~1-PZmy9zw1M))f=6@yEuJEb$0dKf38Olen9vw zaY7TlOue8H*u{^vcZV#f0=Q98yPq&--X!Oa{ZPtX&y3ILDLpeB6B9;!CZD|EuB3Ce z8_<@gs3{R(#-Bmz3c=|9?K>uQ`7y={zLi&G2D_ac5K#5WWD3Gh!L0axcYW&TM^VC8 zsj@n8YL)yp8n>8tptK!ue{Sw?rx0gkSPry55v2dgFOQ`O0>UUqNg0Ssf^PEAY_Iy(5dmSq+45a>qxPK})D5apzjQdkFtn|_r zd9bCLhxw}TFQxvI06Zp&X7W@3#TG#3*-a8BPUfLoBX9_Zw;FM;`bh?-9vN7?qg4Ky_tn`~gJ1aNA zr%kP@`D%Z~v5yso?;ks&)}#mxWS7hiB9bP^%A={-WTB zsuQ8F4vaPq&5@Wz!{y;_82dx>3Sz#Ws>1xm1^t@|NVU39w%f|!7ap-6xF=(c7ak`! zf0kKMlH#fic>kIPlGA9}y2E1)iiNxIYxEJ)2>Mx#s~@;aGIO!igHHmakE-Y7-tsY8 zEL7iC-T*c{=WfLlPg zVN-j)|9*7(qWm?RvMNMXOI73~6#1;+0e6iPAzie}lNi|{x&z+9x#uoWa2lx7f+ly_ zO?45$hYyohvm2mXn2Tza<7sAY3YE30Zk11w)#FtG&9?ey$;dRhciyf68zR z11z^JR{+Jv=ktJuuvG-iCGM^SFP0vv?2b%~iSlS`hA@$KcKz2;I#K38i~@+#j&WG_ z=wO*ysb8_;Dk@6xlSEkAq zzjLSXrp4cRi9!#b$Dhg-7u5Nwe>fd*8X_5$jH^_AavaivDExpkpCmdY@KKMa-O?tJ zJD3uZ0QAIitUw7vX+cJbNn}N*DjS%VSSm~~BiL7f3|%@#H2rd6V#@S7sgm&q1RS4N z%X#n4BnipWTWV0zhI#oa!mt;4^x`{ly|becJ1UXoJy9HF5@4VqyT$QMf0$~ibU`S| z^=cF>kmgmk2l<6>c-01jwMM6<3Xczk+)9^k#LViq-f@9q6%_G?wNNXxeq>#-PueL4k*H#@G~lnp-%y# zm&*RdX%%+BL5frV3J1Xpf4vd}jXF86M5_Cv{fm~Gc$m7WP-b8}{8$ovBv*6^-&Lxi zBdwBx6gQ?lhIx4ltAW3ci|SECbxODQ-X6Wva6O(jrYun#C*33AFYe@1YI%19f0DeYcnmhwZoVElOz zs%VOeX`X=K$Jri%bBmtovSvlKiShf71Ov9q2HQu=a8Vp>57A zUc@|gfCbz2CN}d+_wlXkS$|?)bbH?h*@2;TOdQD}gA0y2`6n9BEYq}w`}u`vWc{|D zmQC>Iw()QUe}dq?e+caOGpabRjq&H~M#?tr4JLjoIFA(9Pp=^@evf6?FtS6A18(7# zHo&yiqR_XDaov8ibY(8pH@rc z&XthU6LsTKJcM!Mf`R!9Tr~DCu&ud@NeKpw={DJ$O+U&#;Nx?J3i?QA!_@WKwc%&1 z2~qp=e?@SHn*2;9sMPmZHl^VE(4A@&cu`vZT`iTL{|964`me*)Ye>O_eJ1Yp9bk-0 zR?=OF6ZGaQ2gEFkrnH2KV0lGpt3=sJI>D>FpjNiCM`X6R7j0`)WTPV?CPs2$Ew5aH zulTN9_`oz-(sE%b>#`~SL`^pNj@joDx}%S5e|$!8dgryrU*1_hdH#PI|6II~pcE;! zkg`~dBHE%Y#MFi9oiziKVazjy$R3}v6~S0rehW{@M8&?J>1 zx`YAnW09&lTuL9O4pVXoHX>J+K1bl81{S58f<-^trsT@YR@w_p8_VkP_{?Bc&=!#q zf2l(9rJWP}+~bP+XqpvwEZK(Y_t;}tzSK1HFF*~-wi3F4CJ+q~y1cu4G=st-0e`WV}OFV4h#n||#Yc9Yj7!!UWPZDh(^Ni*bCgJ>NLp=!ltnE z3mY|oO#UsBf-k6GpUR5<75)koHt*`RVRB*}&+V@fa}^7~~iEt{w`4T&qVC}W<(?Y&#qGC$#uVklZK zh0F~+RCvUTj_1|KGe8I#BP?=We{@yK6l2S0rxSzoa-}t(agqsRb}jf=%TWtF(l%5W ze`L*mu?Wp;O;b`9sTeq?Mb_q7NKu8w38ZlQbGV|2kC{N>=)GUeFkLM+kifGlsUbs+ z+=kQ!kMwZTgKPMo--d-dgaH=`ei^YdbO(KZEN)ir`Bumk!d#2!wGn|8e*tke^^@l= z=EOu1CF};!BI-!OQ8@-++L${d)|XX#(T^5F29Jzom0u@|j{~@9Lf7bIk$@x1)U;f*5XD7y(&a&NUixt+?@s0^;-1qDySKT+f zxlnySIz4)8O>aH|vb~w%eFj?Y4^qaH0;!Al!Q8{q?yHSxaMZ9Rd&*`-ywul`TS2?m z+0pd=j@Ie5;1|6k0r~g2M;*Im(n`)km$kbkuaueTVo#e?rLON5pUnuQ|>! z1ueLnP3)M0cLy)+lXSk(B`K1jb;?5}t8d*-`>9wnV@jS|GhpxLb0(87!p&>Uohke1 zMdnqPb3)0`d`-G9rTsLaCN2E=eUzM(mfp@bE2rmlhBi*q{eCCo3sgebGUD!_w@jM7|{MTGXFHYLF)lyhg#r{n9L$SMJgV!8^x&9Aq% ztcm6a-gq{D&VYBg4FfYm`xxKKo6?b8Myy5sGfIj2N2renXz99k?;Fu?tZfUam-fJW z1_0uiTU#*%wrFL*5CW$@wu#||b7HfX(`AIw@jn01M)bfcy0&QBacw3VPZpV297N z(VZ2HZ|JOVBX2g%ozPEy`f#cdrY-epdtWdmTubB#2bVDWbmuSjf7fCEfBj^C{>_>8 zO(Q<-&)Y8=p)UkrHUp7w-l^8STdjGoTJwIj=7ZAae|+m{CV9Hg{06dUUI=1h;R5_P zc^|^ViP$EEOwri+V_m3%Q8+NWH3i?p-D~?q9jV3rl!t1d-Gf6^F z%05FffA_0EP$H&P8VfHKD%i-igbMsB(;{C-;gpd0PK6vKjM4Y+3 z9BT-ysX)t-Mr~S+1$4A3)QPh?KMt?PKw#i1Kl4=1^&Ww|6HTob5h}UJW`81Z>hHK5 z7k=j7xC^Y<{ArE?W9rMm^?dge4$uDndwJ}OGh{s;_77acGpT}SDg0}!A5E#FqAehk zf8dkh%~ELgF!~|)DMkLu@IHJhyi;RsZ9Yq(m*lf>y{(8>w3|z-Z`Z09&=v&-m!a+1 z4|YIhHJr^4Q;A3;(kW+`lbDD^ugq77e*sxCou=Ac6VciQQ!b`B>;q@=i?IA`(SED+ zOm|V%b)_R%qJtJ9D#ZA%A1qAE-9>Tt!0_Vt;u&!ktJvsH@kSfh2xV9f@njob?~q_< zx|)_;h*Po9t%BJTxfXh<1DC~S`Eq~Na!FeiJe@S0) zCC8>EV=K9Zu)U4U!s#WUj8d|crIi%wI4Q8cl+OgtNeRW4O+c_AvLvsm$p}vmdh$H( z>7hiBK04y3V!`^vqM~$-k3~gg5B8{!TF0s*7VVyVl_l@%B^N1{h@O0riZ9_M7h8Ns zJoRGBAD&AtS1cGk`EtwNdrPiTf2>)5@>Qz5&(v4C?44F}j}%X!aPX3WBXM@cPliY` zuk~)Il0z%+C6}68!c(r>ZSH93ET{MS{T;2}$~nrVAZ5;SsYay^bE(!zr@5XmXIz2H zXkXY~o)#cL&3?Vx>aID8WjH=r4#FwsiQ>5mJU|sZ|z%X-yRREWzH$8>9O$-NpZM7r|~x z`y)RH+YkQBa)ixU%9ZSK6ZoIzSEk_Ud1TDy7nXAy?n|@O#}oaLEBJZp-8PaZ{x<9@ z_<6p};~;92%Odn^voYule|Q!zy)|fd2KZaM)oiu}WU@ZakezN7XUJTqNk_y)r;=xQ z+BdO)9II$pi!PYJ6=#nvey?4*Ht}!+R5(-`R3|Tm6;s8x(z16I^;rgb26}^=s?+(B zHophz`6+JtaEL^qPUQjEn9GPI7vR^3$AZhY?Jnf1fU`kfAw?*|j)> zrRw#QUaD_RXGXMG(eqrk*dbr6-c(*~tAy-nDua?nkAV^)+b5=W;gf~wYNyUEuo4ns zsYC)Px(8$k)$s;s4^d)4l(x!1Bb18Hb@EuUDh@m^E1U;l{>2b9Yb=cxplNO~rm8_R z|6<;XMiBm1va-V9f9IGzORA_Rd9ENHTAZ_ancFJ`p9;BTX}q zi#e&@LU|79p^q^#{eD|a7K;2dy-F3Hnt~|jtLXvqfn&XvnE0x3i2k1>5 zFp0nDLm3Ly*>kFG1%5=~#5_p_2WeIfSdjQD6`-Nr<7ns#e{W?88gvCT6!GpS!xu|F z#s|{qUs{T6dMyRYVfiNBD%65B*9ub|rGot5vl4qbxm3dgWDFT$lhX zluuJS30P8z#x%>nY5Pe<`3S4HW2~GKgcPwm}#}HHreN znAR#}oHD%?Te)m~l@{KwvhY?{b>;bW$Vqvbbtv(O+@fU#-jb3uPwe!o;>IPY0~d^F zQV?ijGd+96JK0CUYca$Qt8+w=f4F~5Z5BHZhBt40JUEq)Sn0`7@u{F} zypcEw7H6^$7+2CXQl#=vR*cG6O)#$Rn$jch$!GcL42^d06VEbiUT04WT=@Kd_Af6o zpTh$J6V;&_*w9QeCyr@3Qw_ec0zX}mskd@}doc{$-I zc;^4d`H%A~Om3h>xY~)keIbglP&R=NR&N5AXW3b4jvYa!ob1LGWX+KPCum;=EcH+; zvhb%5Zw+IAg4rL1J73-IpGT0Qe-D6Q?;bl~s#6ja_+$Z7-R34>YE=PK-8xZlO9f2T zBim|mK7w@?2id7c_$9!s4yJ#hw+NSBetqWe zVov?TxRc!wqrYh<29^rNi-;$v=FcYnIK!vXt`>%KkJNW$!j)$?M{RF>`4Aco)_{Wa+!ygMbc)jo7iGu@(2Lk3#SjAGR zYn#AEI4+C;J_WbnneDnexOZBF9dVGBR>T>k6#;bm?>JU_H;z)$K!OpriEW&Z& z$9&$w}lAmUcc48nnMH)3tUrz1h(9=I|8`)WDA$-Cnmj=;~V^F5m5H zH$gDpef7#B1lbQzRRe!*xZd;?Z1QZ*el~vh=l>nde}DV|et&Iv%p~E}do?XijLr8ymjbCA~Qcoy8;KY4Fuoz7uzd3DxN< zT$#2iDGZ-1A)>$Rky!d9NSryUVC%^e7{(9Jdbncs*Xv@c*^qe0S3*|xtb+*rlVr0v*Op+-64$2uaCiwExc5us z*{txaj=HOrajZ9dgnXOz9z)A5q+je*v$})pAvInX#i289dCq@#BSpQUCEL?9#lS=|`Evh>iJvieV&vmRnZI=(J@v}@9bza`&G9n6 zapT@GXO==2jurU5;J)CtBzJ`?f1S~E?&d=b*2?XqUyxL;lG}-xK9}}2@oo3c*G%`0 zRq~=$-$N&j2UI5pt~N8m;*1RAJgCSbrnY7HT67m`&n<_W-uxFV>5kPT`9LEOl!^ z-;ufJUem~?t9ck!jXopWQe{%TO2>*szY(00e9P3ZUpXAy_=Qp3B3z)1CaQ2KC2M)d* zvlTDAfZ49d(L(f+61)|jtjJgaPksch{1m3r!IPC5OLLH#c6jVUqnRvJI+53Edo{+B z_sW}(S5&fXP~FN`6OSdFR|SuUw2PJC5iXoh3I63FN_X8FNL}%xe=wWo^~!^LD3zNf z%QSN0gL-=Jc9h<`Qz5-~!CO$2-n-lG^e~ebh!g!L%@V4Y3lU#Dz4t&8F1J*A?|~$e zZIj-+^z>-oS9H8c zPVF5s&UH%d&4h+(DUy@xc+Aw^B|IXx=toQK9WA(0YHxZ7f7dCscPQ`F+U@o_rS?v3 zNY$0pN>aY+)ZSO~B)b-xrbP1Ocahp#FG|^-+tbI%n5~rByYMJwCn`NaPmtQX@T3Sa zs+uf)g{i&&$MELbA-0IqdS?$t?m5t`W>@L=LbFOs@Z8NIcaT3gtM|=Vfzt(|j$%$? zD_biMih(2wf2y(v1XZH}dYT>+kMj&%3*hd-q)E^bqYBu_v%a)`X_}Rtbkx z_r!=+7$&>O@9FA1u;}r=B!(F|UA42C7t!e!yo#l|e{z~?sMnR~%JV!v&*awjbR*(I zFRIXQ%BQJaM%JHXhZ3XZOm_mre;{_WyBlkKqs@rna0gg~UHHV)w$KBXx@m>^`|&FWmJxCsM7|a}TDc2vOk&Rr ze#%**I5r4Q8pwuaTQiAodBoh=GHlnG#?E6tP*~VMCMFxB70fgOLwimd(}vcD&WIEC zMVny`QWul41>{9z>mz<0En?x&cxqpY2lhWSe_EimEj@c}ViDWa{2O#nUd#a_u7@e$ zTvl0uXMxLM1b^X4^eo`QV>BQUZR>gwXm?=>ltAOtpyeE#2jKD!tZr*RU<`kb&wjR# zETWxubxkzGzB3+t?N8#lJFvRIvg5__E`1<_E$G&FablQXj?Ig1MMz9Q<1oty&GP*P ze=a6LT;a@qMS$P5Utz0)-#E45?L;R?GxQsnAbRpp3H@x z9$SR)6}est>x1Xr-m2%gs_S~Wl;dEAtuEp4hVyVD-nP8o;L~M6ibRiED5SVkffl+g zEsv+_`Hz-J0TRk)wJ>$Sfn`!mDYjOTwrB99DUc%8SPNl@C;FyQ>f(`d%nYA2f6r0k zzNm$=eRcQ>_)0)Y67wbI{R!U9vZQ)B0TJ(Px{gnN;NjUQ$i~MOEK0;*rZ#yez1Ar2V3yia zt(HIWPnwvk{5`L7?x|NFh5^msf5n04Xsq1d3i#$@2X0e+(?`z=NF3!?>ZY%#OQwz_ zs7r1Qo2t6xR^BGNw%R6&wye78D^@5CD+LaeDU>L7oXD^-&+&Jb06q%N-oinF2@-=9nWTBEH74IPbqYN5vGc~(=_IAae`2}n6PGhj zE$_#1;5$57KITr0!@;jHl|Id*zm-(f1cnFKIM>&>Tor*|P*qc?r+}#f4D`H3bx*eS zIb3OsGp*5RXs=L5VzFHHxO&#;X*Ci_U3S@Hn29{GjJ%HGfBRP@k(VTh{C*|!B-G<2dR<+(EybRyo9qytwqFCE@B))eC?6JM%0%-oh>kh8-Ef0@w~Ycd(?| zlz8X2#KSl#>Cso+KVal0DBjm%~LCZMevECv`2?L)UUqe`QngE09OPkdN?;>$$?l<-u(*+ubQ*(LNJCv2gF zZSaZqs!?Tke$kT zrICR;F}Ipkh`D}fOICq#0wv$YA+< zp&;+5IAvI$iU!R_zomD3UrEZaVL=AoN@|R^bPt!dfBGRQ_z9~RGqrWPV=Y&E)Rm^R+VH# zTx(eJfQv)=@h!&x8%P9}{9?ttQE}Q)k>_aY?rd&&gfhM>7t4iXdG;V)Ov&SYY2a#D?5Q1%83_ZUcp!L7VJu zf0eVl`30QxDO0)!xn6PS$*Jnwahq^=yT4qSEFQp#AK~A7-gI% zZbZQ&F4mhAso$lZZic6d+D^tKuQTY|79H4rkXNgCwn*-jwQO4@?J#uFB`w!u(rkSk zPhv6et4|hei<1=dfW)D4xfv`{Gt3;7tW~7|yKo*;&u~VyMal>sVdFbN<;oN=o?hXL zJ**IuCSGQ>JTlA5S8`9Y)w9l|o#ssOOmV4C;ID0Uf3)b`{|4gID_$TpVOAyflRghh z{GHz9Y z6<0&!C{QL^|5KMI)CR#D?$%dQc~l4q>Ic3AC{Iu*;Wozb_93JN;_8t@3nQT5Rt`Yf z2VA_g)D6lHRhF+{n>;Tw)fN2DB*3q6sw^Gd!+MQ7{I?X=)^ThcaBS`P2 z#Wn{2c%HSIWBm?LGwyu}n}}raVc40oZnj>u)Z{X)R7d7Ha`qig3kb~|O_j+anAO=( z=I-6uf>g2bTW~v}goN2fZ7KWAQEaNIF=W))<}ZT3LK&~D&NFDU|iHlvLvgY z(DO1fJs4IkHX$UwA4dSj5LC=&Rf;y?$U6t6s)Nn9k9iM7vzeaoMS50HV3>xZao$hv z9v8(r6+z_XG3(st=@<&pEj93G7)#Dp|Lt$wUqa-8dYD%5J*IoMG?YKZa8Oo}jD_a> zod7FKIl+GT*?j;Ucqz_xpl9(X^@q6?-3{T1Vox+pF!jS1JH-vbAc4q+-C9i8W?|GE zSuIH8=?bvVX!|4vhIb2P3HiMdbQ~#0aU-Cw0j8<+^t_5W9$F^xk-p)!`wVbj0c9bM z+N#gd5~{h!bdqTCZoWp5*4AR35Y@&WTwp5K*e2oKns0$7OOkvBd}{jwI~w>?xJocA z(ggfzcE9`pEiNm;lN}sPA+uu;N@9p}N~qm2^H(P88X;eCeh>0fRC5D~r}N@u&d;5^ z@`qHb9fW4s;f>Dw+RXq2T_!J`KLwstfb|}?b_K2KtVe?&yVHDzk_kUIjpIwc|9TwFYe|r#R#IJn|CvK0 z==uRYR6~uaXW}~wZFMG0=57`|U_v0~O zRG3ffmVaXNRXE*(PDTs{C_lL_dP4ZMfzQGx1k6Nz>e&M)ddzzvP^I`&H$sHciK(?x^Gpy*gDaHg z5v0+GeQG7`Vn=^qx>u2+ZQNbcCocX%@2FvZrm;fV3;4vS8pV3Z^uP)1jQ`B(LG9-h zei6>~t?3a<0LCF8JzR*TAta}Zc&z}GYS#PwzIrxK&xV{{g8aNqAd%@r1#1)tRB)9( z>YeRfYt?@~ZWXmOX}G{14+=t|G~7kWrDEuA>BBtJ z$leW6AWG9K`D?)K z%&-o1CNM;wvY3UcR8vjEfTykU)agSpCwOqTz|oR&W1$$dab}fe_rz04NN#46j}J3A z+&2wjkeA1_9-elGYovX7SCPoC;w)^;;vr<+2|kF5`z8nF?PEpu&4wGqC~R3-N(O%N z?ot;r$V5eS$%3n)LF%|T7DBKAM{<2`nUYr&Tp{Iq8Bf0RECNI^ovv*NP`ecrPd+*i zAg{)~E9RQ0XZWt9hr!qZRi0R3VRgm?ZM-FB2Y0i(kh_oHqOIzApUg%r1yb}~Vcx0b zA!XiVy(C^ z*MOWvULRol8H*KxuPB)*8=bB>F3kk)A~AiC@+Lw`W@$%C&%F+Z)|C2>OPldHOlVt2 zlNefKE(N{#Z1oeokgrUVpr#%S^p^jlqlh>*RE8kP#;gVY;2xlJ1X%>qfK`7V*rT#N zDeg#a!xjQ-H9dfKYlLOPdD@L4Hv?6`kZOwj;|!-~9+uxiWzR5@FoVw54fkn?LMoZT z%qUW7=?;rSFnX}kXA}`&5yDx0j;75Q@_Y%-RPWGZ@h1wWx)(uXb58h@ko1#uJ1H>w zc4(lMtw76SFc8U!y3L6K9d*jJfsdz@!7O2@;oD%>z|vwS$@;29wyJD<%?kXVjElS%LdT6OfwOws|7 zmYYsBxydK|isNGxgPTimx$d4PhOEzKv##D^vd(s>))z8`H5gMFfBt&dmUYzO#^gdBRGeK^Ck7*J)yM_Wib_Y^ z+ogR8>*WUR=Y@I}UlFtON?e0QKvpcDE8O)SlTFQ%I$jqtl?b0Z-ihU*R*D98XVgi{ zK<}kl{DT#Q?fE4K{Dy6lOHuD-^UJ#(rLE4gn$3j_gzY@ThiyPJ5PCJCQ1DU$nHWZE z{{~=ntm!?ec%WFT1`QOi{{h zr=zcLZ-wNiff$@>ZI(;M1&<~skhHUedc>_vd@U02Tx*JJVKm5tA)|SlzTHn+#pQUd zI<~crW^tutE%(*{snG2mLwKFTtm+ac23E^a9L@D54(Z=4GF*ISn1Ak;PI8bB& zkoddSX3oX4*8P-lz75(N&EZ+mMF!Em(GS-g&EtgC?HXnX>|VM8OzSYMGsTKOq!7a` z-Zt%Z3prCtxs`*nC4*S`LE9d8|9OSyJ?Fm`aRFydM};;Qo99x{wHsyu4?ILEqr-OP z5c-`$Np&0sX`SE`%&#U;;HGx)BIc#&vM&u9bRO2#bRulq7RR=1&a_RWNLob%kH(&P z+8?|va#Q;ZbmyDh@Oj0K_b}%{Ea@D&t5+tf;kCR5bfu8cY}GpqUo=hC#Zf6-dSop7 z2?_{wcb>@TnrHZ;RdakuAJ`>wi{o+Dp+e{};%DN*Y`koBlNXzB&}ht7<>y*A!C@p$ z=r$%Y6b;^}tP?6u!VxdrGy~S-Xe$jClM~PCllj7cPl^^QKaBHKG9cpl%HwqE4vQ3t zsskR^v~OjP@it#L3-G2dE?96Kx70>abds8NO&h_iR^vGigpJcaG5|#sYYTFfL;00A zlT?gviD1C|HPp-KMq9nGvFx#^8+x)^;~HszwKnnZ+5#8LuP->uIvs=7Ga+1fur}Ud ziNydQ$|lEvgn}}mOeAt01sUrUZeqlbSOx06ztjos)iR14JLH9&bhEL-U{1lTS~hb` z64u=yR-`IgC`*Fm2NqTur0hW(#|SoXY_F*nDs_#IfsfOURy0crqp=fXMkk%w4O?ZZ z-(n=k?ilAfp3z+Jx*x$vIWtKU_J<<;dU{bn(=lFj3+DIu2Mg3HUd;Z>7G|HHm{=9g z-Gh+B$~HZ+L(oC^Hxs{B=_cs2z;>XdJxHxNzSRo5HCkW$PqEa@F=czGrlY(6t;*;M z?>^8aXY9-aGlkKHXhwtPnZ|M%bGjS-UZjg_?5PJ%v2czK=Tml%XQe3)WPf3syBOjC zyIuD@rHJr49ueU-$HiUOBA5u~A$tcrb%!ZD4Sq=t=OTSPdq*t7Z$;BtDGsvfrt zz%Np*XO8w}A4ZW%db%F?rF_x;)rBnqB#$f^`tBiP0=YJ#dI>ZHCsB*}*C(-%X>PhL+~>+I3Eu|Nh18?gE-F%pspkVChsx#HHKQD@xH;{|`< zAD~=ii2l#2gYMeN1j2nX*2$d{2yG(Wd9Sl4XN@~mi<=Rr46!YUo1deW`E<65p@aR@ z7b=N;mInGQ>^h_ZU3;DIGkLFrjW*o*3|xsYo{bT0SoDmmuzR0ET7Ba z1|q33X)=uXNh8a*YHu~hL>_{sYw2NmFcSvVsp_;Qj0;6nWAW5LaThBJXl2ii4vPt$ zy&Gv)=o!4hl@!B(OORs;Spa{-P_;a{-b0&if4DeOM1VtsKBL{Ype{nqa`?wj3Ug61 zg-KpKtRk&Dpb_xC5{;+d-(E5%VW#%KnMk(MK z-P(kUNy@d3Kl%QN7My4RSS5sZC@p))yH_^@1z?m+CG{B_-cB8NI=TzIOtXuR-{i`* zR1o{MrI~TAok6E{)qPCe{zMs$RCg1o+o z$d$>=L2_EbPBQAyg^Q;AEhQ%@4ONH!?`5rVr^O~BE;8p;Cd(&AI?2q8=8haR0l4F~ zm+I3nGEXI_(7M2YB1%s%q0MkiJ!+`o-pCq~)R6ME6{gg8ZY9=$iY6&0JB-P&MP2s= z7LS-m-xBg7V45KVdO0&uBmW?M`%Ab@iyGR-^N_QuOuDbMRC_nNo=AW?=SDTl0hf#* z9p{#|x1Y({s+{+I3&!?DiFM@PK}uBBQaPSgvE2puzwxp_gN3$U*(sttX|ub!^FC;& zW#&_=4U4Nd0nFsT)-=N}!|kRLedPR~Y+T3&8U4%h`BNQ4*oU~cQBhry3b1H1$AGL3 z=j8#e!B#=`nZ+vBLRAs2fRlCA&rOyUd9xS5%;v&~ zRJ{71Yg2I`)}vzcr~+p5_E+}6(|Sg&&tN}V@TD8a?{_@A$SBTX&a)_`ZCG6FqMEE( zH@QUZd*;p@9r{Tt=!n%>O_jxv?m^YA;H~K_HBSMmCsT^+W9RIjPxPs~*cWmg4;3EA z8D4Bu*>+)*y;K|bH;B)|9SUD0I+kG5G?_N~CNkZ?k!)GbYwzjm`K+jOHltlwy%HY0 z<3rc8n{k-{s*+Q^R)2nttA1GV~0b@st_*A~Vo~nT>kM5I9 zQJ`6wi-sJU%BY&ug652(P~U3YBUOym|+F}|c?bWWJ7oe!NN zSC#mhjPpgyt0(k|>$h(`evn4R>#QlRS0eqaRLx?-%?N(m^Pm>{vXUE9-SG0<<~^TQ z(Kg=v@HF4DZm(lJ++A;a9$u{ZCYb4VykZ}IebFP4SoCX5~x`)n%oz_L#2 z#oe4v<6z25wwVt+H&8F%Ec^+hhEIDB=lsc?A|pHHN#1BY{2LZydD(WA6{MqGXu{aJ zd#M+tldMOYhh?Mh@97dr1MMrB5M1DIvYlg;a6C5)rC-~S5@d6n1sjZcu zxBfO#X#{ANh?|tdtmxow0Emt2wyZ>5Wi$pcniJ79O&+v#(Tz{&2lv_Yxc;xp-YWUm zWwVB}?u`sOuD#E%tPDjkx-zGRSXtnM6Dc=*F71gO@=)ps)@2B$`FEZP(R2KzOC2Fv zmF#9t0Ct$&CE<>#MXv(^QHOB6JtKztylJ7Uj4n))R5yCqi#l`_x{DQwF_A@*M&bv6 zGWl-Y0?#6Elh7EXzY@cPKk)Lc^4V9|G7UmGP{HFZ+f-HzkjWA ztMsUk2p=$IBY;GN#brD9iE!*?`IisY8uAtsZJX_dsv?Uw0Z<-al@n1QGtj0&`i${x zU>4Em*V}dma){>{we13vyxYS9KfW58+v5_ggGLQtt#M1GP)?<~b6!P(Dyjb~U3KfU z%$!SF&LB9aq(TxEcak)E*(*@8lcUNgG{rE5vi_n}`+j{-#~!ijRZr?el)=ikm4=S_ zxMbi)I}xW+l0s8Obhk0B`?h_*Z7ywT2PC?YMH429Oi!nFD2+=3d1P%|UO~WO-dw zci$_uBDveCfPi=F8ew|j3t5+?lq0g?@3UtHh_xxWcuo0dQHwh0N>>S7?^Tr=i0kzz zSgn_V3W#eq)OVs1nhx6V+yj_~-C-aH;i|A_)s+u(0c*T}JLRL1 zw_+3b3@if6!_xI7m_2N%Bxu3&irTf~3qwdhwlI2iLcDC{3rhep@Ywo#5%%SeD?~qW z;hGq)S6Qu3+F@&Zq!{GVqraA2bm2K&w^&^HbTB{Drg^C`G)y^O zQrGn2WWRehElV={N3#NolGkjVjLRMka!g#-@e-VrK@Rjv?ah#f0wtj~)Q_UNa>=4Z}HnYHm zKGWJ+!f+4a4{Rs%5ydc?C^)Ipd4=JhcV6ieB*a-)K!moiWaU4?QO<_dH*; z4r%tlXM*?WPZK+2rDfIinmLz+pJ%uNkFPqd)~Ov<=MaPn(fxv9#j}e4$l`DJ{eHFm zbmS60CA)vi76Xp-LH^r)RB(Tc8Z3al|HFPYj#Iw3L-rLyj<0JNr?-9HUOyf_7pa-| zmW}c+WOOGvDaRzrVAF<&uzqTcZS5%lh9``7W!BkRa(iU7RTIa|t}RQh(FpQKU<1LJ z?EHFsL&FO5_^6^RMH+@9&an_tJSE8e9xY5bkO^l#f-O9=P5PJ=?HX@@Qk~%&s$!qY z)g>hB^Q7G=tCz6$GUP;w>o(ox@G-K6%bD>*4EU{oFQ79kEr>53_xorF{B4BbK5uB` zAzcK6%$$^#JI%+Ow~yPKZ;fBFlxXv#$~XJB!aCQBChA8(Ac|MdZ}uJM>90>#m}98W zgfz&%@;e)<%+HNaClwBXO0r!P1JtXYIZ}~bIyV?+wQX=2gw}=}LMtV5ltOIC((F#I z;lg>nNHt&PvY-ss2NbyevUjp{obks`Kf9c0$|F&Ok2!vcIQ<^@wo+d`SvKYPTuNAZ zC}`XPdcSoE*MvHg3_JZ5Zx8;V$F31aSem3MUKITs&m@xGibK{DNNFM)Y{?YZIHY)X z!uYc}?5@LP1)xS0Y}DmDXs@;t1jSA}M&m~EY;vQE#qrB?r*i6QBSnmz4_6sYL&2sI zEM_(rjWS+7S)%51G=#_dur*0c5@X->Y6|O~7SrouKa<}ozrjuNLb}<*I>$qw;Rfvl zwGhy`pB)koN6VN49KeHxVElL=%Fuw(E4wdcTCO9yc{?aTcWVj^n#zJk5NVP^>NDS< zttxw_$Zw-9)x%++ZN;d1%9P;FU8A1vj62KcDT-A-Jpc$z!fK(?vWTi~Aq9EkS8O7! z6W~25ucP#wC$EM{0$Uh)@^;*t*0OfOht}R>yV~Zl$MxKCpyn>6h=~or!b_bLCVy;@<+dwDSU~v{VL*6NDA4f zJ))^GF5#HIGhd`N)AHV@ovas~s^J)4tb=Yd$OE2vOCRU6A-Cb(IvSlX?-fpe&OTxm zXJ5NuFBKtqP;{T(7}j=h1{l=ui};Po3Mi&@Qhl-#F{ROZYIa!I2WYZPG5bIP3dVsI?G5Q5BL73fsE5BIJdaqDC`FSZuB@YTXI;<5KO5i2{(_^*bT4 zQSdM7MSc~aJ-ch3hp`nUQ9g=dF#D1r!qE#Vp=8np#hg2(II3{)N{lwojk2H2dlG)8 zY7s=BU_Kv${~lPze)3;m_@1@7;BYXrXQblR z%QLeN(5^D5IIRpWSQ`QUJDP6CTRa@7kn>)RXavpSRVTL3q>gEc=F*g|i3h~}Rm*?N z5r4`nKOwg&NUOwY-CsX~hnWnDxUg?GMrxmromo$v`4b76GB>^E&SuCk%6x4ZV_)Ri zh+xk<9+YJ|gNc?jD!GL;4!eHBvDD6CYWaaIkj^>tKX`Rejv_o@DF8y+-g87Dg zZ-CX`rS0q_@psorB1LV)V=&Na|FI_;Jx>ffDV=e?!p9r=_;=UONIA*a1rkFvRP?+( zI>$T0YCXQS-D1MaeI5_w9!!k+{JU5Ggy@&9!MEU1C-FUMB+~~0V$C?gWroWa z-GfVoDvD>X3USNh7!5EMBlDl{Ymi*mh1JRMyj}tNh<%@Gmaln~GR^>>qSc#0cc^u< zQn7yk-jd!4fE6y%FK|ku%1oI#ZU5qQfac(UkDeCvTj^E$T9P<_uAbobnW|c%m{^9p zST#GmMO@#%xjIL_4H#W+AYY-S7|$?7DKoJg5Z;i+AiI!pcm&L3<}MEMRkUPK(J#ad zog+nQ7js%dRuae06=l0P+IW=_Gk1y8qNaULU&SSXd-y_wZFF0jfZJ33Y>OSi@8S%K zLn3XrLuOWKiRS9KCA4x;g`<1Ei|H<%^k@Fc* za|Mg3Gm=+qlO0$!@_}-l=Lf3cB$nZIRb}d^z;+gpzuIVS1Aqu6G%rsRH|(t#%d#Bo zpSI9B(;bXXtZ_h0aox!`PC75*ixXb1r~(4ahd--}w^gp2bdD~QZp+hfp8ZmAG9ZO} z`3lrPSGmc8du|M+f+c1)M_6T7cnws!*$?C2^it%+h=9bzbmD5|=Y=wln?anE=s${4 zu!slBoUVVYorX3?T%3W%x^Vqy0t6CA<7p;@7+1nW38D==F?&=3&HHd02iaDXXCdSK z9nT5}NBP4>{J3 zNu!&?e*>lV*={h&gGK8{WKpIc6Y^rYUom#8zv`)nbP`N>-hAp$@C)R*$t;RJOfKXJ z&J|EoI%UwKWwHZO8__ng9CA?p(UzK4MqwA1`J7H+v21DJ`$&}DB-0`7D3Naq&-?V?B&* zKA;O#&zr|lP5y^k|4IIyX?zjkY~&yctD|w8Utbtm@^VUF(7RS#ThPIqBm$B~GlG|j zKNfQfHr`O}-xd&Sh%-hXQ~Ef5+!wM5g%?$eUq5c~aD4#%J;5BqlRv5TTG0qO_Bbu- zf*BwPA+z69h+Q>~b9sbm5+J)?1Nd11LBK|tpBl`8aKVaQwFRe9M|QXVLC+!1gqGc{ zAH1GEs+@f#Q zE_IR521VoQSS7AryfHmRd@HF9N_y8z$^mHNy5hS(TPaC;Y2smpxR-VQKKN3idE*0fGzE2j94FYS>Q+S<3}U&m_wGP2kO*Uu(0=CS(*6E{-EPt3K-Z7F^}5G zU@Sf^lVtf@5s*Tkwuk@TO@i}k^Y_N6ZRqTFBicZ{miyU;({C64XS%&%h`+r%OXhia zFh)O_(;o1sZp9ePh!lmDh@;whbCgKQ4o4j9J-CE7H1~R_Sa_SuKoWGV;DOSEN0{@>^xl3uVfj-3bF{)^W|cDr=TB!U^N!dn z-cqgNqjwlAKMYjc@xxdJylAOZ3K}>@EV}iVU-%Ve{-WA4<1o( zAr>>)f-Nmfb%vZSU$f%4Vg*`Z@)Mg_T_L}uhm?!b-Jgo z|J>f)A%Ywh5kv^rB~s;#%F~?rz9TdBZ;Un;t2M>3-(b1B*%}A%mLJ2Q>fIWpTTyLv z$!&$Y>ai!Qd26sYnr-8m}q1FCaOQtOg0ariXSP>pD;+XDIB0hQ-|%E0flcF zRGcp-6lO0}Y%d6$P&r9u8#;T1$1xT+W%Y|yd%Exdl4BXYG~na&Dar*ILtR}tu5?5L ziuDB<-usA#9TCmw%1xs>;s5FY$$jT!<$yFU<0!3=#=%xt#!Q5OFb71Ay4i+-N1 z+1AjHD=GQsMXLeS>%(wV;8j_AkjSS`b2mryO&oTDUwwCudY`b5z%cn({zy+?lyOn{ zhp$qri#o}c0kDg)lm5be+d(%uC;HlO?VNm4{h7a;59n4&kV*6zjHYCMwii%KQX^>|7y!6c`5EqS_cF*0C0MeU`@qy!jE9 zzVvVEk#bW|qZJZi6^lAd9m{Lc>yE%AINVT>)t`opNz9cAMQn@{U6GdTDmIKnYz)BB zQEl7nNZ3Idz`aJu0VM2F593TJFutwbLMJMg6?&c!^5JJ&O>cJ~A~F_sZ_Udi*Vwao z7A(%}0^ez*om)hW2QTI~!r7|PtbXwJK)s$*!W?zf=x=UrvJY3k{&dAN$rH@vjwRQ& zY=4Ut2M6X1uF{gV*^&%Vq#-z#TTR~x+IrrH4-aK=D`5n5ReeMM|M4?k=>BsZP#_?r zY#<<*|8K^OlXHWC-3%1?zaW|h7FPq%{}zdE5}-(D{Qff1%%De+5zrv($qA?KEa3l! z{t$Y!5PE>R!~W-@B`pBdY5l(yvOd`Q&3~&)d2pl(U@Rj-rQv$B&Hs+)uKyHU%{CbZ zc=ywlTW0#@^&^Z)+*D-?sM_?E06dY)}+$cqB) zZJw)B9c1(iRF#->xO-J|hS`$0hUPw8ZC3(W7-q*Cp4{24iMuRbY1PRzCOQ)pn!muY zh9N$kb1lw*zS+fxsngPU1T<+wB1Q^*tOkEuc?GvQerzfh`O3uh3iqkynWrc2ff$~m zhBgP*S_B%kPuZ?yLY?Z!75C(uu^(;T1AVv;fMYjvNru?HEJ3)vc~N~ioM z1y<{KXb+#2?S$mZofAfkAvc94n^NHP&Z=%@As1Rr>Lu(Od&aFR46SQrhBp-L;3Ha% zV$jvkHlzG5m~uNEJ>qgaL)z7n>G z``k4SzBHOrrE!#R4%E`17|fP~G36p_YQr>IUiQ^WhpqVwBkQ#vMQvpAMNx=DhGX&6 z-Qhk3{T+{lay&lD7EJi}*e4LFK`hMo$9H5l-gCY9ysKs}n9UJbafrKfvqx864jsjn zDq6|{Mzz4O_*Dl!Y>-OpRQ++%Uulcn8t|GN{*PuE0phV3owtHJJy5!Su_nMb_I^C5 z%o$X_uSCw0X}Qu(s)~II*2C#xtKKVdjFk*ho@c;=za>VLbTkDWh&RwfOh%L=u|$NW=#Kc|&H64S)XO1Qnw;Pdk?_S|NTgTKKRl;k;qVc%e2pl= zhTJaR5u&%|hC1r3tZ0BIVv?+ev>9W_Gr8!(;vM|Ijm<#^F4lD>XBvzWKL`-`QH(DH z0RB5V%OxZh;LnuiT=YrkY2{XT3}1LmN#(hCUHX6wcjA=%UOxUV5M-<|Wo~<9!nSy% zs)q%1a~faNq@|k2xz(6K{-}3ZUvgbCSy5SJVzjp91XYxUs$L-Dl2$P{O}Ucx7JUe~ znbW-_XOI~z&|H{B6bH^^KK}0=6Nw17Ns6lc(;8Bn1$#u@3ri;1WIV&$xL&cetsN;3pWrxX(QzO-skrNRp^j-Is?~b1p8QTJ#9!d(KF3NRV@H z{pcfrD`u3T%&xx(JW~(|BH`; zzKh(~RCw7;%}ZP5Lh9q6M0*{gJB)LT*|ixtky1>+nsn>d(hqxBLOK6$%?Rd}LAgJ42HBQ0 zEr_?iRxjq%9!>4Xr{WG&`^DD(eCO+FjRsGCt6bt`0u!G2fv`(SxneGM9*F|=Ue6)e z6N?G9R~O7*j<=qH>ABI+(-}+BE=X#TvjmCLJ5A}gTiJ?r)wDSN>w=kSeCi@eRujZN zD`$kGJAYDgOD2*=mUs{g{^)M_LS~~blk2`X7(J!!CVy6ba`rF&fj7ULv|w=$$z^Xh zNsIJq18F=Y1qRt!8P!7A9*6oXu0S!j#iQU<^HgBSDyy3Nh(13dPiIw-!a<^`)3FNUK zGbEyApsAFh*DjTlYTGumzV>y6{(=MpMk60%j^jiUk#mUQ(8ZEFAA~Ct0_>h$9wL^v%=CaR4TLnlmR7jcs;2yoh@G#(SO2JC+*gq z6J3IC`{K~p{GKZz?5z@gXYK4_C=hDp=@Dz{(2a#X4?ptq4iyzxtCQOpCcY3Xp$`b( z@A;|Jvwu*mu4={8OJOmF{GzYe#c+ohZFNQ}4jc@`TQXjji^$3`LchMjlr)oMK7HSh zmsCOu-HLRX@y-kijH1?I>M~nAN2n4vE@$|GG~|(hGCZ%}*Ja(8x3 zlRSKNtsHDJieovOt0{XhJQYph`%g%%iJj6C3;USpXUTNH$L-iP{feyd6<3Am+n&vo zJ#Z_1p>wjX_))G!e%m3EG$J4w!3PbETEWgT$3d`S(dUNGy3iWQdtVu~Y-Gq1MJ@O# zMMb!^Y2k}1I@^~jL4T+y=Gh?{?jQyk)*>^g zp-|qicf@ip8C&G(_^fucn)s;M_Lx~xCqK*~H9sR^N3TI$sZTVuliO91cMC%cJu>F3gBJFcJzsTP8MT3`nhiFp?nAn z${P)ce5dhl+^*U8X7Fw{a2Gz~-9U7Vmt!mQ%kNBv6{~#{6U*rN1}y{4C;jEq>4|^t zh$6jFa#eNJ5cHcTJDoL5m+aipOamhf8s9kiBGZ}qf8teYdsF9C(ZP&pRqql%xgnI_ zXV<6on=(FV0g=suw};Si*{Ka*Jh6WrkbV?b4@VFD4UgC1zrHLCd|#BqVFs3c0T_P+ z(lx{eY20j!Y)az_I9@7T`^K?=Am}bH&YF4(+5XwgmoU?u;boyBdkJGqDf3Ld8VzCF zq=+{4Q;7qJR?gOwkjH9-nWltyT+M5U*ES}1VgB<5 zd9UI*l3i#-bc2_@6#@#C%&s=sY6&{&%=49l})OT$;H{DQ0E$(e%>_u9Kxcs{rErDwGgSO3u$I?`Epp*C!w*}H&6dNAtoV4)i++Xs!CAm@o`f;|NA&Odh4<6~ z_dUmlZIk$;4J<6hdx-`HN=V(CFtGN{zU76mCOc_6May0@Vsu=l62o; zLpk{dVKo08ef!6-tOEoi z5G&b-6u*KV=8rQp8A%2Nw|JB~7`pVgwE9(z$r>1DKA$PlYPAutcYk;!`5U5v7vnwg zHaXn)1=|so=6mQu^w=SsN)+}gCAkXVe)T>}jMpa15%tevBff212Aw97aYmIE9oZ*k z)BlQU9Sb3iz;s^&c&$x`;Eu7;L#GvkYrUhnm#w_ab)sBDta$Lr3dL#Y_;U>crimg& z`{K#xRkkypPV*h;C6O^>*{lth)1ZrKd7Sc8%*$ueQ8!pUa|(5Nqk{ca3>W8Vy2faj zmors0=QHl1DL->1Uav~jc4_{|7T|h8#Gbz+UudR(*`+v*@|vbCE`<#u8qUR^R3{eh zOr=>>;Oy&1Xecw~G5&?YGQsuU?OKufU=)(h@o5;g(ZURj^VpT-EF&>gFqoWYU;BaZ z)m*bMJ6t=5sMQN7&`7{h>!V@ig@ju?SI+bkl+JF_EY;Du7&)w+CR4GC z6B)M@6o&?8K3!jc(#67$&D*O9x?UB*eb~;LaR1C^;XS8r41m zC}wrh!U0Ra@))H9tRYk!?>nc#nYlvRi>Vrhczd#S6BofR zMrIHF{IeP=Xx;b08xae5uPPt<=I9HT^EfCzm=3|Cqa5N<_~#TE)f~}f3>asSkgt-= zDQ(nJ72yz0IDxiKFvZ-=$*C}u_PRr3KL*{o_62$8VtD?qf;dyM_2CG9z5R5OKHd0e(-)v78x0IyxVclv8!`o zcT!J9?f$xvVl*O21PssnQM(|DXIaEA^hCzL2kbf7ogNUXH?CsY6a447jliTUkGf&$ z#q9LPDAifGCV|efwB0^%b(=F!FXo&#pB>!1w>es6D2T&=s16oC#sfEZFh4%v$?An- z*5LO5IC39O$#FsFXI(?KY{ku2%BBVV`)84abE__1VB5MNo)b#vc`wf@NQU4{Ya;`?UE^jeURLdwvi&wedu zHqGyHDc=?EZlm{QEAUW^Tfe*z*M8M-$aS@Su3zQTDnya|M#!#Ezgq->pEEWh;9JIS zi14OJFzgas>b>YAwGeSkK1o@-;j+>dZ!GCqHbQwf4o9tuUpL@#P01s(AC95_Fb;r7l+YX(+A_AD*vWLxNPopp6!n7dR}PPe2+A=E@~jb1GF zQgD~9BR3)3r;RPK;%8ETa!9*2c4nzdB^Fww58i+x80{Doh%=VWoat;U_F)nUx2TVS z*x(H-WgKGnv6W%TLz06!+|BS(eAMA(HTm5Ujm9<-=ntdaecuFmrtlNnw(kzdBn5no zl_rn%d5nhBg&gNa9qFxye(9&l)|0V4%IYE=w2&O^tKpS>^Gz6DyHf6HLsF19_F7M%{c_2O~K zZFutG1kBb+r*IsABWDa-KJPZ$gvEvLSO&Z!BHTZ6kra(l&4Upj@-a!2YCFK3W#165 z`G(BIDc-pXP)GQKp^rR=@y(N>3ws%yzennhU?4JF!cP;SWM$)a71U9SaIKtkJ|mdB+#-I&Re}pmC9V$T^2#4UzX2 zq4=dGDX!sGi$dQ>2v)y?dAjEANkSKa5dsiF1!)%iQOX}TfpruRnv`wfN z`{wL|l?P}$CnHXh6{Qd~xBOd|Z2r7l20uu*=-zOB0X0TC>SYuYQ>W*^2e3_~Y1W`| z^G5dCSu(?Tgeg-BD`#ARKZl}*2!NIgk@&?r_zL7p!emdd5nFwK6{msEGRAbN<8W;m zI(hHhroyUwpH3-hOc|lQ|{^dF|7w{OqNF zejJ+~kya+|iXWmHnN!+{>|V0Fnh&cUGbQ>J0qi$P)ZVisS9Z3o(_1cf28Ov_bMW*~ zSOxUiRD-lm5r6mMb_`?*1aD1XgZ1&gUgHo!yWH)YHI+V8{Pb8#h@1l%ZlHRaLhwJR zMbUuUzAIJ;Xf&}Co7GJtVu=o=^ve_=-gc)(Vn8&*|A-IZXxx8Uf^`XPFd}wQ>4CH9 z-;LP1Lqhgj)Y||1T7BsP1O~lw>TN2}<#-TC{eGqhNrXsAOktG%@fL~}Br4a@2~t+U z*SYzgv5c?@4Cuqf*q{!-RsqOxuAxZZ6Y~noxD}nozv5fRYTv||W>k=ZiR|Al5e{}j@9GGDArn)n+=}}` zIFDp?x%U^#eAkHh5TaP22-sCal7ry8Ne8+rBO%s6SnFopGmAlDGnj!0qSKMNk87n; z%+-A{LOuO7#?<}50t($y3~+Qc1v|_Ap4ibY5MkI6(W9R0#qBC+NNbVQN@{4gu@4|K zcQXGyn+|p>J#YdOMWL1p)B0%gjK~7-Oij~&o`T~`MS^zXfRnDuNo9I3Z4kU;tI}Yi z(Z~Nvod0SlpoidepJr?kbyQY!hIL*j??wON=o6t zK^_h=$>Rqw&^1%8Z?I|pc|t`fS-m8`RoaqmAecjH`s+TfxI>B>{}PWw%du10bHk)A zQPjP7z})u(t|-6sGEB?5RdQgxcvjK zGltz#q=YkjKCqSVJ$3PgUc=V7B)=Fq*n{kqGf`Ju$m2+{0fC%#V}OR;es?(H?HDgf z|I{Z$!t-SH_K{OI;E9hMnOYin6WZloG@%ZqtHb550YL^qGn(fP^4AYQ<*`d(=N7l* z)zTYotI}-)ptLw>>tgL`YaMNfYAS99jgRc?SLH741MX*g4@=59X zKWh-2J}t)dbXuOBk4Z@3HV1ACc3@} z;rMvVS_KHo)-*)t&QRwv8!I(#E|5w zLEFHxmORUC6qI?tl>kf7R!aGg>pPLlY1_1@2M;E$^hAI2;-e3sqkp{cnZZ;`mD?|` zo*ycmgtGmmLc40VE)5BDmS<$^$>`2jvPK!VuF=)Rz=!=h3mNg^9mAxTE^M=Fp;PYn z#Qsg->tON?JL`zgn8QlLbSh)Q^cn7&^rB?jSW?{h%{SCawa zLenW4j?I5c{XQJiBP>j`?mKP4S}Z)K`dJjV+YCpfk~7{bMRYQRa7~76$l=JOqe~GT zbeKwhRWz~z(Ex6^1ZNrgWiEg;Klex*29=lqa6#RLeS9T4m^RNG!ztL&FHeDRSSOWA zInQ`#0>6gT;^MHoNQz<9;xvjsY#o|C~6!d?hdZha4W2;*8d2XIr4hXtD$S~2B zfQ7G!c^Slo3tHzy^aOBY?a&mlpVUKn?@#>}{T6rqjyC@QC2+g$-O zuc6|iV9%khK+J5icgcQ6-N$Q}2&F#DGSqIN6&mWBPG8)#C{@${dOH7HHKlIv+>=23MvrQ=V`FF;8sEqm`{zCGOS zJ(}+fhDYyBIV*1(pRpZYf@9hl(u(!=;!PSJcG8F5FO$qNqD(5&qLBrDKHw*D8sEIP z_p3dyi0w6d%b_|%D8Mr8RFb_@WGOxXx>tW%*SbXSJoYwL_C_n)aTMTy%L4l$gtBJ} zVzEw-DvbYIL%Uwtf^bW7wDiuck_Y+ez+A-L8GLkksC2Q66-F#cBFXK$AccH17GfO~ z1$Lg3o?rq>qQU0k1q?{)cn0gu<5eRQjZj;s-nL^6rYjh-X;&RxU0@*};Q4VS%sA^yjW_GB+8w7WgO$e>3V9#}-f{ zjzO4A1?s8CcCItTq0Ky`o@w0mUInZw8<%euMS=?uEH4zMFYrVe)H%$DU<$aO5JMJI zvB2Nb8RU?`mLfAvmsVnlH3S(pQ$~MuLS45hRXo_8n|(B`dChn49Z6Oa<=7q_vyH*F zd^v|RA-F}XRK@}b^hHpmzM365$8c{)GuX~)@^)cHuy2JjppD>}Pp9|eC7>xOi5 zEmv`_7v*!MJ58&VjBvEI%U`=uXWy)h?c}4rJATs}*5PCT6&Qd7ZZQxJ+_$Gvz{_Df zB~z6^ZcEZ-?m?p3OU+E2q{wZdX;<1@ZQ8ssF9h!HPAAls{dYHmqu-{ zA5`%=eCS`|#y0f_*BhCEWH5h!F*87BHnt-BN?|9f?{agI zS(T|?SckmZ>9b{s@P&mA6~Kb1HV{RbIBd4EPLp4er&i9YJ*XFGizWZLJVB%BV)x2$ zgZZoI!>=&<>V3H>$z`lk;&sYp1g|fJUVrE|triVRrG= zSQ5gnz^~0?CR_b3j~~3M`F=quHq2n3$Hv0`2`K`V$2v*xxY5q~dcY1TDnf$n*KJmf z#m};6l;`5J0#TezF_;F@F9xkq&GPdrjZmAf9+B(`!<0hFs7c*f*0_R+Bi@#Oid01T znuL*Gv@eIup>O5iDMx=ZuU~C*+0Q4yLo`K~%-=)+PX^JRpKwg?zsluvY*eCe)G4`@ z$Hejb2LH!m`!Pum_NE%lee@%|YY=Nu*+t%U*DU`*-+&PXzW8;Fn81WxycDGqMJ#); z3R&C81}bYKx_i8dlsQI1602`VIVdE$D%uOYe5UDzp2mU|g0X+{C4Tb|`cb7o|3jWx zb@9gEhtm~fO=9g{;KLhLU*k18Jk zRIf)ibdnJDaio$bo{l6cnENX z1+C}JtNS{3u|OvZ$tv#Yk>e$a8zRB(o@Nl+@1{#df;f&B(+A&=b69gAKyc$jRTpow z*P>m+Ez%u9lXSk@pkh3Zq;W)wjI4gZi9J0GY`I^u#>aH2ZolB;U`M(KiNCZiBIm;M z{F>DHpwxfxr&5Ps5gld1bzQL=>+rO`^SjtlFKn~hUlr#TTtk}qZicCUK-csu+1!U+ z53PoPfBL;;PE!Nf!{Z~v?U+O)HkGV=aIseR^C;+3myHbZW{YmVAoYD^|8Y`G4Y24K zZ`~Th(Vg(j>5}?Yn-iDwk1IHmmVFLUWdcC}@{xa2pF?WDdXnjZr!Nsv2saj{b~F=K z=Y{7r3s`J{jeF_%;NzPNb@l!+YX%p8L5u?=O>fddcRE+q>JK{ci3Ld*vrULH){V@V z`o>-InBO0py9MmrB6(%Z_8AT~U8rsW)DFJF_x`57>N9tr)>rPa>Hy0qWnEJd{Y3V@*j1o9HW9;?C zY41Jq+ul`@?w(`iz+HM)@c8%>b$sg@6=i?ilq}!0gJbMep6laA6W163n0VO(c|;#- zwYGT3SN4{?ZN!U%rf(PC+BC72_1!%Pe6jm|}?>i;9N6Ib8Lk#-EJk}$!rl?7IUiILu z{L0~VW`la=(Xe+HY4obbIWV=N2V`B%V=AXVC!yey{1>g>CQA7bC&_A1vE8NXxQ&^R zq@gLLyuPn8!}7LoC20t5n~ord?>&EmS93JuvADuz7_}YGQ4?Q2b$?z2`$;@8tn*o~ z{6tcGGndX`cz`LO({6J0EyP49yHGuxc~nwsea*(w5fCR4U(6PG@7-8J%6mYbPj3Ys zZE~Q=ATE)}f%2mNd4d2#zy;@yZ#NWO;|=CgG3w-VFVs0Wx>P4%)aV<$)%breyYn<2 zLddy02`Pw6t9A7oLjQv&>?KiK?O(**6A+?jyYP~gw!3dPnTLbStsyE1rcZHj+0tWa7`$I9Q<;hvkmSO_)UPXA-1V_OJcf_mo@ z6cMW)1v8AAm{uR4kMCpn?C%h5M|t#ENt&10 z9t0hK-($Zago&Iv{wJ~P4H!^hp6Pu5kEG}ia)ed6g;(P7t)Hwa+J$0CqBl<`U%IMS z$i&f2QbpG5zczn`kHK~vkKL1;Wp=xxxD$#?3l;M`8qUl}f1kOouEY-Su?k`-l>!T- zuK<;ct(k;TywU`-tug;c40(W~*WJgYOifXjbsq#P6f8{fo=0sG-hbdoo@(b3iKL|y z@t3q81R@t%KG-b+SeI6n#aXQh-(ThX?<{;^PwAKK9|RslDY&rB8BpS)C>RCBw$N3U zo1Lc*PCHjD30HFX_UDo9P%!ezEEob;G7HBk2J|D`^CoT9Ga*w)f1o`1jSCoo+Y>66 zP9OwGf7a(pSBcjulkzytEgdQ$wQ{N+MEI&AmLKvGMF#>@PA z3`u)l52_%D?7##Td-{yizrpty5&}G1&josg6nnT^(J`khZ9HU5-6&p7-U}jG zEHD!sO5ZGEBoKv*cpJh|v@aFJNp^fAHyLhA?R#D(VcC!BT&?X}xS#Pn^oX z{*|9yyk@T{hO4mU(Hc5-mHA5%VI>OdKn|u3ev#DFaRa(M#GghOYsux6CvUeHlvxNt z=;c)h)wTnPs*If-7hmbzj`CcKxswb zZggfCz|G(Ki4_nTxrD!{xnWatC=#rPvk4I$l_XW+EcER+idnDD-Ru%PD9W=%@ZZe4 zV9m6X)iX=VBknECDIVv9?trVDUxN4PgVdd^P2<83+IxJ!hIsNm%7tpc5@P zfspM|e~f_R-B|)9R*?-wFE67Fg+J(V zsvqavUpRqLgU7Srd{15Ja0LpLmMY56e+KIH%C|lqC7Rj{{z^xYcd|=Qgt`o-EkvF^ z0y(+OcDKz>KpCK|3-U2~+3vu{CUktR=we5}mR2RYc!eDMBVon0+7IgDGJlTUDVktL zzqc4(7sQU^<9nt!#Dq^K!i|Zvi{T~;C8KX0@lI-C}akNE&bw0^#I2mU(W0t<`4kPzgdh*z4nETz;Eihk*Yd-7*vb z;1q6gtBzh=0{Wz%jF$%`1So&_WRB9=KzjeDO^?3}{pX=8PS#i_#kh|guj%w#HvjsM z56CH3$t6nk+#q6Q6r5El`JIg;^{3Le1dcwC3clgPGXlQpK2iu@;FfArC73wJypKL~ zgx?Z0x5m?i(}VBy)ILtb{FVx;+d!Yuv0|bndmh>w_zEnf8E8Ya^8$a%iKW{{sEl^7 zu$d8*f>$IsMSLwH(6A&`8h-{*GNaFI1&NDTD=f0UqG?2=z?e;HWMOZ5_wA3%k@7(3 zGEf{M#!9v38mNoXR_8(Oi(FO~!?N0ETyBafbPA}-?2^A#ghYIBh1nC7-xSO{M|1Cl zGodBo?nC$Y=;EWI55IqU^J`;sMay46_oC;4o0-{?FozXo_6jp3ha1FvZbjO0`O}t| z!mS;Q6%50h;+(wahQI~HRP;ri^iTL_k^dUPJ4mGaS6nI>VY&@c&WwOS8i4j_*LXGC zB4IEbOhrXUx%4!@zP(rY0-P#*5F~5Nfw8huN7+0&14>lZihY0bYnx93@dv|M8;K?~ z0TJnkFT7aYANuHhFkO}#`^+RcQRHwc!t3Ni*r^GUUL58F@#A|@oN~@RFGE4VqrUkkgPuNVC+9l zN;#7I>njJ!*hR*@smYu!=7+Tf(WyT2*st2~l^TgjVgAU)gP5sU-H0J@<=zlXudy1I zgGtTRylFFk)U;9Ix>Z^U5%h&q;TUG`J8Wx729tf3DG38l;p_k_D* zfj5cPUX(iw_ufqe(iGM5vQG5^`?g*~bO~nJAo^MrDVSW@3B_4M%@CL91(oo=Z#zhc_Sti@=b!yIW%Qg1WOOh9!Sf> zk2%3g9-nP@c3m{z6C=mc!6Vw0Un?ZWCJjJaq3jyIoly9BVu5Ct1nrI*>fq_d0Adcc zXttr{l>c!eSKnkrpKnU0HBvE|H?!tt7iQa}3h8<$d9SsFiC;gYf{|G@>GnG!TMkrz zzojGpldC?XV1N*;if&uz@Q`40r8n=Y7!MFi=1N;-;qkZ02&x`#pItyg>nUg_!q%%# ziu^)_Ov8(Aid>@)@wqkN7I&d|BT!A@Th0m&N^^0IHjpw^gzBPMUrbFs#AVcGmwm0tG%#(A{KuAs<63STP{T2K z``_JV-_b{%rw2nZ7aM=ccf`4utjY_kBdU$>KpuxWxBQLBeC;C1(U2)J20;teP3d-9 zqov87bYmsT{+G2X1STjFZ+nD}0E828z9x*nA6qiusoBA~$&_!LJmZ3Cpu%#IdUd6&=`D^05s6+?nzT*e_3O3!_fhBi3yHyhVJDz{W2&3Zp)o^x z_nLY-kbv-S898rdKJt<@<+&F3lPgpHhDCe9j*&S|J0vG8TAGCq38r(;Oj!y_r z<)x`%_LaZ>!f%T6}n(q{P3OL*}-v9}fGqd6E{s zWzMdsZQaBJFO!}uz=RvdK|D2D1u+a7BEh=LOv;r02csfaZzu|Jf7jga8@79HgRggw@~#C z#NM@sXb|g5z#B*Hf(6sII~P6#((nwd-4@wI-{@Iw*=6HJ>FR#gWNFB6^cGI`zFFWx z`vR}-HQ#O??$EjtXI9%f5W>9F**Lw9TH+Yz2gWCZp0-bDBpyT*=L12MO32e4Q+*aR z?kArmQ_>uN#;!KK44jFk%;a4dSapwz$OqcH*q|~PY_cclb3l5Q89e=#RI9@++D(ul z;Q=SwZy8}EcZUEu8A}foN_jaHDWHIc3xOM>(3i5p>#@5{?P^aH5`{bXbw<%C- zy+pw_dZ;(7j_(!K%VdV<$p7l|rw)32H0N4Akl{;z-pjAew`|M(7IFh$X? z%$>DKvOf~|x$)=~wVE(yB4#SYSOD#6h*>N60(?8y;D{m}?S&vNPIANj!S=N^ZlDsr z*%`bdqqk;moEgZ`7@+t$Z7-!pCs+FtUG@~oUDGbK$Xsmf>eb^@E=rI^y=313HvE&8 zzfFICIWM5GrY)sNa(T%jq_Yc~oL`bH-lkvu#Wt=m^y;H&`_#hntR7&Oe z&|tyxl8NxUm*2Vi5^oliYF~PIR;QEIgbwMlTwq30Ei$}Ft^-Kv`1pw}Wf?Xw!Nmtg ziD&Wj_dc@YmFv_`-E>ivcB69r7}E49XFBzNt&*?YF4_w=tA_237WNzdz*}>L5OI5S zo5tGH>sh=8?fIGj&;e-6Xjhvg~jj?sjovdoT8P6Qh~l5Qkc%N zz~?FKMFk3^l76~;P@Zr?%=eG`c(qgdFct8imbqpo!O9~l*etE0JlaT({hIQfCOSud z+NmtMflDCqad;y(DX~ncb6O}h%Qfw;`g~a#*6ZmfKP=6bVXhI5&qBYR^6M z+IB9JjQ|+j$!1r4PLgVW#Z45HngJgc?Z7?;HaxVkq1!XCSc0*vmVFsTEdDuvl;R+Z zS!uMlrXKVXWL8c5;wfm`qVEwi_a!)g#0B9Qxq^gu6qZ}Vl~8qf#N*diy6PLVuOnhu( z*CXD+?;g%>%MHUoy}<8~Xv6)zU$E-_-%QMt*SkOqeOB#Bo!^Dy!0!)l;Nt$DpR;FE zZ@7>AiQm!Rhvs+D;)-AWl8OAoJNzHXhgXExJD#7bdBq38tE!(j=I?jc`~CoX+1I<@ zmwfb}@p{33Wmi8R?0-ZbuHv14WtuF$9{_8Fd+ykRqlW!IwO{_9jKlf*tZ3RS-vHX3 zRY0KjRwMS$#|o!y<5&ClYjvG>-p@z)S3BUh{%o#zGSJT#?kWjx&qeR!Olz`>?W}+J zHz<$yD?VRCApZ9)f9JX9=^5s|o?iT`Q22LKMA7ogVJClTl^>q^#RThr>1&P9H?j8U z(NZ~0@xW02cWvS;!0+|)?)T{zNJ$nFDjM`*LzZw(_4G0Pf3g}WGSQhAi z1jT>pY2|2VF5+nBt?Fj%X70);Y3?S(!XzYbZtUvrVs3Bl;KtzUVY#Ai=$Orf6u4L3 zu$`^}V5j57Kv(ES(j8L?W}4w z`nu*Ov2VMEOJz}iRlqW8I3U3t#1%6j$&IZMk~f=gKdzxe6RD0)C5mg1=H;H2Qghif zl5<>5Jy;mQ9CDO}0Qk-nB~96j8>(65r?xnnw7^de_L&F>S=NZYqSZY-oeR=O{`BU@ zCvUg+w%~$alamjyg+?G5{juG@khOVpls|OZ#2j`KNr|+7z%auwfcZQJ^A%d`R*kVBGkH_BJ)Oh)0p%In|3|Z>t1KagT;GCvy~u*{ATcalw8f(S~$)Jn{bb zFp9qc_h(6S^=IE>PT&jT|ANim0S^-n0t93M1@ymvfKB}W2V2hC-rCLe|1qs;@3_f? z^wVc(+-ay2P1YugqJm80z9>+tQfeRB!F z+flJy-u}lcNwS~hZ#7ELI8uO0MnbX3bgp-QS+2vO!HWKRAxXHpsE#t^4xhAd(FL%zQY3%vNsTUud`zd2FvE@KS& zqnw9)YKX}{{5P{Dt@}FLnP207!BdSVVC#8T-$Z`G>n|$kCIGI~!1*os6g-d5yl2w= z=r*N~gIrtL*ddw5`PgTsR-q?!e!q_|E8&|j|Jx(v|5dNerc0C#6bR@H@qbef|9`3{ z?`URj$0%#+u`xZZN-Pn!Jz0(130r}AcG*`NErVSd3s0O>V~5iOUodjbBw zhxwI;ziWFxUDurv8UI9JN1#5&{AJtQlFnG(z<^G35xTDe+BOP>x{9AOLXdg_s%{|`G32*1b>@{ zQTN>AKFA4AZ`%#Kt#YfM0*3-a^6K{te{V9cEz=Aa_X1Y(U;C{T!G5g*K&pfT+2$Ev z1ADvqWmk=VT+`0xMg=iI{%hChp}oIMyYK6!UeLEOfTA)_J7Blqm**-!QSckvnZu;RCk ziX>3vM-|OD>I?Pd70BclMe;fyUhL;O=_?-gx}ULW{r6zPvjB>K>O`iOYb)? zSFxiY5Ss8=@@X$4ce#I7MkG)qfP!o?u#M?)`fdBSSiImlH;}pH=jOLN>o>Fgm)C7% ztLq1IU_srM5G7Ub+MYKn7X>7eMI0w`uwW94!OtK7qH0Ck6Ks22%hDK=!}4 zg*pWYKnCOh2|)J0x08AW2tWqi00}_$zqg^f1qeU}z5oG0{=cWM`UOA+umA}__P@8a zItB!+Hj{4g=~wfwz5$23#=)v;YA>{=cW+x&}Z7f&ddh?7z3=`UVm} z2Kxa2KLEhD{W=H!KYvYp*kg=v!MX+Lwr$(C?XPXywr$(CZQHhO+wM8%4wFglPAaLY zpOvg9>)jEQTk7j4Lcu)Em>>~2u=zB5$5N>%4_1eJi+9_jJzLRVT!v3=TkPiu#B$#E zA@9-w&VSvvZ>6rw^vJJd^qX7i&cWzt&d=9;_1mKzTv#}NDu3e~WyyI1?jYIVzIw9t zBVAYov2dp9c#~krGe~XIncPG22h*85W$Y420$KDp-AsX8qylhg|C!pOKLKOR`DhBU zl*pxi`fM*n0MHBwHgzJ{0WMqf5st%bI>tK|tW}KHsT5^`u!J=zW#=Y~&t^I1-q;&) zf$s`sdbmq}i+?m2b7Ee*G|$pj8V53_2}QBglmu|{M7L+hXedN>^b?^Cp(7YAc1VMW z^kw5VSr>ys=U9;uo^z4JZe<~t%I`orMzdKAn)50%3c}=oks`f!tH+FeXhMLkG8mmW zNpG$0kh_TgL?C6=9_*AziZmm@v?ZX2;c<>9+74D2q<=nXgcu0YZJFBhlt#XA<`0mq z%aQ3N153|0)lfMEmBi{=r0nkGRJG@Xlb-b2QI0{E4lPcecEz-Ih0>%NcZYia0K(6C zR5}F~&fCIzxoX1D2Lq8B{Ob48xmy}O+_nkbozt15au82tIte+Ita}d)7@)c_-`k-OEPF(fIORX59lKQ@Zpzsk z4VH0T*_q$R=m3Wg5eHlnSg71NaP_b@s@XgCHwXej9Z;{RK~W+_a9$FZj5F^=bw%6{ z31m8vLUc~`A2-T=VzlmOL|U1IaM#j%zn1!r(SL!bO}`_5El_@#Uf$JuFUJ#ouaNpG zI)+{?3qZx2sgDotGvZ02>WZ6yQK(At2|#~tXKH0AG7wNKnqs-%N5c(Gh=$%~pRMfi z5jOKy*6kwhMJ38c)`K8AC4AfD63y!&BzwAI|2)6MCkOCq*O}n$st3*jgt}SE+R{&h zUVlM{AG854!@r9*W5|AW!~Yc>JogVFE=w5jB6U%!QzhQhfq;H4O#kzZYubgg_Z4l4 zc}Ao1I;0RhsQS)V6P>a6`PL3&Q0Q|FmU){pZ!=4nY@vAUeM*Z0vt}W$O?ZHhFg+wo zY-Fls@P2Yj+%2czkO zgBI3QZD76g)7q0557#T4dG-mDd5|Da*1*-ud9D`my;FL@7FyMdY0|}~ovtxB>VIM1 zXA$oMWt|TV53|(=NoMd)QG@$rF^UceV+&yf$IAQa{*y(qNq?;s zn-MG$3Z=BoT8VH`?3`McM%8sw(WFXu5C#oDfWcUaATk|d_mf$NMR;;k%D6Z#~VNT;OTc&O*HUxRi zTJ<})-yxa~nqzd8|9?P#m~dC75ZT|iV00wJsdqi$?LR#ee}~wnz(C*&V~!>h`cN;* zst@cNxbxp&t$(@{3Px6MPMqL)3)1AnY(3}E*@Fqo^On&r#8%ltMaTYTvw)p zMVEE~M`;dLu{+}g3tfld2}RVdU=|4kp@=*{vYgNlCE2FJGblIobgA%ZvyK=7VV5?_ zVR!~5${PhyYL3V`k`SMsAEfE@3N$#@fkLhEltqgP)_;jEOj^>mrlfSEpz{ajbw&4K z(JaDzt_k_mOvPLn!?cF^V7re|Z?lY9o)e-#MAs$XEiXu_Na-tDoDyy+7iW{RywWlJ zZie*UY-j9=(DQ$N_RxunlV6J><=P;E-68}V)A;>vF{8Hr`u^x>uQj$}-=QNe<pd|$YgfStrn&Ky1J?E==c@81SmIQurP7Ns0%fA9z(Rz`s;*csTwcLi! zbm4WRmvXxqxGTxB-9;9EC*@r1A`zA5Sf_a=4)x^_#?)t&M zkVf{nYQE@Y!6je29KZk~L{Xww?OQ+djempMrR^Bz&pdS=%@_iOj{z!H znQI1QBTG5P6)7&@TaOyk-)KcG-W5;CkVoH1=#pf>i0rJ*1~}xg*<+ z2SRq+xWpk*0}Urwj@?7G*lk^(IRFcj+=DX*T|tW{nW48S$H#~D6a=&hV1NqPS|wDk z-T+K@oiGFh-@PRB)|q*$8UIr}d4CUu{ex1|=C0L)0o247`#|#X-UJIhD3cvcG68pIn2@``;arM%Ws=)|1!H;@d>g#{rhCmOJ}m>- zrnNCusSjW0m782mVW{b?RZ*| zf+83Zr-(gZkG#SROOV73b8N=Et$X^>mrxNbSAab_y(i{R*7FqNt51ItZiNCQy;e zup|K;f|MJO<>~zu^OkRiFMn-9R`Qz4a*Y2mmc_zhHt%DO;v(=}74~G-*803gFOVX;_jQAfc1u|k?by2K6o@Ad_li(6Lx)~` zUSkfz{P9@}Mg+9PPJ5}SEIfCaS`m>%e8nw0hRle&-5dsLe%7if@_+Or&d_I6|2*a) zS09|np*iWzRFM-X-jytPn%>CT7O9=8n#rdB_^sm?9G>{H}>#Y*a%i5`~@(gkbq;C_q=?}ow(qf zjQBv2Qq7MxVN2i(PQk|^1W^brzh&(zk-O}?Bx&t5D()=sVD=JI>uo^z+fvr~Bg83EM`{}&tClahuC&O+( zekJ9k=x7M7D`8xLRcF9eL+vgSRFRm2`pJ*$g|4$NHtp{xzoZ+$9r2K!o+s*dm{ovDmPK)V1zEAD~m6`nkc=ywQ%CDqCLRzHn*m zLiCy{!?ZE>U4Q$mtA4w5N!40onfp@n{=6)fyk0pbxoII`N{^l}GnSscSYyAd+$_1Y zl{2_!NJ_}H*Biu>eJuJL5ydnXg#_XRWeW(yUKlC^Pb9~#CN$rbIug!kL%jM0wy{gS z$QYdJBgcpj7QD~sXlD|ErvACdLMbw`I~R5ig-xo!W`A>Or<^?ici;v&5xPnrM_KTE zVVIPQMLGtTH@FT3{$7JcxFOrAlr|NfFCp3iCA1P8@9~Z~!UTmDs5c<42~DCNFjVZR zI2H9rnB6UA4yw8_09i06xECr2e3&(}Kx#I-h| zB-lWc;eX#yn39keVb^-?h;JKASiqGCMRmR3?lLm|cdU0p>S(})YF8c!W44{AjRu3K zDK0evuQOE>=mGSFF?K2`=sx9nD21<+!Q`Bbk`9_=)ZPP1 zS5dmG<<|+pPa0NXU`B`_+ywi=M>&$1x`i1TW%qqXw~h;h3G1*T_*>f?tujn)Nk}m) z%x5-=kkydZ^0k=CRBI}4lRPX}*b7oic$6w}Q8t^yANAQic&x93vG0SBzr0A4i&(46 zSAP)clxww0(!YGFWCUl^hWAu1N^-mCsmT+5W0?nbz zAZL?dM;2W=6a0+vKyGRdE5v?JB0oF*Jro-m=_z}$= zp?Up``VELDu&l3$?S20)TD2g#0waLxd4nU{#%@LU2GG)*U&1YY;Jk8%pldA~PJbt< zjP>{EQRGnv2;Ok;%STPk`ymkl)|;(8EPoAe+rh=y3!13?2F@Ys_-TtX65L0nK=0Kd z#zyNHsqX8pv709|OJZOP5P{22{3de{n|S2f%-lA5`S0(V;`ljerkOI3Znf5(^o!aRTpku^2=Soazr${*%Klidn!RR}sOrNr>Vnt#r||6`}P z#XiLU_0Y~R##+X096+4O9SfgrdGWMIpWpMkO#x_mor(mI;_Ujdm?-Y zmrcc@wo^>)0hmQB*Ud^X@S_SSZZU@K9d4>#4EJY%HpP&{6}Mv45$8uUJ{6^`90Q%N(Qe z5eeR3#RuW;Qfk3bXwApu54ufCOnSb@ls`T$QYL_@_&nOoB&ZXxdXas*Q>oRT4ls$g zPn+n}L+0$SEc-a-_)Bb?l0uLROtVW-yWU@B4O9MQRMJM5M?eC5sOc7Y8jX`rlftwRw7AC4dj(>#kMYD}0( zKuPt{??o#RbZ|OF32|Uqo{(571R#Mm{iJ!nS&S4~+$|R7!};Jsh)07iQPmu~?2Gjr zek|g+&W;3$kUg;WI`4PX-CPEj_9k3E?r34Xf0RKA6@M80!epIlN$eov-*}hyE?K&{ zzi3(_SY#`oeUQ@{I@SIzY){CP^ZZ#>>A92;9kJ?`qdRxy;UVi$9eH;*HWjBo62q!Q z#ZCJ~+222e^sSE_WgW3-87|4dz1TPqyuMGBt`11`$%!v1c{uf@ry{6_?c9y*|7rGk z6?u7vs(-QZNX*}&GALXM+*E3F5PPy7)t`RByx&4qH$6qw8TA6l*}c1!&2ew+(Z3Yy zb})ruEo2rc!o`Zu+~mNlr$X}SGeTLe)ty}-n}{=nZl%4bUq*BzlBA6GHrtg7eK)<~PV zp>Q{V7!I0>KTj7261%*&UK=!Y$RYI%c{g=s-=H!=5J^6ust@MJ1CW;;7HpYzJ+MjI6ThW?1 zQd5ZePaz-~F=HU_rKh3Bf{#ap#xJZ`3(}LF zg#7`fLNiS;F~XrVJ30eTw-$~%0ksCRnoX9xt~;_s>?wwBVl)kij7Rclp`sP5hDa=0 zYccbQ+D1mTXh!yyN``ojz!aSZ%Q)w4D{LL4wFpKs^;Gk;^1rptY32dq2(Y;r8Gk(o zv)Y(RryN9@F&|~WdgS>_0l8}S1~ts)T2Cib4RQT^ImUCgBG`1$iIJNaaO3T=*b*Bk zYpNP5^{%icII|1qeZ7VLT5SW@)q_p+LKR4|$d?7C+79{S{&sSv$PfPeV!MRG86bZKnZCDrQztcGeYr55FRCq+*g>&}Qw z%Lo2Ndzap#*~Vj;L_A?2G>6vA6u)iE%BbClLCs32F)ng9c*a{jYFw)T+_Z-wh%ghY zJ+<7?!~#Z5AgOH`d>i;kZuFf$R<{a2XTZzCg_!*#sqDc)xkqEZ0Ad~0>VK=ID%8Qj z5)c6_+LhHaG|g~bA4b}ER=%nqO2MMhYiQK^BHy)CZ>SwF+-C)gUU0~-s<+&mB3AAI zoGf5;?>_>nAC2ZD0)8jA7uAFQ(5&R{$AKTx6mMgIjka0e48d7xK3k2ve|z9|M|}gD z3r;i=kxE)^pn)ja8gOZCv48c74VPJ;H4Y;gs%*ya(D;6Sa5DK2aU>KATnJp!h;A_j2dULxaXysqCNT!!}t&+ED+gMj4{%t_MDqH-B~IMvX~@(UNei zexxBDFQ_gNSm zjWyNQkwZ@bGS=BnLHjX)n7u^CaZRg!B}!eHK2hyVkvqXSB#ybVA*vPG=`-DP9M)0+Hx*XWvpKL^z6z9>&m z(&wRswhaWS8ASSEe~Ld=#4shYczD=4L32p)>FYyEPobKaXlrM}EJ}YA^*k0ak|Q?| z?*LvX7^9ih_jl1C{P?!4T6Kkdmcosl3eEX9E7+$D$gi;rmG9BJbn_a3KAhx2yTjSA zof~ObA8FOgacEskt5#^&IE$uDKpxcZi8nSjSqqg+e;pONMa)v25Lx5}L?FYexB^rsG9!Oen9ha;vxVQMBXXI2VoR-VYd(!})mzo4q+`>6RU{~D+8y8Y z9j(;id;bfrSU=0Uvp`tCbp({7`8AFd0JOJjnvjmyCZ54ojl$=nX-v4ztl_ zo8Z66952`}eB%PebsvK>@(8=VzMd=ml2t&x4AQR4rI0T$CRdzj_rOFaSw@H)luSO!GG(-J*&| zA`vxdJB-qGl>Ac)0lFp0eq$~oT(0`Sxv3t;6JvW5-q2ZVPz-=kdc#YaJwl`jSK}?R zQnFH%_F|=Eb+&!W;21b7W#D%gl$EC_Dnqpk1v3fy;;0axjxNUwlfbP#4OK=2e2L| zWhNEdPc*rgI~)@fzgtWDmz^}1vyb;DlNkQIqN%OLIlNDtG5Eg$1dEH-MWWLXZy|mp z?@;nj62E_s6|Eh&Kqc3DdS%e5>}Oz^g;lH;_!EP@TN3dRwOb4ZVb`4eqz&m#+-eDVugswln#}da@VZ+%p?EY|iJOi#VF5i_dIktsXy#${f>fm{7G3Q* z+`#&Xt_varL$v1v2BbiAjZ#VpMeL&j1TlYIG!1c^tEarSVhsrhX0?)dm6DpepPr*d zXISBRYIsE$J3+tYB*iLz@=`QUV3NoC>x_ChxDpIzDbgh=$eKTNO5CAjmZrkKAd`E%v{YK`=^fJsl&wda%{D$s_X9 z&QshC)qT%1`WeDhA_U!vCQj*PQ3roNFB>|-?@b~OA!JI?$JiX~ea#aH<|Iu1=UeB) zQ}O?X`5rG_=Kq@z~Q3vxwIo$r$@XA&l+o}!-pePA4xR|n3t6fp5n5cXe_^g(E zM4VQ=DMx161R<0yRo@&aEf{M}r>hVt#*{1UufM#wtH#{~On{!X+LCuQX5>&=2u49A zu^Pm*{yrQzEx+754CHeI2e*H|Gmhk*@*2cm90Zz!&s$K5_Oa>bN(2rAg!iJa1S2I^ z#sgvt1f_i9M?|f?lXvnXg9)Wb=%Pq#qz`SET(IM0NVcP;nH$rD$8) zm)DCsesQ|=fi?#Gede*d^-qEf3vW4F4|&h_dvk#r6b?3G(PwEfXElEtzq>a9hK1>Q zx)BJwj*8fwikOdzaPg^Ix)L=&3X}_Ltj-BzV8J9hTM! zH5PnZ@jJ2enU?LJqkEnl|C@Gs5gKTruu6eS-hyucsa}MiBmD!H=-!)DS74zWj@7k( zNkZ)g9LnR}ac?p9*x`SL`wc&dQQCbe9=*=g zE`vqm+;tJiZ5URqWng;a$47=w!Zk0qCtL78ZIx?Q2O)5qXfl7z>$ulhE34KsE#i5S zs6ugpy;1p$#>w}G;$#hW=<_WxT?(Oj_sk=8^L4>o3C>#`vy8H&APK8xW4LazI5{f& zjxrI!uy6KK+O$J#M8GrHB;GI^xo5DW(UJbXI3`>cxHsM^&zW}%mZxfdB+GB-F{(h;ZciyMPPq{27>7GjkcOThUZ@J>|$`aV=pVf*~BCj%wlVB>*jM6&a(AJFxQv0 zp+G>Cs}+5!8s}yv7V{j5go#^^qqDlEcfAa@k{_PgFosrJ_$N=QLZUAb>ylIXVxrHg zmwN0&L+rKWE7A@sA(#*DyPY5%PI|vJ7z`S z$98I*Dr$D!el+bM-MB}>Ad*m)?uPZF3M7wtJ`8KwZifXSIt$s@rWxY@!_Aw$!td!jYgAT+98Po_Z);fKP3Ox6j$sKLf+tVcQxx(b?it$ z=$;dPDdvu%A&5Q$F?%?!xybCP%5h8F3Z^PTo_qi}|vp0U)hAdHa(@qDn+^4hApcRo}hXQklFY237>uDQEy)rbPgRiLg( z0p?$x;8+Gfd4>v?mazzi3tVWMNfqcApDOOsoh|g^t>*sOv2 z_L+aE`Ca@6%hzQ~>ut$>$@`V&`QVv{Uvjqc>L+ zuV2Ns!uuriBPCp(IYuO|skJ}wpd1VRqP<`e4AOx}_+AX&gpxV|UaVy$7e)XtXdg8Z z*pePh1R&?!GJX`()Z@(~VZvjUHo$Vp0uX9QqNg;pj z?3*XQZ;afTAk#9&C)YH|ta>iZ88&+F?F=m906a{hBS=bH_s@htOPQ^P6?~b01#V#K zY2<4_`_l(`2pe2*gQkZy5P3-Jlb^2^c&9SPq8GuHB9!$AYr^^aB!3+8PB$*UhynD; znj1^h`oi63#R1MBrKZm32}(;uuLpmD8ca3J4F8+t=K2lDzNwfmy{(DVP$n7I2yGo@E^(YASOXYLXS%N zT%K2G_)ZU57>$Rc%^CaVAidZb(6F7&G|TZ@E(RKA#(Vl2uOQv{rbBVVG^~Fz!0L5* z>Q_XVkOK5{z8B)P#2fH-mQGMuZ^6ch&c7m@g?Asg3=ds={95dmf4l@2x`fr}(&ZKe zX@(R_z@!BpQB}hbRJ|wX25j$do(=NhzjO-aOrHy8&ef}V0D%$Y=q~%$K&V?K39sVq z31&D|5k}lfv^=&IbO&ZYp%Z_oHbphs04=D&sz5cx&jnJC4cFXvk_`<1vP+OocP8qFaks)SeZgWil# zZn{V$(hs(WU>(rtGJj4M&PTm#4dJ=0_VCZdb;B3ujajU$^akX(YbbvsgiGW0?w!nQ zuGF>LHsEAMFVKQ-Hb`wq4Qht6Hf~KpmU9nZiOZ!U9hGf;vHJX?v$TIoXiQN=oUod5 z&Y&d85ByjKZO`MA@SvlH<_0rE&A<8gWDb1cW@iTuxS#AiK-?UIe#D8=tJg73UJ`Y# zm0P?4R7A#9I5lR3l%RiC;6kV+>!8rFNdfDw5=$kx4`V~2_s0}T$V|sJ%A%Pu9+{g*sOn{S{IM1=lLP76TTws zcAhi^40q-U-wHJ>ym#ku4i`)(OL_-XP-yA-_8Kka4?9uKGPtv^VF)B4u2kP$cc^u5TZU+g>rNVjC7QyETAiTF#I1iYvC z0d|0_<(XVT^N3qfZ5Q0auWGA&{rrr4?M9Ex@M=xiU)+D2;og4?+!=H$7_?6nS_LR^vh)T3~9YJHOR?C#!7A$|-~A+r-l?Miw;HW21%^GlsCUIk8p z1_c}-Mj^{d<5A(@(j2gQxgd`zrY*kj=5;r;93dsDbjVS$__ZTc@Kns7rlIQ50rs$% zvNbv$6+?fLDYjMSApr;=v;U?Q@?L=0jpZe+SPWP;iaSe&VnEVWmnmY?bDj#NE;-jU z5LeF;a;P*-v!kl&t{Dl?=@LWrpKO1eZotG^QO!KCj>5A|Ob^32QJ>em zl9hsX7&v+^1##3Rr$5kn^eCpQ)3VNH$V=Nq+d~0)0`l891qR!ZYLYRA%sG#TXK}bXh5kQ{2G1)xgyGa47ATe+@6U&2qA8%3#grb_lczT;grYgwynUj% zO`$f$G@CVX=S_+&XJnKYRW?cxAH$WYrVMI`#8;v%nrC|_mYX&YD%WeuYHBv4&UbOC zFaVAgkkrN;s%gP0Ei`e{5W>H3oz=<5YSn+2OxHLOtGH5B*{n{Yw!m82zJrOE0O?#$ zh+>cZg3A&ajwVpNat2u|-W#ovY^yM7}O~Hq#BV#q(xbdyrQvl8xWln$n zexsBUAgw65*)qx4&DF^wqJGGu4(Zg3WRN=vOuC1y;y<|a-7063GW94ntdn#<^DaL& z)M?RmzQM!4*8CJc)$OU3OrC*7EY36T_C8!bL*cyw;P z4WVD=S+y>KPjP63*2)ihaqLoakDq@7VYd{;OUnH-;k|+KLs+bIkaYPivPmiWdt7yU z{iU%+bi0IlhZwJ;#x>AYbU(t^`eh0qir~-+2c z`(Ow9gZ;hYAGp-}%RoQ*toxhp+%qQC`dOp@JKOWq?LXi9`<%Owo6ySt1ODiH_%01>o9YYuYwEqM;}`vVR~q2|+fBRe`)m8txcGbj zs(V~>`TO?52s^y%8>O7^-P(WBeZT8lwZYsv%=7zWKi`Y{qk0#A!;YlM`2BF}wA=ct zYR2>%;{Ut#(`xv>d-UtO^u4>q4gS;l{Hr^|KcoL!YHickN;IGyEAgvKv7Wm7yu0@k zxWoU(_w)R){X6=@seH@f2NwQayWRO+%>UaIyz~F=3j0%ky}glkKpB5ZKlA%@LD^uV z`=gkAw^imeKCN>7n7Di6=Vs?&h29Cx8Obi15?=78^tJ#YB zmhBN6g3p~A!t@j!!32Ma3p@?|d{`lcwthe>KEYPeh*YvmAbx-H=C&N!*U#=omn`WT zvKT~0|MpG%moVMr*c#X(M=W_M`dq11as-c@y+#U7k>CUthqGiN~v>KnksfD)Ov#bS)GS?b(Ttf%{OYpPJ8C%jBZhP9*j+I z$befieEgSHPxEf4k@Eat)^Qp0(yqrXwQ6+<%Mc=`c5Qz(I{*^&Uy)SvPweBu z+Lz#NbsKuX-o)k;+Q-<#xqtZW%dF+C0rbIIX80!w0RH3lszSTcDzIN#hTPRVB^`R@ zYQczZ#j1ZV{r-KH+Z?p26&D4jD~=%RDo%rLCKK$dtmPL6%AN`vnpO!NUeEK4rHuC! zt1*SIJnmnPAN~7WrQ(K$W;o8KQ^P)!iv5?M-@vzx9c`|Dl){?go)a>0qr}r{tKA*n zE@B`Y?agp@n$?lpb-cgeCyq4B0P9&Vn412z*kga@6mB%T?#ye-wAxa{@59!2*w9ht z15TkW`7tWEqhO?19=&i#& zN){HCKGaQ~SZ`OYW8nw8UkiJm4tzv%xI%yY)84Ch_gC=!;`v4@=7wE1*&JlJp|^nf z0Ccz0bFO{xx##}1PE5zbOvIzZqfuSBXF7u<{Lfa~-^(4(*D1gMO0mmo$TR^A0HA~p z@V`hw`u~?g(!j{h(89ph>HpdNj}2-Xc3T_>zI%Ft4D_`66Fefg0VhB{6p@3_H1&U7 z`~t0%qS&~)5qz2d#bI4Ca9Jpu%@twh9>MH=hMm~)^&;NPoV<#QHVQ#0OP?f4r9(D~ zWccs*Y2@*t?4x>@)I6_tMJF7053M%s3}a`4r9{21 zBHB_V<&9~0ibiwCO{VH4#gKWevK3Q0fmCN12jPF6c`i<0 zT1)T>;SbWL832Ks5U82pCMiGc?5#D4T17QA+DKlLz4U2=C1Y-tsrHPyC#kPF0>%0q zjK9S~VJ%BNyFipaJq)e1OYONoNTWpyX4&)wP;rau%ic)Z`8E%Jn=z#POm zZg8guX}bo@9l+*nkW%DM4;U3cAz*1(%prd~jf$vl}KDM!9 z=~-lf_{iT|z z_NuMOGZ^WLtls?~?|!lK@2PN6#n%E$cBZjU5oEJ5O*xxvz}|+Rm|e@PLwk z^n`P7J%dWi8325~!2x;~2D0}d3EDR6PMZM?^b!}1izfE>GXb&Bj(Fm;0w8V`o{jX= z7VY2(0}4Wp1`Q~S|4?=pAIUaxCwG2pzwf(5c)}ipk7JkkbNhb))i*})871hBe@p%n z54jo+OOU+`Pyo?C?u5wibG3{AO)LKkzMEjF17*zgIJ->ArFk3_Qrud!tdHFf% zmAmeL@yq<$Mst7vg|$~SS3z^gw8k!*Ef~7z+uyKvGi#k+lYdK~)2_*)B(Kb1jKx=T z<(%&dmg&6++4)}UGX5R=pEjYeNNcz7A0t%$S0l*(HzP#soF)I;BxGIwM+uEB+y5xx zvsXuuoQ4)}tm|x~-ywjH7BvWsa()Xw&URu>ET#Lem*szNRqveLMIs{dq__g4E5e32 z^I)Vqo0A!b>InWzC9<`UB8dkY*3bwz!aA2e(Hax$KU9>VV&Ib66K%*%hIZTVyxzsY$W0f&ny2{N6A3wA{!1eV7=!UmtfV}%Xlz|gz-i8XvxoiQ$|PS= zW6jf@JGiWF1Hd3d{>|8`!cb*IBapMTF1H(E{ZIG~u)D(Cj*zTbo*r^NvCwyBU*imVx zRfh&jaF5>_ZB%dG-cyLWh-#)K-_K?xa03HDD=r^Xd;#K6)NZG{0!%thfg&8p<$4w#7g z2X#<7Rm@A(P{#uL{Fy6HFxxa4S)`IEVZdiRn19uYP(slCG0N?Wh8hHf7~Ff zRbeY54PB0F`jNzx&R);Mb1(YIcffXw{_EzEK=+y6>!i?H-i^V`&^d&cB0$zSUsz&| zA?BY{J5?tKFe#JaqE~q4lm!k4?a2V}voiMWyY^J#P%_8-TK+zHWkGE+#PEOgwPxZw zD&tx3d$$$+{P?G#{L1wibTmG}#(x8n&<3SKq<22VXzav!B*G zXU#Fo4=9V8d8Uy~!~RnEIUj((G%y5<+e~Bu2pbc>GIVagh~3RzApC=N@p!%u<~mP| zLBZu6Z13MnG;^Zpg%EH+j#+;Y3$01$B48d|jrW=d?d>80LB~SZ-Yc^&$w5E|V<7Zq zyT4Uyp`hj1PcF{&R$SYOQ(ig7V5z;~BY2C%_MxS>U(x5-mHqty{9nHyK0PI@KmY(V z@cuWysQ&+ciFnu=*!*`Ek}+^{`Y&HH2F{Ka?*C`enXuhrK=FSWp`cm0ok6Y3An(+R-_=H(hZSfvyO z8fXWFG!$Yf`zOdT_asqeayRl;i6Q%oYDZHr+UJpIC)TT+1D?)U^hDY}x}({z*L{*; z?$Y}y(jnQV)&;bN9p<=h>|u_GavAQb51ZbuO-o$h{%ZH_<%xfZXNa>#0~@EAFw*Zz zbJ!4MMfn=R`1;YK0EX1wfup8REDKW)JvHab$=XH#fFzSb8L_Y~%sGnwv0_c;@Ju4W z7>)<@U@H;F^3Pub#BdvInO9He5RvOHSKb)ruU5UqYd&6oN`|z5uI$?Knexrr1^oJ_0YMw#lse!(O_n?c zbjx?nO|v(xdJXD|(MtS~T>*9AkAtQ>I2%-SlW z1}C4-X~k*2*}qeHKu|;Vl>hP)W>x?3>aH7tw7q|*<%#a*-GMHy)pk`raZq$nzw2D{ z^L7~586^9=YN+`=V81z^!vAjuDVPVXY5vn8wBi4^3^M&M85B0Lb#}C~FgCFMpCsDZ z{O9aq^MC)4_`m8zdKwyoNdl4yWxaMj^mBoI0FVv8Km%o144rO7FN2>qN=tYknz6_w9b#49Jf0l;-FMboC-moSjJhz*F0=+rodZ zvAI@MXcbkFVoC}dtfLL*?o639q8c+LpTs(@;9v~T1Kd#(7DM7gP;6}9P z?JS)e(|oqBxA;xvjV@~B!=FE3*OSb(p-bhHQguGXY;7t97uTjql5mWsu>K_@%la}Z z16gbw)F6A7vre?z@I2_ReTHG<;Xr@116e{o))I3N>~Jr8!uF*93>}}*yxScEJKiYo zANFyd?M~2cWeA)5yAXT`Z|6V`XY>KwCO-QPob6?|1 z(C%djy99d>TqqvC0pm;Pf_&FL1D3W|cTTGl0D*xWsQS2I-s^yVDVb_n?}UGJW|{K& z-26-h!P}Aj%*c^$r;s5ponQ}QB#RH~2!YocGDoIG%NrR|dD*htsqK>2 zDYQK@cY+s7jq)Tiju``1tN zOOn!~3`>??dBOSEyoUY{O3r^Vy0Wd^*0F6H6&n@XsMt;_wrx~cvF(a&+qP}nH`)6; z_-;FGpL_qVKXbL&p58})`*_zP!Z@lh9|Xo(h%XYZ12q-{>>rB~re>qxq zAE-0-((ov8iKcL;s&!R;%4A7zmv~CWJQ|Dl?oJy_P3!iV0EiI?s}_ITGn+AVfI@#Y zpmnK7R1IXI$wFP`3Wt90v+eRuE%O0J_oL^k!|uE|l|OKWf_`LxZajlfHs#=7fq$Iz zx-1pnS7Ptn_{qDu`m0e?_6+=v01f1A0IdL$?}?i#iMGQOQh5qJh+#{uBU8s0Qg4>0 z-o;)KLU15#weyGXtM-2@8}U0Ds0CS~cu;%XcWTxr$WnmnyPuZeB5wOO+{QD++?Tja zHV;ZW45v$IZPYP`3f+Vshd9>nCue5&3mspk(ErnbqVCfa^w9pv6zKlJ6vVBZjO^@< zz8v8{KKsiNk~FMy*--{I9ux>3j6^6wR+1!98K=2Udnl>OYHNS+eaM2U_hJC;lD(d} z`;!8gQ+~x;V5zelJZ?T--{=JI$aI`uk1k&Rkr^QpTC9%l3KMRU3L_Ev@OW9fol0D) zT_@>h)ncV1v;(5D`IUMw=(1&cJsl9@hER=*xSZ$lQnwm7$Z7%X?(16|29uOqBzQZ` zTv9k>*s`XsVHSU{#7J0gDXV)~J~Bfq8MdH+Yl{F9dry%fjZ7?4LoFn%W@9)jt<-*v zz->IWt;8~BRfkdMIcAp5kKVrZX$$x1x?Jrc%7lM9Dsn^Nw?7gn09=DA4A0`isI`(y z#9$~7xHScvLeWfba?@qY4s0BMZU8>ADk;v|s_hXD=N5lRIA>nw!gib;7$-@M>Qf8e zlGjFj|Dgz`i)F8Yx#Ggv)&i@;Y-DuJ4pyi!XvmsQQgakDaA!ezf1Q{_5~wERk2ikI z?bgn~Rwa5LIn;R*=XqEvbQdd(UO=wSgf!oR%8@Qq6_|kmaImFvYmn>oY*yv4_WF4!A zZ%@$AQj-l8Vwte{6DT|D4BW05)AU-`79_jyffIjLIqu$K8I+rC24FF*%!-MvyaLy^ zXuFU+5)YpB8|3csXDtpDLm8Wh)g9vXFvG&KiY z$?AV3TTQkxVz-;efy_Ryixbd>^@rzjjb(AmX1b!X*c`CD2VJ!kIzEGG^wyiP@>VO8 zE8!VwS*&QergH-aN|x%6hY3-qF^1`pS+x@~K16W2|Irh_j92P2*S6d=uf#Izl6=xo z^VGR<<3QYb)r9dso&$l^RXL10#ihn^$tizz$s!L5J6?cC@L$WXd71IsQL}l@oAY~v zM)Zg)TT^k*BLr_T{n+;@AqtX{m%_qDIW#|m7{rbmL>7ON z|GN}r786k^c|chC0zMJQg-qZk5;SLhNi2p#9$!>G!Z(U2@ZItb$}&9*x1_wfcQ?0=f&8f@~$4{v=g>g;ZR?PX|ucWUBS zLFy?9FlK1<){t5qy^4;aK#i!M$liarpNbtEJV(<{tQ`7y+TVDeOEtV-`KtsKqW9OL z`Wz7AaR14N82-VBM2#H2JV?M)@2@#Q#M;il=wFv5I@a6l2;LpCdQEgKNRYNj!Ffcb zweT-C+j;T#=fHWJdF??-_M@3=vfc*dZ~-}Za!vI=>XV7{D4g>-+JQO#a1 zKdBKn_0G;4YG;0<;qCPV>p@wZGic{8f#i%e_)uSTlD{)5ZZWl^9EoH3yYKRgz;o zK7NIBJu-On3ew|((kQ%wmrmjQs0Hd2vY&v0f8+3OrqTFDh?{VbRr`M{+<3;8A(d85 zd!pc(dczR`PVSb7J(2^H6k&pJD|#CNV(FJq@I2>o1fQkT`BrW8ULj}A+rdZB$v9KR zL0z=I0?kC+&py=H^tDn6IH1Qz949*om=8_dv;qWzTTJ)-EaE~?PZ`l$^+wSFLaZ!P zULHot$iH<+ZE>DVaW{tUCzwiCU~+wb`50i1omQskM5a0Z`tMQnKY zJs#20$i47gU@N*>6mYcsWQ2erWnZy{cyg?Lxz31XsW;QNNno!d2n3@G*+RHnk#~2r zbHM{VA4TBdV_X2^HVL|TV4fTO-)Y$@SnmuB%bD|~MBbArNKb!3uEdz~e^bd)cvaZ5 z1EL^I5_Ron^)hs#t7eb+>)z_japJK`Xr*`V_R&dJ>{aNy8=Y9sxGR5XDh?0Tpwj7a zAHYlfgzERY1+KTwoPR}6qpza6t6|28E-AIJY;ih-hlfzDbU?CKM%_rr=FNS>p8vUhX#{c#bOb z`9jO#=q$r-cGEayBv$%lR1?(Wc2VY;f|gD0>ruPRiQRwDQj78Y6wR8IHsPZ^gSaEW zOIyul0sN-ORY^1}&6mn4%!|<JsP`iI&t5dQE_d$F58nZl;?fT83 zR|2x0z^>4a-nL8L*V0ezH3-9dO0e&Ka1EwzxM_@fy`X>j0V;`e zYt?5iG5vqXT*Can`+=yPo|CDA>;Gj5Dl1mo^k3sjK`bX>JHL!Q_6_yH*iNX0C21w)b_okuyFw0P^(n7O zdOOZL)IB|zaNIEQxqg7~?FBA{r!+oD7fWTo23-$-;Ba#+OL;pTd zq*(2;Nr+cCwVREp?pTk4ts_Y*Z?h$tfj(n;0&;RC&J1t+)EGjtQT0I!0>BugA&+bq z6WV{o5_OxSw0edU>dK6GJk)D`y)-^7Kd^oxlDM;vOonKrOoV!NMgJlD)=*Ya4 zNHG9lng=BJ8acRo8QPrH!?2#K$?lQa??`9LQ}-3Z*T{6RJ;4O_cVCTwJuTT#XmBhC2;|R|8h>Z&MGZxHM*)2`j;=g~a z7_m)pmrTEzXLp2*70P&GCnGyrbe{4JIBD=h7IUzEw;d?pwCp(slK4Tje8(0Fk3?pc zJvPwwSU%36{ms!1XhsE_wfL#zQJv+^dfHv?qj4}ERWw;lj|<6wmKao&;1)Td!dUVO zh7%?w+D!sh)DSJd&Qb~AXB8F*R+WF_7vco6z2Wil!oLykijW@Tax3}vT=_l+!CC7?DR(ut&kJI4`@A2yw8~yWVYrRfq0P$?` z=m8=%Ma;H9=(n|*R5D-iw}KT2PnLb1+<+6d|aVSwFF4N zA1pLHb@8rlCGvi$(E$Sf`KvlG|Hta!+kaOhzk!3Jo`bcWJ)OeeLXmZNATV#{8Av4?mIgP>JNWYc=zEvi4z_G$RHOMb|x9Imm_B&3eaVSIlHC2MQ2EnQnevJHl@%GUQgSfkA#xTT7ewehmN8ClMy+lKNc{` zFe~PU7%y#_%UJYIDQClXco_A zNuiX!&9M-AVf_Z_I}m^A{Cm`pUpTa*8;9nn9Pcy)jTkS|t(&VcXZ^JN_fl&9qp-{B z-jeD(U87XepZHN^fWa_7k?@Se$@#<4WM0W|bHjo9Rj{ogfR72!Aq6x@t*k9BTX=yT z1y3(psU)mYw*?f;%9F9qoXFTAvi84kzF)*a&^mU0uLTHL+7W+8KJ3i~A4GQ$s0e(% zWe+sC1a%SR2L^s8=zJucEF?Z;tEo&n7->H=kSgz0=A{)SOngeN(c) z4z_{!8EosNfyRG35ckM{CBgB*{1*IV->c7 z``kvu4_Fs#6!YZeE~sxLARVW2^{cZnE@b^L%vpuTgMqPFjgwa{Zhz!AisrY(>frE+ zLEk#W^qe45UxUGC-?v`UJ)c3ppvLTV5A+5C01$=vC#ZjE{}E~_YiB7VC!@dmupi<= zf1|CuW%Y^nd&ei*yk#hzi=+WiMaw1yPRMnN53PlwW%mKjbfq{qU=DwqYc7SewOT*H7jA*DO zxRZwrp!ad~tUX9)KSsZ$q5urwB+Rnz<)E2cYbAeW$-2Uu|31+ty!9Vro3&R>Z*T^1 zsH0pikNGoXqhLbnl(-erX*ob8_Om*Ru_u#XbcWs5z#*cbHv)t^V`C|Su2vDRf-)x9pmvleD{OfqAQz=68Y&9#LRz_ zA(EY}9_(N2=z_>8a9@A;$@m2C>B_w?e)#L!U)RPZbXbtVpNJp+BjR7zE=mrj7N!oS zM)q{_Mt|44il&x-l{yNpRt6?^)>fu&Ms{C#*D0-i;*HY2p`dy$O$A!%`x_rH-l?iY zDrNp05Q3pMtcqzTpjNiS06Zsej8%W>%y8?b=jwYVZ=|%Fw+YBH)0!PAla!|)Vr;&; zt(x)Uzz(`~=*3O#+CtF|Rn53f++zTV_>6At&sJ@0RpB@G$TH&zwFfm^#;=vLwCp5( z5LCm|tvZGkR|E&G1Lx=p2i$;w-vIItgg5@1cJ?&C$A8vzw)MHH=Y~Q@>lJ^K^c1nE zTdD>n=6qxGKe|)RZj89QmEnU}VJcQGQ9#%=Fsd4}c`;WpaoYMQW}mDIAnlH)2HkL5 z=_ccz=N`za7akgmEn(aIE_#p-%dExVygHn=jpmeil?KqRWwbEQUZ@FM`yyHU39>8L>5*Fo9A8q|g;WWg2IaRxJ+L$69W@}}(OZ{o z>H5x)6W-j}=f3z7??-H3)QSbDI%|JYy9oBbEj#=dwF;(|juv0m{J$VO{ui>$;-HGl zedUa%@-5&5x*;kC#{H0{nO*~Md4^xeBK-?l{M6m^Nr+nG<~@Ijf}~G7CWBV8Q!9LY z=|Q*ly{OLnLN4C?gvEG|8dCPzN)hJrqdFhU zxXE~kO$+<6xZpHefgoS9PH9DJ3D#cAw` zP2a4yZM@ztyi!Lc*`;^?=5_0f*VHFw2QBl(E*NZXKG(Xb_?Z5Z>mcY#6^}6otIc)( zhu`hqE7yO?gE;@dA=U4(g>Dk%*os0Dh|BekSk<0X7JH4vwiCVu_>3%E4#6M3KD*lQFYLTZjenv>0dMw2Ax; zt`FuWEgt-Rbn&taH9F~4_5co`6RGVMuIZZ`=xJ6~>AzsD>(==hlR;4--(fh0yG=BK z!Hw=4mk*C_hvp3l)vbP42aKr(#P=)5_k&WrFee;55+VN>BtW(1%|&cR?n%wI_!ED) zlP#rQ7q?H2Dlh7H#(E1VMm26_t@zrqP}Q7_HVJvpz|gA2(g&$+MhUU86yN_X1f*pk ziIc9Sn_CnpZ7Q`bs|(@>niv+qhxryB-WDxkh8f`$n<5SIxo$he!{tZM+SNPY`4r$e zKq+)bc`=$7h)s*S&lS;VF77^CzFU8U@P(jVzS@?|DsqiL#k-<@y;cP~Ra%c8;-FQa z>#pfmAON=N=hq7Za9C%i(Z<}VU@NkRyCT5CR{R|?$$TOoX+paqf?=es0Olrg5O4rw zrFx6n9kp?P3n{a+sE*o^bPTF}U{MRZ16_Rsa3;~VZfx7OZQHiZiOoN@GqL~JP9_uE zw(VqM%>*y!om;o+y;aq>Q3=LTDh zD?|uRL(y!#mlyR4nJqds%{W*QYN}`qttk=Gwvf#D&9V%l6yL0R(6qA zfLRJS6E;cDgNTbaimD607?OVZH_Q+WJ)v#hEsQ-&a)(mJ?tsT?z4^(70n~m-TRLSl zzb8zq?}7nIC?b=$*P%s+uFl&@_Fq+I5f5h%fC`eWDa7qv=ObG!pdB-5{bxxJwZ00Z zwZv&nu%HWeyfRMdcG2Z{VM@QY85tLxaWM5mqY!26Sc8Yvkf^)Rjm?!OZ!F0*o3meQ z$v|SqVmv*od3isG}D29_wgQHfw1wr14$+fZYo^(;_w_OZ;g;b26)<+n5~)N#V{Cd zl>qXFrFM?xf1kmwd%KaY=#2GyDTAw+%ve&X$j*g(Db~WJ(DdbDDFl_e=?v>a?w#6O zXC4Rp|AO?^XS<#+@JcGN1tRN2#7)t@kb-ZiMCF&^#hv=~^%g}t4QV7~{m?&&CjdF+ zZCp2EEY73#3Tp110pz0la`F4gpe7RCMF()0OQt3U0DwzE81ygfOK&2i?OsW^NYH-_ z7(NjCqpiG~^G~k-MG$rrf#a3&TKawB;$j6C#Mk#D4-9^$0mNb|73jdst8H<%Mog-Cr z7?#{3;5y~;FTfnkrgr$go?D;t`O`R9qS1z0r89_7OdX`@YVmwflfqO!3a#K+p`>9n z=ln|TN%(Yd0EGqNvk>f@{w=km30%4sy!;1Uso)$4gm*CX22_0A5@`RJ7j#0WdOXJh za}{k3g5TNng&DBo-&OJXZAh#&Rsy1uQp^R&+~pHl1wec;*$;6*;Gq46nn#0yYKQa6 z|9gJ~UXp_%@GN(oCA2x(M_414i@|0c~|rXPnfb z^-*NMPQXP{DGXQBK-TG7qm!LUFZ`Q>ERpM1e#YFAk-r9QjU7_(3Z$!HKZ#*d+ceNz zH;IqmgUtM^%&(C3Z<`7n>iB|3V0l;XtV{eQl~Xdz0RG2m zlr6=z$A4}!eK#$}oI(#lht6@+2(k{L3Z4%~e*ihbG%!V}SU#wpWRtP@h3icM+w@~+ zgJngt;E%WbxV*IKUa67mE3n(^184EiVMuR77Al0TeEe&f(I7+ep z*#q4DK?!&Ic$>_GS8*T|p&U-T+1m@*uCHGsu ze^%RIb2hOx{ewFMoZ`t}&Kf-Ie9Cqv_ySlhmYFSlB;;%%jiA(@p!~y>WE}b(2`n^k z+V5P>hzTAfOEn;fpvePfj7|-&^{s`A-OQvQJeS1+^Uj}FGVe*MNga%TY>~9I$ou_R1e(TiMqi898tb!&Eu9p5cd`C}V7MPdwf)Bch7$QMMLAViWe*Vi zog-Xn&u?s-;+oT{I9R-5r`wv8cyhvr@<7g`z~pY4{#R6RdaF9!6dy^_7d)YzF@Z9^ zK&{4|MAb*LT^=^3E1tN{CFVe5ajD zs)8Jtbe(oZHoe$XqV+u9WlB)R$OzyoYDL=+#cX6Ddf2% zc)o;R0ZOjDXS@QOsV{P1h4;^MhikcRqhzL{L<~dQ=ntX(hqx78Y$?<&iL=eKa7Y@aK{c6NC(-T zh54sKM+G?8lct-`QNY7N!jeOv`r;-lXGz2?nIEKNXTo|9-AQ*l?+9ocYIW2K^^QH( zd-?H0U6K=WiF%;3^J9W?91kEo$rN0`Z#>3WR24cNd zZjc`Rb8~@8HP#*(WcLHnNS;E(j_j=1|0wuja7KQ<^q}v>#FnGoy>oM%iC{w)1aZPm zU+7Q!h5Ae!vyq2aRuy2Yp2P<4e)*mQoAL|a>ABVu5*LTn)cK$SfhG~-Fk5DLG7=l_ z$`XmajPt?96$#vfOK(P4JMyD}xHf)$CaJPM+`(44LMm=HW6gNMGLk$}6$}c5NAfTA zIq)mTU9pA{A^z(1_3cyZ1aPxQ>yZr8^nsD#$A+U=e!2hl4g+X4?e&$bKXo^t6}2dC zfN*)p9bL?m+DSmvM_bjTB$zadEg=hE#6mIi;M>15AL)rlQtk|q-h?>8Ea9_DL;G2Q zawQU|NEz4Uq(P^0s>9fZQ)UjU{?ZZqR*=eyOQM0zB%?|vCz;DvANwrVjajZv;(#?Gp0spZD6p-x#iX&GzXQ9;pg+WR{0)DBsRITGqHZ`e4;_t~+} zKSaD#OC^kwhHjh{Yla$sERojBIZ%4HXWR(4`BW&GUWCthOM1Ztk*K|4m1|3`C_gu4RDog4)Sn*ia#r_@nS2b-yBZC1jZVvCO8<}m zG48&{#QRfqv)vt?P;yo^Jz5Ly#)VK?{T;S-#~UEC?5#TE3nzygNHyai9I7vPrDn5p zZ{mY{0Zu17qjIJr0A79$ywpJHT7MB3k1X9xQps_EHvGb$vx=rD{)oCPoE$Z}4@9jh zXX@=9MtrEa43EOUFtq&ZfW~!dgS8LDbb4RVzke4*b`Q{i%e%5-afX%tHJTDAH`rH} z0tsMfR61)lG!%hUd+i=w9k@(ceG0s+@7&MH6CK!?Wv_lGhKBzM0N)*(nc4Vb{PZ4U zcwy|;CTjpR?WKZA(g2XBo|-b8D!2;vC`**Wx1o*|0Kc+n-KV6t5L$a!x1i~5VKuCTR#ZPb&Adx(|B-L;PWutfg*|H zO3UN*E`#7$1N``uVKRIfdLm-53(&6xLFNS%RTJ zYDuPnOeP6Kqo6Ge-F_Gx1oQICDS(C63>PBmnW|PAVXqML9ZHT`9@4r$_rI)xxUDU> z7k(q2v~{?A-f_5!Q$xacw85gZ+1;swtFz`2M5)LoTKQ{PzDAOc=GSX#>Ef)^DC8r2 z{S_6Qc=DQQUA;i7X1IHP?I50?(R&GGMAC3Jx?n_WnB7s?ch5rM5cgg^6#x*QsQhhv zjM8dfE=yOMPRK;`sZUpmTKAsj3mAhh&d@1IljOXu0WSEzuOR6w#h3oZ9jv@MHl29w zR9(~!q-G9Lm+{?N1@&jq0T^qj$)~j)W0B1rHwTV?kk5W3oyP5}_ltHqDapuJn_|NP zXZ5~|9`g?WO5WSLEb5>~SplFM$rQLe<;kJ2s9s>T_3??nVXD0~1i#WnFR&^xMz?M+ z^e{Ue*oWqxQMcCYrB29M@qbF@WVtJXrD#J5&j!F3)w&pwlG$p>Jrox|9_!U4pv z*!tpc^lzd?G$o7ZrbVqoGo|r!i7vZORbKdd9Ln@N5~ncmhpNDpULVvPfXQnZW{bnG zOzv|;>nh7U98_Go9x?|^w4h}f;-*QW#vJ%)RU#4HP}MA3=Q<+Kc61@ zWIw)moH4EmY7qi6^#Hsd_SXZBZ^EU}W#%xogP9z@IgFPoeH1gB=iufi$%fl9z-CnC zc!WWO*e(K#OmPMCK+jw&4Jfx6I)X|D&P};!2FqZj8it3+kQto&kB=tiN7v~S>0#y6 zMzKzW?Pw^twUu0@)H`YT4aS)Ge}ukoU>b+1(Y#Gedi=bkLjV|GVVL5_>9Sue@u00S z;s1`I=%D=SAf>m4k4H4=`5lM^{Lu6XW~?EZa_5OZxD5=YK1qwba(0x10q=7=&>Fy#z3)P7eoUYEST}$%ZdnEJ*Jnsc+2Wj z(nTx2mL{vZJV1InsJ0qx^=x%=L`WfavGk#p6uAq!?P~~a@({II z@MdhgZ((Pvnf1+WZ)Ne3WIEg8enb zHLnVox4XdeBgzTt!c&giv(PSAD_f>p$-p{Wp1@{!M66weJTLLG+<@2AVV;S)QjquY z=i<*n1dN_Hpkp4-!4=8itZqTMYut(v)gO53$!swUX3?x=Ls^Z4<UMN^Axt*;lyO>|i|x;BWY47zXWfjmL625CTahzgyUyqSL(M&SX!Y*StNJ@X z4A7q=-@MaKD_l~wM}DiM3IS|Yiu~i|ggw{Yc+be3sYyRq-TCaX!a9&0j8a8N%B);Y z{;Tc>1v4~fIg@J9*KF`hwH;hURZg-446^8ul?T*-t?Nwia(k0q%pKym6 zD>zYWs+2DCf;;9As$99|tq*heOg)or1R$gTqSd7W7IE3exKowxhaGNPMB@r08EBn> z=S;b=p5IWg#c1Ellgx&+X3zMFC6An+OnCLAaYqU(eQM>XJP*%iNx(9fK6FMaH{qgf zHfDq`q&zTBqvGK*MIOHg!w@k-U#jzVdEX#c%=*)Bk<81b>##VaIn_|^C;ix3J3t%w zAy-LgH;-C_PCs|V``mC8n5C`{x~C31P0yL|RaP%c2H+iWU2^C3f|3UoK7-pwCKy?q zddZ0;joVIiHCzSBb@vREr;h|GvB5N-T8&CUsFuteTU8^s$hxEbH5cqL`D;C<#3;r) zjjqUKYIsi|$e3eQ8&`Lmqhe5?0&o$IxBSbsxlQ;kl~#<~5nc$Q__N8|Ew;Iw8VCJ~ zpb6Uxx36L-1&!aI<_Rp&Zi{C;tmpDRB&I@l&0silY(r)DFxdYJ4q`27uJV_B zpoHKH!Vi~I-DyVS&*f#6j0RQSXj5r-9?Y{vqkVTpZu&*No(bW7H&)?udca(N(>Ub$ zFNexiQc@g`$y(=Gaoeuk=>p=Za~54`(BYTeQVNi!C5qK()Y z{NcX8Zin(J&OJ6ua^13bwocn@opoqw`ms4wxurOh@iCKK#qU|N+rJ0n?E^f zea3R=t)!wv?a8X8eGaltA`&{eo5oa*vi&o=D8D?XzL2wteTy~aF~B*NdQ_-!O5Z_x z`{s2jh!S+*CP2ZCILCc7QqbM_yU3(2Pw?9k`myi@?APv-1>^l{Q$z66Y9bE7XAfhp zyhiL_fl??gBbo|&3`SXVtkLjG@Sl5(9x--_vNthBT%x&vK2`Y zVcNeQy##O}>UXnBj{rdnvJ&{{SVA1l@lM zmSh>dJw4C{lxCR@}TvQnYGQv zWGmz+X%GcE-2c|FC;#kfavhU^= z+nNF{=|`G0Uhdk~I@8}1cmghSLtff3V)vNKt&8%d$^j;I1QV`2nr@Cx{M+g6{dzt$tLZ( zouzX5+KrEV?X!#zKf83!ukW3ju0&Q-(y^V#7yzb}T@|kP3@fAtxCoz3scwAB!8i#zpLyr#tu)kt0r*;CW&8q;=B)D9X?T;PL+3(D~< zf=&`U)U!&BwQa1K6Hnu6{G{V7;UhKV)6)j=Kc*5&P0)^VI&sen5#`@}+XJ|M( zKLBS+<}kH7OthU(6@QU`G$xS{$i0;3rg_|VzJh_51x>H7hq_lP@jrL|acyYrUZ2~k zfc+8zPF+@bn@%yEshqZw!}b~v@7~Q`D$F`dcxNX9Jt!Z?B(hJwk%`jvEOjoc_G{Qz zQz}TIPXs{T<4cG}pEjtFYo-4|%kf3WJm8>%w&-X=eC<;B{CfeNE-gD2VMsr^(4efn zt^OK$zvxZ0H|IfbJLsKmALE6pR9|YBW)j~#3!X(zxGwk(z~ahbsqJ9|M%poY$PBFi zy!fmt(YduxnwOaXx|OnjIq0^2b+sf0ENJk3=Ajqr5^Cy6ijDtDZu9g5$qjvN0*rv# z$-vcmo-KI0#;8Ie(Dz9YD45-!1rW>tuc|+vi>22$=(X1Q;bK-NWbPhKf-Ja8G8$y_ zf3qco8E+&&U0+$0m(MoXSOmcpEmni*l>G+QSJ6?VN9UcO=E}L-io5#~U*E2p!=vzTMy%s*`)5BTH80ld{i&I-<*jgWK%Dwx$>m^)283CvYl9J9bdq1Amv z-JJQ8y#1u_*fCfeBIWzL-8wj(Ezy^8vGzGqnxXv@DrJBc>117y>u_~_$JZgneHy;S zZMRHzQn$>5$bau(t|MiN=dcIS601#b;-IY(`$NtxTyciT1AbRMw-Q*!0DM!1=Erp; zti*Fq2&n}%*d|L}dSHY$=b0>qryziVcUqBmp*n&%zA?p5$cpokFNS+)wwI%pb8LS* zhg#X0_pmdn6o>_yzO!Bzzr4Y}mSNZQWwI_d&(}NP)^zzd0eU^LrNde25g&5qajRmG zyQ%rd!zK!SsuxAM+3POumpvZccU#-~*n zpr{a8U*yg78dctkQ9f-fmPK~cPiX5N*At#cec3_Q!$|A*oZBY0Tca(^T1~$^zf)UO z#TjgsAck96!J`a)RntFjT=Gq8p6ls`V6{*H{9I%ovd3~0J_5hCVbb*&Y4O2 zmAlNw)pya&kcq=s5-aLk=!p5bNOi7!t@%~;?KXV^0_$gX4JwtT&Mdn)jG1C8yArHI zUe}1kKhrdeWwSBY*_)1=y#Y}Mj*va;Irc^#fgmyO;B&MEqmmaqG7&`RU;&bv#1OB~uF%2dfM!h^rPSj{?YwvNl|zNo z@Cm;wJ)1T}Kww|U9d!IpB(jRDPN)G)%lR<|y8QSre6lOe$eYqpDqU>K4?_ufL1AT{ z+hnfeAh&lM<=OK=G%rSVWdw_@tAl*HaE1?~D0zd7&~+ryMiAQ=5jj~QDi5Lcyn>Y1 zg2ta1kfbAK0GGLa-DUsEo7rXpY9XBje@X%qBLa>XNjHMvCE^FHdf1$4GjpTTvVg$} zJ}P>ZLW2_*xxBUA;%=LV=fswryrE0AoawP9z>87Kki~kFk|>ZYxz6b!Xc44{j5Ho2 zZ}B~ALMk#4Zj0&W(CzWU#_yz)%UC28M88Mjq+7lRfW~){sfx@8Wir5$2fs&%R$dS? zA1?IU@F1yd%hwa$=?)#)Q7>M%o6SCXwo|f^36+D>FL{=sVfZh(esdey;rJGN@<#xK zdr5#zG{9H%nkEgz#?p+P@pW zYmJ8rcr$2%itznBiK%OFY4H)dvm^v#;h-SuquvoHK50Qj2*>=#!X<60tA1Eq_LTe8 zFT~<^OrU9?5*Bp22~IW*Awa{*%7wY2Y-{e(p81Bm_FFiZg(VYhLmH>$&RswW$vwI9oxe>#YZAVk2phEly|y28UQ#KIIAR?F~aT68D-)IDV& z05wp0?$TQ#a61(V@M=&Is#M@pmla|aKu=t_6Ky6*QYlOusbhI@=|{w@pSXT;E}v*w z4oE?MPeF__YLj}%eDg;&@Zrl^7Pj5^wY_Q7X$LJvWTpHiOi*z~gX%?40T<(s zKhuV7;iyhmVH1nJmaixAW5u0ii}B&sp>iiLSMJgp%h!rajgFdR2vB8T}}q z3q!|Yj*P4_lon&rmdi6>FA*cM6W(2;AWFUY18dhzowY=r3E-h5 zVsyaTpfbCP2UKr0o$8TwUAoO1J8hl>`w~dw9dd`y6hwrLr807&w)~^K(JLkOy!6b& zG3*U8R_c~b>s(q0fNx$Jx$#5^WbUQa+fV$kR*X#yWsPyBaZ#s@s<<*>d>gI9-ICrk z>9+a+MO5MNVD(})#jQmN{C>CZfVcFx;dpUG{^-wbwHGH#&UoahFbZWhs?zhP&<#l| zgaLe+aRY*-SkRvdbE0Mu_^IJzu758_MMf(q!!L(&ZJIuA7)BTo*5*m!pF5#) z$u)~sFZY3P*kwJlh^?6jH8tKCH`2fH$Y&{0R1POgdN%KK)HPeLAkA{d0Yr}&NjMr8 z$G?`S+^FMxsX@n{-~Y%g9><*qsj(QI4IB;g?GB%LfKLY$@nx)~{^;AJ-u}U7iFLYl zb9!KTu!(ScNK8T?uQbc9EJ;FCU2n^L7;Ffl`8J+-H${kj?08SW883mghP(A0Vp?is zDx*^*dv%Yu2OBQypHLFw0MJ1PGk3nk8q@|^ruB5V zQg}b9YREfoynLM9R_?$yM(_J;h|;8g1>^V>)7ABx8uE>az zwFK>ZW-*+-l&VNaB(=k9<42Ksk$=Y#IHVwk9^|oEks*eb3p^VEF;eXM8W(`H=b)~cnMwjnL zgK=lVZ~kbYZXer<2N2tw`5~wvyj<#F{k=B_i?T?KPU0@;BmLu*12T*TPLw_Fd}LKR z`@o;@$0nB6eqtqAHQE3zl#l2KaSG&0T=UecY~2hTvha={Qn$6qKm!_Us(z?zk}d-qwdvu}w`Fe5qrVL^EQ zLr5;1vcb;b#Y64)@7WiJSg)S*Ku`IZ#HT}MfQD+nEvm$`-UxFR)#(K@!eyw1GpwN+ znia&;H$9WmTO5!?5~D}9z(kroA4!6SnM?*6Lc$&eR+Uzc%XrOwS>a?o1U4{` zXBH$HVA7@dtTb|f2REWTj~Hw=<3=@&ficO^L}r1V8WMUuH=?Zs<@pMeAxg(=y;Z4F zt@}CPXuuCCZc+D_EA51LQfj&Hu>4}AvN)q6>4A}6(H)@EkuAbDrqjDLfL3YC?)w>1 z>2)DpUzPmMm35%C*&=wwk8Se#yU~*|?=?^$bq6B8iN$DzSaay-EDThkOcagpOmU|( zhK9?DP|gzUuntimT3EJZ(5T&Al2&p^2?Uom(T~UcK}wOPT zp+Hl}uOt8)Sk7T^3=Krs1Jjv9ik$*m)jKJRRsLd|apjNEO@P3xUy6_1K%|Rw$^!h< z?GqweG9OtPSoyi$JW63uu4gIO#~+Pz+87dQ>C6~JA;?&Wc9L7btDe>(Y7b+*;AdYSej`V^QodIsin-s=?-{^qKV?SAW|fV)NKa3)5-6<4uMh$`xoUq@n! zG!l0fj{D{4{j)?pP8R`$e&5b0VjkGbsxeAXY@`ihZ3^Pil~w8)+t&(#2@J$`N)!KX zpKjgG*7nzi2&KCPMFfNcEVUziU!JdV<-2(wnu8u)3v9%$rp(Nas#I)69p`lGaYi05 z!D-bQ??HI8o&7og6QelI+2%=KfvLAdEA@wzj0iJISO zog$Ufzb%%s=~mOc34BX%YYz0d!Ka8p9NFt%5~$)h38g7hy-bVsS92Ym4-10JU89Wk zt$HK!2KA|oI~o95PQzUST=Vc7r$%~C>#|maZpF2kZi^#Q9OunnMrV!kv>wE>w1CnP zcWdR6^)GJR9pbegi7 zch=2q06c)3|M~G(Wd4d;4gk50CCpctyzk+bV)4M;D`GQ5MrC1rsx|*lj(bKoOjY2A zVb$M8EwOs;P;ZgP?mgX^`>@G5Hk@VzsTsqI14~C0SB^R4DfFwv6Q4--TO&me!YLR4-5=!%k?pq`5iTIIJJeI#41KR z^xHWMa}5GD8YM(Z)a^okJOgAM2pAA6UZ20aLWUc3{=}E=G276VFy@~e-LZcm%%+`? z%E<=g@imRQfOqx@GYnp{iNv$bDOS-^dTq^B2^`YXW;cCJ^=XHt4p zcdD*C3KVCV;>BS1*e+o?siCZ&~f$qElk| zIhftMyL1-`H0&+gJHaOaX#m$=jZ*>GNLC_OOKnTS*<3%-i0tA+{s^lf(WI;q>O~GC zGVx{qg5e+sCF|_llpq4hU6KIx#@RdLXE4wsarB2=w_L3BuzrA$4 zX#zCisS|vt3s*cjB|oddKz@X>dH{Zom9QkRXPP0;<7uxe1VDn!tk4933}U*JQs_So z7r76(N|f*B*L+$mx&4O5f zR;cN~YXv#Js)F8Cxlo|ly-@%LlFq5@N%pM{5@!%4^nVdTd8|F4x+5CWq`-3)Tt~QU z)>67r(xW8%SIm!rj1V`bO=Xyttv+{8}NQmU$uSP{kx%3w^L(XS0q0!!A3gZAm0HGayIiy48n{}NFElij1$eN*&y%zRB&XmajopNe^ zoMC8+I$*|w9RF1f;v9=9+}7jKC9#|t5&ARj75BA1#|vj`B;oVCV*AHK#%!Otd8FvJ z|4mTd6$~^)1_>?i^QsR7SCI#YzyJXOfdM%Y3U052hViBX|Idtq35FUJ_Dm>P9u>lV z$T~xV8AgQUKc_Cht{)@c4@iT8fDnF<|Do^cHx+_re0`Vx%a~<`K_UJRG=4wLG4uPz z!uLV-AH+BP7h06@$qd6u{4Gcx&BD>r#u5a?PZ}Hq_rI9`0R?2JvB1!Pe{;$RV1dC0 zBe2cLW`Uvjk9ryX|G5C~oGR*x$)F++3I+o5zedQ{r}E{Ie#=P$2LXZqe>gh0WDv8$ z;F4T?%avmVJ&B8j2H8x9{$D%(3vPE!z4j(%{Qudq_Ql9bf143b0|J8eKWzUy1b#wi dl(52(|6k1}Sid!UqsTaAh2erCrGoi}{2y#V9uEKj diff --git a/toolbox/src/DiscreteFilter.cpp b/toolbox/src/DiscreteFilter.cpp index be74d7c70..674501a50 100644 --- a/toolbox/src/DiscreteFilter.cpp +++ b/toolbox/src/DiscreteFilter.cpp @@ -1,7 +1,6 @@ #include "DiscreteFilter.h" #include "BlockInformation.h" -#include "Error.h" -#include "ForwardKinematics.h" +#include "Log.h" #include "Signal.h" #include #include @@ -10,40 +9,38 @@ #include #include +using namespace wbt; +using namespace iCub::ctrl; +using namespace yarp::sig; + +const std::string DiscreteFilter::ClassName = "DiscreteFilter"; + // Parameters -#define PARAM_IDX_FLT_TYPE 1 // ::Filter type -#define PARAM_IDX_NUMCOEFF 2 // ::Filter numerator coefficients -#define PARAM_IDX_DENCOEFF 3 // ::Filter denominator coefficients -#define PARAM_IDX_1LOWP_FC 4 // ::FirstOrderLowPassFilter cut frequency -#define PARAM_IDX_1LOWP_TS 5 // ::FirstOrderLowPassFilter sampling time -#define PARAM_IDX_MD_ORDER 6 // ::MedianFilter order -#define PARAM_IDX_INIT_Y0 7 // Output initialization -#define PARAM_IDX_INIT_U0 8 // ::Filter input initialization +const unsigned DiscreteFilter::PARAM_IDX_FLT_TYPE = 1; // ::Filter type +const unsigned DiscreteFilter::PARAM_IDX_NUMCOEFF = 2; // ::Filter numerator coefficients +const unsigned DiscreteFilter::PARAM_IDX_DENCOEFF = 3; // ::Filter denominator coefficients +const unsigned DiscreteFilter::PARAM_IDX_1LOWP_FC = 4; // ::FirstOrderLowPassFilter cut frequency +const unsigned DiscreteFilter::PARAM_IDX_1LOWP_TS = 5; // ::FirstOrderLowPassFilter sampling time +const unsigned DiscreteFilter::PARAM_IDX_MD_ORDER = 6; // ::MedianFilter order +const unsigned DiscreteFilter::PARAM_IDX_INIT_Y0 = 7; // Output initialization +const unsigned DiscreteFilter::PARAM_IDX_INIT_U0 = 8; // ::Filter input initialization // Inputs -#define INPUT_IDX_SIGNAL 0 +const unsigned DiscreteFilter::INPUT_IDX_SIGNAL = 0; // Outputs -#define OUTPUT_IDX_SIGNAL 0 +const unsigned DiscreteFilter::OUTPUT_IDX_SIGNAL = 0; // Other defines -#define SIGNAL_DYNAMIC_SIZE -1 - -using namespace wbt; -using namespace iCub::ctrl; -using namespace yarp::sig; - -std::string DiscreteFilter::ClassName = "DiscreteFilter"; +const int DiscreteFilter::SIGNAL_DYNAMIC_SIZE = -1; DiscreteFilter::DiscreteFilter() - : filter(nullptr), y0(nullptr), u0(nullptr), inputSignalVector(nullptr) -{ -} +{} unsigned DiscreteFilter::numberOfParameters() { return 8; } -bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo, wbt::Error* error) +bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo) { // Memory allocation / Saving data not allowed here @@ -56,9 +53,7 @@ bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo, wbt::Err // Number of input ports int numberOfInputPorts = 1; if (!blockInfo->setNumberOfInputPorts(numberOfInputPorts)) { - if (error) { - error->message = ClassName + " Failed to set input port number."; - } + Log::getSingleton().error("Failed to set input port number."); return false; } @@ -71,10 +66,8 @@ bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo, wbt::Err // Number of output ports int numberOfOutputPorts = 1; - if (!blockInfo->setNumberOfOuputPorts(numberOfOutputPorts)) { - if (error) { - error->message = ClassName + " Failed to set output port number."; - } + if (!blockInfo->setNumberOfOutputPorts(numberOfOutputPorts)) { + Log::getSingleton().error("Failed to set output port number."); return false; } @@ -85,7 +78,7 @@ bool DiscreteFilter::configureSizeAndPorts(BlockInformation* blockInfo, wbt::Err return true; } -bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) +bool DiscreteFilter::initialize(const BlockInformation* blockInfo) { // Handle the parameters // ===================== @@ -96,24 +89,29 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) std::string den_coeff_str; std::string y0_str; std::string u0_str; - wbt::Data firstOrderLowPassFilter_fc; - wbt::Data firstOrderLowPassFilter_ts; - wbt::Data medianFilter_order; + double firstOrderLowPassFilter_fc; + double firstOrderLowPassFilter_ts; + double medianFilter_order; // Get the scalar parameters - firstOrderLowPassFilter_fc = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1LOWP_FC); - firstOrderLowPassFilter_ts = blockInfo->getScalarParameterAtIndex(PARAM_IDX_1LOWP_TS); - medianFilter_order = blockInfo->getScalarParameterAtIndex(PARAM_IDX_MD_ORDER); + bool ok = true; + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_1LOWP_FC, + firstOrderLowPassFilter_fc); + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_1LOWP_TS, + firstOrderLowPassFilter_ts); + ok = ok && blockInfo->getScalarParameterAtIndex(PARAM_IDX_MD_ORDER, + medianFilter_order); // Get the string parameter - if (!(blockInfo->getStringParameterAtIndex(PARAM_IDX_FLT_TYPE, filter_type) - && blockInfo->getStringParameterAtIndex(PARAM_IDX_NUMCOEFF, num_coeff_str) - && blockInfo->getStringParameterAtIndex(PARAM_IDX_DENCOEFF, den_coeff_str) - && blockInfo->getStringParameterAtIndex(PARAM_IDX_INIT_Y0, y0_str) - && blockInfo->getStringParameterAtIndex(PARAM_IDX_INIT_U0, u0_str))) { - if (error) { - error->message = ClassName + " Failed to parse string parameters."; - } + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_IDX_FLT_TYPE, filter_type); + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_IDX_NUMCOEFF, num_coeff_str); + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_IDX_DENCOEFF, den_coeff_str); + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_IDX_INIT_Y0, y0_str); + ok = ok && blockInfo->getStringParameterAtIndex(PARAM_IDX_INIT_U0, u0_str); + + + if (!ok) { + Log::getSingleton().error("Failed to parse parameters."); return false; } @@ -127,13 +125,13 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) unsigned y0Width, u0Width; if (y0_str != "none") { - y0 = new Vector(0); + y0 = std::unique_ptr(new Vector(0)); stringToYarpVector(y0_str, *y0); - y0Width = y0->length(); + y0Width = y0->length(); } if (u0_str != "none") { - u0 = new Vector(0); + u0 = std::unique_ptr(new Vector(0)); stringToYarpVector(u0_str, *u0); u0Width = u0->length(); } @@ -145,43 +143,35 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) // ------- if (filter_type == "Generic") { if (num.length() == 0 || den.length() == 0) { - if (error) { - error->message = ClassName + " (Generic) Wrong coefficients size"; - } - return 1; + Log::getSingleton().error("(Generic) Wrong coefficients size."); + return false; } - filter = new Filter(num, den); + filter = std::unique_ptr(new Filter(num, den)); } // FirstOrderLowPassFilter // ----------------------- else if (filter_type == "FirstOrderLowPassFilter") { - if (firstOrderLowPassFilter_fc.floatData() == 0 - || firstOrderLowPassFilter_ts.floatData() == 0) { - if (error) { - error->message = ClassName - + " (FirstOrderLowPassFilter) You need to " - "specify Fc and Ts"; - } + if (firstOrderLowPassFilter_fc == 0 || firstOrderLowPassFilter_ts == 0) { + Log::getSingleton().error("(FirstOrderLowPassFilter) You need to " + "specify Fc and Ts."); return false; } - filter = new FirstOrderLowPassFilter(firstOrderLowPassFilter_fc.floatData(), - firstOrderLowPassFilter_ts.floatData()); + filter = std::unique_ptr( + new FirstOrderLowPassFilter(firstOrderLowPassFilter_fc, + firstOrderLowPassFilter_ts)); } // MedianFilter // ------------ else if (filter_type == "MedianFilter") { - if (medianFilter_order.int32Data() == 0) { - if (error) { - error->message = ClassName - + " (MedianFilter) You need to specify the " - "filter order."; - } + if (static_cast(medianFilter_order) == 0) { + Log::getSingleton().error("(MedianFilter) You need to specify the " + "filter order."); return false; } - filter = new MedianFilter(medianFilter_order.int32Data()); + filter = std::unique_ptr(new MedianFilter(static_cast(medianFilter_order))); } else { - if (error) error->message = ClassName + " Filter type not recognized."; + Log::getSingleton().error("Filter type not recognized."); return false; } @@ -195,54 +185,27 @@ bool DiscreteFilter::initialize(BlockInformation* blockInfo, wbt::Error* error) unsigned outputSignalWidth = blockInfo->getInputPortWidth(OUTPUT_IDX_SIGNAL); if ((y0 != nullptr) && (y0Width != outputSignalWidth)) { - if (error) { - error->message = ClassName + " y0 and output signal sizes don't match"; - } + Log::getSingleton().error("y0 and output signal sizes don't match."); return false; } if ((u0 != nullptr) && (filter_type == "Generic") && (u0Width != inputSignalWidth)) { - if (error) { - error->message = ClassName + " (Generic) u0 and input signal sizes don't match"; - } + Log::getSingleton().error("(Generic) u0 and input signal sizes don't match."); return false; } // Allocate the input signal - inputSignalVector = new Vector(inputSignalWidth, 0.0); + inputSignalVector = std::unique_ptr(new Vector(inputSignalWidth, 0.0)); return true; } -bool DiscreteFilter::terminate(BlockInformation* blockInfo, wbt::Error* error) +bool DiscreteFilter::terminate(const BlockInformation* blockInfo) { - // Deallocate all the memory - // ------------------------- - - if (filter) { - delete filter; - filter = nullptr; - } - - if (inputSignalVector) { - delete inputSignalVector; - inputSignalVector = nullptr; - } - - if (y0) { - delete y0; - y0 = nullptr; - } - - if (u0) { - delete u0; - u0 = nullptr; - } - return true; } -bool DiscreteFilter::initializeInitialConditions(BlockInformation* blockInfo, wbt::Error* error) +bool DiscreteFilter::initializeInitialConditions(const BlockInformation* blockInfo) { // Reminder: this function is called when, during runtime, a block is disabled // and enabled again. The method ::initialize instead is called just one time. @@ -251,17 +214,17 @@ bool DiscreteFilter::initializeInitialConditions(BlockInformation* blockInfo, wb // sized vector if (y0 == nullptr) { unsigned outputSignalWidth = blockInfo->getInputPortWidth(OUTPUT_IDX_SIGNAL); - y0 = new Vector(outputSignalWidth, 0.0); + y0 = std::unique_ptr(new Vector(outputSignalWidth, 0.0)); } if (u0 == nullptr) { - u0 = new Vector(inputSignalWidth, 0.0); + u0 = std::unique_ptr(new Vector(inputSignalWidth, 0.0)); } // Initialize the filter. This is required because if the signal is not 1D, // the default filter constructor initialize a wrongly sized y0 // Moreover, the Filter class has a different constructor that handles the // zero-gain case - Filter* filter_c = dynamic_cast(filter); + Filter* filter_c = dynamic_cast(filter.get()); if (filter_c != nullptr) { filter_c->init(*y0, *u0); } @@ -272,7 +235,7 @@ bool DiscreteFilter::initializeInitialConditions(BlockInformation* blockInfo, wb return true; } -bool DiscreteFilter::output(BlockInformation* blockInfo, wbt::Error* error) +bool DiscreteFilter::output(const BlockInformation* blockInfo) { if (filter == nullptr) return false; @@ -282,7 +245,7 @@ bool DiscreteFilter::output(BlockInformation* blockInfo, wbt::Error* error) // Copy the Signal to the data structure that the filter wants for (unsigned i = 0; i < inputSignalWidth; ++i) { - (*inputSignalVector)[i] = inputSignal.get(i).doubleData(); + (*inputSignalVector)[i] = inputSignal.get(i); } // Filter the current component of the input signal

iCub balancing on one foot via external force control and interacting with humans