From 096d818f5b8927675b31d5ed6998bfe0d52934af Mon Sep 17 00:00:00 2001 From: Walter Fetter Lages Date: Wed, 21 Mar 2018 13:07:44 -0300 Subject: [PATCH] ROSBook 2016 initial submision twil_description: remove doc twil_ident: line wrap remove covariance reset twil_controllers: remove cart_linearizing_controller_rne remove nosmooth_backstep_controller remove adaptive_nonsmooth_backstep --- twil_controllers/CMakeLists.txt | 2 - .../config/nonsmooth_backstep_control.yaml | 11 - .../cart_linearizing_controller_rne.h | 53 ----- .../nonsmooth_backstep_controller.h | 51 ----- .../launch/adaptive_nonsmooth_backstep.launch | 21 -- twil_controllers/launch/cart_linearizing.launch | 2 +- twil_controllers/launch/nonsmooth_backstep.launch | 16 -- .../src/cart_linearizing_controller_rne.cpp | 159 -------------- .../src/nonsmooth_backstep_controller.cpp | 243 --------------------- twil_controllers/twil_controllers_plugins.xml | 20 -- .../doc/dimensions_battery_bosch_12v.pdf | Bin 26816 -> 0 bytes twil_description/doc/dimensions_chassis.pdf | Bin 70581 -> 0 bytes twil_description/doc/dimensions_cpu.pdf | Bin 28306 -> 0 bytes twil_description/xacro/twil.urdf.xacro | 7 - twil_ident/launch/ident.launch | 17 +- twil_ident/src/ident.cpp | 6 - 16 files changed, 11 insertions(+), 597 deletions(-) delete mode 100644 twil_controllers/config/nonsmooth_backstep_control.yaml delete mode 100644 twil_controllers/include/twil_controllers/cart_linearizing_controller_rne.h delete mode 100644 twil_controllers/include/twil_controllers/nonsmooth_backstep_controller.h delete mode 100644 twil_controllers/launch/adaptive_nonsmooth_backstep.launch delete mode 100644 twil_controllers/launch/nonsmooth_backstep.launch delete mode 100644 twil_controllers/src/cart_linearizing_controller_rne.cpp delete mode 100644 twil_controllers/src/nonsmooth_backstep_controller.cpp delete mode 100644 twil_description/doc/dimensions_battery_bosch_12v.pdf delete mode 100644 twil_description/doc/dimensions_chassis.pdf delete mode 100644 twil_description/doc/dimensions_cpu.pdf diff --git a/twil_controllers/CMakeLists.txt b/twil_controllers/CMakeLists.txt index 7261bb6..2b39e24 100644 --- a/twil_controllers/CMakeLists.txt +++ b/twil_controllers/CMakeLists.txt @@ -101,8 +101,6 @@ include_directories(include ## Declare a cpp library add_library(twil_controllers src/cart_linearizing_controller.cpp - src/cart_linearizing_controller_rne.cpp - src/nonsmooth_backstep_controller.cpp ) ## Declare a cpp executable diff --git a/twil_controllers/config/nonsmooth_backstep_control.yaml b/twil_controllers/config/nonsmooth_backstep_control.yaml deleted file mode 100644 index d5761f9..0000000 --- a/twil_controllers/config/nonsmooth_backstep_control.yaml +++ /dev/null @@ -1,11 +0,0 @@ -twil: - - joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 100 - - nonsmooth_backstep_controller: - type: twil_controllers/NonSmoothBackstepController - joints: - - left_wheel_joint - - right_wheel_joint diff --git a/twil_controllers/include/twil_controllers/cart_linearizing_controller_rne.h b/twil_controllers/include/twil_controllers/cart_linearizing_controller_rne.h deleted file mode 100644 index 20df5d3..0000000 --- a/twil_controllers/include/twil_controllers/cart_linearizing_controller_rne.h +++ /dev/null @@ -1,53 +0,0 @@ -#ifndef TWIL_CONTROLLERS_CART_LINEARIZING_CONTROLLER_RNE_H -#define TWIL_CONTROLLERS_CART_LINEARIZING_CONTROLLER_RNE_H - -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include -#include - - -namespace twil_controllers -{ - class CartLinearizingController_RNE: public controller_interface::Controller - { - public: - CartLinearizingController_RNE(void); - ~CartLinearizingController_RNE(void); - - bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); - void starting(const ros::Time& time); - void update(const ros::Time& time,const ros::Duration& duration); - - private: - ros::NodeHandle node_; - hardware_interface::EffortJointInterface *robot_; - std::vector joints_; - - void commandCB(const std_msgs::Float64MultiArray::ConstPtr &command); - ros::Subscriber sub_command_; - - KDL::ChainIdSolver_RNE *idsolver; - - KDL::JntArray phi; - KDL::JntArray nu; - KDL::JntArray dnu; - KDL::JntArray torque; - std::vector v; - - KDL::Wrenches fext; - - std::vector wheelRadius; - double wheelBase; - }; -} -#endif diff --git a/twil_controllers/include/twil_controllers/nonsmooth_backstep_controller.h b/twil_controllers/include/twil_controllers/nonsmooth_backstep_controller.h deleted file mode 100644 index 4b9c205..0000000 --- a/twil_controllers/include/twil_controllers/nonsmooth_backstep_controller.h +++ /dev/null @@ -1,51 +0,0 @@ -#ifndef TWIL_CONTROLLERS_NONSMOOTH_BACKSTEP_CONTROLLER_H -#define TWIL_CONTROLLERS_NONSMOOTH_BACKSTEP_CONTROLLER_H - -#include -#include -#include - -#include -#include -#include -#include -#include - -#include - -namespace twil_controllers -{ - class NonSmoothBackstepController: public controller_interface::Controller - { - public: - NonSmoothBackstepController(void); - ~NonSmoothBackstepController(void); - - bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); - void starting(const ros::Time& time); - void update(const ros::Time& time,const ros::Duration& duration); - - private: - ros::NodeHandle node_; - hardware_interface::EffortJointInterface *robot_; - std::vector joints_; - - ros::Subscriber sub_command_; - ros::Subscriber sub_parameters_; - - Eigen::Matrix2d Ginv; - Eigen::Matrix2d F; - - std::vector wheelRadius; - double wheelBase; - - Eigen::Vector3d xi; - Eigen::Vector3d xiRef; - - Eigen::Vector2d eta; - - void commandCB(const std_msgs::Float64MultiArray::ConstPtr &command); - void parametersCB(const std_msgs::Float64MultiArray::ConstPtr &command); - }; -} -#endif diff --git a/twil_controllers/launch/adaptive_nonsmooth_backstep.launch b/twil_controllers/launch/adaptive_nonsmooth_backstep.launch deleted file mode 100644 index fb8904e..0000000 --- a/twil_controllers/launch/adaptive_nonsmooth_backstep.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/twil_controllers/launch/cart_linearizing.launch b/twil_controllers/launch/cart_linearizing.launch index 65803f7..8e08ffe 100644 --- a/twil_controllers/launch/cart_linearizing.launch +++ b/twil_controllers/launch/cart_linearizing.launch @@ -11,6 +11,6 @@ - + diff --git a/twil_controllers/launch/nonsmooth_backstep.launch b/twil_controllers/launch/nonsmooth_backstep.launch deleted file mode 100644 index f8f3a80..0000000 --- a/twil_controllers/launch/nonsmooth_backstep.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/twil_controllers/src/cart_linearizing_controller_rne.cpp b/twil_controllers/src/cart_linearizing_controller_rne.cpp deleted file mode 100644 index 31fc7e7..0000000 --- a/twil_controllers/src/cart_linearizing_controller_rne.cpp +++ /dev/null @@ -1,159 +0,0 @@ -#include -#include - -#include -#include -#include - -namespace twil_controllers -{ - CartLinearizingController_RNE::CartLinearizingController_RNE(void): - phi(0),nu(0),dnu(0),torque(0),v(0),fext(0),wheelRadius(0) - { - } - - CartLinearizingController_RNE::~CartLinearizingController_RNE(void) - { - sub_command_.shutdown(); - } - - bool CartLinearizingController_RNE::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n) - { - node_=n; - robot_=robot; - - XmlRpc::XmlRpcValue joint_names; - if(!node_.getParam("joints",joint_names)) - { - ROS_ERROR("No 'joints' parameter in controller. (namespace: %s)",node_.getNamespace().c_str()); - return false; - } - - if(joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) - { - ROS_ERROR("The 'joints' parameter is not a struct. (namespace: %s)",node_.getNamespace().c_str()); - return false; - } - - for(int i=0; i < joint_names.size();i++) - { - XmlRpc::XmlRpcValue &name_value=joint_names[i]; - if(name_value.getType() != XmlRpc::XmlRpcValue::TypeString) - { - ROS_ERROR("Array of joint names should contain only strings. (namespace: %s)",node_.getNamespace().c_str()); - return false; - } - - hardware_interface::JointHandle j=robot->getHandle((std::string)name_value); - joints_.push_back(j); - v.push_back(0); - } - sub_command_ = node_.subscribe("command",1000,&CartLinearizingController_RNE::commandCB,this); - - std::string robot_desc_string; - if(!node_.getParam("/robot_description",robot_desc_string)) - { - ROS_ERROR("Could not find '/robot_description'."); - return false; - } - - KDL::Tree tree; - if (!kdl_parser::treeFromString(robot_desc_string,tree)) - { - ROS_ERROR("Failed to construct KDL tree."); - return false; - } - - KDL::Chain chain; - if (!tree.getChain("left_wheel","right_wheel",chain)) - { - ROS_ERROR("Failed to get chain from KDL tree."); - return false; - } - - // Get gravity from gazebo or set values if not simulating - KDL::Vector g; - node_.param("/gazebo/gravity_x",g[1],0.0); - node_.param("/gazebo/gravity_y",g[1],0.0); - node_.param("/gazebo/gravity_z",g[2],-9.8); - - if((idsolver=new KDL::ChainIdSolver_RNE(chain,g)) == NULL) - { - ROS_ERROR("Failed to create ChainIDSolver_RNE."); - return false; - } - - // get wheelBase from URDF (actually from KDL tree) - KDL::SegmentMap::const_iterator segmentMapIter=tree.getSegment("left_wheel_support"); - KDL::Frame leftSupportFrame=segmentMapIter->second.segment.getFrameToTip(); - - segmentMapIter=tree.getSegment("right_wheel_support"); - KDL::Frame rightSupportFrame=segmentMapIter->second.segment.getFrameToTip(); - - wheelRadius.resize(chain.getNrOfJoints()); - wheelBase=leftSupportFrame(1,3)-rightSupportFrame(1,3); - - // get wheelRadius from URDF (actually from KDL tree) - segmentMapIter=tree.getSegment("chassis"); - KDL::Frame chassisFrame=segmentMapIter->second.segment.getFrameToTip(); - - segmentMapIter=tree.getSegment("left_wheel"); - KDL::Joint leftWheelJoint=segmentMapIter->second.segment.getJoint(); - wheelRadius[0]=chassisFrame(2,3)+leftSupportFrame(2,3)+leftWheelJoint.JointOrigin().z(); - - segmentMapIter=tree.getSegment("right_wheel"); - KDL::Joint rightWheelJoint=segmentMapIter->second.segment.getJoint(); - wheelRadius[1]=chassisFrame(2,3)+rightSupportFrame(2,3)+rightWheelJoint.JointOrigin().z(); - - // set vectors to the right size - phi.resize(chain.getNrOfJoints()); - nu.resize(chain.getNrOfJoints()); - dnu.resize(chain.getNrOfJoints()); - torque.resize(chain.getNrOfJoints()); - - fext.resize(chain.getNrOfSegments()); - - return true; - } - - void CartLinearizingController_RNE::starting(const ros::Time& time) - { - for(unsigned int i=0; i < joints_.size();i++) v[i]=0.0; - } - - void CartLinearizingController_RNE::update(const ros::Time& time, - const ros::Duration& duration) - { - for(unsigned int i=0;i < joints_.size();i++) - { - phi(i)=joints_[i].getPosition(); - nu(i)=joints_[i].getVelocity(); - } - - - dnu(0)=v[0]/wheelRadius[0]-v[1]*wheelBase/2.0/wheelRadius[0]; // left wheel - dnu(1)=v[0]/wheelRadius[1]+v[1]*wheelBase/2.0/wheelRadius[1]; // right wheel - - - for(unsigned int i=0;i < fext.size();i++) fext[i].Zero(); - -// for(unsigned int i=0;i < joints_.size();i++) -// std::cout << "phi=" << phi(i) << " nu=" << nu(i) -// << " dnu=" << dnu(i) << std::endl; - - // Compute linearization. - if(idsolver->CartToJnt(phi,nu,dnu,fext,torque) < 0) ROS_ERROR("KDL inverse dynamics solver failed."); - -// for(unsigned int i=0;i < joints_.size(); i++) -// std::cout << "torque=" << torque(i) << std::endl; - - // Apply torques - for(unsigned int i=0;i < joints_.size();i++) joints_[i].setCommand(torque(i)); - } - - void CartLinearizingController_RNE::commandCB(const std_msgs::Float64MultiArray::ConstPtr &command) - { - for(unsigned int i=0;i < command->data.size();i++) v[i]=command->data[i]; - } -} -PLUGINLIB_EXPORT_CLASS(twil_controllers::CartLinearizingController_RNE,controller_interface::ControllerBase) diff --git a/twil_controllers/src/nonsmooth_backstep_controller.cpp b/twil_controllers/src/nonsmooth_backstep_controller.cpp deleted file mode 100644 index a5efb91..0000000 --- a/twil_controllers/src/nonsmooth_backstep_controller.cpp +++ /dev/null @@ -1,243 +0,0 @@ -#include -#include - -#include -#include - -#define sqr(x) (x*x) -#define cub(x) (x*x*x) - -#define NUMERICAL_DETA - -namespace twil_controllers -{ - NonSmoothBackstepController::NonSmoothBackstepController(void): - wheelRadius(2) - { - } - - NonSmoothBackstepController::~NonSmoothBackstepController(void) - { - sub_command_.shutdown(); - } - - bool NonSmoothBackstepController::init(hardware_interface::EffortJointInterface *robot,ros::NodeHandle &n) - { - node_=n; - robot_=robot; - - XmlRpc::XmlRpcValue joint_names; - if(!node_.getParam("joints",joint_names)) - { - ROS_ERROR("No 'joints' parameter in controller. (namespace: %s)",node_.getNamespace().c_str()); - return false; - } - - if(joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) - { - ROS_ERROR("The 'joints' parameter is not a struct. (namespace: %s)",node_.getNamespace().c_str()); - return false; - } - - for(int i=0; i < joint_names.size();i++) - { - XmlRpc::XmlRpcValue &name_value=joint_names[i]; - if(name_value.getType() != XmlRpc::XmlRpcValue::TypeString) - { - ROS_ERROR("Array of joint names should contain only strings. (namespace: %s)",node_.getNamespace().c_str()); - return false; - } - - hardware_interface::JointHandle j=robot->getHandle((std::string)name_value); - joints_.push_back(j); - } - sub_command_=node_.subscribe("command",1000,&NonSmoothBackstepController::commandCB,this); - sub_parameters_=node_.subscribe("dynamic_parameters",1000,&NonSmoothBackstepController::parametersCB,this); - - std::string robot_desc_string; - if(!node_.getParam("/robot_description",robot_desc_string)) - { - ROS_ERROR("Could not find '/robot_description'."); - return false; - } - - KDL::Tree tree; - if (!kdl_parser::treeFromString(robot_desc_string,tree)) - { - ROS_ERROR("Failed to construct KDL tree."); - return false; - } - - // get wheelBase from URDF (actually from KDL tree) - KDL::SegmentMap::const_iterator segmentMapIter=tree.getSegment("left_wheel_support"); - KDL::Frame leftSupportFrame=segmentMapIter->second.segment.getFrameToTip(); - - segmentMapIter=tree.getSegment("right_wheel_support"); - KDL::Frame rightSupportFrame=segmentMapIter->second.segment.getFrameToTip(); - - wheelRadius.resize(joints_.size()); - wheelBase=leftSupportFrame(1,3)-rightSupportFrame(1,3); - - // get wheelRadius from URDF (actually from KDL tree) - segmentMapIter=tree.getSegment("chassis"); - KDL::Frame chassisFrame=segmentMapIter->second.segment.getFrameToTip(); - - segmentMapIter=tree.getSegment("left_wheel"); - KDL::Joint leftWheelJoint=segmentMapIter->second.segment.getJoint(); - wheelRadius[0]=chassisFrame(2,3)+leftSupportFrame(2,3)+leftWheelJoint.JointOrigin().z(); - - segmentMapIter=tree.getSegment("right_wheel"); - KDL::Joint rightWheelJoint=segmentMapIter->second.segment.getJoint(); - wheelRadius[1]=chassisFrame(2,3)+rightSupportFrame(2,3)+rightWheelJoint.JointOrigin().z(); - - const double K5 = 0.0018533548425194695; - const double K6 = 0.09946140462774823; - const double K7 = 21.65458426501294; - const double K8 = -15.40102896939387; - Ginv << 0.5*K7, 0.5*K8, - 0.5*K7, -0.5*K8; - F << 0.0, K5, - K6, 0.0; - - return true; - } - - void NonSmoothBackstepController::starting(const ros::Time& time) - { - xi.setZero(); - xiRef.setZero(); - eta.setZero(); - - } - - void NonSmoothBackstepController::update(const ros::Time& time, - const ros::Duration& duration) - { - if(duration.toSec() < 0.01) return; - - Eigen::Vector2d nu; - for(unsigned int i=0;i < joints_.size();i++) - { - nu[i]=joints_[i].getVelocity(); - } - - Eigen::Vector2d u; - u[0]=(nu[0]*wheelRadius[0]+nu[1]*wheelRadius[1])/2.0; - u[1]=(nu[1]*wheelRadius[1]-nu[0]*wheelRadius[0])/wheelBase; - - // Estimate pose by odometry - Eigen::MatrixXd B(3,2); - B << cos(xi[2]+u[1]*duration.toSec()/2.0), 0.0, - sin(xi[2]+u[1]*duration.toSec()/2.0), 0.0, - 0.0, 1.0; - - xi+=B*u*duration.toSec(); - - // Change of coordinates - Eigen::Matrix3d R; - R << cos(xiRef[2]), sin(xiRef[2]), 0.0, - -sin(xiRef[2]), cos(xiRef[2]), 0.0, - 0.0, 0.0, 1.0; - Eigen::Vector3d xBar=R*(xi-xiRef); - - // Discontinuous transformation - double e=sqrt(sqr(xBar[0])+sqr(xBar[1])); - double psi=atan2(xBar[1],xBar[0]); - double alpha=xBar[2]-psi; - - // Backstep controller - const double GAMMA1=10.0; - const double GAMMA2=1.0; -// const double GAMMA3=1.0; - const double GAMMA4=10.0; - const double GAMMA5=1.0; - const double LAMBDA1=1.0; - const double LAMBDA2=0.1; - const double LAMBDA3=0.1; - const double LAMBDA4=10.0; - const double LAMBDA5=100.0; - -#ifdef NUMERICAL_DETA - Eigen::Vector2d deta=-eta; -#endif - Eigen::Vector2d eta; - - eta[0]=-GAMMA1*e*cos(alpha); - - if(alpha > 1e-6) eta[1]=-GAMMA2*alpha-GAMMA1*sin(alpha)*cos(alpha)+GAMMA1*LAMBDA3*psi*sin(alpha)/LAMBDA2/alpha*cos(alpha); - else eta[1]=GAMMA1*LAMBDA3*psi/LAMBDA2; - - Eigen::Vector2d eb=u-eta; - - Eigen::Vector2d vBar; - if(e > 1e-6) vBar[0]=-GAMMA4*eb[0]-LAMBDA1/LAMBDA4*cos(alpha) - +LAMBDA2/LAMBDA4*alpha*sin(alpha)/e - -LAMBDA3/LAMBDA4*psi*sin(alpha)/e; - else vBar[0]=-GAMMA4*eb[0]-LAMBDA1/LAMBDA4*cos(alpha); - vBar[1]=-GAMMA5*eb[1]-LAMBDA2/LAMBDA5*alpha; - -#ifndef NUMERICAL_DETA - // Analitic derivates - Eigen::Vector2d deta; - deta[0]=sqr(GAMMA1)*e*cub(cos(alpha))-GAMMA1*GAMMA2*e*alpha*sin(alpha) - +sqr(GAMMA1)*LAMBDA3/LAMBDA2*e*cos(alpha)*sqr(sin(alpha))/alpha*psi; - deta[1]=sqr(GAMMA2)*alpha-2.0*GAMMA1*GAMMA2*LAMBDA3/LAMBDA2*psi*sin(alpha)/alpha*cos(alpha) - +GAMMA1*GAMMA2*alpha*sqr(cos(alpha))-sqr(GAMMA1)*LAMBDA3/LAMBDA2*cub(cos(alpha))*sin(alpha)/alpha*psi - -GAMMA1*GAMMA2*alpha*sqr(sin(alpha))+sqr(GAMMA1)*LAMBDA3/LAMBDA2*cos(alpha)*cub(sin(alpha))/alpha*psi - -sqr(GAMMA1)*LAMBDA3/LAMBDA2*sqr(cos(alpha))*sqr(sin(alpha))/alpha-GAMMA1*GAMMA2*LAMBDA3/LAMBDA2*psi - +sqr(GAMMA1*LAMBDA3/LAMBDA2)*cub(cos(alpha))*sin(alpha)/sqr(alpha)*sqr(psi)+sqr(GAMMA1*LAMBDA3/LAMBDA2)*cos(alpha)*cub(sin(alpha))/sqr(alpha)*sqr(psi) - +sqr(GAMMA1*LAMBDA3/LAMBDA2*cos(alpha)*sin(alpha)*psi)/cub(alpha); -#else - deta+=eta; - deta/=duration.toSec(); -#endif - - Eigen::Vector2d v=vBar+deta; - - - // Linearization. - Eigen::Vector2d uf; - uf << u[0]*u[1], sqr(u[1]); - - Eigen::Vector2d torque=Ginv*(v+F*uf); - - // Apply torques - for(unsigned int i=0;i < joints_.size();i++) - { - if(torque[i] > 100.0) torque[i]=100.0; - if(torque[i] < -100.0) torque[i]=-100.0; - joints_[i].setCommand(torque[i]); - } - } - - void NonSmoothBackstepController::commandCB(const std_msgs::Float64MultiArray::ConstPtr &command) - { - for(unsigned int i=0;i < command->data.size() && i < 2;i++) xiRef[i]=command->data[i]; - } - - void NonSmoothBackstepController::parametersCB(const std_msgs::Float64MultiArray::ConstPtr &command) - { - // data[0]=K5, data[1]=K6, data[2]=K7, data[3]=K8 - // data[4]=Pk5, data[5]=Pk6, data[6]=Pk7, data[7]=Pk8 - // F= [0 K5 - // K6 0] - // Ginv=[0.5K7 0.5K8 - // 0.5K7 -0.5K8 - - if(command->data[4] < 1e-3) F(0,1)=command->data[0]; - if(command->data[5] < 1e-3) F(1,0)=command->data[1]; - if(command->data[6] < 1e-3) - { - Ginv(0,0)=0.5*command->data[2]; - Ginv(1,0)=0.5*command->data[2]; - } - if(command->data[7] < 1e-3) - { - Ginv(0,1)=0.5*command->data[3]; - Ginv(1,1)=-0.5*command->data[3]; - } - } - -} - -PLUGINLIB_EXPORT_CLASS(twil_controllers::NonSmoothBackstepController,controller_interface::ControllerBase) diff --git a/twil_controllers/twil_controllers_plugins.xml b/twil_controllers/twil_controllers_plugins.xml index 15684e6..a2346e0 100644 --- a/twil_controllers/twil_controllers_plugins.xml +++ b/twil_controllers/twil_controllers_plugins.xml @@ -8,24 +8,4 @@ - - - The CartLinearizingController linearizes the Twil dynamic model. The - linearized inputs are linear and angular accelerations. It expects a - EffortJointInterface type of hardware interface. Recursive - Newton-Euler from KDL is used to compute torque. Not working - properly. - - - - - - The NonSmoothBackstepController implements a non-smooth controller - based on a discontinuous transformation and backstepping. A feedback - linearization of the Twil dynamic model is also performed. The - inputs to the controller are the reference Cartesian pose. It expects a - EffortJointInterface type of hardware interface. - - - diff --git a/twil_description/doc/dimensions_battery_bosch_12v.pdf b/twil_description/doc/dimensions_battery_bosch_12v.pdf deleted file mode 100644 index 2184e85f56cba86bf821494bde00bbbd3fb014b6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 26816 zcma&N1yo$kwk?cXkU(&4f;-)~ySux)yAxc4ySsaEg1bAxA!v}`?(oRD=lq0^ ze~;0oen z0{9OH5`w#d%ZknwNhF|jj({@RY2ndNWoSQtTn^TEQx`nPthK-PCq{~Z6C8!J1AO_P^OU z*#2q*F|zzE77!yl=x^Q;0seJv zAQ15HecwC(bv-~J(BIYw1Y%xT z?L8?FoSY3Do&Ssdj7SJ%WFm5+NC>douGY!8VI2hJGvL_P4dw&1Z*FQ7;4}|~J4H*+>17ibc1HgM4y<;io z;%xn{Bu)U(e_<D8J$k7PByLEB&5VLbOw=iN5HgPg~hu^@~`A?g7fd30W5!-i~ zSlF5|NEp92w{Z5L6K7CzF?9X|>mO|2o!Y6`TKwVCyO95h^1q_^GswT9_=D{~qxcUT z{3rX^SXll=I`QyGWgRPgAfk7d-qwCEN1gEqYhv#@*$eoupHdccj%394LA=+CZqJQv z67Y0AwXRdRQKCCM*>1Z@OEzzMzQ@BlYo~j2FMTQdV>M56bA59+m+o)g9o{aBW2bxl zIU~?+ubm%+vx5Sh_BZIm%qF+te3_8(tv01c%;>i#W7_V7hx2mP;iZ0Gg%yK^IFd@!y0RB*IY_|I|39kPS8VW=@N0bAHazLmUX>D&}%qHt*~_GbFs|4 zu0A$)Zbrw;a}O?nhHf$OO13#Poa1@$racQ#KSfh~o-To-4L1DhKow)wj|$x3hx#J3 z({bDWXj|c*_^Lgn7MZNKSnCMYm?~*h{IfFQNTHjQv=G<5;?vP{pgK`n{`V}=uf0d!7=w=x(^18Mx zyBx8)B)_a5BrYk^)SF!ejht)^u$ORW7#`Upao)o8tzG%W11Cr8bN8=o0>x>h;W}FN z8Qe%@oKB(S)n`6E2y_1a5HDBKDRp|&)=k3U6q`(Eujh#4NdKJ^K?sxA1tPR9eZ#RH z1>dA zShnvataX(d5nU`7u`=d_tv-eS%-g#;zhE%Na@WR5BeR7U(Xhs%905c`*@hhEI!LWJ9#>ER9gc z690#gxI|0IbWQ2GajpiIgUc5jV2s4Yx3}JH5s^EwcOks{os9h-gz%3V{jYh$%FOZa zc~hy}R*eosJlUsFB$3(W&I}ETt=@xRVe|#VNT(}}z4v^UG<7|jRWRO(oVutbF!Q=W z@^rF&+v%?A5p#Yzx+DasYU1%jtl*vatAe{f7@O5CQ?ZuPsc#GSTC33yNQ%>d&iY=R z4(E+%4%2LlRjkFkIp{z!&zv1oX&bH>AB_&0iZ{6_q9K+LhHtkf7GM+0r znM8l5G5|@5wb0C%e3x{VhIChkF+djp6vCaoFE(xg z19zUkZzesJ%MRzAexkoQ=yj6_yS=QDFhe0sSm(=fgCA(ZY`NH9gZ0rB7ltu(+;5O`aYp1JhJee4@x9x=aOD zJCpHtLDk#rF8TK)XpIJljMh}QLK*OM)3yrKt-m$-NruwKNQP8{Io803AxqnS+-Mbu zl{s9lgss_j*xt}IYY9d9E{woZG3cq|VWLiVmmnk(rjb5GqJwMOCtG-PoPVWS7oj?V zA^l!EZ@e33?NLa}hlyJlvfx3;fwRqv07bMFT-8;4_67}vPP95^}KP)H@x>H3&Z1Oqfi zOfWRi4)T6A&>Q_wQ4r&rT~+93i4D(9xNuF#Q5b{#+K{#FCE4{;b|zd&d0~_EMfiH9 ziVthJM-_T-5+|kBQLZaWxbc?OMzdnn{ZQNg#tJ_P9Z%?dG*tSN#FgMt`@2v(_+Z}F zKV2Q@K*cId<9vh6$2(f%$>OAwKbx1J!yHPwVQ%g2wn_l4FoJpXZfCv7=R|{92Jhko zZhwdRZe`zDB89qdx&rnKE+eL{Wc?am*m(cfvS#$fj+H}C8avI3Hx96cS`J&vi~^ zN?jIq;J+(zVUkqzyAp@oxqQ{m%_nWTVh6X<=P-m0kXeLa)h6nqPVxZ&1q;$%scU`T z95{HWc7uSSMiuK9O<#WU+Sbbec=^ zHZ#80RwFs#^TqOFSCpQa)|G`Z^3J1@R z`vP+|+vM3+ql8`z>mV96YX|Mol%;Jxq4^2za*M-!-u60e^YhB)=#9oYN>hXZ(B?)Ag`p7H)N5p*UBgSjV`1a<9 z=@K%nsWJ;xDUO^|lt?NIiaAa&N5P}kST>t;`6Jt$FUJ#o&LCHQs`VdwwWGKEDSpu5 zK{eFLSd-qK>G-ETI6t|rW;jZq8?oFN*vs}xP`n9n_4+rqPAO)J-j+sFvoI9(^X*^IC7nb)9 zDW;hvQV_3N(_myR{Ja-BXOyl6>!ge%q>=t0HL$maiP_W2NLPJ6xpe~Ko$_0x#%WSw zDAQ)buitJ!$D;jYLJ7zx6s@Lo&xjoBUG{*oBeg^z)ANyhT6r zeGK{t&B0fo{ZR&oinMh|<<#-ZE7?G6Y_`uYFWocp->V!NhZym5v6s}@!@_fsci7Od z5BUyjBJv&cwG!k+Ms7K^dtst6qEEIj@aavRhXSKK-;z6UUO>jX8PTnkzu5>b5=73I zlxl0#cS}m^Q!869y0y7VgEf4gA?&eiyjG)_v3IcNR>FXlUD!G%@T@~58DXm3BsrfM zwjUg+il|6p&uVC-sy58xKNaM6(efzj_|6v>3&l@nytxT2JFs@7{Oa%MRxyFwE_)1e zH)`xrF3X3k@caat|Dug}K>3^}ts#VIHl`(g--fPjb$g`2eGXS=rDYuhOC&U<{_EJ+ zy!{1G_FKFA5-yWR$y8r^K@2Yf-3Z~?FAa6_Q8^+X#@%4KNxR>S)A$oox<{BpWG=1vB+}F zFT;yZm+&iw9x=#?&U9tfr>lqCW){(VMJGE$Z1&@%v6l!?r)^RSU+%y@=X$PhOYw2V z?*yvDe6I%oE#C7giE)YGjGk$F588HQe`%b?^Cob{9P|7J#aSXy!mtc`oHsr4fO94rkp6%)DL*)O~+U3T&I4yM4pag-$&u#a>8GN zUtqjN@V(JXt% zwphk^SG+?m1I1n6O%&-EX)4Mk3hWyT$1%dOAWsh=Ebx*8`p2DFU;Dry9XP+$U1p5& z{%nhFUzbYF(_Nb+`g5m&A zSXetgd25?l<*@I1iKn(Lm`PP4Z!IX>NVCB{Eh7fW8XSnEPD}|m=FDmdN%omHuRaLy zv_z}d*Jm^3^Rk)=inklNYCSMTT;Mh!i-|=+Uh_DMoozdmIm?hM zYs@vEUXkwQ!p$)HL@n(`*Ki7cvL}oA%YtK*&aX9bqlkfJ-4rKs%vsWJpOIV^_BT;@ z`Kcu^3W@?wK|ZU9_yyp<$s8p$Ge(Pz+k~5Iv82ojdP`|5o=fbdO*LS$tJJ1^P=u1) zp?Jg#e&kkn__W0Gy)lBaC)(K8QI;$y+Y^|UEGAB*t)k{$aDu3hcr!l?UXy)>p77G? za-twCRM@_0>fM|S8m!H+z*c^K#L@?oytj$_Pwe=Amx=y)i_XIIKQ3_2DkBb1#E8#w z=%kEFe(Zhr98kV)gp+SZL6bb%)tb$oL8QVTCY5Ul7271;@%LYAM7!eIGFMyb*vi>{ z&=om1e%qe1C!zv*;~ODxY(f}pDLzVL2bo6?6FK%g9*o^xxIBlTZ$C=q8CAzi-G4_h zK6g_jKvYGV4pI`gHvYOW(0l-WIl8>6PT&B4$>JLB)ChSo!EWpNfN+S%(ciKhOG)sw z#I|1RkhN@Jzdd@0q{;cwm8jFBfS1CjHwq+^#1ZAyx$=n6k5{i(i^$F{!ixTx-bT#OJ7N?`D2>j3{riN;^JN7#NGwME2ze|Ga^pXS@C6wxLYfta^N#s2)hbNX^> z-Tj}4^>4+z|9kD{y=wOFvg52G;Ydo1*uF?}4<-y>%WKptmufX{@al_WW9`a?Ka(T~ zC`=T8!j2CV(nN=Y#Bzs5$F2$g+X_BLol58)+B>XVLHQA#Q{~i+Jcp>>L9D3LMa`hY&Jt- zx7}_XhvQ7k4N$q1axE~ zB|mPGk+@te_g|f3QKJlUZiIszuy>h|cT>3v{k$CV`SL2H1VX3mD{nJGp4;)f&ZKF?04NxVT6-7NPUnVx?YpT*Tj0UvO=RxY_elj z7Rfqi?;l$;VN3V{Uu;E_ol|)wE?`#5ka}c30A3rmOTzR)C8h)4HfeS+RUK%UMc@_$;*U%oCyTL)>uJ={6)Sw4G(bvL@dC^(#25>jSr{+1$we33Xg9=i&{@g9(y5hFU%_Bz9Qml%&6 z#V7!~Ij@);Z^pPloFV18+~zU^BY%$gaxMI#P}t7_?wgF;8YdBl(~td@4!^2E?UK-C zCzTY=d9t)7Wrc)1qDs04`DBCex+QKTo3f3D;5V}GZxD!J%ZXaG|B0CYRs@!FG&XU3 zuX0lUca@WhLD9s_;=L;EK`HS5@X3Vgz36FgZ*5}pr&P=Mufitq-|DOXcXk8+hiY1a z!7+k?`GfiYr=b3SRZ4+O%A+j{gT3-EjMquuv-S1%VRCRZxPdlp zG-`=m6F>-@Rvn)BEEs&ua#8v+5~;PHcwty?11>C`<0nE4beK5HUkdW6zMt}I*@Feb zg5!`OUG+zur*ZW;ks@8h8=xJ%PGPVQB477UJN9qh_PJu(+5lki<^ch<^?Q*x8%u5M z;Ve1lX0N>}G&gQi&0XN~)VV%Ni!CjAbu@7&$UT?g17oU-6L>Dn1Yu`TqI!`(La<&A zr{aqEU+I7H0eiphp0=v=Mp1g39F zh553D2r8uJpPQ5ys`?-+3>U^V&IP;3@DDO#XeJY`%aET>FQIuWKJ+yd4A=3MWA%YW zplayc*4qWoo2;IcfL0zwxlo$#+gyaWLY0rWjzSJZe+N2L5~)Y-i##8+9yP};NAVq8 z576A^xI7bkkP)Op;iufw$tO*LMt>V;pKcopOWXjtR*0C(yCFXhzrxbRF5j% zC15c8K^B*(nyOdO3~JkMa%>DW@!*Wp=EHy6H(!Z zFKHzFK-sU&yvh6;qFX!kNP;gO3JY${FSg;fAbs?OwAK_~61CsaT5+dRZgYD$ymG2L zq1}sEcUznF;^Appl;%JOs4cBJNTaiWTCv(Xkxhji0FkJVY{{Nudh3&M$SxZz88e5N zF4O4jw{pmYiiUbY;~=|S-f*YWB&(&y&;4F3OMKGwPs6tXs&2Wo2lAK?Q8_D6N97%& z7kgS3efq3m9D$Lql8H`%5vo``uGmzH6J5x)TA83#l<2S!c=VN87 zVn?oyJ@zC>>}4EPS~+#tIJ&C1Sx{;!0=UHF?A@qq19^LKeisp6W8V#rT|F}3@^g8R zld0LT@bY6#ZRk}wEJf|l47qqAO>HSzWA=>{MfV$6VK*uebcm4HCo-Sjvb^Tg?VV-H zIwalgJCz(gM6FRUSD*W~1k5Lf`Nj*BNlL5{_%z<788zcUm?aHXzmJ9!}H%Sp{;RS4`Y-~&BV^npT=N5qM^&Gj`c zzjAr-D;f%VXO10CD~o(|d=ZrpPgy1|GsR;v-CeFjH5IuB7ZLwmN$s&D_B$^%0dZGd2Z7IqhMEf-lFm;i$>lek!tluf@mKIQO>4c za8PsTsS2M=M#{quQ6BEw%>}({6}0hkQXeP%+jlF5AS;*-^g_g~To%6fXn|M0-=o6Pyg`DWikqq74rtgJ+IToTn?r zoMO`G2yA}@Iig|VMD)r*7os7r02Li~o%<+CY7R$-$4+uPoFGBfErE<|=fKg*Vsndx zDXfNqB23r?o`dYN)YnMQbxawjEc%TyL~iq&r91stl!-CA8U%Oj#x1*<6XtS=TEu(# zQS3f|O;(nvZ*ODB#zIi?0cbMSRCt_>*mgl)Dc`cO#Kk=A&ge)g@xjH(w)=dzEKQX0 z7!Q*GuHMo`t4xjI%Tjy_o=eHK8Yd^tVU!25(M7S+?46#gf}#S*>Em zUgC_Ncy#x6hi3{-BpfiEtZOS&!9vB@0|xOU?0&y_^sS4m~g)ci9CN(mcH;9TR5m#h^># zK9lUN_;7Xc`tX!nYU~~JyDnKzjw7eh3E0ZOcYQ6^FgzeL9Y%ChmthGxWgR#7_`ZCA zvMyED$GMP6)j`(-=b-Q_=+$z#VcRdBD&Qq^SUHs@$0$*a9u9rYCSAGyo?6HF9&7#z zj%A*9%jW{awzg!#sMW-xX6W{l#%cW^ReT~jaGI`+5+;LmmegTKswiH!dypHBOJU-b zrnEc!YiY5oyeJL+BuOGTc>afzuL16%3j&8k)L$thoXT0HC|x=n7)i{EpG*}*=c6AO5l_t*4(~&eoZA{TS(ZJ7}>_VINP();c#88*ur$a!B%S?NtX&W2NNUMD33h= zOg!;5Rj{;#A0ccEom#5dRsEFHiYHr!dycoREQ?rB!lwO{a1lFOC_KoX2lWwyu0<&T z2$Yw`YiozW6@xN`n=Ph-ELd92 z&Q9MStY)8a?LT22)8`$peWzm=Qx;+#pnc7*^RY5`%`B=v3lE1Xx169rW0_x)C1Ia+ zyW*%!`KnbSz$J=BK6sAf42$ofTsOjSu*b})egqnDu8N(d&(Nf)q78|!dT^F;DaBl2 z!a@u>+P-PwU0A~pbSU82`xu;qM(#V8-(gyyPE^t8pZ?Kfs^9uzOWo#W{IQiC9v0Gb zt--)r|0(nf-=q0c_Xb<%^Y|fI7De&YG57q;!$R}OMmPNgr+1-y^}WKydmc^X?2sR~ z@zoYJ-`#XQW3;i^WrKYSwBKFq?y4^pK!Yzv^nwN|N8kjgJLc@c@eLQZpxW!u%Z&VlTUtyxN%KW%L z{Qc-Me>wGojwgO=netOR3iDWxX)4Wi#ly9vqNzB39>n`aOkO_w5Y#(6EB<}eh_RO1 z2pik-($t;T#6VW=dUmw}JGD2-z zT<1i&>6?MwKq&0Ov*$b)jj5Y84jwk0sB6$ZJ+AxCXuMvgwx{#Y&gua^1J%s7R&VET5o_QK5tz z)v#Mi8`AM-BrE|nFjmTUz?41)DN#tJUS*&%BjYB6*7XYh3^F{``i{tIwyj(^3DbIlKi@|(!ep4V*TkFuKvOzJeLOQgX0ei0_{Plid;%E-$IwVuGuF zD;x@Hgle-jYOE-pjp6?CV6Kpzf3aI14x;40DEtsU5^&h>z{*Wx{ULlyzcjsKVpEbA zq0taYU_SK=j&fd2SN}-(=Rw1j@a>R6cez?_joMRS&)MBbBeVg!}905W@{Vji+busXMW>wYxj4_atn{*+`x&U5}n+^PczS&EPT5f?7}eivyQ@tX~=z zLJA_dLQ-nj@1Cz}wx*i+7CpXs2wkRi1lugKHlL*OwK}|zl}d`ZrI`u1oruSe{@h_) zj8aZ%R9~gD%tV2{{|3-z)$cQ~8U+^hJuqVj4>hn;jRAe6qbJ_v(o0~jtev=j(jHw0 zrVy$f;huv?y4f%k3)l)Z#-J*TgU%uP>bT|HlWF_m;KJOKDUJnYO}5xEY6O)h;DQG5 z=jh?^)jvn?=VfX4+X{yf7}wf->?p8Av&SpVC2%;`7OL!rNiu)t=F`QW+EC&YGeUEZ z4=tnRtfL-{{N-P3??U+r!^+zFm`NAfDQFG?S&C-SygI04>@-M#w* z=}U3>hmVp}-cdo7#JJS(WkNmt8h-YeNgWZK;T<2Iu3zc#(VlgF45qckj`p;)+LukP z21BIVV_~|d?JDTAXEU>b>L*?$a4Wp~Ee!&E>JN#N0-Y@};bB7^HdCHP( zF_^frSDJUq{MF<#xf8opFjN6{OM83TIW60Jn22Cia~>Rv`?p_w4`(|<9PHu zsbi~fD!m-OnkjquX{fN3H=yR|r^^e@+|fPx_p&0a^DtLoF}XOU6(i18nYNtc#o5Ne z#z`CFhy<$r8@MCKeh<~Fe2IIM)p?@Tevgo@yQj{!r_)KZC+i`;%fKZE>-<7XAw>9T zT9%^*LnTh;D%7fEMjKg}2I>(>a&ggl+j0JLe!vV}%pYrmKdw`k(L`ph$WSLcV${V&;f9=goy;+(@?eTZQKYs;69jvsZ% z(&|`5j8~7H*Yt~H50*-=QZ5*gy?=Ga7LLIC3L=E#&v>^`3S>jF=X720-0pL5ha}{N zy}N=$sq(VSxtaNP6MXaBm14UFer_h-)4|yE!Nm#6r5=2_D1q@%YA7Q}icLH$q{p1% z^BS`I{^w45GOgdg0cpd|lc}<=LQUv6+xXSV(DQ|h*Qv_M#`Gj?&tyK-Z7h1o0f<;i z*c{s_Lf-{@ORENgGC)Q%A7R$Oe$@(7ulzXZGv{K$i6HXVh+TjDx&LW_YvG;paHcQr zQzK3Vc$JIEQlFeKH8N~tr55tCrbzLK9dAFcaWrFEaR>B%-^#QUX;s*gR&pVhLKxDQ zN_3rc34uU8X^mADG7>(R9Xkij@Q>l<3r)3fqWt7EUEOA2z?xD^9AwszF7J&|n8|#` zF^IVQaA^Mu&guO{J01I*sokU;;?l8D`!e8Enyl(jvs!vJ$?{BcK$mO>RxpXUA_AGE zKxSR$s;Wx=Dzi0dwHcL9@GYB9x+{tAIkP^{zddWnEA~Yz?j0y=7xS$pUSt!JU3+V*^N`91T&REs>VLT6X87?0#6+i<5FL#tt<4n#4nj*~``Au^s z8}N&G64-yV(DH`%suZdfJi7_TXRx5}pSB35`+=!qSbWTGIf#NXD+ddE1x~8u!=>Zk z0?w0^V|R8XqHVgxi}RgCN6=qBgvw^0d6PZqP4*V#b6t>JzmU9JG9o3X<8- zR|6l#9;ubYdit0TRin^?C(|I$ee6VZqpA}&RAG{1M7l5$A=JpG3`eP=#}Dw$IR&*V zY|`!-!6)VG?hxX6jSz~ycskCUZ!DfSjoxRhPzPT$6MU~9MLYp-ClW}n{UgP0MMC%y z6!3PM~uOH~#jTC2fjWvig};UMsZVx*KX=s#UBWM&(Z2=`t_&r&YHdBqH}V`7Hk zS&%SH=Y>!@!=N^xeb)`gF^3^+-lH7B7ID}o(F?hn+&)M6pyF->kEQp$WZCL&I#x-D z3-_kRtApt1F6qNpJeqJ}^@XO&lZ6Vr;GbESMh;4^?0pFJ)mH{9k|{xN%-=ZPa)e*6 z%!s3T=i?SVv7#pLHTpzF(|aiWdK zLqrs8C_h34OG%rG8;1BU5u3SS5XjT~E;;a1GPc5ee>jn8r^-_czrG$t=|`u@D3*V` z?!R;+x^~3iPI2mT*x2Ff`UT(XGGQq}r!cZoGV~O~Usr?09uCp1);f5($aJ*iPJSpP zvv?WIq(|6dHeot}OpzVdXJ9-I)XmlW;Y^S_mW0<|DhQY3+)@;|7ztBOAaO|mLhU#u zZzOU?-lolt0p4od(gUy4*CFMmN9r6d_T}S7x9=l z%>crh2)xsHdJZj9=N6`-=Fq5ECgfM5DIq{SGcCGGULBvmiO>fmvM-tvC_z;8-~-3R z0#vg~nO;^$mM7yl)IqWwm~1;fOuJAMT*SPH;YU(AOAli=97pvST20SxPlIGqK20j= zaH^e;Ysum2>~92RKOJj}JD=*m)L(e>u(6Kv4Lqii%2pS3Y3$cjmq$-seF+o?eFEb8 ztIXVV+U!y6S}JGLgfT=zMXStEqm%bLP=<>c@$%K|My6^9uve8MsLd)INWju~k+G~D z8T#najza1txUmj~-7mVFtnrIjVKDC9(<*GA-~Fihb&q*O0dIv`lRBO(0V;|Vk~&(d z=yn`k*#Q}6;G$F*dB z2kLB@o|X&I3UCP_2?!u*VmXSrFflkOvnWvkqf4YRzecM7Wegxmen~OCxMDCD@7Z4z zHX=P7F$t6FsX8lGzAT;jB!+5+XNV)-Zu0J>bE7Ye1JDsF;E4wN)@VG}cGE#Y`Ji6c zWw==P#F`s(XawQ+NBu^|qLN|=)eLe-idNW~c+qZ4aKZvsfDAms z$~7!Rq;bM={4A;Ud?P|70PazdxHtwk+LY+V$;3bX`4mEtIuV8!A(oGFJ-XW3v2GLp zRah>12PG*1xh{vZv;iYlTsS!Zidt+1TV%y*|I&uuQ+OMboVZ?2+1)t_-sb_NhlJ`}uAHz`JH|nVzZW{iVk4sWZLBn3xQM>E zqV|2Uo4^0`Af<7}Lhxk=Bx*S; zfd0h$JFjmtwB zE*PfQ&N3HpXtZP3ZU*shT1?bjx^VBw8L**i2{7v}O=g<%^?&H;qbB;%b7vujZ&Cmu zZw;os!Ec#+X6I0P(U51c&!RNy7d69b-rH}_eWGTszsKwS>F!Lb^B8h{LtwGwuW;61BH^Z))W*;tyS0)EzWkX<%$bjQ%!As)b z^=AZWwAr0Ts1T$AO)*P$%CY83EZu%SvAfh9Udg<8S?(8|5=a**hW_li6{?_biY1!* zjW0a3c*p82idM79(R^oUF=aGm5#~;K>IvJ>atVMQu>X^|G~opkq}WH%kjq zE3z?lPo|R@1F-!W?V>>WVn;!8gD26JO5gRW z_eeMjh*>L5^_LppP*bEn7*xp>r||@`=&3d>_kPu7w7^u2&ZC{d5?bbEG7A>j58onI zm7&4)i7ohjRBKo`YoDPQzXN$QI+C~u@<+JmNG|9*B3yPV2D-4_45i!}ku(vhi>>GI zZ*X4kGN@K$rx#2eYiR*7)#UW%(0VQy_+EY$P5HW>jAw}@Z)LemM5yxC;uW9ToEv=r z4@Y)Z&$=K9c%dfo@))fS`?|?59u3Oe{CLf&0Or^@_f@F!7@ZfR8eW*vjVeiuz>I(g zc{_|MKnor#S0w0SHdx|QJ#(0X%jxIewL(BF)070#wn z!y4U+1WcC6rUs&V%C81&S_5UJAe?KM1Mb)ET0^fBt+#vIud>q{JlP>l(#4}j2AyjS ztyH`bw%?X)KCX1jLJlRSm7cGggU~5TH@K6A(>r1sLBgbYSzQK8$lCds;&4p-?3JY0 z*P;?IB0N%_a09WfM!z)5#PYGrbg+OYc)i`-Zj#35_(ntbO zFX9-97bW;`I6VP_jNMG8qN^MJs{JW~%ldDhR96F$DC^AHB`@_r6zEw(F z*qA7Is$tVhfmc`_KVXLK=%l84|EQQW@K7xuvDn0OMw&JCskf~!98*{ZyJlfyn94B8 zn|O#W?fDp1hi^FX5Ma%sRR@hSaw(YLblCn}Yj5FHR1}ENY^LIAz>%$%MnvUqkopDY z5hmm%NRhL3PM@YYZMK8xuxa@a^QJmi=`5UB!9F4yTL7mWWhT-^I*hRgK!6a(kHHi& zLU8CpUa3yLELogrzOE|DqI2~9!fUm;No0>VCAEtunW?S0?A3lCI=}cUhRs!z%$od# z^lGn7gJ(H)rL5lf<6nyl&TbSj@)18b8gegst9}?-daE5Ng613+)nMp?pity zislPkalu^;$z1KZT-xEZ`u&H}0Ps4^s`ByOD24vz{LF*O;<5T&OX6*hRJb|P)J_pp zR~iASFofSit_wI%Y^y4e=<_bYQ!gHNzJ5CL_7A{Ta17Ru!OvAhAOf4Tm|Crhg`-kt+*}x=hq;i(k)mMfF6z!D! ziJn)3nc&yOg60R5+vU4sgFBN$$1+mjR?Wrs{;S;1o8Tw~+NWKd2Zb8Ej`_~crc|q#{>CG;SP8wM>=g(ix5QfYo^8AP+@u8t;0Rs?()v_oQUB7e zra@tuX58-0e25%L9P6pdwf#5B=`js6`UY#>(`9R1>HSmN`-DB@Aiz`#ea-XfT4dzP z3-p88(O3-Dc&Rp56(`S^qsjL6ocR;QE_y9ZP7ni^*>NKLCo?-+UyJAGbTSc=`jE&B zb!~31b%Q|>czXpi?LNYDNquv4jr30~ zv&W96{m6!1$?4>+3y=Jkoy3U?bHR~V z{IH^1Au8s*59@_;5d4y+-H@7MedUQ;Q0~eZhz*4C6uZ#ZZ701lA&8lv2>dbERSOU8 zTaiUpDGd?|=`@FYR*$_xu@Tib*yU{;(9)*vLZEIkELeX9Vz{$dddoMN!lq1fE4B&! z(mek-mU(f7<-wFh{sI48cggSzuP%~M52UT|yn;Xs4LkOD5Z3sFc&HrQ{dk84p58)z2g#cVmF%|MP7v>q1{M8=rv;m5&Vs-K`M8^&!A%1-|1TX!BzNhzWNCI|w3f*%i8k7WtU4k) z6WX|jo~0V?A})1G!XvVpC79EQUlLReeX6)6jdC}Xjx4zMVrEo6BYC3peZYZ9L-2sC z`*iu)n0IR5%%C9PM7=dDI!$jzb;oIR2I+_8fJwL`yF z5e6flddqxMF)F$tCOT7!#e9a1~A7#?*PDm=a6=gH-(U>@VxkaM%D#KCC%c){lH##c}w~A%# z=&iXdCw=Y_1<|(`F6|`{Qv`mr$rugtMbq{k>5|t(RgL>;V#7tYL7hFGv#5MnKe>8R zNoaD1^k3RT@G*7SYB=i1$9!)O-{7C%-m)?86B%wpCi(XSez$oaktgfPjVV5ckN$d| z5gdkl;jo!z8-VMG8@+fV*fBV;qwUsd`0NRW&t0>xM19L5Ba`uq zRJyakJ!koF#0MwcNmru;$I9zCfzs7C8C;~{*G08$X-=?9xr_Ux5070-qu0d9t8dl3 zBCd214dW7)9IiL(_+#92nSb@#(0$5hawX7icB)NL*%%t zBbt0LU5AUP_or((9h>aBf6lV4VtX{OWjF7N`!`nq9z z?Ee3>cjjR+u3-Zw6eX2VD)kziMAN*pFIu!Hp_0-*m}Y54HB&Q_7TY4&pXpHb^2W2^k z#z)Ox$I@i)iB)M!E(B+u*;me~$|U8AWPM<;Ai_kuRN@jgtj7-uxD) z*fZ@p!MnHapVdQHR2N>`R7=Ol;gXiTzf0M7A*t_A-|EKkm07qu>)yYG^B-MLSBd%a%1McUnoEbK+dSy9Zj*xl5R# zv)&!+(+?m~>JzL5a@yKCoIcvu)RwWq4AZq2F@;;bp6JOXy;^@mJ?GZupoqWceB(X) zXnOuf$Kxr9B|T_U^y!nuhA+2jH(d@PB}HV~J=uq))aOKg(0eZ5d!+u(r2@@-PQ%HB zZ`V2NS_?>MC+uUy8Q$yxjOGPp|Wm$+A}4l4bQ5DU(;9is~y5v=?{S zpCh}z?&{Jh3r4Md#?aj}Z*rl<7Bed@-)+kutqYS%c6n70?{_SX-qpiVc{shJl~6x1 ziW_+_XI#_g?cRUPkfB!Sgy)Vvip;P`bUn&+F;Uop0cfaJ|BvcNsMkR_^JWiEYTkE`sy_ z>Z#Q2rL{ooTW*X~7*tS0F0(7{_(s`M<*@1~RG1;g`8pm1b&&@Ln z*JpIiQiaotzt)V)Y7tnX)3QCbXjOV71f)+)p4ypf^q_v6rmzofu`|2@0nt~VPn*_ zDErNOjb_jjX4rhG={C)at!UVIw)Kr$pxpyK1`B6(v`Q8H>`4F35 z9-qqN^gSrc6UTKt{<-hZSM`rgb0%lK8ix;9r=VcGQ}SypDN1_31(R8_OL|*rqCfP^D|vJ>Sk_UsY|2zxeB>{D{?MVHX!x z)YKNNa-c{zE3S`Oa8j;x!G%1vnq8TbD%vUA#ut$p$-2$_wj$x2Q=6i-)=huaGq?Jh>Wke! zwz%CZ*1GdqttxF+`*BKH$0Gix`r_Jmj{J`XZjWa^zM$`BN=AjLYYP;r#Q>Gkc#)Ia zA-?WWCOn4!=kM3MJLJ-4wQPTI=OgZZR!VE>Q+Io_FZVl}->&X(_foiEQ?);PPN(^g zNgvZ=CZx@&e;0T#Ykm#h+;&55L2>v=HR=u>o8q5thV6G1h4U_d8(V5NXRQUvuEA{2 zYu02H`E2fckHc54FepwYH%hA)oq zb-mvqhl^H!5qaErf>vw|{!2;y!Hh`pw=LA=hm)I>SlNe+$1tyUO^mr~u@ie@&gp`D z&A(n7EnJ;eqEXtJ#mU`V(oAj~+vjHJyQXEq!L=3jYZkOy)T@XII&n$K&)X~G4}bk+ zNKL9Zb61nJ$SD1Z)9&PwZpW@Qk7EwI?A!Br%9F>Zzoh$@x;?6QP*@nS)FEa2LdSPY z6)fi`ym>XYZ*}Gv`Cg4(%8qQK^I?7FZ#*)V{BVAFU~5j4Lb5}ps5H6j)`q@WpJJTC zHm`H0*xKvH*`H5Ud=oeB^i?&TtKEL@iPTh1t_Dsa*?-*W7P4(o;F~}#-=f7;-6ao_ zlHstP+$h#dpM*!>xVGlD<{zi^%rgEO>!pXjx5f2x%(wF~n;e&#&Yrt5oRt#uPW6Cx zc(cdsTGg%GP{>W&vPWiTSi(KM z+Fud+d25(b@N(@zy??Ci}1$<`Jwi_GmGDxh@hLG4t3bQ}3IC z@tW4F)zqD5Mp!LoYaX)V>dfgD++D1j`CXp%wYdR~K3e4VRUfX}ayy3dN5itqM?W9x zyS~Wed2x5Jhtg#aT3X+A$4GK>F43?m%m&_UsIuMQ@Sm|O*sOgntzu5~UcZ?i*FUdr zcp76_T$ayG{cu};iLF1?VpbI6s9v?|u2nOuqUTI`$n*;gIp|zdKCNT+TfQh{72NFa z=wxa1FqSXM3Z2Dpfbh>XwDMEaJ8Rn(R+5)wm}(hXebv%QEHqhByZuT!qxu=#?psd0 z`vp~}SsSot{jwd`7H{^o=TMGK?{VPTyPvSnEYb5m#tU_SbCs$e0x8^TnXDPUmv(w$ z{Ivxyr}N(y#wK1ndonbvZuK?)&=(2n&FkveHeDt;@%n7-u&KMO1R44^z3VQ<<)5nC z6=#vK?#T5DLyc~0z%T!b%`$gP1Rn z6-j{5zHmeOVq87(o;Wg@jwMR}kfnd95RL#50T~cSf&fcV@jr3|^`e+NVsdP}0_<^bqWYmI_vZGLRcqTK z)FyALywOuh{c!eE+KW9!sK*XwK^wDoHo>3k=x5J&CQx#oz<=aU`(BP#i7KegJswLS zbPD3`91m^^Tvp|~|HtIWxI6W?ot`=<^duzfyxJ&-Y%5#Sr>i~Lq*pVQWv zPQjhiIHz5yROyvZIuA zvfJ{_irVrwY)a&)UF#5hM4$@{aj(iK1DOO<*xzd{1wmjOBVw$1LXjBhB}l(q!5Dg$ zunGq#hC^peB`N!5m_s-zUs5Uz3~*9m(oQZFCSe5v2%-cl*w0CH=865-^PRYCwis(5 zBU}}L(?#wNH9bIm`fZO%7}Q}C@RUoLq=vq zY(X-PYKsgvN!nzwnB_c{NZQuu(&y&A0z>_*v5`{cC9l6=9kY*b|gANU& z#%3V_45lwwA$Wt++k6vLXI=pc;;~Fnu0%W7F2It_0ota_2OezayW~yi$ zLJRQ^@CTq#D8%27FQSE*pcu%ZZyI<;f-xval0@ulf|8sDhurK|LY4v{8zLCtjId}X z45+e1oDrTv1)3Tna}5;(lQ1w2jm6V&Fbz)}0JEY@5k{-Akj0^`va;?k5WJb7xMFbt z4TA{|4mJwL8wrFy7%=$&F*pnkhXyIoqENn=5rXE6=17GM$QhWqc>+F!$Ypp7g2W~$ z)G!!qzh(Xbg9Y(LMiMKHm;!%H2v`e!B{*R3rxZ} z!#EnAOe5gX-~on>F(XnAl`N5A2{^Imjr6$pI+?G)GsIjuwhuJge&4o8L!q-M!x=$B=TLEJ3kc1fN7|Ej~z z?$;IK@Bgnlv9qID37A0$ion*&G$@G2q7gVO633g2M-yOm7I?esW!$Sum{CG(3rTH=VJ|?ITG>gq)1o??krY!K^1^6NX zTeQ{!w0I$p0rdGHMr>VGB5x) zM}VaqSeGK(l=)U*n~23@!KErN4o@Z^yCQuU*6&XRr@fz5zAOgW&Z8TZP-bgBI zV8J9SY}kUyp#KBHFV?U!UpV?NAAtx1x9lL7qaa^a!FCti$%DMXlFNODZcP~o``7I> kI1(Ow@RdX(H{1N{b``>Zc8v=7&>(wv3KmNmyglWA0AKAN5C8xG diff --git a/twil_description/doc/dimensions_chassis.pdf b/twil_description/doc/dimensions_chassis.pdf deleted file mode 100644 index 114b93c755d0dcc85d2da646998d2177305c4846..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 70581 zcmafa19WA})^5kPZF|SIZQC8&R>w)FW4mM9wmY_yj_u^7&prS6?>qO7_tx6kYt^i& zZ_ZhjHLCU^QxFlOW1?q)Biq@XnuCL8A!H=9Gx`e0!^0qBX=`feXz6KcLde7*L&(m^ z%E81SPsqj~O322>%*4VV_eodzq%(5>7$gX_2|1bA2$?vTbouz;Ol?j6Xd(PB2OPA! zqp8^+OUz7g(2Rc{pQ3-=5!(I_jfs(y{Xb|-oSzQPi##8;A3TCVq^Rd z8i3`WG&UAyR?dI$v9Yi*|I4K1xr9pRuq zi(C1#t_hi08IpIrXWAQZE-b~bfn5VJOPHWe{7wlgth zkR)Vc`W%p^w&u=ge;fOIsQ-!K-xG(dsk5Ppp|c_3 zXAOM@Q{Khd`g1CAA_V*^xC(~mrm}y4s5+VcPane{q7&g~@;?PsJnT&wgg+Hn+nN9G zT=JR7|1ltJXX|Wg>+GccSpN3chnphhCzZet@9Y5{=?XHrklbwsB zv8mH%S&4mm_IVKo=ra<2&JKi1e0-lZU}vms>a5N1In^?#n7TWEPLQ8<=lq#bLdJiA z{e%90k^T|_I2NpzLDg{3on`V*6>-PSw`(Pcab!{*|M@LjFg||9bH! zwtsu^UyAVW@?&S=VEf;)lL)U@myX44Lh78V+Ts*w8lmP3AoQ=FJ-{`;5Zs~+1*VIF z6a(H{EY2cza}}#ad8+1~pD%}q+*B|3eQ^#q4@bQJ$o6aRzhu(se0lFH?s|W{(kH<8 zeZHMLjGZFz{cMI^KJD(eK|D&sQt`aKeK+DE8AR=!^8-G<1U(nZwM`RbD9Bpb9tK=WeCK#Utps&;_@PH>ymAg z@r&LQuN%VJ>(3YooDEpd*$%hLkWAqN<>R)Q+zf^jfM zh6mFF^D0MByCM&ON(8m~Q{(l6Qb{c&4s$^Z7@^y!)wF6PHI_H1)=Lf`yQ2`pBjZFy zFXUF*6d>h7O!|X)0%3P0xF{va@k`2bk>Rph3h95VB+C$KIuR^22=(qhzes^+!o?T& zKRCuc;>16~!4`}#+RK)j9 z%J6s)=0E+Ff9}K~5L2(x(zyP zEE#ZhJ3#vvopfPGIt~}@ZNOX?3B(Mrv5n&3-9fSxfVJn+ z0>!-c1QYJe)Ym(>$@6K{Xd+?c2~es7tN7q^0H`leHH{57S*dUFP1QVue2dSsPuiMm zgzAzYWO;vg#ucAzwWG{A+ROU)js&seD%D7kjjt_cBQUA$>J5ys2KWGa8+4oN1nCXj z33DVNbY9Psb=9dp+t}Z_QeM@W%5!z&b@Ig_^C0LNv2e){ww`MX^7g_UxHp1J#vEwC zSPCJ68&74M-m}~<{a>BP@h8Uow=FgvMEQ?tUzw8H@KyB94%t@=JTKuL>zB{U@?8(e zqPw(Kxkpb`#cS@##Pd2P=(7vl^t5+=^=h5i0G@QIOA3~a5H4!mMG13%A%f$HhQ{6A zNgs^m*f~=ar9e#{7hoY|2t9d@zC6>W!?>I(GOA#jhXudTYR@lTi;D-Z=rHO}6`E#a zme}Wmr^$J?GR0gcKAyP43*d9lq=$~z{YX2%!HuKI;@0hFNQsF&J|mwiW9FqRS`@vg z?{7`XLZ3TZrU~j`r0XZTuGk;yv9+mVSWjc-vz1Y;2m)D5Y^&pL~Ym~ zNS00>8@26wo`K4doFtKBG!b@hFe=&y;*C8n!AAaR_mEfJTT!V4vn=tz zyO<09&73@rxqdE-2BWiFLeG69PquTU{UQPG;a~@o76x9aOE>Noxt6jL*@g#{*lpYL3w37wI z(WxMLP$nwot2z22k{9lq+C*CBZ5EyKk;6cm!!B`nzbDH|t4-Z=Z#mA*hSr1X8aG;c zM?N+@kLwICACI-yIRkZs3%7U`2M_&An3;y7m+;GNK>prDm@CNY$L`>_&T1ALh(U*` z1*TWCh9>oUP|K6D{ycg&8nVN0!)B@KQ zP2x;O%*@gUvCB+eFW#)3a*`k#uE@CZD+H)+F2mM-R0;2+m5wWP_t915-cY|wnXpzr zRQ0M9^jxze1bKgiV0*khlYX_bUV!R4hV-G4|GgAEzMg?m#`N(KXt{&ct^n>4IZ+u} zFdiOzHtk-y7h7oVk&yG8td)w;xyOadYP8}Dw$}B!bcy-y60du2fOYg%*GVmzQ5zC| zpXDr)5Vy?afeQ@xruFkycI#Tl*ip7MYmwzm22nft5L=F}R^f@}M{Ta*_pfG~9#q$E zN1kaghsrxlQm#bOD3H$s;Uh1tC$)mx4Ar3?5V?uaO|{!|{CrQxG z&dLZAC4VTl?pSpafLfT`Q7-i#*6=@mSNA5XHTf#-09MP_ucqzQx~xu(D4KfelZpb` z4LpjHuE^9<{zG43BS0m{4NW!AnP^0{j1*gkh?8L+gVT7PX8ssQNQ^Be4}h)Oiff`K zpA#}=R2Py{cL%BcWv0~6|5#7t4u0i!z9pV$3VICdiysiBqUiMZZ{#&%M?)AxmqIz^ zvr0MX*e$Hitaws(z+N=)%4~is1NF5Fio4#7<;U^U$16yzi>Rj6dID2fKU?aE#gkhe zy~pqrwaMmlZ_rOXL0-}=>{9$8R!Y9<`BJ1xpW(nCmUZ75>tfHPDeWABvbu%092rfnWN}UU8I`L z-a(8LT8V_bJl_8(2ILQniw)5|5o?I+!|u|dSg?u%*7h_(6D*`>jCsKN%}~#W>U2Jl zSpUvuj^=&7LdoE4m_&m)?#nzDYG(WvDcB+_v-`OsE1H?!pP2y=gpK(-mS&#SnxMY0O zmYy6ETw9%;wS5bP5lWTw5^&?rPvhWL(p7`%%{sT}U!aAMz4ayevMUUC|l*_ppIy@BCt;eo!1EVl-p>lMW zJ*(2;JQ|JjTV}#VDGYr0EeGn5m@Bs0;uaXF^j#gs(tsV4-aNtO_)a`Sy%A|$umTgg z`;u7cBI<$afUuOg_+W)5qg3&-9M#@D)l|&oJi#*qdpgkJA115 zGKVo;XU{Q*R%~jZ2#{sMgQzg#I4PY&24Bj6QsGVIK7M_BQ-3$Qyt}7>i}0JL7b%9*^m=frV_KM)<&AqO;PJFg94SkyXN{6yRhgWNz6suR##c1aVtL z5(1;b;ii6S(0^CLKZh6*B9zpbQ~AbKxxYZUt2rs8RS?*|Av0tATT0e!sBHYTFpacZ zS+cV5NTWbZPg9(UYts0a%DygIAAa2Tk}rGAIY23(+sG@y;TtD8*-69wBut#}i;ny- z1j)eTq=nZl&RRt(18S|cFi-7`jtkz;gFy#i9v_7x-CeEB_o2V{fLPAgh&`>xv6V@A z_7w-CDe}Eq3!M=ebc`RF4Do^9$-CU3jfl2oTxrLi(VHRik9X9n3W=So=JU!{HFlzW zpT`TwcVcz;=e^8Vu5t;Par;TrP*hsI5DnjhCt!_|MEOrwTijjW`T5CYj%%M_n=-w@eB=(;Krau^4?Jz8}d6C2( zMXZ@!@gw`WIYRy3Zo2tF`OCI>pm>bK-NC(>8Yomi!1zI*dNcc)g;RED?Sqe#5D1 z+t0Q9o2ws2llpgI2qL&cA5NVL>`;937ng;aZPv+NfW%jI&Z@s`e4No#R2(eLWc`-Qwg?oDKTO+7IMWmd=|uD# z*H6&kqf(lg*WS9wU&TI8N?e<;S(^}jH4>e^OR>4AAxOZ%`|t>7p!j7IJuFZs$hG|rU6n*m)GZ{@QeE5GQCj(l6j&Kgu|XPT1t z&Sl#vrOus>Su(wslyl7^YA&dfOg(2s+=$iy;@8K9$<%bQx1~%8t&Lg|%W*IiqV^c8 zyT&c@UScAfmaPLi_iJ6Jn($uxw^1cCB*Er$ySYnqzM1L?CGmi&ePdhYO&>$n)Y3V*4; z+zq{{UGh)kc#(KT8aF z8p#&q?TWg|(MjDh8XQpRxu?icL1ComZ%=TW5z@b(uXvgtKEXMla_E2JzCb0`rhTyf=V!T8H6_5w!uN(a`>HAyCXFd^RcAYWyC0zPg@rXKq zi7IVP$K>MO(pE`RC9+{EDFryI9$ikFb_Js1Sjx)6i>0B4c%l)F)0D^5B5%ht)%WG*erR3Y_(#;it=`xGtqrnf@1B@F*!dc|_QJg0CAm$@)KX6qG8;cY- z)P+JfC)IQxX!$nFZie^%5Qv8__muw8Cn%fmh&W_l1!O%jM}3Oxpv zjIdjK6=Hw}m2Z@O;De%h4i<`?jR=#_#;Q&0y3;4_!bp!c0h@)Cq^gaSKH$YWDrQ9! zxd;dK7y+B8NlPY`KGD(Bg)Mu8(>OU%JU?#A3;8*gnV_4*VGKC>*b=;63a3{>`oRfX z;1p(Ya?IStq&!&-e^7O^mDtv>LDs-m0ZDrYi|?>`s6Y`HwIU5Zh%Vf!-xZWjT{}CH zj}TVx!8;9eOM9Q&C`WJLuNjfc4%@opq(!mAPIBl`z@F^(QY8SKurM?4+4671D`qT5 zE`sz(?F6QfHK*&^J<#7NFVjb<@wh_h-Jo=>62@MqL{cj?#CvCf62lHBINN7GC6 z=mbK;N$`GcmodwkyE&c2irpz&u?e@NA9^HbyEO!X8QI6{1-eHbLpF&%%2s~kYTT(F z%R1Km?b?~_wu{xlTtT=)J)MzNDmA@lD)1u=h}9V!4*+8?JR0op(9;5ih$~_?n>0-) z1bCD+%odf!`F4C!(U`m5DYb(F0~qt`IEwi@Z#&Y z%v;qW=^sgH3J7EY^TLD!O6^OL*eA%5QBIQ72Q*l9v$=3^A`6z@n4rgFD7#rG0P=JR zpb|oLJv+fN%tYJN>QT6Y7$R6(tfA4&v8@SFj*l_7RFjt4AOUBZ4gZq@&;2aDbH8Ug zV*g94_n)?g$UwkQ(Jo?|3AAk~xt8a?MaSEfedQj|ZQU?U^>nZ{yFIIIhQIL7A@7Eq z&zN)5m(_fq$T88;@|y4o z;8Y6Y&8tMw!&UBgYe#xBZBavrTQ^pSJoEp8#0bmG1(*2n<7Wg0`CFvwW3a};-mSk9Vd z!c9SN6t_h~HFSDE%0AT?{*@x<8u|Jw7ARY z$Q*?Hy4l4p>56;4Qnl~O+p>2b+0v`Fp%w99sfI1(L7|5JNi3_%A^japy#qwoe7K3W z^ZS4~4(0wr!J1gV{~UZx4Q$&FqR4WwmgTw~biH0mc6k<<@kpD2!Rr1a^=O+6N(esR z&>wo?j+m5v*8S4hs2Duh>{3<1a*1}Dw!)(}QY~~;?5D=4OW%Rhl?-@y%(i8>>Aa<7 zXC}Yt)O9|q`@CH*(q=cPWu7`t(k|>@jB#)1agVWY`#cS12aGgr;jJ20wg1+Ar}xdu zj3;V))%AuEyFQr^;CxAtwny=(V*=8#Y4%T~ra>$J<-@$jEEAGdo$jy%>24~u>A=O} zx2vh$#c|qV3ZL{|G20dWrd{Ycd=qvpzSI_{Us*lGN4p$06Cz3^HlE5S4 z3&B2PcRA5aB6JOnPfS3ZJq+&wUOXst7w=R^hu-AgGVqKZYo~dfWM@Z^utDa=kF%EM z>9;?4t*fVYjv!~a%fCm)!?wYfk$9QX9(=K-z0kV9x(X2$7_<+SMJ&&)dRtaL-|vg! zm*%~CQ^e%^E^pf|%(rH~i$zPSR^;8X#ynB(kTA|R;{LK;$4}iN;j+$mdOv*ay?k~f ze|+1wE@ukM5I{s1bA+}dg&R)C#P7642%%Hem8_<*L=F#YDGxhl=vEjBb3B{Q?$-Z4b>ooXyi75A$BKHbQEN?h(+1t!oaY+CnRn+I$t@3t| zxcatxzUi#K|Ix=9sz29P5u?Cb)<=$tYT`I*r5i+oFb)F4|6O^nuL1sE)p%F2-lgjPFE{ zaZRlg=pe$)uuY%wyawg?doNkJJ+<~X;)yWNiBU~td$_r*np8A3jjCqJaI&a#ga!lh z9NBZS`$)Um<6WHCu-de&&{)t{1(@Fjq0i+=rlQ=vT8XOszw|JE$@|QxUX zxq0oe=bDOjha5*C%K{b%Yl3{LPxCgJ7O~#m3krfk=aJ;|JzILkktciB&J$>4*&8fm zEwJapE)SDKpn=nO)aP2X=E$m^xx_6bnb6+mj36Y4-{n!K$Izo?=sU>PrInQ49FJhC z#-O$;R*|~8Z^`%6LX{tDq-<7|d%85JdxqlMyqbotRkE~5g7cz_2)RGk7#J-SZRpNd zrk{74@Yd4<6h6}rl}$y2Rnn`U)k$4dJN-0P>njWPQKZi_?0DfNBC6M`><)_X z>Fj=3|0~MWZ1Qvx8$&P@#s24R<|amK`AJ!2CRDimWyADRUfn#i+->5 zsOalGkDQhKsPEa~YBee`odb zWvvA&c`rx9#r=f5xE*TIq^6_G`w3U$P>o|STSUt1i>f!BFBD-)m9lV*Msx97D^@r7e%EudYo`g8P#q}xLsyacW#1SM%` zQd;d&(a6Rle4cJKLD)E87ht36;0>fd$pq=3zDg=c2Wlbz`ktc(`VZ2xxWZi_yhM4r zwx&>;==-z0KhPJ%@cQ)svZ?-OXZ!!V2m85u&HC?qu+GWSu4nDg!7t{hsRH)^&lM-B zgUyac&|in;FK)Fk!S0ej60d5iF7C1PyFLa%UW&cnKr?{C>V;RR&f0l7cu>6448B&q z$oEonfEI6|O~>He$;X;ttc`H}50{*44|9*yg5g)UTKKXp#Ed}o?!?oC``uBTRmV9s zGdli{Q`a+7ye9rda_2Mpg>6`l0=!u{%i@eoD76}R<+ex{4Y05+)OO%XBgNi8Zp|>} ztvFW+?!wI9L#YO2CyWiBBvpGzxgMG=se4H;0^pT5T07H)>zgXLd6(T2{#&m@1erCS zdG2}~FQEX6%P*DPNh$PhR=5;tm$hDPR{{koL-rU*{fM4m zM)Xtv?Ox)udy(eJrxYFoYUyoPx!Ew@#=~lJaYqJu263*k-6b~OZUb>;sD8l(g`lGE zrh;zYFnss^?PaUxYBsxDedk$0b_bjXMS7L5|N4aHHBAKh$oz+V349zG!e27S7&{mCo%h>nX&qup!`OvTit|h^ajo!|EJ3abw)V z*0KrHg<5?LI6=h@0VdjR2-1J%0X^@AYbHMyRYI-?P&z|L3kAeYCs2EifPK=JhITzd z&R1W&CzRbl=Toev462gP_N$ik!zBIh3OB-qUMN=7sF#R6sAKuHe8F5n+gOj6^4{(# zqB#_Id+fG@8Crdy{D9vXw>FQ6RG`6uc*9?G64fC?D#k)Ry4R5rD7U-RsKK1mWH(EK zr>Ri0dOx_^Nce=0?2P@=pI4VQ2jAIln|P-RePd_rx~Xh1%Ar75G}-7D-zHZXK~OCt z>l-&+aFYDJ^iQ>N*Sx13(wIP;=MchRqaWFqb)?9(b zVpzW#H5&|1FoeQ@F@4@DwDb~}0};3DN1>|xo4NY|_bkpUa+Hnd?bhvD*V80h7L+@Y zZ6X%B3a!fd+eW+TAgSL{ziExnR&R2AJgh&ojRMWpeyqOjaEyO1e7$F& zkx%Mku&ioGR?%0=1%185E4=>>`@MtqZ2!u=0#C;)>l_(Wo}9yyg%1O4Z~C}-rl;)j z`Zr7nh#7=YZR4Q~$XHq~L_6aRN_dqYmonoiBY3q~om`z@9m;kz9o>qayXQl`+A2&P zL(uBy?})s3t2@xGtI$@0G4(*3o2`vQFBKwOIZ&@i{y2Gey+yjxVe@g5$@ z1*XTpNS84IZm{jfBivWfFg#l!so4@dfA{{F^-azf}G^>2E9lg%tH~g8#*r zzjgi11?qQOMKzmhlo702O$vKiEz?VG0VE4v^cGex{xy5`V%TpAme1*oC|&@musAk} zTSZvWFg!+sx7UIES>|dDmnn$Qthx{OYf29cv!o$8$#_9fst#iUq*-mZ40H6z*;+Gmn#h zvHZpOOeSX&bC~Nv|0M2WY8{u8g1OxBI1(HxQ{^}QYwtx3@aveUDDK*biofCrNS!(0E_A0O5n3pMr5L^zZM4P@w`LB;W0qTt!AGG3NZLAQ}j@EUT=40mAo0 z{0~4`RIdLE=ySv651_oT?*9uAttVuZGX^i{A3%}#z!+ybw}_vBj)*S*0(3-FJu>tu z^9PXrE#kibY270J1?ZFi51`M>Ux0LP5&r<139@%}B+L#Ng>cmVWPEU+5#FK)jeO6= zUl`6Y_GBYLZO2cFyCuw3qC^D6;FYjIl?j{~KRVeO4M=pE0HNTD{}nut7uFxKwq0Y$ zKtpE@bV-yhoU1UJwzE?O0r5WxniHNmA!5X}^Q83T1;wxCMEf<}^qm_f#_X?-%WgSM zot2j3+@m|h=C9@x?>2w&O+K^pqIP`3ytDWhTilQ=0+}9y19G!$I(~#6LVyDT+g}{{ zF|r7vRS<>)9Y2=4@m6l*IJi0ErUdpuTK>`mNu!1lDEgs*U}ZAB|JDh%f6~6_`;mA! zjo)k=z*#;;%Rvi-kM6K!s}G+&$eHmFE8Ox`+}0{-RqHKy^W~C6?F5hl;JCo&YzM5q z?DaK0RK)%{I2y}I8>-(SiovKTJ-*1Lnd!YIatSWd(af}(m8QAoO-uW>| z3`zRk^Sim{$~NXI9-1P9V89p19q}zjyRB$@5?n7DSb}C?jPJ@8ymOx9Uct^GtPW7- zb^buyYu8wU#cw^iAl3mu<@^SL_n_KfT7Vyf3Ojr~Xzb42U&Akx6^eZp4M3rEgRE;N z*!QbxVPHpzsE1Vdnsr0+yR~Z(EJpZp$=iBP4M^L1;!nZFUomlg*)j82mf@fqEo*Vg zrwd1H?O{TZroj<3%0_IbIkhF`P1u*J^%K^&&>2xJYUO{9*ecj(;G0jIuxk(sCg35$ z((Mfrd8Oo!*fPdcj=+Dj@nQ@56H;wChgNK>0D8dt0j6pF05-Y8i!9xDWMiRr+k=hKKteR+OIRq_V`2 z(q$qPXIt)db%$iYbkqaLTq}7A2Ie%pFlpq6QIg#yWA(M0yL)*TWE+J{jOXy4+Z-qT zA|2ECi79%=Ydp&tnlHKP(`r+f&&yDlcfpN3-&cIj`J3vyiz+)~hgbFuMFX@>)FLNK z^_X?e`>mzu-3QZQ%Az32fGbJYMwB-u*=*MIobafdx>1Z^S)rDO1?nc^MQ-YFEBr@! ziAoa8+s(0WEj&`Ar~rk##iLmJF$J^ni1~nJxxDWE7=X%D{jV&VKL-rW+)g)Hp9Ta-*ryTzoE(aOXz!Sa$G>`x=~gdB6NARw4cn zM~xiFiigS0V*ll@Bh7a~C<*L!>^$)8T3>~*=b|xKZ3q0j1PA$F4o-uxLazrIoAwV& z-Jx5H?)Fx&ZtnB!97LC;b`E(YT;8!Lfk*z>B=5?umU1oT4cZd3dF99KP-CJNl9jV{ zix1o4HN*5Y%vre5TRZNF5POn>08tMxTYzU_6A zPrn22zrag)1f;!;hPiGoehG7oH7mJfHH4v8)|ViHH0B@QVH;oZ!aM! zl2U|#!`dAlIgs1*N_1KxA|E7@0;YD|!`Rkf2wep`+!sk+9uSL+mycn~0apotR_N3$ zWA|!e$MZMj2M}5C7Vl^DMR2NVIiLjThD2N@#`2yv52H%*36pH zPZzKmvMs(lw*PQ^-xYd*@oO1IIr7dH_o?_|Xxp%PfPX&mwu#eB-Ki!)bAF~*om7*Q z`?->T2Bn`MZ5wuBlM=gn@UYQ(VpCnEnmh}=06;VKY$Cmv9}-t=H#b5ohG`R?QC5yv>JexamWPJ9fA_TbF*AzPuhif*V#-_J$bl z6j$yIfJOobHf^9?ZkRh}zqvEvbTtXdLEk807Rw`tX?OE(IkdH|OZ{wG*)v*v?ygVV zTInnE`nKE`?)7u6OQP4IZN-l4hqjF)({x!ZHz#D3f`|z*Fk7opg}2Cb%&2u@18S=S zT_YjDZ^SyvJ02{28JTLn79o&_H68SuTq7%AtSdHRNS6sY#{tgg&p&JlUF9f7k=06M zQA9LR7^6zcMR5S%qL=D@f-HWxtegs(pbK~~Qh+1Uayk9no6bvsgp|7-XMqe^lNQKgthc%tt8vY z$dXM=d!z%aO1eT3%}YQUt8b+iv=Ws=#_3AAr!>yuse7Ci`=YhWRG0uglv zqg=j(mnWsTgXlY|C2_4ly7h8z|0H~Jb=f~hn7t@#YL^Y~Dq8gGyQO{=nLfnc=jX+L z)V%7t)RS7In3;1Nth;}+yz8XZNaC+9rjH*M9|EwMr z@|E4>Yf4#s+UBK&)Soh_xLS1|4`mfzb$08#Y0)pa7wZ8;dbxa^FR-PonXR`GhxF=GGSHtml8B1d5 zF;-Q*I{!?tkfDWUC%+$JcvI9mI=1b$yM)(vqs~>;lA#VwjZ|ZpWE?$6btT^U8zl8{Cq;; zur`KS8Wma~2&T!rC)63?J}r^Kx864S85qT@(KNjw%$S*ls}8KRr0|Or+P<}a3bMCX zG^V$L?g=Bc2IZqhjDH_2S&qtz9tp=h$htsL$WX3;%&BD}2+pC>?rjARPllm5)3Bu0 za^MO_vn4M-oCGVKrf~Rx<{%fei;Qh*NL8NwsA-lRfI{JX&8cK&nzU#A+!W=-CbL-2 zzOB{K?qc@M26)_Y&#+@-B^|lkIE*^*o&HXVqEs4 zpiRdS7t)Z>GqFX0v>Wq?d*W@8B%0~&+xN`KEr!N6;_1$J$79$)(Hwg&>+P;x7vFWi zI#L3XKIolJdAwG5)y1yqCa3iegBLfHD-!O#tNk^;m2ii#A**S~olZf-2T+*7z-9`2 zOvujE9HNetEKsmTblV9U?~rn3VFlRCgGiQ0VqSBK_D34IXze37+7;1q;u9^)A(fvd*2SveaFGvHvT2Uy22zSh3N@QmdjG+dL^gb} z)H}D1w2tJKr+>=hFGv0aLCfmXpik!aRCVz|%j!oKC{zu`_)R}G2a!WCa}qNBXcLMW zs8doWNdm4CZMSnb5(1KbGiLxNne}vz=KfgjH?Uo6kGUL#C$R?5s9beG1ZN=v3?|gZUSp3i{p--~1L(k0!r?&;{5CG+okODR+3gDB zfjIVI8vy=Ekf}YtY0zohiOJfz`>aGqwlF@o%r_UI$|7&>(z21AI2e=bf)V$YT|v25 zo`7*o!K}%(noI#lhF-1i0axW~6Q49whn45rZ1Yf}2aW^|r$Cyr*%$W3ak$m>@r<+V zS!FMaN#bL=kj%)6&~?edp2x}c1mEGK8tXBDZ4=LotzVWuvvuFg*`x26Gw|_6Vh)n^ zTq>6-4DXr55)HgC-{1_=wB2;rZ}k_D%)-|y`kS~pS^gJe-S`tc#{laDhwRJOmdbQ; zui9_~v-M_KZ(J?okpAN;pGDt>jh<1I*!pmA2TT4DM)ILA<2t)PM2`9Eh@^9B*d zFdNnblzjTpx?MTys;NBNRe-$r0y!UiMNOcCC%Q4h76|Gjhai~+C=O6#i_o5!`nihv zd8(dEeTlA-L(8(Mo#z*4v2Ux%{?R!|D!>$!e>`6$M?YnbbYUpUaa$;67Nc2S_Ht#* z&RjP)e_3AkQ~P!*K%*TuxyIb_+d{dm-)K1!$s`aIap#`QfW!hcu^VdCxkzrgF&yk= z+-P0;^m-HJ=3gHl`Hx@Wsg<2NL-{*Uolw5br!StScd3Us2+U$}#mv5a_dXp5Uvf}& zp4Pfo-IYk1N@6ybU#+7wLa8_dICL>0Jw-Xk<%Oc z4E*e&Op|+N?bPX;W%_*0wiA=3Pjbl+CR*Fw0l{Z&LKweI@|&a3F#ffH40^SD zFg)iYo)ynd-#1c-;;|;&syLXv>S*+7sh~UVy}C@_@fsosHu@KLQ!CCms&(5-`hTMeJ}1q$tA?w;U~v zu6g-$Wg@Z7bfKsK?}EDmD^Q$o9+O|Cy4TGfa|@bTD^&1Q;ZB@FatTR5a9NFLcA8Qw zrA*Pz3c*A$w=iWDW5lSIf`<%H=fn4fkC4n^LK~0lXJP=MD^&70IZSVn_uM=mw&v(f zAPMGT9J^yd>~cRmG_U9ZE?`^$wkTPfV;fzLGv|a?>HT)dU6SMN{i`l}&&fUdOB)sJ^ zm~*hF!rv`m!zlOwFZ*|(A)r`%`K-H~SD-j*tR81#v_`)SP-Q9Ju=Ohqk1=s@u=HWm zkkn4ALk8(~I{R9dWV@(4!4M=DvQgxh5g9)-emWH{4evXI9s9^g{I+aAvTD*UL?743 zrX@fFw{Q^$;~Ke_{G*^4z;m>{m;2S;x~4wl9=m^u7uTGK*d~sZ1{qgShZri_2l)R= zd7C_-f{fOf_4cq|waD-{G+inl4avly(+(&i4!^l3HuYB?3OPhMX3{=)xr{HwFW+kV zeyFZ6r}NfYes*k~j&9|hyg2Pdq4k~eh(3Rci780<=e1>_Btt4^_>8xh9`>wfqnIB| z54~|Z0B3o#I)siWE9&fiHi9JRxf%fvpF*x;OCld~3Q$ovOHcxt&3?t{{pLFpQpFdb zsWpNP*X@ohbypcj$6va&9Fy$)&?#mm1h{LAM*DV0F6FO4#v zXP@O4Q?5QcaxJ}E?tlqb=H-t_^T0=rGjZlG9OlpgpYs{&7fuI%F$E}SLGmxFQf#C{ zKr7Cn=rRqM0rEEB4q4}$MSMLTQnFj4~J$#c$m)IT9d1BY9nDNqh?pS|U* zpK>NZpTh9s`28-!eJ%^T9!>V1d73S;k3Hu!S4T-@8H>adMwwfmo6SZJtcs{ZGy6V=bC|IOZb^Fp-mgX5<^Z;!AduQ=lRvx~Z)~u0M*-r! zWM_=WkW9Vt)Obl5v?Y+zMa%=$`|*4lEe?hx#-@4(YZf`DBEQNXy+hWSu(>0r0_l3E zblE94GB`=>m`b_+e7W*)0F-Et###Z)6R>5g*}#-S=QHB{hO6|q zLVpdN+0E}AsATF=qJ?7fP-!<(Hk!{yW?$)B;z*Qjdx=zSX(t8>%5d5(Wikd*zDFu1 zk(1t0Tqsx$@F^moY6kX zEGQp~iSMP72j9mfi&T@20t_@+M|&yxs=ikssPKHVPlm^P&*TLk4lJYrRWj!ms z>5vh(<1 z;d99BQ@=MaR`TUoX!4z+#=d2@#gmk3NP4{SsfE-DqgAiMV;6^R zOlRfx?f!b@PX7i&=biDeDI?zNPi<)G#do3XhCl zg-x_{6fA6SbA=?MGMojYQH3ix^msiPgZ(FRDbbWt3C!kyjTe$>tTRuRzF)MkYBEdy zts?0VSE}ndNNxUZZCWldZN=u@3A2&r!7RN_`?kaMciGt{yI*G~vvIgiOW#G0G>oEL z$fbPM>5;9(;}Bg_JNs?P#U|X!UcTAt!1NSco*pG(K5iK&D#L&gg9y{*j75Ow*PmU9CVE!zmjuOWs@1T4tJ#4AX~7T{2%u-Qj95SUZQcj+E5cqmgx= zqBy6QH`R1t>b+7{49h*=HP2L!wvJEq&Kr~;i0N{>)1+Ah0o8ScWE87vTCqka=wo;n zzP`GfIr78|oo`GFsZ|B@b9Iq0?-h=GUbdc%7(8$9YZ-G(riWkE9GFHUIV?m?d-!;13^soey51raqmHx~v%B8~G8{UnG95-+DdmJPq+LUR6L- z?&-Hg@$sE>bzMxo?ZtIJA(6_-(#&~F3>afHpmOI+iO~S&Hm9OI@K3yG@phCn3#o41UR549Ycb$0;Z6mP2FJ8kmL8W@&&HT*rs85Fp9pNGRyqHQ z!P>qX;&s^;SdCb6cIs*BazBBpa_#*C6@Y3e=?rR{jDLbG8GAxD{=GNslGqE}3nf{( zsc7<9Ik^SxB_7$h4x0CUP*gPj)I0rx?|wEYwTl3k@FNx@CF&Hszfd59VH(Y{kr@Tq z{&BynHA{IJAGj7z{g!ZP5Z;Ow+(8xO2SReyx5Y6)9uiQ(_Jf#r_Y1lyulsWLn<4 z2xZC7rC&1xROTp4Y!h1u`12-~2l6)ol30ej>oDn=CmojTk0%MK+R<&QrdGKbI?}{q z^~-Bm%B&1aDO6TiixEx7HMB-LzBQiei(VDG=Z5PNg7>|)^G)@qF2+N1^zf6?3vxpfbt%`;W$;s{XC4NY8%S)ZZ26M|{ zA5#y_Kc{29@dMgP9(KW0X})_~Yr7s=Z8 zNQjkfN2{y_7$bn3B;W|Vc3~%C3I5fZ>+uK4Yilg>w*67SRQPagTAAOABQGT!TZW^4 zGMpXtw>S+7^_O^v;(uqcm#*@k$Z z)EYB!{%cZ#fp=l;Lxh+*tmb|SolP;r%Cq~X0Ry^^`G+TZEmdJ6W=6Q=K`qre9Z)@J zY`M2+TyYea&FB5NYT&I9Zwx(4=S8n9wW`xfC1+}Orn#+GQK<6wTvF-RpZwgdUN@6) z2h90+HMN^(|DofLn=GT5-i8pf6?Gu73wM^fwmH!uJ0NN}WKtrTCaaM(q9BeWXOogy z&NwaKZ#7K-H%WxVBC^3zpNR0Fe~_#4?>v+F3B2kV+%W>ad_dWz0Lij29m`l8ujQb4 zrgbN{q^WW)iR4o)zf?LX|1j^O?AXZH7_VxO#mxp11ALfFxDH!1aU@1Lazu|jnGBa- z1xgb^M)63HI`&wKsB|5FhuN~I4$yDsM;9yD8XYz^I3Qwqv=^#CaLMBuUFOeYR=?k2 zWwSUB>LDwI${gge7Ym`X)uyo8zw8{Ri(EVu0eiov#je@d_c@8^11K;gGm3el&|p;| zVVJ~%p~)~wZq-+4ex_%wge~)Xz1U+&*12B7U$@3W1#?S3byS*MKY12W(f_vUWTH}O zq@Xt#Zr<`+%3)bp79kn-qR3`TkJSexS2tOqs>J%SHHz!sZnk4@lGOaw2yzZ@Ej%zo_CMYT}%-U1!Lq&69sUKNd@Qr$NKF4#{jQ*PQ`3J z=L|=M15#iGi)`Gx?aNp4*Z*y{Mt#M}i&_66yiUbBCqQ1Jm>X$`enzoRw+uA15r5eh zpvV3(6Y5u*q-nNj1Wfc`$Y-mIYY7hCe9o${$WNI*1HSwNxiv>LUDrreL@xL2u3U%N zI*qpxG)m3foLU#~4Oko<3t*~Qi%O&x2+}({NAPME6?z0tXyN_}<>#s*6~47Bn=G5; z#(81L)E5mzKD$Nz+H>+Q^m~J;q(33hn20vBjy^}2(EQIZb=@~D31kKG=KsQ$m0ok1v(EsY+KCX`45~=Afrr0#%($pZkMG<0%4|fz)TzBs5yS#tz2r zlmaRtWw;tjWvfPHqu3Af)gg5%3+3Ud8j4BxrFANPw)4%mY!meBcP(~+{8#vg`vp9v zKP=@#;xv^!Q);{NAr#t3Wb^BrS)7I6O)fSgKbyEXh;-d=F1)g|$zql~f?Nw$6|B$o z^8K+yM{<7r00j8~@|RPe;eUc0|0Cw~e}o)a89Dyj;ooyL2?sJD!uQdRO^5%dPMY?O$wgy@!37Ch;xd@7;ITXjg}VMr@r^>DCxWbR0+kd7mLRU#t*pzu zMNL9G(y6#q@Ou^fqr*)SYd{;tRZCt1HcCF1qbwfFMG@r(rX;705rxF86q{w)$X>}& z0cjXcZEOF`AL#w#l0vPrt@!ZZhGvhtdOYIJ>GJQ6gnzGuA6NG|BmM2WF64 z$!D9`7RfUnKX3dT&PvUAON-i#CGxLbOiI8e=D{r|K?q&ESsIl)f^@e2M5#B{pIQ1_ z)M3AbJk?qjN5+p&TbtpQ5KwMaPo#HLru_KO3JKA%BzSw4#YaYkUqdYrnXuW3>%TMs zDl0wc^0L>sNaKtj)6;3nk9}}pn{RdVn2MJtXr6GA7S7sJhNcT{!waZ;g8t!94BFL7 zjZ-DK&S1cR7HCG$xd#)3`(PIvwsb7n}3*5PEnH)&{XS8GLllOQJn7 zsbwznmfDNy{OK)4AaksGiilG+uhP&PG8lBKtBHa93%42<&5(Cl0=vge8ULVayMSihoTIJLRhggLex;t$KF zZ1S)ycBw|x{GgFj9xJT6E>}8?iY+Az+jO>?CgC+o)L#a?-z5}h74Y!=-?U=Z_m90o z-#b|&!|MxHJRC~w1UD50-_kyG83JC6U<1f9CgQEH({APp`;9O2aW1jUx2>DmTAA6y zLYQ4P@~sY+(E~O?CLwbfw6Q6wd<=*q(s|S}jnCf-o%tu%80)7Vg&~}$SQ`}__gH6= zK6~A7zy3@iPow0VL}3RV2z$kV))2zFKX;KBMhHgv)zFH>_&I^k7an?;<9V%=?MTfA z*+e>S!||l4hcMKnXJyW)y$C@Xf`)IxqzSu(>5Rb^L4xHA!!;9NDP05~K6}b`NCa z5rEgd@EGU*fPS@3OUaoXG);%$q z@1Dk1d;n3Q=Dhh^^rkcnrfdwREY(VxDfKUF2j2{lig)$NNLk7N{HBqqsHk-}a|zY1 z*|;(wp@v2jf5cVwszc;MH68h@_2iY|4{MyZ6(4nRWD0#wVSsYuBGtJxgEc@C0!~I1GFF-q@GyTlu z1{je-4TbEO(nz>s&|&JdBBUBXl`iFr;+)OvY(U0*te7{6Yqh=kxg-X`)ku8NyxGve zt6W`}l&;gq(a}Ywv3qb)-|0Z(jZtCR+{hjNQTLnMJ<=HWVFIA zqJv^Z7o}PIDyGigqDY)@vY;g2^|=m1Q4G|DmR;ZcEM^C*Jh6uQ26tQ4?)?>sd2UV} zp7Y%}HonCgM0>q)xqePT%|>4Kn8Q>Cmbq~v5tJ12&^RHE;REvzHj6U~wHU0987xbB z8{!lNY4?+|*GVaB4=?oA>@|=GC>Q*k6>`&!mjPXMw2Z9rO{c9?%Mw;rx*9a<=VC0z z7IW`Bzh@JwJ?3+lL_~w;DMte>%Id;-Dh?MB8%Ul%IO6#0cZX9+b2MBIx6;zY7mJ3o z(>`?}TKFbMxynx~n(MKBRV|cnGHbQkkx3ed49LAD*X8aV$+h-ouCGIYHQa(*B2Qcvssz@Kp<+IEK_Uu5DOm zpS*5UT~xJ_wr*25zCEWi3%I{>+DfJ=gD+ttQAKYnv(M$1vrQPp6J!W zH{satTCQ%wNs zPs)Odxfv89qF9>Oc0gM|aWg3wVl+af+N0+0lGlV1|5%*?5CGR$qDB7=o&c^ff zUY)|MyiGksyYkw8@9EU%ubo=v+C!8~K z7!}+}SkmwB@n-ZIF?(AzUO^_F9Dk>moTH@=?Cn(0AL>3Ks|jOEhvUw-HtZB?rnYJN z><`(AE)#Ff_{I)JI8iZrgBTZ|nvt8-S&Ju_`Q-UE+Ds7IyrPMI4f1|-(Ree$?3yAj zu`u!WxE;-!QEcFBrcW71R#Vt8ybXC+9mYvR^KlRgs=#F+hig$9y$Jsln~*xAsG;yk z(7;gvQwXdY@@hZ|NrAJ0h zVu4o7A8OA6jXCttsDJ+1fq@T9v+*amnOVRqC&-t|cU2TMDs0{Q?>Qy!m}&7Ji(E>& zsMWQ_ZzP>lDA%p5@iKVhxAI@Yw5Vx&{<)-UIih7nG`!TQ<&T+hM$v6O*2pT^=xo^O z6qJJ_s!v#mv+~49Oky=V5TYh^CJGAk>}pPl^1N$aLV|I6s-mXRKk=yZTxsFR`4%C| zpCRl5c^~_y_ftwaMDoffKh*qZi=xI z^JQ_Kk+xx&guKv%f7~a$10+fm?jEX>B&un~Db^l3j)kGq6~TbNHA#DPz(q+kyy(Dy zZ0@P#M`Bskd`vYpw;>e?a$fTh5lwPjF6t94_`p$_f+=nIq=txT7>X(Vj{)2~a* zUJS*>4_2ZDpciuHfM^kcBDIf8>G_Gw--m?GP;EhE<_{bCy7$?pHI6i)%b>RIR@>ij zaY&^?q+(8~;9;^|n44ppdm+*`YrRNo)}B25O>t!VO}qzaQOZQl36n;Cv>7A?j3?4X z3Gbw4ETiO6Fze$ZPw@#hR(+>DUC@*J#A9+aruH|TOBrbVI}xn>FA>|a4vWGagqMt% zZ8{_j9j6h;HBDi<&MO6Q5*gAk#f>8<4m_nZZgNY1HvwsEJ`fl%2Q3olvmEC5pM>TK z^f2|Q!@v^zqYQ|-- zo2-X!FM$0gjyZ8VLY&sWU7Kiov+T$+@#L`ifqIJYMbVg<0~xFnU99+#-iVm=O;d1V zpM}J9JP~qJulE(-rt3sQ`0B4No#px1uWWJQyK=WfMBby;+I6udtHkt~gG1KhVm*;9 zmqXnF##>K|P1i2u9;qXjF2uelJBr^OyZjT1J{BFA=Sd+wu$#4PC!`jAGqtr->7{mj(LPmBMmpo6V7AvB>QM z^;48T`m?D&$>9KroK+~|+Os;8J?zTaW{DN&Fa0*5ZnG&yV z(0p$vk*9dTXRi@)5IshiB904{qC{V(?eV=&U3!QjTZjjtXZZsdv`pU|W#=h4=WZ!# zOBb$%31n^Hw((oUZZUSCIlzcmj0nbEbu!ypUu@YB1}8M)N<`i!Iv3`)OSgL^tfXC_ zd=Zj#D06@%X%wF9QVWo$5P|@#3b9cr=g9+vF7nF67U)%b)Cq(SezGN5&@KEeo2WGz zvcNy}ItBr71XdxxjsWHY$&*t9JJGqZ>9%#QJNWY)gR`+)t&jWWbA-1JqoZXB(7H3& z2^R?2uA4qruV|Hy$z17sd@EVzUR}lT z$u|&Qfnqg)pig zNbukO9}+|BJ1c&rBf|b^Y_;2v^T(#^L;O*|SSpR3cQEp>ZjdxAv`inZzY?3!`+s>O zs7g#Ul`P4cfLTq*tsY(@qJJV3KlnyCmO~k#PG1{o;Qm10rXDStHh3FloHfRa?neu+ z!CaRpLcq8pA(VJv9$QIks&QEN9z+?eYyyK<$R=fzyc>IrbSXFql{R&olLO&KAL!cu z21nA)+gl#ENwY(C_c#bsopVi}hl$!zunR}i*>Nl*hP^AJ6MIR>i{dP)%vfOMzYC*D zSyGUjvzdg>swQs;m4$(ZOSfHil?#>8_5=Rcyzz9FU>s!SDD@&LciCocaDXJjD;K5Z z;<{edK!BL9(v{#+!se5jfE!+W2TpGUaXZ^J?9P#dSJSm)a1Ph!^UT+~NVpt@kK&C| zMD|}F?sx4yQ{2_rvr18by**DkzuhM{P{<~3otvlf1baz~QHZn2s=>+fZvJhHRZtl& z2&NQn7B`VY?)I=lDG1-i%ozX^{D_5ZYE~MS9Q^SD9T-#`H+>oa4SoABs87LEuAe8%1;M~-$0o|k?@eDs(*VeB;C4eOGPHl#aKgdIh zZGXof&XvK}{6Of2X^z$#vWL)fO=p9beOm>E+6LDis@`kvm9xawhGfajnf&d&7kAKn zs@I4&Lb4*4Hw@}CliEekc?N$)f77~+tgZr;} zSHw@%Zpc4#HE8RPwy5RVgF!0|Cj8iB)whUWJgOInud5(%gjv*C4}nqKCHwnMI!K!R&?%E$_2779e;@DNXOFZ>KqmUa5dE1EUXUJH;CR z2T=p+(hbT9>a9btqMu9f?b@DMDPG5D2;OvOug%F%?7yJ>u#m8an9nLT^Rku!5Z}Qq z`*aKr_yu`v$u)7vHa6qK|H|!q9_~8&_N269GVb3j^sL(NDhkFLX&u@h3~n}z^tFgQ zf|u|b@L%yDe1|$jELe4$W~CK%e{0Lkx7TN{T!|4IDSz+#idK0G=w$B(`%^4w$_s*% zyLM}fZlm_Bsh`^`;O7VS1L8>YZ}*WY)-Yo%6P00n0Js!PGRh&vxZHKprhZtqg|Ekt zN&*sh_G$^SwV87FWx+v%7r~=h5GX=CCOj`ttAEYh>#C4epy_p_VM4tJw9EjPY5o9Q z;u8rEb1Dxbu>+ z?q@^8geJE$io70d2s|alS+}1b%Fi;76D`*f?APTtTO$NX3?w_4=6GA~Gq^59Da*HXqHqTAYSF-9~@f$E&dUb6X66N5QeiIY@)uV2n#(QN| zwvkJ=tv;%QK4IKQF+3L{{mB=K_rY2Jppkj91drIAR8@oL@ICaTRtk7_+cG@#G&E{) zrf$hk*-fj9?c>RATc^@7bh!F;bVG+}?U#NZp%81JmN;aqLt?${k5I_*x!+#h_TRKX zeB6fkt_7W46&txPhobk0a{RTT#>t54wuK5eA1A%D5P}vxQ&W=^lN2A(6h4iv)=^%VRTEQx zLLE}q)Ia0YMOdiOC&ewH{j|JNX?5A%=@Wl0X74g3u3-NmNdg1Xdm8~L07Y%aX_=Et zK&ZA9H5K(3gjkj{P{FB+S5iLdk6`vKiZoMs(ZUM7-D##n@hQp8 z9&4;){P*KvExURa0tJGLz4;7{0KXSU=8@lY;_Sp48A~OGb!$>Rxw+OwCN_&uf~97Z ziXwB512xe8QL5FOBI=Ppl1 zjbSlZm=CK+kd`T}^7=8KDpiRiYi)YUf?S5N5JxV(oItHods@$O(A$;Bv>>fe-l(#3 z>X^`0n!SrC`-6+(KhM%(K}U2NzxUqX&-Zagd})7t9}8y;k_B`9N|MtRoxN!0^&9%{W=hwB%9%{9dvI0(kLJPÐ}C>ZUo(GwJ-@eIIE-4jzf=*3g=AWf})`p;jVj3EyGxjiB8*AIWRBIx|8d>{W4)>le|IIg!7`rht zxlpy}qZe(7aMWuOeAhp+r|e+BHIaF54|i?8aVS@=GlHQESEf=`_XPVEiZ^6qR9uGJ zkiT-q2bGCDIfbok8e$LopPF0|sW)igTx8dvTWNyvh}+20qY*Fhb-m%so}()S(YFqs zn$WTz$9T>j=muv-|m?R3Mc51=_)5`O_$rfGjVa~<;p|Aj0Q?=WIR*IzQ z(UP|$n97Rul)qQY5ZHm-L@nRjA7aoS)Zbr@`3ARPQwK6T-20>4JpD*&x^u5o;41q%>K>LyamN|GUp#|5-)MovAaNP{Ld# zP$gTXU3MBHX{Q3Ciu7HHy(*b%g+l=CSB1YTtodo$X6%MFr|(4c7Rg|M!8+C8hgc;x zK=Q^Ef)>qJEUhk%3g_2jH=vEW1$1cU&ZR~@+;I-8AN+p6wW6F^a1n6v8_K9 zQ)uo=iQN{ALmWJrJqPgbte=Z;gZ|UL48HvU7Uv0K)71K@@xP0V`Ki|9A_i2qPf<(V zPiw2&=_fT`=(XH+4t0YV&1V#Be+&Pj>jw!w22^(e ztZ1b;Y(r)kpE}$G;v_?Gu+%mq_1%c(LZ6qAXMP0?@Pr?&oE$uioV1^Jh-+?=cSvZ? zNO-7f0;N3?8kn(4P`)#nxQ4((QSU3Wvm!B6~xGWJs2CglB9CFxAmzEJ~BhhxY=8PS*j8x(zmKo8arGIxW> zYN{-I8=R-zQ~J7Y20q=#bPm3*jVj0boAwkYHcrmr#~ESr>quaE7Ku8vyQym4`LQB!I^p~+zbQ{Of|_)bXQtoglzcVmoabDGXA&{S zL(fdW2cJ*0D5&D@>Z;;yOla|COo$uVzvJux-~z$Z(m}yokF)&CMbe`afN(_du$Jid zX1&0^Ba8U3=5cs>U~xrhTzS4xT{-C~qE@c!ISIEgJPMa|Y`_4n!!j{^TMqg7GYf`I z^g8>_+*6JbU2XOJ;@2sZ?1{s6;wE%u7|cE0X6vAEMjyPh(C*fGMY_&*VqQY3OxYVR zfCe$M{zjHP$5rTuyy%+eB&XfsCiD~VS3NG1w+)Wo&js7&c~BdyJJ;`XH#HN>EBU|b z?TG_Xy$e5_dxIm>+{8U7@EL`L`;Q?!#yE^-zdGXt$On?%obo@qe(tnY#(St4;8xL0asrmEt$jRx`pi1`v0Y!>pzjTzIXHGr z*gfdpM53=FW-lTZrSN~!SpL`^)UWi%5zik~0PK)$D9z|KB)V|dZ5;Tv#K>tM5mfTs zH*B(WP*J&g@VjfbDtdlxtwk@dT&uitdNKd|NHw2|k$&R^G6SZhacT@HrAUl>G`~6~ z*DWK6=96i>4P9Svx4L)2*`6mvk~b;TROUsu#u?T zG7CyQ)f;e(iSbDhUjWxMvk9R*0kib5`zr~LV3NGH zA0evUa@qJZn<)XZ>{O2z!>bmuQ*~c_F%>J^SE+0f#lreITe30D2gbNFZs8oHKwaMm zVEs>*mupXttsvR31c>+2zem?Aw$9{aHZ(M_s=g~UckS->?54(AdT06E=Sxn@0SdZp z6ue5hS>a6;hptoCsWID!9JDlOp zF+vuNw0SCtI1*a47*hyXcb+nTlFpGdf3fWj-?92NNpz^{IQc6lyA04%@7^W_#?u$w z>L(z)VNF^0T4a*99Av*B(!_{QxSDScq6d&7lJ*A(A&^u&#EFdKE+EF2f3aI{q>}|xtR;8EU%+wGFQV0po`-qPMzA+EN-SMtJ|*o z=GU0+A1x+pg(egDzQsPi3L(uLi$)&|7R=n{eh4@>q0bLjCGwHZez>G1(>DMiq9KCQ z`j4pB#4i9}+{uGtIS0C3Dj} z&!p8{#l49+0DBxJ{IdZqwtU*Bss=7M$+dD4gU>67*87^$4cs%whGpA=9sgqocg^_u zE{B;VW>)-qS^1W7jPY{MPOFOuPq|JHJ%P`Vt^E|jtdHF*Y0{xbbFxgW75FsD6Wg+#|e$2iR)6y04%V0t#1L|_h13fr9WXh0L%q8W~o~4 ztFgyoUG%T3pQqDxZh)y-OvaWy?`6Q-Udu7!^NH(fqdwQ!UvX0{jfeN3vN1ncE4F|K zC4dj?HDyC5*Bte@aYmaeKN#CwcNKw8id07<@B`->$BT$y=Bb=qx|M$*&>)DZe>oa1 zMpu>3vA+IezVyw~qV32xi{QM;^YhBdfn%TG6Bz7YU4W7^HD;su`%BoPk#r<}xBDZL zn4Zxb6b#h$wDrq{c^c}e!pnMty}XwOM&eJ^R;R}1Y3IA0@|x`(a}#e@>6dEPyGy~l zC`ZirS`G%}S8U{#9EtTcmgnm7u@%-;)ydINbh_Tcn8{z^gF3#pnTLC|Gpe_DgMAg_ zH8jU$Kr(6!K-SDZF`UM#JEPKm-?Xcg}4tW`@ z#MV-CJsWDO9a39UyWHY#qJQcjiIK{aEdh(4pGHK~4sh&mgj-gbL)lXwTjIq0$l?=J z+0dms$!bz?ROYz7%4RWI&uVF@A0<=&+=x4WvzlFfe7HykR-U-5SZjH<75DE8!?aRC z6A$6S?qlz+n8^2T(dnwX+uU~H^{hCHRUYihtkRHy8ukw-a zbHotjnsN;jtP&uq1%c-fZL zYl2qSkm<}BGM>OtNCfGq5X`wn>Vzc?ge8^D29?Dm5Fp!Q;;^$9Z|FS8!40K`mk>oRfj+Y6z`1e7wY*t zk<;@0?E-CmLMP-5(kPMr7&+0s`?tdY*mk7RYJrlr!b{mdClCSC{?b-%pBb)ScU#N# z=MTKDNyUYqAlUb7qzxbo`wo7C2HFuO9l0Ng6BGo#7WP#Tihr%_RUs_`sR91blfbj+ z8AE?E;2DO{LR{|}ZcmF5*--MYKY|7l8^PG>ii$w^c(x0Msus63c+x;@fb1U_nZ&DA zQW6y(CeSYCNpQtbEkJWpq}})I0tO&i;w6aZH9Mju`8`Vy#K;Xlx<(Y?YbO1>BPdjY zd>WWIO$d+bjFUG^d;9esIv6ldQ#)WHfR3Zl2dT`+qxQ^RrjdJTCN!W}{VfOVLlsr? z`t2rBCNtXPhVu|BGYsJJvehuWr)s0r()Dz8(8Yvyqg;FYr`iY(L6L!j{i|4_`3%)jJ2wp%(JhzNMD&%#m`0CsnwIC^O9g{ z03@?mReP{q5#CDAnixO}dLgPNC#HfgVw#i{nhJn`9d1b=&p!m``8{VF0HVtl_-l}iyNR#xMQgkV323F?QgwBNgMNZfie|g$!?>eow{%@H}F3<=0wJg5h zKh&!RT1F@!HlE@Qv!T2Ccu(+dWVmXHGA}D{BMjy{)~4iuAn9UU%D_|1`JM!d>QzkA z@82sF=P?OJJ_ozH}D1%rD7x&M&Eo zd8*|Tr>AjKqvBs6QH=p!DA<|?Ta&yzyw~J{O^&Y;w7TwYv^%1wGsDXK8ldqYT*ruT z^{+?ne<^Z5D$+RqzI^}&UBoW>6d#&G9&{pJnmw@oN^sHDz7A~^edM>IP=d`atN$&{ z!={<~VAhYc#V5$bQpUqjXSUFZ-uyfi$Xbv<6?%o>l#0UmO8k zNXlXq=uNl37EFHKDmf<(z*g4fR6$#PmGpV~(_+5Z$}+Yp23y<4691SbFmC%4XXOpF zjJ0;oHNnnh>3836$(i#J&qUvMiZ8R_FcDieQM!~_lV~?@-aut$VpavFl;tQ!W!~HmxJxFqd;%vO(tGvB3XPR zA!MvDboUr$_*Iq2r`sPwwUioAG}kNg1CHM^?+Rq3=He5tW-GHjuc1MTM)Uc>p2y$) z4u!e|^t=BUW?BrI|NHQ>Tl;APVL<*<=-EHjF45#r0B#zDAySQq)Gfwk>ZX^@Iks!k zDcDnI+yd@>fMo;B7vAGZ&$OZZRI>71f2CBv1BibaBBOV;^Xe=#+Y z^8Zd3YKnQf9{?MPjjY&NI7p&QLHp%m+B5(i(F({;J zWH>ACl0&scmc4aBxqO)Rm$SV?@HL!{vVdxy$Mi_qkP_!mo9}7Os$RO>$PcS9sur$# zjCMfZnn$NNbkdo$KK$h2Pyi$VfjMwrYuuj;!m9V9^0h5de!S_f*BcDjAOJDFqDKDw z!Z;c0VHN2+yd!{aC6NqT9m}(eXXy_`eefl?j2aLl>7^VhJ#ow~1pAu)R3G{vNfXzy z;Yh_zY!m92=VD+C-2g%+XO3~DoZq@c1aSe+oEz6MeB38yl;-#x^lO!cfjaN(9Q|&-g%sEqfdFW@Px_qQV`Blo=2V4V%?-`w$j^|YK4uGxM1*fM1d8Ja|nB4q0oX^m(}f4$;Jy?4Ms^wRD9>8I!PHrb}% zB#ilz*~$*|alIL?|4t?p0}{>IP~eO(1puOCCym?IQ(ukGyH-ihO5QzPjSM0~ZmPd* zp3rrGXAIo7ap_3Jwf&u|5dx*=EN9%#H+vNWkou2{AKM7%HE}No30b#A8}gfu2$k;+ zY`81Tb2g8}OfUYoFqil1+Dy87|6%DKDh#(CTp45AzV&>m)pPAilwG*l$i zxNTQA2Ng_V#>_zmuhEG>&13*OJjLP6O^9cBnGO4VSjKe!0bTT+^0p4Kn(8nfuKI7a zZ#lz~H^A6v^OGL>^!@n$l9L#^xcW!YlC6D1E&{`mE}>spyLLD?cK7UoB76K>jfTyB z(>lF9mqnNSjbljt=g!wVn^aXG?7rGEw%IIC;^y-42Ribzd28f#Njxx!SRog39JMtj z*FcXiP7Th5btKxVG(?#I-WL~}y?_DwofKlUuy#*E z1bH@_(Bq|rG8ZINh0X^syTeFvt2IP<-i;0=D_zunkh^1@uE^G z8)rh+)|&7B&jzqOCugnb#=Gyc(>H?E)53=IRmow>T~`4+8>i^4v?*Kq7H!SZ=aQA* zm6IQ3VCu)@9pcx}8zt01{-(#I`N14vugl8p-ujNWgV(l?y8&LO2eFq|XeZstUEP%{ zKaI#A*?s2hr%t?qO4IWLMq;-*xb+=5C|!wbx|aLBfm^S(PeLfJQbN=Nj_rCcyEmMv z8?BEYUvt5CLJg_jAQ}MoSAv~`WML*~u$f9H2pMoa+OoH=4mDy%_ViDg^u^pveT%Pq zC|?ib3M3neT$t7jMEWu<@yh<;GCix2VGEum zg&4uuaL16I;T_?NHvRQSv1V*81}q2UA2+BXn|>Bl`B_9)x(-{#*Eud3nNSV}#KyxE z@O}}?o|D_eF1l4Y-<&msQW3!a1l_a#|AFo~Sh=|VpC`~7)TC@kxezwq(Cq!B13$wJ ze;z{DJJY^?X2d;vk4v_VM%iH5by6shipHVrDU3Seo~%Sq#SHZ>^(NVQ7X?LZ*V$pL zgIqOAT>nPX@n5y4mo}5&n*2A`dpE&3Owgq%&<1Y@u~qkG+eWPwvV*|0#dGfeGzqmM zeXDex+y$OO0w*bs@utNbF;U4CQFx(*A*GdmkvS%Y!E+QpZg50uUYAh)pamY4Uy~Jd z)~jJh;e|@im>u2Qx!=-Q!vJT?D|4;82BFriHHDOkOAzEe9>7YS&G3x!8)UEfe=+uz zp_xQcvYAOH?(UhmySpb7cX$2b?(XjHE)#cmcXxNs7kAy+_a5v%*dGf`AE*n}O+&-w zo~lzdkI8-0>w!iO6+ec(U%uRSA|i)&3z}YKXh{1ppHuH|9Pbuj0NB$W>hM-jQwfF| z^=fCQjZsu7fM6z9NSnA+U&XSx$9(KsNguVQGa0xq&FB@|^Lk%}RJYXDlh(r4g{K;2 zbM(!8!^m7B<$rq#>o~Nbh9L_lAzkMw_VGO6yUa`d?O_;`?q`Mgk88Rc&07)9ozA!lT%3;Q_Xd+%?wR4?%C zgR#x!F+gvEcsgJ)CM2f~hOjKaE{c8r#meWM6o0+p=*@~h;5~zR!nKIFqfkc?4x<}> zNtpsWw^|;Ffh+GNsU3K+Quvn~O*Jp#8F#kF zuG&PXn)TQjb0%z$wI={^#@X(5O3lSr+kzt%_j4(>M=83d%s~BSWAx6Zi7AQC71Q-0 zSi^OMsi96^trx8HO{O6F0ToZ&ez=>UC7J!a%77_TA6s88xAmz&$;!Sjt_OQ+I>cnc z3h=W9b$CvMMZBPN}!hd zRT0B9RspHWk6H?9P_D$+&NI93@6 zfZE0Cr{8Mbk{6(Tj8g3V-5^bb%^8x|26Qb}OY4!GrhBXP zKLcK-<~3j{!Bu}w_#2csKMe9%^*y6M|KdJIFBxs4=+KAP z!s}W{HaBwa1J*4sMX|36hYwL#tSOVc3v{nmA$J_zj z=DBkT1l{J^K=9I2s}ScE9Jb%OC^x?ps={)&m9;`4$TNkOsVa8m;JTM<5dgHc*y>PR z_c*G*`JCe(>BXMnOwf`475gntC0cour_Hw#A zYRHf}KQ!z2hY}FpA;-$PIU$Pszb3OZY{Zg?b#t^Z|d*v*);=Y3}d*S9*%@5+Nx+ z%k*zOuKJHpO;Al*IA$%Ymfl*m`*p1Rajr!@gyc2hrDplLWK5r55AwcSR^-Nhk92*q z%Nj{mc|E^2WUNNC)BJ&-AI}H;1ipA@94mTUR9n5-S3BQZ1fFr#si(C*$_K3nkSUGQ(KGbGQ?OTai%li3j;lC?x& z1Nm0zKUj`5QHm^4nk?OiCjE5b99+7d4Ytr%`0cP_z4p%pL)6zFu8S%=?xeXy8~4DS zG2J57xfAhy&tz7RIjj`dk0}oC#Ie>r+u^gvg6?Or`i~;IKc;?vtDWjvWVW74O(r zJ{IXy%II{z1-@6_D|RhDv%lzzdKSMPeZF}=^~~SggSI`na@N_m|2*jsU(+~C$uFi@8+g@<><>C7ux5@JAY``YnF6Nwxai--TI20d6FLyAX5ikvT0tEx&%>FY6?yHC zxu2bxE2#~1{Qu?U`CawuZbU0TMR;6^O|M6HYOm4``nua zEUp1T^-6$$jyon`HCP8H2$6*^5pF5QD!Ojg^unq;}RE}(LfxJm33_tSb)k|}6=pR;L^vZK8$go*i_iZ(Qm4t>gir4m-xOWCoO z7nf98F~ce9-pdNfysh^-d1cc94yEFUhhdf5NjA`#=(!>Z-5@W-HA=DC6huL^M4rr6 zz+Kz6=BkO+?fNJ(0+}RUmUiI1Syze}K55$7sl;!k<^?9Kt#M7|Ayl zh{|o0K3SIls!Z0qi3UfioHfUeJ`$54D)_O(lve16x=+lG1;)p0QM? zmjx;VImWzwb*DYbiOR1@A*y+iPhu76~~OS(md%@MI{mP>G?f@4l3iE?b7AsA8$j7e~75jR&?NPNTuN<~In^32L` zCW5%ad}~|Cmk@L$OMw@u{L;^O?~iG8#b+dCMLUi4`%fBH5SThlC35Vgu!V-BfKWo6 zHQ?)2bAi;gk!*a0M)z;9?e@f#p#3;a7$Q>Tqwq?Hm+#V!@p@5l!CloW@Pxwsf7^$x zZ(H#Ysyp3hHE7fzq41mXvMqQv5Y2viW>XmIPTSxSv z$s>r}#xV4cX!L1rYb<6QzPYm)!A<)(Vc)8vRvp*2c&F0WC^jBk0bgo19GawR6;&z{ zUzKpqYG~8knV){<9O>}{)VVq0&0EA0JqLEosdhz-Yazg^eEYTi*uL~A==}9yZ(W}yv!!Rq(WgeKOaIM{&jqf>U4Jfo8^5%nH@ zANRPH&?7m9ZY2)iSq224fe26edy|-s!bQ*A$Y94R|04DyZ|UUlo0aXylLrYvs>uK%TUU z$Sd1-P!mV#(PIf-RnXumN?zl7k4OUEtY!+|b1my_p}BzTmW2r`zX^67yYhB7>R}~0 z1e4v;qVx%W#;jl|Jd4u;X6+A{d$WL8=MQ|G8ywc^7gYG!;2A zbF^{2DNDDLd?M!DblTD0+|-X!oQ*p%=;CQ%P^zFyD!URa^jfoL#d2~K=N#U|G{k$V zddb=f&Vk#v#N`$!e62B_|9zAs{5?k*`IVR$2u4$_--yT4w|}SVdGP^9=I^O*v~Y}* zNxkmP+ZrhIA$TbA#F6PUm?XomK7I_Ay6wq&g08L0(ebYT5IT{|5R3oA+ZQaT83oz^ z6n3|UJ}^)ol3L$SjCiBqa}MQEonk|)MCb>kc;=OBXD95xuZ%bl=EGbHOh0F>Iiv5} zgRcTPeS=SQLF|X*vsMTdN+WCaRszx!HVUnRfa=d3zj8~X1l9fozajR~tZhzN&?+4B zYK#HQKL-V4jv}-k#4{YDVxw1Ua1vIn{Ehir7V%A?g%sMsCJ%%4sINojUt>wqthsYyWsyqsRWk)+q=_W?yWl zbxzX8DRpCGD*DT@kaX)*ksW&_TGyqpYwOgFJ!3bz+pSP#`!t6g`#c)ovkMz?0G_-*-+LtgKi>N-CeGYET^vhFY)q zM}^QgxCos|=Z~*}3^a_2dRKn}`f{7d8H}s&9y;YFdvIo%T_~DOM}L>P%{OW4YH6tD zlAja0KAE?idYFHf*$A=0BqfVeK?NTPHKD52BAZ39X8v+G8)Q%5x*)J9R0080chZqD zU#4&hmkr2{VOJn{@f;EU4E!sR``m%`wGQ?yFBABV<}rD1l z78CjbYNI4YRD@RsMw_5`IO8F zZ4hisNam-3n#E?PW!M!*P;zi68!Hc%d3OLaU#DcWg2B39-N~&NvzMbUMq&ZIZlNHL zz?Lpw!O1UTRKp^^*%inBSfwS-mm?;1A3#708zaJt0g)UDk;Y$%-z??$il?%|>Kd4h ztN6+N%DvfVTj{#eIAfdlm^-j~(EVas5|A5WL^_O)6NhLn==jjgM_iiqv-1}1y? zGDNke7M8N@$3={^F-Q*X-5M62UgYMHuW*8QVQ#i6`D@d#`AUCXgoOVPlg1{o%;y{e z(OPA*{1E3yCAZhdw=o?XG9iMDa~_CI%EXDF5`t5L$F)OPe?prZo8|-ZNeS=2DaF23 z#lA^s5@A%yAcgwI!Sa=AnFRkY-~K;0r}O@1NSv7J-LVO@|LiyzVLJKe9}SQ6-+$0G z(UAeFB_u`h>A^X{DM6Fp<3iu6WIm%F4ewJw#UX)02nHqw#)9<%5FSPn{nG(ERcrwg z{}yO5A*o@AVG@F!vK#b&U(#>@l-Lhy4W+j*G632v-}tYqrz~h+WBs-+d8HxScGgE> z8%5^6F@K|L5`*|V-SZZxXnlyQabJlEB#76%0DA|mfPC-N4|4j~lQ+Ufng^OFnoH$C zZTQz^@KhjH4>VnR&^L~`#;FFT#%ftmTgDwNkiQMHj446PVUQapSK9-9on1=)s-|V~ z+qam8b22u1u)^hIu^M!6u_cI_G0qI%U%bE3$^#xWHt4L*Vh2XrTjE|S??ep5MZy8H zVF)S_rM6!`BKu2;N=S`%t`8GNiE8pea!!{r5@X|_WM7>KtJ4t@*-#JqGa2*KXa6hlc10SKCAD9>R8xLdh@UioQXpT6~jsXeJo93GVvHDqze;iuuOu z-5_;lYrcHpV5Iw5@XSTZmXUyk$&E*kSo(8eSwSh9V#=m9P&#I99gJoH7ICMlUgcs^A5?%RV^r;vruK{2$hyjpHVt` zlxO7-m6i^lQQBjp$;x#|r8PVXNMP=^PS9(}|P#~hWq^v`dbFF^ZFpSK_! zE!HGhZo3v90htHrDIb zs!fe{4^SHwo4Io$($w2b)*Fn49E>6nB`SnF)zMg=4uk0Hk?NtH>@JpgqXK! zf*y&?yV8<3C*%@0NDr9H#Dwc_)LL>;EvST?cqsM6Z>s_1m0>*%O=Pbn5xz%~wugsf_DnSSG=O^_XkZ4#nZ|q=n5EDgWehEcP(U1BqY%MZW>B1u*eEzgk(k$L89sLM&^^#6EA+%uZ zftw)8#OJXcQ%#cKV22IX&j3jEZ4H+Y>DSJHvQg?u=%2lywT-Zop;KldR%bQxbO&gM zCf)yXmpjmB_l5fmr4_zTdb9?r(^?N zM0M!yl`jH9p)1_5N}Dm>qayUy&p?ZFzT^)dqVG6A2fIBo>teUPFI{*X=8RS=CKZ6S z_SaS^5ZgCa1;2JO=WzFMZ8HoRqgA2n{|!Oygi<3@jt+sY zlxFkEaH3j{=j-~v!?a+eG^GB8*gB91C$0OmZ$b-++iUHz^WAfI35mIz=QZEm(ew5G z^c;J1_lZ>-YHl%Dd5^W=!D^&9WX~Afw>)G!Rz2AB*CMbZr;AKooUAew zTJH{GjM20`I%=M|-98Nv51t#Ra|59OW|MvtpI#l?_d2@9o54qOsumC`X0EgJ5dsYYpFL&_QFbLrGIEZQYMLD zU4;gR0N~N(B@7@T-|&_(;)XpO)UX(O@4{spF2SN~2q-TMealDl#O^hVutUhI#}V&g z;Wg+_D*KvxBloP_JlPQ|e8$6$^|Sd{>EsVKAjUZ?Pi1OvkM-5a5}NvT&hQ^eZLafD zK`k@5Ps4EYWYXpnf57vgOO)1?F#d*eBg1gl{h1s9OFt}GhY#X~GK2m006*}vX0h~s z6}Rz06lg~cA+z8qv*6k!`e5_4&3!xVKBaMVNz#r-n~TFKZn>+>W3|=SFk(H4uZCpH z&ztHM)i$gc{(9E4F?qS=$(J%=1X?1jNL(pk5fuOeH1z zbqS+*7E|t&Z^+>DhBBdkINSb*$rD%8K&m+KoUoN~RXqFn5Y`TNif7Rm@@pr4K<9^P zY`NQaYZLN{c|?|I4=Ax}7adGHd#mDpWRBnn+>w4aM2*Qn@hdms+UL!75pE@lkS)A? z2*iq;@7c9~E>qY24J=%nSsZoKomHLWE>Dz;Tk}K33o*D$;)2fiKQmR=yoKWb)RATV z-*jX-8Q3`fdq>twO`_R|8a``z!)=Ays8Af>%A-unb=N0P0wv%5 z@nW1+gCpq8ioX^seX#QRVfmps4G~>B!MUdIi3gLJQDb<0cXVs<(LuBIopTLebZ)6< zdq)?T>gO1-eNQh#bh6V6H6L^7#|Sa*pIF-o@?e2tN*4 z6xsg$+dW&D+jV3DZq|s+xvUNcgVU}D-73}H5A!CMtTPZ{l0=1B=h@DCA48ElL;~M0 zkrh5r02lRVw4eXg{#9A)wwxe0I?VIAe{JpQ(eJ-~oNmYjvhjW~;=38AZwXe4-Y%6y zTz}-~XuG^`9)2f@ahDfNQQ(;qV*9&%Z2z@Jik&5caIF{SoioqGMd6y7z2?4N{H>*( z4Z|_p@es@5%_XBI`j8G$_}k2WCteo2QH7IbOJd6Xg%!OSkH$)}LS~j$TIQQkS_b6; ztW?(xj4u3cK+z8K0qxz!ZPd=8%*QE2E|#JaV(j0f0b&SZd$5+ub~RSo)0Sic+xA{U zqQ-PWupVUxU(amBQe6jwR2za425Ib~0%NyJT|lVcaoNH{%_oDUE{_@KTN0u zk2RbB!NnMflEFZ?r9YX7RqDOKnh-{F@FZk&4-cJqqZGcgt9rYc*2LDgBl!;>jOkB1f%ppbVK~9v(cyU= zQ_ALY<@T1A`=hXa&d$HdduI?dgG%<#$QmK{K44db`QoJ8`6lv(q7&kVrUi&sO&e?;8!G{dW{{=EtNJ27_Go7oKcMgx=~hl>$!}hmZ(4w zx*}_j6Q@pY=K)4lc3(GE(xckQn}`{o(psy5Yg)$fJXc)M`{9x}v{Ohraw37M&aJi@QGl z&?YZXNKldUV)MvW;Q7Qe>!S$yPHigh{X;{1z9q)F$iNmauGJ(LhU0_TIc3Vw!w*h> zea@;yJy+QE3e1p3e85meTzp@7hYZ~7Lg~>2e-W?8n{D9&2 z-puy_i$YxzLXiL1bnHEKvPN)yURc%L`|+MFzr#02G&KrGT-6}yvYe8wLhFWkA6nCT z{Akow?J7F4A~P{YqVKv!4;G@e`~g{aqvdoyF-&pGC{1LlTC_eW)h9&67Tkz6Q^SVX zeI}TG1@MLKJv#oCO{}jnBA^JFIzuK2IUOm|NOg0K#n+ga@Sele;x(G(?HqJvemnms z`JX%Ub}GdaEtB$Qq~~r%=0G(p%^eBxn1yMO3bDmgnOLx@?kNh}xC>IHyq_BH&gunk zDWyy0`jrlj3&I$4;|G>1(-M&yX=26tmhg%{<k`^9rHmccB4FRlPz6p*yakIGAcBy=sz-D$#rhbEyvorG+yOb zuELqoNzpg>%lP_PGgAw%*AACCbb73;+{In#;`=fW8z})?3XE8tsj*MlGT?A;yr01v zbUbLnVw{<7LDG`Ugkh>#6g+jj`)94%btZvGmserdU4~kp;mc^TFg3ljUSXZAhn|(| zjo~s&bv#z}3ddcXJCI$`sR<3h2`U@iXjiDNcJFm_U0%j3b#1%>3p^p{9e)O}V#eBQ zW+@R%Vx^O9n=o;sbL<@7>xRJuBtj#lG42xNODzL=TSfj(f>yGU2f;L?oK_V2p@a3@ z+oOVRhdmF2wi{Z0C79b*JKxQNnWNHN#zAn=8-uSSMvbIlZBJ(KHH=n0H(j@1^mC>h z*qkX+V%4@dw>QnZZ*VOzD@ndYP>Z0^Bi`_01{K)af*KW1`$9OCR`vBL^L%Y^b@b>D zxPE(8>yB_TZ5hOjhsv36jK5TyJ+Kffat>f3X%?4kCN2SdkbjjT)sT3T&{Ve zZ0%uFbfbL3?GKT5r0yy&Msm<(#>lGF9mIc!y#e-RTL=}u}{ofvMg zC%l@USRF&|{i$e9U%eKEqkF;gwh#B_FPq{OW3uKa7)y%MIu+;_Xr!##LbF ziT|CXO(5&lWmP(_-FpoanJ!x7xl-Atk7_h`pJ`*rCZniTq6^eja5Ga4qskc$_|?Em ztD~f-SZ_n*BM4%xuaaa*zOw>gE zu1B7pF`CPb+_AR$xO1K$-F9}B&wWQw`Dy}aHI<$gZtA=v(BC-nZLf+;MyCWA+_dF7 zf1kiqbeL&aTY9D?0Q^s0@ zXcK%m`&9o{YPzqaog2m7an2LoBlez@Bn3)s%fV}0s^yKaSctSfNTtAJV@d8w#=x!`(A|gTRX;XS&&*<_Ln4qubfx3(Ug$J$5+n~v zwKcI=e}hqWvk%A5m}XCXY-9Pk>@}ZY#CeLiti3n*{p~IKYdTa1jYiW*p{e!px z%nf!E@iN7bABHEVXNu_#41d6bZKBg=lda>g9a?v8HeMQ*U?zk8mm_1S^wZH({R`Y& z+bpa!0*~xDl!DyIp-31}VJuTylGFcOO3_#lI>&nNWuAxuCK>*D-CvdBoA`}?To2k^ zllj&A5^Pj~Y3JG`)OW3qev!?=TVUOo8LN}iXeZ;@JoBWd@r7U-1JE-!RG>#R3yuF6 z@D#Q+F;+13s-Pba;GDO`n;-3+N9jWmxCQ8LB zDL3sFGfngTQw|T8CQLSxQT~}vc?l|~dUeR}7Okbeh@T}5;Fmg!49R$9d?`$pH+_yf z`A^pR7&P2>HuQUUQG_&_wOz*kl$@c05h=lgqYb`{8Q`GBynS>SyNsHr@# z15aGSr1)GN9879@0DBl0Z=uCcj(oI5~ZQ0%_H9f4H041|z?}u!;xMuwN3yauwTvDoOm3S~HXSjnQNoL)5uH<49R9S^U z_SA@IrjDg`4?|m1xDyUTB5trffWz5>_W@Jqmu#_x(Y_=ICGgf;4eTzNC3D{EYEtSg zhu93shK7Hw&=aiJ@omhi8jQ6jx9Rh8RW{;2Cw(nM)Q8hq4qi+twjS@cTun>mn>}Y+N0aRdyy36JztKr`6zAD7ob0U!j**Y~CZopRs$>nbE zWvL`@I&R^0Bj}knd(P9D=#Ai$?c%F0YE9b1_lvP0PDzIhF^neIOsvGJUiZUyG2dO! zKp6E7tp#g=T|8=%iqLIF#~WEGRIRD-E#!vQS62oEuCBpD>st2k3gkDA^Ocx5$;Org zvT)d~Pj}k7NtXfa<-Hhm*16HEYvXXf2*F;_n7)AGw*&fCvC1X@V|u%u<0FGPqfW=j zNO}FcMkUDh1=aADH zcc%7AmLC~Gm5I2RYmaB#RK~~)3C@yel)n8I&(ca;dD?l+wi3_Z9Wa*~Ig4M$-;Jje z+nkb`fPu2Zhn|rL`1zk5o*+G=L1#WUfNaVKDf`Opyf?;-fE;Utk6d;)WdChvX(8OxrA|51KA)QI|3G;e5gFm!CyyJICKARSN;|UqrrU@cSbl`*L>u~qt$9^?*d#|UF|k!1AU;tv zxX;96qbTpp6yCv-)jyG%Z>}B~kdO{AIRnc7c%=*XGIo2EEug|QW>OE#6#&S{4)Eh$ z;f6v_{rTlwo)>dc+TJb<043(IrGVy565QAOiaw>DX51>h>iO24=w8XX2=jq<^L2S8 zW4yfM&DH7Fz$x@%ZY}Ve0btzVqLtV_*228FRsW2cpZ?jcTpr(`jzpRjtV60D%w?oM zL$_y@<^rXbZwf^)qtd_9AmtV#xg(%-)OPOP0nsC(wik!_E8G8xEgQ~Ck8YpZHvm<_ z>mu}J7~!@l^5u<8bii^I;kJrk{{rLoUq)+X6T!X~|KJM!K1_wRRHLxx=WI?ZmznKW z<4VBODdF5U~GD*HplZ4l#!hQNVkipM^l9sS6J@7wt(+d>SY0a!%atl&B$?N5NB- zX~=vymhk|_;Rmmfbvei5dy)+PNlMG>@-dUc#cX7U2Znr&Zu+?+8Ko*0c*SL9}@ z@k3a$8>ISTeS1BkX6iVo1>AR#@7BQ-pZqg3ydAp2eCpO!+b;Ig_wK-4v>7$mj;n2W z77pZXRs{l(drIyu+vd=RM-=O)sOdG%>Zupv4EX~+5Z-vx0PvfiX4@m4A*`7LiBLm&miBE4I%Ei zknfzcR|^Vn0aUrzy-zce&7rYH|-srH9Cj@Vg@$xh#KIZcD;%`hhsd#Qa2bU)UWXyK#_9<{Q zdOK$Qv=Pa$uz^a*(kX$lNNgt7Y504UF7?tv2p4?D6U{2mA%dNT>OI#*BLU90UEF@_ zX4or1oR7_@bHwDqTUt!dMp5&8fmgDLIo$Xzk@nyWYFizN{JAm47S6by6;O&pX9>8e;XSZf4|*^U1t( z1%z1d*xb#;G7sy^v##N}z;2^B>af}TVS+W@|Qc}skj=qOw zXM#>f&s0p4j9tnD<3_Rpzk-EvKxELMqzlvu7u|q=Yg^8(s0_`>f!^6#yN!RcrJrC5 z?Tx8rb8gchCZ(=lciUqCvx?no&SL<*%1e80d<3=1i)U`!CLDcT^RCk2a+YcYj@FcL zGH&E#WjtpuhzI`?i|rknQG~K_{c&@PA;ch7Tlf>Np;`;G3^}}Bqr_KQOOtLQA3mCQCz+U{CA@ zAi^ZoIJDsJ*B#e=@Q`!ui(~I9Xr!?Ep)eu3n!W-uF->)ELBwce@c52HEhMo?4KDP;?vUwO6=&R_^ew~Zohc$=~GktH3=k-PQCG*SyK8f3~2e@xvmlZ$~Wb_ zRz+rhXK1?I=hCW<)hT&yeZ(ra{6os2L)n+&8f@wgX-c`YKe}^_&s{5<+LYNMlS6l| zQ4?$sYEtgu%Oh%Rqb~10nwF*NMwAR_q^OX!w7dv?-zU^v0N#w@3`$tKOet3%nCJk9 z;^O}2rOPNO$2*$HcWHNa&;m1nI9g*=1ut}TR(VAgu%dk(z5|C|CPPP0R@ZDv3EQN@nEu~X=0{;Et^OA1s*0HPn!GI8GYXZ_8F@Q>UG2@(*r!P9FTdQ=L{M9YLXy|;=}ynX%2Qgi zEJM0>j@xGt)my|(C9axp%?qM@>a8Crv3lRoQkzp<1Dbb(< zoh&&wuxziGW-#=Oqa9Y(8a9HA>ge;tA&HoYM@T7upp%dlikCzqLwut0xo%Js@7G36 z-o0*+n4)fw>PK&o0-?YN82d$|WP9{cV0Fp7f)=6qgvOx=7$53kXdh)AkOQ-V5;2R| zvw}A1vj%r@%$z1Zy!XTws<_Fws|5p@UK@>i%RQu%Z~(`P(>S(bBty(cM6 zA&7+>-fxcvgaMZnJPJgq!I>j1f_8Zf-1rg)3m!#SOc{S6rV!VRgVZm|olscmC$
2IXFyZQsZ;I{N@aXu7 zyqUX#r-=9q(H{?JTs+7A5R5;(AgTICx^Lz{2|7JTMxedI271LicIQCxABDsboJ63Q z?g+F&kTM+#iSk|P?ZL8lD&SOEX<{Qba3GW(KD*ZcLiU1wcNujEx2xT>Z{1HKPS9#9K20}kUT~BY!YQaDKL1VzIDdW4NQJgRrp(Zo){Guj5lD%1 z9PF6cBO86l)V@FC+LR0{oC`cT|9&XB;4o@R}D{m}e<}*x`8&p7Tp~h!~)~}i))d;>NQ;+X5`3)o}^zK_=!c02D@Ax~& z*hX{PSZAag)&;HtxaM@mB~%V3hlJud0vIhT5Cfs|{j-f}=l`JA&W~OVSv7|=wTcy_ z3^*M#TR11ve5vm_{Hv3??`TmPI;6byviL^fODgrR6hqbOg{f0$r%a_aCFs?nw08{*Nq3O!Sd@C4L)%}CmOGk-K9*) zxZ@>enlJGy%rH!)K&Mw5u6{8`B4ajP-$5MI$e8fICmIy@V7ZNteouZ3bc`~cpfd*| zDXJjKwmV&Lu!_wSSp}#MKxpXoyP7n~7g z>iv6WFa~Dem3B7k5An>{)8m7)W42{`cEPTG$}*hTvN2x>TkGV7?$}2(Z8+f$xohf+ z-wv`!bvzK6IM1gH?qfOjt9<#A-KQ7mZDc~%Mi&%FufGc#UAsslqH?JtP0fLPRc#tn zX*-wAq&2DAaMSCU{Zb1B199x16d`&J%01IqG%EWoAnDQI<&pPw>(AIA7vA({XtzH@ zrUta;mA^F!g}Jif_DV6f^(dLh(uu|3-ME^a$TugT>n7&a6LzPNU$ca`H`#UeF>?zB#`n;qha?}GSym%FO=6 z8p;V>(~jiMu5+2AB?EPQ)TLy7`LS~YSH%d7c5q30#|CdJ9S6oN2X&l=(}aJb(LB)# zmCji0iuNXjx%N;I;cC*k1WQ>Fl)xR*l~K2qQ=zForDE*^d!?3MhVc~IKMvM#Pe`3K z=0gpms0uvzV~>Bts{vdN(cN(uDcY4<4rL{tOl7KIWvWp}O-@1B-0|`?{|aQhd?f9f zHE6Kr&+V8gyL|BaMw7-C^s`Zx@qtO^f$IeGKWru$3Dz|Bsa!(!XShnE558@5sW_nq zm|@#W!Pt=cV+kh7b*pRzUo|+>Hz!?ih{4ODUc$)J3>Lumx#VopC`|?Us<2S=P?Z`( z)h%mjw2EVBR?9pB()!a zcbUk7@bSe*pX8n!kG-;>2iuOiiZMg91D2`HLU=aJ;mlaqoUR*>6Tdo&DLW(Cc=F7& zvTSS{u+zfK5ht99w{~eu+U@8rxX;ci%*~?=)|ZeRDW4DD?kE&*(RCgrEmgT-UC`X=tNuD2hvo~oFdzyBScP{gXzTT;fKZ<`YLxB`@0 zL^LHC7WnG%*W8i!f;=yUc>hn59k&0H?8rG7n>d);04OAkO>CUZo!lwu6-@x<|I&Nh zDFlse4NWNNm7MMDtW2!`E&pcVg{pWk`^c>X;1$AL9#UF*B9S}E7M8{@Sxsc1~ov{N}g zAt2I3s~Nr{tD= zf!A4Hj63#b>!5k-?0$r$^kK&LE zm+8uM6;zjShn)iTew@Z^poEsAYPO;U@gjwpm4A4ydb<+I+V7KA)8uV{LW};%z(9>} z==-;nM&)wLh1AN(4cevx;~ya+E4SDeLvZ;nkF5-}FXP?1O{bOhuFTJ;brGhO%iV3x zkrS4m#I2pt7Vp;Sd}w`y8UJWV_g!4M88>L@lUV9!?t#04H(dtNbV_Ii!QT|r>z+lH zRL)izwTzRX_jBP9(Nd2u%uTNwdOEF>pjV?-4*`gH*DH49hq$K<@XuG5gG4YKRI}a> znXBxUEbg&BQ9Q;tpY5n+!^>F^fE9Bks+s8oP-^P$dWIJJAmjA}*+)mZ7PhlW^%~q_480SZFpdwhSMueu^-IQ_)9Ro9{cD>y7tL zJuz#0=2ge=75y%(+zx|%`x!Hb0g?1pAvo-YbI1kuHf1z3=L8a6Hioi;6&yyU>LQX| zXvhN$ZC?#CeMubbu!^-7A}>lSkf-A+&J=Iahw^d<;Mj8YzEPsNMB52xD85-kS7mv& zWp|2ex5zQ}nj6lmi!1fI(r4Q>pF*leZ75x5IH`_thcN61{a*VuN04DyQ~WlE%qnP{ z^Wcc$Cf(s1g&bX8jEtOy3$DX2zg|T-c%VXZ#8MgMK z)+=a89fB2pEE;4|6^eW4y3{#wOj6_Vq~L6Y(xyTJx#zTE@rr$QecD5k$^}I)r5q-? z9DQjf`OQWG%(qiyi$^jh*(~yFWx0153HTjv1}eHL#*azHtqO*JWSj)ic7p3)HS}ql zXghPXrt`2ymgB$U78|y8?yCso`vSL>lh=IhkFA@H zbaC}OE11i5btzYM)E6tI8%MFzroo}W7R_C+XnRNcz>ZLMTacj3;MK@h^$2%^p8Xw* zYiveF6pNSExuSY9u3_fQanfn^XctxFT}Kab_!~k#I`FrsHs7bOC>t=~$ve6`yXw=P zODjJi8Mndoha?llm^U&x7$?x<>#O(?%lqXH6}|8F%q0qG+>Ug2n{_z8cXhkwZARto zEyd0P&?;WwH#U7`Id#&IBhvE<9Y)yst`Y|f{ci52^hU33ZH2IrKd-Am5^>v0y}GgM zG|j7e{T*S2NQgQ5xjAxNIr^s>+=QU*=z-@|4U6G@a-tsb z@-Mv@0P(gX5z%oZCOCYYhSDYyD#qM|Y1mOr{`-EeZzJUmSVcqdJzKH}=^Ge7Zp&XN zb)FVX?9`g3q(XkkxPFx{?rwqi^)OX2HWT^WUWnpdWnCbT7G(T6P(gytx7yJu<@T8> zzLzG3Mo~YGVWYeu1BzW$Kq~r6l#GNGilxX>p#19epzGsyvVuIkwvRT#MlS|J0;UYg zb#Ce@XjxWecFG|}uU9=^@vX?`UuDzxi7Z-0$n#UN&IW}U5TShlj^T=bjv}QWZc*N9 z(~9f1ZhF`8vUKChU&^^<5rKZt>YFjU%Zo5g?MRC+7pxH=XLideqQpS5?sNF2fu1PC z?zz}iy7ejM$`A6K?6eLwbgVmzjdU9^`Z7N3a3@s_>qL=@8~IK^8uh5~jkjLvVqkNm zrdeD8YQfsPwYT7-s@lBcw;L}xagbqaETG!#xqAXe^MUN>|EfKp#DSVn7jiYHE zY{Of9-}mfxG71(6R-y>u+<{bCzYJ0)uh9aCa&9$KkX|dU?>kbR{Eon?!m#0W{L;F% zV9>A;Y!}&mj$w8X+Qk_Ik~4_XR1m;q6Gx8g2nQzgjqtD;3(N$YpX&<1$;63(YSI-n zzS?GFVIsWHwpPUK;Hq}QyW$o>qhOMmG=A1u#vYMxG+@6>O|{FAv~fU9<=~91r}6e$ zN5J`U)mpb}43D^(2ie`?-ei1)PI!ev;KE09w^F}a9CPbo3Udn>N4?>aRys9e ztIsIWQ&R|G_@$$7c!+{)zj(>@cR0FXk*hu%>x2G1LsZ>4Zde9iie27iEwdtGr>87& ziWV0PcSE$%5aTM-<4!rBYtTe&blN3okxYwVMe}@M45chLSm=RN?RBkbeVW*hwDF zd>ul)_C6XNYP(?PzaBZ>&=xZpI&jOW+BFI7)desNa@u~htvr%nSra@zlC?!TU&?Ty zN%z{2_3rANua$l@>*cbMNYctuC?EYS-*l7bJvD6pGlL#08p%tNS3?=^CTg&xTTWeM zB0da&*tb%R!tpa_ZO+%EXD$}t2WEj9N#=kx{G;Lm0y#()nZ%m!y2uH5ClQ7)XO&z= z{<(Y4(iJyy@$qLJSu-y8s9!Jk?5X=GI()v-$&*c7<PT53<}AUDO!fEpwFQ>P$-1yG44Y~-h#fAmT^6$@4!ZX1g&bv({ytUAWx zDdelDG9rq^V{x$oH2k2sJ)|V2vqEQ6Q`r{(G<2KUswq}H6I#xK^-i%;qXqP;3;228nC;dG1~ zD%=QXBFKWZ=`cU(Nt05l=7wmmsgPmKdtlZhHA)sFnp(mHr}L*9%B*_~~NKbZ$Vi?dWoLl8f}T$LhNnUmP3 zCQl|O?UcN;#rF5>B35!a+143mZRaU4$U1Y?CM-&MLi+89`TYyf(-6o3xf9-=_&Qim zW#Cgx4~gLMM=a$-#oAPvoF_7R@G8>I=m|7(j_sEDVKwTMHALi@5bP;WXh=Kp@=^EF zK{5WSWQB?3t17ssEVTgdLJt1QAL$2Y(~a1=cxsvA#rF~>O0qMsJs@+LYafFgQ@2ML zv|WB(MQi9}?;MiUnCrt0`QTgzgp|?-(SLMQn^PvU7q_Hd_f42v(D4y`Y2lq{<8HA2 z?$&}!FvA;2ts;AIy@F5sHk1_eoz7MB>RcaLPWiCXsJZ|RO;PA|iIgL;336^)QO-nO zVeM0!zTBa9YVD>wenJs{F4WqXp6*wrxkzHkUrVxh0r0nP@oE`@i!T}LgXkZ5863Zo z&m&1A&wI}<-WLKRP7|^lqeQQrF3bW)B_L*p?mi%A{EaqdMvnAH%o|X`r>_c_Bu5Bj zii-8rCGq8ikum`7iU-AC69o0u{4sM-Or|FATePQyFU6i8Q7-o7@I_U()J8 z|Ks(?o9Vl$rOm+eO=qozsS1m`Z=2F40@t*!$`rj*$L{nyj|t~7*uJ;s**w{1(G}Mf z4yr21tyORi2~B)G&mVDsf_q=L5dN5?FofWPeRt6jYqW*^wBP-qy@{X;Gs+@d1d>#; zPYAJBBR;B3NV7=}&H0z>?Xdiv&mNWa2-SDH;rL~|4eMi{pO(Vu6*6RjS+4YZjGyOH zZK$dboC6Nh9^<r+vpTe0k|6mysfn_jwKy7O8Dp02p1wsI^=f6x zv|4%4-nn)m^_w}#VaB_mwW#OKMFZ*-dW0efz!Bv36F-w4(y*+TXv0T->K*nf2^%iY z<+(Hf$i~}w?>-A!8oLrjq_NcFpso6Rn_%)=+SGWm@L0U}t(r?2C7S{KoK)sk7t&gT zCZ4wR;0P0EQqkUrUh#cxq9os9#Z=p{4<9}(LmtC`WDsU#e^Bw)zGjVDyXNb$X?65L z?svVBWz|}#c$dnld8vG7SkoT3;#cCs&LR*AKl(|c#21(_=utsI^@$>~H*DotLA(nF z`A*kT70Fgf6_@Xxb8E@{z{2_P;MJ#8_}M{YA>?!{biflPx+(Zi)IC(98q(hw#mQgx zi>krLjG2|UG?D8}6ux4QPLJ^2g-$O#nro=b zCYE-MGV7+Nyw%(0qzJxcZ^j#l)mgmH6FBo-^D`Me?BF3Fmqh` z)?3_}BeVF>+ENpI_)$0cdfdOi_T}{=Zu9pm_sZndB+p)4Ud*9nlaM7ir{|*Eg>5oz z;%m9R&qswsGkd4--MA}nmnGRE}on6c_FVT3y71H2|7TX(N-a#A#;zWD%hGbL%#7`taVgtuoSQmpoHE>pZ zDcGz)L%X_>hIRRdP6Io}m8Xw}{w6=5e{;t@UG{>=amfvliv)(ntM$rjtE2GbYo<(_ zxA~j41haCvjDHbk()OD zf&qaP11jiILZznvF@kbH zHN)IQoRbB}!8(B1xy?_G4`1{K=Qfo0b*nL|WxvSBNhj#rtlxXXzi&mZOZWi~)Bd(< z-NPrcGEw?U>xidGYWD7{8OPv^VTP}5R0YbW^^CN-yX{#nO5CF1QuiEeedmj#D^L1_ z&hWB#JgA^0o6`m;w0wJ#Q>)%N&7ru7V57fuw3Gj<$YGS9N<-9@9?S^=Z(0|WafnOYQk0i1m z;$uOmlJ!KWl1!(r4&|av&l&n2Dckhy!W)7(cC!#tvwM|}>eaB^VEdwnHZ|RMNP@}( zpVa2__feuc2Uw0k-9CMDY5NSlLi{Y#%7~@sgr1?FwM9gE&}i($ZAD(aRxaC?m?y>T zs{Y_6{X%12LCfHUPGGku!_Z9AX?OHC zO|q2?cXftG{6(D{x-4zAv_$WIqBY>Wd`+vWJH&5-Yf92&#!>CVH2c~(vtN&Qdjal9 znii|F)Z~XmPt~sr$l|9>965^0?(*+*-juSWrTgh$m2_OKJo1z;Cf4JK{O%DY|9;^cA>#KHYrXaj;l;@4R{SWC>39Z-8 zP6jVOQ_!n*=j;uZR#>nwO?A6+cQvk?XYOjNu1I+ym{bac^!6EjlR?{yQLYO8Xd93x zSsIo?lguIHz#NC4!YZegL{)V9>a-7rdI9lqr#VHZ4}0X>x)-Rm=&hg01P4`)%#3NJ z)GCMqsO-X@WN-k542g2`zbG#wCcO1O;x;LBn8S6#)A0vmpK~7GBeuY=13E7D9hRaQ zxO5>htL6A#*+-7B7A|%Yytbg%gTFMH_6j26h3UMt_VVSBRG5KB4UR(TozF+g)Za;1 z3H3?Dq36r&4sF~*>)2(f-=^;A**2&ejHS6MnYHcbxwtpW_=G+BQBKLf@9mRX6bg{i z_B3MUi+q=)a-H!xsFqJud49q`P+-0I0c~!uFl24XWn!MsBEo8 z?9bmmRD}???1U;H_p2s5;_xf6J9(5r2(igM2CYS+b`+ln{3S$ zh;gK!z`?#6`WlKCtrv)!GBFW_n}U^U8X|feEm&Z_FHGo|W>##q3Q0?nlYSAknN z6Qn!5FG*N^qGv|&F^@yYR|>6@!7-R7S_MN$#D6FXCWdX`<6t}fUR#L|=IN33*QljN zJWeo2|I|i_vE@@hqNE?8;-w!MJ2?!NchE(_2PGJI+Nt_ktmvx<9k0B$t7P}Ai}976jv&LlRT(devDn6Ipp_pEti1U z{t^9Chd$dl!QFOs!I1=#LKf4P*$m*(A){#lMSI(_ZUn?JsWABo9|+@V2KhEF=H*4D zb~DPftp0d#^!22+Hkmdd688QL8oTLP8vlp~>08mFWBAXL?{nW3z^H1zYL|k9FOd#@ zo`i|RwlXTjz&xcsyyl$DpHnUsnWJ=i(?l*V(SWIHeoDOIu|BSR#lEgf1K3b#xM%nJ z{=uo&jxR8cnj?^bcAcE7G~F)h;%K<01%?^PdCi)5z1?b6pBL-QUdl_etJ0~IY}{m9@r zlpd4gOSX=&kYv4EmB&iK^Cq;^`PtKHg;kHvroYTCqx70Y4WUFou2#SI~pp4 zZeEKmTe`{3cKYNxJ6<(wvZ-z@JASNv{vOQOIHiW0!p$Ym=@Q?Pb_o?pxmF@%NLf2r zT+T~LeZxnUYbR?rOg@kopaROmcaJHNF>b`j*=MDOLY%xD;zQ*k32>S_Yulnsr zfk3xbt|_d#585Y(=jW72+6!OXn*#;=Q?O**!EF;{xj$BxPEaF=ms(HRJj#>5-r8O2 z@Z_EyafNY6Wf{|hIcfXtLA~$ukWs}EkTddJl?$<>Y_S?1S%&M6u6i9{+<`QZaaFig zP!Gjywm+g=KehxcG_R~5H3QLo>_kNOVNmi2I&j>+@UT+HyxDlUo;mA#@cx>YtW@Xd zR;HFDzFaI&3|9qL8;P11X#P%??FnbPfHDDwVR^N@-{I@iCrY8;@MJ>1>D^*Z9q%Xd z>qwd`_2)Rxq-GhAoz`QF24@t;I*YtiY{@dl*eh89( zoa#1Fo0HQgW4x=&?3bdho6U}`$)fl=GP@e49+0kW+l5Nr)QPOxAie#OU%9NQYlz@W&LoE^hVlKD7pUBIjv zZZ`GW+Tt93%6NI&N&#m#%m1T+JdpW%- zew~($dDGDqrFe)e0U)D|Wn@xm^D~gs>ruQ2lG4*6ys?v_TvgIbc^9uRF7SiaLh>s4q_Z5Wrrux!l0EAz&jo`jj4~rcaX8Z{gL2_~sOu_@j^G zCR3-aNE708fj^#X(Ym@lH=wI6pcLI+XNGAzvd^t#R!~y^;0QUA+9{z@NDlMj7CsX% zE`U=>VO%Nne{-tP*gq+lXt8{?$dG7l&p*?e`Cj<`77%q~QJc_fQYNnu1|wfKv2_)%xVIZR2)M5YfC$@N3K{cxVsW|zQ)jnh;!AuK?YeQ* z?Rz6Q^vA{lLI4Y$DBHJ>@R8BI2@|{hcV1`WBIXGO=5?sB<(1^l_=32S^|9LHa?aoM zo_1`vozL7PreL+;4ySuI=dHBw46P>Y)OaGzQCbyyW!uhm@Hu6BTFkA8c>5#06R;=0}t_fmUOwNahRau+$B z3ptfBn|w@g{(Ax?KLn1o+(Kb<7_KhkYJL3M@$$(eBe`c)ycW&bG(32s@9{)oTD^J# zJ#MGezK!6xVqBPBzxlvp819UInppPcnP(o>=lx*^4rQ|b3Re%>HAdqa(ji%mXvIm5 zaS39Uj;FRlE@Ds0f*@^iKg=d>nU$W)XVT%xEh+EHsMyeF)$wt z*xV`29>Len%k$)J>^(#WcGF6b#b&7U9L~mD6(kO5FIFO3`A zYFm6nSRRbkA0|TzlY>D*enJ|G21LWn@czQ=B zM@Ce5usbfJAL3%-@trtX@Nq48tWWv!?as5$GXRq|OB#Xmh+)269D;Rga&|WUGzkW_ zaarB=d}$uys4IIV+^7R1^Bk5eFskKdE{Mp*7Cdb=1Y( z+v${6C=;k&4(tsaECrUMFyYKUYp!_KmGr19AQayhmt&QboL!yZ z9u8&jo(ys>4-nL*!Vu46dt&=KMRedQZOt?Yq#wwlmN21YE(7;odI|ZbuFm7v3@LI!Fo#9cpASq={1MJ`w)w@Z@uX>qG@i;x^ijA{5OHV#OzvZ7Ko+ ztJs|bw4N4r-OUWon=~uVJ=?RS+Gq;iS7qBL2%9LMt~eLq0F4Vm)eTlttvs3MpVu^} zX1}LL4Lb<)&R~I|*Y!Pyp95Z`wrBgOk7AN+pS$_y)+7CJXWtBYULK1(#MN8Y3ACwR z^k^qoa>At*=;(!{NPHLXOi}`M&grexbH!f0Xm%V=)h?Ul-SigUg%)X@<(A>gFc@5~G4>T_ zy-&-_qq@S&!prMM=kpul%ghs*)mS+;`~^0S9(G^K0sZ7rRt=s^vhLMv2`R6fv?fPO zf<#{x^$M=K&_>tCVx-b%2SxHhcths)uu&+oOa1gsQ!lEencco;@z4zGmpe&ZMyHLg zZQ@wW5;<#Vn0Sx2RFC+q+JVO-%7&BpS}59i-CkOuoDGjRp(2r7*T40`+YvR)!Tk`Ij49(Kfc44(P2zn!^-0SH@mJt6J{9ye zb_^d*Vq~Z#5Q8hsvY8fDyPN3oaveWky6b|5t-;BiWwN=)WdX`BNX<50BaAa1e{cIX z1{Xb+C<@s>hB%2I_atk+AE(?BJEc59bmzsMQgLe)Ik{Q~yn4assXNG$=eR7(aF@bt zwVF9+$GdDY|FMZ}L1n&ik$u7|+{KwJt^3jfem+0|ws_ure(40o@v!c`$1~quQdDc; zy{Nhf?3t^%LcEeWmYg?>aJT`xRn#CUAl0n2A}IeuYBl=pbbmVt=DfNhLSoe0uLyJY zWBa9c){7*BrpJ3QqK}ap_*;>PH}<+K3JQmALcB_d6-Pmnzh~kVOLHZJd@6iArBRYBu$J z?J#NOagQ92!){vGL{m9|f=69GX33j4MHRx1|Ei@Sh31r|XmWVG|H@IL2&quZ`u#IE zK6)kRLeae(+*Q3Bf}y9^qf6#iS+^d<%hcWO@IDlkX;}ElAmNOx4?CzsGw`W_Jthl5 z_pocdkG=UkoYOLB`}M{2Zg>Jbo<^p2?}hgUXBu9~e#Jr46$9i4&0ycZNJ3Sr>z;Zh zqeWN|x5SL-a%ajUmrFDz>ZpkMK^g>q-P9l?jQ(rSck=VoV#8YoyONW)F8Xk5PR` zUN}xcjk363i}7KX@03VW=Nn-7Tg)|9BnvipyxDwQ8!Q*{*OHbqzSjC13L?WMIcK;t zeJI6hfqx^u<}=#mnc{bo;(vUP%=x3XN!0H0a;A>)7{!@^p#SwQTx*tBPnEqM1ta1zd4YA*r=aVX(-$uaYNNO_ zHh4_#jM6U&_%iG-H*UVu?L=MM59Y`18%lgbwdoFY$9HTT9=bW~8;)}w zuRlF@YADIcAyQ3m*dItVX?ESVR9_=#Q5iq^h{&np&y@lD3HJQu%;3kDNyEoq-2oOP zr{Ca90!zfhIlCBljf+~j9ot38a~~#z_BXu325m_(1@qIWyZf+eqkQ5mBhJ{q<-z17LoC( zF|q-&GrWT0n2n6ryY_WvfM2jG`^P5vT*Sgm4{QGgr;H)rcZTe(;tAJ|NcSC>?-&}T zP9!!*3ztzkXQ$((8@DpIi`nT5k(u0XT&YjD)m`q`=1h*P{hn6HvV^gLbeBc0FZN*F z29^yDhAE+b#~Ap9$9O$VF^5McB7SRXN$STr=tw@8>3HVkn@IZM_bU9gvrF^rjJZflhQlI{(uBsDcfx|9a?!}(U2T!&U5|5 zV$vd}9n-io#i9y|rNL~3%MVP9>|FSFkp}5=0z#h!8dTy2mp89V@Q3D*BV0Y%3SMtr z5{fjZ;kYa@tSss)Mb4EU+t*i}+0PmAcHq6IS(|p{tp>j9rv<@!8hoyLt(%2>an99f zD{`)+>NnE88hOgpK>fIUanvcGKFXylVf1+R-tGSW?G5Ixga3GoK*v>=yX0;*4uT(V zsGZlN5;(VcS5jlupjQ@%d4-56Wd(Y-ch6t$Rw#ve(5jHou$@q~zhZi^yTE*uh?EGt znYMUbMp!MBWDr%D7`slA(`q+osv-ty(K)f1_N z_W9fA;IBowdSfQp6C+n6HZ69Z+uFUmbLH+HdEes5WXl-t4O(vuQ|k{N-Fcc&I#)b% z6yit&@97*#sF%LhlTx25OT(B)P!9sJ^*69~bv1NYFQnO}g^}ZbNYU6A%~q*VR;(@> z%S{*~-m|Q;HHL`9zdDNykx5bdFe0s)XLfBvl{F?6UwOz)tUgltWy0(_@OtOEW%=UP zYw5b>`piRS@s=wV>&%-}c1ht5g4EDb_JbdDxbpM{-_?4t+j%`=A^JY^QJc5q$;U^i zuV3K#z+$_66$sPb@Mew~kNa(ez30BWUOv7E?NO2;l*w0e3lSZoSu74W zgF_zWqt6`w-YY1IpVMGzPJ2d))T{X#f)5@a{g{xhS7Fy^f-GizxV^ozH!I^gOGnrf zmW#9oc}=K#61y{U*TUPU*E3%b@$%Jo#ZNVYT(OOdNt4-UM1x`DhYK9qf#*7?i0erV~^JfdciZOUj)AJUF=~}&B9*?rSEI2enqSx_G%{~^lG23 zhCC$z#0W447sn=fR*k;8JM|N2EJ{t-ufX;7sG=#i-e9dnXamSBR_a78zd~An#tc7b zn>?VLlHCiSq-kL2ofZypAw5xB7nhUf)|}+KjR<;4)8J0-YgxR05byE)JBk`aNANYd zCcyArM$!3!$`kh9=bIiG^E95AEcHKF#%%26x23vFXQ<1gm&Uy6gm@wvOhCwK@fmu1 zbdoB$)PsP;qLd_!4tRG^!D2)0dJFm%^itETap+a)cuK~KgM3@ zx+MWozUyMMJyW_&IZ|GseW&@tUnN___L;@8!x9OCV2&R4(Kgyw2D8*^$+2AL+*WZ_ z@;kwBx<@2eT$({h{_f&$TBF{LkQ902o#S*IkF>k_79@V7CqWQ#JF{^Y3U~zTR>z); zbQ?(p7L*ZoJTUWp{iIwBe;0fHEP*dCAQpQ4#?sK9!m$fT!qyj~`QEL*w~y%AnQVGD zd=~Mr8Yy>CQ`{yK0it2Gk*Fk{26N6q_|-}F$M>y`Oht!!Lt|a0Z}@TZnes%-qWyhZ zMa!5ml+72w_VkROR~NwEAUx)v@%7gfs?oj#EIqTpcYPdk``FSEspSq#1d&<+xa(=~ z0AqWmt+y|=)I;HJHq`c><|Kz1Gof%x8_SD`DoY!;Q+_mM4#npacq-^NVT1{nTyMZk z4j0l(Mc%nNig7QTPjBReo2=bH5G%hEX1McoElDt7{fJZxg*IMKjL~)=($Ladzd3id zczr?-u>XwwMmG#>Q0H$JiuJUZ2S%q-V}xfyr@W5KB8$41q*mvUJgvS>(=iq{~e;4^N$hTSQ(U?;Z019I1q>jLL1izAML9@vEH4 zarMy%2VWGWuuyqlBqBr!zt3Y$nGmw@s*F7M_beu zRX7V^motUk#i~^y8$=-8{A=z7vH9WIw@olIHcGl{+mosC>P6$z+lJH&+v?`@0f&_e z2RRqc)tO}FYSh>PhtT)lcTNTz3uZH-5tkzo&7|tpnL=-|BGDPKdRyJr32Ua!moW07 zyZnUCb_CJ#`{g~!=STRCKi2;#e1`L{@EHLI!-rrUCPp?!ppdw*A{d%}h}Ka63hCRv z0h^haLICVc96(|4FG6}2M)rr`9TNut2qO97@7iQZ0xP{Eq`XI{$dZr$OsgN=v$f@3Rs(1f&q*`MF`kR1;EAuRC2Wi|0I22 z-`>m?Vq*_f`$H;L7HGWDpAkyTjDM*_P~QRkAlX0j@}MMF2WSK0*2Xpfribt-sIJ6? zm2AYsg{Advfqw=^0fkkeih%O=fc01V&_JZ0RTLc!AP?L@t3D7saLW7_zd%(@7ENY$ zc5NosU%%LY{o({La{yRbK>%jXpBXG{n(QD(04qBPz`?`Gn+PuO_P@ba25>^#f2hI%wHPZWGn9-8zy>uOh?4^VVrB!dv9bc#8JV@& zpj8+dwb_|8**I9W+1WIiAHG3bWn=_!vT$f~uxYYzZ~$0XIJG$$H91(ApsaFevaoS# zGqHnyG6iix8ya=>kk)2q1Zh4nqWzo7nf_2Y6!JkM+W)cz^B)B~Jiz}wS_}jN{T?o+ z6+391!-(mB!Q-E}{~qQBHW-rxE$NN=fE244v5!wIsWh^E52+1*L~Bv}(`UJ|=V!cI zUsKtxoesN1a?8DTP@T{UMp2e@3Q`YCIp$8j#b|}-?a{isOZ#UhEnG-JMfn z21RqdzpOeQJ0B~dj*s$DZrkvy@i$hvxY;}(Cgok&{88SlRu?3t6pynkP3>g|Y4 zJEnGCN&MxienD4o@FJq_+R{HPjVwR&seAgTrK_QItIFOliot^nJjw=(N6U>m@=iQw z#Oaaq$}<^Y=3>(QtXB#dLi_+H8mCRXJ`z~*LLW>eK|BqCry4?VNNo%4F(oqUPmlh*q)yFX2OB3D7&oL-l zHgj8DiABjHz-i&#N?}7@(g!?)q)NO?>kn^kPB%S5`-cIFndL7J5VCQEj!&#mPq24@ z0GJ=%>8t>h(*G;{vyaO-{epLu&^;fA)rGEBP;a7_z!~pK7#;Qe)eDB zPr;b~uE$@3{p9Hnk^g}w#@}@N6YC*n6x#X!#uF10BY=gK9l#8oF+gl=|C6Vm_-E2hY>oY{u4{T`SIUsJ_z$r z^Ff$@toi5I2-U(bpJf6{ni)C#ayIQ>^Mstf$=@6vD)1lT{}E8j!p6Y{jmZ5q&!|aD z{i-GnhUgpVL-hX|J$d+DZ1oK-pi{pAG@RF(m-O&cD=EOth?i8ARhm)SRtRir_QuT~ ztmr1AWawsL$Z15%&xgq4!sTLRYXwCExL8?QJ8-%1lIlN10dqmq57|Icz)up01uyB( z@L+(Nv>ZUl#vTj+F)%YQ(Hk;?SOBcd3@jX+Y#i)#0O-`h31nmgGBVRMv2Zanaz z0sb51UoHQ{5V8k9#7O@$2Gj2tzft}h#-GOiUr_$e$sdmKllI?mezss^uViCm$){*z zX=bEqV{hRAwHS2Kp(w}5zzCp%rkR=98L5AX^?QXsuy}wEYW_{_KW+M;v46|||6vYk z>HoJutgQZrO{Ar{gl!BRt)Sz(xGJk)qE=&&t7QL=VzuW1{Ee1hLVx z8E}HxnG6g#*_l{=iu3onf7cDPOxzkeWLq18|HL&iGBf~#KnCYoJ?$n#%%ik!u_r8|Fxcs4F9DhTSt4#pPj?V5D5Mipzi?nT&BNk$;gn)_+fbs z;nRnP@tYayL!g}lXlrE51N^J#H|e37kcTPqPecCdHb2cNU9-$s7d z#(zxzS6%;6MZXjLS6#nr<3FbVtFHg3qTdPrtFGU*@gLLwRo8!1(eDKRFLfdQwWWk! z0mVz|4BasP!#U4y+hYMoh^dV|)xVZpzpc5n{0a*W)#|Axj`dc15RC4GU z&YyV@dwuAcx;+Xa^wdDn%niED28s)7@-Pas2ne$aiZC%U2?#KOgg8V+IfX>oSUI3y zMA(Ie`FNOFIoX+61Q>=z&Ge*ZYx?|h6?R0G0w%M_5cWmoV@3YT;_StLQyYKfrQ)7;* zff{dBef7>sDkmgD%SgupN4m2+ISU8FLdZa9t!D0jdpH2Vqj?n7AWsD3QfWOEXIhg(;V`2JhTL3G=zw0pp{%V7nnT7e^ z^;j60|I!}|2P50R>jBsp*#BL|3Sjz6e{9Tv&!qmj{wFqeM!;XB*N8xs>V^S|eciHVJwQnYNZ2_!*@r9Z7 zZ`!i`H8y58j=#jq%+B(cIG8#98XGeQ$6v;X;ZI5a|G9Ut(>1j)w1b2BEN;cmx+Y`> z&?{J5I}m>QOQ=9EZe?Um_&I!k-U_L63o^3`vNEv$Ni8!!0}DGlqagdI%YrNnBCMBR{d89xDO zXl3kRLde1L2}uqBy&@qqJ1?)jgPozSB^->&hMtZNqJfUi`v?%&&-X9IK1d;|nC#dw z17JDHzWlMi(aV8nz2SWl++UvIU(yC#j4;7$n3J{Bdb$YDfk0pILm+G+f+$1@$KmRO zu*5)Zqmbt=*?@o{fQU2TkKtfG;r&lj{{;G<4E}T4kT!JCHPCg?CH$=L&s54fI#_&8 zB=&@Vkn#ChPS@B_`cD|j_J;rc-9Lo(gr7tIsi5R)V@NOf*@1<%@&C*upTqdy1_Z6G z91N`-?A1TvN2oyfSsb6wjGuV_^YV{A2pRujn~?DzCJ7n;A3j*sPSVlmS#CfVM(fuK<-{kA}x^?+L!cps;bIj zG;`Q#Hdg8stGuYFh&--smd*wKccV8wpHol9`uSPWOECT9q4vY*Y~SqutILN6hqq(W z&H0&MmOrTTbEiL|M>fzzh8GuMbn-Cx8Ql2nB}Kg;&yU&e(J^P^#)UF-KS7Gq6l1I{H70; z$R2=lQQF0XSJ5pP7*=zW)-tvAEp`$hWM$1>64l4KubUyVSnD@_@m(qz#GQm zN!&lFpeo+|y|NPA80`2!4p7%z-mr%>mZ(bFQ^3sbQ4X|#4gmSF+=CLX#h4S11h-pn z3or835t_;^dyy1dFZ!_p-ZF55P(RMWWhtP$T(O)PWO)$+Crif_68@o7L?(`;%xyRo zi^orizvc@+`AZ`_Qe9)au)!o}LIcVj-7D*tWhvT1qH-t}7by}(gj2^VKNXS{D768T zz%P?x!=7Ufsktj^N6Z>`2(HQ=Z5PJ~7|H{!FZY~s7Uy{;n#{PVSB2lXXeyZx~JlsMJZsGD+6%&3uYO{N>zkCt>4)Jc@7nD8r3XW= z`+}zc^qwzgA4NJhLmZT~D2-mFeprBN-dtQ?)>C#(!&G z83o5EN6q^C%Pr3x$xpYhTDR?vYsvbwXHZS=DY1s{5|GE}qfs#m$2ujI4q%otLGw^U)5YHgQIW|!77I~q=5DTpi%FBAmq`%I;t z5HD8o92>xP>1s>9Y+PD5S+#sjM!LGqAunj-r)iK@?!&sfA6zUtdJ$c2D&B*(nwa>R%-;7$3&k6DHHgzj10m1b-p*E$INe=kc;y_+%-tOV=z8DfLmB zc@Zr`1X|4gC^bx`ZKav3FsFBPp`Ifs=W9oQaJur);F4^Q4#Np!q&x#AC%QQA;*_U=2&i7nV(C9UB_<$MDUB~V!SMq2dco# zbEK;H@j3o1)J94xdigpGrL4&~IL7UCGOE2nq1{ zcQFPLo$`BDBFxP>?#d3anNV!EQcDT1N#0Bpg61ue*YAU?J!LaLjNvlvJu9i*c0XVX z@04-hVHkkU`nR|K20H)PM*L^&Ffsq@x|gmZ89T@DW&IGf(?>J*gBSS3cOR9ySa-I= z2X66D+zGiT?i|F-Z04DFxRxj|B682Kh1S4=f-dDnuLa&MQ6xG`nVa!}bTJjy`bx$k53c2O9X+ z1q^SbL(GG>Yq@pHsJ>ln7R80$je8O!+P3qex^D5hd5Tl0#fze@Z>v`p=#B=G%9=$jecLx6OmYkI6D_uidXP)IKW+H)t0N_J9@>hMq99gt!#vbri3wjM@putr z0NTl^iaD z^Kn81CqUN*2Q>p{%lo#qFnRy>65+p+m)Pq%c2D!|j5i1vPU9Hx$TD3A^YlA%dtU^p zbL9*BYWHx-h8NVi>x%1-r=0FyP5$pTjkE7wGCVKpUcwPHeG6lAvna}03$}44Ph4); zZfX2h%-JUX&ff;#%AA2U$}4>YO*fl;1mkKdza?eCTfEPL)vL=iW6+RG=q0MpY{B1~ zt0o|dCb2amwrWZH!+2tmp$y9Z^Elln^#Or_lQ(W{58D^18lp&m_Iaz1az)I?H zf(Gd$G*M-tDM?dZ;GL4?Je4xtN45s@rpfnV=Yk(OSVWxBs8H(sYPc3Y2cKa`>fRX?}kkl z?b)=acg2*>mmZsg7g_rgM!Tl=xbByRoAaNp2QL>9ibdUhTK;mTa~K9g*{aJiSg&9| zpYddvWX`mGfPuiC*IEA#41aE${xcYu{udZLKEbe02=%#2w0tW<1spRL9zfNNYmdFL z`CkIfY69lNy%2svLOp4pb*?-quOv(!KI*9iIO?8ZkDZ5ihgFl6Yc*BB;Jo0HAl;E% z9#WL+KEP7{*rRfqFQ1x>I#FIPvf*`Vx;*kv9!L=52AiD`GO9O(Zc`GJUqxKVg`M;L zULM7n05{FrWjjtg81F&*E<~>ED&fQ>*kpr@x!&tpg88!mWvYCNJ_;av7n-(kbBd-O z%%0|6Zeb^L`pj`XPNn0tM85gd&a=2o<$@@xXtbJd8rq6`_HDKaU z%m#;MH2*YrH=~DbSmW{AWu7Xrbf4gvf$oi^SxZG)DujORtKEKY47>h}+j|+x`jqH+ zzX(B<6ea~0oDuV2P~QS($!jmK#b}l85{pP5l<6yudD#l&TIz(F4FNEYaEx3!%P%e5&>7PO zBo6i47FOmzw3g6k_$c*e=W96IM9ZsR4q;T43{LQb4_4^ak5A{#q7UvR7UF(S*}w97 z;dxJbkiCx@>#y70E3udHW$9x*2^_4ND#w#bB{q^1vZC~n5MXwjE|fPFK6XM;VhM!B zcE)k-1fS{;du+whm~CDzU1}t=YQ(5tuf@^DXWs!Gol?Vk0Wz0M_ke#|k5FlK>wlwB ze2TZhCD|sxZR1@Jvm!z@o2+aUpLIf(6XYnt2~`3h5nmwVyYi`xvoKD5m$q_O{utM8 zr3Y=UTynA$=^5X|b>T?68UnkkUSXCdC_73D%5w7VUzN94TCZw`dubDLI0PSXiLfUK z^E_W+)gCv7X&&mga)QY>grdW##Bt)MqjvaAJqDj?Y4Rz*8jbd96BYVV$0G^BG7+Cr z=c9*DhWdl!*`znf7og3w)!e^>#h>Gr{|pNjz`w2$7RutWxQtNk57ft?$~oZTzp>!? zdKQoTKfDu}ZjV%pI3_S^#!n-DzL_E6I`A%-m45Es zv^vP?moJ0X%sB7R+ra|Sl{Qr6kg2o_$L zvja@+pv_E-%W+UOXm#R;1*xsPl%IMoFPT@wybpPGF08m7;8L@y4OH7Z;EFC3iM@ql zH>(bUagJ11rX8hz701ObK)uFcLaJ}Rz;kPn*n z^6vHK_SR9$Lgq?$EPSnqkNhzy(GdV-TCvAkZ%CxwmG~Yri6?~Sq@AP_dmK-)c-B%! zaahA~cT&m8$x%_dNw>TYeep9_W6O0o>)hq{dv`EFIB^O~*z2*U`W2a86>Z>Fehc}9 z?F!(Q8Z#ATvs0}dcH2ziRf{pHfFQ_OpfR@sQt|>5T_PK>>#ovAtvfGbGJcksAJ7c& zGp>8Y&NIzJ-$b9XV+*${2lTuD4%W?^cL&u%BVkDS35q2mFfJMDyjf3KxeAG6V9k}M z*1xvIuAsD^Q8&Qat;3&FG;78^M~|Y(69?@@qEhZJ7Z8T+>z#&DglGJ2mGcuX#Y) z(Q59vhk20jJA7a1S7u?)K84I!S$185`Z9-BOLZRbWLB=oNW6go&mfWhRo!C?NF2Vf z5k+{#Jk`Y^yT<;V*`wdGOTD(J`c5%34H|UJ!abIOJ=QUI9TeD6Zin8 zAaoP}gHmKpSY_}FsxsUL`e7-Um(TB0%qJ1i6NZFzoHuwOh}uoKk6eorlgb_#b?(x# zVBJ9axncrL?&&oYvQ@EHw&bGkJ9X;)#)l@DY+-NiBI}*9C@#uwZzwuIx$G-Ye+QTU z`!Vl7&)C>l|JN$wpdubi{PoK};8F=xQ}RCd{^6KE2Xa5AftvzuB2Kbx7kx5+xL&oH z1;To6jW3`GkGV9*r5|F;J#DBd*Qm>CRmc<-A)tD7lr_!nV>H+oShNdwRyOxq!4NP10;u1JXO}Q&;Om zw@7j{qH4!tIXg?=jN^GFYoDte3_LSc)*M;K1U7%Q$lXF;4ceX*TlGpr;35IbR)Ovo z{bZhWTou`B_H0)QFd>9oD907)V3mp$x`auZXJ}doK!JBvF^8 za{mT;BQs%m+JxHY8V~4u>0r0wIso;h9#`0WL?$XJdpykPvkB^R3%WHc4>gz@i?%ON zzH5J&Rwr^k@TQg2A~-S9`tC!O@uF2=C?-`ra6reo9J4RL9|&1FpB`FyQqe;-&cwf+ zyHP#{lyOCI*Nta93|q3EW!gR|ESnViZG%uTRP)fjKp{FgX9!0~J#44VLa%Kn#}$R( z{F=+dn?v1B$xZyMIH4raP~JVb1jiTDhRUGZNjgE~9&oC^j!_N%+VzBJIMVsNRoBbQ z&6APqw0Y4%9**8egHs%r)C5;=f`k(>tp-aR$GgNB-*3xf5n+J@!4+gnU`*|w<5@h| zO+xUE;;~f}LYaU;O=g-#LI3WGifK(>){tNb;WCU2=1V`MoA>WJeT^x$S`HDjLnRr2 zi-NzSYT%i!;<@0W{KTP6JZ{%(4=1KKqoVnKwnnj#qB)+v{<&zF-P)9mC#v&eq>pIk zDK9VtLrWIEH;@V6Sk|p)!iL%K+706vm>%Cn?aybZ?0x{;?Pc44r;Q3amcHuoH*tka6P~;oA6c=vd9R z1$VF0WOx7Y;E2j$8$nmp_$CZivyPZGam{U_Oy~7S7(c79!-;a&^V?*{j z;w9vMfobcGVB*(pH*6)$7mDm4wr|;9g@F(_Fk)p5F<`os&GoE7sY)f3m&alYPlZEe z#Mohr>pzGWLF=j;pufz=T#6voTUnI_ff)wP{l=9PEaNiwThtW1fsuCMm%o95b2$qJ z*zqvq$Ngd`o;zjpA(+P0QlJ&V0R4Pv_D{|F2% zGCW!B6ff%z%VTxrBhS zm<)ta2gsd@)LMSU{$(61Z`ulSeJnPycn-L8le2jn!b-t+=_y!6f|;2MMGIi@tRk(z zIZP2b6|VIJ2G>RTX)P&_c#ud@`ZX&ZINA%7coLMlxpth?8&6Q#xco=QNq}F7X)p zw6E|2P^Xj;?Ai%<9BksyMQKJW^NEETjS=M=%8KjxP6;n!X2vybxi={-$+b&r!W?|x z69rE_+VneoU^|F5k%?cZmDOc-a5-y;f>Y@X`SK_0;8%FBLvytGu5UEF4PB&3g<28rFCWvsN?z5*zHT@18>*!&i6)oQi!DtS6ukAyW}l&X^y-{Q3m zR6F!7^Sy2ICwrrogU%+}Qw1PL#@3O4&lb*$ke^h2A@merx7!Ht(DK&y*1Gt!7t4O0 zb^1GW{0m_wYiD3+_sIxR{5K;+Nv~jNZ2C#uxKi+c^7Mw3p9GPOjfJ7*A6kpye@LJ| zr1yW`(Eaawelws?$O8ES`Tm_#|4*#aC;!gI{7-(9k?@o5X8KAU7k99jUByS?wPm$?7%N;{mR)s{!YSHs-| zb3*rBPjjc8s@AD4?Oa7FaZ#m)@8yCi&_9Qk>wj-WlGJG z*(RCR%RJ`WBsPfrlST=tDD=0SY7?-($WeRC%~qh7I{Q=?Vp2xYZxp=8@dDU(6*dvm zp`TWpr5JfY;Yh0M_if$<^Omb;O-viDIT^v~uj8$io>2xT>L;zg`LDM;%P%k^jPW|1 z*X~xwP7f{|+`!dsk?6lB!S5!S3@9XehjEq~B93=xL4*ZwB#KVQoFgKOCw(`ZZdw9eO3)HK}=MY?@-ws;60 zf@2*<{o+SDxWNpfNW4F{QZ}&hCB|)-=fcHSw~Y&8H<`n&xA}O(h9HPJSq>C`c{e&> z@EMbCgCp~<#Kq6}`?heDA#9a5&{=)#26EnjgJJEAC0?CdIq$txFVtQxBCOo-RekjX zjug2~tdd*A!IVd7j-W$4FWOgmaxKIx>eYn2x1@6B1w%w`^16V||z%$48yAsASC1tus({geYasMI&{mS&~I+Y|8S`3;-TGsnIYENHWG z-ADrAZ68wSC$7JmWN|qJy-SHm{}Ed?9qJN<{AUaZpmLZ7?X^yDhncB zDWhC?-omD{3Yi_E=w{GbNs+Ncqb|chrn_A-Q6LAtPSf$C77YLf(efgc{UknDVa5c> z5i~TjuvR%w70m*zDLVEqhaM$CeRKj;B3bOVJ3Ju3WQ7xI^NFvl`nsk6c4jqS-$rh%@kWXhw3d(mw*zKgiT1 zaY_=R72&CZ6HrFjMl7Qwm5qz{rC{eE96PAy`OKz*%&}5ssTVWnSj`F>MNjN7qX@XX zc7B{Jox5Zmway-Tth)Y6IA+qA)iA82Ta=En=5ikQ-woRuncmgNU^>l3uuXI`1>+e3 zT-$ZM$KmI$uf@gIEd)GFkH0+_nqX`|sR>lgV&alV zmU$+4o4`J@6-jDrKXGUrx$*vl3>d_EM=-Ww9M~num!m#(!3weqGW4 zF*|xrP@e6LUzXmT?uk$K!l&q=lf325W6#+5$V)KE*fVH@KYRpa%=#LOUsEgmxG(rMeKT&EdqBWbaHPQi9 z%-8{^V*?(N){UfW*5b@2k0~BY+fpew3r36-xBfwFB)$$VE4`zU3&2(8fBzlKK#CtS zhv*V1tl~gSzHSnu-dU0k$^!E=voQI6&TSoC+TNdTlLq!nquZ%5!>@27c8UTSotVZ6czePv>^^IA0ZB(J{V}HFv4XF33u217?ZdOIwM#EQ??}Vm zT2+x4xb2Kmk-of$2rK9$vNd41-sM8lE~_Fr&wMK+Mj+iV+(Ch020U2G(;ZvcM?7nl z4vQF|+J=jDNEnj<3x?flyvWDF)=?#`yMToUsn{{hh_)N_i(cSMJI8>Tg z4^=`B)nDIRxyAcBhcuXV4tIAKiAxi$CJ+n)#uMu!VwSP@W>Bx?S;hqf=~)Dgn)}Qu zSsa>lMI5RI5ns;zcD|k~ z4#=p=HS5#XoTQ!8Xo)`=_})B!&KiA`DBOX+Dx2RniB%*%gBXh1l>bU$5sOI_3ad?$ zu-#%Y7E}#7e=5rlE)y@p(%`SKx@Ci(rv!zl$zDnk;%I`$^4b(e6sDhEI*uHsQH3Wn zo_^AqqU}cQUD?LgHRnl9zDP6Q;ZW$DT;bA#l*I7jZSmdGLh%sIYto(1qpHjE?JZ>~>MTD9OpjcLR>Fz})7IoS z5vICiMi7lEY;r1`-^h2uZn0J}kT4xf(;SO$l(Y`xP>c}}0XhY_*s}}oCP%C#u=Qs9 z(yKEv7E8-5GJd(1-`ys89^R`rAGjy&Gwm?|+PXf=gk%k}@70g1v`=%ffts-Au|bI% zX6Na0fJQ}LOsK_v^BmTNIn=&8aYgP#slgp~PQ@8^+q8_xxI*Bf@UvRa5}l*z<8~gJ z!!f9FVErJHx5>=(*CSl3R#H)HJGhn>`_2~e%3uY@rSobI3i`miue^KkNdYEHrM4Tu zbrUX-Me1W7UyR_V?ShlPU}{iZ;MLoFk#7&vy>_EmF=v%%s4>HF@-971Nu}itQC^%V zs|cO7VaN_1wAA-^=eu~h!f=P=TYq26Gyd+Bo(ZVhm2w|Si=O7&c2V?x725XL4)0A0 zJT>R@7r9(dTUuXz86kLwI@fF?Lrf>ce=8zOm) zVJo2~NQS_Z8HcPu#E*@A?dX!l1^HT-O$nvm{qbtNw(kwFQ-%^jQK>;K!z5ialq@w6 zUdA?(#!@GeTo6jJs3*hyrL$aALq-Q?oiMW~sfD0Lp-Tnc&^3f;f-vAcU$*+ zbUtWo0k*25FJ>_)usS=jL5X31+BDlF8P+d_yAWD^=?OQVkw+4`T@J-un1>XCD#gV3 zVu^iZ;dBY&eXHo6{*nmY{$G32f*cq!{zF?5aUrEdaEk1=JK!a#MwCzs`um>d-_M+hPqXh8vvD1ccQcykjk)gp6J+FQk@dbg(^%6N?e8m}?5*o-j6sDDI=GxSEk?~PMl**}*1sk4|bHF zG?Pvl)3BR>Qe#9;%Uqm1sbtKWY+Qx>++Ng^Yy-I1AFsv zdSSeYm24Fz>mDBA;T#hmo;D}C-vXS*42lzhLZ0VC}dM9)UC@P)a2`SruX&8;SyZD3bA z%y@H?akk}f2iFcMp@_)rx>VyMAIdC9f!}~b2C=w%djFeTn9vs32<@RVdgga%s@`JN zpLX4Kmbt%n+52EYSQjL>$l_O~iPVFCag~Z7sZArD1q?l4n-#DIj6XVBwKHV4sRxu* z0;9$CDe=qNiV3%Y5CuDnGRoTywzl%_0&pz|Nd;oAK7Y5YKQ~h+$~$_|;+`HQ=K5Hq zm&>4XX_ExYcCAeXL%>f!F%*X-zpHzllWu~x7AtO())zap1xN+bZo(o#w1tipYX2mc zKIwuK9mCUpk`~qI>CTC6;G_b0)kEzfOS%UKthk>9r>WwdSE%QknGDO}r;5$ROa1=L zl+-;G!4#~4)>AQn{s0MqV>t#n^z3$F!waMIxeYkpjxHR5+^)2ms{^ZCyXs0Sih0*I z@oy;S5b|<+_`(%^d)aw0bEjE51<`7>7E{)&(xIHcq>O*s*nojpYpShgs&zT)e*Lih z+F`vM{*nmS>G1qoBS`I3t{!no?`f|*RCD~R)PK|Sg}Sm-?&nf%v$^NH&ih*sk0fWN zv!q1ygw)!B<3N-(`QpX!NJ2R>%a<#?uLl{7suhx+nY zO#H$hywL`Sa~{8NcTNS!uHP=8Z5Cc`cHQtgP9p>D2@^smuqtpE% z0~ZN29}J@JY`g9f?smG+tyh3AF~oX28R}sj?V%j&kd9`=0vz(ksm^B{kPDHfaG;}E zK(tyy=&6liG{*B;Ie%jHUHOTPvVWb}9#It&cY}-OCzVGgG3X<>RUEE(P9^NOVQk(I zdR1tqyl5C1ojxm!aG{AXV*3{8qDrNrd?c90#ev0!(BtsS!t-Mk>4fK`6fg%n>)rVf zY449y(UcTQT!;Q6%{q2eWplzfE&&m*1I&4nZU`44+s2BsNG-E69=wnWJ4s0OTb$&c z2>%o&OaPmihLS@9Qe|jWZh+3HhWaTB zxRH=8>;4cw_l+%R;HQlFLE@TNku9yDksY-<&> z`Bi5{dvofC1?i=cj8z7N>8?ZgnP7WJZ5yYll)4UAoS81PBYJ*o-mW3OJ@4T3d)T~F z%?y0#^dM)-RUCHsAuRXl4uX5;M*dA;E(&w#^2~bQTGD5jg&oliR_vfHGlT=j zY?!lwF$Qj2Jg#!-lgx5@l*45cON;S-PUgNw%c#IQONeJ&;smyX93uI;Au`;&k$$51 z0Q6c%d7TrYoo5k@CdyqWQ!o#Z)|S%8a(3aL+1y6Y5{kvqEqo`{ye{|73tUxqed*iL zx-vD&{HrAmBgb`#o?f>g-1kQe1_6Ap4ri@eC)d^wYDxE?9Cgbp))jtJFNiz{qaur| zDO@3rkNJIbskht{)z&`c64-8Bw-u4Ncr5|kNK`OH7zUw0%3#WIX&8F?W52^hAuB)s zWmFdB(s3@7pL0&N@B^~Oq7!cLD*3YCe;a3=nop&6+9B%|tw+*m0K78PW;CM^~l4o#G*K54FN*6~2#nq<%-P zZm5@DgRt3k1FN#GYE>r3}!QIk8XE3~zf?^$8; zrCU901Wdj+xtXzkh8wOBF-3+bJ&_QB^fwCGwrvqES;KQPkll0@F^93Oo^`&$6Wc-i z`Edt8t8F46BYyQ>_pKG>WSZOK1Qgr{AEZZhrMiB5p$u(cD)qVuRqRO`f~@-V396z9 zme~7vE%rrL^?dYj;O9w0@3i?%K<>%+fSD75SdRkKvUIn(pIViB!;8LDj!{Xa!=7waz;h` zq!~rUQ7vdR(aW%vXi)rN^i8+8obZTpHkO}p2Fz>OgecJGyA_63VBj~DD_f0RC2NqX zQnsD|#y#;6q_*XqFaRm{La=fC3SMcv;r7?Z4#z6THSF4h%s>Lo6+_Qv92Jmdgo8@W zg{%SU1?LL=$HSIOvat>*>Iti(hIgl_RwK(z*qTmIxh3?{giM5!B=H^A$fX9J?hf{0~{}YGX+3?OGzmVeKH( zK2{W&=Q$l5AqqO+WfS7Bj4KfOfsO6CYxjoR?Tm3dg}Tp?)%t_y5OoA2Ry1CEht{kt zs#)|G$Iln{(y$o39m=@S3GH_Ri(=fd>LfCC8s(+CJyJtb+}f+-(ld(5eE!LMZqF}h z?=wOrs%LFkA;`P7*n!G5aGjQeMSE&espFxOLO#3Dso!+{LI>9)20XoTgmn55g&0hU zkSKHfrxM{4>cb`S*9TrZU8JB~;QVTDNgzyJx>>?O*u&6@cx-rM?hHo4YTFxcqnr$e zp#9NgwpVort?m`imN=R$NLTLHH5G~5GQO=SF2!$=4C6_l$CnI?DFH2af^GSlG(RSTMFO9}#T0jsQ$@E|`1v2KN{f&+B{c5#B?cIv4@+ z%~O~KQDg0oIHQlJVdn)p1S+O3mpn)N6i_Loi3}qwv**hG9JHil_}9)Xl|j?bf9&;QJLs!8rwM>db@1cq?GE zTfO%5xxZ&IF|0`*8QAsV6GuU-+1+@;8z*VVd+R+%E)dX zYFI?&;g|h|qE%+4l&MIntgJbIjJ&AVQI${sb`03UbXccGx1>_c@ z1w18{fH+J(6-#{piA=aOEF;WzsfLYso+G2leSougn2 zFfjNTHYSP-`roQ04Y`A``MO=;@+BI;C1Q|^dfm;a^t*cldAsICI2gx*JXoPD>gAFK zy{Pxt=%i-!d-ile6D5|ZHBur}Fjce-qsO}yB{gH=VPYmZ@aTpUwqyKWt1srq2?jRG zsWR4=0j6Hp-|6RGtp-|2kCsQV!$<6Re{a|xik+ZYxIa&v9+2zFc2rkbii|(+yJx94 zoV5V#kI{vY4d0WRyw$rty0~&gT(@Ko1Vm4!6zyV;zu6%Lpuwjn6%Ip88Q4W?_Gk*q zzvbvJg)(_^Ft9M}xQj?T7#a?0B$!sJju8h+ELySF+8=gkvF4f?EMBtJqh;<3rx|D$ zXmzVl=R-1ds_^gipt!zWve<%e4wRo7sJP^H%11l0mEGn=rxlI!vy#`~yJP;?08t#Y z)ol{JW=QYpDPlC}VbLoYC=3o4t@>)6Q7L~Nz}BtJkq?w7pe3&bQ3_pwFa>g{d0|r+ z2w9d_0bO)C(SFi(Do6IXbPlQhfX~052EDtyjDAu)h&zmA}~la<79!2uMry%IpPyLW96lT`jET`O~4MP8juk2$#%!4JBN+pRZed!lu1 z!SaWrNvUmlM{JjC>h3kwhr<}kUf$3XZs3@sFfHfB+?0gw>{%A*;dcV?y4wZ;=1m?D(uN(#=*iRFT@Fh z<)yZ2@^Vb>+?KI_HCzH~mFwEmasZMs<~oIm+gPizYCB`H+{}uT0zD;|UZ|M#_)}JX z`G6}N3HCp6Px$29NhWJ8qkkNXpNuf#woN}b4M-4qlC9e{nw|wd^EX~(ejt>cT>8DM zyLc(0D6-vlHFS)d(-)*oT5#tSKh6R1dIxC5$RVx`)$LBZjJT8}#W@H~x^zGOeo$3T<+Yj8mC<$B-f93u4Yc7T|O^* zgKt%XlnFtdo4OnSLltCk@M~lpQwRFkaKkc(BG74Y1_}zr5UN!6TDJ6|Pk2vOw`%89 zGj=ptz@P}tRm6f7+P*9Q)_(h!_WNNe{?4e`X|d5=cV6wHHRbo~70BeFN`Klh|KZz% zZBjmM;+OB<*RSsl^C&iF5ry{@GM?^N7#N+;%kz^L+?}`=W+s~L$4Bcn3t;Kj(C}YT zkf$nTRV!hWMt8vjR53YZ7}Unv2|?5|Njd^_#UZn}DQ{uEP&;7eF1)FtLKqDgBCt~AW9)0_zvdWvmX_{ ziv*A0Qi?24>i?vaQDp6j)#Zh^;gNNf8g%Kv8L>y;9!SZE@$5L31 zPK-~5q;@NAzie}DnpuB;k$-!5@Zr1=SVYT{yw;GJgf6>Dy&DfQ(yjBV)2-9_71!eD zlSxTK1+%wQQn7^B^aExm9p1K4FYkBtvVEjiEDDepZNBgT%GPpYen)ty!yXB!%@K_R zy68|B6H^ap6QszT2=?6%vjdRn6s!4k%x%$JpYdJhl#Z{_%UR#Z@+S9W5aW+hPK!AQ z1EFzXrfrf@=c;#?da-rhPOHsS7I^1Xwd5;f6Z4OGD7a0E%v$GaJooN98h^KA%)&a6 zTpwtteIAY7P0ZZQQzML9r`6^>KM97f6nnIj5l#MRc)g>Q=HU?(O&%byR%yUZtA&o;ZcT~v|8Qulyt9bj^8dda$558R`4 z+l*mFNqr8z3dUpacqta5X&L!2PlaFjMgj-b;Ws4JpfbK5nCD=yYb~k?>u}XB&{^Fo zC|Og0mWRez%a?VWq`aacYL zSYe*Gk5IN2YE6$_-httwJ;$a>(cSEgmiXRSE!Ib-L4mF_{}AY?^qe4jqJrR9%lE{$IuC-n?-)4g`5yhI3+!vy z^BY3xQXYSMy|kRw7R&)R7eemxrvg~$4s0N*XmO|r^n6KNh&9dt`hFV!( zNrsAfxguUse|_Pwf!a(Vx|93)B%Ru7p!MX(hx@zzC)w0?n7PZf>Ef!nZoOFfGOo7g zk=PY|ujet?!?qzTdYAWAQzXf8xY=MhH1iAfRa)f)N+Gz z2zgz37KwGTW{F-r7l^*WrQ<0-5^v;8b8(@h`Hm}+PGTm$D;);iq*c**#o$F9?H0ck z#iL{EVj&4klwGGF+n%9cWFgSumPACp0Hmhbd6s(2o&`O?J(|f+9dF(5l9)0{$HX8< zT=I^%s|=O2_Hp^w`vA*Ao_Go9nT#pv7zQB9h5uWx49+tKt!c0kL5tTa?Ml3wLcBA0s9_7JpbGIGIqE z6n`cr1JS6#CYGTDrNJ54Ehu(~Fb%J5U~?S5wYC!HRI7MRoN@ z^+8ri@Bgp8GmnP4`yY6lM3#g$+oY0h%xX4ULY9#1Sz?UAFpOnnD>1$+x|UZh6KKK_)=E8>6n_1v znv!!_BT`ta#qw@tZg`%WMw|-EscpNaq@&+Af-4?YEu3t0ihq+~diP2*UsnAN^A9ue zOi2$Pb|RVgaz@-uvDzBD?P^Crh{ERC{mf2Vu5R==Uza#9P3s#RR9bwv_1-AoO@3K| zK7{7};m(8CEc0Pco*Y1YeUZ&SNI|Qe3A659)P~=PDpB7X_mg0udvi2)R84Z4L)NN^ zb#a7v%`Y3)7Z#vC{XE0CxXPyz+VqZMb>#W&95S|fSMTMac&p(o^*E6jr=KI_7`<~H zu*0_b#@-xX1ex=kR8$KEo3tEcta%DG3f^sVR!P7!Ii=meH0+s$-Er77_2M?xL1ahA zHZB9r3Ta!|!)>PnG2g@^RC$zQuURy;ii;$P__E)Id6vnFHJI5qa1M{Vq`rT({Zr9n zuZ0Rel~DGH0W|VznZ+on)vD) zPc2rb;~gy-Et|dKtgS?bvcC8HrByhxePj1X;z+o{Do$^t?;Nuc;irL!>(t_^0yn+E@GLo zj|i(AdT;Em%ThjVFNM<(x~odsK(yN>piXuD6V4Nepl zWR%JpRpsiB9a2{GL!)-~9hI#gZDdOWCGB^XB@fyms_QB>GH=vR1gT1~556CYm2?gq zP^IL=b?lzf5#SWd|5^4KBBZaXVq%X)9g5Z07cpWwDJ&gDsO2S<9Z|Gc}7IZN*O8cO%L)>GMcLk`md(yp5tE-6s6*<_R7Y>ZMo?07+cZ2RYd z0;t|yr98Gk?Qsrdi*H}zeB(3mq<|j3g7hBcuu5c`^5&o zzVIhDZ0Z;aBXJ|ia8l_o7dc9ywkE#`CvZfHm6{8~F z@J~&nq%WH z(veIu5KVhO*T&z>)B3pWroUU>ypjC8f~Zhad77U*F|u@llPg=;g$q)vF~YKJbQ) zYlV8Efk&&@ro`%$eE)hs$GQLT`J)s+AxATmcu>u@`+;EI@bfDDLFHU7{4RR4mYWfM z-vC;}j9=lI{8!N3wRVI{_(QY2_bcS`uM{e7x44FN#+vEiWH)M%4q10T4)yn}K3UCO z%{2?JN-4Gfc-~S_;HraP>BMnb5#Rp72K>(P`>eUU#&%v~nJQBpN$&ZwsWAU*Y2aHH zjcPYu1@DWp%6tdD&WQUm9U4)(lQNg{!B2L(hRddDf|R6=57#G|+UQ!#;0WqLvVm+N zc2D>maGvJK&3mo#20lc!A3|H^^?n)-CnW0U>hrU|uq0oM*j-5)+w9CyT^+@7$v@s%5=WDj)l&`hndiyPt> zD}CFTRoxB7+$BnEMg5rv zGqf(nZoKov#E}^`^qB?{%_&LBIoSy(#&YrAYq@Tc&Q|y#J*5TyB&z1=sq@n#QbEXF z_5$;lZemAo`qYo!@)<3jzE#3Cy8xDxNJx{fZ%heS90UdG74J*vYMRw}-dYwC{kZ1J zSvkcC5b~OP1%rr>9L55_E(j;dHs4Y6Av#uZu;b` z#jUy$xwz5llnFVLag!HcP7TS9yWKKT$Y!3?4vxRzxdRz8wbQYm0vh5ve9N>?HblA$`G}3&e#SQvNKQU9f(S-dk-666N`C>pzk1JuN=oI>9l^Gr)P{?7mOj1ttq3_3U$Z_YY~dHT0V= zTzh!_eBzE;m-6(qFLp`AI~RnGDEO5z(ZXwKpBqn3yc#`v{zmN)xdFo1+uItitGv>M z6SDW(9(#MTOk3WltjJ#BW5((J$|vzNodUGhn=y3_ZpIXG3p8n8*qzBnvX@ZX_}j~K zA$3OZune;?g!ntPs;ZJVHEw}F`TshuZiEm^c2asP)eJuU`kh8^o8IT2+&}Wtw>#vP z8QC52-tFbX?J`q*E6{@$#M(b?`9boq>%H{!kG4CDc_PaHdMI>P^Q4|lhJwa`Jr{c{ zM}+C@R`&FrKkAc#RmziqQdk$4LWqYw`Wy$=4*Jsi6TwX;o3GFD*tOZ8yX9^iS}Eu@z4z6tJr7yMYTkNtY+jMswTJ=^e?`LtcJa=nAS#l5QdpM~k$ zZSRoAPu0|^ei)4l(>TYXJ$T@wolP3Iyc9NU@|^C^^A*iZj~ld(o{zlTfnMm+ot1dW z^hNB7yWmy@mRlLP*MbFCs-xPX#L(9p9`7413TAyJk-p>810BH=fxDQyvvgDP?j){?X!FSI;%jy!fnu>#%%0|mY_lOC+*!z)kv-Qf*N7@{1 z_x(5R=w`GHj}6VnY#(~@fPO@(-iMc?dXY5s#;m$a2m&{aMHNGABMQV}HckdFvdn+f zjxs;Xe6P-FK7cmA>)dEhW2m~y^k>2Dltm$~%Jav42E}=GVR7oont3fTmL*AN12x|s z-#hs@d~Q_C`6&7%%7n!{Xo0L-bfhPyl~?(PSeS5Hl6$1Q=1_=D{ug!g$#LqDs^RjO&t+Io4;+tdkJy1+(>v?BK`}}mE zbN128o{{p+Y8HtT&fdjMZ=X6k{utjiS!YTU^>~*oTbf>c3gU2|Vn=CtxyjM5z5YoM zuY{b6L@@vH&ER2y2j(wBrh;lZO9~G0c_-gN7Y_QCmbR7e&w1X{nabxbR4#ZgQHoXf z!qBr51>rb>4MsZtjmMuQ?sE3od8b8}W|B0KEi`q^uMtl=wm92pRxz>|b)9Mg@=j~~ z_zk633pV2;zueDF7-$mKk$P2$<{TEbys`h~g{)e(PNp)p>zz*?v|btAYN9CdeDhZg zsPBo2_D$BzbLKS7x`K`K4l3o|uW!H_+Dk^h_tbQcG*Ko7XU2KQ?-vE1b=u$^8B5_N zZ=IUf`)aRgAG&orEtclxZ0AYFO-nMTXpcm=i>?;tcJW=(eZY2 zuQyCz^zbj|l;32Sde^!rG(0f;yT1YI)v3vx{xn@@Y0S2o#oQU2i|)=@Idl7ZUiL~@ zw(MDmoVix@j3>JNh^c?xkr~`mMN(*fMO0iQR;8gS4dZrGPm&a+q<4__FB@H(GXn?p znd~AS#qL53x_c*7i`Dmkr`;O9+pXEIZkuVx8|gLt=%`Wb(3QM1!WQ$}EtRJ)HbaMm_xDq^hWXqWcPEtn-H%kksu(<34F z=Ep+J_aMmym7mX;nc6B3bPA$_>U@mVTMNBCFLUlGkh7VSl(Pt#`)=1Jt4Z>q+3&3? zv@?(nIABs>;S={N*=bfKnxmDP*5>n_tE(qdoW@xSo3gbvEE*1)HY*!GYEXLSozD}z z&jTMd>{D(2qJ+s~18;oa%0N@pus`uHpT+RVN83=9l{#WOK-;@xTB#$66UQ}?FI z&Zy{VbL3`L8G9x_Kj8Hu26|$~8ti31`HlJG)Si6#M<{Y31pi)=(@Q)$Kw2~a_b+=rNl`8i2wTI^nXtFDeicJS`YJU&h?RrSQ?Gwu=q(h=q z=_{^e=nQ+VgW1eurDl~g-R3pJ%_=bspRVLm{ZclRY~^Pv-k>e7y75}dg|phdsiiDt zhkk7Cc*f*B_$6JpSG=Vo^odG{Mv;W>skn+gn+OMC184pAa%|wJlmNE?rU6TJ=`#ax|3TpXS1z{gUS`$pt&Sl zh{T?U1qaaIL}eU%nXJO2vQn}RsIeM1`=`!asF>3cyMl9288i=(NYveQ1g~gmbBxt7 zs4pTSqWPiKwk?}L**rWdcXHJ5tv0Wpe2vfb7ps>h_$zr-Y-J+Guzv;ld8S{8$lHDd zz+N=Tlwp2%d}|F@Op(qW1Q>__j1;1zt_%C(&@PmkdpNn|h4W#A!biFhcs^ax;h z0!bP0M@ED;-jVowLLwb$s0Sc1sRTQSHpSHuPiAB=T2c=Qg+kN;%p{4R=wwT#(-`%r zL`Opq3bTY|r01qH7F|isREjIac-bmx1aKgG1#kAq4|)~BedD{JAMf8iP-%0_@A0NvJ?4}vj3m%mVsKvsGJI=T_QsxQRI6k!TSqs?LH zrGHr903ApgAkYG+M>ujRgaU}9OCc;H5dvk3MgpnONDu}Hrhh^fpO6!k6G%6T5Su~m;RFmR4V>BwL@~EV4B2A{)g)2_G2e8xN~=-M?ZXSFZ4X=b-?Vv@;qj?>_$H+`<#_w4nJBALmfLU_ z!eUSH^M{2BRG|l9VVU1Nqo3b@eDao3_72-2-@8ftdEpmX)sz~-{lwERoKCb&4>Hu* zY;gUcSG+6<#Bx1LJtozm`OsiIwfLf>G9>==!BRW#>yycYDo%;Gh!=@ltu*4r#8@0b zHa4+w6;FE;ouL>}el`wPW`F?aN3r^B7pAZqB;-Kl&c7SP!?ht%B*gRJ*5bem39md3|RBQjmmZ_K#%^z?N(2o|0^ zJF4R`CV&5g*_(&xqR_p^rc2uK8z z93#29QRzK|-Yqrpt6>Hkbp=$rrsJ=HHzQoG>@o^h zpF|}SMfL26L@G>djp#K8+m%h1gd8JL%^`XaRf;}kO~N&2d=-IC!_ZwDK+FPUZAN&d zxFxHWiZcYx{o+9Y`_-E0Ms%{HtSfoVd0)V&r6G2`kR_n;(onP{P}vpl0URy{8Ip(| zFvMCr)|~cTV}~vXfkgu2H_+peFksXGh`awVZ0(B%gkbby2*WV=dOt21#?Wcm$OWydMpOz}`H#)8LIz!g) zbdrW5K+-4_2u&YRvGCvMvDK%<=Ng*ZQlo`Ij+3n2mRg(nDwf!7O=|<1 z)UuY#XcFL@Hs;s+$XH8rDccJFd36w#Rq%Ai6C8jkf)#M=+(}M&w4_`ZM6#9>Hj>tY zYB?(r?MQ0gu0%a=ZGD2b0|9F-tRT-S>xuJpbOwIRj0br-lAYXeo^rx?`e}6>5T-{% zgh7lXR0la>#xZt~v6c=<&^IV)2K62%Ebmy5TexKrhXh1UVUmo0O2{#B5Zn-s%JDFVe2 z;t9+PU{X-XFUfS_fLCw;L7Qabr3^r%<>62m0t^F8g6l)!I3yGYgMonn6eFLlZ z-J(Dk;MYUNmdsk4VOf?egzn}wZfDf#|F1ftT131}kB#u_YbgG7UoCdw5a1{q!iwBAdH>gbvL^g;lC!%jnbA3{ z2@v8ENWu+hxv=$KvL@hc=+khjJRZPJkO+7x&^aK^);6+`)kkZr2O_ETcjQV%0(H4k zor+}Y`q-5RWD>pi;>dU>TRCA*ur<*J?@p!)%UhFxnsK8L-7E;s?iN%J5_ze;kV)(1 zEXA%D&rt90n#cm$5$Iir;`%oU^k%3>bXgy}s-L{37v9<3iE_q_N~K!iU0o?|AW_Xz ziaG|`Ck%n+P0#*&t=0==X!SP@{%3svsFYuoyKYDV9sm`KSYNR~Bn|-GTe}m8u50@* zz`O_PxLc7)ZgxahS$a*cCi~acxMT+~6a()8$gdZ{KRilr4*&DdY6JYAi(VD@Um>f$ z_=C`Y?)n2KttR=;U8}zMgV2BO`U5AeCi%}@tG@Vy(0}gw11GH}`8Rj5t}Z2kT^%`L z4`8AAn+={d%VI@$svX5u^w*SY&78~Z*QCo#Oboac2$;$N(^2|LMpPMC9l{X6o&X#Q zETI_-s>4v|;pJ3-yx*@;%vKgDbb-JU?cZgsOqkXRTQ^}6gDmYF{B!EMW=CWBIw=rx z<=!;>5E#Ki>rX`3HoO>4vj$pI|D0m|F|y;`9HfD T3)ogzdm9!E24J?A@5A~(;3s_d diff --git a/twil_description/xacro/twil.urdf.xacro b/twil_description/xacro/twil.urdf.xacro index ebc8381..bd22a0b 100644 --- a/twil_description/xacro/twil.urdf.xacro +++ b/twil_description/xacro/twil.urdf.xacro @@ -98,13 +98,6 @@ /twil - - - - - - - 0.001 diff --git a/twil_ident/launch/ident.launch b/twil_ident/launch/ident.launch index 002625c..672ea74 100644 --- a/twil_ident/launch/ident.launch +++ b/twil_ident/launch/ident.launch @@ -1,17 +1,20 @@ - - + + - + - - + + diff --git a/twil_ident/src/ident.cpp b/twil_ident/src/ident.cpp index 028497e..82d9d61 100644 --- a/twil_ident/src/ident.cpp +++ b/twil_ident/src/ident.cpp @@ -47,7 +47,6 @@ Prbs::operator int(void) return sh[index]; } - class Ident { public: @@ -72,7 +71,6 @@ class Ident Eigen::MatrixXd P2; std::vector prbs; - int iter; ros::Time lastTime; @@ -80,7 +78,6 @@ class Ident void resetCovariance(void); }; - Ident::Ident(ros::NodeHandle node): nJoints(2),u(nJoints),thetaEst1(nJoints),thetaEst2(nJoints),P1(nJoints,nJoints),P2(nJoints,nJoints),prbs(nJoints) { @@ -110,7 +107,6 @@ void Ident::resetCovariance(void) P1*=1; P2.setIdentity(); P2*=1; - iter=0; } void Ident::jointStatesCB(const sensor_msgs::JointState::ConstPtr &jointStates) @@ -160,8 +156,6 @@ void Ident::jointStatesCB(const sensor_msgs::JointState::ConstPtr &jointStates) dynParam.data.push_back(P2(i,i)); } dynParamPublisher.publish(dynParam); - -// if(iter++ > 2048) resetCovariance(); } void Ident::setCommand(void) -- 2.12.0