From 2f4732cc14634035523365b698f8d115296caa9f Mon Sep 17 00:00:00 2001 From: RKJenamani Date: Mon, 25 Dec 2023 00:47:23 -0500 Subject: [PATCH] Code cleanup and README edits. --- README.md | 8 +- .../JointSpaceCompliantController.hpp | 194 ++++++++--------- .../TaskSpaceCompliantController.hpp | 204 ++++++++---------- .../gen3_compliant_controllers/helpers.hpp | 8 +- media/controller_formulation.pdf | Bin 0 -> 120426 bytes scripts/test_controllers.py | 6 +- src/JointSpaceCompliantController.cpp | 38 ++-- src/TaskSpaceCompliantController.cpp | 42 ++-- src/helpers.cpp | 20 +- 9 files changed, 226 insertions(+), 294 deletions(-) create mode 100644 media/controller_formulation.pdf diff --git a/README.md b/README.md index c1e6ac6..699725e 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,7 @@ # Kinova Gen3 Compliant Controllers ![build](https://github.com/empriselab/gen3_compliant_controllers/actions/workflows/build-test.yml/badge.svg) -This repository provides joint-space and task-space compliant ROS1 controllers with [model-free friction observers](https://ieeexplore.ieee.org/document/8781838) for the Kinova Gen3 robot arm. +This repository provides joint-space and task-space compliant ROS1 controllers with [model-free friction observers](https://ieeexplore.ieee.org/document/8781838) for the Kinova Gen3 robot arm. The controller formulation implemented can be found [here](media/controller_formulation.pdf).

Demo GIF @@ -28,6 +28,8 @@ cd .. && catkin build ## Usage It is preferred to have the robot and the system running ROS on the same network and connected via ethernet (especially important for torque control). For safety purposes, **make sure to have the e-stop next to you when testing.** +To ensure correct biasing of the robot's torque sensors, position the robot to the candlestick configuration with all joint positions set to zero. Then, zero out the actuator torque offset for each joint using the web application. For testing compliant control, return the robot to a general position like HOME; avoid testing at the candlestick position due to potential instability. + Running instructions for testing the controllers: ``` # In terminal 1 @@ -37,9 +39,9 @@ roslaunch gen3_compliant_controllers controller.launch ip_address:= -# The robot will drop a bit as it switches to effort mode +# The robot will jerk a bit as it switches to effort mode DOF: Value: # in radians diff --git a/include/gen3_compliant_controllers/JointSpaceCompliantController.hpp b/include/gen3_compliant_controllers/JointSpaceCompliantController.hpp index 032128d..d01dbe6 100644 --- a/include/gen3_compliant_controllers/JointSpaceCompliantController.hpp +++ b/include/gen3_compliant_controllers/JointSpaceCompliantController.hpp @@ -1,37 +1,33 @@ #ifndef GEN3_COMPLIANT_CONTROLLERS__JOINT_SPACE_COMPLIANT_CONTROLLER_H #define GEN3_COMPLIANT_CONTROLLERS__JOINT_SPACE_COMPLIANT_CONTROLLER_H -// pinocchio +// pinocchio headers #include #include #include +#include +#include +#include +#include +// std headers #include #include +#include +using namespace std::chrono; -#include +// ros headers #include - -#include "pinocchio/algorithm/frames.hpp" -#include "pinocchio/algorithm/model.hpp" -#include "pinocchio/multibody/data.hpp" -#include "pinocchio/parsers/urdf.hpp" - -// ROS messages #include #include - -// ros_controls -#include - #include #include #include #include #include -using namespace std::chrono; - #include + +// local headers #include #include @@ -42,111 +38,89 @@ class JointSpaceCompliantController hardware_interface::JointStateInterface> { public: + // Constructor and Destructor JointSpaceCompliantController(); ~JointSpaceCompliantController(); - /** \brief The init function is called to initialize the controller from a - * non-realtime thread with a pointer to the hardware interface, itself, - * instead of a pointer to a RobotHW. - * - * \param robot The specific hardware interface used by this controller. - * - * \param n A NodeHandle in the namespace from which the controller - * should read its configuration, and where it should set up its ROS - * interface. - * - * \returns True if initialization was successful and the controller - * is ready to be started. - */ + // Initialize the controller bool init(hardware_interface::RobotHW* robot, ros::NodeHandle& n) override; - /** \brief This is called from within the realtime thread just before the - * first call to \ref update - * - * \param time The current time - */ - void starting(const ros::Time& time) override; - void stopping(const ros::Time& time) override; - - /*! - * \brief Issues commands to the joint. Should be called at regular intervals - */ + // Lifecycle hooks for the controller + void starting(const ros::Time& time) override; // Called before the first update + void stopping(const ros::Time& time) override; // Called when the controller is stopped + + // Main update loop where control commands are computed and sent to the robot void update(const ros::Time& time, const ros::Duration& period) override; private: - std::unique_ptr mJointStateUpdater; - bool shouldAcceptRequests(); - bool shouldStopExecution(std::string& message); - - realtime_tools::RealtimeBuffer - mCommandsBuffer; - std::atomic_bool mExecuteDefaultCommand; - - std::string mName; ///< Controller name. - std::vector mJointNames; ///< Controlled joint names - - // pinocchio objects - std::shared_ptr mModel; - std::unique_ptr mData; - pinocchio::Model::Index mEENode; - int mNumControlledDofs; - - std::unique_ptr mNodeHandle; - - std::vector mControlledJointHandles; - - // DYNAMIC PARAMETER OF KINOVA GEN3 - Eigen::MatrixXd mJointStiffnessMatrix; - Eigen::MatrixXd mRotorInertiaMatrix; - - Eigen::MatrixXd mFrictionL; - Eigen::MatrixXd mFrictionLp; - - Eigen::MatrixXd mJointKMatrix; - Eigen::MatrixXd mJointDMatrix; - - long long int mCount; - - Eigen::VectorXd mActualTheta; - Eigen::VectorXd mActualThetaDot; - - Eigen::VectorXd mDesiredPosition; - Eigen::VectorXd mDesiredVelocity; - Eigen::VectorXd mDesiredTheta; - Eigen::VectorXd mDesiredThetaDot; - - Eigen::VectorXd mDesiredEffort; - Eigen::VectorXd mJointEffort; - - Eigen::VectorXd mLastDesiredPosition; - Eigen::VectorXd mLastDesiredVelocity; - - Eigen::VectorXd mNominalTheta; - Eigen::VectorXd mNominalThetaDot; - Eigen::VectorXd mNominalThetaDDot; - - Eigen::VectorXd mNominalThetaPrev; - Eigen::VectorXd mNominalThetaDotPrev; - - Eigen::VectorXd mZeros; - Eigen::VectorXd mGravity; - Eigen::VectorXd mQuasiGravity; - Eigen::VectorXd mNominalFriction; - - Eigen::VectorXd mActualPosition; - Eigen::VectorXd mActualVelocity; - Eigen::VectorXd mActualEffort; - - ExtendedJointPosition* mExtendedJoints; - - ros::Subscriber mSubCommand; - void commandCallback( - const trajectory_msgs::JointTrajectoryPointConstPtr& msg); - - // for debugging + // STATE AND COMMAND HANDLING + std::unique_ptr mJointStateUpdater; // Joint state updater + bool shouldAcceptRequests(); // Check if controller should accept requests + bool shouldStopExecution(std::string& message); // Check if controller should stop execution + realtime_tools::RealtimeBuffer mCommandsBuffer; // Command buffer + std::atomic_bool mExecuteDefaultCommand; // Execute default command flag + ros::Subscriber mSubCommand; // Subscriber for command messages + void commandCallback(const trajectory_msgs::JointTrajectoryPointConstPtr& msg); // Callback for command messages + + // CONTROLLER CONFIGURATION + std::string mName; // Controller name + std::vector mJointNames; // Controlled joint names + std::unique_ptr mNodeHandle; // Node handle + std::vector mControlledJointHandles; // Joint handles + + // PINOCCHIO OBJECTS + std::shared_ptr mModel; // Model object + std::unique_ptr mData; // Data object + pinocchio::Model::Index mEENode; // End effector node index + int mNumControlledDofs; // Number of controlled joints + + // TUNABLE PARAMETERS + Eigen::MatrixXd mJointStiffnessMatrix; // Joint stiffness matrix + Eigen::MatrixXd mRotorInertiaMatrix; // Rotor inertia matrix + Eigen::MatrixXd mFrictionL; // Friction observer matrix 1 + Eigen::MatrixXd mFrictionLp; // Friction observer matrix 2 + Eigen::MatrixXd mJointKMatrix; // Joint compliance proportional gain matrix + Eigen::MatrixXd mJointDMatrix; // Joint compliance derivative gain matrix + + long long int mCount; // Used during initialization + + // SENSOR READINGS + Eigen::VectorXd mCurrentPosition; // Joint position read from sensor + Eigen::VectorXd mCurrentVelocity; // Joint velocity read from sensor + Eigen::VectorXd mCurrentEffort; // Joint effort read from sensor + + // COMPUTED VARIABLES + Eigen::VectorXd mCurrentTheta; // Normalized joint position + + Eigen::VectorXd mDesiredPosition; // Desired joint position + Eigen::VectorXd mDesiredVelocity; // Desired joint velocity + Eigen::VectorXd mDesiredTheta; // Desired motor position + Eigen::VectorXd mDesiredThetaDot; // Desired motor velocity + + Eigen::VectorXd mCommandEffort; // Commanded joint effort + Eigen::VectorXd mTaskEffort; // Task effort + + Eigen::VectorXd mLastDesiredPosition; // Last desired joint position (used for checking if desired position has changed) + Eigen::VectorXd mLastDesiredVelocity; // Last desired joint velocity + + Eigen::VectorXd mNominalTheta; // Nominal joint position computed from model + Eigen::VectorXd mNominalThetaDot; // Nominal joint velocity computed from model + Eigen::VectorXd mNominalThetaDDot; // Nominal joint acceleration computed from model + + Eigen::VectorXd mNominalThetaPrev; // Previous nominal joint position + Eigen::VectorXd mNominalThetaDotPrev; // Previous nominal joint velocity + + Eigen::VectorXd mZeros; // Vector of zeros + Eigen::VectorXd mGravity; // Gravity computed from model + Eigen::VectorXd mQuasiGravity; // Quasistatic gravity computed from model + Eigen::VectorXd mNominalFriction; // Nominal friction computed from model + + ExtendedJointPosition* mExtendedJoints; // Used for computing normalized joint position + + // DEBUGGING std::chrono::time_point mLastTimePoint; - // dynamic reconfigure + // DYNAMIC RECONFIGURE dynamic_reconfigure::Server< gen3_compliant_controllers::JointSpaceCompliantControllerConfig> server; diff --git a/include/gen3_compliant_controllers/TaskSpaceCompliantController.hpp b/include/gen3_compliant_controllers/TaskSpaceCompliantController.hpp index ea2803e..a1523d4 100644 --- a/include/gen3_compliant_controllers/TaskSpaceCompliantController.hpp +++ b/include/gen3_compliant_controllers/TaskSpaceCompliantController.hpp @@ -1,37 +1,33 @@ #ifndef GEN3_COMPLIANT_CONTROLLERS__TASK_SPACE_COMPLIANT_CONTROLLER_H #define GEN3_COMPLIANT_CONTROLLERS__TASK_SPACE_COMPLIANT_CONTROLLER_H -// pinocchio +// pinocchio headers #include #include #include +#include +#include +#include +#include +// std headers #include #include +#include +using namespace std::chrono; -#include +// ros headers #include - -#include "pinocchio/algorithm/frames.hpp" -#include "pinocchio/algorithm/model.hpp" -#include "pinocchio/multibody/data.hpp" -#include "pinocchio/parsers/urdf.hpp" - -// ROS messages #include #include - -// ros_controls -#include - #include #include #include #include #include -using namespace std::chrono; - #include + +// local headers #include #include @@ -42,124 +38,98 @@ class TaskSpaceCompliantController hardware_interface::JointStateInterface> { public: + // Constructor and Destructor TaskSpaceCompliantController(); ~TaskSpaceCompliantController(); - /** \brief The init function is called to initialize the controller from a - * non-realtime thread with a pointer to the hardware interface, itself, - * instead of a pointer to a RobotHW. - * - * \param robot The specific hardware interface used by this controller. - * - * \param n A NodeHandle in the namespace from which the controller - * should read its configuration, and where it should set up its ROS - * interface. - * - * \returns True if initialization was successful and the controller - * is ready to be started. - */ + // Initialize the controller bool init(hardware_interface::RobotHW* robot, ros::NodeHandle& n) override; - /** \brief This is called from within the realtime thread just before the - * first call to \ref update - * - * \param time The current time - */ - void starting(const ros::Time& time) override; - void stopping(const ros::Time& time) override; - - /*! - * \brief Issues commands to the joint. Should be called at regular intervals - */ + // Lifecycle hooks for the controller + void starting(const ros::Time& time) override; // Called before the first update + void stopping(const ros::Time& time) override; // Called when the controller is stopped + + // Main update loop where control commands are computed and sent to the robot void update(const ros::Time& time, const ros::Duration& period) override; private: - std::unique_ptr mJointStateUpdater; - bool shouldAcceptRequests(); - bool shouldStopExecution(std::string& message); - - realtime_tools::RealtimeBuffer - mCommandsBuffer; - std::atomic_bool mExecuteDefaultCommand; - - std::string mName; ///< Controller name. - std::vector mJointNames; ///< Controlled joint names - - // pinocchio objects - std::shared_ptr mModel; - std::unique_ptr mData; - pinocchio::Model::Index mEENode; - int mNumControlledDofs; - - std::unique_ptr mNodeHandle; - - std::vector mControlledJointHandles; + // STATE AND COMMAND HANDLING + std::unique_ptr mJointStateUpdater; // Joint state updater + bool shouldAcceptRequests(); // Check if the controller should accept requests + bool shouldStopExecution(std::string& message); // Check if the controller should stop execution + realtime_tools::RealtimeBuffer mCommandsBuffer; // Command buffer + std::atomic_bool mExecuteDefaultCommand; // Execute default command flag + ros::Subscriber mSubCommand; // Subscriber for command messages + void commandCallback(const moveit_msgs::CartesianTrajectoryPointConstPtr& msg); // Callback for command messages + + // CONTROLLER CONFIGURATION + std::string mName; // Controller name + std::vector mJointNames; // Controlled joint names + std::unique_ptr mNodeHandle; // Node handle + std::vector mControlledJointHandles; // Joint handles + + // PINOCCHIO OBJECTS + std::shared_ptr mModel; // Model object + std::unique_ptr mData; // Data object + pinocchio::Model::Index mEENode; // End-effector node index + int mNumControlledDofs; // Number of controlled joints + + // TUANBLE PARAMETERS + Eigen::MatrixXd mJointStiffnessMatrix; // Joint stiffness matrix + Eigen::MatrixXd mRotorInertiaMatrix; // Rotor inertia matrix + Eigen::MatrixXd mFrictionL; // Friction observer matrix 1 + Eigen::MatrixXd mFrictionLp; // Friction observer matrix 2 + Eigen::MatrixXd mTaskKMatrix; // Task compliance proportional gain matrix + Eigen::MatrixXd mTaskDMatrix; // Task compliance derivative gain matrix + + long long int mCount; // Used during initialization + + // SENSOR READINGS + Eigen::VectorXd mCurrentPosition; // Joint position read from sensor + Eigen::VectorXd mCurrentVelocity; // Joint velocity read from sensor + Eigen::VectorXd mCurrentEffort; // Joint effort read from sensor + + // COMPUTED VARIABLES + Eigen::VectorXd mCurrentTheta; // Normalized joint position + + Eigen::VectorXd mTrueDesiredPosition; // True desired joint position + Eigen::VectorXd mTrueDesiredVelocity; // True desired joint velocity + + Eigen::VectorXd mDesiredPosition; // Desired joint position + Eigen::VectorXd mDesiredVelocity; // Desired joint velocity + Eigen::VectorXd mDesiredTheta; // Desired motor position + Eigen::VectorXd mDesiredThetaDot; // Desired motor velocity + + Eigen::VectorXd mCommandEffort; // Commanded joint effort + Eigen::VectorXd mTaskEffort; // Task effort + + Eigen::VectorXd mLastDesiredPosition; // Last desired joint position (used for checking if desired position has changed) + Eigen::VectorXd mLastDesiredVelocity; // Last desired joint velocity + + Eigen::VectorXd mNominalTheta; // Nominal joint position computed from model + Eigen::VectorXd mNominalThetaDot; // Nominal joint velocity computed from model + Eigen::VectorXd mNominalThetaDDot; // Nominal joint acceleration computed from model + + Eigen::VectorXd mNominalThetaPrev; // Previous nominal joint position + Eigen::VectorXd mNominalThetaDotPrev; // Previous nominal joint velocity + + Eigen::VectorXd mZeros; // Vector of zeros + Eigen::VectorXd mGravity; // Gravity computed from model + Eigen::VectorXd mQuasiGravity; // Quasistatic gravity computed from model + Eigen::VectorXd mNominalFriction; // Nominal friction computed from model + + ExtendedJointPosition* mExtendedJoints; // Used for computing normalized joint position + ExtendedJointPosition* mExtendedJointsGravity; // Used for computing normalized joint position for gravity compensation - // DYNAMIC PARAMETER OF KINOVA GEN3 - Eigen::MatrixXd mJointStiffnessMatrix; - Eigen::MatrixXd mRotorInertiaMatrix; - - Eigen::MatrixXd mFrictionL; - Eigen::MatrixXd mFrictionLp; - - Eigen::MatrixXd mJointKMatrix; - Eigen::MatrixXd mJointDMatrix; - - Eigen::MatrixXd mTaskKMatrix; - Eigen::MatrixXd mTaskDMatrix; - - long long int mCount; - - Eigen::VectorXd mActualTheta; - Eigen::VectorXd mActualThetaDot; - - Eigen::VectorXd mTrueDesiredPosition; - Eigen::VectorXd mTrueDesiredVelocity; - - Eigen::VectorXd mDesiredPosition; - Eigen::VectorXd mDesiredVelocity; - Eigen::VectorXd mDesiredTheta; - Eigen::VectorXd mDesiredThetaDot; - - Eigen::VectorXd mDesiredEffort; - Eigen::VectorXd mTaskEffort; - - Eigen::VectorXd mLastDesiredPosition; - Eigen::VectorXd mLastDesiredVelocity; - - Eigen::VectorXd mNominalTheta; - Eigen::VectorXd mNominalThetaDot; - Eigen::VectorXd mNominalThetaDDot; - - Eigen::VectorXd mNominalThetaPrev; - Eigen::VectorXd mNominalThetaDotPrev; - - Eigen::VectorXd mZeros; - Eigen::VectorXd mGravity; - Eigen::VectorXd mQuasiGravity; - Eigen::VectorXd mNominalFriction; - - Eigen::VectorXd mActualPosition; - Eigen::VectorXd mActualVelocity; - Eigen::VectorXd mActualEffort; - - ExtendedJointPosition* mExtendedJoints; - ExtendedJointPosition* mExtendedJointsGravity; - - Eigen::Isometry3d mActualEETransform; Eigen::Isometry3d mDesiredEETransform; Eigen::Isometry3d mNominalEETransform; Eigen::Isometry3d mTrueDesiredEETransform; Eigen::Isometry3d mLastDesiredEETransform; - ros::Subscriber mSubCommand; - void commandCallback( - const moveit_msgs::CartesianTrajectoryPointConstPtr& msg); - - // for debugging + // DEBUGGING std::chrono::time_point mLastTimePoint; - // dynamic reconfigure + // DYNAMIC RECONFIGURE dynamic_reconfigure::Server< gen3_compliant_controllers::TaskSpaceCompliantControllerConfig> server; diff --git a/include/gen3_compliant_controllers/helpers.hpp b/include/gen3_compliant_controllers/helpers.hpp index 92a5d6f..1afc6ce 100644 --- a/include/gen3_compliant_controllers/helpers.hpp +++ b/include/gen3_compliant_controllers/helpers.hpp @@ -32,17 +32,15 @@ class JointStateUpdater final void update(); - Eigen::VectorXd mActualPosition; - Eigen::VectorXd mActualVelocity; - Eigen::VectorXd mActualEffort; - Eigen::VectorXd mPinActualPosition; + Eigen::VectorXd mCurrentPosition; + Eigen::VectorXd mCurrentVelocity; + Eigen::VectorXd mCurrentEffort; private: std::shared_ptr mModel; Eigen::VectorXd mDefaultPosition; Eigen::VectorXd mDefaultVelocity; Eigen::VectorXd mDefaultEffort; - Eigen::VectorXd mPinDefaultPosition; std::vector mHandles; }; diff --git a/media/controller_formulation.pdf b/media/controller_formulation.pdf new file mode 100644 index 0000000000000000000000000000000000000000..3c100c69874c081b866d7d66711722189ef01ad4 GIT binary patch literal 120426 zcmdqIW0WUPyCqt-?fO-hZQHhO+qP|V*;QRumu+L;ZjI zvAxOPYX3?V44rJ90so*NY;WUgYv&AL1<)%vnVMJ{yVyJZHSVur0DASmNH7AJ|DJzw zkhC)~_4s>(9l*-*ue_Q4-&PC&B>=sWy}b*7^IzA>e-Q<+{i{2-f5F80ze7VWDFV>u zVP`aCWn^PBWMXGBGh|_5V`E}vVrS;yFlAsjWn?il<>O&6F=k+4W;0}FXJBIDG-fqn zF)?LhU}rU9W#KSkXJ_Qo{bvB2U7Sn}ZDBmJjg3qUcFYZo3=BA+fBd8mS``B%IYMU8 zfG6U`0hA7*B2w7EDi^^MY0L#lj(LzQz0gFc$b%%nHS46X0b^L@kVX?#5Q%B$y;d#ZQ5H~%Y9 zFaa2**9Iej0#q7u;EP-!bNi-WWpisUJjoB3BnHo!c+Ly_!4A4c1^v^ zD$0&mkyW3n_SKl>@duvqPqzjs2kZy}2HOY+pb7{eS8$x#|I=OmPAC75slxVlE~a)a z&i_#EKd2=8mxG2v_Wv;LANyE2S?QSA*#I0YjC35F|M2cFb^kW_U+5^AI@`NC8UMwL z`M==x4~G8^)<1>+iSK_4*8iM2m>8Hj{|iosTH5hhVrYKb`hCRZcPVX%iEp!HvWrcY z3nokHr4{88MRJaETvIoEhEM|XP@$0X2oB4ExK zI(mJEK^#PZXjqaJK@+Ms)-O#fI<@yMxX8$V=7NU7-Ee_c%ONaBsEfSKL;+k zs+~3N*AFM6?dj?5=p2v+2oYKZeiQ^2gWYOCOiT^c_6+sG_<3UwMvzgxn5fx-q&bKf z1CN~VTn^1#5l|5UqeCYJYY)~zTnU>t4zX()mIi^520>NRBf|`7>B}HlKYkL`Hf8FB z4yAs6kR~z7Oz?af=csB?)@7a8Gy)ifgA6!&Df*`Psx&3JsnL~m&P^~Dr-E7=1v1XF zz~u|UjcIgD&$+-QDPYfil2u*Zs%zmeGJ?Uee56{rTb4VgnpF#Qg)Cplq}5-ad`)X* zt-YTbHV1qvFXLgUVbkO4Btf!*r8-wXN;ONGvdILR1{ss<;OawGRa3?3!+JM!Sg(x; zyzL|tlYB<`;268LfwBxLL+jBH^)WcXN?~wi_0RVU$6aaEayu*shB7+1z6clvyE22~ zr}o6lPw5j24V&o-!Lzl4`fanLR_4@+%(9o}o^@q@E>~yoDURX(WD5C>X*qR70g@TNjqUf zj{%z=`Uz2Pq0aI}QS%H#%VT$X@H68ixnwy7FWNi4w@V%;okAq^qQgXc>6h`HW9xm_ z2v(hxrZ!7-4KEeY77Drx25W*<=r*{B_FkGMD4waKt**M&g#@mDx5O@$b5kS+R)5JP zG2WLen5IgVnMFNU9>z=q(>InQLQp@sMRJ=}okNi-2W<})@i&l^1jR%#Zld4o_Mg`d ztOZ*&)!5YdXmX@flPJ$D?sUCdj%0${Ewta&#WWvwS%M_R#DjYx(@55rB_Jur@ftI( zrKzv;3^c^E^8PBCuZr4C)>Plr)PON%Hc@Gs=>T7_pX~#w~Ioq5ZuwGTm9{(nlO@6m+ds?BSy*B27Lnh zYIanRdow~M&A}EsI32{OS<@jD44_iy+Eiz#iv=DGXxeBu##lJBE8dT$B36gY-Yp8c{Yyq{#0f3dt! z!um}D^RETv^+-xA0`J6;6uWADo>C)$NDj{|QA`3#V*jXfgNnht@Qqr@uDeb8c6iN) z8jL>=K8F&P7FQyG_E5wI4zAR4iSyCcM}3 z|JWRK@I{%q2*RDojx;Vdi-|xWQ}u#HpuGx_OvPsA{A2lSgo3;@*fSS}QiKk6x_-Vm z>*jD`x7GZuI364&6w3dr7}^QthIlU}1{@?j{MT!2P)K9&#*aMu6E7v) zce#R$<7@G_dDr@Ij#La9iR>N&Hl*_5!{|088_FPlG|=%ULjGoLNZ3^&{KQpJ*JpF4 z;I5E0kUcr;*c8xZi9EpAk*!g|>6z`ru}gw4jBwBUf7@2=tPk0O{^*N-pwbG*1ek z7*3Fwgqxa{dyrdk#M&YY*)M;w`1U=8=uqS&RWOsc85!;|i{p+A%d%smI$g}cdX$*Y zsd(|C$*6NYyVYddR0Nxu5)|sDUWo^6U4tQ1!{=|-gGFAza>>>~yO-s2J5Q*;zdoJ2 z-fJ91&Lq)aCRV8`J zjFWbI+J4&RJ%rg#mKw&!0z*s~zasW0{HZbzH<1H>b#XfeN;Z|!qL^)qH7jte8?{QG zpn$dzjJ=1fOa?{$!7rQ1cu%}Ae&-0`)$1-IFJL^MlRD$SDGvN1FZw91Aaa$joQ)|{ z6qdLLoQHfNEJ>=9=__j9&`XK(7Mpkl)${F8>-qWTohM!}>2Xyxs>w7a6SuFOHFC2QK$CxpkZ6ktY{bIJ3=mYlW-tO*yqgt5%?*s%RfRUAj z;XhRu6M%z(>F-+LU*h7QF8*_c!ueO&{}-JR+YGLtvyMUs7nl!CpaTJm5Df0_{tN(x zV;F_Ix{^x(bB7|>*o4N}z(*0PL((A}<9yz7zW!G4QdjRo=!BGNC<#-3e5mb(Ez?Cv*?Uz+XW&f(Qah5tvpp=qN*-5@-g3&%g$|xVY6P zIsvcF&bfSDUD?>!&=7Q!t6~tBHiR$>z#UwL$wzPl;cgF_0`7r@pa{O`^;aE^5`&#> z3gY-AT@KLX=m^B?3m^}q9fX5(^}2Hi%nZf{mJbJIIY0xZdNMfCACB_JW&r)Vf)B_^ z{oLODdiuhL0{PsBV`2_oT@B7BKq@Eg1u=q!D3_pa;OgLJ1{F}a-wp$4ldmN6kD`Os zga72i{usjpOTbVD4akN0=-?q|7LVv^M6E;}d~%Pp=^5a0)r7I418!^t70$_-^*bhq zb_C1f{k<7{S)27cuzw?8&mR;PYH?%F9r=jv$wo^dA{bUf?#@1$9C^*(B+bAah#d*) zV0RxP03XP}ote6MdzY2>qR&6&qGw1R{l#N--~t#!UNpcLfU#4?&q7b0K#jF?aRTym z`&PEsgN(z?-HT^*1jhibEtGHZ9r;B9q5Tn>N4Jf5t_UvpH4XAY zsLojq4%hpv-XO30rruxUzs>)--Pi~8a;-65M?N0}{P4Z|@^=|LdvV(L^*#B(PxtK) z_Kkn|J$(BuE3r28=P5q(EB@=d2x3*xhWCrjW3MXu9`!rbKwcT>Q(qbXMxVJ7j4ix% z<+E088vB6-(nvvi-M)&=*V8k-;-R z9zl3ov>UjN^Ba`U^zaVyOPzR9 z2M<3_t&gyR&-GOQWo8RFc(c#UBHEdOIndxdbEmnIiV=l9ZPT&9a!oe}4FaQ9bi^$k z7w+I0E)_fQJPy<7n*Z6L+D3XVFPctq!~4^sMi{|bQpLLKv70$gJ#WKSRQn}}pF#0P zxT-l1E;U6|`JwW;E4ali0A7gMr;NuoE*O?R%!=SDRXZ=n+t&Z|&f;XFW^H+#9p=Qn zM45(BYt9}t%FM!9mf0NoS3-zH$ZOvO@{DJyFRaj|L9YHpclta_52V0mfV`xA)A{zf zDR0eeERCl_J@V@sKHeJN-Q)Z=B=q5+a=UCH0_j<$Ttse+cZ))F4h|*FDKlH;Dl^Sz zwA^*2X1eg}SRso~#INrOMS~G7XOj!+5fdI3FF)JQs(E+5NxCZ>Sny4J@-$DSPvp3+ z&c{8k6)&v!^NNKZ*QRNAPIbBTm8Ews1~sMb{<0WskxXKow$`Nmk;uJuuxOo8xygT2 z*4lGs>1foFe48b^nE6i&=ofNLo|rS08l~KsU*|{WhXd)AF~WCtNc}$A)Q5PpGSpvE zZ&b^@Mt51a!gH6`xf5IRg$i34Z5|r32o+1BM{!ksx-N!4Y?wW8iu*5ECWUEjv%tO zKEhPwauDTI5(-?d=)MCvGn%A{xo+os;waZqSh|b-L{cd{jL7%%#&*QHx-_FDb+(LY zAi`tTuk|RwiM%JMOg$aARNWtFeK~}dPP2f5a!g%KwTFA>k~&hvbgbqz)8z?b54jbi z%}h@~#NIGYh>7xlYSxkmgQ}qeiLaY2^2!mn94hms6g@`5(_d?@FR4%1A6!;I)*8y8 zD#~^Pmn912l7^w7Lsd35_v~#Wlwqe(KSH%`;CQ%Gkb*ZQ?G^K znTDlWahOracgk^~tm~17jEAP(JNLmmG0D@tH=OXqg6g+%!@1Cz+BxE3p#MA;$>5}J z3k!;7?b|yve9)@~r?*^>Lrd=8zRZCOOW7WV{d($>VX-&*qAN;OKc3GWcCzCffW`PK zY|&@`_@uhB08id`p(Q<44^Rx&zb0(YG9oK>-5#{bkh@ynFe(79;zNH=`W}ynO zAG+O>g_x5|!KGHgrgw@e2*^E_hB3ji!yS4EMTJ^F7_wUOg3Uoc=#SZlP}k+*ji*e+ zT#ICAZg^?@TmuzH-1?c2Wa#XJrqGpab0G6gd3H&IdzbAI^$^`ilq=hkW}$`=4_@}E zO*%%576VNQ6D*!3Fgb69@#)w>h|+LTNHR~=e{#~patc?88($hgD3+FX_PTiNpl^dc z<1RilGam6C*o|#`BDq*^YHEWO9_pv!^%wm-S(v z?veShq;`aDs+&Z^u<=yY9v}W6kM5+xQFKd|qq&?qIJK+DD27N_IA7lCpb8J=07ew)r|KTqyRgJ@+i<9GTVoO%)m z4gJmT5>AZTs2YmK2`q5~G1JdXHk_p!4!!NWw(6)q?2;^}rWHT`P%Hof;!tPU{>b%Jq?!fW$Kg1!u2{WHwpzA`oE1>T8 zM(^~z30V?-6Ki7gZq&#^ui|}Z!0hbm5_6)KY(-U=BP|_Cgr|W+A(c9X?LuG4*=A+c z@s*vd#I79_Y%09!Y4gsU)n*>8cDa`{vhmm3^F#;C!}h(FsQtg(?Hsp`vd`H6w%13MVfIdvF%I*K9gRs7+c(55u#7DFm&hLvL9mFBEqfE5 zr=B_~v%-G&qG{5NSFH(L7t1k{$agKjC*{|c8wW$lSXyoRbKy&QqBWmg{%jvaBxDd< z06OY;Yu3jua}oZOoGQkFKq%%!`EZ$5H(VlV1@4aOOG6XM2oO<*DTzTW9f$_|NE5Ad z4Rgk-w(2hj+u34!LBBvZTX8WH#5@~72yo#+9;ET=BKIvHloftluDfN_hWrj%+O4p+ zk{({{faeBzH$2r`Vn#g-bdOdwiZ}#bk%7GUGJ3^&ruP|w&FKSUoQe6Tr7^T^m6CCtrt=r({#@1Kq_8g`wvnd|gbU{{9#GpH5TS2#* zl(M7)#%4Ksq5#^EgxgZTWs)x}sKh<=8#~6Jnt5=oNz}K&wV#B%EyikNB;f`h+)c=# z*jq3iV)IA1_!HyS*vEM}-wDb{jdRwc^SAQvAF*u%1MPWD`y+QtD9l}zWlnrix{k;= z5cufqYA}}P-jPE(4^h4*;*#&^ies&-RicL~U_8Ax>n7HhkvD0-aOyT_8{ZvTnBw)X z8{DGa-6xkyi`|KwfraBL$1|4xFyM;R--M;TsYFo*j2=VxS-a-P_fg5exzPR6KRjAL z;$nAD++NMy!n|=)1qF1ZR2+7xnHjpV@MKLeFL+fTd zQb3s}@~GYs-~TktjVp1rseh2bq7&}IIhu@)^#UnqYWAOQT38v2TKS=ovm{vc1ZoSs z;*3#4w@CdQ+Oe3gIdK(WT=p{0nt92!CBV+f^x$2QU8!Y6g&>`)_{si$(lb+ zXiXO5>{;MGY{6fJ$Y||_rG0<`cv_mdbQ;C&R#Nald$)0oW>;CdZ_I0LcUuvuGB)Co z%meEpk=6T;?48tbCujX{o$D}0+^q;J3x;9U$B5t}8|5CbH~b`9uG=*>Ah!V@6ujaw zx#oslAc;cOV-D_kAL9j5k&v1REyD^Bj=*qgu(4&t6N0La&6zqgnuy=`=8=h+Y%9^T zNFX5h7?$i~jjnr_1CE^mPZmdwEQOXT^&c^xRF1vZcRM9}gTuYKc84;oC|R)$p9-5c zX#VSIu)K(gld*e=LkK1F+&n+j(=JJiq&OXR(O{vOganKmA|!I2qOsPQut6&(8KHqQ z>3TMdij|I!As-&CltVczpp`e^3#>Cud)jHpYO<#1C&fqyUJkU7hZIZi>EKsL_UNk} zRYWW(77SY-Q*|Q{^d=E2HJe{g2$o)w^mPWbJt!@;I__vVN(S3B@3=r9(iqRC>0H7xX`dvQIhSPSY*N=#UX^ z{_!?58d-pHn(A$u_}Mq(V)nyi7z!Suv4*~OYJ&xQn5TNgWdIkD7Q^&{CN5Zu^PI0p zE3uo9)|`x%1yjwX_&E#&Gbo5BfuaU0F5PcvQ{roFT;%&H<#`q(>BaMEG=xYrC>eS= zMdp~T4~?!s!dKFLT5BmDdQ|T0YafFkbL-yc-L5)B;Iq7leUt3%hActCdZ+|ru%B6o z7wIHm&n8XEn@yPWGOk6#Mx)Gs6b$=_7r&6xC}huv+OKf;2o(H41p4iKw~nY;7@eqb zrP_CGsm%A>u^N-;TiNHM+7Oqlf|h0y_VTL`_!JIUv`Vhko()^}Q&mqP^BPItTcfx1dxtcp>v-nS^fu`>j0`-|RHdo4YKnTzYRZ#eI_augbu+|;J# z-GrZ}hMtVC@j*qpIhA@q_w9N8_!{ID`BFin#E0<`OE zZ_=~qg`on?q%cR3Cz6PqWwEFD>VwTnCyFj*NyEY*Pz>2$<#@Lg+*`E6X=j|FiDzcn zV)8ygieTW=i4%0H*c!>= z>~P{M)-?3>ten9pDSxoOZTRRlU?-3&eW^XZN(H^&G4s%-$&V~)|+FZeu)-)TjlLs6-K_^ix8{r-=HF6Ns_xo7FG?n(fe0T zEShZ7R$^6@+e5SFtmUBv!I}MT0-Kgr-L5OLV?P#0Y4cmhvOACxDm|$yb5hI~57Y7l z52&ABaF9K`lZkUCEe{L%yl<{;2xaEqNwA5x)cK$~ETtYM=7nXS{Ck+&$kx2$t@^Ixv2Hbbqv!rOC&~i?4Sc&Xiqj#D~ui)mPi8u2os= zFyfyFe0k1Rakc`)YB7NLOc)4i4C2AFz0>&CVDhv8Y25ptj+rlF-^XtS* zsI><6Ix9cYI`QdX>Ty|qaM^bgazX79;r)Z`s~#A__7ru{9du-x0%9)b3Y3@1@tX6W z;LXznH+vr;<2R0lY|Ue{g#|4uFnqgZZLmEVL7Vi{^aU2Qx%R#d&HHyMaBgRECE>?r zS*}=KtvFz!ANvtcYVW2apF*h-C{0osQ&<7qyE3bvNwp9^{>(%;E%@l$s+8u!KnM); zUAIeTE^?N)X`-$BTcp$J+O^Y_l%~fcmk8gy&J(+k$jMncJtyxn^bG7V3WUO&JAYnwWbtU9GQgA)*y4V5Fk<93l@?#&0e4OIncM7Pl7X=9p2n(^xn&L2 z2$2BZ7jvTfeo#JWN&F6A%6QS0j^l{EGF;@|{ybi^kScA(=`#{fSDX*&tWvL>t6iNE z5&E?NO+l5#8qRsOfVAvG_b#e!Z75ya+=aKV^DPc8k?$gZ6N!C z^_I?^(LR?t?`=g}#=*_Hu{6og2`XT80PKXeRBe;e#@RN&&ye)*Et0{t> z<4ZhP{md;z12-uwNA7aj#9!F1qTE}Ya(QUe;SASnp0qNr4cj+Uw>eYet{tA%=hvml z9dh>=yUyM&KYo~0h7ym>9c@Hd8Wt#`ZzB~x#gZOAH}?%hMYCJmhX{YV{v+0Utqc|j zLm7b#ctaZArl3Gq$%0WLvJk(S9+N4=^pTL~(hmQvS2^D`LC0&Pq;bzZ-e!eqFDZZG z8p*fEQcAdKB}*fQSu4eRT<-r+0mKXepKOXDFPzR)ml; zH%Ts4O66E2+|byXa}#kRrQp`--)G z8o|b~UMUt*AFhsv`cYKecoTy!HpcSB(uAtu37RlCz0R8|jE&G9dNvT0@EPV%uyU(c zH5Xdu;GX68@?f86a7{=2Zr{9x`?YjFqn}#5-5=Yno>g$Y+$&SdE0&Kg#(#?QvE%ZA zwK@ozBgu?w6kB&L)cR)0`$@~yP-4AlOlbYCR*{4Jt(PXkg*}t;4ieI*Wo<&TzJI5X z^G8u!-g6}-eEN4^v`eHi({{XkS|@-qwl#$9Yt*18_gE8rH1pTdz(pfBm4r?bOr=#8 zd0RrH4`|JtHop<|;Ii6A zbSZN`2o5U)5$DGtt9%)j9K>oEY}HDqI8GG^iR2iXpFWDLnLbK~=B#F&-g-;$)UhQBn9ZrXVLl`J`W=px#TUB&eL0G`3@n#>(4R zSAcmiaT5(ch+(QQ&c#|*R99OPN<#*UO~;FgwD?mx7Lv=z_8E-9jHPpQK#dPGf7ljB zBC?!Av!2QI^-RlD?AgKlWaA0(=Ht89z_roT55gFf0*B6Kff909ueR2Xa!IKLr!q&K z-WNJ{Q8t4_m&rV0W~UKqrodBElb;PQIM7o|^T@<~@m7dF1~2M#2)LPi;V{Q)iAZM0 zXO#9@)S`h0`d>P@{0fBf3X;pdB$7Pr$J|(LK~?H`p0$GUXj`;kd08T~)HM!UaGH$1>#77b0$BE+fTI&P8NS znuQR>{gyi~nJY1?kunW}N)!avgKQlYo)djO9%6wF!d#x7G zq_ACWTxDd7FFOxU8RkuXYkglE?q(bYeQ-1H!YM5)IhvNDBbrQ2faevfoENbxMmdxD z+bK6kmJBJg+siY$1X;))mVaf7U^EUPAAP>8WkSr`C!>vy!N>zSAZ%-RP;oYfahi1S zbTFOumdQsb+8pvH6_Z6@Oqt_VqS{Lo_=?XbxV3XZ&NYqzmn_@1*wkFhvX>SqD_<@W z<&I^$kVZGM3(5URQ)*x&;7(z2#6epRkDTZpsDni;mhND0-|8~9>yQ(B_7B}7_3 zratAsl2QX95qeO{gD3=1I%aLzlI@R40u!MfOjW)@EOSpV*FsEYnpv#SczYJ^4~udZ zhmwA|qVp)wOJ5zMYluX(kpmCeKLI7U<3aE{wnH?O;|DCV1jT%d8j6^7A8fEvT>I!T z>}a3f^`4ClmyEFH>8!Z(=G)poD|Drn^SHC_4Jk_hSV;cxgdaf*yxNM1-Xd_YBEdqt z%ao~y({;__*>R#Yy+ZA19~74+SY{xIf%}yNF=7y-VfULNZ-%@9UIIsI$d?KGixIEd z-0L)7btx=8sB~Sn;k!$2nbf~I9X8*}Bgf}@UB95658q%m*710I#7~W}O2K^GZ@Lk) ztZAMhn`*Zyn!rIIiAz5IhgJbraxB9lxQ{be9RA1DMA5voo;egLQ7>|C9!>l}qN(B3 zPcH~2i)nnrDI%*_+={h{$TUjuQQnN6Zx3&>C{t?6%+K4`8klDPQPOY@SjWAguOi@7 z>^}>T?I}E3UIkvR!A^a{u%~sveul5MhmF4e!ds>kOJD2uIu?1RzADx$gFW%S-BU^< z11vf)(M6iD8ze@~{YoCK- z2Ozl#vl-QoMdSNIsFi-vaP_z~ILuo93gvC}N%35YvoV=!0mmru_OM{?eyoYS?ZrK; zDarRdCR5&Hu>u*?1Un5~dgba|pDHcv!yJ@0>_V<`Zge;=3Zh@cChQK_-^zxS2Iuu_ zl)K}+Ght7ek-e^zmt^mmkS$I23O5_LGA8IYzJr*)i?!0|hgs8D>CUVqo!~3iY=4r~ zNaOhsvU{K@VPCC8(cH*bm*O=Ex4)3`%Y)Ie3k^FMG9no}*c*50@n19eQ&@K6F3ukv3)8d%O6T1}Fivz(iK)vs_I z;2~?*>QGL-Rg(XK?1=u5R!H%HUaz!&8k!GcgROXp=4o(hPKd^jPeHP1^B}kdozhp_ zUCT_FYi(MnZCg`wM(WO^ZD{Q{3yOI{7EUj$#_kX;fyWZYl9&=@t#uV!=-$T^h11z@PYB_N@X8DBy4WoTjt(Ks=Y~T5&L@*YC#c_$fBYOeyQ8&Q-hU_&` zoTOQDYfW8HA!cJgIhhUm^}&dpF6O_{NnTzTuZOsWazvQ9@ubW|WyNpSXKqMyqLN2t z9B~1jyvm0~_h$Nou^j1na+x{XW54^(*zRpP)9%m{{X5pHKwp1fa%||zwSTyMGBpmc zD59rAnE4PrRb)~)$X$3jXL!H$yYu(knxp-1E!mi)WK1cYk+z$|OJwI0Q%7qhwJ{&p z7%@SdM)F(&Wcw<(%yYg76ykzTBc;fuXq2Y35c_$!yq9LSj_NqnYN3)ZbU6yXiMlx` zC_1GqFIL1_4Bh*-XF!Jcm~#olN>vtY--y>AU~0e3;s{fW0AgwM2SdxIDOW(NlrR*s zi->z*W&+=yJjOUd)^LL#R+Wz6R<{^R3B7IfU`_`4s%)A2z}!ga&u4J#?J0JcXP)Jz z2f?sq5f_P!J%yQ>e|@~Nk-}tNE&sW^!#>CtMSE+_q5~o516f7v}oDyJ-y3icE~w~JWhl` z+0jwFds52`il-)!wcY3OzqBAl_eitEhoTB1Iv<@sxK1aToVern2DN{tgV4YS$$AGJ z@x|onFOKJL>6j5TuYlV+cD(52(hw%1q$`;FY;h1pQ36}~#+J~h>yz4Di2OX2S`<%1 znS-LZMdhN!KlRFyyCrSJG-o#c$u58)$r7%~fd0JN*wxo3*Pg=>keXrtn>n@x>lUnf z`(t=lvg2N738`_BjEZUmO6=N3C#G7;^>8Cs+*tSKC5367x<{Q|&$2!3k7#y%6qD2s z$=IqI#AYLJQcpU(R1hTFYGP7>rit3j@tOnU-{z|o&0_3^yUd2N1vHK$i>2#X5B7@^ z-f|8dKUvE!%A&Cqi1=k5P1{a>NkFPKfH?AeA)a-HN&Gi4JS_j$F+9xd|LlqQkIe*3 ze}j-2{%(BuKVx{jqSS4p{kqT8g1Ee-}j>1Sw?kZ>o)M;HJSp6q3C zVOK(#Csl%gN15LQ5J|YR2SLGnjBp%(_#bcmzS3>{!@m7~VSep?{p_0?A1f-IF1`k1 z2(2p6tH=Y;<6{h{YOhIz3W%2vNRN-ti-?s)408(j3XNQOD3HL!0-<~AfohPTzzQ8c z=%rwh#|MTiZ{-3K00By&aQu)qxS;uf&~!pqIkY=;{z_CMEd~-90K?;4WV3x?je7JR@$MU;G*t6#Gw%! zwb8~U;h*3z=J|K3v@hm4G?<7z`m%0`Aj`qQ)&9=kYU8zkUr1k5yC=*W=F1| zKb#w%974D^-mm*{AX*x}SVK}PQEw>mjxJzS)83^8g+;#mZ1O1rkhX~p4Fwf}7O{aI z16Dx%QzBP;J38C+SGHwcfLxS9VzJ0z=!O_xFgKhNP^FM4q!!9zV zD5@y!e=*S1P?fLdsHI{TY+(Yb*e){QH-W)qTG*Ixj_S_ShAur_iiDPx{5;M zqD{t_Wi#}+LefU-`@_fH%w0XIcg%Vzj%hcEL5hot9zE?MFob~X>_sM33lq)_yTHD| zK6&qI4xJ;cp5B04O)dZnTho~P^aT%CG{y~dz7A>y4fXVL3Ro6+Ojo=VcXLoeM*1S_>t%kjx{uOD}~ z&2*4q%6;NIE&SBPXvtJ_6Gs^Y^h({T?xhk@o8mt9rsi)c6hhlwPYahX^YvQX(gqiL z3W}@IEoTn4jSMMuo~_M6xa^c$poE^k-#gaPURv(}q8`hJDm%wt#eOJ^vqT?hxI%3< zock$V7B-s1-;td|{IJgsy?Bh|t!iDo8{bhRTJ<{ak@nLMYj_;bj|-6?pr6*iW%$96 z_%9gwK@W;dLZGgPyJJinqVESRKzPdyjn{@a|vGFWk0vcwA zk_@jIOi`l(C1^{|{OUL}&ZOsh|7g7)9!*+cNt}DTY12ZhufNzq@BeKA4ZZVBo+O43 zdstn|$-T9Vrd&UeB|i#t9g>ahkMmUflhYJk#cI)Mf_R5>o_#le9VGgJ21-*nd5O%( zj2h>KmdA#T$neO1k?);G11V}$;3*SCuq`?V5s%*JS_aJ3myE`g2{2wQ1O!5(`de#j zTI-ov+Io73Kl#a^clQ~G&;ekXh3dzOxwl)%s6Ln6#m$@n=g7Rug2;_<$lDg~>ImQG z7`#|dw;|s#mciqbjX-9O-fF`|eHU4PBy+35rET-04ZGJvTm?<&E3Jru?2+^Z+C<;n z0fX+soAQ z?}pPCV+aeiV5n4>&&Fq$1(eU#Y_lzh&Lt_Fpdz6V_qEIlJVtJI_fgX5ST40ck$aEFf**AR3m1jWt1sTB9r z=aoWsjc^qVB@MsS0@}eS(dDY&+Z-}`%@^}BEi#C?s=;wb#>k*J$LayzEsu&}A&5~% z|K472!gP~cQO7E#x~x%Z6NhSt(+x9t%8KvCS6z+xqvl05=L1ubk?$3Wh?nPMB1HZB z!)B{J{mo&h$YR=s+C1%u-p}`{{^Ba}mQ}rmlz`#oZh9PEj--jQHe7jf)_SK(v6EmO z{=#=VmmP&awN-q4U ze%(|~qFf6|#Ni_)&49hKyz8Xo1psuphw2t4s_qeP-E5xZ`(^aT<+1NO=Qf+8;xQb% zbs+Dxn>n;l3%54Jvj!PFA@l@4(zco0nx#95!7)#SswEljylWY<2{KmA);hf&!Q1GI zA7zIXmbpVQ6$_1MkDoZH=jN-S!^Hy1eq4fQGF{^9O$lR)q6=k6*b%E->r;GfH z(Ri}=FMpkx$+eyLhcs#xo&{~a7JivRpTx<$OxCnH2J{7dKNTnbyDNaR+IDle>2jk% zQ7?JO^?SoE)b&NAW9Aj>P1`!6u!fFkIj^-Ey(lLfp*qNS;KjrtA&1u8J6%iT3N*>J zeQ_ls4ovzeVnf0Rbq)-&P2+?>YtKDXdjJ9_AK9$B$O+GnIVQiNj&eL+Dty71g?tg; zQS7VBR|l7BrqAh(>dQ>=UnTI+G1&X|TXD8sFjAXb{aEqvvsq<-b?sQ6r%AMf*`(AW z|@=qF8Q2MBeGzQ_O&ykY{QNI3~cwvtgLpAy3A=orJqtchrv*SJI>-T zKI4+dxoHkMuRRa#a+f! zp5l?`M_<%a8hK~$2%=vr3rzfQHg$s_9S=^HYM*~-L233E3%l$LF5vUW4g#Lay9p?9 zJEicAq}W7mU(OospcgAVk7icT{0P`5J9_PK$}qC?@C2#sGDN2EYWyCVIj-^m1tVy6 zDAxdL`1Fb3xk4G*{&85lk09*;d*>hfkgಆ%C@Atu+PB(~;ujV+cP$49Ta!cLX za|o@a))66l5wG=+oj1sxX@FT^KRp(m9h0FArLXLUe&LvWR=K+838Q54Sj=}u5?QfZ zuu2Epkl0XPdh;e4P8P{tEf(|nU8i-bm$G&_h?yth?iLtK2O6?7nHWg1ZM02scU?rT z8=6)lJDTN;N;pU9O=*(i*lf~T8N!JJS$Fs()saM}Sc^8BsGMu0X3}N0p690cbsy80 zDyTAU()om6^-OsS+(WDLOJ^X7j=}cCGWZN)jT`9WmMk=sACacZ2`*EU;yv59xO_FH z_2i=|`g?90YPauhWjinO57&9wa$Bnjf+3Ql>|3t$J=82CWZH%aTl2T4e;9vmX?ut~ zs?(XH`1L`sK7nn2un>I;_M%f`lxNW!>mp+&|9o5YS@!txx~t`yXr6uUY1}`(U=NPk z0OJIHzT1KWK*-=j#?cE|wMzD$RCJrTbqD{)moVnsXiE2G|Axad+6K-o)yFMMd zv*N)_7HJ4}gf;x0(nF-;H5qqycuDz@hB4C<{}xBxR^?D(s$}|kw<#Rn_lJAOS!Tnb zEZ)Vmm{yu{P=+SeEYbWIdT(Bx*E|04QyC@uhc!5H+q)}m&a`V68nUTklzq@VT2|<& z!%)fjj9XdCwlxRc3${uPL>C);ckp7{2uY5%SC^rfl(NkmD&KZ5BB{9{|LJC7#7ed2 z^wSs`*|G!r4eOc5j&|5HN0KY?(Sh5TjY_G4LC9k70Y+DpB8(0fp?1^`cuN8~x1Z|+ zQ(O|m2{AQ6(ein@bbfkRQ*fEU)b4)T6| zy)x-pz@ea0dG}KeWj8Y{Yv*wbcq2pGXlw1yrh$^*h;A=fFZI4=$;P-?TT2;~3s`iJ zQ{CGic%lsnW1=q&6CmQ|x1PDkxN5({6t<;WZ?;;8^qdP^QQRCk=0m0>)uCBhCU|)` zq{^?Ap7`>admcMYqQ!7m4xwFPawB#KAhBkKpoea-m+8QBqG;My_R*D$y@IJi$%xHR zBxv?>7}_hHJLRCxEo|N6u(w^T5>iaamFVJ=+*agAOQ)GJD>oR_Y*3SJeyuXlS;ATB z{kqP$Q)e}sL#|n2Ky-*Ee{qwlUVBAD;n5pgd}yCo(X#!TZ?5z%VWp}D_(|+YgH}3J zSQH24#ioG&K53D@USL*Vrzfy64!Wi01EzhMWV*-QE%TU|uVd?IcVx3wOs<(2&B`P~ zPRf+X(&fEoEU+N&!F-|+t zPk`XPG>XHANXr_7{nl3@1*PXRg<@^Z5; zCu=QJ0oD%2(#|9?B%vY8w0EZ-t1@cco9{u+n>pT5z_5B4hPp}Wcu^{NrrasGP<7i5 zd$A!?hs~xwLDy@dd9(3kgTSZh5o7P=__rz>r<`ZLRSF;{jkx;|>km0j^J+hxJ&zoj zQ2JR4`mt9@I;r`JVq1LhrCxjN*6BST$F}xE?&cnJ%dy%#3HKnaekT(aRc9p693GnT zK^f;mOd5?V-BE9jK8KeGeMC6-@Sx##4E6mZ(|jjJ0rQiszu_#{iFzN!`3%3jl4nC` z*NmBbxgKig0lxM=+6VYPg0aM{`L}EVxx(|Bh1f6H(&76UOWC~k@e%95sj+HaL+M)O8`@j(lB6?Pn1$-p9<;H8*Fg(yAuE``lXcI0c##_3B?5+8H~u z^zwMQTeyadU-Q=6$Unw}iTeV+rP|_^OoPS6Go{ZZX``(t?u#;gr@vO?B-!zpEsVCp zE2-6L2{8(O(K?pI!~0mZ7EHpg&DVZD$@_UsA&)BMlZyjj*vN}J^-2bGT#=3%F%$vZp-;D_zqX?3MNY|J_ zwoypTqfU&sbGvdb(gRs(ytJe*77B04DeP=>Dzz?w8U_?*JVHd|I)*3zKK${)n|DM2&pF_k*IJqmMRSQU~UyrS{E#7daRI4{a?-LL--#_lmjlqgsb@Yv=Z+qP}n zwr$(C?YU#ywr$(y-nW~VyxqLrY$u)c>GaR8PIa9+-wBz@{==+`hEd?=+a%FrQHk_< zo{=vKw;4d`m!GHBc5lDHE9I#UthDOx)a3!|ks|BD*r#tK-z-^?i9h2l1|-g`&V(oOLad57-i$9G=Q5Vt?4Nr?LT#vqdiW485QKRcdhpNf$lG z)vtnl!j7$ILxsnDrmUZQV-UtSX*lYS=gc;Pwp!)T2q9ZKwv&u>o$zThl*cnx@SssC zvw+Yc=5Z#r0KHdMB>QGxi1J5tn#Cuf6SGqmfcPGGN8MGb2^jkPnm^H3+1-(~2pf3z z76v90ojVA(y*-|Ov92(dhXhNrYB%x#29g=WNVraan+9QLj`Bk zH3W+Mg~;gUjxWaZmGleaX@}1Cj^-yKjz)J$EoP^&FG7volR>^%9fzrrO1=pPd&@2K zi#g_QZck~Vx^lHgQ;wvq7O_NB_;Zzj^fm#>%YEXUY$XL9OGsm zB?87AUi8s@JU?dxv@T*P;%jyqYN>#m@+q4Yr$y82g@_>#jvg~8=L-Y;JBzQ>jL&*W#H?81qC z`WX`>Jsx*U3)a7x`<8L3e5Q>Ggsv@T+xom>jdI)x^wzSP=54fo%!TAdJ7fDUp?@Q0 zX?U@@7Ed_t6NB+I5D!RG+WuI0$%${vv2%%V0mUI?&^R3d1~buMXMaj&vm$BP>_qK~ z@f|H?NsNDxxQ#nP(SRDM;Xaj3=R`n|FbDl9#U7NzKSNW1l;;DQ#`Auy)D(Q9NEIu{%je7U2 zYBmhjokJQIDt`}3Tk0DUX!vNUs-!r%NM zGgb-z@DUP$u`Ykn4{!5wcR-$sad)XZsHiM)qOn*H$*7Z}KvuUSSZCTHWfr~0MVD}V zL&gdi>4B-cp}#9qNP(N-dlTOu8`6}uoW|E-z@!#1^@HP^7j!wiEW!&S9rn!GWxbpC zCjr%7W6&NE>uLJM<^tu<(NpkY_na3Q&RGc zn}*!RLhjQ4SQbd0B;T?0sgqZBO`-Gq8_z{9V!AFbrH<$Z+W}?+npxr?fD9Y6$U!ON zwI@!J8(wkPf>09#7lOMY;pa#xq-3l+pA5M6qs$?>p{0!a1S*g>9XJf^08WidTAiJ$2f(h z$q(54J0*|eC0&x<;Bxq^3G!{+Mk#Xpq&G?1_VW%UEXTv}saLZbnrQ7#hkOmIVQ#NS zuLqly&XU_=Vdhs+dYqul3r%lzP^&btdh@2o2y}r- zhr>Jm`}qtH0HDNgV-g5NVOwuS9UUI<-qVOJ+sy`yP+7XuW^}FC#uo=Pg*!8JbaS?d z8B>PKIk9Ry-|LjdL>BBx{7Tic4TT3xPpK5YI$`?c)=0b?KT{lq{?d{{8C`Cysr0wN zl2LcG$9GT)9z374)$AtFZ%F)%xo@hGYhF)6V8`>%c2(po)KaUH#CL@H*b(>bMaV!y z9O~HXOQY=X>oZ`e74_uXdUmD+q#F|aLi<0njVs~{nQZUnVbuF?)v~ja<_ycDovwC} zKD!D|Ny8Q?xSQjTC!i>*s50JcRYhJZ-1=EqGl*|x6<0R%M^D|AW z@3zQ|)sgmYntk_e5^v8O0PQAeT71bJ=NB)s3j))9-Tn$vgB(^m4g@19zsYwW$Ne#j zhwtpQvPj32n}OaDJjbdjl!l~*@3owKOj=BAFb)>&R)5Ut8zk2a$51)RT=>g$hlSli zj2ycS)tjhT{{`dDu_##&kN_J>VjB2B*kcy)&~_z-*hY&P9I=RAhb@{SzGR0oTfGCp0%OOnHwi3)n@f^%Wi~I4a$t>+DEtz zh%qnhzQ)Z6owpTFQX9@*En|)+u9Vy@j_1>75k=yXv%eK_y5iF3#rz9ucJ^GQ*bh+U z>)vSF1ou>^?ln(}tgG<0k4qmQ1`%vcmgKg|6wlF{_O^M9l7nxu2?|wiM;(=tNmV2mb0jIqf-<1YOjaEq1QqGvS0vMV zUX}R1Nd#7+JeC@2ZK*u{(=NI)^b5%RjLh_?#=Bi=8(ZH@dTrYHEx3F6gQnW(Ow1OE z(^ijsk&F^Y|ILKifB07aKWYx!za{VgRid&{>9;+gN9j7H>I##*4lv{*4uv9EhfH9< zYN1@Vtc_2%B^H;52>bc={DPp}#N|Icy?>16N$liB8Df2gE*J)MB7x|JB|S(VAx$8-HP z{f(XwB3m-|s(JOgre>!O!KgsP=8pb|Sp?jH5h7;)OEunhk9Sc-HtH8PoM{C zmP{_=lsbYaU_5MB4XVTDEG@By0bDhBpQ|(%GdtaLWN*k>6wEVG3dEii(gDdnk>ouj zv>0FSEW`0YC}^Sru7}V!mN(M*qjM?S`GC6_qJ5t6NOY8d%@fJ7C@CH*Cv?jk)v?HB zET*)|{A?cmHa9Pf`+WAj?@ftyZ}x7J8{?iuPSkfgDMBcBiuh=pm_Uvc)`OAqXk7Z= z4eF!uvv@Ki!CYyy2jho$vPKvWMv*b45usd0#E0bZ_%dt9Zl>SK*Iwr?8F#VTT3wGD z&R6`8(G@;t_k)WO-Q7bYuOZ6cd-(Ue)_{2@#BbnEr*fzNCRkYiKZAvX{{IXX8M{qR zgsw}qx-fwAeilArMOql(Vq;*ACt#VoyPDXcBgk+Qp%(b}*SJQjESm(O=w)3o8Sh@dSf)pjNWJ?uJ~^FimVYJAgPWRdw^JQ#xm}|xBR?G;UsS#_pVvQf2R$C< zcq98y93*_v+neoit5tDHg5EeI*@3(VKNLS)m#(93Y+k(Zc4Y?H5=XqSWv$7N^9|zZ zZ@|b+$9e2HVc%~m<#dV@AXTG1>$miS_33)<;qNKylk_i(A<^z&&4L#5@Z0APBE8$R z5dqV2x1&m1JkfNYhV3YidKUNYnL82tr-na97l+KzwFf`&rWVKd-t1i>bqEdW)xvms ziv7%=uh+DZ?_$6^in%-R3g#cGQFswSb%5cNiA-F7JpbkIR8?x z@~Y(lfPAo2Kyd#HM22O;!TivDOk8fslmn>l5^0C}s(1y5P*GTDf~o@=d{c((k{!{& zFi=n}26E7^e~aI7EQ|x0QkO7>VnauT#q?wK-j?POt2+rmlfuG z(L0Sre@ufM7TEIDu_}w8c1)i|W}KI2Wh)n+x#7!dOF8=^*!hjyWBv z7a)|CNTa3sOrxvisRCl)Woy(4J$vc*T%!p)54yHl5Md)Dt=*zTI63~d@Wm-4&17x|^fJ;sKUK3b8h$$ARBRw{;QZuh9{ z>8m|l8x zY_skXE^ncgSAMmPzun_MuO=_Owf|c3rhi^(KX+Hxe+5i`!Bf8RoL~It*MAG9e&7i{ z`Iy&#W5yeqk8MOdj-CJB&*H$(U$39dEGFxscvhd4^kFeX-@oMJyntU7@_9nm-qQB? zT1Wl@%KMy4|2M(>U!~0dCGg1^S}Hl){AV8sJ|hzg+yBLwl*MQIpZuhwlQTXe%m2>q zHEU=nVM!qUP4|i|VGHA?Qr0`w4 z5Xrf?xTvUZuPnQiL_KP)he*iPavl^wzq}P0$c`H)S}66DB~;%ls~7}8i>hEHK>t=z zseqPQ+k-+oOt-;LkY=fbPnAV-F3(T( z!<>`DXLD-#mjCr7h1a%cdKsMCu-a9$F_dL-R`wS%o6% z#%ub@nX@NXuGE$(_1YIBZ+h13 z$U&j0Y}yX|)_2bw$pN3Jxwjm; zlU;B7C{xAXiJK#^S@}G=5i=%daViShyFtOe`7yFVzFj(4wmAp0vs-~T&?+hnaj#|Eu znwQY&8&U`aEw%{tL+UtI_)xHy>8;d4FdNEs45n{rus-0i#^EgGvjUuZF|LI*x2!#jZwfGx=veFEyvU;~hY)?_8PkUXwU(CQI^X_yV<8d8~z z))FixSDH2eb|JL+$q-#2jz$bu1V-a=O+X{6NXdl=+_sLS;jxmJ=@kQ9x~T5V&F(R% zfej{{f0d>3V?4Yr6FRF&VVo+iq&FgNFtFBAwM*_A@tb0v`GlXM~aOlLZf>$P!Yw5S_N($fz{K4HPLkIKdQ!^W`N8V}W@1 z1qO&!B1u+p$M#D^Ca}D6C#Kp7e6fB44s~aKRR4T^%caMu~ynK47bx2R>=Yn-v({2gp?v^E3Jangvl> z5saInElEOEF{3{cQ}ZVM90oEY11i*f4<^)07o|)oD9zC^mW0e#GWh@sJmLd4gl-tW zvHz*RukqI?a9d>nM|82aWu9iMxBZg+<}){pzE$8tSviDR9++EVS>oT4k%{UI#R^lQ zZ5Sg6$01Uf3vG^R!bbv<@vI{^%hQr)>y-Bs@gQ;vow3#JL}d5Vl)iIpoawkdW6wrm zv$e%+hY)61j#h`K0B5){gMFbF6;GUgdtqnT@jb%GP-{2>1#LvWxp!0{sHg@CzP;5g z4@W*@BU`Mskx5pB34IoqdOfjrT$)zyY(S+G0Q+1DBwK}cso@lq!;xm)vX7GW1gDVkHV%jIY2 zNv9kBlxFGsry^l`WWiaN)#b49{lijKZzoC;u=ds-1<@T85PAt14jg}UpzCaaK{ZhmqO zt{1f0>j`6AJm6m0@hynfY`nMd79K7edt=Ez*q(0A-(47foTE1V2~lu*&MlvvJIlWd zbWd77Rbn5?c`;cQOjxr|>&CpCCC44}c+X@$Ki?l+?F&ZVWj%9gAChuUN0sxdAC0*e z8M&8szkL#Q2{?J`8;-w*Pmtg&9BtQE(mngc@5H3fL-X#fPcBGf;2u4EJ$>UI4&IftaFQPb&dQBIelvIc5($Hq4*R+LyB z1sU}$Nj+Gn=4sPaK1^x7i&ZU&yl~$pR6eT{J|Mo%4nDjaOO&^of2GNT_Bfd8EZ?OJ zR;$QRm>8%#!LJ`)6kHW3f7?B(t_X=5asC{CveNinsT(QQ^Ys;%1ZT(DvNE5r-dkga zj=fBu`z2}_#W(+mk?pc_&gS|?5_^}zw}E#rg?*&>R>wVI-H6>HjPS{amnB7wqox@> zzMDD+6n=^O8GSo^fs$~xXDIqF++&8da#xy40N*cG2mNieS;d3hmgs00V9Mipxzw8wpFA&dLor+IU9O zjjcsEeRt+A%wdhn{(B)IvxHurc*Z2a<_O&B`CFu+B>wbUGzw-1yvTYB%d)`7M1)hd z9+ z)mHu5JILZIWg^u3jb32jPVnDkXaAM|{(oq`|1dtb|H#t*vyqp9@gK1LpTqyE@i8zl zaWMaH6^xi>P-X3PB--dsEqhG2e+QX6aE#DlP5<^bBnUi6tG)oxze^U7Rc_OpEv|nM zU+weGMYC*P?FH4QN;5o5dnRdP8|WGgF|ez%k*S#hGJrUx)LDHa;My9y#=kSZyrS89 z>q_7^l}O>zUt8OzFBa%mU%bQL-`0+iB7YN00pkin-o6#Q&IxGE17ytubZrd)+uHi; zmo!iZ1VE7=9t+x^5t<+H3c^vOFcpN$qjODNqqBSX{gujpCL6bJW_EV+sf>ev3-HL$ z2+kRV9C*7*0L~6^I^YFBrmh`!Z2GfTdk#{gvz-I7uEEpOvjG4{TceLwmGDU#Kn{z| z${%bD_2>Yw0pLr4kstI7;Nved8nLB+YIDqGFG{Aq6q{T=G{hZgT`L1PM@LUa8<(cP zHh|qcVCI7)fC^dsVegpaFCjhP4<|MN7xbs!*0;%b7!lSeUrfNsi9R@4eo<>o5o+JU z2rh_xih`lTqoWZJ01nL$KG3yJzugNze0~hi+*Qn-*#*CU^uJE#H`RT;=l0CbHTL%Q zhPI8hUj?E|JlmaEjg5Ihq^msuM`tII4vAVLN+unqdn4*wl zJQMXcu6j$Z4ff8UqmrM4u88=bRE>ZwfGull>n?6@fOsZ=BNN-{4>155JF>Yv$rrvM zJC?Uk&VU?%R67&@FB@tBJ3sNB8h&_$zUg6{quWopVLu{bS6Ba#n0Bl_7-N&e@Tb;S zHioeWy|?OLT2@^E;Fi{VBk;QK`_I{|`ORPrf1K;?-_qZ8LscFQ4;v4RkzUE4I7LCA zE6_WWlM_ICC;NZz$GS%wK$jie&+oMutofrF?r&X+TN4QI+i%LvCdW6INnEd~|4l7u z0r*!d9qQfYQ6PY`AAAP^7F*W)X3+Pq$JQ_N`)}3*U)Pr&__rTZqC;!zuaev=-N3IH zymMXs>rd1@Yx|9@omM`K?(6T2msHL7XyN)Md*D)E4Xd9v4S=aDYs>F^w@q66_U7~c2WygFCBNO|<1Rr7 z&U8PTpEbs)R#*TnEx%oHD`_u*tv}u8Ca0!<*H5+~096#x+VwQZooY5;AJSFelbD!? zJ786!U-*x3mo|WENG~FrzsfydcpP$Hxk|eXj@LPs|%&)yc2G6}FuuG*&$H z*t5;`@1Vz{4WO%6C)tkco88T3bYtKTAO}EI>aV{Yh59$RV|RPqi)({#XW@@&*SPf$ z;I822H}C_X`t>j1?t}9iRu2vAC7*V8H3ik%t-jq>Yt$FsMe9=bzXuhae!#uCaMS$y zTAQ?g0X+b!e#tWrY3f${U^vb8d) zgCh5iqa^-G_>wzhm-2aL<2b-O@m{HHX4m$DD2I5um&muP6D>3MCV^W--Jy9)^^4p_ z&>cICk$mgH-pJ!FD;MHN%n!Xq((I?sMlN28ky%#Sv&cO(tTo~-0Lm{QvEsjjEuu|p zmVTG!(6&t!vqpZq6O<^-r~e``)_I(^da%<8A(0Mzs6xzXPWcvAi2)k#I?fBFs> z+YH4{@)sn_6tZ5ny{a&hji*%Oh_0I93UgKcz>5B^GyHfFr;(<~CU}>O4Sdigz}J|r z$IbFk&eSp{i~`+^u4Fr6We`lpg`KU9An6aO&Q}6gk}Y;^HpO&TT7mQf_AT+;Oy$E{ z50$ZP-Sj?t8{Xt>j=J z^D*bf!AhPK|1VW_ONj276|D<_^}`T%o)+A^va>Vk*i)k3gb z75U)JqLXmu5AaeG5G7Plol6(;8Z<}z3^|M@_iC7$&#>~vq<&4buSTT4>BK+L@CK7$ z_eFigmCk=XUt-OqoZSZpncZ86gm;(}^GAXiNOfKs7r3;fC-9EoaxbxQl5t}Bv|Gx* z41MJ+400&?%S!*qe5jtMWc>IZVd^KyJPz5`?C9Jpb)Lqvw`kftbul(xCR9v{iNdK? z&^9)qMz+~A8}L@o;L<=$ldw0^&7jZ^YKmMrwfjlE-3Gc9KJ0nd@0KaY2By` z>6>fX72_gf655Bibg!(88p-XAnU3Jy=r6rLCY}eow0AAt@u0#N02ZXUH9h&dio(GDQD zaJayG0^q>CGbRR(22x>m_?;m1K6ah{9F^Y663DTyoI0%DqevgmQ4e`xx}4a_;=!30 znHM%DTU>ZxF>KN=Za=Z*>ci-W1AVtGCQoX%Q(*GaJ1-ZyC1um%K`#%-mPrhcveLVd z>u78+mXhYgI{RGz0D5>S(r1h953jhH$w2Bf@7v7TniS_<`5^LL52B;EMf>1ltC?-B-vU=;g%&(S**Wu$}Qy-B232|9q+NM7hz_qC9Tt#SPdF7GMm)%v+jqd_V zYoK%5)OhgnSj>7IoRkOPls6PJkq-w6p1hz2p(9Th^JXSG(xA=hB_B+9=szroZG(A^ z!4#;*kUm58ZfZ>n#(6hOv3kn!!5=m_15b*1&C@p2k5j41uNgqCuM$`az_6 zv)*CiJbqlQk)2Dg3s;yd&ICHxIMsIcd0I4%A`n)ZcW`IxEydM82|jK9j!D{gaaG`U zbBa_QSyhd7Y1_!V+>S2}iVQ~v5&e>Ttq?g4ZR_qM+lBy&GNKqiuLE4LB?Gf*=^BH~ z03Ng4+T_Uqhe4w9t*edqUhJVXE+Qt*%bJ37>uqhQ99k!i265E$ntyz9T_p?YampU&TR}(+zRI{KctNYZ#+-q5Iq?-j>xbgrI^Q2r;OMI!zmr9QiH@+YHws?@ zYHo*HN8q`27Pu~xHK)6d0^n^G|HP zQ?pK4*dEuNQY%G7tRwNZu@gFce+M^nA=}&uXNG!pu^g5agItU1fM99iRn8=&=c*u9 z2isEu*CG(|@}z*u*eS%T=HUv6zP9tug@Ox4a@MmLAIQn3B{bqa&zOk6vt;sNjW(T< zzA!f8k)e$j;rNXcYXG&ig^5Z@=Ew(6&YEH=s?Jpl(qBn1#Rcu5)JyC$E#!9wHOTF(p>CqFEzFX3dEtwhjTnm_eKHgFBK|7|vssAVWr!q5 z!sk14*k3Zk1|L{TjR9pYDLfPYQ_uk)1qB#AH*n=pJ=oY0aT>inc1>{AoSoj{2N)%xH&Y7bZg278;K~AFW@QGPoT0;%DH}!Mi zG0XR4b4WxkeEmi*wLh^?;e-CdjPZ4XQClbd3XpqeX=@VUXt@-(898`IK`Rv4QW>d%xiZMEQksk-UD1MxicX6;h>Q3u9x6K}YO=+~Lrs48sZy_L$f+Bc`XFzeu z25ToDF%zGf)>({y~eaO4CLHIOJ;vkMYZNM?5*h(n`nmPlH1S#|hh60(S zh7jh@^m5oqC0KSIn@+iYbc8!(O%W_n3aIc&W+U1Jj;u06;z*pL6gxHx)1z$R-m#Ub zlXh1ylQx`q8C*b)1ZXGGDJQA=E5qTYM=b1wLNfiyEJI&)w=j(+d9NxWWu$ST;^n{3 z76UE%yDzJl63Gd=`ql89d_#gvz^&5u7A&UO(x_-&adX&M#67t0pTugi4nr@=-=2=z z8XeAKi`oU9a3Q!+)l(s19xDXFf|rIeNK#6n%-))QcKGFf;~0E->GVwh-8P+Sv4>tRLN2j_$-}S z5K9HJdhK-VsvcvoQ zO1>!YZS{P(&u-2x{Q4G@gI9fZDNqmOu0ft_EV=^7ndJ~sJ0$a`3z@tvf*)UFzZF|U zAwU@Tws*E^K&E)$3sHl-eq%%Qmyhl8B&!I%;?8THe3KA&JJx@19AcMX;jgQI?cL?> zNxlIz4H^o3hd0cUK71zafw{T~Nm*jw!F(-EKHo zccz=;&)hdzjIjKrTAzz+3^)AC$YM28)dAzC`I%eTD7#Xs|EKz0ozQ+PY!Xu>$=B(9 zkP$8#P7mEgS6w`I1|4!IH-6&9ZP^Eg5(9g#48=}*gs#%OEqw%lL#j0*U&zIZT!qlr z9ad2rrRYH`aiMxVGNav8MajaSDOdW?SYN4Y9hUdPPXoug;59Gcr^>$AT7*Gn_uPqO4ygBwEyk$Zbavj{ZR?^POBaBL})GW8m zwe=6e@&MeMdoaM)v%zYcv;QTiTY8u=Y06Hj@be-g0{R@hFbkMh?+^yMs?6fuzrFK> zxAC!IR20zNpdmeM)1WsaN@Im;yEY#ZE-MQFOPoC@6!-Nh&%c!{QNw zd@Hzlo>t4~^%1?$Y`_AQJ;$D$i_QdK-jJ3qjqx|2WAoq*Oj+;=LOpwn?&=nHB+OB_ z`7JpzlIrg;imh?HT0zGO`l&RdwEsx1W*4H&-!*yMZZmA>%Gcxm$P@BP?GUUNZz*6= zmSO82AqcC72oA{LHDTWRIAR{dFMz;~s5)I&QzFq+(};I?dp4YyS%?@#pIyKONL~+EuD`#;kC{c>&MAg2)EppFbhd%5FWMR}_|3xs`E+aun zFyxp0@GTZJ7DwF?0^I>)OkbyQ-HGh>7#76?vk>@-2}@w`mR6!~rlNSM3nhnT+2Oj~ zaZ5VT)Bwn*>6qMgyxwt>QEc*z5+X1+i@TnT?54kDZB zwHeRsssTsko#pzHCTRa&aHuqtlVxj6PV+6eXQpCV&9EE72J~qC>uMq)=XG&Eh03F_ zOjVta%x>Gado521f$DLQ7=8jIf(y=x!-Z=7#F)zqub~1tjy=s;Dcf+o{Ov5Au}Gf- z!v>t!LBBxHy+m6;B!%8)(fB!|uht{2rY&CeY)>ZE7JI7Ng!VZG1;msJrD7%Aascv| zJY8m3CF0W*((sF1BI0U-CzAs=(QId8=nxS~!U9j5QfHG>9UEV6w_JRt!j0qR9Tgfw zP~zJbe)6@3ZP5lhc|y?Hir0KBTAoxFKX+XUy1yctH~P9&wYL$BvckUO=O8l5W~yu~ z_x)&Ee>l@~Uax2B-=qa3KVm~aL)~|-<<4*6Wr2F6_?=J5h?JaNJdz|X_6SxG_O4TB zBu8tAc8z`y4gFNP#0Jg+pcwcVyE9O#O`m+WuNzC@c)89x>qK)W=jEcca>pI74x2}F z_isW){T#J(J@6aL25Z>fz=q=TC+#RykK1yVv6;?25wfiz-k&fnCAbvDdVud7K-dXE zmY<*IcK}HOz$-d|0_-SOMwoQFXROVj1F0sl=pk>zot=wJvKyjw^a^B8-r9FKF{x}_ z=v4*Q$Rh`qnj40saWn>4sR7!5An%iK?G=~Mf~X6S3r*LmY8&btGFB*1M}gF%pZ5E?EOWYI$AmDY5Nwja`R_lICE#Mmcm<^lk7j_#?c!UaJT zQxb2lUMpn~+J0?Y7B;YcRY$Z&Vi<(CcHi@svoMhsny{S|Fm^-)A0?q_l;-eje>pKn z7@k?5y};6=!Q3mEc}gq+T)NPceszkOrFn}Cd2BRf_L_rF*MP>du=uMU(h-WJ9tW-k z66Xwnxh0lR%qX#cP7MR5pO&J1RKzGg+O1wD$04>5CgQH^`3%!pIcYrQY8%Zglf_RH zqX0dFC8aTR)Q|TRHCG{<+wG$L82M#dw7juJ;*}vWO;%F_ptJ6HOsgcd6Mr_7rK0QC z8y9eYP>pP5Zu7mT#&{JJ(;c~Kzu~8$M3Jby2+bsRt+VO(N9kxbJX>`-C;N?69}uE8Hsh*XnE|CC!)*=}aH_E<0FLdx#jXxWSRSayzziXmvh( z&=Ab~=K@qDlI5?LUj(ppQldDq_h5qss9TXfmDqUC)l&jDOSqoky^Qk3_re)8% z*a9_>n;I~}uH=V{^|THA;JQfLohlP`(vBNJ2^#}Sar6& z!K!e_5Kd3mGT+^vaSMT(TYTPLpz7&r$0f{{i z+}Xlutn6trG}%a|VFL7?NI%m@|p+Qm2NtjDEVMqnCy3VtbDNZa7L_Gfqm>!fK# zxhYh*c6T_nDjOV_3#GEF3wYxVqNkIK1@*I_CCX863Gu6xG2hKcp&ntPD7rRhi+iC) zF}LI}OPFMuG3iE?FJW*aXwcs1yzz(wpF4-{qcn!8V@5*)ALh$^3-^zI0A0J$lVh_M zuJ8!MckBQnpkjmfD6ylMXn@_t@#f?ieb}wbD;cm8jPy&q`WAt(lz8`kIcqrczwWi& zn@pkiV|wb0gWGVTW9tTwcAf;Suu8n%a(w8f%<1N^Q08$2`z2NbfegNXv^VXF$u!^+WG@DxUq3WUuaL*4~p;{CnCXu)ft zs98CPuUisrVJ(*Cf;ZJobuRo!%)uC-midWDdMV;#6;}8hMz+Q>8Kc*k@pHe&b3V0} zY_Ak_&oI5RxlovNaLnq|ZOAjj?o#-?WQuQu!Ps2vfyQs+E+t_+oJHj(KhtspZHYv3 zO}~AXls=2FHMAy8*5Bqi!XsbU6JCa`d;T^nWZLD1a)VTjp&FAf<>L`($-xsm{NR{N2?HtB8pFe-^GJ0Plb(zJ1K~r!J^X0&9p2 zl@>5NWX@zjpV3zLZvungvTmfUrTIod9E z$LRk61z&T*$DMK6`{G@jb!h?(r^Xh68@0LXAS9P;qVU-(L>xVd=&Q#3_;bylatIPg z6*USmSjyC*sk;}Nt7#W)^7nZQz|VYv)>hN9I@^}EgVo*`Yy^kqE{K!umpsvSa497W ziW^pHj_09Re6Ir?Zg3`$#xs8ZU^*O1E=gYlZ{DNf6xg+a#7djGM3)1_lw-&IGo=_P zlWYI6kNStR`!=!fX4B+4C>ffz>W~R(ya$piFm2uLh5s13V%>M-kUpu#%SLH)cJ*!} z4|YAlRzqF}jr}sDEt3|0F4u*?W6*&DlZW6}q@4gh@$d#3kkOlH4*Lf8*Nb(Vhtb$O zX{Afy@V0+-da4ygN68N?axD5IUYyk1<0a*S9XMIVnVBw12jYDc1B=IfEB1S}P6B)p z76IYYtCVT{0|m&`#Lg{>#SJxC@8>K(OXAMUA;VII{ElZip|xr>-QFGS>^ZhD6q9(~ z6v=7i*cWeg*IKE00XS~Ua_$P}_l1bw29^7R?SUwMooSo4e`vEGJ5t+VIy-)wU&jf>!uw99_}R8P zxsfF5scs`qDg|cyW|b|+k9(ErqWMl2a3Uu9KnMo5)rcGG1q=GcL9#Lj#r)m(Goni&c~ujHkAcW_10}?Ez;1mH+mlX3r0|E z7||k_giyJYB(~+y(lh3xzM?3X))2Q6)hVsf1qg4ZcQu<~p|bq&TIE*-1VqbP;2iur zqAY$=d$UuJ5d3IEXc4e6W7-L`%Cvdo3S;;UeM1-~fN5rwcNmG z!TR|g=GoVA#Y`_ma}F`apaCX_$>VZw7-`Mql{ICJ=F1dMqrO?5AJWyMw`mMuv_A0q zG?=xdw%bShZzVxf_E5t>san5j9wj>a*SEXNDLN)Y3C}lg?*e7Sm8mc9U43}M2JZUA zEc8rWu70|yDv!yUg2@>N!5(Pp({Z_x5xjc?Q`|Boi@5zr{OHuSx4ccUd|QzXiT>px ztwYInzkH7VixHz{bRcS^&oT35v~5Ry)jE!7Ms#F%(J)(q zpc^^41H1)L_|BdiaC3$3lQUHaK>6rN3FPmCC-A4kZ$(l)q zorJZS9f)uJ+j%8&Qahy3aresE8b4D=f>BMynRZ0WXDP`l)mU>cv4hTUACB*3%ufGG z-h$V}aHn#!W6tQbEW5GEYc$;w}`Fsz_z) z(8Gc-Y5e1UWawmJVs1Tg4HsNX#;A z53$&qt=~u-L#~ILF=B5!JPR|A-+>ea6Tlyr8Fx~+xHXtdygB!37MycoENDwz zzMRAZBdUP{F`L14OhtA*V+0)?0d%4_&hJcjLe_cDilE+JVC#(Sw<@}ITs_i$aN`3i zFy@dh>j-kiZ8q9(4Ke+r+M@!2cQIdvJbEsa6j;lD&KRwpxS?<8&-MTG-+snA{1t{j`?jP%LOSbp8aE5>auf-HJWhmhPwk3Kyan^-R($d=D{^Fq$FJC!DoFW60l(Kb& zjYIu$0d+_`gS3QmOPZ{EFi7(4o0Y;nW%|B%g1H@|muO(kh!5L8^HBU7#Z1RVBDz93 z?WrHYC0F+*Jw*~VGFp6%R8iunfHZ>8l5Sv8td!OzV@MDs1t2QesjB=y;w53JSbCX4 z9fC&ORI1I=MsnTA_+GddBde0~QqRInYk#DhM2+FYhvaOS)Xx#Ww ztCY|tAlOPP#%GOQfr^o<71&HzA*UW@Y{J4Pdi7ItKoy;zt`%qh3aZVyA+U-c4v0zR z$0G1=OSDNxbg|;xq46e$F7QksL-YGH3l;MnnR??cR)+AK+b5w1kelM~>;~qCFN(E8 zw)*9g0dWGA&&Q$-o`AI&HR|1)0T|8hVw;dj=qlYtC%4u1-{t=}=j_;I%+KT4)g{ z)`}<2P%}H_3uT6qAq22{`jL?BG95})ul6qpQ-DJkiWLB{PhL1~QUb%ZR-96Hzh3@r z&mMvin%fX(Pfd5|xCxVyEGy>4jg%pVoo8j%Itvb-{bhb*LGEdfv?!Z^+w7)SxR;8i zxKz$>{}<{rwQ*C}_yN*>%B~PPS~+xDE5O1%LnXGj zXYy!ic}2ii60o*8tgj|B00|b2;9n|4X|*|d90CP^`?{diY5Yuwb~BRjZ5S!GGpfd% z^sE6u!pJR=g?Y$dW^Wkr@p=cX6r4tq4#W*}x5w`mTBAVCmGZI*(;mJTtqXPPGUQHPQ#$CL zJJ&J9Gn6i>$FoO|Vp>4a^p2K&_G~Q8%tNYJnFFjDmP$d5-%u}zquZ`>{@IDUoQ%zW zCya}LnRP3o3`-6G#R0)#(V@3KFSxToG=hEg`A1K-M(VqY!0I?8w38jvly6K+Ahc}9)4?hS3lW>Ie{8Qg%PC$qE zGU#VuKrne#ruZdKo8o2-I*}rPU?(sLa|t3}GnM4b^T*Z=|)K_4t zcQ2tTOomZ7@|@&N^flcZ8&U|P@4??dFY>2c-qpL%`BrL9%~y~;1^IAhyXrsE=Zq*_ zO=MDGR50NaM-f;q+-QE+-(J3ct|)R6E%prhlq~ZPmq%d}3R5DkM-!ZsY5=)2uHiu? z$r7A*XA~V;?>TbqiI8XL5^?W@5VVx*Cvl;Oikxh)?f~%jFFgJ+mSv^)tJ?jO<*7#^ z6^LzkW#jRYE1DBw7hQxpJj|r?_gN&a7tEmAXzVSf^vgvE?DTrW>S}s09YXumI5Rrc z#Mqaii4|i(_5Ne9z7{KXg*G0K5=W&rfwc7Q@=AF` z4`aOr#;Mh!gOO$<9CzZxIh0g7>P%h0Vm!fMr#1+|Ns(E|*K)3O*=iZLWwjm4GpzV; zg3fP0X;_$4&&_Tu+od@2TXN8M@w~x^7)s5TA(MCAoBUval99e^6-@hTzKSi*hz8yW zyuXr&F!P@_Zk-S+$r%H8`9>5~P7@j2&Az873*PZWK8L(}Xm6%Cu!kuCAa3vAxH|X! z9|+I^^bUnRQs z1+%a7SN#`xr_;FM6Fl8sPx`dEma~)Y!)S-95gL9%Sw=n30C`~>_BTmOpfkgvekz% z&=bp?uC$h$hh3CLPuJ`P(RB41XX=WgdI;>&ovs*IGA7hvfomhtjs7l@1|hyy>7Xwr z6zk&{`~NJweK(oexp&bu!M3;1NH#A48TC>@8hRFa>E+PI@6xLNLQae9weXt@8-W^B zK*xEqv)Bkj5KJm3_^5{Eag^>tKY8a~eg(1a@(_gswMocCqJgMhda6|^&VHwZ`wgWG zw~(>M2}EvZ|C6Oa_KBF&VfNae@G>Qe79xg;@fLl)H%`aaR~Da%PU$N}xdENJP$)Cl zWwwpnD9KTsCl6~bkS(DQ3S?E`@M!X$6um&E;#Jovr4{1h**fwF-s~y{uUW0oDq>0+ zU#44cT8K&!oc~A!_IIDs51Gh}q1FUM7StPr>MQ7zPcHbOXy+!I@P%67XJ@67l3uAF zynr-v;-4KMQFO;7FXDbJP@-EGh4>k0W{VDaL3N@}`Cwu0lBH1V)gfyI<&;bz@fan) zlnrC$hQaz}DLpf8nl4BvC*m~{6NXwHOw^0`^F80)9jgX#ouD;!_2;i8)e`#K;~ywV zIb{33R;X`+LhhR}Ht&QzpKq|sGI%J+7b{R?UVoo#o2-TO`_$0Zz60Nc^OwM5P{kzI zUw;WYw}Pn$Ea|g-Dk!5VExTd+sf&4{(ZzKcQ6T!c>i;VtnHeW#G6{}kHn-%Iy9+fR zn;&N=AL^lnZAQftiz)%)PtJkckOCxJM5OqvUgRu@I8bvJ{q`G%fcoQO=sS3lcJ0bR zvRU8e*c`^A&jrR9@p(ud&{+8!zepy*u29E#23%Px42Y#TLk%C<>-qxewLS7LQ z9@4PgJNfV!_oj3L4rFZ;gjbTdvcKa^xNR7}q{H2>;5|+jCwicFzP~$5$PjT4qmeb1 zxmbP= zA{C%p5Mu45hE}N5%Hv4sxy>K{1CZek#015YHOeK#l^H+!moyWd$xUD4 z_a*rtz%So5%T0!)t6<{bHjRaZ=7cIn6f{#X=4d{P^!Mk5r>PvggmjC&jNURvhNQ{BTYA3P$ER@~UtM%-Ogrgj3kd6=5Zg<`_ zh=Nu_2I-*~DX>%B;B@k5ZHmf z3SO)GQ$3mO*}IXq4PCt^A5KzHccJo96@xuCTt6w@quh^?LwomRM-veEt&!#KWC zPj3ZK+_hPV(ocpe1ws0zSng}DTyY`d?#)$uHs5bz`6hi8*1wu*OoY=g0YlV;2WsL+ z#h~Uu>F=(r80rwsI@L4c;gspl-b9h+-*?>+tof>3(ek51gw>*E2%&vbh(vL8IR|E= z-N|qQQ`*%lClfSE{mq&k@z;J9w22>Tdl^FPm zQ2C^=w*-HbReEI#Ulq1rlYWhBhmgXP-MDS~@ra7e{C=?{#!UhsgMB;QZ#s=_xEbR7 zZ4BGL1z<`79`UPP9j=hJGesB8pnc@pG<xGMVftq{z=)J-aWP$w0u-qz&YJ+5;EzUfq`aMuroy@Zbu&g$Z^+bvgps+=}wmIc^ZaV zm8emBkKxdun80HVMDFw56YOBD-2zaE;?^<+dn`4Q64;EK;AoF7Ht+fP{z#;@3wn1M z->c~8g!0#Kn&I!Yh)eh)CfQIGq27s>hf$*rr~Qx?Tb#AbN)G<~ zwiAyb8I1w9b>JX=t2UWG9h`40iX$tc zYa2>n9hw|Dhdju}BrLi#kMYEGn1@+eDA5e)LIg9-1F@a2p39{8YooU_$hi*CsZqb9 zI4QaK?F*g!UCxyLA9KE8wcOqZJUp{ zsY0KHcSJ4JpgyyzXY&AS$(PB@VOZ)BR8W=txw~aGyg{DrkV2XgN*lwDPCc)q18$}r zUkbrhVf7muu@J*__xe^(8vw`rHI#M??J{9vcg0jo3yO_2IVuL%_s9mT$YZB-aR$k` z^q*Tets&@o=!5!Yj6XLW>lwhWsu3%Ouk67xdf%I5eAiI&6K)9(j92sdWan$*iR)Uo zJQ^9_br!P-k7U@ge_7x;n|`<;K$y(Um-}O$K7{=bsOb}@7MDBIqr`PAlR}9nuD%Ac zMl2U-FG(%G3THb(Q&FwhGTshVtGJ4rw8Wi}I=WY0;QoCy(L|kzV!qcb5@PH6+`c9b zXA?Qsk$|NZ(4V{5l0_G+;dvWQi9Y7vf$?3_m`h7^;k`Z|iwaHQc?>2enTH6_sK(>_ln(;1MDAp)%B0;){E$w`M^fD;{_dNWM&hsQG-&RE z^6Q5{ESmerCx}6h0^}bQn$TAEbjBdG0cn^sPN_%P9v=jW)yJxy*z%M;-d3G#kTYG~ zJ%{@HbS|SKP3_^A62KQWtHVztS=nlJ#lGBGDqrI|s8*rSVtpp?Xu71k&G1WR4V(%M zj$q=Z`E%)%GobC*V7_QaS7<4{KE0|523M!i&<8Q;d1rzNUKyaA%2N@&GPqBMt^OSD=V%WJR#;7T9>3K-UL&@e%m)g8~E&E5KG{PT?7XEqG? zPko4Z@R0}?=NL$2sFvao&{3R;yLA2|LM<&GKsNvd=KAv9RRn48u1jM1?HzqY0~>%o_G#bI+vtznzvrJoTU~`9 zH|EAnd3P4i`Ti0cO zcl)AK9minKuAWCdb?+XTx6AUXtQMd>Ntl(D=fJMMwfj6i7^hJAS??Y6)1e8@F@SvY z$zJ!TzuMN1-SGMbW+7})XDff=!9Q#()8W^+F{A@9=i%-S0+J6@Ko>xPo|=2k-iz1X z{0yJ`*8b5K{HJFI!aQKw7g@nS4fg2=e06ns0T{|bxI_5c_xJqGK6r8xx-L|+9gsjl z8w2N+|LWDOY+C>A=OLbfK7ety`^5v0r%H0l?!uSQJ1={$F3`SGLd;^0N~r=l6(e&=vt8zPF+qf3cV9 zvy|3G1d;11m0N1e>?CuxV7w+5I(iAaf<@ZwAt+7iV7_+VVus00C z8Fa8KZ$*oNow~EP=^<73_cexd;Qts2sIOiNf%Z<0_uuh%zl}6GxA<{tUIV`l19xtx z{qf5IT7@)z^%#0e0|BH-78bBye?*&s-6 zZa+~FfdXj!Gk=7L0OFQ==Wo3PR(=Dz01%$==z<*XLsV1AQ$uFh9Ektnh%k8kgxT%-C{F9W>w&pyw>_$iKHWGk8 znJvMguIQk<8v<4PBtXyViPmn!lIDgDn)h1Rt3y@reW@~y<5uDuBdM@VXMm6A(loOY$V_l)lOg7zVa&+RsPk=kat_WbN$RL@d%);O^<=i?a26=Iaem{?wB2>n>ija8 z4QdymJUSql1$d5YYSY?Oy$knN4~)zKUS6>|#>RRNJlQv=4FC82ro_gq>fsTg`9&FL zr^SG5{d)^jj_6E>Uk2klNYnNi7Im*1$fM8hRfQ$&LMB6nXW;u$gCOS*fWqb57{)t; zB=oM|u?5OPa}o8IqPmxeGCDoP;%Kf`)O~iXuNy1X&%t%3U}fm*H?zjLMWvOorE$W6 z*nCuq(p}bTEd@+9e>)$$n6cUp4UIwha<_zvZE##Ww@aEmc>4UNGeU7)Sbl3Kq#Gu| zIo$ApI!yS?ge(TXFa^XronmWSyl#{c5Jq09;f^04*!-E=E~9kQ{6D{Vp}!t7T(6!< zwGG`5CvR+z)`y3~vZ-9t45q0TLw-nFw_Ef_K%lUTrg4k3V3->!{2;>ZdF>|YeRrN@ z{$+-Ki6t;DAxSZmi;O-Ns`EDr{h821jZl9rjVB4v>ecM4ibMHY1bYYQ>+n|}9aKvU z?BxgtW#8aOTZ+2*^D#3Y{8FvTt}kJid@@-t3Rq9WWLnk=aac(`!>E+sTtaR7S z$n(NB;d;|$cN{$kI(dzu>7}>X)Jn_qk={`o^fYX@%A#x;dLt#rnxerSUP2l)g#no; zdBJTef`TeGwsT4xOGh|5px%`4@*Jh$(C*!<>%1d0%QR(Aa}y}(8nOZ!KQ~svz@PWO zj#l$(8r~;k?(Ba1Iax-9F1Whn%X_wZ{z`ikVz-q)d9iyPB{Tm` zN+7xBru;fF^(D2Yu0w>&2=~$k5?c+mNfLH5DtZp`@zI6O2iKxs9I>rG@-c5cP>J;& zk=Bh_arF}=^h{Xyaw%Z0hUzdYR&|s;4gsJg(1b2>NKlX$#rm6z^Ahc{Q^U!3Qv3Ih zLuFU7BST}xJcrDsz}&;-AGAB}31d5>iOWSJ-V%|P=Ym>>PC0_yA@~s02P@hp^B7WP z+w+$5sS8FeFZ~&J`ae|$q(ud2Kqlh1G!b-^$eZM~i1HTh;-MdY3qaG>b9l|BlLgg7 z_bfuC5=fX5>bkL)6$WZ#JIi9nOeWs0Uk#1-8wdCCZive#C6afnXkuf!^sy($hr!Vb zrI0sfq{xs+-rE60HUsM=yj+(K4HpdG8RvdcI^!_jVgs9ofms_=5*OH3Kqc6b8rZ@? z0_sinf5OJkV~LWdO+=g7Og1^sw;fD>oh!J$~+w^wa*J5GH-1o>3LbM z9_AW;Zgh(vc1Cl)l4KtocZY8it#h@P>l8PSfG2QTqdZ)xHtxJn5UZ;P)4)ttnEz}+ zBVSN-^1Tc7!9}|Ka;Gyt2$3Ghr@mTV3?FQUaKGckHJ#ldhXD2VXOAkJjxjsUI;u-xrj*DP2DV)iEz+Ytbcrmi#^m6--X1fYt{kLwdgyj;UG}M$k(BKzNBnw=Y#dSh_5+U=_LcjGYs?9wA*c@*eUn9H%G`lN_GgT?JB zt2!tC7<;>~NV@I^i4;bkXkXNoZuy2_{l?)e_=u_IRFTdPw~96+9JV*Itx53rS0gqg z&2PYwK{CvEICX55F62qAa4RqF3wSzwz8iC9 z=gZyqqZNd_Yr~hx{>RZNE}~bWB4=FOFG+Px2OY)>yxG2zB%3M?l(C+q8JZf4S#qS!pbP1msD?h!NFOXXxW z5`pDY3b$6+0+MJ~7<&pol+0%>`!4zIcDN0NeA@i=woH=fk*64D{a(d#;U)x8vUO-? z%E_5A>6g~fO_{1W^N$qNu0~s4J*pO3Y3vuCuLLqbxR}rhziz9de)Y5oSly7yV*y9t z41dd4ok=qQj-~Mj1Ls{T=*$G8=khzQ+tT(stMZh1HI(i->p=LyFyq=t_3sliRZ1(F zBVg*kWE{ev;XG1N`5Stc4o{#~LsG=c;_HJG2is|)WT0Su{!n|r!twSNf7-EVM9 zZ>>FFzIe3u(pyh2%I#T^2xHs5agPjxD=u3EoU;5yVWm;`-P(Y=cXg5RF6^Z}1iHjw z@=AmS(8mcg^Tb2pE2n@HmY2HFHLvzC1>P-J!vVEBgE<`gtA%J+fY)9efmHj;{KxCn zErWj3ttc$Nq|{H|khahLa5jE~jDGE~675yD<#PyYmd5Ht(x4?CY@=<0m;?g=!RQWm+5Y1OP7mCS<~YJ-xFr3=Zzt7iYqK*hN%=G*{OH=r)tp8j?*`w&=`q<@B?+TD2hkqtNg%LQ&hO7 zvWd7vTTNhyn(j*ny^|K2HECzay1z0I_TP#7qPAvwUyWW<_&&u?DKQ@gOAVjy-9SJS zh9TM!W#USLjNeVQ4uS`31+9t8WIc$7LK6eAwYeNuX4`7$>4R~Bj^FO~&&|hv=lOV@ z?mlxS1Lr9?zh1w6rdIE~;$nk?f%N!jN0035ZEmE+-&VhG;u9shbLroY*v(uPM5!(F z&NJ%4301*iC*eMXmsOPM+{{m+xl3{R0u-;Ioq|zKKNA1go*>69!YtKE0f#$@k$2A* z=w_F(r8C;(u5G{ZK&Mwokzr5{f*Z$|zi834m1~ z9rw!b?d!>dscVew#lEF~%C+8+KUJA4e8q$st4@OwA_;;7g#aI+mvPqj7g9>Ai+tD7 z_g-^or07%Kh7%6uV))mMT)d5@1?T9Shjp&~Caj!BF8f*4eg|wN57e>&}DNB11rc6T-`D zKq_FF8~ye1kq~r*eUl4D^u`XcuRWrkV~Q-+?7MQ+qa`B%UQGa~$=iH2q%vX+aKsT+fEaCv(X$ z9m+Gpo;ylij~zEr6uP8QNcf`jHhw)h?Ym4KqP+C~J`8}Co!k3tm+%{xY0H>ScufkR zXogB6iDbV9ir$HAT>l}NpNl~`L3w^`Q&?Jje&Ibu@BAp{zvRXHeJY;*2N8N{n6`df z{URA0l+Mj&q2rD$ZDMnGpxaFv$sSxZ&^ zkOj!8NR{}rSQhj`!sS^yKZx#q`F>9a8OvW3vUTn=5adw~DCKhx&X4!n4Y8$xtW&aZ z9O$nmXH~Q!7T_2gLtf|(i&ZLKcaz5*X4SX1NMxqLK2;Xe00#VzC3rqskASJVeg12} z0lgu{jKj&A@(FXl0Ch|^4tOeBs4}j5`BtQLZ3M9>1@*A*5uy8 ztXkvpH3J~Aa;+A7Rl0sH&}Sk@h%c_XA@mfP%d1%okKohKO+^6#ew%lF{s9A&TalI( zsP5ioH1myG&m}#YEH^)CvSa#QO%0vTcRb34NVmyX{8_&_j@97XZRq4Bmtk9yh~0>C z&sl+ zn;vY%1WV77pBP^D+;4r2usTb_EkNe1M3H|zx>%x6!xb#Ks4|B#l8|fT#+oH1Pv0fJ zgoV~BS?OOO&6S5PjU5CexoO5Vi;VCBSBRqcUNH9XpvL&!W`M{XO1or7EnBrYtFyUR z(J3x<7U<)oODjT^&$%nWTr_WT>>dKS=ZmHQ^;s|GyrYq4HL1z1#4*(K4Tclu)KVg> z$X|>74&&4VQG&*+S1L%R4B_dl}n>uPKt;{STwCa+=e|?pSVMlckT+?E0 zoLt^6Qetxv#=jh)T|E*YPVqM7S{TTTgRxrQKiqlW zLeJG-t(H`a*UyKGSjtR8^*G}|zYIUH*2%(cBT%g8`-ZKy?@N@VG2O$#H+Gp#z3=#i zt}zhi`1LXSs)X4aBfG`uYoINY3=boN)jd$Tw&1g)Q5h3D+_E>$K*XUI@^UvHOkjp~ z^F=tufiLRHes4jegAU8Yn)Y!uSSzlE^oQKxtP$F;0Ks6Zi#Lxn?M!(y%>yiy4F%j< zIQR4{PYzx2E6sKLHAAlCsHFV&;aKonoP;yraQdWn(2l*JrT>g`YS95zy}}%dSp(JJ zD)&3J+*=&q;SOsHrSMuWlmfGQcz)AYck@=?wZ=2M?4?M=V)nVyZ;Hiodxt6=NqJo9I*D4JQwfGO?Nt+v%#%2Qb;4bZxOS;M|vv_G_M=PAFy$A zD$bn98Q4z`-GsZ6v4HL>w7u?wE6sG2bXG{fv3opP6mtX*^3WqE+1n% z6=aA3Q!(lMBHKvlh#x4ZeF-#opTWFiC>*H>h36IHa^ST3K@Jzp)o4Iw@LdK(JN-QX zg){Y6wWXv-SJ~|Rvk{y}Aa>>`w3}sqVR<~iEp15f#Yc_Fm$ssA2pf0k6tT+7cs=kMe0&V#-!&Vd2Yh7~pxi;(p`c#x6^)hPC<| z3{*6rzKe%Lk(Gu`(D)MT#XzPv0S6L2k;#GSQcXguQ-X`NX@_~>g?|Z>k-@!ek9Og4 zQrc*HI)Og|HAS5)w99)Y{|Wqo*Lmx zA!}M?Vf3{Y+pl($6-0Es)kWWW1)IH+1>ikFmw1w=fZWH4SY|ml*!cJj9NN2*W*=4S zeZ4iGB_ja_&kTP=eUIqXVE$d?r=`?(7qD5#9{s=)b^K)&^`b28zQRdW*}sjN1({QU z3xbnEn)f0fN|QZMv-%NJFovm9}Fg9 zQ}ymWJ4c^;x>2*Knvo=;sPu*RKIMazsLXc&ICWOQwYSd%*gdWY)L_>q$t3{TYu z7VqKBZc6pfS8|a|N*(3;jS%fE5?mb-rx!;*A)?CHH{vAyGjLFMf2T8&8}VtF;sHqH z2`rnntcrS>aW2?AU$x!@6S)CM)m-{gTzI#`EsCCAr12reDuPy2MwvtI$=&Hw9p6EH zGU{|!#RW`bxW`=j}t@Vd+3E(yYeQelhL3`Z&tydlu8N-UnnK5jS!L9~)~|D#izld6&9dnQ&k* zeG=?)dd6c&`pjd$Fgm0VB0Y}wkf&6O7SxFDR8)9=m*5asDk_G~zDN0`0H%V*A^Yu9 zPTFEpP1W@NvP;u>SjY0LJm=JyF#}feJvIyhX9%S%Tbhla+gVL#@SW7Q{7>#yIRDcl zSUud^T({FG_r>Y?{rE z13{xD-T~_V9rCEbL?b_C%wXlEl(qN1Pw-+?+QRN~oyWKGy{n^q2K;wEQ&Eh}DTGpy z)K%l22UTd@C35GT6E~!_>g)7^cp*~kOCZZFE>>yZ;C(B7`WRyVQa4fA$(^07xm^G9 zVXodd1_C3+VSQmpVutKei3K3$Crt6m++nm-u0}KCZGo(H84X|ThH_gi%LAE)b&N-ROzeQ;v)jaS}hN0xjt&G)GYT>k)rkljX80QUABvU68 zYi1zz zDCX_BVv2a?#6dLIAAeR>$%E+7URsg#5QnfT(=bJr(v_5RW(Z~6m+1@bjxWd>&~FGB z`zJwvx;lTsmnk(a{(HcNiQ#`8uwnV@gMwKnr(UY%m?ZJ+7BqJf8bN4d^#F<>p@PLPkorvO!0nV&}i0SXW>^dnFR zkIUYM2y_ActtK~N2OLC1DC=DECrH{iKtQTi1|*ypz%Aq6`!QAz$YT&tkdac*fr0>m z0Q{5S51j8n82~kgYy>~I555)F5ri0gHKC9Ok8^MqEOPt!iqvO03W|`FgmU_Q45#1% zJV@w9;2r=6aSq}pd}{&j1d1VaO<+(o%P-_G!9f_$KnVy)Pfza`haHFy<(_nS0O}za zCkFt`00i?2vI*>$0y78N{^vJoM1Bm8!6}fy4;v;QPJ$i*2S$KehtSQy9c1IUzLOUN zPT&@fVQC5MtiSK3w|}D-uq%K+3>e`E{Y$-#e}^AfaLb=F=;|uZjv=lSerOwU55N%= z_-U!>J$^?*4`6KjhaBN3BB0<~Foz(VdJGNrEtv}w)mdBv+h>D-c66cG#rAvcUZ3J8h1e5DLHxKtT6(7Kopn!4WX~9hTC@A0y0yjw?+7*N&`Ioy(6V}z8w%98^ z+&!2E!2A<32!KD|ua;&3rWw4e`|~^dmwF_qifU9d3arOZ(ieSU0@4!p-Xu8<$R08h zC=kdWA|wFEr-9#GN4x+6|A#kteOY&KiaqnX-1h?bi`y*T-?)Is+2DVnB}^Igh!Q%C zzIXc)exL}T>pA|wU-O<{r}y9aFY~0|_40iH3;r^z!X3aj}e02fPa2Xh2_(;p+B$$^V;7xL4@+e;od9b`Ar$T%6`(r zDmrnOeomht|3&}`IB<-GA#D3JkwD#{io}-lu6?3+0s?*AD3EM`2Gp$M?*W7$|JXEf zAQ0reC_if>fkIe(OA8@u031O%1AT{y!4L#|k^T@vcaA!6a82t!36{RKeq9Oy{9B=J z!HdcY+~)|V9dRv}%!EDhMASYewHIm6P6dW?FHvgk8!oYV8OhG2 zH3_4dHv^@@yUSiD>U>1xK2uiMF;gw~%IxH=WC=dQ)LnT${}%E@U(Qv2N)@EC>T z9S}#?xZbeqlHWfSmp@rY!-A?MWPbcjvaN-cB{bTZ8G;KYr;&gS!)|>RvQObBwO#af zj{Ve(u|$h5%$m(6Tr-f!-4)|0AK>68W8N6MBH-JvJ{>KyXrUzP$#@0|i2app>C`0e z@#+`t*^>L#m2%~Ew!5EB@zl>%a<6@s&jyMX0xUapDt?A8?f7^V$IQ(0yd6)6^=cUz5JB zxW8a8FBAv7cl*&9(uQYR$BTENp| zAtCnOLJO5qk|0<;FNdg^xo-s`HPG7t?#6j=}8?nSaAT)4v@(B6L; zj!Qi4dnTJp&Ovw39hE`g^f4jW<(eIoVc*>DP?TD0lq3@9!-Vi^edi?gmX!%yA5IIi zj(yxdDU*K$?#zsIWHJvH6s7f8Ry}CHhu9BVnAQn={KnDs8(U+8anH};8cikBXt}D= z?QQJyR@`5bF=Qgp=s$Ac_F3`L8kqbGhjnbH#=Sa0xYmOCRD{n+9YRRZ>u=Ygahp7b z&w6TbR^zzU?)i5{bEhTGSmg;VKVK@;=H3le>x?lW?Mm}(#id`qo#Jw3!<22xuaRrm z^-lV|-Oz9ZPLIC1m|+}qnZ<=BT*$QsOXh^&vdDi>>a2U}X~QU~0nVHzGU`%yR6$G| zJlpo|9NLz~EpVaL%4$wWMBa$$p)!EpI3 zm-IClw6V%_x*TU%Fv6h__S#9bbc=U@OiB``JEf`$rcRIyUBx{$Ik9NSN}UB?qG_W4 zEW8kf%tl8@mWmd8sMGP3->h2>JI=~VKIZXl^)pA7mk4aT0dCPQ;OjqKBm;Xstw&Tt zj#%k6MOnl<22TX>%jJ-biP>;Au}oZXTYr17&73S;c{TLe`5uj!Nv06C53C|*^}4Ns z7V$m>+uiVNpA7;F?#2oxxv1Q{$Ip^EFPr(;MsI{|;y4WU_)OM5MK9rPo`j!W5aF;) z#_M3xXm)UH+iD~w!WU#|`kE&FdIEGEpB!Swk6QghtgxhQzn0N>aUpv27 zrw{Ry@Z+@e8LMGzO;F)^?EQh!bZWc1EzrQ1J*j|9>|jVDllJe z!P$};*%8Gt&sxOlIHG1pq>j^9{1#e=?PvqTF|56#518I*{=K*qp(R2WMGP@NE>>!& z1z6#4AV2Tl01~{K7Ozf0;le(;HylDRv<&SaDBeL66}vkoRsNl4WL%-JE>77#>0l+? zkKc-Q=a0%OY!KaoNt(V5rSpjZD!uKea9n4K62}lA{p0$Fv*1GrKBU;fDdP;>WNKO5 z7j)L{N`}SKx^9T0dY`MxJbp~!v#)RO-D&%pfl!(o!s1=z=uXTn_MVsLu(@>Bra2My z6&tqtT&q`HJa?M7n*#gHr6m{o(TV*@#53aKF%?}pWvhDJ7!|m=n}{4R)86c3)c9{V z!ow;Q*o{`^l0s}(On)XW8U^Yl6h;IHUK<6e*pqJO&4ec@U7GE<&pbnH_4(k-OOZwC z6TFVmX1;&fMPhvCxj}Z_xA1nQ6!n)k91i~sgiE40jbTMvFPSg9s;e%;2WCM9 z+TDVd_VGcdO>!&SBs z(n`>#b=Nhp-SZ!Ok6Rjs1Hay+C5|b`5lY=}0w?I(St$AY8 zu-rwfU`j>4PIE^&tqys~!%O*jXn3ba_Mblm5j5k4T@{M4$fb{nyTU0LS|wZ8pWDG$ zIxr63iEm(HzVnHv@=+Ex&EKF$Vj{W}ZWeN;&)rbZHN)ki{vun2sZ#Gl+7>pl)!zbq z`T72LH8oDl9r-ikBqsI`FHt&Bke<6?i{Y#X&9?(vxmmaAZl`57k~SiZxKW?DM-43H zqO@>u;;j0MwlfywlG^-)O{?E0YfpiZX&;e^{q*@oZ$OjE%H%TnB!W7qZ~nRG5bZuf`o79u4cD1#SeM^nJR1Om>^|p~lV!_@3uFve(;e2;4g{ZR1<-@igFU?9C%n6$<`t0poN-CYlizP9VA*)M%E&d zC;m1uf)*U~O0iNa;sckU@i~H2ES|YqSJUhcCSj0# zHP)MM%n{|c3_#nd!O%=SI5-#Sjh?m&YfJ(_JkgB`dv^T8zB)pBwS{i<6w8OtMpaEu zK20(PV^_@^ZWv_9sSf7$Z0qGpEbK{O3LRHb@Og~fF3V2_a6K~IE&Le{`?!L0s_-i` zAZ{OzHKFa{9ds^352lZX-@AG7l>M?PDAEcnWRXatPCqV_S6e`iBO?sZNNe@2 zQ5UKZ;&7o&VjG8>Uil8UzjoG`YU-{TduwsM$T(0Qa_uUj_K69N1q7JW32?qedD$RL zQjIJENY`-%T$R5ChknjhG`J(BTvDxQ86dv4CZDD~$}Y_v<&WZ>3Ql2Lleo0@@cTCh z#qKL(N+T0h({HhUg(bOb!~wHmrmL#RC>7d?@2|mCDSOYuN}gF!SWc*W(dpoWkI%>p z%cZ%W{HVcio#|%w55D$unrb+Lgf<8*Klkm7i|X6qW}sA;BqEsrW?DB9S|a8U<$47d zo2iyHo%7Igu}ii#_SpexBoR!RYaHlsU{z5el$E?p`m#8;)i_j#bv<48S5bC+Zax3J z70L3mooU!gCOGz5=*RTJ60RCAi_+E*sv#|_rv3O-&#KqLNqox@=$ zJ};U9a(VpyYGgE|mNyf}N(R&Ji0;lTm>I19!Pq$kX%e;Rwrm?+wyiGPwyVqjx@_CF zZQHhO+qS09#rb2-iMg14mANA_Z!>bQ_gPQ8JT}TpH=>nEiH1;C77q&h{IhLGjpRwk zqU(6j$C5TX_du_WyJGVF;HH{^)M5&DkV5j}u&*k*|D6ZQ{GdDxg5K6I;#%y7%4SPr zyrdUcR6X#ii5!5nkI+BYu$DG?Qy=K;4;)*3ISF_ye`q@*$6%sey{8V(4EiS4RvDh@7fD5aq=TF-Qhz zbd*rl>=+~N!j}0mvS^R6L~|B?*DFdCC?oF=u|Gb z+7VxQcv>$K-zU;m(%jhSl-cfWgRP<1hDcq0ji;(6j_KEqJ>SE3aAzx z_N0@<9~w^zJ}g}DIS$&QV(r^)#b&i ziFZ4~k*B)9XN^*`fB6QUBeYEg01e=pYF54Bx-C68(Y;sFM!RPZjGo+zTML0%W8@fu zb(R?P<6&*+Pe#E~^Z480v@+S;@A+bugo`9e4x@N|b`;eKuR(g;hwGRrz=D z&Fs}S3JOJf*cukb&VO6>JlN@opyW^VwOKEtk^8DA2K>)^7uj8zYz4;=}=^1mGQBmd%0_* zQY&82Jgi&R-*bA}b)2dUTtxAJSp=Hsk}8?%dCn$Kawqlvi~$g_VQD=f}CQz)!R#8yHA!V-KtWx0s=m`A~=HhYum zc;&~Yt=dFeeW4Kv1`%N<&PP4AkmYJyOt$=jVpAZ&FVH7|!C z$VTF$I&ovu4<1nzdZj}0WF3b`>Vk2<=x zi6dK3$i!~APR<#e)`BLEs4>`Q(zWK4D^<;n@M$O7J5!4}*V`Cwz9WA(4z~^SWo&`E z*y^EMN2xEcz5V1RuKN{iJL6s0zLZmTh_0}k6jM`#VwQIO)a&N20YR~S1~QQBz>ytk z0`2n)M_D(TKF^Z4w(6FywX<&%<*^LUU?I7aRoo3WTT4xTV>sTLEe({|e9Y7JM)ikt zUZLT_CD?*|{lBztjlO9aTyjzDuY^%Gl^)ICnV--w)Hpl}JTLXz-5?P%Pm=RTgyI}a z3p1@=MWSZ%joPnAel^E$?m72MFHCujbp49jrQ z++TEiSfDGcOBLpSvgpHQ2uP;g$DLsKTP26JS|6h~Ent)mvcPeeKWJO?_z3y82=$Z< zrQ353a7^~D=j&v?HbYhri7GQeF3|Az$0X#p;)4>3^3Pp{4n*!W(_=QO^`dz~*NMRu zMvfp~i4N1tD0rX7+O%)1d7$#fuwF$DdC%zq2m3o>c8(nHQT^LDv8;Yik6pq84`h}3J16)e1b zFaN@4bWu9!oksU&D%wV9uXJ80Jt`-*dMBDsQCud<<}t(eE)h-?pFH=HI{5|@`OC-` zrG-;?ZP&}EQ2AxYSKE2IC>5+ilds{yX{wd@;UpvHI)N$=z49ZvG`%_UjV?b*PYm=j z=16n3HOlO~$I8oz{ z8q8KXwTk+q;W&Yp?$mXJf_YpZ1(%e8NNR=6+?c!_hil0dkvRelZWW`;md_7%;Q<$M zZ9uldSBUHS=azWROMsPR2!sW%C$QT+ccUzIQ091|gb3a3J+}>#w;}}~vHIBnKm4^P zoRjKypbjhOy;)cu-ltW;-q;OCuU=h#Ja$QRHi%&`e}?Lg7Nd$JULO$iWd(wC<&AGf z&KL7OPL}&_TLnqltVr_$UBi04){+O--m#b?wZ1g!ycGsJEZlxENWV7e1oxiPh+<(a zB3(+9w2!yNIAo5{*y@3&pE%AH=C04-g{Eb}SZVMGI3XQ7hze`>!8SW&={qgauUv(U z=ra2t)2hNsx?c=Qd6_Q;+~S2$Tsnc0+Z6QN@l53jBt)(%bhqCWsL|iKXmo-i zf2QSb;~S2l_0ZRi&n&f!qr~M8BqjJ0w1kyG>I9b`zj80hg>-MT{a7UvM$h#1OE^_J zA?f^`o<*#|-GXxz=}3_zs( zmP)>CB}jN_YCY364HkHy&2LOYB8HuOSbz_ShWAI!fU6DAK3w33JajSkxyE zl~&?m!GJ)!@>JXMX&vL9s(x50R`ijNzTP{B&Kf|Wn+nOp=`-J2vX#$773otFQ+K*Xeg3AnuNAkZ))5fKo zv{}&X4{Sl;@^FAex440Uz;xb`!gYG0yp@yK&$0k8Gu(>K5Ats0*yYmhl$2KAJ`d;^ zRgv7;$IOyx=WX24>5zEdT%vb+p_3ns;5-!0#P?}3PsJ3ySgXGgHtb#NQwD|XA2z+C zfm#-kE(PEs$nTB!S={00o&9Pa!F~tJQw|k}o_pn?QgFvRshtJ2e!uyXJFMo3;!mpl zx6aN(mPe_I#T2zVT}^p*>ir64SUciL=uf@##LK71=6rfV16WT?irbkFkkO8C>Hh%7 znf}*soQ0L`|Kf0FLN+d@|F|grI~-@{Wajw);JA~Dip>fid_IWM{4bou)I7oV4pE#C zXe=yK19Pe~B&5Vx6a@hRp*S?8!Xjl!=raiDfLE~`_nem(?Te3P&5KNr8?USOm!=<1 zo?l|cLgS2)pgN!d&uAd90mi_pUS2lnj8H&+gMosCiuU;UEQJ&>-z|QbBfp}b1Po{E ze}EN-`iZhRvv3AcLl#GJf$0>xKJUb(&A>KbYAc3=cLK-%}Lk9x`CMYaHH2`_>HR{@9+*M!j1s+8IRtNMS z^7y8q&L1E~P(kdSf%f$SXMzL;_RryS5-_mBMT7r616H=-?VW{>{syglffPV`eQ*Y< zWqiH)>*M|d6DacI94wHBrOpAhju_?)h9rUZi*a!l_4)A$4UEuym4OiK$gl5BxRXc% zZ4empRhJuVR)HOYuodISdKNTXwB5}e%7aj`Cmrn#9l~Yi+&qX_=wydH_GwF->TvZy1#7nXO63%7Z^IWF)=lg z637K|w_AZCPM>P>b91*RYFFP<2h;D{7K;PO&k77bRHWCAz}^Qjl;hX!pnD(a*U!Q& zAnX?$gn>jU#V(MGNdDMQShVs0vd<_dj6qztFB{Z|03*=*)2CPcP#j#aV8Q3N-%oaZ zXmeR`bKBZfkNfvVdA|Q0_-9Zrif?Qw7!**1KN&F9CeiJVUnJouKkOT#z6~n~sKk#V z!*%|5`Pzp(&h1YdDM)XR5w^kK%OKFtpV%!3Qegjmz1<&{BcG1XpVV)f@gKS8A9~3F z*r0d#-5=DuA0WbNiNu{8q+ecLJa!eiF@1Dk?>%`gyFRqFFc9D$fQ)7euok3obMaqg zLB0F^gm?Up5{U4H48KeR9|M1X31;v=A|Y-*yME)3GGIq<#P~p}hzm2->PL`L6G02q zYJ?JS*@kjTg4{wLup>ace90;ch+swC4YmQb&VvGjK}dgF8RpOXhEfb(q{M&f`{n6r z(9%EL%PD!-EO_I-IW_p^OuMG@ed6-Fk`<3lD+H8%Mur3e;5$>m15OkOi03FurCn9BYU9Iz7)${#Y?K@*&0X(^(jkj*hR6K0H6xe0C#z9Fcg^#YYrS(?@mhk_jUS9%jK0 zSA#Vxn_xh{ndHs%%PFaM#L#XZsbfhXXX&}ERYI7q!0l#0{E$M;v4gYlC~J35U2`ka zQZap8lD>93&d4mTwjdM&TldIc1$6vJRm`St=JGwgGp!ek`3M=zazU$K} zIj@1{rasNbok|T(!-PUB`@0d|oVtqfMb*i9_qi0a81?cokGtmy!d*CS?h#D^sCpwg zhO?^Lc1;ttlY7VrOrCKsiU|@vN?oQ#+rICHGzs} zuVZ6pd@v(%d5>S4YYMsvF|7ONrXi0-bSF!ya)ef>?mHh4U!KED~K7l@{(%v73gc{D(gE#Y0ro4MH z#~E}aPA@E>9o*sveympFyQEdQx%S zWpOrD`{q|&n5;bkujZwmK5o2jnkN1xO=0#$?x&>yI|_h%r8ASb4*i8Hp0uBV^q1oe zur`zRU*{)ZJFX-W6)n3ZY<>mDc*%pNT6UoYU1 zp$=v(QWd=%ImZta{l`%!I?D)FO%j9r?JNVCaMw^fp2Dyt>R7#s1hq@mgpU%mMwF6dXz4Iwqr#`*dg&{6e zkhzijk1t4-Zfu#%t!}%bHZKLVquj4kHwmP@zN$qHF3;7uk1UoChvQWz7NwBiL2=ls zla1T^V;EFW17-8ke@(XOreKE+W%IG`>17|{*Y)>X3sd@sV(Wov4vwS*PtTY^@knH2 z`5^L+auk$u#UVy{`Y5RJfZBfO&2Qf85D^cdC;d1G34A>?ej8NeIXhPvv-05{-<3oz zEvp6s89MAbQeX%sUH1{_k@Brp*vh5TMrFCI+n!Fh+A8qcEtY1_;bwKo=VF0#y0`;%WWF!s4Ng}h_~^HYmvBW-wp5Xwwg%b-)J8} z$E}LS8I8AoU#Q5st4H3n@b-%whpM^0RlsTY!a|py;c}8|axo4OysQ)) z?P%jgwUbEAuha@G+N9Wg*|MoZ3UxV@>H311iLfyA2jy)QCF z3my zexpfD9^C^|GOn93rDlNgyK8qkWDdTZN42GbIIarzeCQS7XGg+%;Gh>E+nH_F8}At; zu6wJIB4S;mZRRolHWKd=MK&}x42m)a7iLMm81iIGy4Rad@vXf$jQSVGDNO8AUFS*k zwsTL48rX4qSJ00^-m&C&x3IGgtmFK#f`B5^P(p3~AoT_@B7!dZzu$J7k<17QB|^!y z=;i9dyw3bFXA4HswV$)-YA=6hv_eC=o6H`rByANRy0;_ilxS3@9SKv42?!r|XN6Q! zbhkxPSUdI$;iLwKCb66|MFoM7tKCkVg?ax)?V!I44s2-SnRaO!-xs}Tx*>tipjHJI zlW|#jx*xpdbZK;Oy-szqTX$1V&k;0WztXGg-co~os^J9Z&~Bz0&3nHk%g_ml(2ihJ zEQ;C}K5oy5d~SD_Ce^i8j088Q5)B~OBa|<4{?OEgFFbiKlSJ|xP@Isz z$L9J!!5n8xN!avG9@Lw8SwD+UAB-N0wt93dEaSctP0J2kyH4d7<&HVjB=L5PoW5Km zCMIR+k2l6&cug;?cG* zr0k&lI{&E)v+^^dUYP7Je|Ko*5&><~!t$AnR-zu^H0fL(s+MxSC2l08 z)u&+J3(;?d5fG+;EXZe8Askr>&WR2ui$| z11|%PJpcJ1#<(MOlKl1+FRv(&jB6_VuIJjQnO`+5#xkyQU&y!^i?2los*(5B`soXm zsZFnjQ>GA!CbD(@>fZWvq0Q+xQiL9hWZeMKO=gLVL4PAxq21AGcAV?if+f#s%2dAV zDQA6g_9FE1aI=35^DgQ+Us-#@ub@w?+%r8cwUwYENQR_g%j}B!B5I{qDrZJ+CAoG) z<0Rs@*s#{h2~Y|T35U&70toLWfA&lil}v5J@X$i)HqYz62yjB;((A$Y28USW*Ww52 z3#l<$^GfibyO>i)kbCNpH&i7?&a}xyHNcZ{>xPsH8z@_%@(78)Ajh0V!_Y=vr}Hmb zDwV^M&lcWhvg=(hbA%z!p>crW%lS}~$e#k2na)nDEpdem-cMy2%??%11?0AF+ar3~ zCHAdpMf{q}_D4~7{upeNoeM%Sb)_?i%%BM+@xUEi#DiGdr5)l&?enh7+hX0!G1S zlz-}9{^GKtt~|%|P7*9fmU2HDo$Trks!WRnrWC>mG+Sq$-6n%#L=juH$(LKQYw-X(;jP05pkR_}xn0nxoIOz>(&786X;J&mb@2TfH~w4t*b2dy~C ztLKhAAsH-nF|WM?w^T{D2Hp24wqS^dq#P_MN8la0mt9Mnj*DpP&cV8U5#a=p=4e(} z^c?z9&EpJ;BOh7GQK<~7xiHt$h3KtDtG~u(9t+6XmOLthSS;4~k(u zSuu}^(QfJdM*o+a?eBgSiNZ`eQXZ`&`oee6cym&FTaZNi`2;6V9~epG@u(yiDx8Tp z`8lMsHUJ?7!~T=EU~v52GnikeR|bf1)2PD;>UNN3JTVx5ilpjLXUC~%bkCs28WqCH zOG$V*ISu%$&g9uw>~f*01$DJ)U9qPX%rh)Jik7#&XARS>F75@yMyLX)E&{w@+YwVn zsRHnOF&US#Nw?+aeU>pqQw}28FHTWMj|;Yf9J-b2&tHCZ)ns(k`!&dFQ|arDhrFz7 zuf^>SU6XExG5=4EOANbHdK1h$YF@M4+g`bPM$I!sYXs~TmXvOq;?ncKg5mVV z&omE2Fl)zgD25+_8SMK-AY4v~rp7x>5S_fkDoI@6N(|8)S7@Jpu>NS5P?$GQ&W21i z4t5iRT`|fjY893@@bL18D~R^q>XL;-%jCR`O+`FUh`Ag2vD22VXvUXQ#`!Dz^*CEr z_3E1gTxoX79BN`cl-7Osfrx&5AzWv`E;$9R*SJBcWEVL>J*d=A- zbn)GA3ogdZ4o!cyQ>#GCQaEb7Z;=$uodY$ov1#}b^O0@Yf9TbGJa`;(#Bfl)tgWM1 z!Db>qMC6w`Zbwd_%Es}r+iDyhuReM6Zs_0(5S)YbRd{~$aSnlm0j2Q?N0vAO}(ae zWzb*<<4^@H*1f0J*!iY0L8vFq?pk7h^r{O^;XT@s@Nje}9xaBmF3|ZhI7{)}Wu`eS z&COT*uN`1h+bBL=72I05dc(v=T@Si}N@ zhXhqJ&P(VAgkiZpu|a&L%y3wj6GO^H*_@euIth@(DpuF#{2q3X7x8tm*sc9F{;czE zoVGYak1-LZrGC-)nI#UBv5oq=C?OYOl0+gJ(z#mJvaOV=5}bDI(GCViu$d(JCU?wV z7**PTG!wmGieji- z9BImECTE;9GE#yKZ6Ay$2L0h=^96Cxm`aT9Z4vS>_ah#yU;T4PM7o?o+ee~n8#U0Y z))6bLiM>(jf6Xvs>(Nll2M9m9MF-U5JSgp{ZBn~{6iYk`@}M$c4hmZC8r9~bHu{>3 zKI4{mIgPZrc0WpVYTg3soc6QS#z zOy9E>dKB}E?Vg-BAFhIrotR&+gI^m=5Ej~?`iN5WmH!N8e%segie(9tt#jUWk1klo zAwLYgF1hjdAk|qmZ_CAl!=4EVcJ@znb5N}C6$wltH!8nFaSzYs^WB5Cowoyj_1_!O zMLdup&j3_l?V4#|t>a#&vUQ?yn(Da$o4GB^vK`g3PLIJ#atBG*W}>aMnEc%(&*prS zN4ZsB+ORvl9h7fSfRc24~J#9l!9(dAF^ci>}$$j4Q^@3x%1vT};HF99F&4U_;! zU)QMVSwMc6nFU8gvn9e27v2JmSue8}jT{8@^5s7x1%UFrogWUvm>**@8+UhfTXtN( zG8+JgOUm(>*twepfI%F3kVUVkQ&}AQYg^vj!<=H_wLY7IQa1PSeOlk?_4Fox;3<_@ zMiyi?X>`6^gqveSX#}h4v3+=(bagrSf#nQ`k*ENtql_P&L`Kc`%{8dOZ*H=qwu*V- zX|})33iHB16(ieBu{Vn4mhFmk1NfI+VG8lVaTR%_Z*_5T*RkY2!R0R+m0yUDv9-NF zJ5q!!WGYG(y8gzjLPuEPYnZG-Q45m`0k^{y^${qMkG%?Sf4z)5IlRfY@|oz#**7sVS)ja}9cFwT0=i2pX9#Z6OGq8W~JVO+teJtQ$%l0qA+j>{++`V&K4;W9X^RW~Xhv3oS%E6J4{57;vs@;r8Lr?eLd%8x>VImK+dBTXlLA07fG$7uW^W_g)}_Lgg`%*-^t zs<)(4-`tCnylHRI9qoK-QykN(BL!*87(4C1hQ*&I+#TJFKlRh9%{gUT=x(e`M#l%p zYh^~h45h8?0*xGm@iUP=rUQ>h=M(TB%>qm3dr@|gzSH77*sxoWW{N{A!31IZE*4hF zdleqygZJw#OzfTLl5)x#zqzhuJN>F^Qmm#ieCvzo<(xuD!xKi2HDmAa3q+IShg9@>W@Jsl|fALp_!yaOKRbv2@L^wuw0{24W%}aY-F!UA+&s9rK zm2sSOP;ip%&e`O9#J4Qb6()KITD0mnqmOYO@@t3@ufvlVdHLJ&$fJ`4 zI~QR4#aJ5c;$wZDpo?r)?b7mK?u=1s?o>!Wr`u{10r5`G3pC zn3*~M<6>tfWa46B`p@luhhxl)?Ck$99gBPhSIFF$hkz0O>w?JG3g+@}h4g_0bU?!Y zyKVsz1PR=|{jc**BpWnWF&bQOc(_Sn*+C7|VTqq?HRnCH@E@gaCoC(d`O(Dqf zeM>uGSWtb#!jk;L!oairg{H>WAYKWWc!D5i=f=hn1|Jwe6~%Mw9x`MmSKp@Owh_Q$ z?dpIT8$eRITvNH+Qd5CwWn?yg*cu%UfkUx7w9{_RaV=z$gHI3g+kto(}Ad38%o=4F0W)4ax&9Ff~7Z252kK zYHP@-BSE?)udQPS_s`ts(Gf5e5bwq15>VAb$Tdd<`?8^ZX#vLDkR*=-yfEtjHG63FQ9-Dd;%uW!gKy;M?w?6qjVSdLx2Q33GjrNeI%w1FXEWT$iCpi>fEqBZfplhz5 zOg|T%*kntKB1dF=pSpMazmbu-U3@WlaZ!D=tzI^WK%4IJO^nlkd+o1!Ghbj`Na zZ~dyqhPw@7r~q2)Z;OJYguo>3S(&l%wZ;1zi#P4+Z;uJ-OUx&g_7YNByyz21C{lOwS9TTlpGq z63CPmi*KXbD?Yw?*z>+*lzTnJN?_Lejl?BweG8)dM}!1{XB0oz)Q&G)brKXGsBa1{j<*^ zp!*qcgB1%uyZIKA_{Klqa}(k-2!J&Hai&@QvY^}0&UQX(wG<{(RX~ClZ@dxlae_?t`Z(bo9yFEDnV0yyd++lv^cyTz{d0M4E=yTj} znB3}ru6&?FIYOrQGfb|h-9u=uKs0Uppp*YC*ug%^$zPq5$;*4u`un+e9}1Tsp`3MR zF?FZLX_t%YaWom zqY7=@4tEy!o*t+Em>ATieAAP*y?N)_{jC@fZ_ua}zwHXbWvOZ{vVFZrk^lXNStadZ zw8L38mzA7)E8mKEg(cCBF=wR&Hcs60cnXA^9FM+~{&w%B*2+V!_;j z-S+g|ug32eObt1I!pscpEv@EI6thsN!@>|Z-$}KYGS$N}$VCb01lG(7O&#{26mRI! zKKt4U!}}=gS|M47^Km&u{}Z2^2LIm^mP|{P@|MBc6Pg5T0`b|H%N5AS2rvj2hn@5* zz;<#<1eO8bss&G`dV5e9oQO@S9mJ8ht@7QBt&5UO5?ZvYx?>C50=Suwb3XaLl;H+e zRDRj;Pb=HJ-s7d1Iys$~plU1O4v9xE=6P2xKZDw8(94oO)W?Ht0l)MW;*f{szq*sf zB+Br}Eix$P0Rqq{9L%0uQ7DzA>xWUEmA>|4a`9$~VDjeCE^F$i@U`{~pw3HuB_eA> zD#_#K&xPvc*Rr0#A7(^=mZ}Ttck^pExmP=8tMev59F-8nLqHO=vcaPUjDmtxQXRGW zEAWF8JKu!+0*mr#9A|r2&$wibGx|d?Lu;mfjV^Acr>qR4%omca=Svz1lgGR+vpV*o zx?C(qbc>CuEK^3TC^H8z!w5*QazRE?uydE{skrd{5Rb+MYULT978va+#tt01sgI50 zd=N}9N`))EBoePYJP!K$dyU;6W9&prh|-{IEyXlNM(h)2#&LQExl^oY9M^iFsJrUB z=YllNGVFiDl2F6*g2rK7upCOz&w=JGuuF{gH|Hxr+$P;~U311@fzTv75ZyAwro~Et z)kXF0WYCQUKosHwb_HniNd=dnRTAWP?bDNfPcbaQE;h8D9XZ|~5-fxhfiv=EUAs1# zyE>*BB)vQCm@R2Px_rVr`$BKPyIXfO@HcZ}KA@O>U+mhYLSx){lvm z#84r?)ZV0iO`BVaY}{0m2*=i~Tszmzg{JNki`q@K1sLA~&Y!oU&dC7JW_IPFzl{}` zBRIDGmD^sJyIDrf0|GcyH26PwB0|OMh0U}B^|aS}K(df{(TBN}DR!x)(V@o6h_1v! zF=Up9e>KZv=`lo$siF?45iH2;?K4UOM#9P8T{E4woHq+Bc1HyUy$JYdvoCLdk--Lu z`b##Mon}ok>QQG!WYu_rOLJ78luPSa%AK-8+GxSrAS=mJD7_8Ryv)qSv-Mqju7O!A z<80>Db-;HyL|C6lN%hTFmDXKfP#`s~$8E&CZmHe>Vgcu!D}MB!6CK)EW6Bef#c zc}bdMTpF-FWnoN=q|&gw4mm_s*>ou4vsP}ANm zlr_*oMf4EMXwW2e49l3NY{iG>Z0A<#$uol^X%0N&@kNUyc z&Kz&cl5=q*IQ`^CCeY_?%za~w1j}$zj?5~*>dT$r19Z$t+xsVJpogbqcy}bL&H;m| zGM4y3k=}?rbr9T62($tcS@S%ZD!lXa-+5!q^h7v)pv{m~!^tWpG`~5gV@7?5{k$Bu zA2s1&XRt(L@u)`*FMK-IsL9ed84XYSW`pn2J`1|zCHZAP0Ub)57m^8oA~W{0�i> zYsZc-#vaajw53I0-rl3GF3pJwNf}kwb}Pg&PcJCs+5V*u-9F^+cg@2atl)lz`;>ps%#qe$we(g zZl=eAU_ot}Ybz4ciSg|n>C6}{HD2H)_69Jla$1jiFUyA>{RFB!Kg?Ch(7(8L2@*_U<~6JHId06lZ5zYsQ462rTMl1E*?rKDD6 zPlla_vlDWl$Ts@pWeVNQ^iRroy^M&*9utIav*(f<25L(nVlmLkyuUIyAz$^8N8R2! zdLaJ13JUSgmHjqi=CeDv?X~OadPe*$1kL5XD#^shoyO@+1AIykh2-*%O(wysGAcC5 zI;){fCNnObLmQ(`n&g23nN89T5Q#~kE0wXE=lXG`TV4q^(2MZTQ zsibzJQsP_PM%$!J=w)>vto3Js(5YkKrTT3q)%NG}z?o|XP?)%-dEgrZjQXDFZs!GV zkZBL~?;N?_18T*b6?5%@H}?p8)E0L}f5vgb%=L)Yw{xQ}B+7%x-M`Z)5 zkr*kob*it^?MwmKM-qmJH^JY1aZ@mSv3a*KMP;^goIr4@5SAPZzXUe(>uU_igpKRnG2kyj4JSba`%G&sS0& zsMdO)vC+yHRGOYZc7Klx6;RH@UQDCCZPZ9&U$v95W^N_g%y13yINV;sPiCmW1kdW-v47f$y%@^P81c%lEc9+uSv3AG4%5 zoyGhZl&Jo#PvAV(D!_~R=@GNyfYp9+oVK}c|6q%+{mJG4(?$?nP<4Azrc7*VcC$n# zVFvHd-W1gHXghm$yh)F@ATmm`Y=i-vETWRg*$+E{mMpj+U$XZaX`TWN8CYv;NMOBJ zm}n>_$Dik-&HFn`j%vj02Nk6YdI$n^?xO?n&Qbj(9_)8r7>sya;FXO}R_!;48{9;k zts0QGMzlifU%gOOJ9~prqXjq?>S*kZdXQ|rHHER>OGp;7qua!gFxdTb!{tJ{+Ze>7 z^5n(f->_4p#<#i}Hi@q?IDkxH(jL#qd&v8>Cz; zdU#a69frKm+S%v--oA(@orbWcDbQk>U`47oUsgip8=?`EshtCwzVtRIM#K=&K+)xO#jN=aKbiI@6h4p02~wj_q*$`V8e*lM_x%MVd^C*H3>8 zwZKX6)_q2ZK5V93vHvU%tLWI{=ezz&)1>O=a8}7`$b)iVdLBHf>aX_~3mokF4MX6u zpvFZ<0k@|n$Eb3;zKezGVraD~!3}*lGPhahbsL!Hh41Rya}sceERXh4@D8L$5f zPO34lJGGo5gv=5Gf%1lNeVwLu!rtGi8)%@*qCNRoJ!+sRo_fWpTVA!HO{Dze^YU!_ zqMhDvSOroh7LLq<0-wO2H&!Mgv@@yvzqt^D`*J)FR=vF?iV1P`jUHtF*30kr5!hjwU0a8qOScgI>;djfQdx19H$0HJbSP zs0WZPD2{A88E;ie9ULfdia0Sm2Q^KmlI;HAQkkbnV0zPU$l<`6^3qs|pN|O+e{Yr` zlTMhWekq+i$|5%?4r^jv()Y{;T;OIjc3hCaBYl>fP*#e+OBAk86QdRB{ecwA4}~Yd zA$ENcwi0LfGUPBx*Kvrm0)0#w+a1F+7*|Lx6`=zMT~&VbSFzKF(v}PEcGiI!Qr|c2 zFTz&$d?*=_L4Rg}N93xlTLAkZm-oVkzk*uUkZCq%im5a>9e@)x&uUHuzfFaM-r%LdSLOM{Pjg*NR|>Y z!rXRXGC!`G58K%mQzpCu`HX<5AD@E$l{P8v|M6^O?9?uG%YO1JU6%&GY$B6=X!n}z zoLV^7uopNlP;7%C#LnE>4<_a7$<|#myEZDqcBZ#-*O3a3H{ARQb>+>Ok+{%qh7NS| zi6~A25yl6+X{s1P&3lu&s=%pFO2;)h%?LqaoiZiMJW@2?Bm8p8hg8{*3YE33gIc zo^m=;zZluON*n=@Jy6r&RsE+L?4N!p4El9d*k_fEp<%a~l){tt40r|ecY+UNI!Ed! zJ(b7AgdT$K?y}1wNE_YN>0ff4eoOjK3t8N$@uL172a}GA`;o!5JJR-Ml5^m^)hRl8 z$HRPV3 zMU4p0jVVLIZb2pmmxnA5Fh5~^gKo$|R;PKZ3O4Ev9lJEg4vVgs7BWR{x5|=L^5Az3 zvqOGoTPYbh*2QtNWjvcTjfHp z&W^|_KOS-jr;Ve)fW&sBD1S%A-^;0cBXA}`vv(jgJ>s15`V>bEqog zvkTH;d`)9Dqm(tqbw0LDum(iiL2~8l+K7d}k0mke>;BQ%q%8$i@9Eh}&9JU2r~p&PPIrPOa3XlptckifZkT3`v%L z!G++GULEKbHZn_>XO3P)tcxtw-n`^ZSEj^5QBhz9zL+5KC*A~qeQtw9bcas+BoxMW z2v6^6RfN|RM?I%mL$^rLza`l;zB0Wr9oG0e zfesfdg#dJ8L0fi{_1zVy@$nr)sd)khrLuyMG;e%QEzZ_H?*EIebLtgFiMH&vZQHi( zZ`-zQ+qP}nwr$(Cz3=IVn{+4rR9U~EQgh83<4Fi;mBl+VRc!0A#sH|!$pg5q7rXxj z8I~~v^X~Z6loll~!cbxC-Zxvf#rNRX2gGSR&5iQI0aB8$TmGO}siv__$+)P&k~3x; z$t}*)>z&>WZ0P|Z_#FYFyTblvH;f8^vFBD!LXmC>r*4v${)kdJW3u{(toznjMq#*G zZMbrX$7GevoLmY;W|paeAsQ&CBeJdxGdLEj3NXk0_EWD?8+7GEHpGln_Q5q}H&K7NrAsx# z%Du{bvwE%7tPuFOKJy61_xLTS-FNh~WJl&_9Y zSbhvb1rTWU+jVv?ubEBGa*$p6f49nulvmIW1(x{W8pBQxF%yCi?-X~SBz0{sJ&S}Q zgs2Z%iZGU790#kp-G}OahMB<7{l$)dzceCy4NDUIt8x!s#TpOVHD=Xkq1oMt|5U3; zDCh9Kkl=mHqUHoajJq@j`ed2e%V4xPduF8*bo4zTO_)Wl3$s<@;N8lUxBc@9kjJID4(+kS&c%u0GX%zN^g^GUv4=Tw#VC9WpV9U(t0 z9b~3&dx?5o0Jnm<2AYD&8C(babvbYx%@om1=FMz*)4CeBxy}X~1LewfK!|Q(Z3!v3 zw?j~E`(D`q)E`nGs{xAmGKCqk}EWp|QGInE! z2&OOOT)fFp87^de$yk=w0*&&HLL^275?xX;)b;4CuJ3RKb{-BIzflH$n&RPge+3!W z!tN?geq9QN0D4+n&XU{}`bT$$Oe|cf-+<6S*|(3|k{kNqqJEJ1mHzvCm7XvDhGAZs zMncb)2m)dHO3?~o11?RQ(RX+!`nc10n6S!Uq~3)66$tmfQx8_YipGp?hrFO@8^^co zLhZh&QbJMmK($*Dl3uv69i4~XIzS(knH*YyrABi?+MtJrJ6n4QqNUo4aFS_V1f6fr z_*lI;lhzEW7;XtyAFB)(@-NUgxnGsDBCE=jWmc1hH6(vFns9kfa&)Th_?qB$RQ`S) zwGHuk%-tLZ>%t^eFSbl;bP6{-jwZEOeVJ^LM7YPwE5Me?`g!mpsi#>4rCcB(IenblA-a(TmS&L)2U)_uHv44P zE2f%%s0TQfZDPbFb#z-G1R%>xY>l54L$P&tC=8onRx8Q!!bY~i&2*crVI#cv8$1>6 zBNASQS}(aCZ!N4Ht+u88914At(|YZmljPX;?2H8!XXl=a%QVquSSfo-jk|0M=!|5& zf8Qr)>b`Wn2{K$#JLDz)RMIR=PFvF%}~K*4oxM-(g8A16SR(zs_g2ujmM@`#vpQ@_??B z)YCEo)|-h;xQ*NJ^kDg7=gQ04_eVo!mbpq31z&U!&x(TWOMx3Y_#y{C1rx{IAkd_i zP77&Upo8p@r7KLM{tMYmGM?8+kHyDvNM z{0^gCNNm&9qw!ECWgbSkT@TO7L~ehvOs+rD&7>A3BdR2qS+2e7jCHisEX$<~Wq=ao zgmN;81Rb+WYvZc8qoQ?wAJpDQ0p4`F@5DX5RHR{9D8H3H-Mo#*?-_~+Et%H07!o@c z;r+gr36@Y(GUj~ES;rv<#tu=aFu}I~Zx?E^|M_^FGD5T(pgQY|)5X(5mj(epjCZDP znU{jyR??~BY4FgOa-P8n*7#=ZIssqxxqnT_E2%1FG^p)@B<*ME?mCu*fevyM63erC zeWH8pSWv(!pZDJ@G)HWZe(%+SaBu?JfAu)9MajUF%>7G+iGW_82UhsN$&MGb)1M2W z2^e-WvIY(d3d_xS>nZ2#P)d;_X~S%e<&NzWbpw+*E|5GmvtFH8RjaVIfAfV{Ce2>N zlR`ZHX8b3aEx~!Lw<|(#l04uA9gn?SW7C@9A0$9W)t7<3GRS}8z%jGTOt3hR3jT&< z!z{}7UYtd<<>169;_{Xz``|C~od5>0Ec?&TD)X|40S>}11>LGxZhKz5~UAO`98tnhDc1EatHnE%TQ8npl zIz?}d>qUe#3w4LqJNhaca;H5A1|UQ!MMm+5u^cH)VY1il&_XRKidRH{SNM#92gJ&S zFT*^xp^u9QQNd4XCv|u@)2rcTn6cLr=cahiDK-o}g6;LTxp0Q@65qtEsZjN>7yA{y zNYY_JJHEW5n-CZN6U3y%H6jM#YoJEVTX_07Yc&~$;py;-zDkyXbgkdjCzSSXIeoB{*&Q!J!nn!^>Ku(1z zlq3#W;F3H)!rv`@fO)jm?iQ7Nqp$=>>)Um(_3%BU+}j!>(X!Q79<3?@k}t{Ix9LXO z>Cani3*)mDm)Y#*^TCe6_U6{g|7pw}li+cIcHqlgx8$Z~<2?B`T`dRzpOBp;v|6TD zG=TGCN4szCB<;u>)BKrby{Cb+z1nzsEza10+7XmJk?(W2S465MM8pxg+->7%jziRa zOK2hd_q6_pJ;FC8t`P{)h+--Sr@VoQIMB#t#WT*()A12FP|{DlfZB_m%KPDy_OEd@ zRxbXRk=$B02^Z|`sG8-ulxw6}9Fi0@d2W`X=iJt4@HM#+r5oS3Q{10st8_}id1+8aE1(ix}Y(qXHhe6!;&7hhZ@=VP-KI%s{w8=!_RuI+-PElO3 z0b2)UxN2QYPp)VbeBF1>?A+fd(o#m>dN2V5fo94eGwtW_kv08hN;C(*h9o@{T4`gv zBMKVCZ&p9Z)dU#he3KDW`PD?sLf3beJ$Dk=7>>rxVj=^n)IO=ozKVas1N=?Gy0m?X zgG0X;uf3Sy?joY>6qfs+xyx0!Zn%hfmFQVUJ&>;Qhq2mpUi!M6$4Uyic>JAwU-FQB zERT;Sc@opj2n_#f4_z0+%TBOy?QLdE!=B6wXtT#KKfcI^NTl5ovTYx$=A~08fldo z04-9y)`$CDwhm#=H@>Ria9m$u@9F_8PsmK7)W|cS2iqS>6DBwIy(NFp{CJ^Q;7?;> z1ggDA6o6r#lJGB$*Chz2z{1_eSEXnx#Jzd@I_ypcl&9Ap*DL58P;paBtN+_MtOnn^a(kb9rm){s& zWxLE~Y)*Cg;A$aeXvecQ7_mzUD&B)PTnW)$>L0tbU=V-4bZXIy6T`+Xz9^o>c}Dw# z8fLebM=)Vi8X$bx16y>kzcP8MCnzmUs~DapsIcGD7zolc=M7@QA+ttfx4c2a-l?B} zTgMRQK3hS&~I!OSUzOIypLLo@nCWE$0?gF8^zl$%rks{$GHgyQJiVqO!HAP-~ z3G&sZQxatb+w|fZBD}=5{g=}vNTM* zH1fd|N-;m=B&!3?E<_=jvWs==ma@ac>yz^HF<6NDQjXfU=Qd`|mmv>G6ru>#ms0m(2cEG}a3*$zm@-R{yKhOYV1$2JM7y)~L380uz%)wm!;2H|TKMkB!cZ z7m9{2{tMv&=csbz0meJXK)69t&`Eav>JFqgipA8rZ=s{a-rfayIjzk0`T}@eWEVB9 z!KQ=8ZaFS2M7>BGz3lmeQZ>cBYi&9M?Nsd6>^r_MU;B(+6+TBE%EsAh`JoI z-R3e3QrcXxkV>R(YQQBVgEaavVPFb6bJX|81k-a=uQ!vNrzd-_27;l4u?c`!f{i47 ze#hl|T`#Qb3;PCNQ?)*}Bzj^xj!Euq7+FJL^vral9mkNver`M;84h zoe2KQ>Fxq=m8bI(9^@RT(06TZgekEmd$0|?doMx!kK)t**5_?0fU|&e$9^CHNvBH1 zW69oSMMBS0dUWXa>kBV8Z*oV;&^Z_nsh7U+q5mHya zw{d{JZ4DUieTpe4rJG+4<+E(dxLGog0x=3l>^rwyjEvVKt=WW$iOgn zqg)eD>E1pz9XFj@q7sEgYQ|v)>)Af+h)duC%)mwKBvhxs^%bvFy zfF>O8jV^=F7!uv7sjPS?+1%cD;04Eso?6(b9m*hI5*l{Zl342{1(AnvAOGKHi&5f$ z;D%2vJV=mP?q$oR6McPbg&3PGFgjLqWTS6w1AnJR{RE(+b?2~4eU32dn$f@&IwzY% zy*H<=KCb@hq4KpjdYB0j%f7e4$# zq%}>yi|Ju%4LssNC5s+fxu1*?W`Go3)IZzv#U>#}O{CvRGM9SL$PzGbBm}`$ww7L; z8x@|y5N&_{p*0J_KDy?AuYt|gkaI71z3*2$CV-9oZ@?&-r?iJe@S$YWb2gnxC1B+_ zg!}^5P=)F*wGWQmH&1culSy-*3nBWS7s1RO!z=by_{yBib9{(AXt|4TOp<7iZX$?; zFP=LfiKZ3HoN8xg6F(41X|fb#PVcT_Xs+)pIPNHGxsX!!I0g!myF9wjg~s%LPK?m1 z(Ud!?#_u2Py_8oUS5?#wuB3n_6fdx>Gsq8u{ofevo)oj+RZiPajq~kVpimusTJFbK zeTw+;l73D#_gRRl4&Q9nX&a5tk$`JoWyq>HwMoEiaQy0m`jo`oHyqNq+NdE^mM$1HwUB?o_d&FFh%J+#Cs0AO%09Gd5Ba%uqbOi!>T7u`{-? zwDd%JvIUz+lu;?{_R~zsW%Hf83CHP`$6LYbf6p5?u;S*_NrBE~T}^Rz!(*H^qOqJp zA!%$(wIu$v2F*1R#&57%N9r2Uu)wQlb}mG$iY5=FBu_uOTe%{DCMtMNZl`3k9T4`8 zY+z&{N;_cF+GVzCl?Sxu?%QZ6oDznyZ$cTZ9Lt5$VNCM;xFs{u5C*-(uXjyCgEKZa z!**>tsIq#ys1r@dN}Rlwaw(^C1aS|ekW#pAOx3x^2=3OsPR@m%-DlH=gh%6FnLctb z3})Q$WFzLP1To~1U!{Dr83ZBT-_1mW*{zcv5y4%u`|@I#VK=~v*QiKaFxO|h5;ZD1 z`DF+^H)4$WqQv=x%$CZwkn0Y=K-1=_xF z$;-8-&46?gC^jv@wURM5AnnV4_bLwXqkQ=DxAHOZPvL@+6(Lqxb+FI^s>QK=5t z_7b3D4VF}x8}@i(xffoJ%SkkoQp!iw8zbGQT49nJXp=rBP{Q)v4hg#IJLaYXj6vDF zSWr#^|3#bReUc|(tg(@)C2UObyh&Slk;4O+3{4M4tK7eYH@LUN-=Ge?o}ZCvh83Bn z_K+gQekdAjRH7ret!M+CsGXxOU8Xq-qek$I5`2)pLz9Z7djkOBKXFOKlxiohCBZhsK7ixSya%~Ane6~W;rBkDQDP8 zUC;;*xLm+{=yuX7r#KEczTXNv;~P@Q$kqhjsWJ8q-$GqoieVn$aXXSy&Sk%XcQ~x% zgSe&nmr^vd7T@felJyjhRj+?^(;J~iuM9rDGTiT!F__KNLWsPYcsH`EEBA);$|Y?t zvb|X1>TO0tZCeFl>CO^K)NhtoB)$KelICmfrr1qN4v{=IN+^T!z2SJnt3y};^TON9 zdA@$gMxl!VB;2UULFu5Qb4l#Xo8uNf@V$)kQBz@&Es^;3|6nG&Hj=uqR{nhdGTm;h z61u_PtSv^6AGQHvwi$qYZ9m4u*|d5Af*k_u1vF`l%j!Jh>-8W7c~uRLs^)F!szR7x z>GMp^5S>4axy}wah0DO#g**h7g z6VgUrOvID4V5>P_$Ec^%v95$vxDY)o@J=3ppAWb$dnP;!w5py*uHkUP-kF|DN{LvO zGf2R4M|vBZXN?UUbTq3IvuPZjnz0f4Ai~s$)TKUb=0uLTO#XoYGyB0ogB&WibPDqN zWaKMyk)KkHNyy4J~p0D$Th{_%b^P9F#Bbcr+M1eW1afbL>_+PdQ9AP+3cTJVo@6SMvD#%4M6sotalz9xh`{) zanyL;9h{KcY>Vlq(F>NdP=v?q>6bD1m@EQ#7y3@0+5m5fJQ$gvJo{!mSc6xZU}>5+ zCdd(rHEzsYT6FIR>DP@%{+M>ej%bhh7v`uNMq|7ZL(o(sC=*}Sly}A`Bnjar;v%cY zfAXCMF7NZijju^tiZT7cZ8RgVhO{t0%R_H~%XI9?#}J<9nTD?R4|-xl{~^U}NlYMba9%3i>yE@D26nq3ecF|%3X5V;l>t$ICX{A6p-C@;S7@ zHZ1VdbfVj7^lxi+~3k}PH&jXbF-n?L|F z8%d~X!Wl}ve&9w8Ym@I4b1zCD(&dvUjHFH343fgtCQv2`RXbrlCh-Ucm{lEO=8}-* z$P3drP)B-4i93m+wW=6lMP0V8r&wjw6=5=03E`LfNn8oK3JwPC7`F zO==$y5FNl)r@>Dhz~a%m>3FzAZlrP?^DkdXgMHO~S$x02ib zTMohE%FJ6LsP0|2y&3rsN%wZSFoZTTvVFj6sTvizldwM4);=6d?*@?LS$*>z5!*A8d?3@@70r0V(uIOdc~?0+i~Cr zN2*kN7<~$z;|7RcM@ln7{%#6^mCMeXJ$5j^5a1&fq}RpXmrac^$s>4nrHdV@f#G6=qhc9j$T4D4uXFz^vWEi*%fR zS%nT9H#&@dQ>n&Xziu1T+8m;oo;p2a9q!o|T>c0>bqGi?$2AYn{n-TuvRW7BZk>Y` z5_(Po(BUnzI_}DP=s$5B13JThY3H`A&TZoMxl;y(UVsHet%w^Wfm9a*r_q#tYW$R4 zHTu`~`pdl^!;t0 zdbFQ`)h;O8gDW4RsQMIieCRnm%pAd$OmPB|NYZkI3Z$L!bZC?mKiW>_Q?$VIv$h@D z#o)!eJr<{20VJJV=3=`O8wjkqWcu=imEgR4E~iUNIx_YRw{&*H-%d}Qz!5r?(A2UF z!8&j}7IL6+a)~IoOwxWpN$cYp2`5}h&b0OQ&mKXjHg&w)IU;7GcEp3d;S<@IM`tRD(rZr8 zMyP1W@;HeA8D^|%wDCE@xP;j69?`khbx>XdJKeh8M~cGjShNRFtZ^iCIdMoKa2$pD z?7>C;dDV;%c0!S=1B-{Go7bAF)GHY_aPZJvD>FH{tLW1yGG`SvO1%J21!i-yb z2^czpfkf+>XMAj>v8MeoJpDT%`4M- zkT=vZTWzcB2jK60LdV0yQgg1A;Jn;-|0?eqTnn;80Wsn>b3#a$@h}F7F!0o64lhU$ z=!n}vQmsDH`053b!p|^te#Wi;%?Ss#O(_oJU9S;|EFl ztzLZWOsz{ovE~>Mbn~yY;+A$vaFoO$$0jj_&9mq}jxQ1bQ0u+1tN5Xskv>hlGD0^NI#k;82xHjUHNm>8{!}3U}V8apuFmM@XvEXNLX@ zyo3ZdS9GgqvO7&0?sO>9iXOlRYtQl`4jNf6xs5!eEym}-GXeGIa7L7=*d%qtLnq4) zS>3B)H9I=jSE&p$c7nq05JYLd66P!)@PRTlsIRUF&p0&mrL4fMx#h(ks>^#P^{tCm zZb`j^>DUJq!~Ii)?1!$wS(5=(xfsWaf0oo6j>23?sXXl#?ouJnG-rD~d-u@uxlckpji@4252l`-p4PPsQG(($YO@GZaIGG$qBB3{un%0_bR__~)*lmb0 z7{^#RF=xG*8O0tGt|AV=?1j+_q1kh{=J`h_9a9Q@g<2^r(cvF^e zUy>2Z13)F*qV4Xytq&S-bVAMsx7oxWK`nZ*P%=H~F@^mENUutj9fVwAS0#iyfi?A< zJ{0g?v-9@?(y4*8XQS}vkM1k*x+o9zu}YDh84$dVsTI+ENUY=Ow!Ii^NdK}EX(*2nm3kY#Yvy4Yi&#(d19GnrzlxoCesN1kf{vJ&UuwE z@DiuvkutV1RccA*+9B4gBL7JigXh )lOYp*9ltnsd%NV#iIqjPMM zbG}{=n^*_BA zY+To7NnzVTzztLHW5?<4dFEL8#meTBRQ4%MBvu1JgUtO-vTfj_crXcG4b zo=c8a{J}DNnrn0oEj#TE^sL!0xdyS+2_UJX(+Q9&E9&8<%hM$g;Bi0P5K6 zmg~;oMWjbP=LoL&%cBRj*}QL*8TwD~jSJK2sqKjTC4T z+yf87%n^{3Buw;tY_nDIa{|k}*xo~YW-%%@Qj;KWG59E>ub{lKDGX*>{&L+EuBdW``u#Gg8V53)dj>8kV15hdYjHz|v}B$rXZm^m_O{ zM|R6VpAO|tQf=b?<2Zn4u9YCW zs)pp47X{#xakvcOf|1~Hq@wE; zzAYQ3!5AU%5_1Ok_~8e{fNLR8HO*+!+dcwIwjMLX^YDlA6R;Xr8}b?Y zt7>lBpgUC}b-mj|6Wk^~1YgYTxii9A(Z!h~-RCQV{;Q(0aMgs{HxVfck^~$^SzM}8 zqKW5yXcqkYz=UvkK!-f((@aiE&UT~OWGH8~gBE)675O9l^*X+9G%6Pr;r3mz@H=sp zVROWd#?46fwUWb23j$8OzyMXj@b%%A{P@jH#J%vA(_lQFQm~9~H?d>-JA|?KF@y{Z zA%9sQbS^%i&z^Zr{nEf2ljcs&6>-~`z;eb1wRr*wC0MPP2vbA>u!=7zom^d8=<=?` zD}8-Q%^e(4Gtt}1<{i8n46+j-T)V&8}d+=#wpCOuwCQsS9(AkW^CES`;EN@qr zq)WWiotNWh6CqN>-35(4QI* zCAr^<-B_oCu!--YJ{W31bLzk=;o-+(>_Jrns}U%>06sC$;*w%58s1y36*J@9M=*xQ zRPWqYAIg^(OlY5Qd8zu{jRZXVh4kRd|H>(q@t}=$vr@IM|33NU(aInVSborLZz~f< z%G2xEYzUax&LKalklu^bG^V>^vL|n#(uLpICsZP;0p^E{H9{ft3xtYxlH>SBbh8-t zG3#^Vr7U=+^L6f7nEj4Jb_oWqjuTaRqF*PkVu4=d?k%=5#H$EK#tya*Ry$C*6Rt58 z!a4JMjI7o`HS}SK7EfhpMNqcGQHt_JT37k6*5%G73%qUe=>!wNgQZo{O;N0+1f_Uu zLFT98!w)YxxE5Ci6^QC7cu1!$(74-V#c!oce5{@El!U%9tYCQKVz zr_@z@AD&{}!33iVMbGPR3AOhXcl3bjFEZ<{?dHyn+Ew{t8`n_C{b*B{`_Lb&8ztTH z370FZ#l|l))Mj}T&8}_lko6Xai~A>6b-sr-Bp@REZ2<*j!2q?r_D7B{{9<-z;KDyW zrtl;W;?$LJRpE=6Co`>XNrZ_JT~C-1JF7fED-IA2zpK)e&8Ij~eaX3!%caKKVLfir z5ws%cOVR2Rh{O_cJS=nAFY#5}$W}Y7NKeXXEf0*hOfjy_qIofj{*%tQZQvil$*y-I ze}Mw*mL;LMmVYaiqzJ#64kB4^WWY!J!N)82IkWY_DTHXd!d~$(s;Z-DIG>Uxw9pm+ zlBJKF;goVe(OcdNb=p#^kPS~fpA5G$XdwAdRY(l`^3V}G@gg!KYXv^oNzZ*b&R>f~& zNL?Um)Dh6!j3hUanCg|RJ?}P7tJll}5SFnu$X4%7crfF_<7H+ma|i?{O+u8Be0=XK zKxh@<8@iEa_V@pFKTQ0qx?M3wb2pfvOT;ntiZw51_%Ug0BwE?5cwZ8ac$QezkI2X= z9-qN5LM(3glBg?Yt{+hsg)F_d)k41x$D~qP3nfJ?soOIZxw2JZl%B5pI@y;C2$&8P>3CktJ1fLM{tbzKM>7K=>SmUNG^ zt zOGTt+nAdFu>3rosn%uog-&x+m_KNRzfB`y40Xq`~9K-JwRV*{#0CQ8Is;cS4KbfsS z!x5){kDOYHU$-A!r6W6TAv&jXq6!@Ikq-A}p*P6|W|C{WS&2Os3u#i0=6x69qt|90 znAvxuQEPi{ubP8a?=3p!7N9QT`tmTMUhWK&tf z+_7XfWf)-E&*J;}|d;!pq( zd{_ME#qd7jnE1$v{}sD7)XztGR1}qTJg_Ov?dh;ko{%Pgb27@A@J9-)JrHoo9z0&0 zIU)hAPY6r{MJVOVasv}Y|{)MA_CTlUo zt}5ayL~sL5B-&bUGwBpD3WSa%$dX-BeT2TCb1I8`o`;1S%SD@>HZ@!l%+$1E3j2=# zpug(!#`^0!h*vC(579P4?t+%q9j3PkSObO%U+^6tA{e3$bovW$o#;V66?qgfK0f*P;gOxMTx?vQps4zX3D+A9c1 zP^qi{UcBs##d|%;CbkWs@=45yBD&tu9Wj@LCHPbHfvk7i1(jT~jL}}7sn02q3;er7 zabFXOdRF@0D1HFM4TI*Mn6$=!T(=~zN(?HwH{=Em79Q~bMU*c}OaHt#t@>2_1=dhk z7kB2sSQ;Ut-&}8zqtUs;@{rB+uC(MiReg zLm0KQwQ9*#EP3BgN=7CVtdlJ^#b%o`(c=&)(JR08%6qarV#-(6F1Avf%iULM-!4N{ zhIm^_Nsz;KqgHe_$wbcPnN>sgZiMW5AY;c&Y)Duia9FrLg`O~2fI4lDKFV_is?^sz zyhD@B+jEog^N54FN%#|;1a2I(n)`tYb?~Tc=f z%S^U>ERXA{6w^hKtPDeZ{8}cSRf3cS1Vv!fxHS`Tg2~I9!&0pZuHk=@R00UeV(|y; zz^=V&xq(f)^=pTIv?{=UW^EcQrHgu{XHA!Vi|&6_2)5+s!5|kg?%%w}Aq-k8=UkJI zn8+l$Q2Wg!0pt7&qyeMw@X8q>bCV!{!GyE_Kpj1@2e~#NG!lC+MZP2!fgOFj&r zXTUv+6=efIPmOs#8&^6$0m{WI>O$0>qQOY&1a;@IVXL^A!(HuH$zmH3bI~S{u6xG$ zURV^X!9|WQaC7J;q|>sG%^E9WSgq?Gr2)Y&#kiMH^$p%-o0&91G->(WcZ-HZ6$diZ^qt)xQpu+fNU zKOoPuz|8^4HR`g#-_A_`C=N74=MTb3XqDB0LMMTD6H8N9irJ{8}=u zUPT((g7=vXb|(|h=pzVjFA>dmE%rU}yXWPl=GWj^n8>?bj{Kz3%zbGu5az>W1CtG$ zh_&K(Bz6KCyIp3=iYwC@$;}24?IDp#qni*B^oZIqUW{jmX%^`(mfxanj#D-$aFJkI zaOplB>?@@~Wz^R&{KFFu#~vDwkMcG)T8`A^(m{)| z9tmCX!b&C&CJK;Q4)6+HHd)N`kb&WVRbXoexiGU#N!^efF`hcR-BmOf9bgLNDx5v< z_dfn=$w~YtULx9T?eDlalM z0s;U?Botr(QE_&5DFhADYg|u78OPm@MVDlfDJqe00|U8 zgj5hoae#n71OmkiJHibetURa}Q9b}Kp+6fI=uo_4W&V!$He#%-x^_;V9Uu>aE`Wrj zq|m+_hrk5tX{^7$0st?=D&%Qo6$BtLAelJ?Q0U8tI24`+InAn!ruzESloZ5uB%)9k z_v8~4KsSOqxj!Qeu+v+xAYh*u*m;nSfu9&M(FsU87a@Zmr}VsiHTpU(SU+Yw1O!aT zK!|&OK7$)TEmyyY6uSOCnD7ti>JKylz^^-o>xTpJcGW4;+{wx!z6fs zBS=4@1V+DrjvB;O3@U)X!n~dU15(iFND%J;1j+h;GO-;ljQm<-5P&1HZ)SY3!&v(v z!(ax8<2uX`zmfr)CM>ARKv$QLf_jWay`KuAZ3Beu-Yg+v!Gpe0 zf6sQvtO5jh9(~P9KL!rui$0rJ1{whv3Q{^cFra=s0R3GA@&i3kX`gNVzMQ_9c1)n} z?Ri@O4qF&?03f&_pM+0?{#*ut)g558{kObWzgh`F0ss`i0U#XxSO}DhzNVvThIc)y z?T;?vZopLmoF4&z{kplnTWfomph5+SJij47{D%6-*xZm*!oR$PzY}FuF)!e65Yb|Q zK*d7=00?JQ2=}*ot{`H#2e3g{MD++| zed12w z0P8!r*TRw9R@;&=`{08WNKj9|GN%6Z2v9L2AprKwU;z8(Zi{;0&>#?9MDlp)daHY2 zjEMdWu|fNLLElWjML5GlJGf;%d)@snk8huC^9Brd7{Si2Sg;9@PQI9{o|-ko=cMl* z>E;de6{3QqGaJJ@1d#-MCGz za+c8hP!xQnhEit3qm(Btb_e{8hDYjyaOyi{k$nfYIR^%nCTyOue-Ma%h1*zCe>-L) zTzpRZM`LZAJ-l(E@K7$DmBV@B^YeSpE2dM}(ziurGLs9wAp=K>XxyrlQc}ic^o}w6 zngsP}>hGKy>syJ-8I+e_r`B(jzS^rv;=^S! zaTFWxmXu5!gh`^d2(}GxrP*KwhWh{gm+9rtopv8Hx{C{(Z!O`8gpgW6U7Ghi*jx#i z9rI-xrDeDhaV#{_T2*;5U!RZy5~yH2I+O{+x0^Cm!BBugd10P$txZ}k;g zHs=VaG&$~+KYgieiGaWP7$72P<$S+-$-a_)Zf~x4MTCde3^%!$R7LFjL|lY;pFlSW zaAz)ty*(W`@E`Tn;I7=AXi=?*?FfsNxk`i7uJhs=+IFpB&m}*2T6a~&aNEpiHT{k; z9`MBs`G-2=d#NKf77_|pYn&L-+camm(5tt-lqU@LI6>^%Kj*+0`w%&~v98a!_UQV} z-I#pOc?xPP`UV>-oCZ`L?~&NW2aR0{icr$__Vi} z8a??-&ePsOerEk- zZR6J9J^#|0KQ0~NqkUFSk7`&}fRAuz$Ur8&i}QCVsxie^U#2;~0lQQ@#N-Ijt1my{ z^rG?O!|un4Bvxf_0z^iga(hS&rt=&qoy+^apWop0)Znge`Xd(uAqU$LM*6&U*yKB$ zpl3O*g{xG$g(ouPI0pSjxUcqlCb&y zQtbAkf%*&cR-_U@EN;RQcY{-+hv!J^Co<6_OLFGYOe{A}r_o1g$5k@HZ9_AQtnlW% zSkG+8sGL_z8z+lTm&aj!NNCt1_5oE_lok24cjD+*|QJ#0$XtkGot3tRP;)^R)LQ53Vmh$->sFawP2~R?=0}0%^ zUzY|x_~(i#0(4_JUCEk|ctVOcX+la+*m^JMA>|_9+Kx|Q1=9UdVJA^W%swX!TfYh| z7E1H1NDgKY0l@Hz4#($7fp_aUA0_jLkJBJ!Bk!#YFpcMYiLt(TOE|cL?cPOVHx#Ql zeb^IqXr8C0wN+)YwzJ{hA3EJw;fa9GR5_kC)N5O>ycj+N7r+JyGZcdizq# zWtTT}(1AO&xX@7}mrVVS7vaSN;zG?^#Gu=H+xPpXj*H^)J^1x`#zdQa9*sKpU9Rz@EA-8$ZNCH1p0|=%YQ#oIw$0md{2%)O$gk*WV6%nPO!c_0J=-xq(0}) z1y%XfGUsYypF>>zry8weS5Zqr#_!$Wu%}|bKjg=jR;)zzX1hj`IE8fw;x;iJZ2(J-)ToxD9(h2a za986B?Pd?vMvbp5(R!>_KkS{?KG1 zExwhIPPsMgt{?cMy;J8Fb1GHgBmCYRQ}H$G+^%}=pNvd9X|AQ&2Qo;hsSH=;OKgXf z{M=%6gt+~y-Lt&Y*!kv4ah3C(sUBRcDf|93S>`O0K9<);{>3ax77K^NWiK3--UWK~ z?!<1(!MgI@K6V8mrh57t=EiR6Sg;^^J@*dcSz?*`kU4kVhJ3JzROuRA^iYX^_&}Do z9<3q_+0Pw|9Th0Vqaxt2*$RK*)=Ip- zzPq7J2+`&ENH-k@c3sZseD!kc7W&CE9+xxn=Q*c0vpsckTtz0|t)$MCDo{cP4DPIl z%}DTIAgW2tPkVF4l^A;Mh?OG_geEl!G7 zUfyEt5FxC^Rd1q2=m&1$A1Fnxdq?c6^RhH>#T6vz_SodXSa>F}a(yo4<2>@-r5QjZKX|7-eh0;f<$;5(=Ah zl2W=AJ5_~BuW^4KENo3RDXBeXiQhwXz@E+65WE_G4W}}8p^MfbNC&`F+1AB*9cqAu zM=(sh8}bUK7C?eXBM;HJ_xT!7GSjRNQ1ONaIzK||P*R2(X7homq9oE6`uDa?vgp#& zHSmV}rqqMdHqmeHKf`8q*ZeeEj6Pxr8I+N$PJyrQ{3?grKgv4CxlHDmO&3(UE$@a9 zcXg;#JgFr6R%wjiZ#%K22gl|U%dh1r$RYHX2!2%lYojUYYpI)fYcZ90f~7lW9C`>l zGVdx*?C77EW&ED@ZKmlTx9T=>lAMUuS>g1~8c5~Ld4D>E-R^CAg9}SeKXb1uaE%kI zTa(RbEmd?gA)UR7rB*bzyTP$uuOyV5tBHCmVQB2Y!xZ7%=-t((kNQ5yi%IhhJMT*O zSV!~TrZ#;FFtG2R*a+_1HnB##{gWwt6#BDYYWo35qHipbeVDVyf4}LEnO7OH=k%kyb%p!jQUs*iuIvr88qz_ zHse?nV}XBn+r+va0iewcF0fNdDt%Wb?rR;ezXx8yzXF^rfNlHN>bo=_iV&AHvs`d`DIS~{d zw9*ycSr|>6;f`!-ifi4JT(Zh^$JUW6kZLi}->m3>WM0{))a*>Fc{b6rXDvBfFtKg5g?W zqh&Lj`cNW3nG3=+hQ|H0@3J*AW}0CQEZJVa-h7aX);#O2aYVl|vs%8P(V2-a>%XJG z@x8HDaszfDx1^}k*{`Cn>O>|k^TYHlnE@1;#Xfu6PYptinCcPY_j+Q;hC47DeWy zPFaNN!qKhZ^By$Le9YJJ(N3JdHI$6t>;P^NF?x=DZ=6>l+l`x26LtM>9hQ9kMSld7 zfPq<3tu5v0nTic>=L2{Oe~GFbxSIM%xq2#qK0+`foQlV8cc1*byuy;q#-ihX`3!DO zGKJ?XTaSZC1yZXDQ7V=`9=hp##~DOVsdm3E+tIJNthL=N1}D#ndEOwB$#e1{=%{2{ zCRC2#&IyIJAhHlamlA8iG1NJ7hN6^$Tb8#6K&F&7bULPx8w2%xsU*7U=hoKdc_lw< z_Uz+w8AcgLA>JN_iPc6d=*w8+#MiS4i|)W_*QhWGn`@Q&QgAnuBDWN8L*!-cRyk>&Ybs&J^8HBL1T^OWZhecDG?RsZ$eA?A~< zNlEAxEhixy;x}>?vdT3bBnGHHknAQM1kl8Ida)+S!I>b{(XS7xINaGm=s927DS!%Dus&W=Lor%01 z2jMH4&$iQ|y}yEX4QX*>tqNPhncGV{zktc;T=`4BZ?-c*-m2f0iBdeocrSU@%>c;P z<|gyn*wgY_;~w>^t6k58Wxko!?doGu4DJiy$VxbwVAv_(O)987?L|a;KV)C1Ijl9< z+!lYubSL0!(R559f3`bBFLw7huzc_FIO}c^?U|9Sf=2^+sDiOplXglQR>@SR z7fr`dA_?EPy_lpZe$Moh8VcX}2Q}0-Ykz&(^hLzHal74QdgSHFxS?~6LEu)vQ{4lv zqY|PwMIRhB@HMRU*k&D9l;kZFh}dn&Le61x;~?crjEw2yN4j(1U8?{zltLRxotosg zAuO~mI`(L%W9We$Ekg~r`x>i-k&idMxWvt~74|mIN6ACIYQ6wxlQ6q_me!V388%su zXprylFW-n61FYB#FTMI-+7{Grj$~`$9L>J3Ha?u_= z^ImRs)hRs*o#)EOk1HnAh;&URY4O#li$>kNmO0=Zis90a21-LS%-h&0Q{f$DLm_O) zggB#)?<(X=E<uSVnzn0e*w>m>`~?In&>{2|8W#}*M|24MP>EXP(E{w5u8uQ zw2pMzu*6oS)#~FDuOANy9p+^Z+^1Z@WJ<+c>L)m&p|xiR>NXS1WYtJLnL<-Nzm#xd zWK61yH6tg4tIcF8Yze=fH!2m~sW10ULh>N8A0n!62*Rr8BWP8+W~`Y7QBti^%{GJD z;7*{=SM#dzo~F>Q2QkLUR#8YW6N; zT^h?5MQh#DEewPK+Uvc9MpOH4-DY@5gycdNq+8n0>i-g~Nu_j;rL{f|1s%VT5X&u# zlz!6Eb%Va6%@5Hj(~zCg@ay*rdrvw(f)&=(il**OPv$bxNZqde!fE~oj56Is)$u_v zj@EYH(Ij$a!%JSFr23&r_qBlB4$d0@`D@4EJ&~)X@Q`F~Zl3&WRDa9s=B@*A6s!$- zhYjt0ZCr)zlQ~_*w-a+VhfL!iUOz(fLQh#Cq6Or1EVfsc#6lor`C@(nA zC_x5wS2}9hBB*#_(z}n`4W5%sv_;;^@98TNX1Rv0Hp^ZOPwihuL$0f|kKs3lR96&_ z!-&4IjISXnyvDix9CQCOP-SS|@s~zezY6NVGhAcF&HT$gLZb>F^fr8L$lX<1#FZ~1 z=8W^=b!F4b6x>jn%;UVT>tP75&k#`c@H<3%<5Wj%^R5tFDX1JWG86n=6fh<^v08!n5Pt z=9uj@%(=N@%H$pqfB;sR?UIh*3B{zc*?M{orurnA)Ol%$zgv&fO!-StZaFP_FF9+R zu)YAFxKo4D$z=3F=zI3jz%v1lU?j#$a}#{}RT*g{!pF37d@RXI;&2ah(^;QszjHQtb>aB3N$`YUgke!{T&M7Rvt}th z-UVa>o|wrjO|-+vTg5Jn)@8)LQOm-&JLY=B21dHT@Q&cQcqm5;OvQ7AS~!2-UF*|8 zKyGzybrdXXm7uN%VnWZzPhIK?DLv?+_*V^k!Swem?HM>=t!mt@(2Ixi@@oUdWfGPk z@{}YW^kjD=;r0RJ?Z*l&fC-;NP=TtdZ5D-RYAR}h)XH|!N^D!KxieeM#p~16N0Cn) ziaD>T94CQ1tH6#GIiXG1251y~`TVh}o5{KcG+Kg07lws$EUiKMkGG+&ixx~`<(2N8@?lx;~onS59hxbRo)Eo z2Qeo25n-|2f8)A>wr|?7@48KQLt)P;ECfrju!k8Bl>}KMI-6@QpP4+GZc`G=pe6=} zdAXqy)WG4_P(pppJeJ01Gc;fNa<4ipQS*_O14Rpxj4Gb_e+vRAl&tN`n3((Amn|Z! z^<$I&_2lthz26ufXu1KuF1O*4ea4To3Gt~Av z?9GW(?&?LYa+y7jT>8L;b={;n;$RUhMi^e9a>HnK>oj%iVbbJnN30xwexA0|394jPi)4-%=*8wItFG|7KZ-`>s~*kS0` z@q@awAm9delJ?P<`R(1(_T%?!+1`TL--6iK0JLy$1AicaI>7*nrnmS~{)|}sfY%VtA_YkxTpk_% z)i(HbU*Bes`pxdZ`zR>KW*K*=-sto&hXI5gAOfSLNx2ndHSd?f!w ztnm@Z2wYv^;o(`Cz|~mmqgvLn(EPz641wnXI)QYy15*9@$bprovHks&jD!k+%{TnD z{~XN&Yw&SRY5DuB25^l5ot=GT9Gsd#IstUuz|AMA0F`t6WBov>eo*^?-oNYtvaPfK zXx`jj@k01x{YbMk)ctX?r?GqZV^;yF;&~AADT{`|9)jxurm<=MAefunK>JR!Ipw`6jz@o0^MCh}Q=I&mkN{K8pA# z;-TjcU$%SJ|9Z8##OlL}=KSJO#}^ha;W1NfWv@45@y*!syO;ME>PVCQtXKIV{L_Mh zg#4ud0Gz=9cxbHG|JM1ZrXb(TlAhq7sKEK~$m)^%FH^wg;f+DPe*_*JSe(Ft@M&%N z`SSd@e$fl;9f7C?&=CAN<}r`MALU-unC36(zCHhF@#Xse%RN6FfY^WEzuiopE9s@` zi+a}h4*YZ(x&pdmd!wnJ_LBdToV~$aL*5&loPyRnKK%DOI6B+`zU!d-{%VR$!9Kg< z{7xphGy?zw{aU^}W&bQTe(YfBe|hlj0RFV3K))-s@%bZ~uJP3{;>qR}VL=+|KcravHd_AD*}US3Y9r{*B|2yjt)vPJJqo&aU#Jd2 z-|c&4OGxIQqE3!L>!rR8K9L`s0M<=@1-t=VOa2G} zaRItk`Oa6$p7e;v;q}?Rz##$FXZ{2N0bHa02zS-;K-Yg$ZvCjax&73!v41E2jQpsUMFCs?e}AQnq0d1?{bYezJtH~%r*JMK>;2{*0Gbssq% zb;aY`z%F`IfkG=&wo_Z+v+%0xk_p*3|Djp;9X1}(aQ%i}*xgC*s1Y|HvFG1$m5CTD zwT7mp{^YHN#mxO;4Ws^}$D3y?LA0}`oQ-N=4aCpWIyOCPSp*DBzlMT==#f!;BuEJR zqJiL6DdQGDA2lKdo+SdgE6-ooYd55h=>eV3I0M?iPT`=fxo*XR?v0YM}n+T_lryF$-*elbHU)Xg#i~2;Y zhvhP?aiosiQy9LOkPOa}$zBnQ|UH}&1K zfHQWwPfwRHBWYtIuQU11B1g;V`R$bQoN0ZQJ0*=N$q10irAe~q zvbsi@qGJU??=)!b1~LKFB{>=`;~_**x&jwM`UK(KIF>$sx{Qj~jj~P)I)md)79v&1 zh4K{NqmS8!Q8a1;JHE1a;Z@itm#@6)C^0H?*HzW$)egM{(lwpH%W{i3OBKF+6l3|* zOX^Cpa6EyUTOtR695vt5(<*zaKw2zZrk9}#mnXVvo1jmL2a_s#mHSGkva(Q9WsPQ- zg~%D~GjGp)$0*`_RGm~q%$kex?=@HXUzip`69S6aMIT!c&VFg$9r=>j3Zp+|9=i`V zWa?b|I%;@GAT(S!hA=>)oArU}TrS9@Tky4YB9`_uk+HgQR?oT3LE;f>zG?E0m(MbH z1MhFdl%<}x<4<|67FGtOT5BoAVPHrvym2-rglGlR6zg7Z8jtuegm;4kU^2wE`*W^W zb>d}AI|i0oS-%SR2mm0^6t*_f*H@C7`oa~S3L0TvVw#$-s{bPE(j#^Toyhpl#-;)6 zhlP)K>j^{|_JE&j%{qcQYAK9MER@W!027w*uVO7SQlGTUjMM}-w4pQ_jib}|qKm-m zFG=sY2T(>60kzLjUtdBqPGZu9k5Q@4;xcV%;=5r%P+JVh&i^#tt{!-0j|L9?pGJgXq)lT%V=HD)oWb)vwS)a8{NXoBT&tK`0KSh_y$!ub^ zM07EEFYlj@yjuz;qzVXR#FjDf;%3A02Ph;2mDJ7VyqD(P4{6n3m0ItaZg}Nn$UUJX z(`f1#joUJuof$Hps*#HWX2B3QKS`v&^LwUtZbd}y?z&s4^X500KR4BN%k@ZICzU@5 z63nQPP1i@2$1|08IE&2ZU=Rx%6FBk3cLbGSXhxhxxAYcLL!OqVrs(nHNz0*Bh+|HU zL~!zIXb&7Fd|5SsCW#C(q`p!WAXdi5#;BeZw3!g5LPD!9prANmFusVMLKf~~@q}(c z@`kMVs_|%^ef?GuSp=6x@lo#aFt&E1M}VpG_8x`hhrl0iA(QkFoLeEbXss!NxtaE8 zoBf+A3|}cF_uNSuF{1VfWpGb>r~heHtzSXp;Dk;V)NV7O9qcH{ZZ0;C?2+tC(jvn} z%Is)%S{u1toO!u9k;O?S{8Lh5NMLQWXs8k_;~uI9~wIm$c7C4yk%8(N}G9;(-QWet>6m z)trLgh*>J7aoH^(=wZVerd7PJwMvyb4R@N_9fhyXn77sh^V45r6EUv$9g1R8cEC4Q z$FUB|sLH!0+>%XMJOo9k&TzSC2xuMOtz)yQf31D*gd@fM6aHdd6bES8cd8xLEqX55 zH2KM>mGPll9yIT2OMpS^{TB2sdvo0RtzAr~Ybkba3ES)1sm8k*0oUW`bzI`oX%BlS zhwgZx@_jV#Gj>hResH_%&JFS}aJ&o*S)9I9pYI8zfJKaWi2#Y+N&%?lYT1(;8>@o& zhNKDWvKQJ!>dcW8#t9onEdDn)kJKtM(g_4dic<(wfZp?@;*Lj@;2<73PhU!_9%|9C zUg0NXaHyjWntb|rqO{nvkdMWvhpOI8GY5SjBwg&xJ}_r(FN&F}YL-$gjOQYwVx8%c z0QKp(tN+fSt{jwQkMOsv7%l1Naeb7aU*%ZrNi(Pp)iqmfvU93tUc6#^dgkUuMgOki z);au4@MuOhKxO=>CcA;8R?^NYO>^Rpi>C8_nd@V{_+*7VU1(`-)5WM$%c1d^qaLmU z*%T8CVbc+j>Qb?|AXv18yj>E~mj52%@YB3z1Y2}}=3SeavKN*{R1Mws`>hAz_s>8F zGzPcRo1#QbF5}F7FX2Dah;_0NOH~`y?zx39BCutL%pQ-+GFlfOB&B)*mZh&@_Vpr? z96p=`p2?69+mUjhQPrC{Heg0bSj~h_g*R_|K|-_%OA8taf$+Cw%O{u!RfVc1EB8J@ zAVNCD9cc_Y5Ly~Ri)hZN%-=1gdIEx4oB*mj2SL@{BC<4BS|2p~M34OD?WaT38g0BW zk+ZQBoZxKYW&?f{LOqdD7fCfj=!qzn65`xBEfY0?0AVOabWj_JChER zQh}QwMt1O%_16eu9XN!-Xz0c}ExT)NbVJt&-sg$aJYw=%v%%m2=M;&Z z7X6e8rvq~aIH2%psDJKkL%==2Zw|sUfK**;q)_I4KieO_Q62m8Pn$WBq8(D^R7f~s zgcG9@d|RqpV|u4RJ({2wiM$KcmhZNGpb7`)qMQ?L8cg%t3JZW_v1-N2?MVz8&y8)Kbz&W-mWc$v_)ufPGYJ>DvnF94ig8vYO ziCtT+u-19>yOEHJc_FIzjr&GM-s&HX5$YAAcbUx+3u_M>>L|n2(#1h-TR!#LF=ULg z3;*zbobDrq<6qJ@d+?!9KR+%{b09~V?1BW*st~>lpR-XLVFGfkeS{p18rE5CHSime z6ifYbE>`S97gO*a&RoGrS1vU>^ZEhm1{UhguQZ`Lzw_Fnl|%&)#C1Pwo0*A$g4oD_ zbsja(4c8y7~ztv)m)?B+Sz1@jOnsUCoArTqVFlYKbK3h5CwluRI6V? z615P+h~Rk*Ki}m>FZeJi(Kek=K(iatv6FH!v6Vr{8;{OSA3N$+H8&2b!vFq@eAz+4 zjl~>sz>|Y?!kxy&ncYY13X6Q+NS8ow!{4ZGt!AfUgxYq0Md*=;O-PKk@S7I-F3rUa z_lmG`Pmix~M@+JV1IkC;_=AKpo%MPB;U*#UmJ_Pm&hNM4~?8SN~$ zlQ!)5-HE)VNkxbA#IQe=Z>Il4Mb~YNUBpD&$lM=9rGUaz`ez zA&=}Hy`$I-OO`O#B%^NTJV^>%Z!H>|0=t4ubD&c{rUPv6=Hpt;k|Zc-8oHb%((|J$ zm7Cbqh}N;g{X#Jz`bxF*?h5iy3>+2QA-iT8bV^IE-zd8oGCrPpLqb7jPyBCa7|+lV zZV$~sSq(;57E^HzdFOl=wj)b45|z`)#Ggh`&RMTH(7w{dZdlZbZyOt;;x5wtr_3`R4x|0 zM|vOLf0lLO8;A%Ab};rGtA;rm)}^Z+?`#Ze-5I^r&+$i9Dq`vNBBYm(QtwdqxAx9K zuY8+M=OF#>c`SCXAdoK0G;@N>9Y0T#Rv$7mPAf^NbkCWkD4)0pM%<K~VrMO?mBr z$ZOavubjx7&~wA9EK4bFSKr_^6b~ywcICd$7ZejEGG%oRJDcb=tVful zYx~4afJ-l1weW1cat6*v01ofHI|WSInZDg-as}JW=_X{UC=xUJyaqZl)^(+=T9RDeBiZ%;M$N?j9jOPva^Ke1E=|hu)kz6=XL83;yWzHE z5Ck@cBRd(S`C#Jy?>ibBelGi zLm?3Na#6tys?gXpvG2zFT2oE`$!H&Rwe7qi|4Fuqt^;h#1Ot#G4&=R zC?yfpxb&4C{s<=9a&zLt)!|vlP_-TghNDtDIDgSjYc)Y)I=3gHow}d`)zw5=&u5WQ z<=y~reP~qty_?wm!VKun6i`BRAs!fa3|`a_MXB+#Va#C_xZL6m%fR zfz9!Ahekq}P|qXEhHuQZ_m4AG=PRn{r561RH#;s1MNe zV>j-nsN-!rRm;ub=JHP-Ih_zIZ#e?8k6yr-1;+`;91NbGiKfVT57G<6_;1M!I=HE7 zA(jrRPh~IY@qF8A2Yjf0*M|ycmnyhhN<;Zyb!r9D+IhSS{Z!yxw+^69{Pl6TSAho) zZbq29thxm<<;d8DVbvZ=&j`$#uEEI{ls2!r^~Wf+ocvlE5J$;k3*qZIm#t&GJcb3d z@@Dt8Wq=Q3`bwU%rYa8=MdyR!dv)$}Xtfk9W-4@~s&HN3OsD{oMoJ;3ZQwtmtMtc` zSpLBWoEboIQ!02Ain?q>QsL3kIi$ea(-# zh)M%){pOabyhwuklA3 zc<=(3yJGl#RL*mqO_=Ef$k0j^maky5|9V$IXu!;Er6_5r7sLBzO5D^bU(hq0o=f1| z49ASCH@@l9`D#`m29(Hez{444##QqthiQ=PJ|LtR0d7ucp0NSesWqSxy+NHWp824Q zaTaN@BMuBVn2pgM)Y}(uJFol@1c2L ziwcS;<0Q39<{;E|sGr5Y4AT3o9g5sg>YZrDL^^vtjH0z#f!ts_Y2|dHCJu+!-W%*e z^|8r56E@#k@~CMGJn|MZ!yFq^$8vwZ;CW!xPa*X@sGj8Wyt5dXFTTh1iFV`PVyQEF zfkaVM5!o=e^0iaS=1d&<$-#B>IdFV0W;D zJMPd2^FrX{h;fb=Be1aAOEme=<6XIkd-S83c>CwXKb~n<5Wo>J{K?_9lSt*-1hJIDEr|?9t6=Owh~E>FP+^m8#FcQ0?TmAt9Zer= z+a9HZwIo`1#vwNdNS|}cZCdnT+X9y!8%G*-Il~!~a%(8L#b;uMy=C-pCm2P+OtjyO z?J!GHO&fh$d&nLkHifefO(jBPf!!g=2GB-{W$`vC)C_C=SogOo^K~*Z|C|Z^0oF$9bcP!{$1AQj9c)Q}J)J_*|0(Uj@}GI7M=oEfi1q|B(Wk5-?Cn z|EwuE3^llK=6L6>|DMj>25E5?U$sGc13?p9nDKk4vSqYM_P!UZ*jyOp4M$F=bv5Bl z(t|7xKFMOj9S6lC#pH54+3WKe;JI>KwCa!XM#kne`+|9iaYJwGaLIkn0Ag7Cgn~VTy;d*3!2he%j)y<>Sg;)Z z-uhvXA#fk1-5#7Zcaiz?T8%45N6;`8$^%n2H%E_3Ta*tue3;|nkeXPkaZb(%j?SW9 z2J6S{rcd~mWvtm`-wnQ70Xr&Wq?mqm5D9cf%OH!iCw`)R26@3HnyZBJc@t7QSXYt* zVYbsg8D`f=?cF-lP?<#EiM;rGB<(Qfg6O)8*IDx0q&m6H_S8!oF3k+r+b`Be=kGDN zk~MT41(K8YE!yfj9wx-=8DPg{M_U((ts<=>Pk~kvQqTDikQW$H8|qf5HGq{WvDKY@ z=5J%4*BpJ^1X%LO-k3Clt{Q}5B^*y1rBz=>Di5hDT9LiFWoNBC@L!2K5!&wSNSIKO?- zX_xGmxHL$V1uf=X$a`!>G8f2Eqy6K+lN@tQiP^zf-K|UYG9~&IiK1MPM^w_ZmmNV9 zW`wTe*r`OdjqUYEEFPk#n;H+u7D_S_R%~OhH653J3gj|hu<>Pec_60Rhg2qV9Y1^b@n5O_PO3` z7DpRMLzWiB1r)+2Rh%*cldO@nGRiCqjSNiU8RK#t*{n6urv$Y{$IO zH5-I6@^fy(>-6b*GJScY8hj^lpC4ivq65guVV~jWabgB1`di85(Yh2Z$&E2R2yryF z?z?+)kQKR#odrpxw|H2I76W1<*QX_vRqiX{Oowm9iE0A?=j5Tg0wv*s@S+11WdV`m zz-d)cX58w*c4GFnXe5>dmehcLlR*c^bVl`Dj0_GW1d_yM> z9n72p`7w(S`ZjP)5MBJQ!}Tf;^Yig0-EXG`furzs*Z+-naR___{^hyro(*vu?w%{( zz8XfgU1*#{*yt>`f}G43)ySX{H*Gx1TFpO-ML-1l)(sEX>O;Q%u7=BLeGIbuIznT1 zb!~%ptU7_5)9-|hY16#)8zZMbCM{3uD}pi+w^FW+nkSP~b`7zEzyOuvw3Ak|;GX7_ z7)U%MqTJt#v-AG#9U`$?4Moys_CT~lwSp~25gyTPi(mlw!E>5E*pb*5`EM3_x3{nt zSyn4;L3SuLbswljoPXxuBQm!h4$NblPo5rZYMivlbf==ry`v6{>*@pPA=SWs*Tm`^ z{T1L9E3c(8FV7-^bZ5KGY7b9r=hQ5$8Z$9}y>5O+ANjf~PZmedx){}Fy|`W$EDqQ3 zRDxRmwgAg}x9b%9ze+NjK!5UT(YIbyWTyi%)W-&&1B91UY{5l5d>0ic?q`!Kaxi81GSqLQLTf^~SVZf^LpV zcrAn7G>VclnE-1}ySaPJPO%N@(K-Oy6uU3>o3leqB>kOm`BcNPn*EjQl`K|9cv#my z6CJ~%^DO2GKwf9I1|c|L!K3Rn_(-MC177u`iczG$+4qpLc{QuLYGtKJJ}8kVtu`_` zptlbwYIc&J7|$pU%;<#2Si5x2Y}e-?#}GOWa#X-hcC>V!sGcP!mTdB^Qj;FEr zhL-Q!1CYf&})^CaF?KTi|Ym-n12ar)$9-3Zf2Yv|2QA^7{Jl zk?XU{m>7k>H-;ClxClL6*7J}V8&zWrxX&fY9Y;KuF)jzyYIzxSw8*j~a;J!OEXSQ^ zT+@#00_L&kp*C>vEuGD=;(RRGL4HLZ6f}$?Ru@%`Z&v=U%c?aQ=i6oPgU5+>fOBpq zQ6uxhKQ!6nZaW_UK*+$XMaEXSU2_DpseQ+UB9oXKf&aPH5#D*eNB+^Bs^9%;C%zR4dhn; zNX@+~ZfHWvq(Di2X|qDkni}n5Dv9ioJuMjRWu_tc{1`uun4BYuj0aO0+l1Y!gNMsB z(7AeJ|1|CBYoW)UkgwcD-2OL#ZG|I>$m<96zv!kM@@p}-W?qLnJsbSg;qQO1a6 zj(zxzc54I2wBRo3`8g8>{M-7>2zyD^Y9xa+l$awe&i}&FMKZ(o>j_M`zd}@OdT~Vb z<5^j5o#KZC|3em&rYM1zkPdw%hbL4|I-qqVjSb&AwLyV?Lrn+(A)E!5e!|?kd5}or zqToPuo#tu|jqc!5_r|uQz38Wf^OIwP0x>)5*kUB8tlU(bgBbiRxTzysl&eXUA7ekp`BDbf_q_tDLyHVfrdrb>jPV-OdGMJJu=fY+&5k=t6n%OOmm zvojM^dfcVHnz4V7(|*hcgw2iD9sUVk75_Z9V)o^D{YT_wc&aq1ELLGrKP^Nsp_vGm z=TRas=7n;se%>)wQ=llImq1O%k`(N-zJn%avf=~31%(wET*3lqKq9d`%W7!kHN(czGw%@CIgv=2{tyKE z=)IHA5eot;+cRzLI2hjG1u&N;sfQ1RhjA$C*(d`^vN2H5jd&`!vWwO<2U+9tjF}n* zVWnd6k*}v_)a}dG6ln^jZ+4MVrb$#ldp;AaF#@}ueAbm;OEY$t@e}~P8wE5rI61vH zYO&UYR)mJ!n03)h*le>&m7Rp_GCW_`^d%BO%}D)8$pD|oAYWpvwe_H;6M1oD{t-#7 zHHx7_m1YUvTv^n&sq`S*&5u+bP>new(Iv!qJ7LZzbN(Z(rtDXss?YEiTY!#2o-r8) zyu#h+@qNgaDz8BP{aI?fe(F{=4A1p?Bre3`Z{5yd!l7E|}X6LM(DckiJ)QMAyVI{lz9A*^^u1NozcE^gHJ< z#@=Rl?HpTs(}PW=tX^>YI}9HRDhabQ`OmXs;=ir!C7u!;)+mM#b~EB)WaSp{VoWq= zz3B!95v5Y45%{IbcN&bzg|-4he(AOIlIC3~JSk`OfZ^id{#V+y@V}#=5=)F(T0yLp zcpw1)zo%chYqE!j(`Gwn&OKa=xhVsYxaC(}!U`Y^5yR6i`HKHWViDU3fGkjjnuuLV zrwT;8m6`IPTYpN9W}8B-Cpj_jpz90K6Q%_02B`|qiAr(M4Jj}gkNHH+AjtvhxPQ&< z^EesoR^avLBqu;fyre1_yGKY8af~CQmIv}>_&LISqIs}Ic`_Lj0A(qeUFqE4WgJ4c zqUhxaA2FNf2(Q-``n|w9ptgO8_W!XbpYZX-ETT}|dmK`+(uf@|$FqHW1gMobR zy%&)1SUF&>zwk^X^DIJ%oQCi_;s}iA&H`}co=0Q@q@5{zmN+*|nKR2|{To56C2Fp` zEO)1CO>UbrACxL z@DR})`}!$f@6`8~ZqSM1p65Ft+@j=P0gPB%XKNorufvX$Gm(s(K>C3KFXT-YUktpr z;CgN+%iHkOC_&3x;zPb}+R%&SD)=S2QM?YTn}&?C9;&0hADB&OXV=yi+EzqC7d4bP zM_1vDGD-T`hMRhRwKn9`)mCEZn4ikv*Qcd5DeNvWL?nt!6zs2NqbdJys~WyX9oSMZ z{#3ZE{TvL|6_E!KZ;vqav23@Ik``LjlI#iW1RY2!#pnFk5|z+9%UfBdKIX8zMb+yR zBPGq70@DwqEMs@;Y#=ZtyR1?nWb?a?Jpc-wi{f0`t6u~7qw8*bd3lQfsO92;)njwhv_cIW&O^E!%<`MyF%N{(K!>>4SUEl!!d45VV9 zA`^tDt@(}{7b8K8nan!C(YFB0wac*?q=1y8myStQf3j-~sn+h`?ZIoafmE%A?7QhP zr^A)uzBnd#@be3)1y85d0nBA&g+LXO08b_lgi0O$bNZ&-h0pf~W!Ux{dHCY(n*7-c zNpOcC9J;EUAT;4X%?4N7iA^R!qd~lg1?`*EC#aB5u=2DGA#x2d=XC+SqfMumYU!yhV{+n%4HE`c!)C?|$y#z#8>8XiOo(lWa4)Ji){W;r$bs^KzI5wz++Bxm`%5$z zf2~hGbhS0+f<-H2e-1;<^z)tadwF~;lDP>{yJ08TQ?#c8%c^2|+wrO6_}k(Ww2r+H zwuD|AmmWEZ!;i7%?oG_8?YMke&n^ZfW{tx{PHDRThz!-y#EH(sr0kyvy(DDFAXnzq z*kCmrw!)p~&?6j~v_%?8e$(Y|N{naZv+zgr5JYlQYy zy%#K<>9v>yG)yp*;%Ytbft))5N$F?lkQ**ia}x)-q6uFQ)0N||JU%4Sh>D=e)m6B9 z9;NX++D;Q*YnO;@Gg2}NJD?cH?&Zzr$M76)fxMURL)OVKb{*&UIw+RT#T#4OA`>=uWl3LOGh_aw#3)pE4PoN{)yBVkI~C``oG>oqzKqeIs!R4y7bVZoJDQ(li^>HE9#pR+2QIx+@e;B#QLd@OZ+!(>F90X? z*oUu|=%~##2rHMcnT}UDgs%kdVgKns#7IjtQs!JKU;mMd} zGP(5p!0O|sO}olI$;PrOW5!I!_3yLl;ePb|J#*KrsFbj@4&L85z+lJ|%VPFySLL^ET^(?RPzv12;fg>!eY|)j^Ayrk% zaj@Q$QEgh{{KJuT)Y!%ZXmZvu14|IrENOTf2L&dNZi=UeFqWdP;+9aCRYBiva8yJy z$L;IVC!hpS=VzQASxAu<@1X9a3k_@)N8G}P>5**TMm0vL40y_qSy$>op!|G!q>UZs z`rz@NX(P2!nU*k&!Buelp%2bo&r?XABIj|d0RcLL>tWN)%!5x8Pg5RNuIEimq73y> zOxRb&_z$wAqP5g66a2QVi;WuKg#Sx3 zy@u*sEY*pn1*mzdj-^U-g|G8upbs``$|+6dVg2BjUF%rZr4)6RHjcy=J%~_=h^(T% zac{6CWE^;p`%)o6sW;tP=~oNYC4}}JFE^XNco8KodrNS5EjKsSC79;Ot%v=q+)h0# zM3Jj~CnIGMDZh_}qC?I=r<8tUhUkv^uVGd}-W{fN-qvY6GUt7ZmSF=1B*mlk=oipvk06g32rsf;lo0ECr=F zI|%2kVvotT^)QwmiwEy#$BENkwZ4yPEf0)16(kt}O}V895v)=@O;=$R zIqjpYBK%xhDJNO)-tX>QGhkVA^OI}jG>gpK6+N|Db`=>tp*<@dlq8vo6iWy}fIGn-k(zmX zT2IB#Vd)P3_36A_o$`VX{2ScQ7_LfuRoA7eaap<*x>q_nlq`ls_sxyDCf~uGO5RSg z*$x#Y5!WzU6#en>;55|B; zoT6J@aUy?C>pilf2qFZfK~nWJrzi}urn+XNiG;Z!0a29dVHxm?GM+AzP6=pKcbtI& zmr`ZLJ;kXhUi`WP6!SsImfV6Sn5!`1Vsm=apwhBm;Sfq97G(paMhHR=g>pV;cpcl^ zh}$$m@ojW~@uiCM*u=SUr1Pc7(nZB}97ha(jwUANk1--cheb{L(d5JQSR;zCZch~7 zNu!WT{w+Q4p2tIT=1Gd9BK;8Yy=nfsqd;oN2@!G_GbzZwrTE1fuO?A5g)MPT*Q4vx z<)SE_2HQ8k7p*p7Kre&3@!B{g(KI- zKR>*EdX8%R#>XAj>ia3?)mST>8~-g4EZjdjsd@OQZHO{g>NPV3Lvq%9t_5Bl|KvY!9^W-(4dLz!PU)Y1%iIb+p;o{2eLNp3_Yfi zuU0nc4Hr8((ol^KsK3!FjWWS{f-j2uPf`VhvWasg6Q+F0a&(fUSBwPxt%0#Eh;;^< z`-&a3&PhYrEut(AB>(Cs9@7LH_Uw$gFzV`p_?5Wok_=S7KX&!~W#_!2qr)0+HFvFx z&2;5*xX9!Kx>XTTmw8>>Fr_W3?p>64Wp$o-T#INvKsaK)y@=98`SAps8HQmqtQQSW zslq&z@)_D zl2->~#r&l*(=T3g7Dzswgo}c{PKK_=@#0=?_SI6;R`NoPL(3?7l(c^N!>7!2!H;T! zEH@Cel|2^S5-|+6MP63AL5{fo76OD#BkorD+G}*>#SrW-E9;W#f2ss3NwRlZ)MU(COJ$nLhj! zQTgiCT@*!HB@)oQkkm^Wntc2@v$;X$0^fnLSlwZN>NaLrc?qC9WwyI-+`tBZsWyVG z-cM6A4t4JI@auc^l#!kZ4F2i(JotL*K&5?Sui*IwxN_412fvH&`N|7+tiq|jyCLbk z2Jzbrmn#R3Ad?>oHudNsKtv4n=F`6M^>r(Okq%IMl!n$d_$zFzw^Pt6CB9KmTs(7V zadN1riS1P0Rj768q%uzd6!i9nc2-Y>;&)_^5ZOIi=n{-nr zq^hV&FiZA;fgOPr8@JrGHV%lBba7aPxzi;pAJ4NJdjMg4JL@G&nKe8K+Yjl=Grkk3 zFoF<(J-v-TMA!>??GrX-XFj8wj$mLZ1@{W-=I#lD@WG$Mq!7vu+iN)g>If8y|wv+MX^(g7QlT` z@vxJg4z_!mZbcQc7O(_hE7D5=3>x2Cz5a7Bedix3R0>35bx6l&^w1WG zx_Hz(L@Kn+e6(KB5Cs|Uy6sy-B%cvuljkuwk#=l*C?{8AUplNa{>!DZw~Ra_K(~I8 zhHF;BDMlWQg8R&;unnuS)Qp~qrxl`)-w-Lt{!kn6MlP&W-+!dim4=;y@`1^G`h zcLtn0Gg#DoKa(PexYR~mM*Fi1%(Lnb`7RvVKXo66!JW?!;m^(q!uB8Zdqih#iOVd? z9iv;Q=6Q|`Mn@^mU1Z+%%a*#v1lr@k40j3FZ#o7OE?6eFTwZLZULj_pQD1M~=~5*a?Zk$T;Zvi0C~kfu^U*J5hFt*eF+VXCD6aIH|iy z#9e+W415vG;X#mCjr~?2(aIw4xrU!^UlNy^O>^HkQB1Y&k`LUuu`Dty(rp?T3p1#{ zaj6yzm!=8TX(2BC%qZ`dEB&ie6|v^avAtt;UkbNKvs5C=m5D*qe)UV37?(MDlC*OH z7inR-gCVJnEqzTVc|lY6lI?d3-hBf^mIeJgwZ=kiR)>v{C=8Q=ze#a8c(T+w!eJ<(9XC19%Yx$Zi&AHp)o<|>~gzh_2+G5C#UjbSAud+`Fl@^FIrWTDc zO6yQ_z?g!vp%t{Doude7RFEePja(A72F@h13>hVs<1aiY-o=ads3lekiISj#{h8*= zrhA7_Q=FLML&mxyE|i=2I1gu3!fh$AlsS#P&62a|Ei z(W$vFz~nvEzsR$|5%+08cvcf-0!SV6Y5qSo&p>({>+8PSkqN z=g%bOyzrck9!rk!$#dO$&MW7V^WJ;Tj~`1~=aOf?@tjT`OVa!1xLn;QIpvnByzmsy zA5&)QTu*-9ZPDY}BkRqdH>&HbFL#GuwYkFM=CoF@t)RayX4Q@RZYuMAxEnkqfPVuB zOjc<88*?+;e~imNTbBP7m(c&h#cQ>hYRRfLKFy9qLIGm_>3Zcr++pnr0E<5^*ZiVy z^TR_k#%0Owf};EQVhL|US$$pc$=NsD&hD<6=hAk8UsHR{Dvg(~F13bMz1h5F&G>6| z@iUv4pY89J%G$4=1IpFsc1Vnua3=*f!_V4 zk@}YR5wi`kdrs`0_A%ofUyl&?xtF#|8+G>Uizlh{OwDY#uJfbsg9VVEc(?>3bfz072iiF)vGq(6;3LAL+VwD zqAaQP15Bd7xG$j6qG3@>Y7o%j$WMk{(kwkaVTkWi$llA?yT^vjB(7LVEI@=6-LQr3`uC9TUme4{}5s zW{$pRm}b!P+lSBEZwJe{!4rvYM7Y_NQv#IU7s|cCYfT66hG)9RxfVQ{r8>c4fzza@ zu>Qg25$8JQIOo4{>52gP!G($^m&Y{czj5*Ve{sRlKn%T3^RjXQV?UckgWk(~a) zg=A2&SMndYBn1B8GX8@LRVmj?9|PNo0HNufOHzn?Wb|+TXK#5tZ29o^kM(fR!I3{D%WOU}7_(5Af%T<)QzE7WV&;7Pg;3 z0DOE<&Mr=-hPF^1S+**&_WKM7UB~Jk@X71IL-_wwT#~Jt)Foutkt7u$!oJ=gv5~9P zcoAfCb|yP-p`D-4UAgB}TUwAGN7piW-BY{&BwjpUp=@pa)%CQr;pWl)p@oN+zka2g zy2Z`ld5vu6&*RPRXl65y9u;?k9~tJmV#}{UzKgG|uk0jQWoW)N{j&pw7G$_PZ(bbS z(-G$*fhSaxq=%8G<96%ZG>^k9Zi6i~%@u=aXO=E0!v)37e7nl8im=Okx_`jJsk3vU z$#%sT-}%V{-@NuGj82Pg?O_TxC+sVcg->K5wY$N0%dhUec7Aj2>8G~P{?wLgwWJ_VJpA zj;}cI#Rtj2F#D{4VjKc_8R5L~00NOWlw{y_0C|w38~}?5ZQv*Y{XVET>fj9q?90^vepl$(0E`hdQ6(#E0#{Sefv^q)Gyuv1N5U-g=qe-?mTqcYK|}s6!Vyj>abxQm5kO5n<5uN8c7G_)a&_zCWK88rBB0O0ul4Zwumz5qh!JGB}7?*w2&ywy+$!l_k_ z{W?jMf+f8^yoQvzm}t(!YxfFpW~A|-Fm-izb$3Dj53e0Lm!-=~5nksf!4TCH;%>2;Gj=Uc=3_9^j@6tD+Mu2e;farj;D|a^XWF=W!q#|STauW zg-R?o+(+EA=Cj&_RXiYKLQU1wfyapMiQ#IHv5o6{gG^cPlY+kqvizG9_p|H#1oed3@7q5S) zZF{VHZ2lbj45f(HN7`s_btP_=UceKxyXx?bq|V=t1A^UV01)F4D98@tNdORtzMv!m zYXHoGnBV|dg>M2w3G5kB^2Boq5b4rEuwnufNecrkDOgnY?&<)h5%QMM`G6TRt}?cd zlKhGViC$zzVqj@M5yg-*rX%im5Ccs6dF|(8AO|>I;YJ4>z*w2^LMKQ7T(PHZeRZyF z_-Z;nTFz^y9hwBN!eA&l+nr8tIgRu!4H0I1I>jz%XJ>a4C`!0iUMW(WDM*%RAm|xd z2>94hyzQL_=buS+-nuz|j?Z>*T#K%?5w70bBXqOg(m2W}jfIyJRvf{)@604l)Q3kL zv`x3wBc0>W!&mUg`IdgG_z!>9%(9p0Nf|x0-Z0(-a|i**m!~Ss#w*d6=h05_g8wrB zIZY6LmY5&&R4>Kmee}5CJuXNe^OiT#=ew!XLHc4~J(EN)$q||Q4-*CYNMCEMA}y7Q zdT-mfC|v3;WDW#p%iDD8<=li(d@fKU_fe%SL~rmF#342R1^~|g5CC?Tf6in0*M8~$ z%8QHt>6Z#faNeHJZ;Ag|Uf7UV*gTmb{m2Wex1&u|vxKkBroJuRWt8K@@-Y43q!JwS zck-us)}dvX3%)Ir%yuk18c${P5ob%W|Y4?T6)YnDbj4dO^Khgz8oR&eGhHavg%9M7hhuO*=so)PZoKB zw+2l{#hk05%kQ;YV|AzQV6{mtamx&+!+|QOvX*ad>S=cBJ(&h$uaUI(KB#H!ANF+l zsP6+3vNXvvx2P2ss5GV)_0fvEXd6Ie!m=T4w83pdh^RDhDfM+6iZup~butX;MHYjg zUK9@sQRj4OD`f=fagmWd9aja}VbC-O7Br-Bzetzz1Hyt?Z=!FoI0|q%9As7>+b%Aa zg-TK8A4!lMqv40k@#z_+KRAXwJ|p;@?l!PI`aKZ{r-gchc*j6AkkH?P?|UC%Rz2g( z4>;hNg46_8@*GBq^4o!O7PLkjw>^$HT)?e85T`T4clG0IH*d$3&p532B@FKNo{|IY zu-}S{tS1AI`)_cSmc!eE=xQJnS=SYD#62mzVIp#7xgoKk4=^vswZ}SPq%HaHj zK45&2=1;Gb9Dmv+mHuNf$y{vIAAylR6BGF(FfN=6k#ez%ee6(7MFr#9J={NjM1t=$ z_;79mpnt~Bkz~}5vbeL(aXGm!GXIekcb@b0Gl_COIS-pZV!|iq&(9a@$C9N#KmACJ zf9Q;Np5o18N>o1i@&`{T^A&FA9-n9Fk&R&Yhqp7-bN%?HeR}+3neRm-^>17G z<#n@IcbdcYuWGj3k9Be6cZ@HL{dIZ$Q29%JpE2b3yFD%NhxZ;hN%^ChOD@9z~_n z10Gk|-*JaI(C(p88G91EF^B!yZxCk;)G27+^0{@pPg*uedFx(pKRqHl!fs9VX;O{8 zsA=)!7q}fibSC{}e6vDtRX4vSX=!ySGFcza56Prx)G{ zp=5U=Jzd}V@ZdM-? z>p&EMDj=&!0ie489zB4&fFRoifO$Dqo>Aa+V0DDOfU}DL$xT`q0E@j$y8sHjL?v1# z7>f)#13}{DN;>&1NtARcs7zGTvt@>a!K$60gEXOyiyIO*b$JHVU{(OL19SkbtN`G0 z)Aa%;`*kO?YSOgGyMP|Kqz`GE%8!R4 z>V@_hB?H|#R@F77o1ZP&bfL3a`LQY_8UXa=ly;Oy#Of%i!S)nKiT1rpTHDZ=B+>;A zED5n%%|9MToodFC%{r+=$Rh)=6BB<)EefDby1oXkCB8nB>*y}w?diBMH*KK zYhen%@)Uxw4=_uOo8Nm)+P!>9V2svXqV7#<{_-Eoz&KRNsx=IWysjOlLDlcT%A(Cp z1(rYO0Aru<#XZ}Q#$EignJQz`W-oo4aYsFFUM)4bPuC3uF0SPXeBU0Wb`xh@&BD=| za1GLVxT@~*syoG{;AarG7magUpW>ty>quue#i%<1JF=_%eS}G04!5I_{CVyA)Wg2^ z-97pBtoqc`vi7}g`u)!J&Odtbo!9UkH2non_RgQQ_DyK=9Y*%v!|0h((m5s3l4ZyG z)pkJH-i5v8nK7RzbdB1D;z1nBxSjK7;447)LEL`t@pfn>PWG0+M&k_c-@wfHAHvMe z`mZqmTkZ3|D&K!=pL+zIW?qD;=-iR(HTi+9xYS1p^~>ehMPl>Xr^TF(`PhcsOk)@K z)Rw=m2AN-}P07`vOAE-}r|V9(-fp?ocdE+I@Nk`0XBViUFo2t!~ zneJ}>(o?k6Gb0DvfnW!7MtxKr&bZlM`k6td2llLbjQ05A6Gbziw^SSBIkB1ZZkb10 zV$Rd(HhL&gqijq5)|8j4S6~)rc|MVG^S4A96RSf^g1@BodkdIU(%J*5ba0gWhURz> z>ExQ|TYpXrG-Q}r_J!I4#o&26a`ru7VM=@qRKB)c(64l+>S7A(lXwJa%HhCt6m1aX zDfEb9PeEci@>ieRvM!zje~RBT38G{m{vFLB^P%S`^WlX23!w7masaYkkU}doAgoRW zN<9h93uNuDOh}_zK{LDq)=?ZCP~M zDl!=una(0_fR_eVJXmvTHW`W*l1WG%?QV)MVL5w^E; zF|~7XCSdwONr`}7*3`t(P{`hcK>O#Jfq<2hm5zy>jevuNk&c6tK$n1C!O-bvJ;BdO z^?$8bGIh3hbuu<}CSdtT_SerpsCYX3M1?6Bnw$Qkewx~u{3BBAAFKa^XfXmtMo#vB zD!bL{+VTftD1I}wH`=yMm`8qsXTlRgq;9IVO^W&{s-{T5cF5eTW{vzk<~#=sY{(E0 zgox%oN0ZOl6YgZs%n1fB#1ZilSSc3$2nRfxc4qoLdnTaQbjZ)%XAKhu$Iu6+wCM3yY`(*i9gtDFmFv2PkCiPO? zB|WBrMU|>+$*#$@jhx6_pDNASzDkz92Wmfe0y6g{lM)&FwNY&E&8<9bc^o%<bW8yPgbQl=!e?3=B3RgRV#98UPyAK5a2H``BXbn#I= z?#1=g?9R!qGw#HLLyM;|JYkXT7prs3iS%X;h3ArXm;pV{cabqr!#qix!InhGN58As zi%VxV(?uICw^q;_D6+%w5wDO8Ys4(8h&EZ1Dq=|(dj}Wpt^Uqt=^OS(nyRy3y_-+8 z*x4FHYUDtOV{sV_J~0KV5(uAW*6STjykRlz_a0>rutipw_rf!V7liSF)21PZko*+~ zU004qT_b*RjPa#dZ=h782iJmSFh7n`Xaf;^qwRO)M^!iv;=4Ac%IkWG31oXoK)|oY zSr9cVvL~Kepx@}U$ECPu-jHQ;j4s)#JM3nCTu*-o!=R)I-INe1L+^=_5p=*J&)?GB z!{3a!S+uKuIhv4}UF^|WNA>qYr&Ikg+x4H`)YE0?X9>Y$Yx2jXfyIhuM{I!0R+27Mrz1V*IdG3Gi1n?>`g+ELwyz0 z?6=ceju=U(06*pMNaIKR@F+3J{5CsKp?()4HYpM$Q5cUN0I6B%9w%OuL+4=}Bsxcb zz$4JL?bS}S4uM4?LYp;ac$~@S+(W5fac(|}Naz`%m7WP7s@}7%tAJJe=b>HKVXx5~ zi?CektJiDYbVq;b*_#Qv^zVk%pLx!$fHxlx>+VNXT1erPZ}X0KkM~FIJ$6H2xH?%O zB(>ZP;W%TzP4*&2Wn1&M4Ag>B9$OZ7o0Zw0;k&WzLl0rpYZt;%`kH`Ddvu`!M2f>{07XPdN{Neq=6&tG^Zs4?=xe?FHs$%` z_r&L&dw(&|pI1FXY#me=N=3LUfrmh^fJ0E5pHBqzGmp;Wmw=xR8k#T0Jmgy{X6g{a z*%6#@@6dM;!8I5t@wE+dQogRJDSDg^-+?H^50q8K6@UtQ9!dpD~YytYP zz$|^!v;5h&`wajOmxfpV7hVwBMd+)rP_4`yeFO@v@4CU@n_y>Pts6Lbr3G-aPQUuU zS^@pDVF3oA-`v}K3j9d}`~1O!2oZuCp)sz2gEjzd4CNF8QWCi6=ds6N0S0XS z5c}k=!aF?b$T5yUn!AZVYH(l_5|#i1uCYEUdELXYCqYlA&*7ZkmWXz0S=>vjAXyqimk0B~7>8w2P0`oi6;>=NI{{nd`az885n`{^H%iaR~( zNA7nGg1y;3UnSq&`h1|8wzA5iHT<~W8|36+H()Qf0RTK7LO+R$BtSsno3uZHilW#s z@0C!yJNZ-&+8_WRAIg_ojGvW8Gd&=^Un>p{0AJ}c$d0926ak<1zcT?t0^&R1Prhj$ zcL=}vL%zrFdLll0pq1_%oZc?YzAwN1Hx10w5@+;-x#zroUMvA%M|QBA?-DG*Z{@Ja7b%8E_YV6(-XmNsTApmz?Z~z-byVjl>O%;UR((j1}?1%_}m)>tN zf?Zsf5A48T0H3RGzz{&6(VZK7R6(B2%`2%d+M*7p?+|}}XoWI%lt6Cwm;i}j&c)EC zT-AwrkK3vkDWj|69L)Rs=p$_d;&&8snjW$fQ`70nWU8shz$6-+c9y?7GkX5%oOjyQ zg|*L!JbU@-Z+7DLxct7}fn4b)?otyRva8Vv#z{2K3Z0|X@S>S?M}68^;%sidUNpg9 zHch;Z5qeccLsCQ)dzTs6_LWi0OJkNpFz#wDziF3&->ij3l5EzfrycWmaxz7WElQXx zB;9fj$UIbeHLmcnG)T^hz0r}Y&M+IAXFgygizpZcDha|>OC)A>@V9F}%PKjc z^i+6DdTV&9^-2uTP@JkOSXWy}IMwpUj zU{v>Nd@b_N#c5Xwk@Pl=w^+^UJRgf5EM?+!_m9sa?gLLyI&2rPeX%3O9|5zH6rI## zb0fhuih_p!h7s=Jdk~pAv$B|J--}*rb`#j{AtNsgPtMyG^jy0bWU3E1+Zf{s1t|M< zspMPCiaT#vbIRQ=J~8_)vmJ*FP+AVXN`J5`%2#Wx;p(?f_?VB##jz{eedx_2tev)K z5`8ZFIyH0fYgb)OoN7eEZBVCN`9vK*k4Rw^tWt%q%oHJlY(7uqwcy?d_=FeP-7~bT!*`b8P&iDc~}V6 zo_zXSV<|v_=e!(FjTn=adVT6Gjr?*AHP@7gKVyfqy4Ocx?CR#Yq|98T(}q_K5@IeK z@nd$YMw=OKEU0#H?yDFm3<_gEkUBJViC1qDx<+$-?JBJk{sqjJ@OSi|3?{g3Tk9o--jO4ThL6nnm*R&P)5x zin)b#isM(8;500px|sibr-!JxhQSr`yf}rrNcvaMG*W^zme2iy+iohi_Y1_k%qEK? z@eKT9P*ilw-=<(3xbmMC|1y)lMvANpYu*_nk5-Wp$yK9KYQ3m`ya`K#J_|n+YbWy5 zqhPId+a`RJpAr#g)W_CjI?Xy8B62#|LQk|(=f3{t!$Yjb82+r;FCRv0~>%bxt#zIvHy&Br+)`{-||1D?eAs0C)Tz^5g5L>V!4-b2KV zl@Vs&6B}w0NoA`<6v`bEQo{ilx4pbLdJ--^yBcsO-*5Zm%uIy`}ly}<;l^1G>yqEH0 zwl{Q@vDesF4LRYXPb|4!SUaxi*|-yTfIifOWM8(L`C2JXyQ&*#`-QouvQ5Y-DyYyJ z&|p$`?O_f0@{02=$ofT7$(>2b8(&O9m_jTyu5HH}F#_w8_KlX=^&Q@co`^mUx~p$` zlZ=_c_Q;1a(8ctRTjnCQ1PiyhM{b-w)&bic{d0s-<_drAm4seb*vt8~pJyqbL0P+u zC^vc{2|ztN^)1U^@0HvusY>gjiy-g0vO=i`7^G^Sor|(B{OYzRJyp@KL__7@_>mLX z3-(5RbC8q}d>k=2nTWHFFdbyHC`RegDP;qe)p>6BMw_z!?w+!bMM7O83RV(oip*HV zDyym|TvZ))rPDxFT*LB?ujm|JYj{8*=NA9T#xRp@MI1~z#Bf|U=#`F7S4P!eDW^om z=@*=EIl;u;uwzex9#V4n$cSWl5!Wj~idlA3xhSGK(opUCli(ryzFDiT`f_c1^tLdk zBnKA#x2^CcO>+O_^ck0u`(}7BDOk)~)52tBn=Z^J;sgqX(h656$EL!OP$O~dRSWG` zXV(lXrZx(;>eHX|@ZHQ10zYha(K8BT3}vdU{QLv+zPj#8sZt(h^B9U>qfHx_pAOKj z$ZZU!t%lt)&H=;8%nDAKcGA#!V7kWCfvO;b7mAhhkQUaY)?F#c0`aC@J4_93U4M~? zZoZ1clj1`kDC=g5Tb141hDi!)?xGh^0HQ9i03$t=H;Qw| zq1#gM%pI@o%xlTFi-IiaEoyfXM4)k7hlW~QIEXN9(Tu1fxYx?z**PY2cGO0t)`aB) zF2KT2%yPdCSbAzB6?~$b&}!`+?v)AMw5JYqT^Ww=k|sXiwr=;zN=7p_eMH=J_zaf?Fex+gB$)iQS-W$A&Ycr+rGn9LM;u;g>>69Kx&vv_F{KTeTG z%U+cVgfTSGk{=~5IV~g;9}`3KT9=#s0lC{u4!jm&0kvh1-NY$q8+^!p3nRN>JL{tP zo5@hlaxh4~ESn=%zY3tRdMF1WkH?d#KS2Vx6asaPtC|zxJ6rwrK;djYzOZz_SKec@ zAQNS8-E-6~#9EGk83Ss0`*$o{N*ZGQfc+HvepXQGBIoU|Lgisa`Xb|a)pOm(3BoN< z`#~(IzTtyKevSJ1jC7s26hE6JUOwl(`OFCt+(p!NGpQeVC6@$iNSxW!I5KD4!m5dn z!t!vAjZ0`S8di?pxeqtQ?|}T2{);y6Ej$9|4fGU}M^R2T@q`J5O1aJAooKRdZc0C> z{20wGu#BrorY6nOA)VI6R>d{QU{0Pz8P8EP8LBnX-&MJ+J@c6o$Zr|uo2>|*xE$4k zH$0ulrg+bY(+*e2es9l!Iy~#or}X}IS7r3!l-2w`aotANFPu*-J<2zqyZHpY9Cg&) z8HHB|faoc>@WVGae{XbP&6Dm|0G>dA17Ezejmf&`VQI*~iXGdw(aQK#8YGKwj8Chg z=nCKK2)~u=zrwkR z#SQ7+KeL`~@{hU1*@;xj(mv&Uq88E>o~cYl8xhBNPv$5i$N%t__Rwpa^y1&{+7_lK z_W2!x`VtOnO*~vP;hwTt-ps+cZ{r{JK7}=9fvfCn=oMvC*r_C{)ev!i?hy6P%{1dF z31z-js(tWWWNCvrX=!e*60t4gli+{z(!L(l;OZ+Ztx^>RWusyrU$~uhKHV zaUBCx>4y>A*xthzxovn%MeFxe2ZAEWb<23EA#3F`REsrJF$)ic;2bC(2~L^kMpWR# zfPg|!0#~w7VG=ej$=R2H1hH^pub<89IseGlX?nb5g@63sNSi8WkB^m(>>aFq^GJEJ zPra~KfY;-|D-m&NqVF!Uj>br`FLMOKp${^|sEW1ejqO?tO~UPL?Xr?jln5@wIG?TR zmBh6yM)?zw=lGrV2y8#PV{tZNn$xGkA$_R7)SEy%-mm1H#(EgFWnvHRi%xHCc z#|G}&jiHKSNj|1@Z8?0LReobStP_p;MvMG$(7`%V=y{hUESzu=Mc#r@kk2_v&+?=sE!{h)mMDZ$ z@R*M)cT3W$HnZfig5U-qX8r+p-Pq=q<&+tiqY9H-{|i1 zB8lI1(F5r~Ku)#i(ulvW1S08mu!&s2QDn`q2;}W>#m43kE;|-KRYdWphr^V+AYhL& z1}o9G@~gqw^c}VGpB6K}rs@qS9y+a{g!+T(y}exEdA^FdZMc&gAldOKJj+kRwGT0~8kug*=AqXEfaWIn5VH zdpY`){6twif~Eh)&|jT?34q5OE=A1JV3g&# zSYrFW$3f?kAn!K~60{ciW_d1U?YPnKKP==7|63+}1zPhe6tFv(jN_62^%lTA^8GQL00Ez>t-`2AJo z&f4B}CYWbw8I|53R3C#bgMC{2%$h_e5ds+x$*7k2p!Sc3NVE@foRS-E&a%rj=IW2z zBdq$;ZgA+Vt5CK^f1MqRF!@jRdVpn<|7tQFgIbj8&Vl(wB3h+U?05n4cc(t#E$xjS zRxi~yqPil4e)$_N6>V`=kTTfs9-*7b5R-Co-_muSDZC}P!bQ}IG79usfFW1y${`xW z>*n1NWvEJ-ibwUkZb zoq8WVJNvtASXI&H(GsgF@ptq!iFre!indPz+xESd zMbUnaHmwS-{P>{nUZCdjieg9e&??s(!4kE5)mDr(gmb`N%ImlZIIvDV`~l_dd}JoX zyXNSkarcWpkBjRa)u^8vwV>Zg-@p{p9V2$)W<;nWcpu`VuK!(1erM;dIG)rI5FFxm zlatql!^H1ckL_J+E~U=v-cx*8D18BHYO8%;4IL%*i;>3P+J?iW@HZ1@)*#(ecWHgW z7}-#j-hIrVGln+ZSX-EJZuK*`?~?&nSc6|K4z+1*dy+%qano2LpZiQ4{9(@`*as_S zs0k&VTBTqi4)o=2_$eY*x+lx2_+1uM7WCj~NWLiiMWlH=DC8$Tz;)w0oyP%I6gRY` zbAzt|V?pJlT3c52lF&^O%_?sgRI$?RMCTrroFo$U8yW?iLf!IfXApBvyx!9oxI|LQ zgX8&3J;?-#3SUQ_fHlk=D!0gjf-5Bg>I-3b!qx(|(%q@fq8o8Xn7l~ZZUfldccdmc zE5H?ErDiLQg^7h2)gf!F#`eHAFq($sEc)e|9Gb!768Ej1D{Mfs(^suIYeRGZJm0^;j^Pa3IZ zC*)0E9r$P19loOXAde)8eydj?555+naE=rg*UQr5NR(KwnrzPjzJ#4B^wkKiei?)q zIOHm`zVO@$!`Fw75l%MLDCo;DhByghhKMjsz*$BCQ6HRFC^|xT`OuP8R6Pv(EiIDR zDM^MGRlrYWf_lURGGn!F4N?4W)L`f$8#J(@NE2gWd0E;rBjBa$?{uikJmV25GeKSO zVdvcT5~9LH&u!^UlW_RzercePdtz0zQjE6QuFWBINaSGJhh1 z5iHZ50?|SvyqJE6NYnmd>iO6X&3YE;iiU65rGP>vH}7bM0#}h)X zpBRQeieOr}!)@u%5L`0>-4on=F@GW7jWu}qY9>T>20qQ@J9mbyVL0rFpN(m7&ClG( z2ovv|S=!XN{PNGrj(VDVV&p1W8>^Hb-t)`oGNHkf_CbDjn2boGbf!j^j^hmP7b)hv?QCyBvHUL%I|7>U!NA&Uj zp~YobXi#xs3?8mm0juoz$+;i#N_Wulc^MEKx|@@lw!g9Goz-zz1j{Gzaaj|9U%t`t zY$t^>*>+8|(L-CRK@oXv#esbuG5b`Qhf$|CpHKygYMOTq!M<9X zbF=v*9(Pn3^?ZgXi8NUHdRCmFmMgi6#-x>14 zf3|sQNK{(@aAQ&Xa^AT$9x+pn`Q1j`i=-jG0L!zUoLBZYoovw4B+9oFMioMCJG=G* z119wWchv7auCZ^&r_Li!rxlaPwA{V&18zU+oWy)NpyBrvb>C!Bc1n=YU;O$@1>;&V zA%&9S-W0ay@Oy51YU8~RIqB5%{DOvIP+@+{+;}Y}5)zHCw~F3+KXW`Ya+c7dC>PAn z!p)2?hXJem24I;R_$<{szn1(~R8`o2Bix5Bw8ujjv9|lZo>hwFUCWBIA(Cvu;^8Z! z2^ba87JfW=s4gbpJoSmp+Y4|V(C)rNjAA!V2$SM+bF{5mU!?t?=FT%Hs$`4fM9Cl` zX>sJjk_KUNAZLdxK^Dp5Fu@&x0cHS+f(R(76j4wz3Jf|%K=R;Il7M7UK@bpSMWRSD z?{$6FbIaPQ{rGO(P+i^UobJ=N?w9`mZoe~vUggM*8s6<#UVm3mQNt|E6MNzWk9W9! zcWhs!%NamrsNX9iooxHySQselfvK%hQ*ag)}ctr_~eW zSKWJ7#QR3ZP%B-!t(T#f8Q$B+1;GC&j*G#>s`$k=CXJ_TTBf8MHjmi~^qhQg+e%5+ zQ#IuHZ06@Bq~^gxhhJ64PD^QzHn*vW=AU23wAeL6nbkcF_3qU#y(~rvL(i<0DD`?1 z1DforE%DF?c)nXWaQoD;k#`)WkFH*%T=Z*(RJ=jnkU*~t8nTAu)c8J^73qs0C$l`W z)@ZX|2HxD9u&;b@fSx;MHqQ{MG1hnJFMH27-7JcWo5}Cgxq0Hw(ng947wub{RkptB zmJxcCqj;(%>a^15UhneEJuCN40h`OU31w2z2wqQ*xKRb8moM@vu&M@FP*1Y{Ef9-c7WIBeT{RW#QHpe z0u44gaqd=!g*a}_q$S?J(bUeOLis`=B)LeojgPQ^wQBIsJZT9V}_JIcN@v8vBWkA78GR9KnN%y;Uw>I;(xDHnZ zPae^0+8dCjsz_q<=knwA`+0k{avBejF=5Fyr`CrH@>{)ML*g0t*3&RcjR{UW8*<|6 zIHsy87ZAjhMbc&tE#Ek9lz7}cMuy-PS1jbasxeBAGUkOQ5%=068qe=vycrh97g3CQ zY~#*0QqQul+JUrCkscu5c<~#T8to8Xn|7`IU_p0TD8E&LMYdt5vD!kyF3o6Dl>EH| zYkOt`y0n1?sfFI&*d4KONvhhS9PlgT1-a~rT&c&<$XR)#++}NG7ZS<83QeTos*fXs z%Ehb1@b4i-@!c|nqCm|$#jrUAWF1a9eLcFRRnp6DvT|Li%G5eo(3cv~<$x_RZO3`P z@-;1w?UJ!2Zcv3)?unFm*NtP-MfD>KS!z4SC{=q6L+%H5A|&b_#VC#1O=&=86Pq5U zpJ-p{C|o=5b?-=Yygz(-wZzW(QJY@n9vN6$8p#F?~_I2^JR7fecSR$jyd?G2z_`^c#3_hEyrSQ>! ziGrD5?&_;dHz|A@`D*0IBX+Hj$c$v)@2{rh1ij-_E(sBj#f1Y-n@GOnr4Eb$9FO`G-35j~go# z8?P5%%90AGf2Wk~Xkvj9f#V1L`61UPVdB^9Hp`~mKS@Pgq22s>A^u-(mkO@DWB;Z; z`afZ$*x8@TO(eq&r>9yTw+@CLHK0k7i3kGp8zGXKYWGGJAlCD1S7S-jd>Qnd0KDABght~U! zklg+^&IW$^{{j4D4kqynTuFVxFTztMTMkMS3I}-9b}ltGPE|H&7Le@ zwy$4{WBH_mw})9R!RGbL^BNJMugT9#Dl#NI?fp6xx4QFHN{NcftwHCah|oS`Kfo`h zV9U+g^^@Y}k>nQSy6cYW&g4_aG~1;4BJH?Ii798JZ3TnqOZxSkv#(cnZGAkf8Pdz$ zJzgz$7p{Ap=p}e(O=qioW-50dNJ>c@r9(arMXmJQpUU+VxPuCPo8F@H{>(~$hg{=g z#_G@}qj2ELMeH#_m%5GG-hC4yo@4hpI`qU`EyGU{|loBGptBq zR6xth0EIxIkth@vfkxx87%wOQ|EonX6VP&_dVod8V9GzYb#~k90V9M52Ktj24C+^# z-{~v>JVPin&|C*_r!rY!Gyn}lVvtyU6b_5lMZs{oNEikILty})uTcO8dIS{!dxG+T z0s$eUu-{o!5)koUQydHp!+;%eW(HHj$zOwfbN<~2Smnkfg@jNk0GvPyWc{c+{1GMo zCQS5jrP98OYXCGJG@%EEfllFsKrka#RB|u{lrMgJf?CHQ7GPuq<|H^UJcz*pKwXYA z6O>4j!@vX~ztZ{u`~awxL;`5=0_BnW>CsdG^lEDbcpKr7BrFn#Bcbpp8VQ5J;ZRr< z9<8TGMc}DO42f!DgrJZS7&MNA#)E^`Cu1oX3KfUIV<}jS9tDp_n)v?hdqno<;ng5? zU`@mw%-oSDDWA5f${Lufy^Y`AwUy4x^}Kl*9~+WKwCOC?rl)U45?; GLG(}mhAh1R literal 0 HcmV?d00001 diff --git a/scripts/test_controllers.py b/scripts/test_controllers.py index 2d844ab..5c2a1de 100755 --- a/scripts/test_controllers.py +++ b/scripts/test_controllers.py @@ -29,6 +29,7 @@ tfBuffer = tf2_ros.Buffer() listener = tf2_ros.TransformListener(tfBuffer) + print("Switching to ", controller_space, " space controller. The robot might jerk a bit as it is switching to effort mode.") rospy.wait_for_service("controller_manager/switch_controller") rospy.wait_for_service("set_control_mode") switch_controller = rospy.ServiceProxy( @@ -65,6 +66,7 @@ if mode == "stop": sys.exit(0) + print("Switch complete. You can now send commands to the robot.") try: cmd_pub = None if controller_space == "task": @@ -103,12 +105,12 @@ joint_states = rospy.wait_for_message( "/joint_states", JointState, timeout=None ) - print("Current joint state: ", joint_states.position) + tmp = np.array(joint_states.position)[1:] + print("Current joint state: ", tmp) cmd = JointTrajectoryPoint() # take input from user dof = int(input("Enter dof (1 - NDOF): ")) value = float(input("Enter value: ")) - tmp = np.array(joint_states.position)[1:] tmp[dof - 1] = value cmd.positions = tmp.tolist() cmd.velocities = [0] * len(tmp) diff --git a/src/JointSpaceCompliantController.cpp b/src/JointSpaceCompliantController.cpp index 86932cd..f240b1d 100644 --- a/src/JointSpaceCompliantController.cpp +++ b/src/JointSpaceCompliantController.cpp @@ -250,13 +250,13 @@ void JointSpaceCompliantController::update( mLastTimePoint = std::chrono::high_resolution_clock::now(); mJointStateUpdater->update(); - mActualPosition = mJointStateUpdater->mActualPosition; - mActualVelocity = mJointStateUpdater->mActualVelocity; - mActualEffort = mJointStateUpdater->mActualEffort; + mCurrentPosition = mJointStateUpdater->mCurrentPosition; + mCurrentVelocity = mJointStateUpdater->mCurrentVelocity; + mCurrentEffort = mJointStateUpdater->mCurrentEffort; if (mExecuteDefaultCommand.load()) { - mDesiredPosition = mActualPosition; + mDesiredPosition = mCurrentPosition; mDesiredVelocity.setZero(); mExecuteDefaultCommand = false; } @@ -283,39 +283,39 @@ void JointSpaceCompliantController::update( if (!mExtendedJoints->mIsInitialized) { mLastDesiredPosition = mDesiredPosition; - mExtendedJoints->initializeExtendedJointPosition(mActualPosition); - mExtendedJoints->estimateExtendedJoint(mActualPosition); + mExtendedJoints->initializeExtendedJointPosition(mCurrentPosition); + mExtendedJoints->estimateExtendedJoint(mCurrentPosition); mNominalThetaPrev = mExtendedJoints->getExtendedJoint(); - mNominalThetaDotPrev = mActualVelocity; + mNominalThetaDotPrev = mCurrentVelocity; mDesiredPosition = mExtendedJoints->getExtendedJoint(); } if (mDesiredPosition != mLastDesiredPosition - && mActualPosition != mDesiredPosition) + && mCurrentPosition != mDesiredPosition) { mLastDesiredPosition = mDesiredPosition; mExtendedJoints->estimateExtendedJoint(mDesiredPosition); mDesiredPosition = mExtendedJoints->getExtendedJoint(); } - mExtendedJoints->estimateExtendedJoint(mActualPosition); - mActualTheta = mExtendedJoints->getExtendedJoint(); + mExtendedJoints->estimateExtendedJoint(mCurrentPosition); + mCurrentTheta = mExtendedJoints->getExtendedJoint(); mGravity = pinocchio::computeGeneralizedGravity( - *mModel, *mData, joint_ros_to_pinocchio(mActualTheta, *mModel)); + *mModel, *mData, joint_ros_to_pinocchio(mCurrentTheta, *mModel)); mDesiredTheta = mDesiredPosition + mJointStiffnessMatrix.inverse() * mGravity; mDesiredThetaDot = mDesiredVelocity; - mJointEffort = -mJointKMatrix * (mNominalThetaPrev - mDesiredTheta) + mTaskEffort = -mJointKMatrix * (mNominalThetaPrev - mDesiredTheta) - mJointDMatrix * (mNominalThetaDotPrev - mDesiredThetaDot); double step_time; step_time = 0.001; mNominalThetaDDot = mRotorInertiaMatrix.inverse() - * (mJointEffort + mGravity - + mActualEffort); // mActualEffort is negative of what + * (mTaskEffort + mGravity + + mCurrentEffort); // mCurrentEffort is negative of what // is required here mNominalThetaDot = mNominalThetaDotPrev + mNominalThetaDDot * step_time; mNominalTheta = mNominalThetaPrev + mNominalThetaDot * step_time; @@ -324,14 +324,14 @@ void JointSpaceCompliantController::update( mNominalThetaDotPrev = mNominalThetaDot; mNominalFriction = mRotorInertiaMatrix * mFrictionL - * ((mNominalThetaDotPrev - mActualVelocity) - + mFrictionLp * (mNominalThetaPrev - mActualTheta)); + * ((mNominalThetaDotPrev - mCurrentVelocity) + + mFrictionLp * (mNominalThetaPrev - mCurrentTheta)); - mDesiredEffort = mJointEffort + mNominalFriction; + mCommandEffort = mTaskEffort + mNominalFriction; if (mCount < 50) { - mDesiredEffort = Eigen::VectorXd::Zero(mNumControlledDofs); + mCommandEffort = Eigen::VectorXd::Zero(mNumControlledDofs); mCount++; if (mCount % 200 == 0) std::cout << "Initializing controller: " << mCount << std::endl; @@ -341,7 +341,7 @@ void JointSpaceCompliantController::update( for (size_t idof = 0; idof < mNumControlledDofs; ++idof) { auto jointHandle = mControlledJointHandles[idof]; - jointHandle.setCommand(mDesiredEffort[idof]); + jointHandle.setCommand(mCommandEffort[idof]); } } diff --git a/src/TaskSpaceCompliantController.cpp b/src/TaskSpaceCompliantController.cpp index d8dad49..c59a605 100644 --- a/src/TaskSpaceCompliantController.cpp +++ b/src/TaskSpaceCompliantController.cpp @@ -142,12 +142,6 @@ bool TaskSpaceCompliantController::init( mFrictionLp.resize(mNumControlledDofs, mNumControlledDofs); mFrictionLp.setZero(); - mJointKMatrix.resize(mNumControlledDofs, mNumControlledDofs); - mJointKMatrix.setZero(); - - mJointDMatrix.resize(mNumControlledDofs, mNumControlledDofs); - mJointDMatrix.setZero(); - mTaskKMatrix.resize(6, 6); mTaskKMatrix.setZero(); @@ -160,8 +154,6 @@ bool TaskSpaceCompliantController::init( mRotorInertiaMatrix.diagonal() << 0.3, 0.3, 0.3, 0.18, 0.18, 0.2; mFrictionL.diagonal() << 75, 75, 75, 40, 40, 40; mFrictionLp.diagonal() << 5, 5, 5, 4, 4, 4; - mJointKMatrix.diagonal() << 10, 10, 10, 10, 10, 10; - mJointDMatrix.diagonal() << 2, 2, 2, 2, 2, 2; } else { @@ -170,8 +162,6 @@ bool TaskSpaceCompliantController::init( mRotorInertiaMatrix.diagonal() << 0.3, 0.3, 0.3, 0.3, 0.18, 0.18, 0.2; mFrictionL.diagonal() << 75, 75, 75, 75, 40, 40, 40; mFrictionLp.diagonal() << 5, 5, 5, 5, 4, 4, 4; - mJointKMatrix.diagonal() << 10, 10, 10, 10, 10, 10, 10; - mJointDMatrix.diagonal() << 2, 2, 2, 2, 2, 2, 2; } mTaskKMatrix.diagonal() << 200, 200, 200, 100, 100, 100; mTaskDMatrix.diagonal() << 40, 40, 40, 20, 20, 20; @@ -273,13 +263,13 @@ void TaskSpaceCompliantController::update( mLastTimePoint = std::chrono::high_resolution_clock::now(); mJointStateUpdater->update(); - mActualPosition = mJointStateUpdater->mActualPosition; - mActualVelocity = mJointStateUpdater->mActualVelocity; - mActualEffort = mJointStateUpdater->mActualEffort; + mCurrentPosition = mJointStateUpdater->mCurrentPosition; + mCurrentVelocity = mJointStateUpdater->mCurrentVelocity; + mCurrentEffort = mJointStateUpdater->mCurrentEffort; if (mExecuteDefaultCommand.load()) { - mDesiredPosition = mActualPosition; + mDesiredPosition = mCurrentPosition; mDesiredVelocity.setZero(); Eigen::VectorXd q_pin_desired = joint_ros_to_pinocchio(mDesiredPosition, *mModel); @@ -323,7 +313,7 @@ void TaskSpaceCompliantController::update( mExtendedJoints->initializeExtendedJointPosition(mDesiredPosition); mExtendedJoints->estimateExtendedJoint(mDesiredPosition); mNominalThetaPrev = mExtendedJoints->getExtendedJoint(); - mNominalThetaDotPrev = mActualVelocity; + mNominalThetaDotPrev = mCurrentVelocity; mTrueDesiredPosition = mExtendedJoints->getExtendedJoint(); mTrueDesiredVelocity = mDesiredVelocity; mTrueDesiredEETransform = mDesiredEETransform; @@ -331,7 +321,7 @@ void TaskSpaceCompliantController::update( if (mDesiredPosition != mLastDesiredPosition || !mDesiredEETransform.isApprox(mLastDesiredEETransform, 0.0001) - && mActualPosition != mDesiredPosition) + && mCurrentPosition != mDesiredPosition) { mLastDesiredPosition = mDesiredPosition; mLastDesiredEETransform = mDesiredEETransform; @@ -346,10 +336,10 @@ void TaskSpaceCompliantController::update( mExtendedJointsGravity->initializeExtendedJointPosition(mDesiredPosition); mExtendedJointsGravity->estimateExtendedJoint( mExtendedJointsGravity->mLastDesiredPosition); - mActualTheta = mExtendedJointsGravity->getExtendedJoint(); + mCurrentTheta = mExtendedJointsGravity->getExtendedJoint(); mGravity = pinocchio::computeGeneralizedGravity( - *mModel, *mData, joint_ros_to_pinocchio(mActualTheta, *mModel)); + *mModel, *mData, joint_ros_to_pinocchio(mCurrentTheta, *mModel)); // compute quasi-static estimate of the link side position // input value is motor side angle theta not link side angle(q); @@ -374,8 +364,8 @@ void TaskSpaceCompliantController::update( // *mData, q_pin); } - mExtendedJoints->estimateExtendedJoint(mActualPosition); - mActualTheta = mExtendedJoints->getExtendedJoint(); + mExtendedJoints->estimateExtendedJoint(mCurrentPosition); + mCurrentTheta = mExtendedJoints->getExtendedJoint(); mDesiredTheta = mTrueDesiredPosition + mJointStiffnessMatrix.inverse() * mGravity; @@ -429,7 +419,7 @@ void TaskSpaceCompliantController::update( mNominalThetaDDot = mRotorInertiaMatrix.inverse() - * (mTaskEffort + mGravity + mActualEffort); // mActualEffort is negative + * (mTaskEffort + mGravity + mCurrentEffort); // mCurrentEffort is negative // of what is required here mNominalThetaDot = mNominalThetaDotPrev + mNominalThetaDDot * step_time; mNominalTheta = mNominalThetaPrev + mNominalThetaDot * step_time; @@ -438,14 +428,14 @@ void TaskSpaceCompliantController::update( mNominalThetaDotPrev = mNominalThetaDot; mNominalFriction = mRotorInertiaMatrix * mFrictionL - * ((mNominalThetaDotPrev - mActualVelocity) - + mFrictionLp * (mNominalThetaPrev - mActualTheta)); + * ((mNominalThetaDotPrev - mCurrentVelocity) + + mFrictionLp * (mNominalThetaPrev - mCurrentTheta)); - mDesiredEffort = mTaskEffort + mNominalFriction; + mCommandEffort = mTaskEffort + mNominalFriction; if (mCount < 50) { - mDesiredEffort = Eigen::VectorXd::Zero(mNumControlledDofs); + mCommandEffort = Eigen::VectorXd::Zero(mNumControlledDofs); mCount++; if (mCount % 10 == 0) std::cout << "Initializing controller: " << mCount << std::endl; @@ -454,7 +444,7 @@ void TaskSpaceCompliantController::update( for (size_t idof = 0; idof < mControlledJointHandles.size(); ++idof) { auto jointHandle = mControlledJointHandles[idof]; - jointHandle.setCommand(mDesiredEffort[idof]); + jointHandle.setCommand(mCommandEffort[idof]); } } diff --git a/src/helpers.cpp b/src/helpers.cpp index d4d4df4..15dc287 100644 --- a/src/helpers.cpp +++ b/src/helpers.cpp @@ -7,14 +7,12 @@ JointStateUpdater::JointStateUpdater( std::shared_ptr model, hardware_interface::JointStateInterface* jointStateInterface) : mModel(model) - , mActualPosition(model->nv) - , mActualVelocity(model->nv) - , mActualEffort(model->nv) - , mPinActualPosition(model->nq) + , mCurrentPosition(model->nv) + , mCurrentVelocity(model->nv) + , mCurrentEffort(model->nv) , mDefaultPosition(model->nv) , mDefaultVelocity(model->nv) , mDefaultEffort(model->nv) - , mPinDefaultPosition(model->nq) { std::set missingJointNames; @@ -60,8 +58,6 @@ JointStateUpdater::JointStateUpdater( ROS_WARN_STREAM(msg.str()); } - - mPinDefaultPosition = joint_ros_to_pinocchio(mDefaultPosition, *model.get()); } //============================================================================= @@ -70,11 +66,11 @@ void JointStateUpdater::update() for (size_t idof = 0; idof < mModel->nv; ++idof) { const auto& jointStateHandle = mHandles[idof]; - mActualPosition(idof) = jointStateHandle.getPosition(); - if (mActualPosition[idof] < 0) - mActualPosition[idof] += 2 * M_PI; - mActualVelocity[idof] = jointStateHandle.getVelocity(); - mActualEffort[idof] = jointStateHandle.getEffort(); + mCurrentPosition(idof) = jointStateHandle.getPosition(); + if (mCurrentPosition[idof] < 0) + mCurrentPosition[idof] += 2 * M_PI; + mCurrentVelocity[idof] = jointStateHandle.getVelocity(); + mCurrentEffort[idof] = jointStateHandle.getEffort(); } }