From b911e032a9db4ce5a4bcc0d24d1870cf49c7888e Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Wed, 1 Jul 2015 22:38:42 +0200 Subject: [PATCH 01/19] Initial work in the update of the lwr_hw package --- lwr_description/model/kuka_lwr.gazebo.xacro | 2 - .../model/kuka_lwr.transmission.xacro | 101 +--- lwr_hw/CMakeLists.txt | 72 +-- lwr_hw/config/joint_names.yaml | 8 - lwr_hw/include/lwr_hw/lwr_hw.h | 117 ++++- lwr_hw/include/lwr_hw/lwr_hw_real.h | 46 -- lwr_hw/include/lwr_hw/lwr_hw_real.hpp | 168 +++++++ lwr_hw/include/lwr_hw/lwr_hw_sim.h | 56 --- lwr_hw/include/lwr_hw/lwr_hw_sim.hpp | 120 +++++ lwr_hw/include/lwr_hw/lwr_hw_sim_plugin.h | 91 ---- lwr_hw/launch/lwr_hw.launch | 28 +- lwr_hw/lwr_hw_sim_plugins.xml | 11 - lwr_hw/package.xml | 3 +- lwr_hw/src/default_lwr_hw_sim.cpp | 322 ------------- lwr_hw/src/lwr_hw.cpp | 445 ++++++++++++++---- lwr_hw/src/lwr_hw_real.cpp | 266 ----------- lwr_hw/src/lwr_hw_real_node.cpp | 46 +- lwr_hw/src/lwr_hw_sim_plugin.cpp | 344 ++++++-------- .../launch/single_lwr.launch | 5 +- .../single_lwr_robot/config/joint_names.yaml | 8 - .../single_lwr_robot/config/lwr_hw.yaml | 3 + 21 files changed, 953 insertions(+), 1309 deletions(-) delete mode 100644 lwr_hw/config/joint_names.yaml delete mode 100644 lwr_hw/include/lwr_hw/lwr_hw_real.h create mode 100644 lwr_hw/include/lwr_hw/lwr_hw_real.hpp delete mode 100644 lwr_hw/include/lwr_hw/lwr_hw_sim.h create mode 100644 lwr_hw/include/lwr_hw/lwr_hw_sim.hpp delete mode 100644 lwr_hw/include/lwr_hw/lwr_hw_sim_plugin.h delete mode 100644 lwr_hw/lwr_hw_sim_plugins.xml delete mode 100644 lwr_hw/src/default_lwr_hw_sim.cpp delete mode 100644 lwr_hw/src/lwr_hw_real.cpp delete mode 100644 single_lwr_example/single_lwr_robot/config/joint_names.yaml create mode 100644 single_lwr_example/single_lwr_robot/config/lwr_hw.yaml diff --git a/lwr_description/model/kuka_lwr.gazebo.xacro b/lwr_description/model/kuka_lwr.gazebo.xacro index d92a178..07dba79 100644 --- a/lwr_description/model/kuka_lwr.gazebo.xacro +++ b/lwr_description/model/kuka_lwr.gazebo.xacro @@ -6,8 +6,6 @@ ${name} - - lwr_hw/DefaultLWRHWsim diff --git a/lwr_description/model/kuka_lwr.transmission.xacro b/lwr_description/model/kuka_lwr.transmission.xacro index e33e824..4ea70d4 100644 --- a/lwr_description/model/kuka_lwr.transmission.xacro +++ b/lwr_description/model/kuka_lwr.transmission.xacro @@ -2,13 +2,17 @@ + + + ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 @@ -19,7 +23,8 @@ ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 @@ -30,7 +35,8 @@ ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 @@ -41,7 +47,8 @@ ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 @@ -52,7 +59,8 @@ ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 @@ -63,7 +71,8 @@ ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 @@ -74,90 +83,14 @@ ${name} transmission_interface/SimpleTransmission - PositionJointInterface + ${Interface10} + ${Interface30} 1 - - \ No newline at end of file diff --git a/lwr_hw/CMakeLists.txt b/lwr_hw/CMakeLists.txt index 3b115b4..13a50bc 100644 --- a/lwr_hw/CMakeLists.txt +++ b/lwr_hw/CMakeLists.txt @@ -23,7 +23,7 @@ find_package(catkin REQUIRED COMPONENTS # Depend on system install of Gazebo find_package(gazebo REQUIRED) -add_definitions (-fpermissive) +add_definitions (-fpermissive -std=c++11) catkin_package( CATKIN_DEPENDS @@ -31,7 +31,7 @@ catkin_package( controller_manager pluginlib kdl_parser -# INCLUDE_DIRS include + INCLUDE_DIRS include DEPENDS gazebo ) @@ -46,74 +46,44 @@ include_directories(include ) link_directories(${GAZEBO_LIBRARY_DIRS}) -## LWR HW BASE CLASS -add_library(lwr_hw +## LWR HW BASE CLASS TO RULE'EM ALL +add_library(${PROJECT_NAME} src/lwr_hw.cpp ) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} +) ## REAL -## lwr hw real library +## FRI library add_library(friremote src/fri/friremote.cpp src//fri/friudp.cpp ) -add_library(lwr_hw_real - src/lwr_hw_real.cpp -) -add_dependencies(lwr_hw_real - lwr_hw - friremote +## lwr hw real node +add_executable(lwr_hw_node src/lwr_hw_real_node.cpp + include/${PROJECT_NAME}/lwr_hw_real.hpp ) -target_link_libraries(lwr_hw_real - lwr_hw +add_dependencies(lwr_hw_node friremote - ${catkin_LIBRARIES} -) - -## lwr hw real node -add_executable(lwr_hw_node - src/lwr_hw_real_node.cpp + ${PROJECT_NAME} ) target_link_libraries(lwr_hw_node - lwr_hw_real + friremote + ${PROJECT_NAME} ${catkin_LIBRARIES} ) ## SIMULATION - -## lwr hw sim base class -# add_library(lwr_hw_sim -# src/lwr_hw_sim.cpp -#) - -## lwr hw sim default behavior -add_library(default_lwr_hw_sim - src/default_lwr_hw_sim.cpp -) -# add_dependencies(default_lwr_hw_sim -# lwr_hw_sim -#) -target_link_libraries(default_lwr_hw_sim -# lwr_hw_sim - lwr_hw # this is needed because there is no lwr_hw_sim library - ${catkin_LIBRARIES} - ${GAZEBO_LIBRARIES} -) - # lwr hw sim gazebo plugin -add_library(lwr_hw_sim_plugin - src/lwr_hw_sim_plugin.cpp +add_library(lwr_hw_sim_plugin src/lwr_hw_sim_plugin.cpp + include/${PROJECT_NAME}/lwr_hw_sim.hpp +) +add_dependencies(lwr_hw_sim_plugin + ${PROJECT_NAME} ) target_link_libraries(lwr_hw_sim_plugin + ${PROJECT_NAME} ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES} ) - -## Install -install(TARGETS default_lwr_hw_sim - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ) - -install(FILES lwr_hw_sim_plugins.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) \ No newline at end of file diff --git a/lwr_hw/config/joint_names.yaml b/lwr_hw/config/joint_names.yaml deleted file mode 100644 index 213369d..0000000 --- a/lwr_hw/config/joint_names.yaml +++ /dev/null @@ -1,8 +0,0 @@ -joints: - - lwr_0_joint - - lwr_1_joint - - lwr_2_joint - - lwr_3_joint - - lwr_4_joint - - lwr_5_joint - - lwr_6_joint \ No newline at end of file diff --git a/lwr_hw/include/lwr_hw/lwr_hw.h b/lwr_hw/include/lwr_hw/lwr_hw.h index a839724..06aaab1 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw.h +++ b/lwr_hw/include/lwr_hw/lwr_hw.h @@ -1,46 +1,90 @@ #ifndef LWR_HW__LWR_HW_H #define LWR_HW__LWR_HW_H +// boost +#include + // ROS headers -#include #include +#include + +// ROS controls #include #include #include +#include +#include #include #include #include #include #include -#include + +// KDL +#include +#include +#include +#include //this to compute the gravity verctor +#include namespace lwr_hw { class LWRHW : public hardware_interface::RobotHW { -protected: +public: + + virtual ~LWRHW() {} + + void create(); + + // control strategies + // position strategy 10 -> triggered with PoitionJointInterface + // cartesian impedance -> strategy 20 (not implemented) + // impedance strategy 30 -> triggered with EffortJointInterface + // gravity compensation mode -> (not implemented, achieved with low stiffness) + enum ControlStrategy {JOINT_POSITION, CARTESIAN_IMPEDANCE, JOINT_IMPEDANCE, GRAVITY_COMPENSATION}; + + // This functions must be implemented depending on the outlet (Real FRI/FRIL, Gazebo, etc.) + virtual bool init(); + virtual void read(ros::Time time, ros::Duration period); + virtual void write(ros::Time time, ros::Duration period); + + // Before write, you can use this function to enforce limits for all values + void enforceLimits(ros::Duration period); + + // Set all members to default values + void reset(); + + // get/set control method + bool setControlStrategy( ControlStrategy current_strategy){current_strategy_ = current_strategy;}; // CHECK CONFLICT + ControlStrategy getControlStrategy(){ return current_strategy_;}; + + // Strings + std::string robot_namespace_; + std::string robot_description_; - // Parameters + // Model urdf::Model urdf_model_; - // hardware interfaces + // Hardware interfaces hardware_interface::JointStateInterface state_interface_; hardware_interface::EffortJointInterface effort_interface_; hardware_interface::PositionJointInterface position_interface_; - // recalls that commands sent to this interface from outside are overwritten by our fake velocity command, and do nothing to the robot - hardware_interface::VelocityJointInterface velocity_interface_; + ControlStrategy current_strategy_; // joint limits interfaces - joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_; - joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_; + joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_; + joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_; joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_; joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_; - joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_; - joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_; - joint_limits_interface::PositionJointSaturationInterface sj_sat_interface_; - joint_limits_interface::PositionJointSoftLimitsInterface sj_limits_interface_; + joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_; + joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_; + joint_limits_interface::PositionJointSaturationInterface sj_sat_interface_; + joint_limits_interface::PositionJointSoftLimitsInterface sj_limits_interface_; + joint_limits_interface::PositionJointSaturationInterface dj_sat_interface_; + joint_limits_interface::PositionJointSoftLimitsInterface dj_limits_interface_; // configuration int n_joints_; @@ -52,7 +96,9 @@ class LWRHW : public hardware_interface::RobotHW joint_upper_limits_, joint_effort_limits_ , joint_lower_limits_stiffness_, - joint_upper_limits_stiffness_; + joint_upper_limits_stiffness_, + joint_lower_limits_damping_, + joint_upper_limits_damping_; // state and commands std::vector @@ -61,6 +107,7 @@ class LWRHW : public hardware_interface::RobotHW joint_velocity_, joint_effort_, joint_stiffness_, + joint_damping_, joint_position_command_, joint_velocity_command_, joint_stiffness_command_, @@ -74,17 +121,39 @@ class LWRHW : public hardware_interface::RobotHW // computing a fake velocity command using the received position command and // the current position, without smoothing. - void init(int n_joints); - void reset(); + // Transmissions in this plugin's scope + std::vector transmissions_; + + // KDL stuff to compute ik, gravity term, etc. + KDL::Chain lwr_chain_; + boost::scoped_ptr f_dyn_solver_; + KDL::JntArray joint_position_kdl_, gravity_effort_; + KDL::Vector gravity_; + + // Get the URDF XML from the parameter server + std::string getURDF(std::string param_name) const; + + // Get Transmissions from the URDF + bool parseTransmissionsFromURDF(const std::string& urdf_string); + + // Register all interfaces using + void registerInterfaces(const urdf::Model *const urdf_model, + std::vector transmissions); + + // Initialize all KDL members + bool initKDLdescription(const urdf::Model *const urdf_model); + + // Helper function to register limit interfaces void registerJointLimits(const std::string& joint_name, - const hardware_interface::JointHandle& joint_handle_effort, - const hardware_interface::JointHandle& joint_handle_position, - const hardware_interface::JointHandle& joint_handle_velocity, - const hardware_interface::JointHandle& joint_handle_stiffness, - const urdf::Model *const urdf_model, - double *const lower_limit, double *const upper_limit, - double *const lower_limit_stiffness, double *const upper_limit_stiffness, - double *const effort_limit); + const hardware_interface::JointHandle& joint_handle_effort, + const hardware_interface::JointHandle& joint_handle_position, + const hardware_interface::JointHandle& joint_handle_velocity, + const hardware_interface::JointHandle& joint_handle_stiffness, + const urdf::Model *const urdf_model, + double *const lower_limit, double *const upper_limit, + double *const lower_limit_stiffness, double *const upper_limit_stiffness, + double *const effort_limit); + }; // class } // namespace diff --git a/lwr_hw/include/lwr_hw/lwr_hw_real.h b/lwr_hw/include/lwr_hw/lwr_hw_real.h deleted file mode 100644 index be1ad32..0000000 --- a/lwr_hw/include/lwr_hw/lwr_hw_real.h +++ /dev/null @@ -1,46 +0,0 @@ -#ifndef LWR_HW__LWR_HW_REAL_H -#define LWR_HW__LWR_HW_REAL_H - -// lwr hw definition -#include "lwr_hw/lwr_hw.h" - -// fri remote -#include -#include -#include -#include -#include "fri/friudp.h" -#include "fri/friremote.h" - -namespace lwr_hw -{ - class LWRHWreal : public lwr_hw::LWRHW - { - public: - LWRHWreal(ros::NodeHandle nh); - bool start(); - bool read(ros::Time time, ros::Duration period); - void write(ros::Time time, ros::Duration period); - void stop(); - void set_mode(); - - // low-level interface - boost::shared_ptr device_; - - // FRI values - FRI_QUALITY lastQuality_; - FRI_CTRL lastCtrlScheme_; - - private: - - // Node handle - ros::NodeHandle nh_; - - // Parameters - int port_; - std::string hintToRemoteHost_; - }; - -} - -#endif \ No newline at end of file diff --git a/lwr_hw/include/lwr_hw/lwr_hw_real.hpp b/lwr_hw/include/lwr_hw/lwr_hw_real.hpp new file mode 100644 index 0000000..9f4963c --- /dev/null +++ b/lwr_hw/include/lwr_hw/lwr_hw_real.hpp @@ -0,0 +1,168 @@ +#ifndef LWR_HW__LWR_HW_REAL_H +#define LWR_HW__LWR_HW_REAL_H + +// lwr hw definition +#include "lwr_hw/lwr_hw.h" + +// FRI remote hooks +#include +#include +#include +#include +#include "fri/friudp.h" +#include "fri/friremote.h" + +namespace lwr_hw +{ + +class LWRHWreal : public LWRHW +{ + +public: + + ~LWRHWreal() {} + + void stop(){return;}; + void set_mode(){return;}; + + void setPort(int port){port_ = port; port_set_ = true;}; + void setIP(std::string hintToRemoteHost){hintToRemoteHost_ = hintToRemoteHost; ip_set_ = true;}; + + // Init, read, and write, with FRI hooks + bool init() + { + create(); + + if( !(port_set_) || !(ip_set_) ) + { + std::cout << "Did you forget to set the port/ip?" << std::endl << "You must do that before init()" << std::endl << "Exiting..." << std::endl; + return false; + } + // construct a low-level lwr + device_.reset( new friRemote( port_, const_cast(hintToRemoteHost_.c_str()) ) ); + + // initialize FRI values + lastQuality_ = FRI_QUALITY_BAD; + lastCtrlScheme_ = FRI_CTRL_OTHER; + + std::cout << "Opening FRI Version " + << FRI_MAJOR_VERSION << "." << FRI_SUB_VERSION << "." <setToKRLInt(0,1); + if ( device_->getQuality() >= FRI_QUALITY_OK) + { + // send a second marker + device_->setToKRLInt(0,10); + } + + // just mirror the real value.. + device_->setToKRLReal(0,device_->getFrmKRLReal(1)); + + std::cout << "LWR Status:\n" << device_->getMsrBuf().intf << std::endl; + + device_->doDataExchange(); + std::cout << "Done handshake !" << std::endl; + + return true; + } + + void read(ros::Time time, ros::Duration period) + { + for (int j = 0; j < n_joints_; j++) + { + joint_position_prev_[j] = joint_position_[j]; + joint_position_[j] = device_->getMsrMsrJntPosition()[j]; + joint_effort_[j] = device_->getMsrJntTrq()[j]; + joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j]-joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); + joint_stiffness_[j] = joint_stiffness_command_[j]; + } + return; + } + + void write(ros::Time time, ros::Duration period) + { + // fake velocity command computed as: + // (desired position - current position) / period, to avoid speed limit error + for (int j = 0; j < n_joints_; j++) + { + joint_velocity_command_[j] = (joint_position_command_[j]-joint_position_[j])/period.toSec(); + } + + // enforce limits + enforceLimits(period); + + // write to real robot + float newJntPosition[n_joints_]; + float newJntStiff[n_joints_]; + float newJntDamp[n_joints_]; + float newJntAddTorque[n_joints_]; + + if ( device_->isPowerOn() ) + { + // check control mode + //if ( device_->getState() == FRI_STATE_CMD ) + //{ + // check control strategy + if( device_->getCurrentControlScheme() == FRI_CTRL_JNT_IMP ) + { + for (int i = 0; i < n_joints_; i++) + { + newJntPosition[i] = joint_position_command_[i]; // zero for now + newJntAddTorque[i] = joint_effort_command_[i]; // comes from the controllers + newJntStiff[i] = joint_stiffness_command_[i]; // default values for now + newJntDamp[i] = joint_damping_command_[i]; // default values for now + } + + // only joint impedance control is performed, since it is the only one that provide access to the joint torque directly + // note that stiffness and damping are 0, as well as the position, since only effort is allowed to be sent + // the KRC adds the dynamic terms, such that if zero torque is sent, the robot apply torques necessary to mantain the robot in the current position + // the only interface is effort, thus any other action you want to do, you have to compute the added torque and send it through a controller + device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, true); + } + else if( device_->getCurrentControlScheme() == FRI_CTRL_POSITION ) + { + for (int i = 0; i < n_joints_; i++) + { + newJntPosition[i] = joint_position_command_[i]; + } + + // only joint impedance control is performed, since it is the only one that provide access to the joint torque directly + // note that stiffness and damping are 0, as well as the position, since only effort is allowed to be sent + // the KRC adds the dynamic terms, such that if zero torque is sent, the robot apply torques necessary to mantain the robot in the current position + // the only interface is effort, thus any other action you want to do, you have to compute the added torque and send it through a controller + device_->doPositionControl(newJntPosition, true); + } + else if( device_->getCurrentControlScheme() == FRI_CTRL_OTHER ) // Gravity compensation: just read status, but we have to keep FRI alive + { + device_->doDataExchange(); + } + //} + } + return; + } + +private: + + // Parameters + int port_; + bool port_set_ = false; + std::string hintToRemoteHost_; + bool ip_set_ = false; + + // low-level interface + boost::shared_ptr device_; + + // FRI values + FRI_QUALITY lastQuality_; + FRI_CTRL lastCtrlScheme_; + +}; + +} + +#endif \ No newline at end of file diff --git a/lwr_hw/include/lwr_hw/lwr_hw_sim.h b/lwr_hw/include/lwr_hw/lwr_hw_sim.h deleted file mode 100644 index 05af043..0000000 --- a/lwr_hw/include/lwr_hw/lwr_hw_sim.h +++ /dev/null @@ -1,56 +0,0 @@ -/* Author: Carlos Rosales - Desc: Implements a default KUKA LWR 4+ simulation interface that emulates - the joint impedance control strategy using the gazebo_ros_control framework. - It is based on the default HW-I for any simulated robot in Gazebo from - gazebo_ros_control package. -*/ - -#ifndef LWR_HW____LWRs_HW_SIM_H -#define LWR_HW____LWRs_HW_SIM_H - -#include -#include -#include -#include -#include - -// RRBOT hardware base class -#include "lwr_hw/lwr_hw.h" - -namespace lwr_hw { - - // Struct for passing loaded joint data - struct JointData - { - std::string name_; - std::string hardware_interface_; - - JointData(const std::string& name, const std::string& hardware_interface) : - name_(name), - hardware_interface_(hardware_interface) - {} - }; - - // Gazebo plugin version of RRBOTHardware - class LWRHWsim : public lwr_hw::LWRHW - { - public: - - virtual ~LWRHWsim() { } - - virtual bool initSim( - const std::string& robot_namespace, - ros::NodeHandle model_nh, - gazebo::physics::ModelPtr parent_model, - const urdf::Model *const urdf_model, - std::vector transmissions) = 0; - - virtual void readSim(ros::Time time, ros::Duration period) = 0; - - virtual void writeSim(ros::Time time, ros::Duration period) = 0; - - }; - -} - -#endif \ No newline at end of file diff --git a/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp b/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp new file mode 100644 index 0000000..92bbbd0 --- /dev/null +++ b/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp @@ -0,0 +1,120 @@ +#ifndef LWR_HW____LWR_HW_SIM_H +#define LWR_HW____LWR_HW_SIM_H + +// ROS +#include +// #include + +// Gazebo hook +#include +#include +#include + +// lwr hw definition +#include "lwr_hw/lwr_hw.h" + +namespace lwr_hw { + +class LWRHWsim : public LWRHW +{ +public: + + ~LWRHWsim() {} + + void setParentModel(gazebo::physics::ModelPtr parent_model){parent_model_ = parent_model; parent_set_ = true;}; + + // Init, read, and write, with Gazebo hooks + bool init() + { + if( !(parent_set_) ) + { + std::cout << "Did you forget to set the parent model?" << std::endl << "You must do that before init()" << std::endl << "Exiting..." << std::endl; + return false; + } + + gazebo::physics::JointPtr joint; + for(unsigned int j=0; j < n_joints_; j++) + { + joint = parent_model_->GetJoint(joint_names_[j]); + if (!joint) + { + std::cout << "This robot has a joint named \"" << joint_names_[j] + << "\" which is not in the gazebo model." << std::endl; + return false; + } + sim_joints_.push_back(joint); + } + + return true; + } + + void read(ros::Time time, ros::Duration period) + { + for(unsigned int j=0; j < n_joints_; j++) + { + joint_position_prev_[j] = joint_position_[j]; + joint_position_[j] += angles::shortest_angular_distance(joint_position_[j], + sim_joints_[j]->GetAngle(0).Radian()); + joint_position_kdl_(j) = joint_position_[j]; + // derivate velocity as in the real hardware instead of reading it from simulation + joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j] - joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); + joint_effort_[j] = sim_joints_[j]->GetForce((unsigned int)(0)); + joint_stiffness_[j] = joint_stiffness_command_[j]; + } + } + + void write(ros::Time time, ros::Duration period) + { + enforceLimits(period); + std::cout << "AFTER ENFORCING LIMITS" << std::endl; + std::cout << "SWITCH STRATEGY by: " << getControlStrategy() << std::endl; + + switch (getControlStrategy()) + { + + case JOINT_POSITION: + std::cout << "JOINT POSITION STRATEGY" << std::endl; + for(unsigned int j=0; j < n_joints_; j++) + { + sim_joints_[j]->SetPosition(0, joint_position_command_[j]); + } + break; + + case CARTESIAN_IMPEDANCE: + ROS_WARN("CARTESIAN IMPEDANCE NOT IMPLEMENTED"); + break; + + case JOINT_IMPEDANCE: + // compute the gracity term + f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); + + for(unsigned int j=0; j < n_joints_; j++) + { + // replicate the joint impedance control strategy + // tau = k (q_FRI - q_msr) + tau_FRI + D(q_msr) + f_dyn(q_msr) + double spring_effort = joint_stiffness_command_[j]*( joint_position_command_[j] - joint_position_[j] ); + //double damping_effort = joint_damping_command_[j]*( joint_velocity_[j] ); + + const double effort = spring_effort + joint_effort_command_[j] + gravity_effort_(j); + sim_joints_[j]->SetForce(0, effort); + } + break; + + case GRAVITY_COMPENSATION: + ROS_WARN("CARTESIAN IMPEDANCE NOT IMPLEMENTED"); + break; + } + } + +private: + + // Gazebo stuff + std::vector sim_joints_; + gazebo::physics::ModelPtr parent_model_; + bool parent_set_ = false; + +}; + +} + +#endif \ No newline at end of file diff --git a/lwr_hw/include/lwr_hw/lwr_hw_sim_plugin.h b/lwr_hw/include/lwr_hw/lwr_hw_sim_plugin.h deleted file mode 100644 index 27ef669..0000000 --- a/lwr_hw/include/lwr_hw/lwr_hw_sim_plugin.h +++ /dev/null @@ -1,91 +0,0 @@ -/* Author: Carlos Rosales - Desc: Implements a default KUKA LWR 4+ simulation interface that emulates - the joint impedance control strategy. - It is based on the default HW-I for any simulated robot in Gazebo from - gazebo_ros_control package. -*/ - -// Boost -#include -#include - -// ROS -#include -#include - -// Gazebo -#include -#include -#include - -// ros_control -#include -#include -#include - -namespace lwr_hw -{ - -class LWRHWSimPlugin : public gazebo::ModelPlugin -{ -public: - - virtual ~LWRHWSimPlugin(); - - // Overloaded Gazebo entry point - virtual void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf); - - // Called by the world update start event - void Update(); - - // Called on world reset - virtual void Reset(); - - // Get the URDF XML from the parameter server - std::string getURDF(std::string param_name) const; - - // Get Transmissions from the URDF - bool parseTransmissionsFromURDF(const std::string& urdf_string); - -protected: - - // Node Handles - ros::NodeHandle model_nh_; // namespaces to robot name - - // Pointer to the model - gazebo::physics::ModelPtr parent_model_; - sdf::ElementPtr sdf_; - - // deferred load in case ros is blocking - boost::thread deferred_load_thread_; - - // Pointer to the update event connection - gazebo::event::ConnectionPtr update_connection_; - - // Interface loader - boost::shared_ptr > robot_hw_sim_loader_; - void load_robot_hw_sim_srv(); - - // Strings - std::string robot_namespace_; - std::string robot_description_; - - // Transmissions in this plugin's scope - std::vector transmissions_; - - // Robot simulator interface - std::string robot_hw_sim_type_str_; - boost::shared_ptr robot_hw_sim_; - - // Controller manager - boost::shared_ptr controller_manager_; - - // Timing - ros::Duration control_period_; - ros::Time last_update_sim_time_ros_; - ros::Time last_write_sim_time_ros_; - -}; - - -} diff --git a/lwr_hw/launch/lwr_hw.launch b/lwr_hw/launch/lwr_hw.launch index f09cee7..564ff46 100644 --- a/lwr_hw/launch/lwr_hw.launch +++ b/lwr_hw/launch/lwr_hw.launch @@ -1,32 +1,16 @@ + - - - - - - - - - - - - - - - - - - - - - - + + + + + diff --git a/lwr_hw/lwr_hw_sim_plugins.xml b/lwr_hw/lwr_hw_sim_plugins.xml deleted file mode 100644 index b46a3f9..0000000 --- a/lwr_hw/lwr_hw_sim_plugins.xml +++ /dev/null @@ -1,11 +0,0 @@ - - - - - A default KUKA LWR 4+ simulation interface that emulates the joint impedance control strategy. - - - \ No newline at end of file diff --git a/lwr_hw/package.xml b/lwr_hw/package.xml index d7ae027..01114d3 100644 --- a/lwr_hw/package.xml +++ b/lwr_hw/package.xml @@ -1,7 +1,7 @@ lwr_hw - 0.1.0 + 0.2.0 The lwr_hw package implementes real and simulation interfaces to the LWR 4+ Carlos J. Rosales @@ -35,7 +35,6 @@ joint_limits_interface - diff --git a/lwr_hw/src/default_lwr_hw_sim.cpp b/lwr_hw/src/default_lwr_hw_sim.cpp deleted file mode 100644 index 422b9ae..0000000 --- a/lwr_hw/src/default_lwr_hw_sim.cpp +++ /dev/null @@ -1,322 +0,0 @@ -/* Author: Carlos Rosales - Desc: Implements a default KUKA LWR 4+ simulation interface that emulates - the joint impedance control strategy using the gazebo_ros_control framework. - It is based on the default HW-I for any simulated robot in Gazebo from - gazebo_ros_control package. -*/ - -#ifndef LWR_HW___DEFAULT_LWR_HW_SIM_H_ -#define LWR_HW___DEFAULT_LWR_HW_SIM_H_ - -// ROS -#include -#include -#include - -// ros_control -#include -#include -#include -#include -#include -#include -#include -#include - -// Gazebo -#include -#include -#include - -// URDF -#include - -// KDL -#include -#include -#include -#include //this to compute the gravity verctor -#include - -// lwr_hw_sim -#include "lwr_hw/lwr_hw_sim.h" - -namespace -{ - -double clamp(const double val, const double min_val, const double max_val) -{ - return std::min(std::max(val, min_val), max_val); -} - -} - -namespace lwr_hw -{ - -class DefaultLWRHWsim : public lwr_hw::LWRHWsim -{ -public: - - bool initSim( - const std::string& robot_namespace, - ros::NodeHandle model_nh, - gazebo::physics::ModelPtr parent_model, - const urdf::Model *const urdf_model, - std::vector transmissions) - { - // getJointLimits() searches joint_limit_nh for joint limit parameters. The format of each - // parameter's name is "joint_limits/". An example is "joint_limits/axle_joint". - const ros::NodeHandle joint_limit_nh(model_nh, robot_namespace); - - // Resize vectors to our DOF, resize vectors, and reset to zero - n_joints_ = transmissions.size(); - init(n_joints_); - reset(); - - // Initialize values - for(unsigned int j=0; j < n_joints_; j++) - { - // Check that this transmission has one joint - if(transmissions[j].joints_.size() == 0) - { - ROS_WARN_STREAM_NAMED("default_robot_hw_sim","Transmission " << transmissions[j].name_ - << " has no associated joints."); - continue; - } - else if(transmissions[j].joints_.size() > 1) - { - ROS_WARN_STREAM_NAMED("default_robot_hw_sim","Transmission " << transmissions[j].name_ - << " has more than one joint. Currently the default robot hardware simulation " - << " interface only supports one."); - continue; - } - - std::vector joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_; - - if (joint_interfaces.empty() && - !(transmissions[j].actuators_.empty()) && - !(transmissions[j].actuators_[0].hardware_interfaces_.empty())) - { - // TODO: Deprecate HW interface specification in actuators in ROS J - joint_interfaces = transmissions[j].actuators_[0].hardware_interfaces_; - ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "The element of tranmission " << - transmissions[j].name_ << " should be nested inside the element, not . " << - "The transmission will be properly loaded, but please update " << - "your robot model to remain compatible with future versions of the plugin."); - } - if (joint_interfaces.empty()) - { - ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "Joint " << transmissions[j].joints_[0].name_ << - " of transmission " << transmissions[j].name_ << " does not specify any hardware interface. " << - "Not adding it to the robot hardware simulation."); - continue; - } - /*else if (joint_interfaces.size() > 1) - { - ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "Joint " << transmissions[j].joints_[0].name_ << - " of transmission " << transmissions[j].name_ << " specifies multiple hardware interfaces. " << - "Currently the default robot hardware simulation interface only supports one."); - continue; - } - */ - - // Add data from transmission - joint_names_.at(j) = transmissions.at(j).joints_.at(0).name_; - - const std::string& hardware_interface = joint_interfaces.front(); - - // Debug - ROS_DEBUG_STREAM_NAMED("default_robot_hw_sim","Loading joint '" << joint_names_[j] - << "' of type '" << hardware_interface << "'"); - - // Create joint state interface for all joints - state_interface_.registerHandle(hardware_interface::JointStateHandle( - joint_names_[j], &joint_position_[j], &joint_velocity_[j], &joint_effort_[j])); - - // Decide what kind of command interface this actuator/joint has - hardware_interface::JointHandle joint_handle_effort; - joint_handle_effort = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), - &joint_effort_command_[j]); - effort_interface_.registerHandle(joint_handle_effort); - - hardware_interface::JointHandle joint_handle_position; - joint_handle_position = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), - &joint_position_command_[j]); - position_interface_.registerHandle(joint_handle_position); - - // the stiffness is not actually a different joint, so the state handle is only used for handle - hardware_interface::JointHandle joint_handle_stiffness; - joint_handle_stiffness = hardware_interface::JointHandle(hardware_interface::JointStateHandle( - joint_names_[j]+std::string("_stiffness"), - &joint_stiffness_[j], &joint_stiffness_[j], &joint_stiffness_[j]), - &joint_stiffness_command_[j]); - position_interface_.registerHandle(joint_handle_stiffness); - - // velocity command handle, recall it is fake, there is no actual velocity interface - hardware_interface::JointHandle joint_handle_velocity; - joint_handle_velocity = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), - &joint_velocity_command_[j]); - - // Get the gazebo joint that corresponds to the robot joint. - //ROS_DEBUG_STREAM_NAMED("default_robot_hw_sim", "Getting pointer to gazebo joint: " - // << joint_names_[j]); - gazebo::physics::JointPtr joint = parent_model->GetJoint(joint_names_[j]); - if (!joint) - { - ROS_ERROR_STREAM("This robot has a joint named \"" << joint_names_[j] - << "\" which is not in the gazebo model."); - return false; - } - sim_joints_.push_back(joint); - - registerJointLimits(joint_names_[j], - joint_handle_effort, - joint_handle_position, - joint_handle_velocity, - joint_handle_stiffness, - urdf_model, - &joint_lower_limits_[j], &joint_upper_limits_[j], - &joint_lower_limits_stiffness_[j], - &joint_upper_limits_stiffness_[j], - &joint_effort_limits_[j]); - - /*if (joint_control_methods_[j] != EFFORT) - { - // Initialize the PID controller. If no PID gain values are found, use joint->SetPosition() or - // joint->SetVelocity() to control the joint. - const ros::NodeHandle nh(model_nh, robot_namespace + "/gazebo_ros_control/pid_gains/" + - joint_names_[j]); - if (pid_controllers_[j].init(nh, true)) - { - switch (joint_control_methods_[j]) - { - case POSITION: - joint_control_methods_[j] = POSITION_PID; - break; - case VELOCITY: - joint_control_methods_[j] = VELOCITY_PID; - break; - } - } - else - { - // joint->SetMaxForce() must be called if joint->SetPosition() or joint->SetVelocity() are - // going to be called. joint->SetMaxForce() must *not* be called if joint->SetForce() is - // going to be called. - joint->SetMaxForce(0, joint_effort_limits_[j]); - } - }*/ - } - - // Register interfaces - registerInterface(&state_interface_); - registerInterface(&effort_interface_); - registerInterface(&position_interface_); - - // KDL code to compute f_dyn(q) - KDL::Tree kdl_tree; - if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree)) - { - ROS_ERROR("Failed to construct kdl tree"); - return false; - } - - ROS_INFO("LWR kinematic successfully parsed with %d joints, and %d segments.",kdl_tree.getNrOfJoints(),kdl_tree.getNrOfJoints()); - - // this is indepenedent of robot mounting, typically with positive z pointing up.- - std::string root_name = kdl_tree.getRootSegment()->first; //std::string("world"); - - // this could be parametrized to allow for different end-effectors as in the real robot.- - std::string tip_name = robot_namespace + std::string("_7_link"); - - // this depends on how the world frame is set, in all our setups, world has always positive z pointing up. - gravity_ = KDL::Vector::Zero(); - gravity_(2) = -9.81; - - // Extract the chain from the tree - if(!kdl_tree.getChain(root_name, tip_name, lwr_chain_)) - { - ROS_ERROR("Failed to get KDL chain from tree: "); - /*ROS_ERROR_STREAM(" "< "<GetAngle(0).Radian()); - joint_position_kdl_(j) = joint_position_[j]; - // joint_velocity_[j] = sim_joints_[j]->GetVelocity(0); - // derivate velocity as in the real hardware instead of reading it from simulation - joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j] - joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); - joint_effort_[j] = sim_joints_[j]->GetForce((unsigned int)(0)); - joint_stiffness_[j] = joint_stiffness_command_[j]; - } - } - - void writeSim(ros::Time time, ros::Duration period) - { - ej_sat_interface_.enforceLimits(period); - ej_limits_interface_.enforceLimits(period); - pj_sat_interface_.enforceLimits(period); - pj_limits_interface_.enforceLimits(period); - sj_sat_interface_.enforceLimits(period); - sj_limits_interface_.enforceLimits(period); - - // compute the gracity term - f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); - - for(unsigned int j=0; j < n_joints_; j++) - { - // replicate the joint impedance control strategy - // tau = k (q_FRI - q_msr) + tau_FRI + D(q_msr) + f_dyn(q_msr) - double spring_effort = joint_stiffness_command_[j]*( joint_position_command_[j] - joint_position_[j] ); - //double damping_effort = joint_damping_command_[j]*( joint_velocity_[j] ); - - const double effort = spring_effort + joint_effort_command_[j] + gravity_effort_(j); - sim_joints_[j]->SetForce(0, effort); - } - } - - // KDL stuff to compute f_dyn in simulation - KDL::Chain lwr_chain_; - boost::scoped_ptr f_dyn_solver_; - KDL::JntArray joint_position_kdl_, gravity_effort_; - KDL::Vector gravity_; - - std::vector sim_joints_; -}; - -typedef boost::shared_ptr DefaultLWRHWsimPtr; - -} - -PLUGINLIB_EXPORT_CLASS(lwr_hw::DefaultLWRHWsim, lwr_hw::LWRHWsim) - -#endif diff --git a/lwr_hw/src/lwr_hw.cpp b/lwr_hw/src/lwr_hw.cpp index 05542e6..56e1fb9 100644 --- a/lwr_hw/src/lwr_hw.cpp +++ b/lwr_hw/src/lwr_hw.cpp @@ -3,16 +3,18 @@ namespace lwr_hw { -// init resize variables -void LWRHW::init(int n_joints) -{ - n_joints_ = n_joints; + void LWRHW::create() + { + // ALLOCATE MEMORY + n_joints_ = 7; // safe magic number, the kuka lwr 4+ has 7 joints + joint_names_.resize(n_joints_); joint_position_.resize(n_joints_); joint_position_prev_.resize(n_joints_); joint_velocity_.resize(n_joints_); joint_effort_.resize(n_joints_); joint_stiffness_.resize(n_joints_); + joint_damping_.resize(n_joints_); joint_position_command_.resize(n_joints_); joint_velocity_command_.resize(n_joints_); joint_effort_command_.resize(n_joints_); @@ -25,115 +27,376 @@ void LWRHW::init(int n_joints) joint_upper_limits_stiffness_.resize(n_joints_); joint_effort_limits_.resize(n_joints_); - return; -} + reset(); -// reset values -void LWRHW::reset() -{ - for (int j = 0; j < n_joints_; ++j) - { - joint_position_[j] = 0.0; - joint_position_prev_[j] = 0.0; - joint_velocity_[j] = 0.0; - joint_effort_[j] = 0.0; - joint_stiffness_[j] = 0.0; - - joint_position_command_[j] = 0.0; - joint_velocity_command_[j] = 0.0; - joint_effort_command_[j] = 0.0; - joint_stiffness_command_[j] = 2500.0; - joint_damping_command_[j] = 0.0; - } + // REGISTER INTERFACES + // get the robot description + robot_description_ = "/robot_description"; // default + robot_namespace_ = "lwr"; + // Read urdf from ros parameter server then + // setup actuators and mechanism control node. + // This call will block if ROS is not properly initialized. + const std::string urdf_string = getURDF(robot_description_); + if (!parseTransmissionsFromURDF(urdf_string)) + { + std::cout << "lwr_hw: " << "Error parsing URDF in lwr_hw plugin, plugin not active.\n" << std::endl; + return; + } + const urdf::Model *const urdf_model_ptr = urdf_model_.initString(urdf_string) ? &urdf_model_ : NULL; + registerInterfaces(urdf_model_ptr, transmissions_); - return; -} + // INIT KDL STUFF + initKDLdescription(urdf_model_ptr); -// Register the limits of the joint specified by joint_name and\ joint_handle. The limits are -// retrieved from the urdf_model. -// Return the joint's type, lower position limit, upper position limit, and effort limit. -void LWRHW::registerJointLimits(const std::string& joint_name, - const hardware_interface::JointHandle& joint_handle_effort, - const hardware_interface::JointHandle& joint_handle_position, - const hardware_interface::JointHandle& joint_handle_velocity, - const hardware_interface::JointHandle& joint_handle_stiffness, - const urdf::Model *const urdf_model, - double *const lower_limit, double *const upper_limit, - double *const lower_limit_stiffness, double *const upper_limit_stiffness, - double *const effort_limit) -{ - *lower_limit = -std::numeric_limits::max(); - *upper_limit = std::numeric_limits::max(); - *lower_limit_stiffness = -std::numeric_limits::max(); - *upper_limit_stiffness = std::numeric_limits::max(); - *effort_limit = std::numeric_limits::max(); - - joint_limits_interface::JointLimits limits; - joint_limits_interface::JointLimits limits_stiffness; - bool has_limits = false; - bool has_limits_stiffness = false; - joint_limits_interface::SoftJointLimits soft_limits; - bool has_soft_limits = false; - - if (urdf_model != NULL) + std::cout << "Succesfully created an abstract LWR 4+ ARM with interfaces" << std::endl; + } + + // reset values + void LWRHW::reset() { - const boost::shared_ptr urdf_joint = urdf_model->getJoint(joint_name); - const boost::shared_ptr urdf_joint_sitffness = urdf_model->getJoint(joint_name + std::string("_stiffness")); - if (urdf_joint != NULL) + for (int j = 0; j < n_joints_; ++j) { - // Get limits from the URDF file. - if (joint_limits_interface::getJointLimits(urdf_joint, limits)) - has_limits = true; - if (joint_limits_interface::getJointLimits(urdf_joint_sitffness, limits_stiffness)) - has_limits_stiffness = true; - if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) - has_soft_limits = true; + joint_position_[j] = 0.0; + joint_position_prev_[j] = 0.0; + joint_velocity_[j] = 0.0; + joint_effort_[j] = 0.0; + joint_stiffness_[j] = 0.0; + joint_damping_[j] = 0.0; + + joint_position_command_[j] = 0.0; + joint_velocity_command_[j] = 0.0; + joint_effort_command_[j] = 0.0; + joint_stiffness_command_[j] = 2500.0; + joint_damping_command_[j] = 0.0; } - } - if (!has_limits) + current_strategy_ = JOINT_POSITION; + return; + } - if (limits.has_position_limits) + void LWRHW::registerInterfaces(const urdf::Model *const urdf_model, + std::vector transmissions) { - *lower_limit = limits.min_position; - *upper_limit = limits.max_position; + // Initialize values + for(unsigned int j=0; j < n_joints_; j++) + { + // Check that this transmission has one joint + if(transmissions[j].joints_.size() == 0) + { + std::cout << "default_robot_hw_sim: " << "Transmission " << transmissions[j].name_ + << " has no associated joints." << std::endl; + continue; + } + else if(transmissions[j].joints_.size() > 1) + { + std::cout << "default_robot_hw_sim: " << "Transmission " << transmissions[j].name_ + << " has more than one joint. Currently the default robot hardware simulation " + << " interface only supports one." << std::endl; + continue; + } + + std::vector joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_; + + if (joint_interfaces.empty() && + !(transmissions[j].actuators_.empty()) && + !(transmissions[j].actuators_[0].hardware_interfaces_.empty())) + { + // TODO: Deprecate HW interface specification in actuators in ROS J + joint_interfaces = transmissions[j].actuators_[0].hardware_interfaces_; + std::cout << "default_robot_hw_sim: " << "The element of tranmission " << + transmissions[j].name_ << " should be nested inside the element, not . " << + "The transmission will be properly loaded, but please update " << + "your robot model to remain compatible with future versions of the plugin." << std::endl; + } + if (joint_interfaces.empty()) + { + std::cout << "default_robot_hw_sim: " << "Joint " << transmissions[j].joints_[0].name_ << + " of transmission " << transmissions[j].name_ << " does not specify any hardware interface. " << + "Not adding it to the robot hardware simulation." << std::endl; + continue; + } + /*else if (joint_interfaces.size() > 1) + { + ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "Joint " << transmissions[j].joints_[0].name_ << + " of transmission " << transmissions[j].name_ << " specifies multiple hardware interfaces. " << + "Currently the default robot hardware simulation interface only supports one."); + continue; + } + */ + + // Add data from transmission + joint_names_.at(j) = transmissions.at(j).joints_.at(0).name_; + + const std::string& hardware_interface = joint_interfaces.front(); + + // Debug + std::cout << "\x1B[37m" << "lwr_hw: " << "Loading joint '" << joint_names_[j] + << "' of type '" << hardware_interface << "'" << "\x1B[0m" << std::endl; + + // Create joint state interface for all joints + state_interface_.registerHandle(hardware_interface::JointStateHandle( + joint_names_[j], &joint_position_[j], &joint_velocity_[j], &joint_effort_[j])); + + std::cout << "CLAIM: j=" << j << " " << state_interface_.getClaims().size() << std::endl; + + // Decide what kind of command interface this actuator/joint has + hardware_interface::JointHandle joint_handle_effort; + joint_handle_effort = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), + &joint_effort_command_[j]); + effort_interface_.registerHandle(joint_handle_effort); + + hardware_interface::JointHandle joint_handle_position; + joint_handle_position = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), + &joint_position_command_[j]); + position_interface_.registerHandle(joint_handle_position); + + // the stiffness is not actually a different joint, so the state handle is only used for handle + hardware_interface::JointHandle joint_handle_stiffness; + joint_handle_stiffness = hardware_interface::JointHandle(hardware_interface::JointStateHandle( + joint_names_[j]+std::string("_stiffness"), + &joint_stiffness_[j], &joint_stiffness_[j], &joint_stiffness_[j]), + &joint_stiffness_command_[j]); + position_interface_.registerHandle(joint_handle_stiffness); + + // velocity command handle, recall it is fake, there is no actual velocity interface + hardware_interface::JointHandle joint_handle_velocity; + joint_handle_velocity = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), + &joint_velocity_command_[j]); + + registerJointLimits(joint_names_[j], + joint_handle_effort, + joint_handle_position, + joint_handle_velocity, + joint_handle_stiffness, + urdf_model, + &joint_lower_limits_[j], &joint_upper_limits_[j], + &joint_lower_limits_stiffness_[j], + &joint_upper_limits_stiffness_[j], + &joint_effort_limits_[j]); + + /*if (joint_control_methods_[j] != EFFORT) + { + // Initialize the PID controller. If no PID gain values are found, use joint->SetPosition() or + // joint->SetVelocity() to control the joint. + const ros::NodeHandle nh(model_nh, robot_namespace + "/gazebo_ros_control/pid_gains/" + + joint_names_[j]); + if (pid_controllers_[j].init(nh, true)) + { + switch (joint_control_methods_[j]) + { + case POSITION: + joint_control_methods_[j] = POSITION_PID; + break; + case VELOCITY: + joint_control_methods_[j] = VELOCITY_PID; + break; + } + } + else + { + // joint->SetMaxForce() must be called if joint->SetPosition() or joint->SetVelocity() are + // going to be called. joint->SetMaxForce() must *not* be called if joint->SetForce() is + // going to be called. + joint->SetMaxForce(0, joint_effort_limits_[j]); + } + }*/ + } + + // Register interfaces + + std::cout << "CLAIMS: " << state_interface_.getClaims().size() << std::endl; + registerInterface(&state_interface_); + registerInterface(&effort_interface_); + registerInterface(&position_interface_); } - if (limits.has_effort_limits) - *effort_limit = limits.max_effort; - if (has_soft_limits) + // Register the limits of the joint specified by joint_name and\ joint_handle. The limits are + // retrieved from the urdf_model. + // Return the joint's type, lower position limit, upper position limit, and effort limit. + void LWRHW::registerJointLimits(const std::string& joint_name, + const hardware_interface::JointHandle& joint_handle_effort, + const hardware_interface::JointHandle& joint_handle_position, + const hardware_interface::JointHandle& joint_handle_velocity, + const hardware_interface::JointHandle& joint_handle_stiffness, + const urdf::Model *const urdf_model, + double *const lower_limit, double *const upper_limit, + double *const lower_limit_stiffness, double *const upper_limit_stiffness, + double *const effort_limit) { - const joint_limits_interface::EffortJointSoftLimitsHandle limits_handle_effort(joint_handle_effort, limits, soft_limits); - ej_limits_interface_.registerHandle(limits_handle_effort); - const joint_limits_interface::PositionJointSoftLimitsHandle limits_handle_position(joint_handle_position, limits, soft_limits); - pj_limits_interface_.registerHandle(limits_handle_position); - const joint_limits_interface::VelocityJointSoftLimitsHandle limits_handle_velocity(joint_handle_velocity, limits, soft_limits); - vj_limits_interface_.registerHandle(limits_handle_velocity); + *lower_limit = -std::numeric_limits::max(); + *upper_limit = std::numeric_limits::max(); + *lower_limit_stiffness = -std::numeric_limits::max(); + *upper_limit_stiffness = std::numeric_limits::max(); + *effort_limit = std::numeric_limits::max(); + + joint_limits_interface::JointLimits limits; + joint_limits_interface::JointLimits limits_stiffness; + bool has_limits = false; + bool has_limits_stiffness = false; + joint_limits_interface::SoftJointLimits soft_limits; + bool has_soft_limits = false; + + if (urdf_model != NULL) + { + const boost::shared_ptr urdf_joint = urdf_model->getJoint(joint_name); + const boost::shared_ptr urdf_joint_sitffness = urdf_model->getJoint(joint_name + std::string("_stiffness")); + if (urdf_joint != NULL) + { + // Get limits from the URDF file. + if (joint_limits_interface::getJointLimits(urdf_joint, limits)) + has_limits = true; + if (joint_limits_interface::getJointLimits(urdf_joint_sitffness, limits_stiffness)) + has_limits_stiffness = true; + if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) + has_soft_limits = true; + } + } + if (!has_limits) + return; + + if (limits.has_position_limits) + { + *lower_limit = limits.min_position; + *upper_limit = limits.max_position; + } + if (limits.has_effort_limits) + *effort_limit = limits.max_effort; + + if (has_soft_limits) + { + const joint_limits_interface::EffortJointSoftLimitsHandle limits_handle_effort(joint_handle_effort, limits, soft_limits); + ej_limits_interface_.registerHandle(limits_handle_effort); + const joint_limits_interface::PositionJointSoftLimitsHandle limits_handle_position(joint_handle_position, limits, soft_limits); + pj_limits_interface_.registerHandle(limits_handle_position); + const joint_limits_interface::VelocityJointSoftLimitsHandle limits_handle_velocity(joint_handle_velocity, limits, soft_limits); + vj_limits_interface_.registerHandle(limits_handle_velocity); + + } + else + { + const joint_limits_interface::EffortJointSaturationHandle sat_handle_effort(joint_handle_effort, limits); + ej_sat_interface_.registerHandle(sat_handle_effort); + const joint_limits_interface::PositionJointSaturationHandle sat_handle_position(joint_handle_position, limits); + pj_sat_interface_.registerHandle(sat_handle_position); + const joint_limits_interface::VelocityJointSaturationHandle sat_handle_velocity(joint_handle_velocity, limits); + vj_sat_interface_.registerHandle(sat_handle_velocity); + } + + + if (!has_limits_stiffness) + return; + + if (limits_stiffness.has_position_limits) + { + *lower_limit_stiffness = limits_stiffness.min_position; + *upper_limit_stiffness = limits_stiffness.max_position; + } + + const joint_limits_interface::PositionJointSaturationHandle sat_handle_stiffness(joint_handle_stiffness, limits_stiffness); + sj_sat_interface_.registerHandle(sat_handle_stiffness); } - else + + void LWRHW::enforceLimits(ros::Duration period) { - const joint_limits_interface::EffortJointSaturationHandle sat_handle_effort(joint_handle_effort, limits); - ej_sat_interface_.registerHandle(sat_handle_effort); - const joint_limits_interface::PositionJointSaturationHandle sat_handle_position(joint_handle_position, limits); - pj_sat_interface_.registerHandle(sat_handle_position); - const joint_limits_interface::VelocityJointSaturationHandle sat_handle_velocity(joint_handle_velocity, limits); - vj_sat_interface_.registerHandle(sat_handle_velocity); + ej_sat_interface_.enforceLimits(period); + ej_limits_interface_.enforceLimits(period); + vj_sat_interface_.enforceLimits(period); + vj_limits_interface_.enforceLimits(period); + pj_sat_interface_.enforceLimits(period); + pj_limits_interface_.enforceLimits(period); + sj_sat_interface_.enforceLimits(period); + sj_limits_interface_.enforceLimits(period); + dj_sat_interface_.enforceLimits(period); + dj_limits_interface_.enforceLimits(period); } + // Get the URDF XML from the parameter server + std::string LWRHW::getURDF(std::string param_name) const + { + std::string urdf_string; + + ROS_INFO_ONCE_NAMED("lwr_hw", "lwr_hw is waiting for model" + " URDF in parameter [%s] on the ROS param server.", robot_description_.c_str()); - if (!has_limits_stiffness) - return; + ros::param::get(robot_description_, urdf_string); - if (limits_stiffness.has_position_limits) + ROS_INFO_ONCE_NAMED("lwr_hw", "Recieved urdf from param server, parsing..."); + + return urdf_string; + } + + // Get Transmissions from the URDF + bool LWRHW::parseTransmissionsFromURDF(const std::string& urdf_string) { - *lower_limit_stiffness = limits_stiffness.min_position; - *upper_limit_stiffness = limits_stiffness.max_position; + transmission_interface::TransmissionParser::parse(urdf_string, transmissions_); + + std::vector::iterator it = transmissions_.begin(); + for(; it != transmissions_.end(); ) + { + if (robot_namespace_.compare(it->robot_namespace_) != 0) + { + std::cout << "lwr_hw deleted transmission " << it->name_ << " because it is not in the same robotNamespace as this plugin. This might be normal in a multi-robot configuration though." << std::endl; + it = transmissions_.erase(it); + } + else + { + ++it; + } + } + + return true; } - const joint_limits_interface::PositionJointSaturationHandle sat_handle_stiffness(joint_handle_stiffness, limits_stiffness); - sj_sat_interface_.registerHandle(sat_handle_stiffness); -} + // Init KDL stuff + bool LWRHW::initKDLdescription(const urdf::Model *const urdf_model) + { + // KDL code to compute f_dyn(q) + KDL::Tree kdl_tree; + if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree)) + { + ROS_ERROR("Failed to construct kdl tree"); + return false; + } + + std::cout << "LWR kinematic successfully parsed with " + << kdl_tree.getNrOfJoints() + << " joints, and " + << kdl_tree.getNrOfJoints() + << " segments." << std::endl;; + + // Get the info from parameters + std::string root_name; + ros::param::get("root", root_name); + if( root_name.empty() ) + root_name = kdl_tree.getRootSegment()->first; // default + + std::string tip_name; + ros::param::get("tip", tip_name); + if( root_name.empty() ) + tip_name = robot_namespace_ + std::string("_7_link"); ; // default + + // this depends on how the world frame is set, in all our setups, world has always positive z pointing up. + gravity_ = KDL::Vector::Zero(); + gravity_(2) = -9.81; + + // Extract the chain from the tree + if(!kdl_tree.getChain(root_name, tip_name, lwr_chain_)) + { + ROS_ERROR("Failed to get KDL chain from tree: "); + return false; + } + + ROS_INFO("Number of segments: %d", lwr_chain_.getNrOfSegments()); + ROS_INFO("Number of joints in chain: %d", lwr_chain_.getNrOfJoints()); + + f_dyn_solver_.reset(new KDL::ChainDynParam(lwr_chain_,gravity_)); + + joint_position_kdl_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + gravity_effort_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + + return true; + } } diff --git a/lwr_hw/src/lwr_hw_real.cpp b/lwr_hw/src/lwr_hw_real.cpp deleted file mode 100644 index 43b0722..0000000 --- a/lwr_hw/src/lwr_hw_real.cpp +++ /dev/null @@ -1,266 +0,0 @@ -#include "lwr_hw/lwr_hw_real.h" - -namespace lwr_hw -{ - -LWRHWreal::LWRHWreal(ros::NodeHandle nh) : - nh_(nh) -{} - -bool LWRHWreal::start() -{ - // get params or give default values - nh_.param("port", port_, 49939); - nh_.param("ip", hintToRemoteHost_, std::string("192.168.0.10") ); - - // TODO: use transmission configuration to get names directly from the URDF model - if( ros::param::get("joints", joint_names_) ) - { - if( !(joint_names_.size()==LBR_MNJ) ) - { - ROS_ERROR("This robot has 7 joints, you must specify 7 names for each one"); - } - } - else - { - ROS_ERROR("No joints to be handled, ensure you load a yaml file naming the joint names this hardware interface refers to."); - throw std::runtime_error("No joint name specification"); - } - if( !(urdf_model_.initParam("/robot_description")) ) - { - ROS_ERROR("No URDF model in the robot_description parameter, this is required to define the joint limits."); - throw std::runtime_error("No URDF model available"); - } - - // construct a low-level lwr - device_.reset( new friRemote( port_, const_cast(hintToRemoteHost_.c_str()) ) ); - - // initialize FRI values - lastQuality_ = FRI_QUALITY_BAD; - lastCtrlScheme_ = FRI_CTRL_OTHER; - - // initialize and set to zero the state and command values - init(LBR_MNJ); - reset(); - - // general joint to store information - boost::shared_ptr joint; - - // create joint handles given the list - for(int i = 0; i < LBR_MNJ; ++i) - { - ROS_INFO_STREAM("Handling joint: " << joint_names_[i]); - - // get current joint configuration - joint = urdf_model_.getJoint(joint_names_[i]); - if(!joint.get()) - { - ROS_ERROR_STREAM("The specified joint "<< joint_names_[i] << " can't be found in the URDF model. Check that you loaded an URDF model in the robot description, or that you spelled correctly the joint name."); - throw std::runtime_error("Wrong joint name specification"); - } - - // joint state handle - hardware_interface::JointStateHandle state_handle(joint_names_[i], - &joint_position_[i], - &joint_velocity_[i], - &joint_effort_[i]); - - state_interface_.registerHandle(state_handle); - - // effort command handle - hardware_interface::JointHandle joint_handle_effort = hardware_interface::JointHandle( - state_interface_.getHandle(joint_names_[i]), - &joint_effort_command_[i]); - effort_interface_.registerHandle(joint_handle_effort); - - // position command handle - hardware_interface::JointHandle joint_handle_position = hardware_interface::JointHandle( - state_interface_.getHandle(joint_names_[i]), - &joint_position_command_[i]); - position_interface_.registerHandle(joint_handle_position); - - // stiffness command handle, registered in the position interface as well - hardware_interface::JointHandle joint_handle_stiffness; - joint_handle_stiffness = hardware_interface::JointHandle(hardware_interface::JointStateHandle( - joint_names_[i]+std::string("_stiffness"), - &joint_stiffness_[i], &joint_stiffness_[i], &joint_stiffness_[i]), - &joint_stiffness_command_[i]); - position_interface_.registerHandle(joint_handle_stiffness); - - // velocity command handle, recall it is fake, there is no actual velocity interface - hardware_interface::JointHandle joint_handle_velocity = hardware_interface::JointHandle( - state_interface_.getHandle(joint_names_[i]), - &joint_velocity_command_[i]); - - registerJointLimits(joint_names_[i], - joint_handle_effort, - joint_handle_position, - joint_handle_velocity, - joint_handle_stiffness, - &urdf_model_, - &joint_lower_limits_[i], - &joint_upper_limits_[i], - &joint_lower_limits_stiffness_[i], - &joint_upper_limits_stiffness_[i], - &joint_effort_limits_[i]); - } - - ROS_INFO("Register state and effort interfaces"); - - // register ros-controls interfaces - this->registerInterface(&state_interface_); - this->registerInterface(&effort_interface_); - this->registerInterface(&position_interface_); - this->registerInterface(&velocity_interface_); - - // note that the velocity interface is not registrered, since the velocity command is computed within this implementation. - - std::cout << "Opening FRI Version " - << FRI_MAJOR_VERSION << "." << FRI_SUB_VERSION << "." <setToKRLInt(0,1); - if ( device_->getQuality() >= FRI_QUALITY_OK) - { - // send a second marker - device_->setToKRLInt(0,10); - } - - // - // just mirror the real value.. - // - device_->setToKRLReal(0,device_->getFrmKRLReal(1)); - - ROS_INFO_STREAM("LWR Status:\n" << device_->getMsrBuf().intf); - - device_->doDataExchange(); - ROS_INFO("Done handshake !"); - - return true; -} - -bool LWRHWreal::read(ros::Time time, ros::Duration period) -{ - // update the robot positions - for (int j = 0; j < LBR_MNJ; j++) - { - joint_position_prev_[j] = joint_position_[j]; - joint_position_[j] = device_->getMsrMsrJntPosition()[j]; - joint_effort_[j] = device_->getMsrJntTrq()[j]; - joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j]-joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); - joint_stiffness_[j] = joint_stiffness_command_[j]; - } - - //this->device_->interface->doDataExchange(); - - return true; -} - -void LWRHWreal::write(ros::Time time, ros::Duration period) -{ - static int warning = 0; - - for (int j = 0; j < LBR_MNJ; j++) - { - // fake velocity command computed as: - // (desired position - current position) / period, to avoid speed limit error - joint_velocity_command_[j] = (joint_position_command_[j]-joint_position_[j])/period.toSec(); - } - - // enforce limits - ej_sat_interface_.enforceLimits(period); - ej_limits_interface_.enforceLimits(period); - vj_sat_interface_.enforceLimits(period); - vj_limits_interface_.enforceLimits(period); - pj_sat_interface_.enforceLimits(period); - pj_limits_interface_.enforceLimits(period); - - // write to real robot - float newJntPosition[LBR_MNJ]; - float newJntStiff[LBR_MNJ]; - float newJntDamp[LBR_MNJ]; - float newJntAddTorque[LBR_MNJ]; - - if ( device_->isPowerOn() ) - { - // check control mode - //if ( device_->getState() == FRI_STATE_CMD ) - //{ - // check control scheme - if( device_->getCurrentControlScheme() == FRI_CTRL_JNT_IMP ) - { - for (int i = 0; i < LBR_MNJ; i++) - { - newJntPosition[i] = joint_position_command_[i]; // zero for now - newJntAddTorque[i] = joint_effort_command_[i]; // comes from the controllers - newJntStiff[i] = joint_stiffness_command_[i]; // default values for now - newJntDamp[i] = joint_damping_command_[i]; // default values for now - } - - // only joint impedance control is performed, since it is the only one that provide access to the joint torque directly - // note that stiffness and damping are 0, as well as the position, since only effort is allowed to be sent - // the KRC adds the dynamic terms, such that if zero torque is sent, the robot apply torques necessary to mantain the robot in the current position - // the only interface is effort, thus any other action you want to do, you have to compute the added torque and send it through a controller - device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, true); - } - else if( device_->getCurrentControlScheme() == FRI_CTRL_POSITION ) - { - for (int i = 0; i < LBR_MNJ; i++) - { - newJntPosition[i] = joint_position_command_[i]; - } - - // only joint impedance control is performed, since it is the only one that provide access to the joint torque directly - // note that stiffness and damping are 0, as well as the position, since only effort is allowed to be sent - // the KRC adds the dynamic terms, such that if zero torque is sent, the robot apply torques necessary to mantain the robot in the current position - // the only interface is effort, thus any other action you want to do, you have to compute the added torque and send it through a controller - device_->doPositionControl(newJntPosition, true); - } - else if( this->device_->getCurrentControlScheme() == FRI_CTRL_OTHER ) // Gravity compensation: just read status, but we have to keep FRI alive - { - device_->doDataExchange(); - } - //} - } - - // Stop request is issued from the other side - /* - if ( this->device_->interface->getFrmKRLInt(0) == -1) - { - ROS_INFO(" Stop request issued from the other side"); - this->stop(); - }*/ - - // Quality change leads to output of statistics - // for informational reasons - // - /*if ( this->device_->interface->getQuality() != this->device_->lastQuality ) - { - ROS_INFO_STREAM("Quality change detected "<< this->device_->interface->getQuality()<< " \n"); - ROS_INFO_STREAM("" << this->device_->interface->getMsrBuf().intf); - this->device_->lastQuality = this->device_->interface->getQuality(); - }*/ - - // this is already done in the doJntImpedance Control setting to true the last flag - // this->device_->interface->doDataExchange(); - - return; -} - -void LWRHWreal::stop() -{ - // TODO: decide whether to stop the FRI or just put to idle - return; -} - -void LWRHWreal::set_mode() -{ - // ToDo: just switch between monitor and command mode, no control strategies switch - return; -} - -} // namespace diff --git a/lwr_hw/src/lwr_hw_real_node.cpp b/lwr_hw/src/lwr_hw_real_node.cpp index d39acfb..948c29b 100644 --- a/lwr_hw/src/lwr_hw_real_node.cpp +++ b/lwr_hw/src/lwr_hw_real_node.cpp @@ -4,13 +4,14 @@ #include #include #include +#include // ROS headers #include #include // the lwr hw real interface -#include "lwr_hw/lwr_hw_real.h" +#include "lwr_hw/lwr_hw_real.hpp" bool g_quit = false; @@ -33,25 +34,34 @@ int main( int argc, char** argv ) signal(SIGINT, quitRequested); signal(SIGHUP, quitRequested); - // construct the lwr + // create a node ros::NodeHandle lwr_nh(""); - lwr_hw::LWRHWreal lwr_robot(lwr_nh); - // configuration routines - lwr_robot.start(); + // get params or give default values + int port; + std::string hintToRemoteHost; + lwr_nh.param("port", port, 49939); + lwr_nh.param("ip", hintToRemoteHost, std::string("192.168.0.10") ); + + // construct and start the real lwr + lwr_hw::LWRHWreal lwr_robot; + lwr_robot.create(); + lwr_robot.setPort(port); + lwr_robot.setIP(hintToRemoteHost); + if(!lwr_robot.init()) + { + ROS_FATAL_NAMED("lwr_hw","Could not initialize robot real interface"); + return -1; + } // timer variables struct timespec ts = {0, 0}; ros::Time last(ts.tv_sec, ts.tv_nsec), now(ts.tv_sec, ts.tv_nsec); ros::Duration period(1.0); - //realtime_tools::RealtimePublisher publisher(lwr_nh, "loop_rate", 2); - //the controller manager controller_manager::ControllerManager manager(&lwr_robot, lwr_nh); - //uint32_t count = 0; - // run as fast as possible while( !g_quit ) { @@ -70,31 +80,15 @@ int main( int argc, char** argv ) } // read the state from the lwr - if(!lwr_robot.read(now, period)) - { - g_quit = true; - break; - } + lwr_robot.read(now, period); // update the controllers manager.update(now, period); // write the command to the lwr lwr_robot.write(now, period); - - // if(count++ > 1000) - // { - // if(publisher.trylock()) - // { - // count = 0; - // publisher.msg_.data = period; - // publisher.unlockAndPublish(); - // } - // } } - //publisher.stop(); - std::cerr<<"Stopping spinner..."< - Desc: Implements a default KUKA LWR 4+ simulation interface that emulates - the joint impedance control strategy using the gazebo_ros_control framework. - It is based on the default HW-I for any simulated robot in Gazebo from - gazebo_ros_control package. -*/ - // Boost #include +#include -// URDF +// ROS +#include #include +#include -#include "lwr_hw/lwr_hw_sim_plugin.h" +// Gazebo +#include +#include +#include -namespace lwr_hw -{ +// LWR sim class +#include "lwr_hw/lwr_hw_sim.hpp" -LWRHWSimPlugin::~LWRHWSimPlugin() +namespace lwr_hw { - // Disconnect from gazebo events - gazebo::event::Events::DisconnectWorldUpdateBegin(update_connection_); -} -// Overloaded Gazebo entry point -void LWRHWSimPlugin::Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf) +class LWRHWSimPlugin : public gazebo::ModelPlugin { - ROS_INFO_STREAM_NAMED("lwr_hw","Loading lwr_hw plugin"); - +public: - // Save pointers to the model - parent_model_ = parent; - sdf_ = sdf; - - // Error message if the model couldn't be found - if (!parent_model_) + ~LWRHWSimPlugin() { - ROS_ERROR_STREAM_NAMED("loadThread","parent model is NULL"); - return; + // Disconnect from gazebo events + gazebo::event::Events::DisconnectWorldUpdateBegin(update_connection_); } - // Check that ROS has been initialized - if(!ros::isInitialized()) + // Overloaded Gazebo entry point + void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf) { - ROS_FATAL_STREAM_NAMED("lwr_hw","A ROS node for Gazebo has not been initialized, unable to load plugin. " - << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)"); - return; - } + ROS_INFO_STREAM_NAMED("lwr_hw","Loading lwr_hw plugin"); - // Get namespace for nodehandle - if(sdf_->HasElement("robotNamespace")) - { - robot_namespace_ = sdf_->GetElement("robotNamespace")->Get(); - } - else - { - robot_namespace_ = parent_model_->GetName(); // default - } + // Save pointers to the model + parent_model_ = parent; + sdf_ = sdf; - // Get robot_description ROS param name - if (sdf_->HasElement("robotParam")) - { - robot_description_ = sdf_->GetElement("robotParam")->Get(); - } - else - { - robot_description_ = "robot_description"; // default - } - - // Get the robot simulation interface type - if(sdf_->HasElement("robotSimType")) - { - robot_hw_sim_type_str_ = sdf_->Get("robotSimType"); - } - else - { - robot_hw_sim_type_str_ = "lwr_hw/DefaultLWRHWsim"; - ROS_DEBUG_STREAM_NAMED("loadThread","Using default plugin for LWRHWsim (none specified in URDF/SDF)\""<GetWorld()->GetPhysicsEngine()->GetMaxStepSize()); + // Error message if the model couldn't be found + if (!parent_model_) + { + ROS_ERROR_STREAM_NAMED("loadThread","parent model is NULL"); + return; + } - // Decide the plugin control period - if(sdf_->HasElement("controlPeriod")) - { - control_period_ = ros::Duration(sdf_->Get("controlPeriod")); + // Check that ROS has been initialized + if(!ros::isInitialized()) + { + ROS_FATAL_STREAM_NAMED("lwr_hw","A ROS node for Gazebo has not been initialized, unable to load plugin. " + << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)"); + return; + } - // Check the period against the simulation period - if( control_period_ < gazebo_period ) + // Get namespace for nodehandle + if(sdf_->HasElement("robotNamespace")) { - ROS_ERROR_STREAM_NAMED("lwr_hw","Desired controller update period ("<GetElement("robotNamespace")->Get(); } - else if( control_period_ > gazebo_period ) + else { - ROS_WARN_STREAM_NAMED("lwr_hw","Desired controller update period ("<GetName(); // default } - } - else - { - control_period_ = gazebo_period; - ROS_DEBUG_STREAM_NAMED("lwr_hw","Control period not found in URDF/SDF, defaulting to Gazebo period of " - << control_period_); - } + // Get the robot simulation interface type + robot_hw_sim_type_str_ = "lwr_hw/LWRHWsim"; + ROS_DEBUG_STREAM_NAMED("loadThread","Using default plugin for LWRHWsim (none specified in URDF/SDF)\""<GetWorld()->GetPhysicsEngine()->GetMaxStepSize()); - // Read urdf from ros parameter server then - // setup actuators and mechanism control node. - // This call will block if ROS is not properly initialized. - const std::string urdf_string = getURDF(robot_description_); - if (!parseTransmissionsFromURDF(urdf_string)) - { - ROS_ERROR_NAMED("lwr_hw", "Error parsing URDF in lwr_hw plugin, plugin not active.\n"); - return; - } + // Decide the plugin control period + if(sdf_->HasElement("controlPeriod")) + { + control_period_ = ros::Duration(sdf_->Get("controlPeriod")); + + // Check the period against the simulation period + if( control_period_ < gazebo_period ) + { + ROS_ERROR_STREAM_NAMED("lwr_hw","Desired controller update period ("< gazebo_period ) + { + ROS_WARN_STREAM_NAMED("lwr_hw","Desired controller update period ("< - ("lwr_hw", - "lwr_hw::LWRHWsim")); + // Get parameters/settings for controllers from ROS param server + model_nh_ = ros::NodeHandle(robot_namespace_); + ROS_INFO_NAMED("lwr_hw", "Starting lwr_hw plugin in namespace: %s", robot_namespace_.c_str()); - robot_hw_sim_ = robot_hw_sim_loader_->createInstance(robot_hw_sim_type_str_); - urdf::Model urdf_model; - const urdf::Model *const urdf_model_ptr = urdf_model.initString(urdf_string) ? &urdf_model : NULL; + // Load the LWRHWsim abstraction to interface the controllers with the gazebo model + try + { + robot_hw_sim_.reset( new lwr_hw::LWRHWsim() ); + robot_hw_sim_->create(); + robot_hw_sim_->setParentModel(parent_model_); + if(!robot_hw_sim_->init()) + { + ROS_FATAL_NAMED("lwr_hw","Could not initialize robot simulation interface"); + return; + } + + std::cout << "CLAIMS IN PLUGIN: " << robot_hw_sim_->state_interface_.getClaims().size() << std::endl; + + // Create the controller manager + ROS_INFO_STREAM_NAMED("ros_control_plugin","Loading controller_manager"); + controller_manager_.reset + (new controller_manager::ControllerManager(robot_hw_sim_.get(), model_nh_)); + + // Listen to the update event. This event is broadcast every simulation iteration. + update_connection_ = + gazebo::event::Events::ConnectWorldUpdateBegin + (boost::bind(&LWRHWSimPlugin::Update, this)); - if(!robot_hw_sim_->initSim(robot_namespace_, model_nh_, parent_model_, urdf_model_ptr, transmissions_)) + } + catch(pluginlib::LibraryLoadException &ex) { - ROS_FATAL_NAMED("lwr_hw","Could not initialize robot simulation interface"); - return; + ROS_FATAL_STREAM_NAMED("lwr_hw","Failed to create robot simulation interface loader: "<GetWorld()->GetSimTime(); + ros::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec); + ros::Duration sim_period = sim_time_ros - last_update_sim_time_ros_; -// Called by the world update start event -void LWRHWSimPlugin::Update() -{ - // Get the simulation time and period - gazebo::common::Time gz_time_now = parent_model_->GetWorld()->GetSimTime(); - ros::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec); - ros::Duration sim_period = sim_time_ros - last_update_sim_time_ros_; + // Check if we should update the controllers + if(sim_period >= control_period_) + { + // Store this simulation time + last_update_sim_time_ros_ = sim_time_ros; - // Check if we should update the controllers - if(sim_period >= control_period_) { - // Store this simulation time - last_update_sim_time_ros_ = sim_time_ros; + // Update the robot simulation with the state of the gazebo model + robot_hw_sim_->read(sim_time_ros, sim_period); - // Update the robot simulation with the state of the gazebo model - robot_hw_sim_->readSim(sim_time_ros, sim_period); + // Compute the controller commands + controller_manager_->update(sim_time_ros, sim_period); + } - // Compute the controller commands - controller_manager_->update(sim_time_ros, sim_period); + // Update the gazebo model with the result of the controller + // computation + robot_hw_sim_->write(sim_time_ros, sim_time_ros - last_write_sim_time_ros_); + last_write_sim_time_ros_ = sim_time_ros; } - // Update the gazebo model with the result of the controller - // computation - robot_hw_sim_->writeSim(sim_time_ros, sim_time_ros - last_write_sim_time_ros_); - last_write_sim_time_ros_ = sim_time_ros; -} + // Called on world reset + void Reset() + { + // Reset timing variables to not pass negative update periods to controllers on world reset + last_update_sim_time_ros_ = ros::Time(); + last_write_sim_time_ros_ = ros::Time(); + } -// Called on world reset -void LWRHWSimPlugin::Reset() -{ - // Reset timing variables to not pass negative update periods to controllers on world reset - last_update_sim_time_ros_ = ros::Time(); - last_write_sim_time_ros_ = ros::Time(); -} +protected: -// Get the URDF XML from the parameter server -std::string LWRHWSimPlugin::getURDF(std::string param_name) const -{ - std::string urdf_string; + // Pointer to the model + gazebo::physics::ModelPtr parent_model_; + sdf::ElementPtr sdf_; - // search and wait for robot_description on param server - while (urdf_string.empty()) - { - std::string search_param_name; - if (model_nh_.searchParam(param_name, search_param_name)) - { - ROS_INFO_ONCE_NAMED("lwr_hw", "lwr_hw plugin is waiting for model" - " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str()); + // Pointer to the update event connection + gazebo::event::ConnectionPtr update_connection_; - model_nh_.getParam(search_param_name, urdf_string); - } - else - { - ROS_INFO_ONCE_NAMED("lwr_hw", "lwr_hw plugin is waiting for model" - " URDF in parameter [%s] on the ROS param server.", robot_description_.c_str()); + // Interface loader + // boost::shared_ptr > robot_hw_sim_loader_; - model_nh_.getParam(param_name, urdf_string); - } + // Node Handles + ros::NodeHandle model_nh_; // namespaces to robot name - usleep(100000); - } - ROS_DEBUG_STREAM_NAMED("lwr_hw", "Recieved urdf from param server, parsing..."); + // Strings + std::string robot_namespace_; - return urdf_string; -} + // Robot simulator interface + std::string robot_hw_sim_type_str_; + boost::shared_ptr robot_hw_sim_; -// Get Transmissions from the URDF -bool LWRHWSimPlugin::parseTransmissionsFromURDF(const std::string& urdf_string) -{ - transmission_interface::TransmissionParser::parse(urdf_string, transmissions_); + // Controller manager + boost::shared_ptr controller_manager_; - std::vector::iterator it = transmissions_.begin(); - for(; it != transmissions_.end(); ) - { - if (robot_namespace_.compare(it->robot_namespace_) != 0) - { - ROS_DEBUG_STREAM("lwr_hw_sim_plugin deleted transmission " << it->name_ << " because it is not in the same robotNamespace as this plugin. This might be normal in a multi-robot configuration though."); - it = transmissions_.erase(it); - } - else - { - ++it; - } - } - return true; -} + // Timing + ros::Duration control_period_; + ros::Time last_update_sim_time_ros_; + ros::Time last_write_sim_time_ros_; +}; // Register this plugin with the simulator GZ_REGISTER_MODEL_PLUGIN(LWRHWSimPlugin); + } // namespace diff --git a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch index 2cb4b65..a9b1ea9 100644 --- a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch +++ b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch @@ -29,6 +29,7 @@ + @@ -89,13 +90,9 @@ - - - - diff --git a/single_lwr_example/single_lwr_robot/config/joint_names.yaml b/single_lwr_example/single_lwr_robot/config/joint_names.yaml deleted file mode 100644 index 213369d..0000000 --- a/single_lwr_example/single_lwr_robot/config/joint_names.yaml +++ /dev/null @@ -1,8 +0,0 @@ -joints: - - lwr_0_joint - - lwr_1_joint - - lwr_2_joint - - lwr_3_joint - - lwr_4_joint - - lwr_5_joint - - lwr_6_joint \ No newline at end of file diff --git a/single_lwr_example/single_lwr_robot/config/lwr_hw.yaml b/single_lwr_example/single_lwr_robot/config/lwr_hw.yaml new file mode 100644 index 0000000..486704c --- /dev/null +++ b/single_lwr_example/single_lwr_robot/config/lwr_hw.yaml @@ -0,0 +1,3 @@ +lwr: + root: lwr_base_link + tip: lwr_7_link \ No newline at end of file From ef792ffa27889b8b7fe5d38fad998b1ab69f1804 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Sun, 5 Jul 2015 15:30:47 +0200 Subject: [PATCH 02/19] Update .gitignore to void QtCreator projects and typical build folders --- .gitignore | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/.gitignore b/.gitignore index b05a404..cd7a158 100644 --- a/.gitignore +++ b/.gitignore @@ -18,4 +18,11 @@ ros/kuka-lwr/lwr_moveit/default_warehouse_mongo_db/local.* ros/kuka_lwr/lwr_moveit/default_warehouse_mongo_db/mongod.lock ros/kuka_lwr/lwr_moveit/default_warehouse_mongo_db/journal/prealloc.* +# Kdev and QTcreator files *.kdev_include_paths +*.user + +# Typical build folders +build +BUILD +Build From 253a2d1ebd26666a5e70a02e2cdec6c95c5c2cd0 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Sun, 5 Jul 2015 15:37:04 +0200 Subject: [PATCH 03/19] [lwr_description] - A small fix in the name of the gazebo plugin. - Deleted unsused transmission, and robotNamespace tag I don't what I did with the urdf, I don't remember I touched it, perhaps only fixing indentations, but it gives me a lot of changes, and some not trivial. --- lwr_description/model/kuka_lwr.gazebo.xacro | 2 +- .../model/kuka_lwr.transmission.xacro | 7 - lwr_description/model/kuka_lwr.urdf.xacro | 746 +++++++++--------- 3 files changed, 374 insertions(+), 381 deletions(-) diff --git a/lwr_description/model/kuka_lwr.gazebo.xacro b/lwr_description/model/kuka_lwr.gazebo.xacro index 07dba79..0ad8a05 100644 --- a/lwr_description/model/kuka_lwr.gazebo.xacro +++ b/lwr_description/model/kuka_lwr.gazebo.xacro @@ -4,7 +4,7 @@ - + ${name} diff --git a/lwr_description/model/kuka_lwr.transmission.xacro b/lwr_description/model/kuka_lwr.transmission.xacro index 4ea70d4..d042848 100644 --- a/lwr_description/model/kuka_lwr.transmission.xacro +++ b/lwr_description/model/kuka_lwr.transmission.xacro @@ -8,7 +8,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} @@ -20,7 +19,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} @@ -32,7 +30,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} @@ -44,7 +41,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} @@ -56,7 +52,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} @@ -68,7 +63,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} @@ -80,7 +74,6 @@ - ${name} transmission_interface/SimpleTransmission ${Interface10} diff --git a/lwr_description/model/kuka_lwr.urdf.xacro b/lwr_description/model/kuka_lwr.urdf.xacro index 0414647..39e7cba 100755 --- a/lwr_description/model/kuka_lwr.urdf.xacro +++ b/lwr_description/model/kuka_lwr.urdf.xacro @@ -23,390 +23,390 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - - - - - - - - - - - - - + + + + + From b5689f0ee7fd0df545522987387b82af00b27dbb Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Sun, 5 Jul 2015 15:46:33 +0200 Subject: [PATCH 04/19] [lwr_hw] A lot of changes, hope for the sake of good! One class to define the robot: lwr_hw The class parses urdf, transmission, register interfaces, everything that has to do with the abstraction of the arm, only dependencies to ros-controls. With 3 pure virtual functions init(), read() and write() to implement different hooks FRI, Gazebo, Vrep, etc. Now lwr_hw_real and lwr_hw_sim only implements those 3 functions, and in the lwr_hw_real, also the doSwitch() to chain the switch to FRI/KRL. Hence, no more different KRL script, only one that manages the switch. The lwr_hw_real_node is almost untouched, but still one pending issue to solve, getting the node namespace should be clean, it adds "//" that need to be removed. The lwr_hw_sim_plugin is merely a gazebo model plugin that instantiate the lwr_hw_sim plugin, so no more different robot interfaces, this is the lwr 4+ plugin. Added a document that explains how KRC/KRL works for reference. Questions? --- lwr_hw/CMakeLists.txt | 15 +- lwr_hw/README.md | 19 +- .../KUKA_FRI_from_WS_Proceedings_ICRA2010.pdf | Bin 0 -> 485234 bytes lwr_hw/include/lwr_hw/lwr_hw.h | 54 ++- lwr_hw/include/lwr_hw/lwr_hw_real.hpp | 213 ++++++--- lwr_hw/include/lwr_hw/lwr_hw_sim.hpp | 19 +- .../{ros_impedance.dat => ros_control.dat} | 38 +- lwr_hw/krl/ros_control.src | 194 ++++++++ lwr_hw/krl/ros_impedance.src | 73 --- lwr_hw/krl/ros_monitor.dat | 20 - lwr_hw/krl/ros_monitor.src | 77 --- lwr_hw/krl/ros_position.dat | 20 - lwr_hw/krl/ros_position.src | 49 -- lwr_hw/package.xml | 10 +- lwr_hw/src/fri/friremote.cpp | 2 +- lwr_hw/src/lwr_hw.cpp | 315 +++++++------ lwr_hw/src/lwr_hw.cpp.autosave | 443 ++++++++++++++++++ lwr_hw/src/lwr_hw_real_node.cpp | 41 +- lwr_hw/src/lwr_hw_sim_plugin.cpp | 110 +++-- 19 files changed, 1172 insertions(+), 540 deletions(-) create mode 100644 lwr_hw/doc/KUKA_FRI_from_WS_Proceedings_ICRA2010.pdf rename lwr_hw/krl/{ros_impedance.dat => ros_control.dat} (97%) create mode 100644 lwr_hw/krl/ros_control.src delete mode 100644 lwr_hw/krl/ros_impedance.src delete mode 100644 lwr_hw/krl/ros_monitor.dat delete mode 100644 lwr_hw/krl/ros_monitor.src delete mode 100644 lwr_hw/krl/ros_position.dat delete mode 100644 lwr_hw/krl/ros_position.src create mode 100644 lwr_hw/src/lwr_hw.cpp.autosave diff --git a/lwr_hw/CMakeLists.txt b/lwr_hw/CMakeLists.txt index 13a50bc..3a5bcd2 100644 --- a/lwr_hw/CMakeLists.txt +++ b/lwr_hw/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(catkin REQUIRED COMPONENTS pluginlib kdl_parser transmission_interface + gazebo_ros ) # Depend on system install of Gazebo @@ -27,11 +28,22 @@ add_definitions (-fpermissive -std=c++11) catkin_package( CATKIN_DEPENDS - roscpp + control_toolbox + controller_interface controller_manager + hardware_interface + realtime_tools + joint_limits_interface + roscpp + tf + urdf + cmake_modules pluginlib kdl_parser + transmission_interface + gazebo_ros INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} lwr_hw_sim_plugin friremote DEPENDS gazebo ) @@ -48,6 +60,7 @@ link_directories(${GAZEBO_LIBRARY_DIRS}) ## LWR HW BASE CLASS TO RULE'EM ALL add_library(${PROJECT_NAME} + include/${PROJECT_NAME}/lwr_hw.h src/lwr_hw.cpp ) target_link_libraries(${PROJECT_NAME} diff --git a/lwr_hw/README.md b/lwr_hw/README.md index ed14745..94a7d90 100644 --- a/lwr_hw/README.md +++ b/lwr_hw/README.md @@ -4,19 +4,18 @@ This package acts much like a driver. It creates a hardware interface to the rea ## What to do to run a real LWR 4+ -1. Load the script [`lwr_hw/krl/ros_control.src`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/lwr_hw/krl/ros_control.src) and the corresponding [`.dat`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/lwr_hw/krl/ros_control.src) on the robot. +1. Load the script [`lwr_hw/krl/ros_control.src`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/lwr_hw/krl/ros_control.src) and the corresponding [`.dat`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/lwr_hw/krl/ros_control.src) on the robot. 2. Place the robot in a position where the joints 1 and 3 are as bent as possible (at least 45 degrees) to avoid the "__FRI interpolation error__". A good way to check this is to go to gravity compensation, and see if the robot enters succesfully in that mode. 3. Set the robot in __Position__ control. -4. Start the script with the grey and green buttons; the scripts stops at a point and should be started again by releasing and pressing again the green button. You can also use the script in semi-automatic mode. -5. Once the script reaches the loop where it waits for commands, and then, you can proceed to launch your hardware interface + controllers + anything on top of it, e.g. moveit. +4. Start the ROS node, it will wait until the robot goes in Monitor mode to avoid loosing UDP packages. ROS controllers will not start until the handshake is done. +5. Start the script with the grey and green buttons; the scripts stops at a point and should be started again by releasing and pressing again the green button. You can also use the script in semi-automatic mode. +6. From this point on, you can manage/start/stop/run/switch controllers from ROS, and depending on which interface they use, the switch in the KRC unit is done automatically. Everytime there is a switch of interface, it might take a while to get the controllers running again. If the controllers use the same interface, the switch is done only in ROS, which is faster. ### Gravity compensation (ToDo: revise this procedure after the merge) -In this mode the robot can be moved manually, while the position of each joint is available in TF (__IMPORTANT__: due to the robot own software policies, this mode is only available in T1). This mode can be very useful for calibration, tracking, or teaching. -1. Load the script [`lwr_hw/krl/ros_monitor.src`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/lwr_hw/krl/ros_monitor.src) and the corresponding [`.dat`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/lwr_hw/krl/ros_monitor.dat) on the robot. -2. Set the robot in __Position__ control (it will be changed to __Gravity Compensation__ inside the script). -3. Start the script with the grey and green buttons; the scripts stops at a point and should be started again by releasing and pressing again the green button (you can also use the script in automatic mode) -4. The script should reach the loop where it waits for commands -5. Launch the hardware interface. -6. Start the publisher node with 'roslaunch lwr_launch state_publisher.launch' +In this mode the robot can be moved manually, while the position of each joint is available in TF (__IMPORTANT__: due to the robot own software policies, this mode is only available in T1). This mode can be very useful for calibration, tracking, or teaching. + +A hack to avoid stopping everything is to use the joint impedance interface and set all FRI values to zero such that only the gravity term computed internally is sent to the robot. Note that, FRI is command mode during the operation. + +To do this, you need to load our [gravity compensation controller](), and then switch to it in ROS as with any other controller. diff --git a/lwr_hw/doc/KUKA_FRI_from_WS_Proceedings_ICRA2010.pdf b/lwr_hw/doc/KUKA_FRI_from_WS_Proceedings_ICRA2010.pdf new file mode 100644 index 0000000000000000000000000000000000000000..49fb876e9c868756666a6917aea4273086ac1599 GIT binary patch literal 485234 zcmZsBb980P*KKUuwv!XvwrzH7+w7Pf+qP|Y$F|Y2U*8|z``*1@{Z)IOs#UAznseoW048=lMp-L6Gb1M}FEdjj zW=1h0W@c7aR%S+7B34c|762=wJP`+@0ueiaQS}c3;Ns-q=Z815GyM|>p6Krb9>&AT z%=}*`0XX1cnEo@E*@^x&BeMH1#tdL(`3Lq_Mt@(&%EbB)j12(z2gc6K_79Bnf7#0g z`1`pmZ0!G7$HLCU`S&weIGCCL5ct>lzxQC_VE@P6SU8!O|9%Dl!19lH0KgxD{}vAb zU}O0^2LJ#&C+9!bak2b8zdww!{hccSD+l{OFg9j(=D)>bW#(l0`#M&Zf9Cw>2msgL z_X1e|7mSVd@A;x}9)_G;OhFtT=6`zgk0bw3`XBGhn%P;nSQ4=Sm>I>bY+THo7{zUjT+BqxOzcg~ z7*&Y=7=oYQ*~Q7s$o7w)*NhDf4S`7*A=Dut`tcxyAi$8oqUu4+xcD2=PnmR)Ejyit z_Y4GdW;-jrv9M}-bhFw6fZ-j$?z|{R-yLA}Gj);(KH_N|%{o*n)K(r$ir>IerQ~Rp zF6sTKPB~o9N84ZMGi_y#oeF5<+UzJf56xV<4w?z&0pG4{uX-}jan=HXB!4W;LBU}# z=&rh`}vq z6k=as^8+r7jm*t07F1Wp@}`X^>VkJ4K4YUG`^|yDuz+^P+|S@){*1ovA1B9GjlOA{WB+G`y)>x<^R_j+5gD@KYWYW z+qsz8xi}NC|B=#v1N;?|QPIfh&kz3%tZeV{rwl|)e}bA?8425a=={~M+5a>X4lWiw zMiD1_hkt;|X3qAmP9}e{`^)G5UjlzU|2uv0KMDL%r#L4O`=93W*CIwu1>r%to$O6i%v^LB|GYXFRn0tH{?gZf3HdAie@Fa}gqT^F{uc@TPw@a$nSg{v zz+w4RKt;gyNKyG@WMo1QbZdkeMDjuyBoT^0zC%fYyymorVZboF=mt7i=EWlF}E=-Nd5|hdGuk}hhXi} zt)Vc1+79Sv{1Q;vVR{C|-5 zmw5g^@>l?D?5zI_eT@Gmmzju}i<9d=4=hA1EUfG-|9Sc&t^dh!RjRYg!R*r2zG-5l zt+(-d&WgDN>UxVUCF(jmMT@P4@&1wfjPLA}_f@aEYpwprYP0oqX->tfTN26y^#T-@ z7A}xzbv2$PmL)bPbVw08)(JG0<>@JSzLZqx1<)&k`I7p;D*})_2m}IxIEYd}|8d$Z z2PG_k5|)&eIxxODwlX^-vK$mR6zNbv$_5N16^I8Q;!6u+&Bu{N|cIFK`eV2Lb_Yx=u^`h0u&B0lepj^@_Z96QnZRQV(< z{LD4-l>xvme`OikTJ4_z)se=xu!F2};}UnNt~>83PmL zeYuZK>HnMpHzcz-GPIO7tg<&keAd7-G`rs>;m>|c1LKB9X0u`@KJ&jm?HxI|pRU47 z*0udqdB{ERXC5T{bQztQ3KdNHT+|Pn9hzPK@>%?>)hAI8TM{={rvQtgs{(sk`}X;NQ8$W?*j=es3iYH11nv=GtKf;s{Fg#O6VggycL zLc#^ko+C7-%tQS|WcC5+8xZ=MWr76G9`lcg%?XgdNAxw1{vZ|y;l33Zx<6eYG^WT) zdKbyvEBc%(ZM*hAQTcIC_=-k(7tY^2_8Gn+&^-2$KYIn^f6~~wNBDYCb05y%N&EE& zqWKFt^FO&WT>Nm{yR%z3#q}fT`Vvj&|8=Uf=A)1EG28f?aFoCEl;@rLcZTUrIDa(O zXE>HXnqis!ljr^?<-qR@TT9zpjgX9&+=${s1K|^a(vQ>8zGv#iF*rlWI*!IK)DPXX zgyvxIzOAi`+KgPDM~ScF@q)J}vzPCW{v)>d0@qi$)VU)#U;VRS`@QimgzuI80^|Pi zp{Il{ua)}(`%7_d{wZIw%r7Qm$6M(@7jyz2taZ=U%(*q`E2m#-5rLnLji-c3{Kpv` zYv~|WpA*k9AKmw}!9xg{UZumU{q-6ylQ4e!?TxnW<;61ghXQ&pcRci(B3{D*wx zTRsg2b1Pe30Pk8;;@b#@X249J`@Dd`uh_MZT6m*R)eq0Usj9Cv`!Iz`o38-{%1@T$ zUFTK*A0{t9jS=fu-?lBH4s-DW77gs`eK6|3d{{q9ua9vq>F+P)zG&X555F^|Ds&^1 zxCQh+K050m%q;oKJy-2MWBO@d+++IDIDek+_{_MyzzR%ueum~EbbKH`X^q1hK3%JS zU6X1n&aDk+hux~|9z%WzEQbaM1g8w%`J3TzulZ(P-qafO%~F1R)zz;aUxNVcfG~yV z>({X#z%VJ;!O`5JjOWsTmx5rhT16$4pXXc#+!{oIw@~3FG!(Cusd+QVh=lO~3G})9 z4Ywd#KgAPbeq37PCb4|^?G(AkA1wt{yJb^ccG!#D@A$)PFLAnikATqeG%{-^=IJxV zdvbYX(n=6lxj?mxL;Wl~RozY^=$j~^$TZK#!_$-*5iJXdH`YNJ!0Wn-iAREL;Xl1L zBY^uQ+wEnxc@=U012F~ltL7m9C)RQ$ZnmgSB(%U`%w1gkZvLw>N+7#WbUtne z$Ol~7NOV8|maB|r5ne{r{T0Pmm`rr-^rx$$I4|sF{rW zD$}@rZT|U?=sGGc`m|u+UuYn5)q}Fj%w9#P+uV4FNbv#bf>Soq2=t3lSUl`!2Zklb z6Pa&C{O6V8a(Y9B$AlXDZ4L$19`dN<_BMYxxn$16I=7m)f)|2=@r}c ze3_TmHR)%6FO2G@HrRPzG#MZP)3w|HUb*lcWJ3+o8rK+NA2gmnu(rtA80wxX3+p&S zkYl{~REWPO76%#|rN*tg7ZNPh+e5rwQ%yO%w|3PyGc0tf%+FpijS$*_wHuyXK&? zy5M`}+LRDWJRT}Zu}TRoN1S1es9gpEPF$2TC+S4?_i!5cyO|72>Dg^v&Hb z&0P>XoRs_=l^rDJryL%DAI^>1Y#TyV6qGD;jFPYniw~80L_hLX1s>M;xA5j43Ku_u zDcg``bjz{wH{5f_wU>E&fPMzJ?2#-IoOZe3-0_h;uDjbvEq===G`bXu0tOF|5ynFPbN1RB3vAT~Dnu0Y zr(SG*k@3bO?-rp@laxm};&seu{gZ0Vbzf145f2tNwlhdmN^?Y_=14Igu0r5PmE)$V zHHaEyZ*9sw?=K0AzYE)L7y%B4j*GUcBw)C`Z+_qJ1wsOHfZ04fx zdX!q6Db&{8N*fXUT)LU%ZP^f_9PDs>pH0TmW&H~#X)5`?*g>v$Uu&)TK|C-P9`y}+ z_)>zJfr;NEz+;ir8YP`{8(srmi!^ATz}E-fw8VmwQf<=<&yGa9i@j4Uh)*x37XpZ{ z-Ou`9vu4|pIkOLG(C;IIK`v?i!L&LF50=w4t_6W-ppv0Y8E^S=QXVfoX;Q4Fau1_S zk!k0+^2woWkcG&bcNQ2oXDX^E#h+46oqu^!uerj&T3Ckg(RO!Cctk(tbi7v}tIL04 z-6<=X*igE=ADOlb|G+Nb3;L;3VG@UO073;QJ7gA3b+fo=U4=zRO|m3PpWNy`v? zz@vN9Uw~Um;uZMy?K0e^$-9s*e31=h!a&@}#j|>OL-H9AMPTYq)#X%yUq-f5y>wT8 zor8pn$;f*I0@jaj1O2hy@nSbdkSap^miwfE9uGV|?hUcZL&|zDvbVG3c@lACT@LH( zZ8)opX3&F(&ytKonWN2T+{<;_Su{`Cz!-LszIK7EnLuuD+wNI9spBejc1CV{MEuJk zex2F&x}`29eI<_8sV6}+$iUndu!#8KV{`UuH=&~cLo?aCjCzmFn?JX-`ZukaHzGfp zKU#9jTk>M?RQ?QWC;{1YkFucW z;RZaEtTCWe6kSt|pWK>A?_we2!aP>rC&i6o>!sq*+7tVuRqW2GN%JJJk9~Z6I`Xk| zB>Khqi1eUa!Ze=KYpkz;?RU2wiJw02ILQV1^r@e1b~;V#bvR7{qX6yd{=_cLZ3Of>5(=mKrB}r5g6$q+d)~b6$kGt-$nZldy-t7)foJNV8v4CVqL-d z1&swiph_J1_hut8$0KX9jNpR7k!P&J=gs170{2zIP7ZQKOoaAv>Kz^&2A4T#8(PW9 z4p+#?7EjFFL@h>b^weY*mTyz3g@(Ph_F#jd#D!M3()$%x$p{YKrsp?kf-9{Slj(4d zFOGV;;lcOP&4`>N0}rJRk(4H5)MBeG0cGjC=A!?wBIZpzAorC=vJdeIL8s|JL>KPS|U~B5h z&v78ZpE)>!uy#Dw;Y#!NDn+mQ#zkTYL|0vb@kFj`gvFe_j#y#m1#h;H0xAw=ye3GI zoEvYox>xt?NZyeu2VP}=4D+h0R~HcE-mGXflnF^vMOJR)v#%_$H0G;9~~@&Cr`1a+)3+Vs28`mOjBHYU=6g_T{!&0p;@m%H56n+GzFLkwSRjOol{Lu z$aQp^ke&V*?RcBy#=jEsh{0Xl+2t>L)EEfmCkAK9P)^!-Yh^Z5W}=;Bs#HwLm@s_~ zNopI5)&1pD+*fs94U15CNB~f16CWgPopQ=x3sW-&&Hdh{HJmX5g)zSMfdLNf%2|Qe zi7OdOY!WLIetOg2@x$;w4_%tMHKSoEx%yj7Yc9$CrByHG(xUa^;Vw>pql&wg*Ib+a z`j@D98( z9s$;yqqzq7hiQaa0dbA}k{u-j!uMpB8jpt|vD>=aTOdC;v(aIi&<`m%ADGiUKlt_> zJG!$xP*z&e;IpujxU(|zJ5xQoXo5zQC`*Jg;R$d=n$A7b$x0)6ZlTF*NVm{l3^|YV zk_B6ETr&nKih=7IBC>X>uY=HXOe~aSx+r;3K{Uqr{c-i!mo&_>n4KXy-X{iz-mBHq z2f`fK&Th$4C=4heJY?9{ddzb$C{6b~Omx_$sGtz6gl{ZS!f=elh`z}_K~+UDgk6cGYG|f@IJjB9)zeCNrDP?D9>vw_Z6XWDt(uI zPGJ>gYDJ2G>Rts+Mz*R^xqdfj(OY?b*u*^>P?(1-AHq_0@{$<4fNRrJdgwUl=xKFw z)jY|aTIldn*@@fX4$=L_#!*1qs76Pp{+*NI34FGi)%a%ca8iWe z+y+I1M@{EvMudYTVUtrvsOXOk4|og45JI%@p_=blP+Wq}P1fD{(Y~SZ zME2G1tF2Q=TgqluX3qq_O}!ZIBT~RhDkhJEJu2+&Du`mWBP`^d-!r3lHO)kD2MU_d zBv3$R1dV~Vy|8NQd6AuVm*7aZqzUO>t=vC*6@?~gjqWHonH&)7(^@7zLy9dqd#tRn zzx-aPg$m}IRYCpLq#nb1(HK1PEBt3;UH;G4^xNi4l@YTX3VfH_OpLtX-5o~>H7 zb{s=L-tSEvu`e^Ej;OiNqoOV|^yh)88<$MLBQ_p0E44UV-9-J=g);Br2WfShY6ZtS zEv&RMI#B!P46y;2szvjc;-3CVmG1b1K_RD%aYU`;=*n3@>l|#5%wyu`hZnQ(ym_on z82i7}Gpg^$S}>ml(}5PDexTK?!tnK}uXFw`rWB91zSQdJ9B;EeIH4fbAh%IenkxQQt0VlFxD<-JF0F9AuP*Cvi$RH|j(Q7stE? z;=nEenY6RRj0iE8{|+5|<&3uptre$&(1R8wN!XpE2(6a}>31^!5fYJG@xYH{Sy)-| zs)5kli+CA|q3N-8tGn6Fp3ZA54^kOZ{yH)=A@W*?R+C2GOp{8ctquFefk`3D1m(NSA!xsUs*L;C;!oFHC*0 z@Hn0%dxhB>Uf>(Q) z0!c>#8sfR8ZczWi7)&_baCk-e2!x8Shvva%D1hANz(Z(qZ3qD|{_nxtoD5&O6F5ru zJ{g>8)E{@O@_A@bmiL};mQ@ehMT_vI8NSPHXz`*L9jQ>1nWngB?gU>35#QZJe7|&832>Fn1!>?bX zgZP1~B@Lkxq(|B+$ObRHj# z0#j}z16oqwcWkX)%IFrz_u?~T+F-BV>^bNjBeb_~Ko!sxhS}d?2=arSxhm#TDB-@v z1Gby_Vr2+7UrD9h2qLr`DPct0r*@(>YVwP+EYh;3B_=8G%>mhPzuep`?qzbBzBr`r zwKa?>IOA`3sDiV=HwO_rq)F`?B@YPZz5m4081jT6Du7xsYwDD`_>Q9w{hweuI-pd2!Df{0>2uNQjF!qHe+)r866&30hyd5g*i)6IybL0quz!SL0}-o%QrplHug>k@ulD`fGO6ki3rk3k zkI&^Z8o{{r>)z~?N8Nl&H;CDG}dYa zu;FRKw%uj9XImN~c3^S`;*tG8c{e;>DlQ%FBXvFo!>1;S@>_YSy|4YlT^neOs9`%= zyStGsLJk}WpCD@9 z;DWE#X>~Cx#Zn9!Kke@F8u?nUo;m4Xuz(yEr+9n|)wwmLX8cL0 zQ}~5vJ&idE(6uw;G;kr22oir%gGhF!gZ05iP_0_b7@C=Az&U`jFHk|hWSx>jNF@$L z|2ogev}XtL5S_0^ky1|cI+X)_l+ti>j*h_+HIXN+v#6DqDT7F0>L-1N)X0X+SXvOY zsAYW1=wRFZ-l=C2sLYp4l)ddZ`;#%2mx7VHxX8Byoz41?7ta;04ttLbZ?sV;1<}Dz zqzkvvwm33mj}EL>zbL?9+vH5WMQ<@>ad6zU2}BwnBpYz@tflS0!XD!It3GVU$D5Ll ze$O9kG3yL|z{kq+M?^jRY0*gEeO*0=20Vi(PeJ2naW1E9@dNup1wL>`c%jVMxK9hY z=N%J?UT6tU?6cu*6{|(Ce8|=CQTHj-4+pPjCJ(}&qEb$n%mLdo$8jL%d1$-J1n?5) zIWuJ}y>Hep(!E+L0<`ZX{R%8P7S1hPLhVDbG+gL}#Ij8CWJeysNI?%AcB?*Lt)}{Y zgQiR9uaB=hD{JOPvhl{5G!KxI!y`Rspnkp_z|}8ip8mE;%~Z+#t`JxoVjvlQp;O=k z?LTPFj>K#$zsKGB8aj}Oy8u0pc(&&_Ey0SFW33`88}7Cj&|AVnmg|}Y$h7hKZ3-@= z1#Zq$;Ba^kGEm)uh&{y&ZJS-hC3zlBxO7XAxJ`9Gc>I12#uYQ@2bD@T;#BUlR*quL7IC!q^X)6DoKsS5WJ0zZ1?^}B|<0@m^H zTz(bebDq{#|6?~8pE`w>{j1Wif@DNT4;Qg}{NDXl0-{00Ny=sYERWMdU${$ZN%2=P zVKl=2IdBVd0M~?`E~)?b!+d+~-tQsR2x?l(u(!AoPY=qGi~cs>R3Em%eEoxuyMbC& zj_PnFo%s%$qlbNX8*5U_w7aW(ptIW6+sbv9@KZ2J>sLHZjF?o_Il&%l zzNUSn1clmQhE0(s`4vI49am86x!oq$>fe`m`sUy1Io771YUPDB<0A%YV@zRD)#N9| z{Sy_?z1j@raN4FHo>rfxT4d}fDYJ{GZU>ad0FZane{;`Kk0oRFABJypDH%9ZClCSN zJ-DsD^giMzj=OFV_J`0FTf?a~5jrw)wtlSkZjshEAb|E&Wurz-9qrkMzqlB_a^*{q zZc|E$OuS$UXoWvpW4}+zMc~oY-(nUMJ9tgfwGu??UBUWpnk#%)sVPoS4z??32!#bR zB2&K5<6!ETJ%O@uQe!F|U|8=w)WuoK4?-dY2I@d`xy_2C>8FLvkuK5N?XVA9Sz344 z+Pbi}9&V06Kj^Qu=3tls&u#Fd?}gpZZMKky&oZc0Wt{j$j>hNkciL-DQ(7uXcxkVJ zxZt$31e8yiNXuk=R+NHn@nWZ(Y>1O{NN{fgc=jE`HE?@Y_Ta63Nua0oJ=A2E#VwJ; zPL7LhlP2s_148pVaxS+5tzi|i#WVL4Z_H|3CbQFG$!`b9P$$ZSB=53~-A7`^x*uRb zrcTayZ$&0krTWQ3(C$b4K1d?y*AQ|xa<0)xtZ6Sr8L%|DI=T3#k;RTsKJhl2nXG?N zLaJtk^>l6DP4?7qwCRlhdKg%NX$0X5J)AzDR&nAWnI!v>wxzA2mR#lZwc^Z(dr7bo z7`Uq<9pB*;wdw+_UqsWcfg&{gE*yU;UpmKQP0Y(w-?f|uqo(4~bZ?try273%1>~Yy zbv+c4sTElhopJ?@Oy5wpage{%8nZBptMZr%^21zSIeMTq+$5wg$SY9w*10!r!?9NN zxY^hWk_`W?tgFL&al)E~I}&jznWkYNVGF%x9Cx-YJ0SR(iyNCZ7<6=-!wTgpq>Ed^ z9O>;EvYnvTsPP5jDNXYu!7=6b$pCTILJEA$)$!8Y!Xor8=Ht0gz8z~+QXw`whbJ~> zCt#*6S;v48r;x*HMb*>lxJx5Uv(k#SJ4 zdDfsBT7qt{!fl+9$u}Iq?!#r>dC5of{>;cA^wAf}Ml1_Pg0y%qohzK7?Y*Dcn(Wo6 zNz+Q@e9U7$c1iFE;_*pL=tb3SLSDgi2p><&>?PYJ#T zLWae+h#TD*WTxf%^5>AY5m=MUYo48mf~KvV)C@{`6SfWu^roV9Epg&9KhT-M)ict! zix{m}uQt69xHGT-oFKqJMlgOomGO0JWQAZSZW>?0#DVfK9i~hZonLgdrp}K{z#Q!l zBsD&i3iuNGvC7KtTIZ94JZG4<4!3kivQ$C1$>VF&R?@Kd6pF<`uUv2^AnVU{a#=v5 z=35Vkn~qh+LT((JU>43bK~`nRpXvnWbumfmM}Uxbpc%_Z>k3JvyqhUs^!1MLy&5Po zE&UZ2y-EI3yeBHCb_b&MoRmn2k zG)BT<&n-rN6t^?2y-}E`wpQrImn;lnF(mF5cd##A8Lq|0w(A;_<$6%gdV-aEG-cIF zyh=VStwV6zjxpZ@T3+r1Cg*jne!9tD7`qdIPu%Wmh2|{Ur5YG$xW$x7vhqElY8ClO z<7=qDlHsdT!jv_9`7rabBQbOmQh|2_*h2xX_cI74%UEdP``!+5;HotU9P}x+} z5&$QMP+4|tI|*u&;#wEGQ?bi{|M>9G){79VPrf4PSyHVB!J$EKjxe594#BGxCcB+K z0st3oPOW~o`@F3Xu*JvzA^Rj7L2brcidD8`*M3yWl@5~chpCIn*(?h)FTSaHMuNY| zn2rk1niR+zB67@zpN2#ndUG=zfRPJn9vq)b$m?Ey7F0Z)5r9_<9Ink*@=N~9*2g|e z?`hz7nhfIXQg&g^S$f6>$9DqiQ>Tf0+;zevGa4`EhT8G57CD3Uas&|)N?TvIcX)}>SI98<|%1}Mc`PAnrREzGsek@`>>#y`p zX0SsG7}W)Sw(`WALfZ(F^@YPJYxZ7|0lD^49(~C_{B2%*^U^v(@PRwC+o0y?LKmvC zd8q?>dX^Gdt0GeSCXw}fxVpi<$0xd>Jea&aJ|d7sD$d^tPabVMw|zAmqCw?rVv>zdsQe3Q+Hp&fbjS(|6|5vZ+}d#f{%%aO$&sU1}`Tp3%0w z)`F96e5SdcSqpyVrEz%L2GHf#jNlbYWEz(Uji1sJ6B$6PDKRK*p_rCjoLO|7>5OK} zMPR||-Ig%m;o8D7)K|-NWx>f8Z|Ua`M#ehF*jnUNxnPA3hfF2n3E`}3Ks#^asxk9K z8$sp~(-z}-K}^8UR6cdl?(;k1P<$34{L z+Ik`|D_%2vC-}|c(N=I`N%6TYvi>_s_hGVG%2om>Cv=#tS$L{C!5ME^nzSnyBPra z^UMVGse{CHyljoL%JrMKF+*_!Z(lYxUQA2;$i`6LnM$jln~dNcXkhTSiWe+=a^I#% zVRqgb>Y)yqFwS>9ZCjpjrmILQB_iy2#U?M)G6yl=I~&`z$l8t;Lk#c^4s}Tx{3?-b zj{=~exT#_#`+4#fbQ}2O@WwJPz2@W{j?j0beU>>;$Gd3d+{I;yk_Yxys;TeXYvV4K z?V&h|N@*>8;hs%`8G^R1PJn}4Zhnmk?JCv_#M%;-S+kSl4Ssi%k#`xvT+Zz{mWDM* zxhf_msM~Z%2>Utf_o0rOJF<}w7x`!zf);gqHO;fJE?V{H&oOW}ddB1qAiHtkm5|&L zuuFmsR36@e5;a+}#TeEPjueP388nq@$T%UAzzfQGzXY329{Bbjcc9Yr6A`7OW~IaH z?c;_6ce833rS=IEqQwU(hPau_WXe7&7UBf8!&n~((khPzdf6`3%;vtTCr=o> zjfaTKir-6{!a&jvW94rQ@%IYU1ue$g5BnKCKl}P`1?2%uSl}2n$+dfXZH@*PXTGWK zjUk};Pz`>vNo`;<*hEhXnvs1e1297HRVI~cZ-?%n+B{R+{?(VI(L3YnDcvVoiW0^i zSx_n^f%>+&)=y5^+XPE;WApywEpED^Q5fmvzBXh~TKU2dy)=uXld=uO*q{4rlYx@oWQ<<$AVN;q)1_U3%P{f_pO9ev~X zcArrS7=Cb$>oNIQ(!D;DTV}qBdPD4Phdmf$j7Cb1skcu|Nj+q7mY^P&#=J9PeE!xD zjD44QE#iy55G8@WBB}~(52_yWsdMv_t4iM;`GFQ7vJ7TV`}wQE_5GNz;e4`_mH8Z_ z?JB;+vY<^~s5hm2wJNT!wa8t7j5JSwi?^oAqxOBO!=I4p=z*mVRt~=wX}!y9oN>Be zdL#d0vx_Kat~34+%4rh0GQ8LtoSHs&xNM;5ypBic}-sPbbgSu%zbRPUxV+fCtm*(L5IVUt$H zf&NS)v8bY1b-Oshz)w=V+lLC0$jc(eZe-KbMy~kM>aPg?)**i56A>fUDC3oHB~Gg^ z^(lMeC#S9F{&Z;d6;KO!Ctcx0NM{=Ey2JR8*}rB`(DNCU759b247q>J6!Rb0+OsY@ zBjwa@s~79+70@n59PDzsNB6I3)rr(CQJKj!eXIMn)1* zZlO($I#PHQqD#K~fMX3aQB{ z5sA8(7G5_g_VdDl%hB((R>&n3BSzI9Z>IfnXLt^T-2Eo{_ANVHQe#4uo-&|as!y9vpD|OReRVs_ zfi)?xu_d$s!r3ZT1|Crb*mTw?rPyOSUrc@Yu*Q4aIp17{VJ?}u+sHWDM!(W4g`Q$y zYZX27K+2*`#;8|m$A5x@EP0BYP2NZ``l zq6;s7M>+I$)bM)@MC+OZe6g2qe!W2~m!X)oVI7f-%Le1_8~*bvCTH1H^32hSn4d@k z?k}2n7A>QSk6z8cfQDa`HxIuZ(DJsDgXsgj4Ew5nFq+kgUSP)oq~i&#dNIgW_PtWu z2*9W@YH$Zg7`rpN=*wx7k1QZ#(ihY9f=^2)qY`#pv_AP3d=Mi{BRBdqb_o_}SEVR{ z9F8RlS@vA;R5Mtpi)?fZ`vmNR(_Z6{{A#! zO{_a28QN7jWF}kzRc<8H$B=eu+FPWM)WSx8jcl|dWzF-rUTB#wv{vRWh0YSP=$-)W zjW!NEB%MLkw&2jxk)FW{F4@Q%Q)$WUC+MwbJ}QKbun6M5YF33jz^be1Nh=V8Oh!;r zCrr+m<+!xrSIlajn=N9j@bRIWN^b()b}FfEE8f51)jltZY=Z_|#VSto=2T&nIZ{pk z)*;isAr<{-wvX4v$M{L#S_f|q=|J5{zX10h_3w2sWcZL}II zOgvbJ^(h+zp)o|!YbA^-6ZGMl7Yo$h|B-f6k$=kl&D%i9v=<#OgqdrcS5oDZn!vW@ z+km1)X-;j1^dJSCSY*pv0Y9EkJBf2SJRPU&PaW9`TW)uaP_&QP^2F{Eyw)tqr19D( zb3#5b+x_&^@PeY=q+iN+*-12YQ`h%sm_=IZ_>O2VdKN|Z>^<@pl~c#R;or}Oa_D1R z)jD{@oHL9)q-Xma$QFi|OeS3NozM4w9_;jbX&YBNv}s5qnCs)M_&oM$!tafO3PN9n zQ1!clgEC4;UYi}bnVUs0#Rw=-?As8f^_K4u(WkR?*gM#R*oh`OW=Y}+5EME_-K(;A zBVzj~>C&W9Z7?@>2mk1WBkR7TGMwAq;kCzh^94vagz2EGD~PU{viHpZEv_Yq&W!PNnJmctxJV%*w%n*OS+uWV27+;WbdTWQjE7OXV{q zP2FB#)mA8Dn^dr!Ea)n+qNGew-X-5IlBZpeDtfbjmE>P>;?SO=Q^j^<a3Dl>N(UWSSw-Bx1T{seT*ADfj4YI<0LEbL8XvAPhJxN;y{s(VASG!`vz(I`^*%6 za<&1CABE<9gr{d$2kZ!Hy5yH03iR=?IjQh51f>)V~OkX!s&Uu3tcxJ6iorLwfu_x||Z{Y;U*ie&tX|zDJ zwlq&^E1@@I|2+Ns!p%hRigEUE$- z3In)xICK1o`iaPmpU;Sn?KqmRP%|n+_B1*Y8{81jlC`Qf4qaL4qpLrp?n+4wCJ=mQ zqNMk^0p9UN@DN94y05vcEN_~fi`rd~dXJ-vTt3kX>KMG`{=+(hLdX<@(9O$^v|?HJ z%UiVhGnKvDo^O*yRhp-tl17DW*lYItl^;wyUXsd{F7o}G#r zWC%*7No*{doif3mOazZ5zR7Qy+~0hNRuWf*)}~b?UvPT_l&0TJi@r;r>un1B}8-lS>v!*pwr2nzwHL2ooFac8LtpubXu;kSh z%rb_=2}~LGm_ei8I)Pm~lSJX8k#^By8@3@N>!f=)tDRcZ$`>x0jY5IBQbVhk;8L#9 z5T@u>zojVd2plWL*`>%cIqRREs~YZ`6L?c_dGLIFZF!M}BfvgoA*oIJ6T+Y~*$NP) z&Nce?Ls@YyVj^QWtSC$A^eYi!Hlq##sRk#yV??xmI#GQC*T30j$Iv7rJ03V12h>lH zXR%P6Xyi>ucXA`?WAl8D=r7M8gq7Ei$wesKKv;L%Z$e8jGB*--=tbaycDzUFrm1Su#==E*C3 z>tQ^r!NtS81}vo17tT4&80Z8oOLc@3*w|s8I=qT$uHoR}s$Pk9Q+yAPC6!u{svGfd zA5L0%fhhS8KRh1c%~lErE!7>qV#G z=<}i^a;lr`O4cAHbd0Cyj2Iz_kVk7o*kId9QhtDr(#?XIn&JQx<}#@YVab@xa#VC< zR&V;m6_eJ?1U>Vnd`9oeD7e^7z>`bz=L3P}b@nW%IP)muqZguuE>N>&J+#|Qn>eYR z2@rkTBLK=#{XUez_@wLmKqKT;>Q_wfg1a}k#Oq?>m{QA3>6|YNodzZRr!#-&al~_N zw?6X@q$R0h?@$Duava6!)v=hT*Q2qJ736jEvAiE^DCfw%&)`I-e+qEa@mzO1s7lT^ zj6!>i%33X`*vQdZPkaWRYiohlS81L|P92QaEa%CL4AtmLDgs=t`|RuH)ddFp6AZA< z;Rvzyoql1)O&|P%m`bLSji5@Pg+wopqTRJ^#{|bRqk-J80BaX`ikrFKQha&+khC%{9XdsV?$DJ- zCaN;;`1Vl>xL%bvs88L;yI_U0tOo9p*BqhFl{F?knDI;QkZ`Fc(S1R^8YyeRR`elG zRTJE_inhsuV9xC25Gm@p7=9qEFpqvEp&a8dD4fTxsN)-~`wW?*=<5p>_X#Pc>Fl4K zZ6rxAW+eV-KTMVjKR1ozx8T}|HF`t8ll1dPJ4|PVk)^31;p)uYb(DVL?>Vg$!r@Jq zhU!xHe^OBILp|N#ZQqYMEu8frq(cn}6Fk(9IOL6$H%%l&t)QuCLO?Vkj*ngHl5BL?U8L z1?QWS%rztl^;jfxT)oi2pV)#}Kj|c+o0xYY=QGub8}rQfO2h?hDz=JOlRvy@Pz~ZS z_#!0`x2>1lm8{doKTft(2f`yY+=oK*JT#kjN|yOWMCNC^gz0w19B6 zIoCY#OQX9sstfe||ffIGezLsf_ z&3GNuR+LI>97lC25b7x{NJxCpq3$#!J~0B>FN(77C3R^L#=$S0heQ{c5-iC@-}<26 zpW|y0xX*f&{mt-mWL}MMKdEEjp5UIbf^&fdlSfUH83ZcgjxpU5NYBR;a_f|@0%{JJ==;xo{ZFosr*vT50{Om0mh{j{R zPs@HsTdkMRDDjj|=er9TM0}^007=8E)}%yt@lH*8Hmb$kL0jUg;>Q$MqP9w)3OX|~ z|AtkVmCRZy;3)!f)PrucFrhqYF7hLj@_3Te!NU=Bk)=3W1?HhCIG)W*K(dS^GK+UEtjr=6LI5L-%-zVEEW@ z@L-ims@v_xkclewJUC^xiPeT{MV!-u?m>F)imU^hOc#VdN-nidU?MFxmegifM*N6ifq->mgyYCT$M3C?O4ek2cp#`sfvn?=_V~>evu+rgVR6FE2!}es7)X?(? z{5os>20yHVNMQpyVr|w-HS>a;y|qq}2!hN$U-Cx|%0_rxuPIu(<(1o(99&WeG`*`cFnX*CvE^(K5+H^q6v;87t2&)x z5F)w4%xj=tZ~iuwe2;OlQM`(YW1nS}jY#Dpc4DMC`-769a++{~*x0fL;>3YSn*8A7 zJ_}!kW|&Xx#eoI<{oxN~T7MkTYo(>16Cqi`_rW~St2P&^9&L^5(+QL|)VoXi$?NsM!B=HyW}*EONzjPdkCnW|N zV$=`AO77yIIE3%L`&!kS68_vDs4`^wAwv>84X4H?7jvyD)qr1_TC_*%tGp`mHqUR+ z%V@gbwek|;53jsf_>NNjQ|L!f6jnI-jvLqi;p{EI;!3u5;RF)g-QBHmcXxLP?(XjH z5Zv7@kl+&B5(w_@4#6$JZ8DRY%(-*E`+q;p?!9X7wW_MCYS-$g-s<&ckz@*_HJ1~` z-XA_p<qpPz=4;o5e)$sh14eH%F&|5Ufv9}t4O3U3EIEuCn2zPZK`L)SiiGQ{w ziUzBdwi^tUTbd4GDTSXDkluJS)>W`v`mTjxASE}7S{35SC~|0@U7jDfRAGIf@qBg8 zQtG@~@y<9cR@OxpBe6ufNd=0x+O)T#44pafDX0i*N;rTT z5vLMdQ(pK89J>bWwQ1cpQm9< zpN6iW<2nla?qjL~6zW;$)x%Hgh1Nzh2 zO?W~p*L`E9s3!Qp2L?T%<=3law98o1Qn8iDn1f8kRsmME~vnbt|Y{ESutuGgQ zzFB_A@1cJG*=Y{7>}>Han~+o5gBX@h4h%yhaaz4Q$GXGKgUoY0V#1TZHIR)m7{NIK zHWIXn3CZ|qv7GlC4h1;h`} z+AG`IfsAhhzgz|^x!WQLBcZsubeQvQX5(Xeiexpb-RY%o+r)oNFJByx^|lZu_Gn4$ zlSd!JWia2h9rq#z_-Pk6W7n>l;9DZx^ucU&D5M~I+UJuntD)jpApe+S`vE!Yy@vue zt(V=en%iB9T*^vVAxlIF!A;(=A*VCacw%(xN5lNeXwt(1_|yNI;L&57GeuN2S=K3; z_IC!Yw(8$@sa;X(evy$t$qd*A1NkJ-!n0;m`;f8kH}B*nr|7-`=8-oU9NSYG9x#K)gJX z$^zH;Fb>ci@1JxtCWJAS&D!i5RI=O$tkq4KhN!Dhz0Q1k04ulN^9YYLQZrpqmdC!A zc6HFimSWj6C;<=ntg+tuan_8#zt5nbLDG$1uj2)VehR+h-DnBztk&b?ZY1Yj~b|C}Pmd~*gA=oJY1+4SD`hxJ7yoH!LxP?(tJ*Cj_E5#dG|@x2!dYnETVdX z6TN-hOiO8JVAQrFpA#7xqu-cvbX8*&LE7~r6g zf4MbEi92{(O9i#bZbQ^OgQHHgYKR>=OCZ}w@W@1+vos#SvwxjaA~$ugo@kgVB$|6C z@*G#|$NG+y6UnZl1N<63KP=>XD*7qXv!v0p@4V}e;}8f4-6wK_;s7dQe>y5^R@{Pj zc&a|GF;?t&#&N617l^yk8_Wag6H3^yP15Q`w)A`rwyCItS00ugrS(FbP8MnUVqt3| zjzt>7MIIbKcv^+lDJ#6fn#~SvYev61w28ED&jE2T3~uAUfN5s-gqeYj&zDt}8DY|&3@Gvv9mQ$C0PG#C{J@41nL@kxJ2JSLnR2MXLU##9B}>+nF^ zG7dDQeq_g|`$OCGY(-G_qu+#P5EElvgAS&%5T;jUF{sqVi8p^Itjb7&6qB2D)d&me}ffqD{?EV zyh*)q&llEeo-jFI@s&}oCQVjk& zCJgCwAn3WD)<+)nb2_8&1D$rIm`DZ1;+!E<}PuXl) zd(0`&0%pL6qWtFc9DlPnSS7R|Mo^((&Ks%?eB61~y(48=drlvbb)tyx3Sx>CEpT@v zE3hM{Xt{lAI2eN)b!D@X66&v3YMJTyf(=&Vp;)he}Z-0$R<8AepB(wFe3oE*DOzPI8p_PNX5 zK3Dj_g{qUpa2*aEp-n4nVidD{-!DbEc*Jdhd%?r{9L&crLyoz|N5rK7MUhlT< zcO3<{Qr>>h-fXsHeQ!R^MnR?D4Xr z7)%WoNnUSB^+TtfEs#!s3#_A-F~Xdr^%|FPa{7setInfM$8C@|)bCP=ERtQ5MbrB2 zD`y3fB_N^d(&b^I-tf7FH8!4uiP9;E<|yF#=*cdLho&k+0Hc*SS{My@5ykpN?m)Lo z@L|*h<^Bd7$JwOHPSn7N7LU$5+*%q426aN_OsFA6V6h+2f zt+Yjhl*MS&7LwvjwMc0_#oDv8sz=VXeV-&QmT(rF>Pe3;E#0eykv1a~=Ga^X>eh+{ zIQHaco*~;|KU?EV8%9vWGDv;ZE<KCz;pC&c&{LL+@4)-+1ozxz55!7fCfa#zBN&EhOL|5wbbmEz!agzUqLw z8BY8(TxI4E&eFI4n)V<$f2@>h2GqI-gk{n9T|nfg8z9UdT3~kW>9HOvOpg!CjYdVF zY(n^y{FPDsrY&VDb3vd7rCIB>kamUdEG-nG#8M5T@$l3*K)q|1a)PY?^R~vK--6J) zESF@TSV%!V_wO5cbG~|8NxI1d$xl0fqz?zs^OMT60 zP2!1d+C(IBrME?G=-^lELrc(^v}Eq9CIaGHJujf5II+;Oj8ZQzW4jVpzQ5uXgQ?fTj#Y- zRl)nUY9*Z)tSf(uz;MS4V^j4@K)smu@{TNsS$SGpRD}<+ymDa8c`0n=89ghHFz^Qx zNc+z`x#Fvw(%a6IF9AZ5;OZjwANE;1h-ZGL~(_X*I#FXl1Yd8VPP^BbV@xS>izm-B>IJm zwpctw&cSQWCz;d9CZ+j5Bzl(;*u=~o!3ZkdJSA_jZ^oczj?8h$#n##!>0*y#k2D!y zuPMQ>6D^k^ze4jzs?o#_o+qH~lBtRcC1lB73kvep;A;tCLzFVfBB$dI;MrOIp{vlN zqL^t_^U)@Bph&f)QhV*g`$gAe|6J`r?-<4JR|wXhBQPtldAQwn_g|d__)1RSu{`*4 zEIXxN9ZOi14kqf5WaaVHv4UMmAJ&H$Uw~n;^q%`C&!Vg6#mZr6gfY1z5grWU3~Y zy&p!aCI={dDvEKl9Td<08B~?qcvC3vhMn5gCDu}&ChJA|`fyFszI94IOf0D5DqY8j zM#z{U7P9WzS<=NpU6;}U|EK5>^8GV~QL*BsC8c``?Qd|YRn*r-@KPivp6V`Z8Ey}* zvo!r}xtK>qwGOxo^dH)M9Rj_?bztT%^FoX?!NRIOeg-^#a&&qfP={T|zml^44uQhR zY!g#~co?&wFLj=kvzy)5i5+B<&JTl!bCsE?_h>CCyCc9Bo_&p!hCjB zInF1pI#C&&9kIN3uSeEEE^97ES_93I`!jcxilC9m9H?n^3`2;z0>j_z(}pjkI6s|F z6XipA1b1^xTeyeMi!@CqzNxKG3L)ti-MiOv`(n@JOCKjr7DJYJ56(VWi61mCU}7+( zS~`D3zdm>kudmfZ{xQHZ%#gCqGud?ld9CbpB+E$blkFilsP(Xys*R7owfkM8I=!WN z-Zr>%08X6<7&A3Q_A@=N?tO9k1tSGf*DR*3*M{3@8Kn9poyv{j7wSMAeNO@~ZHM=` z<7IH=%0#_ufKpnv<)?%AD>mOtr#Jrs*+wmb86yZnR^Ob*F1bi zQ9fO%*`}uqK@*BsIXents|0S_-s>peJY4+pEtP$u3ldwzm8_J;ydLFMo$05CvF=5K zEw#CnBVNh8>0>(UvfS;y&pM0O$%}%FxCQa&l~3*&b~Ijz2z~Ng!PZiAHOPEcgfSE8 zxDRnSAmljaKFKxvU``WSGZZ4J-T)3KNfGPuI%8C12D|d_Q&D;#YFkXuhsqy~cR^t= z8T+O(87ET(YFCJ!Cp(?pSfxp&KD4J#W|nZFUWn*hx2&p7)@u-4IL;2)2BI@w5{(^W zPz;_7-e?ng)IGH^&?b}x{Fo`;w%D=r>S9WF+^K(9i+oypUAz@_UlN05Mg2q@;xCue zk{vsmwQx_K0x>{J0kNivUvXm_GBe}nU?VA$Eu#N)Ct+G;3hPgUR#4}In8*(XADm&U z9n{C^l;u}Fcsyc3Mq5m+1qE1>86vlvW8-=?3$Kuo92?*qN{ska4^KX5ph~3qq{DmE zpxFn;Sb{uZP+Iw949nb-_`p#eUQWOuyO11q8QC)G>4Rb+P76nq9kQLZTWIQpo9>s? zSEgmN>3ssK^PVqm+7^#NrYd;fO zcZ^=;#iZBwwqT62)=YPjp({H#OG5w##N3KIPxFqQ<&ZUbvdo+fic;Um$OvHZl(=0gCm4`&zD62yz8CnpGikRBnlR|>6LOF^lEU;=>?}V-GtS2;;WPj zrz5qfTpC@lT}js}5?)%xs~nH`Gb=l9sa5h_ygO8QH+oimf6&4zk=QBx-IGdo2_syb z{mS-;WmA?#1l5E@!J{-DhS;>)#6c26AtI+)6&(!PMNzao1=Ry z6_;)?m?KJ7=|bY(V4Js8ZcYc7<}9T#abQMCg{nzbiawEivQRsN643>QTd5`8e53(Z zVD#HK@r@HMl2)n_+t7T|(Qt6Gj3BpPUoUH#NaUWiuZLF*K*I6I^odh~3fIny!uu|M zH80cpte9^pdkS-WT*$@u_4~DLRS7wN+-IlRplN=Dot-xuDv|W!hJ(v&zPc$GcG6?b zcGWOPnwQ$<@6y+aC>3KtLE6TI)5vn&v8$cT0K*}aXsk85}2 zf2HeWCT3@vkuR8;J?tselniev;=?8-@E=D)L*H7Dw{Zv&x>@-OfxI5 z${zaBt`m)pWN5rin?Eqo<$NH{VYejrGW+S3^zd z7Wb&k$E0}4_Nlqd!!s^;jPe<8!;LXwogX~xeSWBVmr?l{A@;J(L!}mkf$vmMJD&7D z=n)~j1Fz5O7(F!lp+~aMd$o0H_qG*Mxw4UFG1ca_-AAAu;GMRylpfv3Cf>8KioIu_cT>-&xEWTEQFGy&EW z5+ZmoQ{KVY34_0PD54(=_eKb8hJAb1!3_R$sCwAd@)jaIHDdUB2vh&wQ?v>40)eZ! zudTJV+ZplN-g6bG_A}RUo{1K@5XgI@+@aUW-_^f$E_dHU!slnN8n&YQh^{Sl`xj~Y z#4G6689UV(mxV{Z-@u{kmq|tfIL2U5y0;RnTW3oKi#l^=;K{Q?ZTe)WOg|$kBe(T! zl2Xf?ci;syJ1fps^UK9gHeF>A=`rdCucV}?KxEJH_IqVi-CVmMv=%=amI>eos!Oyw zl#Z$`v}d=9hLYudouNVscL1a^xKGknG9R_rR~ci4`>FkF9yl0YQ#8ugVrtq2JE1o&?1w zoA|fPOUKk9l?*vDH(ae5Hkh}R|B&}ADTeBK^u8hKg!26!JrIQVRx5h)!VASUqIVv; zsX;KFmO?JQ@63nBo!(=NV$_<(JStO1KTHfE2+nK&xcyFERmIUgVsoMX z#=Y35^ZYSv*?FclDZCu%LZ{3YT_sb~BdAVf8`7$6&6B%~`TJYcpc!tE6Y9@Bu5sF+ zdlApQ*d?oXFf#gqPIeoQx3=?};b`M%Oue^y^qX&sQYIdeR5qbK&9kZ0KIY)c%l9#V zVddH${LUI6XsW&`)TtoESshhc2Vxp_7F}Sqblu>VP$%>*`d@42zk3N-l?LYz(hQ z%G<3J4wNKcJ*$G zbJZpan~ey7vo4%f8=-k8edKG{e9n3K?X{8TdthkCfgBoY`KY%8bF;BUNC`4DjtN?o zHfVTwFyRSO`RNl|E!bTH+(O4CJSSNTQ1~6YhPWw>FynfL9a8TE@^?XLU5PcUk4QXO zuxyOq9mH~mule~FLo|s=xf>=t(zs^LEav`m_3ds^u3=kni zrxRUpfI(`1gosfrZ{#Mxm(ZrU2YgKd%X4{HNpDl~D}f97s5nBXb5FoGFSd%T6Q@HT z(f+DvA>1TwhrtmbwB})2U&K1vU>Vu2GRqqgc0uL{h3#2}3$dwZ#sZPW^OQYUCO+eX zZT(K;{=M|EA+bHJ=VQ2EQ%k7qF&nd1Gt;xlG~NhA>(&srfqN#eNLy329POc|lBeZC6j%wXVUrrT3op^g9swV??rFXgw z{Gd8ISjF78Y`SG1I_Yze>w3|_#o!2AK6U$HK!#BglHbAnHpFu~O)C@=3%Nt-RAX{=}nY6R0RB^SuFK3MG=a@Gh3d+vr;y7{BRozVF|tZ`4}LC;2!0Cz8(S z*fQ@z+|UY1WiUT257T`PTRJVk=Tr&t(XS<>rwqfwgi3#2 zMbFGj3feOjo&@CTW@{JBow*iBU89vt&bi#h```}g!aXC*V9?c4CeGbF-viDG)Pf3 z3HVCLI&MSYJ}7V8;uH~lyLLv1gP;V==5B}5eWzGWvjC}K4%|5+5QB>rbR7617oUaz z5q(MeQ=4yWdnF{sPOD6y8C?#Al*FS@zC3(QN|~FF12pqMCDnBs2+FM$1|yKXnc4#{ z_0MR)&L%f0v{F&2WhJ7pk&z6?5F^G+&+a7m4OL9bBolme(F|iAcB|RAR@{688$S23 z^?7TBMi;*DS>SblQ#HQv@j~8=cv=3H(bJ>pyfYfm;*@wj0sr(2yXup(_HW+ z$~-M23j+c0jh=vko}L33AfDshPi0wsYh%Da!=+p4n>rFO1C*SMtyO_>&w;V=?Zl1E zP0gHMtN;RzhA%PhU&NPkU*wl;0TRFf`sRiLHm1PB=>ad{)`4;7DF6ZhL4XiI7^rLI zqz@1Qhyug_;s6PNBtQxv4UhrI0^|Vl07ZZjKpCI{Pz9&~^a1*Y&Q8VveQP^o2STmH;b& zHNXa717uPG*aB>U?{)yYm*D$ie` z6JHAbt#<#B{C9IEc6K`UKPvT`_+t8B^nne*^v6g3kCOlMBmcMbZ)X24{#GzE+h1+; zoA{f;OS`hsv;XS6-`kY+uZCk~r~lQZtSo;uEgL&C9owJn56p#$l>r!E3it=?z<+IX zRz?;A4hGiWZGNlBZ)N;;705{PGt++#rr&G%Qh(sVK+pKcP-5oznSQy(%J4^xfX2Ty z)JwDe_vC-v`E4-&KKlM1;=f(}&k_8$(r=mmt^};{pM&-{h2O{D-#Ppo3%@1*Hf7>q z_|>9J9Dh9@zYoQKHT$gzS^m!KH}SU*_EPvu&;I^UzWYVX!S*++)8EV%A~rxW7jqj^ zARUE`fQ_U1U+KRnF9Zd|gcX#jmCdb<9ccw^t&D!-y zPpw~f|FQs9f{a?n#pAKHe9Oy4?On-LtOAr3(@fm>9-!31R*)Ny>BL402=~@4~ z%YSkBqCegIiDbA;s47Y1HJKYj`(L2|AXI!g@K**-{@WbK_Vmc8<9(9mb$qz%4|b5S}B!C_=M`K zP@4_ZzC)Z{j6g&&lwQJo112`1$+58!Ze|%K$5d0ZLhP2;Z-o)w^g#~vu46@S$~ZXc zdSOMUZ;|a7qjR*?uTZvWoL1kgd}vg!P*bWu%;a2sx^C=PCi>!mLy8n`bt5V~!~)G$ znn>8)0e!nqvLPAw6D0qOQ)#u})>B^5g=%Zj3<~Fa zP4(YSNHoi$AY9;-$OeKeGeLy}w+OopA3&1M#dk*#zl5b?s04hfc;Mc>NukkbiSueZ zMMXqK`Cz|N6#*6Ha;;cpzp{Qr2_GI7d%wy?5uw?>xw*BshN2SY8RfOxKPPYNJZB`VfD(n+q3bTZVy7kGT>mb+?&AZ0U{P^LkcFL$$?L=BWn&PL@z$sY^;%zB+ zrHs<~DLM@b7mh6pE$f?#uP}2OFxHkEjturnn-|=Jn z3Hy)sXcewiR8=MF6;&S=D?gg&SMAf>V;8^29i544#MI?_dU~@Tv;f&L*D_x`$D7$? zyD=?+moRZmwurfU=2l{P{&6UjEJZqv)p#6bGI3JLr>?Q~riM??SEo%72XKPkk=9~( zFgE2VZ@~5uLt_e;II-_ZO?{sr2D3I)m@ZwlQc5{Q3@rFW;t8TwN5UCYQD-PO^vYRI zQUm%)W5g@ll^yliR4f6*9)97&wDs603sIaNzQSWs!J+u$nv*vj^Jah(%z2~r^F4$_ z3(i-_H6gb4%H!%h9+ICah)2{;Nn#WN`80aF-BS9eb5)hq%o*NUv9Cj%UDi6+>r-T- z4&=VEHgS7ReKI7n(Cu_i8e%mA8oNL4HD05S}JNPp`s(iXa*u?GF7@mC2bCu!WpCZRLv;w<<%bU zC!T@+gz0Hq(n?&usNo+_1$(c>1wa(3A<%WqVngtTtG@{Q)8HA%>m{$qjam>43GDN+ zB@c;fCF6#Z>SL#;9(+R8Eh)iclW%F2XYs+r9a zv8IP8`&7#uQuG*YYOq$-Z5vm-&V;UYnVMD@iNuVLx`gw22kxHNT!XTsDL{$er(b(W z!wvepzinmr>SP)_AnM`=TWSItWpjm$=b1$t#kgsT>xO$OC^o!qldO&b`y->RCuT$H zkYsg@Wan9PGS@p(%2plw_KDiy_eo}l5EwsraLV*;c2$juF(Vt9UY8WWF!pZPTV~cm zXP*sT&92k+G!vRXmEe3Ck{%i(>nGjYKx~zJqzv=7Y;~!x5F-ANf^<)og^9U}YFft! zoq^NqDypsbdiNN!j3X5#D{oLC&)Q7P^)h&G{nB%f94)}Mn?04CIgSQD4koCMqGeef zTBfNiT7RO)xrL-q%)IDqy7D$=ezCFNmGipq;yV$JU!WdcHfWcww&hVX$+49UYc?mj z9T<3e=P?rBx@6(_6JeJrX%lBy#}oRAGV~HAt)9Gm@(NodLjH8GTT&s$xHZ~};Wr$M zX*eRZ$_@|EYQ;0lxN6_0~T7Xuc3BkPw2a2PKmV zm2IQK;@(7732Pmu(rUf;3!33^xaTfvMy$lb^|UR2#aKWu>U$qV##MIs-h1;y*=U7x zqSJ{qy*fTovlgU6xQ&7D=c731!xNrHH5T;gm>Nl+p{{B-lzv<=n=IpDpKba-ez^yo zJZp_KeLwlliy2>7XgTDw&%W{Du)MS28v~xCMsWq{(>Bk75400%7T~K$cc~l@pKpmtA{Mr@MJTt3%x0 z<*`>O9H}}^l}6vc&*BE=%s> z@k-RlB@XLBhQ82edA-j2wL~jYt$}&Q#d~r)whR~Ze2zVwOyPYyVr@Ww>N-?YP}*?^ zqTi9fng3pEn8ogtnZox}aWLb9A8+&7(l9?vL;->J;CI8p*Z$RC%8#b7!f$1zl>$FI zd&pTngexJw3xyjrY`}|$S|%t(KGNGrV3mhEeiTZDjG^bblmb5+Mak(L-3U2r zjk-lO{;rk;E;rCn(Lftks#I56IFe3wEWZ)T(B-fd7yw7U8fDnmap1CtdXQ`0iYJN? z{f2chvL7Bg$`yhKy$KC~q7b5udO%XPuHH;((0 zfn|hX1KW&qTBY%rvclvF5veEN_SKSng4cLHkOS)T(15Pj>J$?R?pJ7S4zL-rRN}Gw z=&>x_3*G3-9Z}ozeJ=N)PrQN;BE0)8v7aE;3eZgK%^hf4dIdQz90laecuX{)y-JD` z7;y1;Q^EwXh@a|9s_%bXSW>Rz#+x|HNI$~ONQu``pJ{XIC^_eSJbCc;qgB7fm!DSE}A2^HE6- ziG)gXDR@>r6-&uo1eHoC>Fu<;HD*tXORtaX=KUvtAegqCWFwA(#u!6G#qz}BLa~%t zaw?K#Job;(hLQK-qT^Y73nma8Oe+<6a);C(qorv!dtya z3>RKMX4%Q|W14k8AFqj`xc07glM-9Io8Tr3eAuiflX};>EuN7FpJfnU$ym+y-6j0i zG7kZ7Yo>(IH4kAdWO&%Q7qZJ0&E%c43G979@S`;hkZWy@pMa+&%XcL2d?F;?;iIT? zbKWrHqq|&Z<*_;8d&r5o#4xKy!DJNP4g+~7Ire)MMHp!Ptn_P5#G~EXl;~zZd?q~5 zE?1iy+()er;dcoXax!xKvQ+O3b5Q7fM&|^;8P6)B;q_}@5xkb8AO~5={VXZhiA`N{ zM3WXn5N~YK{gv@R0ni%$91RTt4}W>62m^L@V0Wt} z`RbLtI=pS7ZKSB+MD=w=Gpt+0;wx^aV7enutZ`NbvrXVzZ z78zOk%2I?lOOr~B+|fm|k?oR~BgCF4Qq9njU29=PYdEeG8SE;FjcsaH6mi9(NWE3OHjkp(Om`U?Wl^VWaEa zSu$?%wuEJ1{qkBW8-rezP1BQ~M?hsXB$0F2blIe5cqq9j*|aAdR97QUzpwdnt%y`S zLtoWg#9_VI>Fg9xkQPE|w`uCtQyd)9*A|&q^6_K+utX{61%xHqG8zOn$=~fZ^ zxM-eXYDh7O=nrHi5d{lmd$1soHq+4dw>x?a?1-oHyJex$qKt3&PsPC<>v3?fNLX#M#==dp75+}F- zSD-5wfCU5pWu^F3c4eI}ed?(W=BBbS=}E5L?@>DAEw`OPLI?~ACwZaFs0vEl9b6H5 zd}m274KIPPjs@CMZ0;M|X@XmL{7j{Uv(W7Qm4!enfl;S`Y{-$^r7>kSYer^OW}<6h zp`~xNCJ2R-Av+z$Hg1&r*tSAngT{9HYsXf=qHomAa_NNVf)0k7R4OY_nRkzy>b3A1 zm&K5riI>_ykNH1h+{xydz6V?AYSj)p7WK?uGLlU@B;bYC2SL4ttconPrRTaYPQE)o z-_PAF+l@nJZ+8Q|;6ERyw%W!{M?#`nwq9n}V|F6E_83q-B0w$Cmq;AA?o5qgLTX)| zoRB7#MH@dw?2gB?xHs?-B2y%?7SOceZ0P@h!|+y)iR%JOJ_(tTO&K;BC1FNOM_AEb zYUC0fEtR?76o3L*Eo>m=v!$0G3{0t1z(l}wQibu5JTDe*0f_3q#l@%1r1 zWGpD$j2{Y@e^uZuuT{vv(n%q^H4Wi)q?tE>>7ht9*@S>Gx`n8vLe!f7^ zYyX&ohlI~w90RtlCI&|0P`J198UMB2fF@bW11>k7he>H;iuNHY-hnt{G!1F=DN07BhANf<8nzVDanY%a#~d9u==T9{P-9L7|n## z4avHkMiwTi2qmmR<<3C{I=_OopMNIeV_^)m~IO=hP$Pth3Y zG>lznGRyH4_*UBjG1(69O9&-!FXWzXQbNLT#PTaEu4Vi7l1Cye;dc@v`t^`WRQWqk z5}w5HC%Wi(;wB@cRyZAAN8n&~^`V>eraWVC8|xKq?++g1QMBp z@5oxHx82@QvpNgoUteVH(4`ztkxV;Lkr0yS!zhF$4VV$}-q9R!RFW3FhIN!JffaU@ zLLR29?+Vp8`#yp!BUUZ*Fmu=zd3X={=_W>Db0G|Tw@jWi=uMS2O-}=aqgnX&Ba=uc$ddf(5@CeOaq~ZKfhLmf%8EBY980af&I}N`zfwmxkhXC8Zoda*##*I5eAwPCQ4Dxs&XSWk&4 zJGVJ&?QDx3-T823ZK4`2#nS5Pi)0p|q=oEg>Ss{?qOua%XEwZZ_r$hV(KX1Cd_J<@ zwqX)F9uQ4B3t@fxoQ%A(StTbx9Xsx@c5saC$#}b#ZRR6W)*&$!z&GP7G8l^}-=*D* zLp!zqkQC7{cK0^tL89uR8y^J6>KYJtm3d{lSX~{C+|_KnK@xEffZK$a`xp3^?Qa@# z8CxS^Aip?;Fef9BQJ$U&xNghA2t-3Dfz0B@`cCGyHvi?evN;ecrH~L(6nHVzl~R!s z&=pmb&^0l)(YMlN{L|jnfkG4rSOR&&3Do5YfLJ4NiJ8F6$;plr0B|%juyvy|GNuFw zI6IjEH3iKb4b5y#Oeg_B!f_*KLt_UD0a1Br0x>gNN2fm+wF%hiSeSobVEvoV{3pyI z;^ri#^g@^pkdv1oVE7vnW&4|^{C|UoD2Ry3NXk)*8(X;;JDD5m)5;lGncF)X{})&U z2$B3_A@}Fv`rp7h0ozYT^*`CbwSZ8;@9Xye!bSeK>Cc>AFnQp*{eOV+FKEHfCHtR1 zz)!`Wc>I5_`_H9&7QjE3?%CM?T)O{#;hz52vOWD@i}pY!dVRM)m-~S>0xrMS{(*`A z0^k2!EdRaN{%_iIX14#`s<@$%p1y&ekrB$d_z0yG?U1zW)Ro+qAsQN)x8YRJaV9?q zdoG2NHIlnbzhSS~;O*GpCA+VZLwMUF{#Y4&ZkP4*PkUc$@I`RTj6>({+s=NHWJ<@jayt6neXm*el!{&x~E|KI0~ zKR0@Ca|8aG)&6zPV1Fs)cdUS1urUyTH~#1I^bfGl*bUN6X}aYa zj&KMKGZ7=b|ssj)(K%F z=YNoTlh8#`cA%b=0-zn19;Jv#N5pSDj80=ReeB>Fk3y%#kVM70%mt~YwPSi?STut|PQU`^V>S-ARkbj~5QBig~`+ZENg z;^wK3A}~y*Lyi&!pN3!~ zJi1q_SJnXejP;DHHZqJ54T&jyx!1&ilp%6X$cj)EF%p88A$yRR4B>sRRIjk0xLvqf z7&-(VLrAKyFanGLW`6`mG`?4MZRDBJ)JFx-VeOsiama!XpU%|-k7$qN*dI9f;?d4+ z0ooV|d^SAYy6up>|bx)Hvw|$4210K87T%j9=8r(zCI$u%e8%3{`R<;1f~Oa zI#gIEaUwyR@J+4-y(`>}wi{!7(Ddxn&p#irRe5c80G`+FOP~FWu zGLDCkt`DHixl_u80AXa&hVMm-mm$Ykin6WjYU`Zg)P^cPGhGG(AxClRwEUlS_sku* zurupXGWl(M)BZIgf6&-ekt%E@A&6Y>Vj`J*gB zs1|7EvTPPIbAV=OClWyEh2M_o7{O7hkssY$&^2?TVE zYYI;!c%cl;s8(84TU~A9o-nHOM#k?A3j}%H66o$wLwA2BQFFffx&nAow`RQ-w4{K; zLM!yRC6f3#>Z(;}B&r{CZIvoA{p%{0uaw{Afvpjuv2DR5O{>V9e6y9FNBM->&Z2UQILxxRIc+eh<=~&` z*rjRy3Q4a9tFk|BkL{`C=#$;&#*@pn`cuH=)vJk96)BaFo))VE0?px#YiidFDV7AK zimfcubiq|$nqCz}*Gc8D@oNk;Uj6RXr?ulS8A{n#M%p`Nt-7u}?dPwj7hKwQFbEDG zIg`c>n9V8MC-T8H6}JG^W^ivaJm8(IMQrmam|;gUoXrQ|g;Ewzb&+H6@j(3bMg16l zn5MEx&F}4pnSfX6=fOI-UvaXgLJ8FhSy^z`5a{Eq5Q7TIk8Yjv9{vG z#@SLt40_0WVPcKX!RtJ>0zi}<_wXvoa0i>=;=-?6xfK0TZbyh3XKNXRTt)y$mANT^ zAV*}-2gb}>Hn*y+U|;=|S92a!@%bF&jjA%MIkM|{oV|r zIG9s-6p|qwzpGeG`WCZ2E%cBRbVOv_RyX|llEd84`V&hb~)oit7WomYcBEjbXrR$1YnXCc}_P1bzvX4C}9gk*-pctMLvr`!Vj+OQk$^l zqwPa5pM)CDsKC7t3pH*fP5|=l>3DsAwWG*LWgNO;n+6P|cgYF=d@XW!t!eag?zgOt zc?WDSc)H#P1Vp;ml2D!X^)Ua3xwn9-T+8;oahHO^-QC^Y3U_x3cXxLv+}#R?!rk57 zU8-<*hX?2M={~pb>AttW@s07`*dt_RuViHUPn z5%U4o9_-)1^iE{aq~=d3ovD-{mM8ms@fznzVO3OmQL_m#Q=Cse1cWT?Vz)upJYVXn zDP=t!Q?HINd+FN(?KG=d21UVyUM$0VHtxdpG$_nw@1sKNq*F74?qsRNzdPw2`%>jz z;|$0kvt7YC4NIsVT(sL&y7x5dl2Ucu?I!Z{S=BBL@(mEZRjF#p?whHm`W4M2QUppKYm(;j>(UxHDbFKch~1XvdQ71pJPiPYA~EeS&6kPs zoM{I6eCu%AsTn@Zmy;SE7nl@;RU9_cd&6}`?umgilowj=U>Z0Nz-Qwpe@fmBY@a*; zqA!gQRo3sr$1wWvt^d>IkMKVfD-|Qh;pWm=KHL)Vi`fBpCpFU zC^8)97K-SgiUD0=H8*6UO4Ana+59vFL~~EL&^cj4JnPjrD-)K6HwoNAI%3NgNzW2M z;PiAK_AQb8jmmkPHh0(7aRxob$3)wxPSFjkH5;bHhS^sUO>`^JNnA6e9#X>Ra~2l* zi*T!%(`S(Bt&EHL^gD3+!4+UDju>RMizA0^K!NGz+#)y& z$_cM(G_}N(W&dYc;}Kf-g4m4nQMvu2-tevyHk|O=kgbj&PaauJhHulxzoPpNt|x*# z(f7bK$?lF<6lJ5y5WWx1n%-bc`#qH|9EP7F zE+#kM#)UtIeL-Wt+KARQz0OgR2%Iq*$h8G%$?dZ|q9JAuJz^?kzDhK6JnMTxdd|zq zYd64yP=_s4S};sv;@)IvoN?H45tK4iQfSCc@9$whcTzgN!Z_z@(8VW$ zUXtZ)jk`O4u2-u#5u9Ni%Xgw$Nv}qXmble=dl|Sok2sPkqSVpkeT2lzYUmxKQN7Ti zLJCkbiLbFnr+`_sdyVRP+MwQov8iYOzLO2>g5{;M21~Ymr+QfCxQS+?(MHlSUf%mE zW+jJST^jNHBunmy6T+e~#SjiK6Vdm=v0q}B5fU)coR9_!fXOs$2B2I@@pa2!np}_= ze-V1%=t#ovGyc!G^(TbYj5QmKDD(Ji&@zCP&o=Cy*;up5erP{39-GbV@h+$8B<`ZZ zWX@W|^D`3~{Eey^kq!~<3bjBiP1~J^0Ma;lAjp-;HB?F%6M(oU7bVWqR}RP(7k6SP z??`@3KoMttD~vq(F%Ho5%QwBupR-!#nGBVOF|sEhi@ye!?m+Pv^XEeGtR0`(jdlgC zP0b_0+@rzCClkD=J=Q`C%{IUn$H-5S`Oat=EAixyF{M+a@gT0UCSP0?!O#*ZtaPc& z8GW-NAFQHC49^>TdX>wz34Qu5fN{9!8AwLwUeUFamT&R1h6o!Vw{91@g(AQAgnb~z z8n(~#q0nI%dYV&S(vF!%N=SE!w5TK9rmGvfHF?VpYZ^D#I;d4mj|rWIBbeUs>6m+U zZ6HS*Anzg+6$>MKuXdn1m3rw?8M2AJ13I55O7O3-whU_CRV0cvNP4>_EQne#8R14< zxI@hQ%QkMyD6jziM=V+$`S>^`N-N8f z3TsnpvtjrsX;T$tljIrnUA!y{{L!SQ=#YjcpAW zV%{Mlr-h^^zvNjjg*cQA@%a@Clc<1nQW?A><*BOuv!ea8S|v8%H7-|+%0ex2D99ry z?vz_ty)0pw@@f#$Ob>vKCzvN_4oG{41rcHL-JA1rM(x-}^9iPznnNRk=pl2{Bc{ z;4oN7lsVlJA-k9`f^BceIqVl^Wr}Yh5SCT0R6!*sK^!&(ElRz(Xy6^hcN4-lh9_;& zEhjEyYK9UF8R7eT*WPZuek|RAra2m{M6(m*^~gQQ{gM^tO+sLZL3WiJHB+dqmayT$_7`u{Q(~tW#)y3dZ00ol|inS^|kvR-1D0b=$6M+D_@-IylnPD)f}V| ztrCo;O8K4Ht+0~~pX5@Nuf`WQ=gd9AJJG++04Cfle9Aa#W*Y_L%piEhJTGKJB73`W za`z1EOUa^*N@t<)J^|Yr56kq63pX62rNa>}`x|4s%%%MTlr~7vre2DpGiFvQQ8xWb zL1pyxAYxp`poAOlkGq#%u53+NHF*6n{8Auavz%LF@~|q@iyc$RW0>WCB;y1E$6{Ih z1=U879-EoCJZ6Aj;b)4d9xW9&{~KZF{ZqrJo(fyeX+jO>D33(oxUo$V5OFl>vm>qB z!gr>jZ^Y9PVZXLVc>Z^;Gw%;Z((WE3Gh4rz=l%>pR0<1O?!a@LEq72OqtA-!G-z z(6%E>tguRY3rc1b^E){qF^cUR`HH?LWnx-O#~_9*s5?7MD09fWNl3;g?>2g`J4IKf zrLu|8g~Z{FHPyd{R%HFNwA%GIGceBsP9uQeOuQ8^tWHz&swbw?*|5g21+0-_l=BmE zrwmj=owdc6sv54vx%oGw@t+O3?zbK-ORyj~n^(-v%NB;?45S{&?e@6RAh@xXeU9t| zqrmwJsIm~iP)T6nGWtebVSHy_yEYznP=dQm>i541)B?jMpA~tlY#|=gjI|vr(LhGAB`lW0F*xJt zyEk4qkQ=+2Io)~reOkhZWMB+kr0*&c95haKuMU)4Omlk&Nk?dNQOOQaSbYj)Fd}U< zq#6&B)vz?q=R_WFRGQN49xN?urOxLK`(s8o+FCMJWEX0$$^I-k59X0LkLTmX()ZJ> z@xQcc5JLu6p_E20`j^jw0!+wT2RQYMKl{R*kK-^Ioj}QX6;Po@qYIa}B}KkE9fCPN zA1+1y+@&L$K-$XMVnLIJ{;5S~tfD$XZJ6D)4J|`D6?y-VHdVGzX}flCW)9~iOXAXB z=Iwb_KWFj{Rz?bQ9Q4$+j7lA{;#`jxsUhHS1hczhSAPzEb4Ld4nrZOYL9K|tvQm8BbWsm`ll+GM zg{qda=vKv{_9pL3_LBoF%N9<}gldkn2G`c?0es+Bz^Sg;>!P~&N4tY;j%0X{K0JjM z;arxB5hT$z?G{uB3||S2x;kX3&5vLUJ0f}JPiQ{=3kHD7Mk3Sj9sy?I<5HeS)~U0^d=F%qN=Sa$Nm4WYhO zOzqewf@;Ff;`MG#N2*Zn(^!mC#q1*!=n2f{w3$y8^*_A=%1SsPGaFf{`Af}cZYd?3 z)my8CN`)f<#u&>gcrCfspbxDE}A}_^BTq z3zb&n+SLy2JOO{3(H~Q@S}KQ0O_3MB9Q1XWNda;a!mi|(l(CF6+zoWbsm-(O!VGPO z@hoo;whrS~(H6uyI7$*a5^%YiAzA%CwOi>_?p~gXC>7P`!hQa6WVX*VzNNa?83FA# z=1$lGdCJgl{{5C!qG?vD6`wnikhU|-cv|gyPKy@D6xGdg*$|?a!Y&`pEqSxBa;16M z?60w$R(k}eKVf4BJOO|6hUl?ar83rGNIbeIi#~!%05v%pH1T5K9#aRER#eiq)2A@I zV5+*mJ_R{b=TVRJ;uh;Lb=;OTMD;O1E2)Gl*-4jqVQV8INTR%6iCY7n9DskU7Y#_dQG9pF<<>Xk zf-AO_W?A)ZK;4AK_S~%BESwX(VvuLP#M(M-eI8v^!sqVTn=hU>_i1%EUBIYn>dpQx zbOElq`b+5kp~u65<7rF%QBYgOT4kSTydvlIwDz9J_OVNo zf}B;3UWZ>l7@DG73M2Mi!f>_8VCif04+&aiWa6_42{7X9!6bzw%-9wQfD}?%YDsSV zcFswaDVMOv)`l|#7pT*n+aK1X*jQE&k(?`Y>})A3Z$tAE5(`$+>kg`DVBUc0eG+d< zj-Q`FHW!uI>QEUtdCu6}&1Dbv^1hgip2B`nfYP5$>w4O33)^utFGYM=TEoojunV4I zMZd-|*&NgFvAyP)$G;t1AuJ_2Qk$HR<}+8zs&U^ko2Rv?Jx75zjIY`PXdR(|w*P@# zzSot6XS?;Da$w4?Wt#*I2)G$uqGAXPc?}#V5$!=V@jl7t0Kk@Us+(J`3DZ8d-okA+ zxT9mlr^9nJKs{Y6`y`| zB2A1W%`ls`2PRDr&^?rT`cIeguidL3 zj^;nPSLyJm>EC1jnBR};J%IX8zSV!a-2dLI%Jydxp^Dc~zPH$EULH8B^OS4mZYnLm<+Nm_p}*y-uGlj!NXySp*Vik4-ZQ64-@ISE*q z#<70RWFi2@ufk42_a5kpP6fy*AwdC2j4Y$W`^`43I-W--qjvlDGtRvkSxeYyCQCtQ z{Ip7#j#WZ~)KzuD2Czo6xCNCBk75KzX(_A32)*7OK%5^hhf(ktzuMf`->SLZ#1pcM zGUicgpV|f- zoUu*<;Vkq;S+gmV=)@2?z96O{o%z-7_{e$kO*1G2AdGycK8FLvE{cfj#q1XRV)4Ys zxVSikDBgwv5eO*CiY^UUbsx?Sf>6$%b5yy z^|x^kEpaZivf71|>ewc#+ugUWWNAq#7}n%?(NOlvAM5Xc z{A5PF?*T@Icf!rfCa=a(y(QATQF+}D?;FUxMX?44#x+S-N!hU&fxX9zH&HUl3H$&7 z>$S+U^&1YlfO`BOmRyM`7NG?k*LI} z7*aj%IYgzyl@u(SA;ggW+C!Ft8L@L1=$cn?roz=!Q`3I+%)dD>mqNI>GHcDH=7A3p zt|JvM;3eNPcEd%_%?xKltwKl8cDY`gD=to}A>6CKo_RjUTWjf%>1$jbQu>KKckZyU zI)EA`VKnG0XIEFVZB;9p>CE~pMIFfnzbbDz6&RinngZRyrGZ3G<779rNQ_n7ur^G0q_P5U`_g6;`P!Wy6Z6$&Pv=N6frTD55lk zOiX`RGNs$g+q)IB(Hn=F%65%sqs8?tGb620HS=+IwKplrW#9H(LFq~jlNZtN44${u z*5Gzv$Wmv*%hvVSY7jCp5_S(3heO(mMk;bFO2?eT)5yZ=c=#UvdGy{v?ASZ!vWv&+ zTl#4FD3a|(o9x${2=VBJ3n_>f(BXs7tG_ZQ|4g|35ySssLjEP_BV=l1^sZ@QWngHp z!Ng4a+s%(h|9bGS(1&gLfN}n?F~0*qze@r91_%8n4e-ae@7wkK%_#`b|KG z`CsBS0>5E3(tpEglxS6df8781QUBkNJa#sw|BPKxih-5XP(m6wGk2}1que(+6xkad zp;N8r9|$HPn_{y;8bA}!O>LU{L2W4tjs5Z!9epW8gvN*jvCA^&8+}7gXApi$$ckca zC<8GDLnoII=QV;F5xSd|v&433IQ=fkU8Z}x-T2u=HW9i$nuuX_i@#IHh}oCt`dBF# zS4k0;5nID!ld_bxZ^IL>so&=8%A^llHe#T(j<$MxK6!u)p_4q%A8djZs!dwPzQ}I|2M6OyK442xt!hw2t)a7>#BwZ;viFR6=K4yK! z|L*2$+$YgeQZi!Z5&$I!#*oW(4KgeWYC`D-MQ@TJ1VEf)JmtL4V_>+h`x=`O?Kooe zmA9Kud^E(}fEXdjf`Ed$7PwMzd`g@{;I11&LJdy4kZ&WRR5kioMGxq91`-8HGgsb6 z0SN1}{GL$qXUbk!42C;0h*hNabw-Ag*)lkth}GoDt)d&F@k)6?D_9s$mhv7}L4#ZV zr%6g3-4M811WW z(XT@(#@LbwS74)jqhyfk(fH$q<-7r5jQcf{5U1Q?*-QF7_0Dzsb34 zC4*7vnSSN563Cjg!jFwZgAuO_f$QnwsSRE%tiU8Fb4HYk$nymVB|2G~X9@KX-U+wg zXeZ7nji2^_;_$&aYp`W(Y!^eRHC%MlnlY+sLtpZ);LH zJ03)iN*oqZYMX&!bAZbe8X*?0*+koLv2YI?3r6=iB-eH&=4B+j?R>D_{5qn(!A3>F zNN!hL=-*KHJUQImi;PLWK0Jo&>=%#@ocY;RJGlq*fP&$O-44WJnGv^DFK|gf;(6g0 zMA1PL$c5T5(131dgq6j%UFTrfJ9j9YHM(3wy=s2puqWbWel`u*+hUKV<}b)}p!oiS z{FP@K)0aEulE+G!xx?z#vd%3>A>-TR#tifM-Cvocf5)7@YYF`}7XJGij)^AGFt8}7;St`YM-{jTc5&OrYgAo^jAKBnJn%?F73-uI94$Mmu14_Ne% zI<~)+KbHSk?_=AK@(0BF$9C-RAn70FKVaG4kK&`RzwiH}^Z}gyG5@Il<4FGAk|Q{>G&LtIP7y?8i#KZ~oEf|GS^RKE!|5 z-}mGB^YGz+OX;$IwE3skNa}YLCu)Xw6*hLpcY2wP?N1|!zq+gbat!egMIOdKi}1a- z_Qx3FqxknR#QWa<)$8P+8Qs5<-}?uv`ys%mN~`uE!uNM+y?+wo)3?(zFgJV;A$eEA z`&;>UExdPyzQ5M>v9K_;`OxV5Z`kkOlz!f2`hHjC`;*wu@9^)3q~Cw4#P=TKVgC{R zLTl@2?O^yW@uvx^|32XU`{HjM|D*2rp8vM=d-1Pz{QjMGkmKJ^l%v(xcf~>jYdgb# zE%5i-KgxeWjoBC(nE$ikTDdEvs=~tZX(Yb;S-m(VeQGvIZM~T}b}4c?c)DDQ5Ez2& zF8L@CJ|rZOWH`MfK40>l8VSEmziUa&{JVmWs)oB;GmF;st25~MLDQY}+aB+m{Tc93 z+_BzCTgTbU`k7}(B}5H5NO)iBAr{guYTKe5*6wGk$5$T4w7$`l?omT)!L1Ips3p5y zM5mo&Q(X#7N#@dY#*Rh5cYr13h6BsXU$;h8ONDodA~IS86cnUim6~hQ<$O&zeEn@9 zafgM4MOpOw+p2-#5h^y)Co5)L?~p5KWYK_!z=5*5<*+C?SXd4-4#HV{+6iLomEVz=i04h#QBOf=7DtwHASbMyF>QR$Yi|2jH<5jmTdvJ<4E`$ z+a*FsPP^!uM^EYl)3(MzqtJ!aeDkDo4Ib|oD6Lm;Xx1MdDmCxkvo2H|Ty=zA{cY;* zjQ13Gh%CK``Z!zsi=S6Qn0w{7ExUaerKt$l@v%a&d*AcIZV4R|DSv{7FxE%C0IZ5; z<2xo%Mm$5L>BZ4UzQD1Kt|a6kLP7Y^tE~@RmFkjZLwJjz0clR~ZS(UC1UZ7V1s+HM zJ3a|j=t8Jeuf;a(J06{pETQ@d37@DDL<$6fF+>G|(oeKiycfax9fB?t;<61?6&)o| z4ZsY7(F?ME05PX7wS+Pj2X+T@kA7)cqN#ySXHF-%q^?fYmxF?umbcn95uRBqgjZeENZ*}aWjM`4pGL>MXm#Bf zV;X&SOibnV?+C>m;w861AX1mEs;%^xVVI~MvYWgdSo&qLx71c+J(j}0cblHIYn6q` zd#8}oQOQq)$Q}+QJa{;o#$wImX8yDF;A(!{JaYl8W(*zTTdcvTjL195Zfr}K9JPs( zIVyudm<0OBAyE$47Pp!^YK}^;ht#Mgf611_lIsNNC{wE9V|m@k-FE`Af^|FjKe>p;;{ZlMk6%wFDTo@55{(BFZHmC?;M62HUPA29)CZtPBeX za~n!n06W0wfyJS2q?js1&`H1VRE|G{NJnA-IY@YTINsIt@A^aS&rcW$8UtK)Hslpm z@oIhGMnvh+}#O@x5CmGSg_--fN zsZy)5p~n_cwj6A+OWpWwuZkLP8DVnd)&r(EYhvANI!EOJHSALVs&8jn9IvR9K{;!M zrEz(UnP)R(a7>~VxGZmKbU*^{$;H{!KDe^IUv5$i1uJn@%7 z#)Eu}Pr$z@OkDuB@$fhHy4wqNc=Hhq3Q#_nuya&y zkHsr4D5fh1#@G$U?E0JO(#<--buMfQygCn-%(Zbrh^8OGeuq5FhDp^(fl@>dEkJ_D zBv0aU&AEfH3%c=O!#!=kEy}$&i|l-EFzsYBGWyD|%&YJk%YBP~gv?1<)6 zIVWa0q!jP7!ekJ|U$U?<(t~%CE&Iy_MO?RhdKL}UNrj_kZ%K)<|ij~JsE zmc82S{PP%9w(j^nUSR+eu0~kT6r_8Lo^4^T2_QSI-tY)>bZVa^ZBJK>Y#wJ9BAl9kYWBEBI$e2VeAi(sL_Am*g?(ybK z7EqJu6>Jm|ufM(@C~QKrjkR7iw9rw&DNV$aaE=gp@9dvs4J~D!p-+XWdNZN>Ooqv$ za<%EFkS;Ht8Ur^CfE}&Lgs1;Qo?H#5n(qcD1fSZsm ztG$ah41lUs_%ep^#QrAP(qANF^IXXyqfolZl#1&u{1C*U)T`~@#h!+H`AidJNv9={ zcyn2|sD6!#YLHdRmun}6A=q_^l@H1z`GYe#*Bz9gkjQ#X z@`k&o>nU;-qynKrb4EPIcE_gwz-o2L4LB61{K8D6LFE=9d(yV}D^$EaS?eJWj0B9hFt33Yq-C>O^4p>T$ZjhU+CV5_oh@YO1s>#J&5rA7 zzSTpp4{Rme+EJ@z#Rj5Jfe*1%sWgZ7>Py`QGywZ%UuQmPZLLSm$qzbnyh>nc}&(xg4bm~g~wgFE>XhP5R|$bMiI#K)yEBnWRp!6qr3bTJ=l!?de(1R0%U-}l$k zuG?RRacmO1iJ8{G^@37l7y{j|lW5O0Mf$o6Vj@H=o~G5~*d3c7riz`Rz*ze#f`_}} zs$X%jxCNg9Ms~K)KeyIO%%pmS1|<#tGC%AuO00yN820ak#fp6d#pXcNgSN0CUR47v zK0DR%5vusa?RRz+hEwOL4V1(eq1rLs>lp^O>+M*%j5lQALxlOtV>BixZ35?p=}Kdz z=G4#6q<T?>)1|K-BQ8`9xq3b(8&`;W*}M3A^D_DexGmDn_;$z3B;-~eFn1{c0f5`h;30FcW)C)^3eckoflFGA z*VC({qs|m&(2w!pxe5t~zf`~2=#xQ!A_QI_<44#obULO!VYRzGuFs5&b#Vsno}*i( zL946s8YDJan5|X_ree{vI4dO<^^64O$MhXC@Tp*qlybHn-kv#zo_|9Ub|VJ=T9$7q zz{AffRwVKMK|4|e z9Mzf9-JTjwjh)o#I9a+MX2P}HQLRTGx&2v@1pkZ}wWLeg%>xrunY5JEjO1y!*}@gF zQG(Idh>d|mi#y%(VRGecsRf@xJ0=C0Fg;!-qq1Vp3siHCI7LxTZnVLMTSl@Oznc?d z4A=qW0M5gXxjFv$nm|@W5Fkl53&3CAT1rLG6{eUymO_O*p27AKU(!!P7ilPg`Pa@I z^p*u;l4U}x1-q7n-P80Y*SHIC`x5W$LPu@Vw*w;5ZD{Xj-y7Zdasw(?;w8|OKA#`d zV&{lC7Eq0*Ozw!b=S*N`qV=Ny<1=)LW(Sx*CMd<^P$4Cdh1I#U&0!2-%WaYQdA8{5 zPjf5iEn9lQ$WDm;AmP-GIF$kQIy)vn}v8-zX-jhwA zuRbL}IMzs9p>$Q{1Tm>oM*)n*@<=ca4j1t<$KiQa83Jv;#o7uDdjdS>SY0Wv=c-#p zdY+%r4a|M_r1_*BLWyWeiF@>liv5i}8{Q>kRC}dkH!1BgvfB65eW9g26;DEj3A{Zb zML(9Zb=|VMsZ!Ksw2=7K={lS7ZI^>>4ATn$CYiuCYKU+u$$+qxhYrsap8MxiH3S}< zD%$I~oXi^`xIwxv_&Ei%i7h(J145@t=UoKvHO%!jymF*&VzSRo{u{Jb2i+8%Z?K*q z@sEVz1^v!ef54e&bH9=Fx6d>aZ;YCB_2o*RSM|GZgRsg{PABQG+6B1*4KKHu@9lsb zl>~@uS_RY$Z7&&WA0X@zTOqB_8_x>6*|CsQGBdvq4T^yRQOg<^+tGvW4D{~`jcf1i zH_sLC>?^=eiP^Y&s4+nxy99=4`3u}AA?j&b%GX_TW$@XZOfqoiQ;rT%^v95YshHme zt%bcQ-l@UW#(pqiYj*SwhCop1%fD2YrQNr(LSx%Ns?AkrD{e5((p$q0e4=xv3f{PK z15X`}1axa;(M^MBQqT=nKgiBNS_Oxyd)P#QQm*wM6=a}#i{Kq8U7h5YKhOu*WEP&8SMh4jyGS6Hk z#~#X^Xf4Q%BcnRq0CjHTsHQF*S27*(+kE6gWKzu7OMM^K2%hf(x55^}rKo&}r%&}; zrLXvUZ<9NZX`5JRu~^V1h)E)|r+KAAU(q^4iR%!H3E+zO1?m-@7dKP9(FhMe%}YW@ z-?iMNjW2~;S-h>oO9M^-q_3~9Nej|KX_C!H{hHpbL_caTrY?)J5x=C*m>96oPL3%@ zHjAzOf>D=M(;zBPBAz$rgA|>Zl9?f$C1N}{C$)|m)NCeQ2bCafE63nS_33`(s3K&u zDvPX@NcuV(audGbT& zJq8^~XFA(ixInGGNmOiHbc%<-aDH_!(vzd_2{wxf>%2gRSJ^&E+3#?!aW#}xazc-- z1<(^Y7eRvBl?+N6*oFe?I>|7bHUC;0T2p0|)!}-5_`GKx;;nH#A0orcCYW_{((KWy zf;dTI0Y@H6RX1SBagY%Fs8<+sb0pz%N{so)-`nH&d6k^Pt*D2fT1|j^7OD7kDRVaT zNQ!vX;ycTZ9@<*L7J>^L_H!vWiQx5~QuIi`Gp?SCVHjfgN}kPA(U(pU_$zra8RYrH zbN8^PPvy}uNi$({oe?6TNS_MHkV--pCwuAmo`Py`!Wsv*448EIGsGxkfMqat@6D(cajjX-F^`ETkqchBgGjSFs3f+$&4G;7z@G4+%_-pD#*PkK= z zf`jy{{5mrWz7kJQcw|kxb@pNb#?Z%gUfp;dCxC_36yWxqIsz2hBtU8!E<#5@HDDlf zQmPZBaX|=1T!Sftq{YS=r~)_bd>KCn$DCffVR9cMkcGF(7ZdNu>uJoOJ9XU;@O*N% z97$``dlO`78-$s$hs&m+Xg_r5*;%4UhGYVpR~%dVTezahl{vG3qq_h(3NbWK}y$4@U0&CLIq-Mx~q{M?$5w`G4|0gnkSEAF4cG9Ceg^U*BE)G@H5uoM$)=G;>Ez*HWUXwsJa=1y~?Rp+LI4ewUY#Vi6ZoRC50(3P4cPXbeQGrY;N)CQny@fHx>V#$OEo5xg4Z?kpq7NuE-(PNu~T+BU(ygEPf(l)@F+5 zoD}p_+&tXTaicqfuJMT)04h)3=@rWo+jE5LG1Z!wR>nK(> zu!A#yY?MiBJd`KKGySiQ0EJDi`^SE3)MI-Hn<&)gWNgf1wi^={ZU#|{C~g*Tc$EdH zG4GlTkPYj3lJh2s!8md>4+K1E%wm+hgMD+J?H=nH`?wN@YS1qU>V&6<%yWUplAEQ` zvU`kBam(}d%je~?oNj3;CFC+0XcS5b`_e`~1*eH;hmibh?diGb){VON5RIrc+1nEh z@UpsNyTJzi{QDJzK?|WtXWM*JHlRGs)o4YwUgew^Yr>pAbK`a4ButZI572b;vG0&c z*!cFyWXf&q6*Ps&riAjw-4;9>IR6lb|1mwu=Sv}*;mE<9c9st*!zeYAco&n++rr*Z z_WewC#�m+i)tLLBRU2DoR*Gr8X;AOcoBIX7G^i$fD;u^MezjNDn(=`#qd+cAq>( z>DXHnel@#|F}oKvJRdzGJKVP*`-lKv18dt+z1zZlsr88YpGlp5Ewe2RGLXF4~v^l0P7Z7wpND zF_KLZDHc->D+p&GmLoo!Fylnkh}5`jK8YD#SETGIO{S7+n zI_pF5T58CSjL>7581GW7(+UddNHSE6zQ^xoFazmjnsH=aL5Xvb$g|a(kKo5FOyQ`Y z!2LAYK1Ifg=EYR9*H7XUia9XMt{B2S$*%r=P2el1{1?=F;5CgpojgI^B%6H)x9e$% zSr%=L09EtHn)NGauOssKchEwMy+Nmy9%mPDgT4y5+HVhflb=#=^JO1d&Q7~h0XBus zcsyM0L>6Kuekk8W!axP%Y}YA&1A$4e!D3&x-!aNsa1y=H6Xn$t#{eicEpQK{QBfVx z#h-vP(xj(HxyI7(vS4&3u{7B(ZH}Th*JbvEWu90<)pwng^qzOI-?xUR>0$*)ml90N zKS%BrtSC>8G9tX{8Z>Zg?J%><_SXADB5yQ~-G2r@?mHJ&AQS^xt7@%$HCy&R8 z$3fpPhn$+Qr5s^4FK0Vc`DZ=8t^;pC$eC5WN4k;gaZDT;dqzi5JVEC$rCIz7`H)>*9?~Z9z&!b#W?lw&=AE!!j5jBsu~_VLW&m$q;%vLu~<^_ zX%ESO4U_D7LlPvv&jlQvZ33=gDe{m#8metN8y+x8Sw>N=beJw=Op#d9W9jPAqs7SUW2Yipg-s^9HEHUG!9D zwKmy2bDJ!6v#C4R$R}6&B^o`U&j<)sGA68RcpZ>hnB3A{=7Lqyo_IKoq2SWpu+_DV z>BmMT*IjmLNaBPNjpA@6FI+nnHw?NeGON(((?=9`A2})F;D7Uz8oU>VcG;`i$WU9Iv7vvCcLr1}Tp*fS9UiF~z-rL=;k4SuPN1#w zlNN?D=|Ga#WfOI1?LZe}~P>WXXsP-p`bsHI18n*?ShE>f_yGYX`W{hw4u8y)nMyHms3*+v^&34)~n#Uij_H%TCaU6t=U7O;WAQ zYr=uG{@Qcy>%wlu5*@7iRhU)0qca>_I&k*)YD2LNKsUamYQh4J%C+`Kfb1lz6?4y8 zs`{pava$jp4Jz8t#EIXLd_0;BvrYH6A(JvP#rI5%b6lc&wN5g(h{;yRpuNP|KZ@Fa_*b^XTd* z*A#QnPYcpHuPW}#Tt2*WFkeW1ej1t_%&Mnq&Rw2aURCc_spP#mbT6Pu+D!fRU4Bd^ z_;Eh>7}Up4)WYB~jGCb+-FdjMM^9PdlWzS%3(-~~(sxpK(MzH@u^<5hA^^+01vj%P zms|BTa)J`>!cva`W3Tu0(2<_KK`qHqu9FE=eNt>13pb#=Ur3`A3g4sDZV3^fiy5bF zUB5%i+f83;G&2w5;D3LXIRk}05Po7Qk4icy=?=i3qYqpx3!p^Idj`upi&`({Wv9Ym z({{z-0&pe*w(8M-iJaS?6Mxj{iEE*yvWl{Dz4#d}m{-#X{ATKRx!;kI4fEXc8RcOnvxPefg$TWGU>vrGUVp)s{YH=d zDdghsg!BIzcV_-AOQXe~_#5_*@R=6BOP28A^;}7j*N|0mi+Qj&^ zy(Dq+;qqo@zRV(ss6iudlz+wHAHTmV1Y!ZMjC=8p!12j(U`qz$%;ZBOGrJTCpTnq0 zjAz~trRr*OuC}++zKI7nuopd7 zfC3*@d^=0+wSo{L_Hx&-T$&b$*g)4N_@4t0W`YtrmK{xN3pvDO*sh!ECqbX=oHoE&!Klv%Bww%X&CL!V3O$q8uxs6K`B{_C3_>(Y?m8YK#3I1D`41Q!#G1h5V;RdKApTsn{gefDK zf?E6B)(*|awe@>058OcIet+#r&}OYRrwyeF0}x%tuKj609wDecf#yxNcG&y`l(;l$ z%N=4U4MIijQ8c#7Ta$~VLI&kcnfQ=W{Uu4OD9}aUww~2+Ll4I6Iwuxvnvy0P0lKnf zFYFH2AsHa*g4x4gZa;OiQ#OzsB-u_)IN;Iu35=5Gn3-nxK-+XDPb{+>zBK~@JZ-J_ zFHkOP>^0aNgt0^QR~=MU9n3`^FGBDh>)GkX5331m!4Pkv)a-8AkAfv;@B7_1BATnp zkmsLJch5^~Qpnh~*&bX4F5<3u^w6oz6q$l?1?N>PoNc58VsU}p(RUczk~JU{&=)Dt z`BVO=S4{=nwKzL~hoh3>={*y~9J5I+Jw6Jma_h{S+0S!e&T!UOYpiSHxHAE6__9i! z4cdYzH&$Lg_SV`}xDk}LY8y2H!;~HNJ!M*6s$4z~P&Ln#;PK1xLSM!C;E5{J@t5== z%ZL+_z$uhuu!>HHe*ZPnriP#lx6---diaU_j=B-cGhe4nH_>)boxq24Sk-2Q25p-7 zgW-T@Hjn$no7|f01aR|%qgC>(_8;O`xn)44l*D1Zj49=U?Ot!ro-_BG&%Ih35tIE6 zL|}B%3OWTG_AgO<^!TH-`=+AWDJJCr^|4wGI zGrlLt{c|Q=2@xR`1%W?hVf;g(_1_bI?;PKsQ||pe%kF#Q{{Z~{4`**37iHA73(qh} zNk}s^3=$$pcPT9(DV@?O-7zR74h@1xDJ=p@NQX2C(jlPIDc$|;@j2%`?;qbeU(62` zVeYy2s%x#i_OhnJjN(RT{KKLJ}9}DsdKX_#C>7ilmF8kcs6`TqT&OQc) z1EfcH?SF>~%2|8cTUu)=KKd_(C_7u&TK}&z0dJ;mwjqQMt)4%#hFC$s3wkpHk%eIV z*9!*2fMH@`V!~jU*tf7Sv2by4adB~QaPV#u;^W~F;Njrl-@zv!BqF*)go{s1LQF&g zz9&L|2owgc0asySViV!v;DMk1e|+7vLWprNZb9Q3q^7-1|B#!PUr<<7{IR04s`_h9ZC!m^ zdq-zicTaEM$mrPk#N^b^>G_4lrR9~?we^j?{e#1!Jf%&_8 zXwm*j_Ww?>7yrK``!B)%mt4~jd>9lM4@L};hFlr$UzO-W5cJ7N?>-qUF^EYrt?}U zjfS|eQ;o3SNz1`xMp7%VLu*%%aBvk&H0PORVLpThd=Fm=ly<|9Z(nq-Y3@!WlLAo+~&&)U$2AUi1D2nHVqloa2q0EV|(N&yY?%HxfQ zCqOhoA`)bn!h&`1E$G;xs9O*LaC_qwBw{8h!%c>uiyg|lCDWB46G5CYgmFij8jGLq zi%dj1mO!i`8DxYV8U}`~fhqSao`6#orzZz1K?y71BnNBpHFubFqJebU!{}2o>9fB%cmci%jZh|P*6y@ObrDG}R&4enyC*V}VL`);8%UNv$XVY2%$h(nLcZi35GlX~2{^VZbJj z*fIFThA^!(Fs=PIl_9e}IhHs%vUss}RQ>*=cfz!wVcHmc;zO9|H+4v_AK|wX4PF3>^u@=bVTT&KVJNlZkj1-$kAyOZ6=DeVzs%UlnA8 z0Bsoy;26Q4kT#JVOE(!Dc?dskzz_zp3_fr!MF-$EP&oPv(#EfZ({r3-sk8z#LJ186 zV$1X5BS!c0KjU{om>4o)wOzD9>=+bePPe>i7vg(nwQnbU7WpBX17lz>z`V~6TYuB~ z18SMjTB_QWe7Sa;IE8W7-i4{QcLj-2mxpQXzbA7CEdj7L@!1gU@rCAR;)L5vlHr83r3ZLmL8`E3{G)XhJaCnH!nZ~2Aqu< z9UG6>p?O~5x8Umrax_FqB@d!RhM$apIAKd6^z#Ti20w5{^qVmVIgnj+YK%;-emU09 zuojgpXk4xMajDVfkJ^w@*_>;f+RQ@uI)533pDFm|JR|RYA4;rxeCZ%3 zyg7mPQn~LStiPj`h%mp!NTuLM_6ddu2B#MdiAmPr1r8MMrX;5i^oaw4X9R>!j;vdT z{}69ljt{t;HxvjHy(pmp3-Seye+aZ9(?u+U1L9-WGY5-d1c+IRLG=*W8$=TEZzKXS zof5$l*M~%KP6`-f@odVsT2L*75_J1RRKW$*!WgV%Je;3b5@cy@FOLeCDQLMMOtg5G zjLb->JdUjK;`o8)F~~px646~v0Yy~{LGyw=p>SFan9$xxJaNjB|0onyx21#=1%?Ye zFErahMnT83lNZI=$%GFgUQQS7TsTo+q#$OG@-U!hLri%-IaW@ho#^->P8fg)Q~fj4 z0&pORKq%0Y-JLcN?f${Q712@88y>_Chr{!j`NW3ZP>50rVmP=$oeW1-2A@#_lMN2; zBcsR`jl~58bS6#FFY(O?TXuPry6?Rov& z@IFlFU<)Ai(g-v*(=P|-@ero9y$j46cnTOHz}+fiARX{$;9#7<&EnCX#taO#wW(@l zZ4ZTOs$vmOgc5)sCCK#j!K=Y2@JDo-*f4dEd^z=tlf2sse!%*a}lWDy1*j~Yawy%h3DQ6vx3iQ@&c zD+d7qA~xCB3R4@lNz&wK$;a2^`(XjW`NAIA);RJR-#TyTPD;Kx0^~Y)Y!woGVjBk< zR%nPEWaJd-$68UbRZuvc9qin1uM4CGNwg<16=o$v+NAG6>}fT4(@t_^asHVWCl7|R zkVb$2K^VbK*As)m4D1*asXBteM#i+w6U(b=g)hkt+cc>gaQcaFVJJ)tH@;$@lC$<7 zcBN{IL54-gBRFHnka2crMd*;lLVNr%Py)dDrYGRW0UDThffVS`;7obt0py2KnU7#d z&;!#qfx&_I;jD?f0mWy4lx0B&0zg^}U@Vz}0>}v(==bAXu0g|Wkce+PV?#_4$XR8_h~XHa2>`VC>D<}x{PD+A@*$673f@WeJJ z<5-a4+pymmJ^YW0bvvLl>WIjt9R@2yK2!YX;{r^RndnDU0ou@5Q1hYK={xX6k8^A% zJIp6gJr;DuP&m*u$l$Re@1aoI^l~0%L@j`@qklsLuEoq}hrtZ~K?hE29D1BGJRlFX z9{}?K!QKP>!rkuo0;HV?1yN1R1F9`VHH_vj+MfSRs=*6J|IfiT(Y0694FnGi z6yG98Rvn}&c^DNMjH%lDvP&UA3rr4JvaxCq-l97bWJpUQ2Mc#BGP0mxdAt6o9`tRo z$Ok}xmV!K&b!d!Z;826XSBsUZfk0;h;G^whpngN&4O125Ry4u_#6re|LlhLXf%EsC zgLsnX0jfqK&$29S?OxNG@2f#Dsj=i*L(Yq#G#KFhyrZR{AS)Nm5k`BxM<=>gv0#}yl)YTr5qchrWK0-YY_z>k?|pH}j*(jEX+uA~tYum7u*5c#Z_s#TDF zO)wKeGFn8Nqa6`MF#vu5cTur+P}F~_X)B%2%uX6G-Y$S*PVDA#imM89AS4t(-lMZ8 zoTO5G3c3HFi;Ap=>L`T%!neOuOm=UIY6w@V@JmT zs0HtQ&aq;_r?-dFXnx-2ITH9rU@-t=MhM_$KTFWHQcz?$DTd=xv1tFR-+^Kg=Ng#K zkLMJ?WGqZ;3Ma!R9hAYXQ9#>X0DJ&^A*SPri6@YVPKbiXAW)+`1qT1sJsFDvOt}Cc zt;KX0T9G&)rkFz$fHS>(xdp&6+8h8OTKaAP(&$Nr0O67o$QKsh)vZGVlYz)&|nrKgWd*!j3J!~ykT-8G$G#I9vL%%WEOxPa~UL2g#fGx9Z>4&xhxK) zA@Vo>7pbR7Cv#Mz|)qDr}t zsC^)>2Bs|tk9}7$;0uSFGQ`9KObMW@Ks52(8@R90H8Q~5O>*SJ2t7?#D=PUa(xv4c z-5@&ihvL*yU1PHTD(ta8MW)}m$AE>zQ#^rO2PWQ{n9TW~!6_T((FVk)o@VX(|NAk7T?S97%Urn|E{bPW&7h zZH3CQ3hKGE!xR7&TLSTpOj;XykSn1v0+3nYtQZIv4`6DLqDYAzLtaG!ndz(W9SPMS za&}lj(GLA-BcSq2%YPO%r6r>f@;Had;w5ljP-F6dSqbr(#y|Ky0dpIU(6>bnhTf^T zwPWR_TNVuaBMb5*%G&?KE_<^3usrYTq?ZUn+fT!5%{L(Tu-2LOrenqytp;_shZi6E_h1@^C{D*ZP!! z#n_1AiAPqUBbcbAdAhh_v-i6Qu@ zlhB7Z5G4Bzhz4d^rb1F;w-E9?r&-MBvJ)iAz zBZI(CgV}*b7mpo$Jl-0R|zYmY=nZM^@wP9Z$D| za(69{Unicc1gHcl{oEkz2zs#~(<@5FW`500lq2a|9@C{FJpVR8|9e)d*T=K6td>_N zX`)LRMhw>M`?`M*L)a$Ihpq^BQ&FD+wH@%F1n2m@P|2XlF}ld-3M%_oI zifwz?1Pku>vQC=RwjKbR!I4qFA{EvPlNeb1n!3~pw-WD_XVumuPJz)gJWvDmO9rS@G1nXDL2j18jw`3L}MFk@I( z4yD1PLQfk6po5!~2ZmjY6*4Cy_(c|NL^}-YdQ=C{{qBxZp-nzhGm~D)cH0L`KO`e_ zj>&VCxgcl$$L5tHzkb&(*Z$S;n{uT(I3F|4(@8ZM_vCwUxVib-MoajNk9<%BJNB&n z-2xte{=-F{?UC5yjh4A!#i`vgR`R{u(CEh+S(9rwklw8gA2G`A8wjmEDs3`rg?NJV zGfU5TmVDq>%IGhihAV;JE2Rc$zWLJ18HV}Y{S}h1O<~3$@$f2@;`9Aa)ig4B{n4eQ zWnzn%v68%JlQR+%PhCsk5pfd!Wz8WzmIwKXZLxyOr@ih^j@3PPYI;vD2DbQ*-|of? zJuF&JebaHo%hxaczU-ca-pgVa&&dUUkyxB=t%;1}7FfL*DhuPCa{c)HIE$}&EAQET zsxND~2>7LAeOU-HSAH@@jq*=$_gj?+{(H6Ikvd1g{zi2NA+M$Fq)9jURS3f?)hc@N zG_aE6yd|aaP6MCQ=$5k4@-4^x9vtGk#%R}we#3F_ecQ}!F|~z6!opAbP5sfY&hHFo zj{Huhd=I}Z#)fpvF<5fHVb%9Zvk^45pI$ff`gMM2RM|ZcT%t}=(f=_z#pq{)3ERxL zR{*nPOH?zY~+)j@obe;R~rT*a*4;sDfC-^ zn~1wieOGl%23U*TyX)+YE*<;)ezTf6U#-^RM-tE#m)Fh-mPh$C7^scKTpy5XAN4D+ z`SE`c4W=Rb7;T2=5geqQwa9YJjZ>XeliXLD=q^F2!&5Nlk9AfcGo*$NU7}NkRtw$aXz0@qDFy_fS_ZdMS@MbU!vx zZUkb5bdX#9rVcCpb^ZECl!4;3?0Va;jIB0N+4}6Ht~c<6wdu51`6mM@%fxEBS}~mO zA2&;&RJmp#J%vYh`2y-=JfyrjZ5Q0uCiC9CVs)}UujCWYcY;=+=-m$U|Icq z0o0e}QaxX2#a|hG)ypGoh}*w`9G90rmpy8XjAGxTAYb;&s-~_88MuMWJm?;~k{S_Y zuMU#>eSV){Gs0}U#?35$8J;5X2V0#|#hxoLTPN7@-EuWwhShGhnA1fWY6x*yu5_S4 ze+X#R!PEZ+vxl1&bBAD_7Mf-bzn#K-Vc$B9E zIw5c{*H_HfxC7d7^bu*q>2ENdL^oA&GGB1mNU-;Qm^8NuLPh1*B@+ofQ9h(kY1;Zg z7ngR;YkIdSBLm6fU_`ChDpnqq@*wY47r*g{HNs47e6H@Pjk)iDBClH<&kmV7rYYT6 zA$Afjp7^!|^en;D<+C-#9T~zCvNwGpMcmPs`8dtqX?*hIpB=M= zvq^?IgqY5k&xVD4SM(*@A#b}jeJFLCMe9JyVo_uFC8H;&S-DJ2I3!=P^`)Bo@|0E} zu5+#ClE@>{13S(7@RyoR)8xv;>z$$VjX$l?)6OWvnEua(GDt;d27Kj>?I*!D5{sW( zw+ti-^n1E|-->iPlb^K+Pk!zC(oaF5rNf+&wI7nWZ?>!U2lJ9_B+zz&%Cow@G4>CZ zLB1|#H}#Q3>{8JUBvdb0vzn<`%9#Q^`}# z`3D%A!eY8fK^~HuMqS)4`8tF~Zy;MRmL*=cV#JVML#JEpgH)W%Tso76!;2Q})l+UF z{QTI&#{3U0E-e9SaGIU(&;l}2_O64Ar z;4~bM#{NF1OXdGW(b~RWeQARK1%}=SkN$?D;JYV1RK@)Y3aY4~S8`ek4<%TKz zouyAx8U^#D8p@}B_TC;K+})R@x|^pFymn$4PQTJL+i-hpqbPUz0Oi;=lw4jeyJi;s z2fy4?8mA^|r;Of=gwlYmIub)%-whd!ZPN1KGb}das;cOt>w&aja>lzP+g{wjRM)H6 z4VeloR#AqWW2y1h_31(}&aB;K8_%yE@+$+O%MVyy5G@+9qWW95*yo?^^?;}5hJO3# zq&7AB;_qW-lHDyN%=xT)cW-^eL)%qSZ~i27r_rNW*18~vJ&mvbC&pd2_q`H?GM)A~ z2Y(6j>y9W@G?8ZdFX@1X6LSRe4A zXn{@PL#D9JSKD>lzrXe*Jn8z%qQ}4fbDIMD*XhYIMr|9}x!Bg~=1otGw!~9q+ zqQ2|x=I^xkI!*RoQ%Frl@oN5X|0`vE19`xF#&%YCc=jn3v4 zU?vR8SWs#wYz;sZeyw4!f=tb`fCRlXkNo#k zafr;oW_z%XLM* zi<$}EskownGh_zl8{05fEEjX0=LJW~a<>ho3bGrVw|svV5xFpPMXCF>Id(od$6Wo3 z7H1(>scwuHd-Dw>p*_odZGk5-Y$83_w(yc|yiCG&Pv}JB?dztd56oYryGD2z3hei6 zn4g5>u zyP^U$k}Y#j-r8GVeewL>yfXKRx1#LP#}@-hGvZ16TwI{`^8!r^u59- zH;{IE+&wI-#y#$a5Dt9ny7=%z<2j=58kE>QLvb9q>N7_aU>0dFh2I@33{G>#Z z%Nx6G_LQd%d}MprwK`?Z<4|R=+w#f_>sIqKouuE5C_3@npPf3DUzWsTmQXtpo9X9x zJQY&@jc0Eo_7Y>5;B5I`oio}I_PyD9*L}Zlz0_(MzcdKA<2AaZKaYLwZ^?KKS>3o5 zR8FM%B*9=d*1F8sDBUho;Byq%U(C`&HOs0?b`J6I}^Sxr7XQ2v%foK*CX{8`=by1z|{ z1WDRfet-^BW{NxIC|ixcziFH8R7j=#QO{mif(^|TwT82a%p8h@=n6b5yNao2yFS+4 zU03>PqsrXWQ44G{oxcO`*Uz4uV_n$25G;%at?g%*aksBtsdYzQS}cU%^Y#)DVfTZe1u_C#E5%vr|gdZ}?8+U;5%?hcrg+hmb4PBaQAU0* z?#5rXb*VQy|7$MJN1?0riHLDm-nF*+{kDRADIRH0e_R!5XwsI+6#MV|K~CY~i-?A- ztqX3I;}9x`7~YGOpLK^MK!+bPY zoblb+<2ZYG&5$1yW2_Y$IiU4T{Fh76tzA;R%7)>iWowgO&qz8~Jh#i3AS~sly1A?k z*O47=Pbt;OZv#Zz7))%m_*66|D3ZOL!kVCbf;ri1L-krGIY21r*d)>=ndPf}uwpj@ zxfkE?RfclnKrQN!d@t>M_CT}l_^mU&&a&m=4zW1DNN=Z)d13``S0%&K;rpdkMgd>m zG^Q2(*nSI_&>M2^A{*TZ{3EdO)NRcpUcd3Z-gEkt0kJ+dD|S%^zv~`eL$0{!E$$g7 z-T~UU!3#dyLyQ)M`E?HSXTxV~q~F?ki?Ti1r5&xT;Skt98oeRoupm(T=$wc?`=Mys#ygL)!fS26s7;|`d8|SytHOz%ZOm< zqu)QyySlbUe(yYgN0LR0T9j7nJ}AibR@n}cz2G%6{S~M-#FeAfOBTHq8zl}fQ;t0A z!;=e!q7dq4zV^8wO0`q3xd7=cv*_PUvV@t1@9`NGdK}*d+yf_f1mQ|x34Y3(EV)h3 zaKW$s>GJ;Rr1P9Kt;1{2^QK%Hqt@>4j;Zi_b$=fx!|Fu41qZdVD-)eYGPctdH(VYr z#CN5`Eb=_TTF}3qq2)eUK>1-u_2Ur7BF74}39YnA{>rYgp&rkA)wLa5)n^j7}KZdv1$@f>OTgfQ8tYk`+kB08ov-LCYHKYBjc#j zw@Tv7rUoso0h0-F{dRK}1Dcz|Ubf{aR<#);AHu2D#}CaWExTO?R%!wd29gpVm0Quj zXc6nSdFpl~nqMP7b(M6lkKJ0pkE7JTx%~XE!U8Ah*Iwn?E{VBiZ-!&n5X04&r)mb0 z>QA-21mFBZsSJB~vAy$>NbGIp{%gFrVYlMp^QPccz+F2|x`&hTVU72SH_8wl)xbRH{TD030V z24DC0dh=jXt4W8G)a=LTvtY*e_nqMiS$p>72}khT`nrX8^O9NywGTjamk>E(k&va9)obUgyX)XtN7uMXWI{ae$GZ#1Lx2)p?UNKl{D2eKg7_o}K%r!LIq zeO_1nc|ngi))?|pu43cheRSW?TE|yCXWBny&eD!)y}Eo*$xnX@eeHhdYqYqXKcDHS zzqeiLE~rko$@T7C?>jDh+dR!1h?gri>@%#II6bcMge~aK4)LYSo*8Jzk)PThe&Gt= zYAiWctftwfcW<{>#b5R2!4CG56v}5PRpzh@=Ma0m>9M1Zq-40`bS>=5`EZXRN^rok z%P@?@!M~|vvj4lKW4xUDr0?^0qD-=U;j}K2RP|Mei;wm~^*4~z5KWDzEN6L#(gy15 zrWPZ@8|=`u!HLjWdpbMN1P6~Bpy~wIxJhD1oN5raN3l$fCuMx|hfDL+~b^Jg$m zx3RLF20eDr+Rjn6fB%Bn<7&wPy1aM7n=0CW;e1UiEq^xbkD#({Fi6|7AO6s%F)&k<##k zTjRJG1@DTrb*hAm#dIWp3VM7PmZES-pLrGhUBLVClzntU?fHY^@|-@tk5d~ZUbh-R zHsoJE_>E{^)-f7+O8@;RSV1qY%1$6zj68YUhV#{M$Z~p!=S8-OcF`ngqTaU%xFdJ8fwfx@H>gt)FyS)GRWzB+8bf9?l&)Ek|d6{>Sd`mr}YT!>-4o;c@c(G#k`MYw0Y zAaaWhPU(KpWw|RjZ}?*`s0CI@_o8)$%5TWoP^D$T=bCZPw0f~gh)#i>cH_-UOQ)!$ z*nA>}s2j-URyH1GdOIWq|NHskeQRzJb4Q0Qu zW<)KopI*K3_SNmK?0&sYjcy&4#8Tl9^`VRN+Q;rE#bdfh67M=r*?>1gknk!bU9TcZK#PzAP&Cfg7sxfe2z|YH#Ct|ok zJO!@eXFzuYc_l?~nzUdRTD|#>fW*?RVESE&!PkTpKCd{ovL!xz!qf8VIeW`x!$L{n zzv;tgW!Zuu;Awktzi(Nr=W7PYZMl363RZiNG8h^ewiWo4e8Z7a?_~$^iimYXW?t8C zyv*6%0Plg|Op1+-U};04l!Q6@ySrVvxxae}mT0^)T(skZBf_4I#~PHH-WTHSQf#6m zk2;3ql88b)T6=FGqMcfw-wykFDA(0B88l|LvCapO&Rp6b9CFAfOBgMbnssO!&KUm^ zNHXGsP?nPZ1c0Z>t5#q?Y+Lf zf%EFo%fSitsm=KxCH8rnX7E7$#0OD<7PR)3&4gQZql7h(7|DK{{@tvmO|8p zezduw48c(jDHR|`h@i_5S*6Q0DzE@Y@ehB9Yn%Y@#vQ%rHwvd^) zg(OP0LbS*70h35i*>uI1@AAgmmy$Wn#eSGjWqT@o!m~0lpYo?NJ0*hQA69~k0wu4q z8l|1*)g-IKy~bEyS>ZDLdW}HEUbU1t9vhc1zE>n-a4KhwYprbN=$PzO(@6P{S;k#? zA*Srp@R$Cs5?QhO>B+svtJ}LuGm|Kva@_(f6HLnuN z)B4P7M^}CBrYn2YP3>vkjU zEHgDBlAE~3KNUB<+S)2sSv)D@YE|nVE1FB6Zq^L%a1_~`U2NaO626^xcl+3u&hbKe z-QW7pjKF}6Z{C_aGQv!O4(HS7GeHTKx}x6PK)pNabcCvMq?eQLh4Obv+YL+LWiru! zuhyL_-VYYbX0OTzrV_kLl^D-oQlO0b;wy3?=H3_}mCYYD)?!VBv!PFFT1Qu-z$Z-{ zJzv~*YWS{lJijZg-UvZIdMvyvKnk}R-|4fxGS=6SmPiK+RNAiYKFM##Zy>}l`jq#W z{(}+Cut4G6%5K50ua8T@mX!Thj2Q~mM;dk;dEZzt2-usPZTRW`<{kJ_^5&_Z-kZqM zygThA?PN*`?5%PTh*Zi>7w?PZ=n5$tj}*lLVeeq);4y}ZA9<5vsU7O!=Nb+6e+I`q z*=wIEc-*I25+2P`$IiDEsos&9NM7VrDEKwlXGXd);NiABc$+dbx{C6PbD|J-{H*!G z;khoy*Xr5&y%*jQMf(Ffo#JmU9=wr3+#Y2}d0>Mwo(`bW)iUT5Y&SN1%k0Vd`78hW zXjZMDTeO1O?B)>Y3bMYZe^t<9snqtvX@O6yghzW&^W@9vIH#G6e^!83VMULIkurJn z!kvn&w~GRX7r2=mr{Jg<@^^Cq$< zviacwBg=}Llx=YlK7U9rs=3}GfFf(4ZfWW|DGsgb02c1 z9b3{PqvQB>hx}P?jn5^}DcZAWR0Qss2ga3D0 z+Ncsv3{!%40Su7)01+w=8+oae5!3=oD+|jwuslR?1F4+svej<#&(bvu2QG0~1~2>` zR=DbOI&&z6by_F&?8W`7GmoRW8%RvBV`f8#lXCgy{mcy z!BW~MU|0~!ztv!c+4MPf9x1)WSrBqB&L%P-`LN}bl>s@IV5EN z>T|7ghAUNaYI4DT2|rciXxhDgDY){n6{}@@RhUpllu8wo3L(L5r=b);-{LdJ0Q)uF zl-d2_kfRi&aBc2P7~7H_xx*w@u)-z#RdO(A`$7weUB#NuZ<^7v=hV~t*Gt7l0sN87 zKPQ)yd_YSl%vBWj)yuw*LsDza^>`}|NW`ZFJ?D=2PZP(NlMkd??7$4b}2fZzS z#d#PfzI)do#+>{#Htof|#|XwDq(vU4?Gd2#ooi51D+V9py8yq?z*J-ihdgR8MboZP zLrhIwcF-`Nf(SYLR}3c9iAn>2{mBYeGh_rtSzgt9E#xQ50X`N150e8Vrrs-u=xs2Q z2`+cFJ^x7=UC0hf@di?%w|Z9k#6RWkZ}r_#P$Ku(2S^CAhj;~xT^F|AKq$Cj#?!?v z5btZVd9zGgk|smP$wTSKeYpK(G zT+G`z_gZp}cs2fwF6vXoC$n+hhtK6^11uK=q3;!r@vPREqH97CZ- zp^=9Lm})X)&38&s}q}*Yzhq7HOp@J0*p^qcJz|ql0@L=kw%KS`Wq3k?SwB93?{o6qu*9FZm-t?@y zeuy3S)BWMIY@t7Od<>=D784O(zm}ZsN?#O?)bfgFCJRY6C@NF*O&?8Qzr# z@*vgp0k-B@?%tm}`|>KObZUP5o0VpH*~x&X0|@iP49haafNVPJeQ6I^e>pg5ZZcr) z45z1iQ59#ecYqR_2Y6PzfD^s`=pQ*Op%aj8N&%BfG{;KuC}9%t*kUK zZQ>&mWQ;Aq4u(<)Z#ay}4Ncv_2b@L7tUsED2G~0~X$*$xa%dI~;(7TpXh>pMD(B(E z6ywJf=TO;)(r93lE;=549i`|O-f?-CuudJXe;uHAealqH!{kw7UQOy!b;yUaZ25Ly zJtLA$$@gbq+4Nem=UTXdQB`@#rbV*f)@pEq=Z+y_&Mb=ZI=ImPTSZO^LwF$V@|I(t z;_Oh|T{7R8*>`yeiIpaQF}eAVGYOUXO0t%cmBu3Z-d^*|9&cm~h za5wtA6HZG&FA+-KOG){tltXI7v_$b#y7l9i#PTPf^gO}h+@9I1Ee2dcgZqtU^JgC{ zQ|jXweP|*aN9So(i);i+f6+5gS}aEOZE}QgUdD~dcFBjxG7KO9a*jc1{zJvNECy%x z1`J`Uigbd&R>c7dF&JX-C)X1Rg9NWA`W&fn;-b(&=4Hljj<8O?t>z$|<% zu9A6ckOx5Vi-JorWt^H*%W`ERo5X!G>3Hn3kyVp$kHX#6OS08DmqH0w$KUjOQZbEl zgG;g=)B%YVSlz>Fv}-<6{ikkwCG%#T-)(D8{T73S4SXj9-+Zo%UATMXOM5?B+^S4+ zBT3yND_hkPbl9luactP31Zdx2M6U`}gSA|3nXWqk?f@4~Jlc-vQw+`v{w-CU-c403 zdUjH3b%9Xg3@tcZ0Mf35sp>z3op_pcyXk2)fi8~8U#BTK1E|GvtdDKsgIc#KjvZ4% zkCz#xreYzu(*Ga8~A8sPhhVzE#0_V7ySs?4SL~+SSAE z6uU#Oz`)wZsggvwJic9F`|riQHz+5+j+lB-mO9||>=$egG)W$3T$6Xc(zCT;kR92#GzPjBd zRu^MZHe7?*)HKEK_>?*>vag$HKh)7oD~Z~|qz>y8hoYucUe>Hgb!a(E$MQP=BvF~q zCgv(JBe*v=UDWGkyhWeq)!pQAUyYL6)Y@ap56hZb>eo=}y^F2&+GhA3cgwu9X}9t2 zN~ur5CWRKRd1FP&heS3yyo!wI*?rNDL7V`%gNvXiO#E-@ z@x1orBcp{tYuM^u4rZP*Jm-BxJie1R*${f0*bm=SO)-~LiKwaC)Dz7BUTn5qNOoH- zKds{UnoxG*q1o!bVOD|q%k!0cypF$O%a=!24k_o4TRsdv6Y!3g5B7NNr_@mrH+Q8> zdn8#){GwZtk{mAW=ee`u{LcC*k09+rIdq%8DOzZRI0s z7Ap}aAMGsOo=ucqzZ=o*`#<=KUnZi?3oAjNrRTgEzKClbE3miTM@M~{S{^bucG*0! z8vl4>mOj(*;MH*c-A7q$^rpqz|e$>^+^;Pt;tNQLkOP zHv7?HH0M;ZF-CvS(ZDGfu|W9zD0=wYx3y~9DeTdvpuMvqK+yQte+TU{-XhpQlj8Ip}P32#ZKa#-T}lI(f+Ybr!kTBhUX$g|}BkP5W5SGn~ADintY z_k7x(EBESm=S78{oN%q+>5$5E+v|J9GgmXZ*HvZ6vJmHTB;*Ft z)9nKqD=k<4+(^pfiBpWrkTzvcsjr2Xb}JZt!9UF^4;Fn;rqU-{R*U;suX9AqUYXUP zOCRjhXPer)U7xO5_h_uSJYVbQz4TbzQ9%^pyhJ4=4ML7?4ZZtvy0d4r7}E7%THPr1 znuNs}(% zi74Zfb@iBdGlQ+2KVCIRq;FUMrnunr1?Rh3Yn_@`@eI`p9dSI|Pi6^~obyPqrG>^a zw;Koz_5WV71?<+Zwqi)?cQqsQ;*CGm9q^EU^)rk8opCfsRZ7Vj(eR3%fxPpjx^H5< zclNJsHv9GUA7a-jN$}$NGiQqPb48P(uG-fjyKl^MvIh^C8)v(;m&2I1d`?+@#rZ@A zC3Zi0>TTqIc&Q$+8~DNCy{h$h6p`6=wXa8YS@5qHNpGUgHoGY%sC`~n`yS?N7WO`P zhZh@N+S6Sl5kPEuY^M9Ph(pE8>qML(+}3klyPs1b@>~Db+6_eZ$m1HPFK;Q_#So!q)>78T5*8JN%! zBjBdQ^(>bEg?_?{^blBFKweA^JR9wIdy-+2OOwAjxi`8rSlc>X<`0Lt#JVor&}4 z?&M0~*`hkN{wKbHJhPH2wNMtd>RgMNF=Dg38IvX8IXs<*AxlADwH4l2++JrnF}h5@ zB0@E@Txw2AXnPKn{*hcwZZ>>8g|Fjdd8t^=mXxJj+$XYDnjM837^b zwkx$LLd!&5(+R#p?wH^hJCi-d&?*t`0%v9eXHBffq$`Y4KUa^+Z&SAWs;X{1-hKYH zWE-ULAXXU4?Nr~i>Eqo$iYH+0g#D*4Oo!+0nDB(lCq6`Sql>iQ%nc+??{)MX%DTlv zvszt3h zZ;D-46-msIkJ*a9$hLUjyuuUIOiGn*$Wm~pui3+|yFWq;*1mqk^d1hsk0mVZVOBc- zd9Q6GhRP}7G**~g!r5;!Yu{!b162G2U>gK_${a@qJ!`*kxeS`T*(i= z@!NQY*T6U-n?v6nqLu$;(v`kS-+7-i8%2L_eB0?k85j39OSYZ@v#ap}+jicG#jN-F zSZ&do^^fHek*>+-L?_sjZ093%KWbX10Usr%QQ3NaZ6~KH0NMS+bC&Gh8wno~x_fNg z^6t4i{6m38yV=IOgRd^R=6fz>?LEEPzLWjdOI;>sq-$qG2`PxpMMsS{8kc^ay}#w& z5*ti%TKG-t)QiEOqEXFs@o$13XZ0Id6b6xHR@I}A>CZnurmer@yE!i$6NsHV?U*`U z@Xo_hVADmuY@w$g7c)XLq1*Baxz4W_nr@t@h4XA3>bHH}%}6$|pCqYA+GZq3S-tkS z1*d}S%ZLale0*0y`ttGLl_Q3if9{aBV|Q-l%?KrbUD%uENU_q7`c+%zF|w*Fp=Nl`%*$lvJa?XCO4GOZL^o4^rarFethR9VdBS!X zV@Fp~KD=+RP$)a7{5faVS@V^tm7Al^#bLBQw8Ogk;aF96yJTvy!2D!c#(6= zt|FL4D^1Y?Petx|PDJfl{ZbYkEWX0Os0_r?t^fLEAhZ%DcQZQ8lj};z9UTG+h2eFe7uUV3_2bx zUQ^WKUpJK^)-F_>F7!?stvUMBAk{#z@wBW+(C%yX+Ro_CFE6Fbp40COP0vOz3>VuB zll_D9Lgi9Pd3bLfNSV*=O}&_6Nt=PZAzxS#sTYaF7vke~OZofe!gF)2rLiR?tNAvz z8R5r;&-^;eWEt;HeSRJu1zeQUeqwb4=`i8Sr$mypL-XmzLdK zzG>P_6SY^Xd?1v+d2Rb+QAClutF4cl=%Qt5JML-q-k)i%4_}?{EA;Ugit-W7M;{mO z%`%s2y>0>XJEU)UdmWeE0+w+h?U=^dy&{i`D*9=Ld(n5^H|d^6je z+=}Ua6<_0SN z^7cV$hf*gmX%Yv@7zdw6lfo~|SoZq1gNa~;IUhvjbTcN-LcY;f;!Jth%o9b49p#Ay z*DRPQocFOEP|&=ZkSBN{Y#CxqdN$sEH+*Z0gprkTVHA%tydT!KN|_A zT4Cjn-R7&7eJ3IpuVwu*46EM?r4(Q44tp}qX9{BH$WIB=|yiImG9ZWHPLpC^{H_gi>zk$b@}r+eW_bRYsRl87{0@U8S)tiI0&=^{V2sHL>N;XEI6@k_uqx3>CYXqRx_OxI4gj97;w<|74q?HzqM zt{hH5h^IbTrGF=LN?ENL#__++A3EymajWXHYnrP@=Tf?oSza|NH*fjyI{-=itIcuc z_j?_yTQoCR@c#gZMXa-F*Msc}G7z>&IHAQBq;;PP{v02O=Tp-D-#xwbR@1x!APAON z!W=N`f~d$d0ARnDyh=;b& z-%hoPk2dD|N7Vg5)AZX7CdSuI(=6e&)9sK)4ZI2wBT>)*I##x_&`sZR(H&?6L`5(d zMInqLfEkKnB4J9v$XHSYF^4#yWK1XmAfZM%{7z|r!YP3p40Yy{DEg3^qcSti05*X! znV>8%nvs#3U@)9=PZahAu7`#At6W`5_DNOqWe6!2JFj;C0D%$t0bd`OV!pLmweYPM z`TYL?D<7j|*?-iq={4`mSN>lw&gaYD6+B00b7OU9c#+9w5UV4OG5&g2&1N~Au)h5{ zS)=Rl8DudFlB{`@yPuN(02Dkot-a>8sc6@WeWhF>#*K0Y=(hP~RyN=;CMdxT$Q!Up zHN}?k1q@W<^|y@OQmrcegr_%O! zXP)>YO#c9cw^Fu-OG)Fk(16wCGv)NCEjpaY*fso1Omvh4j0PS5dREw~V~k4yd3GxiyU(JnDI6865nUu$I%`c_`&f5L-2;57yK)0yUQzE zMU6Em#ETOmuF&KN$i@KAIN6t6(a=5ilPAdAIPB)dxJkG|xp>N_TRbzWCLIjKjKUwSfTyVe0annC{n0VDa;x}VjU)gHz~*IKh@<|p$102*GsA@I!FpTqU>Yocg#&2#pLk+!Zk{JW23Er3s^YvijrS+%+E z)3UN>*Z2Mq{hsb@7E3rhFD2npOlhpJQhCSBA0xMF z()e=9<)eY^pUw#K+cJO{pP59U43p4TWf^sml(k;z`it<7;}682ALtieCe<~=1@!k4 zlWS~%LjV#w1x0L-xIxsD>P>U|NjA}?v`@M8SAo1;;%!4-x3JZ_IE z3aHJtkRIem6}ZL~pa_be{{USB7)B{r2IIf-rUXTQDgc3&q(nq>k7@v698fWY8UTon zzO=?Lk9uHzI(eqZ7-#{fr38%iq){0^og0A}rUwb*O>kOToiYah07#vGct`L@>Gf`( zO#4@jn`1qcJ&bpI`hUUvkEG%Jx!0-nnXh&`dB6A{ne$(Y_2jaGRaP6YaDD6KF%|uk zUvud}MZ9 z=bqJ`9+y^i*QsP$mf{@;OvoBj!lH z+3Sx=``#MJy^~nF%U*}&{9(kt(L5F&Uab8K=rLb#erQJ6#WVvAFc^8EpcrTZGfKdG zjr&~qlxV&QiUA-SW1jJcp^ZL6`IA~hO+%sh9j{!xKMpk({{WVk`jxzFdzITXhyMT` zRjF>!Fp6`YhnC%Iz95#y4KC{DU$L&zvAO}f9Wrs21KifnG_8rF>^-I8y*hUk@{g%i zRccakl(kn)eb@aDsdTT}3hPMlt)-pEf$qz}W{@qyz94d_6gS=BP65X?<@*%ndz~EZ zD_HhV*{%Y96Y2K^V9l!P5@2KxyKFw4kG*}4My&>X{%HN^o{O!31_yKRUr4q*$g`Dr z{{VNC1QI|$dW#m`rD@|B0gyKs=bTkp89f<^JZhVYAQ|icqm>Tq#<-101gJkzOO**W zXGs)WvSC6!)}_KPpwy+@n$*Uue2A3^>Q!-0FpPFWl$+e?e|Z*{sLWX5ZR9_ansq)F z3tJx~cn?bO?y;?S3rX=z>kg4R&Ro0sVTmkNOMebn0iSyO(z|Il6YJ^QOZGmZ)_w~7 zA^QNhu+vM-SD3A}BG@_X#N($m#qBC1Zdjih*+r-5J}CHyrD>NfCY@|k$aY}IDJtL+ zI+2zcuBbNFq-}d2s-Lr+(?_HDqQ+@qf3xa02!k` zL@|KH0~$p;jERLXBO;g|OcUCMNZJI(ngJ1>l`LdL_2#O;Wa}EF8by?sa{SCbSmVwM zvFJa?*c#`>Vq=A->PzM3&dd%9c)N4jHdm0Dq$e3UKIXn=g*PX6x%Bgrin7@p1P>gyFLQ8z(QW>A{{U$A74BiF zCGS0va4j;+eZcFPTvi}Oj}C(wKM?dxB6l5paJ zRq-q2er3d*TIx53!M|31id)-3X#`f*(4iuf?;u|a@;idl320HB)DX%-J-@!Q6C zA7t=Xg<=CgXuqCTQ{T#tAV2hLR#juqPnWo1EB#u$Yg+uRJ9o1@&hJ!Plz}6S@{AiU z+2_!ESC@gnOA9$lQs1%loJqvAbD9+B(x%rdyKUd4th}|?<)QV!{i1v*o)VWwlf$}) z+FHl#!r9}G$St#O-0sfb!#M3-N{i;)`6p9Nk8u5+p)q_Q@VP00B-hes2b{{Q*FWrf zSJ`BW)UJH)X#MndI^1QOfsvZ}GtG-Rfg5>v#tz~5QDU3ab0z=`31Qx}L^Geh^391#P-u`!KB&@X>kKOWP#7ijx&?bKx>oROw*M!DZhse5){&6%%g0K6s!29Hy z%fsX!`FK(J(u?Id$2`ykOtb+5 zE_w<8iHEfUB4N|gmcTHNYBd3bQz(d!YGXcS;Q=}g?N`;ZBp(@n6lc&3dI@z75@O@jz15=zC#_0c&eA^ zw*I@b^lYmxSPCjT$?pFEu8aEI`LD;GCP-FfSwKY`kzX;GVw4j}=zW%7h309rd@JK$ z5w@p!Jgp(}6rG^#mVSJNvNlNx}U9IvcK%( zrRe%)ua5j%3^!V|r!ZPE4k5>P9>46L#=k?zaya4OtJhxh*!-7@IGT96j|+x&g5CE% z`M?|jf$3jVd?+7UKrqk*WOWrlH1y_xBc=ll05H-6@rU;I*8KbZcHBSu-AWsLdqkK& zsI4B5CVL;7zA!ejN8mj=_4eB|6Wkn}efbJwJ+tJ2n#!wcD%+lJHg#!X=Q=9#{=XxL z@g2UArr+2$m;w0%O$c(p9QG$9XPymZNy>5ejvSK{io{c!#I2r=*1!BWbL!o1<2S;s zL%}+xj}418#I{Wg7H?&Zj#COZV*>{q=e1)RQ&PF~E^5|3fcP5}Hva$x`~>9`OC`O_ zm&YUK@^2{bMs0|XK>HfrsLesdH(=;)|L8|Vo2u;Ao;OH#bW-ydaL0N5;5(k+<)k{ ztnm)iru?7eRV8`Fd86h3004L@*T=pq(6l?N`7GcXTvN1=jL1U94iI|ekJi67uRcX{ z>>(7{^u_P&*=J=OA7uE6;s{n?yLQ6PS8)JkRe>FO_O5Sk`xRZTVeOBHB z8oL3p(pFXsHg*IYf(fawNxF^Lnr_ib=hj~d^s}k>qeQ(PIPkQ-OzP&&4N)YW!0f2G z$^2_ILEh%kYq|HPE1+XYpav002I7r?X5L2>42_qsp`Zv^C;}3+0TV4SBP&y35tXN~ z$k|V&F`q^gLm*)}pe#mD2kS!^!e|4V*6n50m-{*^pC$lzO3Jw`doT6;tDh5wmL?pW z){o-O{01%{zo&n)q8f@fO?8eXJ=a0%Nw5xD;VygGhWRl&Lw|FLDmd_!VKf*@@A8P!gh$!N)b$+i}4PWkS z$@M>B;p|2eFr)R1Jk*l=)AL)SHDi$f0xhlx%FSePmB8JhV@8hv%Mk7`Jr-3Tn_5P zx&Hton)>b^;yI+YMSZFH!PB1ffNA%j1{2n(1|0K13_qO!MrnYc{=|9XGhIuEBD2V>6p0yel_i*ftWX!GDM0(?#UVYWMuwSHrBwE_cA8E zlNj1D+nPCt$YNbyIVTD~G5$21!;@W1N$%Jy0tP;#{AwJ^i2 z_sF*h8Mhv}Ae`4ydow#|&vnstT|)VV)#U9gktg1MNdQ+&UG+KIva&w&_$#I9x{R-F zs#wJ=UTVR(t_VI!l#qRJD_sIQ>VA*>F}}LgycML+bu-N9W`Smrw=<-2x*=oS?NQBg zO>BW3oW2w6v^0l5)TObCkgqy%JR ziUxfI$E{t78ci!%3}HQJ5nkd^3^Gc??u_Hq(@N}STn-_INnC>==bq-N_5_bE@s7Nf zkj%yLfzp-BNca!p<^7L{pt-fZ+Ru_=mmf4u*pKtgd3ml|hs|g@HP@r+pLBZpK5vQ1 zu?rE0m#XO3XZ>h?d28`p+UgV7P0Xs;&t@Hn_U~Vj;xfvZ3hsqn*Iw(n`@Rb{qncr3 zilX#=J3gr6ZY5bK+K2aRz&^h9b_Uzkoqvb4*>7%a^!OKb#oMajdJ|U)ZlshJ?8dD{ zPA+oUA5d!k9n-CRESLIVo#nEPKvrSp>{53XP%;V5|k;>oMOK`RV5iIEgAZh>Bez!mZ_hl zKe9)STK?lz(BzZlxr9s*o|2~r1KnFchqZpikY-=ncttsUanbts`Jd1HQur zFLGMP)3?j=vG+ZDN6m~h0M^Ac1ZUcq3@76XHi`o)s~|kui`y6 z@PHFJc=>p#kgkxdID-Wd1Gjc352DBr|hXKBkI41njgU!{0*z!=#Qhvtwk6% ztz&z>MtqD7q0T|?$4sAk=cej&YIjSP+8vLFJ}vlj!=4TBCWUb{Z6&sm5OcY(7`%)@ z!jYew*1p3p$5Np}Fq72qF?ec~D!D~n7G?O);VB6w;?!r>W^4RF@SLnim`Od?Vg5}|>+~3V3X7pe=f++bZ@Tj5{on93JZ%o+R4N$q zc%#F6iCc!}`^d-oRQ+;?ajG?KVj<#B4w4AIRpfF}hxDiQx*yCAjZVgIiu_Td%i%8& zTU+WV^2uuIsmR@t^sKRXx=#-^87tYBLX6c|wz{L0_;ca!73({Rj5Z}^kdE9Xb{3Ffg1`yM#6!SvhXQ^5mV_v5VG^d z0qR0WwrSW8dnTK>4b1`>o+twkS)X9FgFovZar!U+09=Z=Ek@37Q`Hs=clo#!rJ+$r z$$t}kUaRKBk{zS@)=ov+q48gcb$N9Qr%=R#c&ueBgFJiUKA5m*a_SJM`)UA=-S!jx zGy0nOt|7uI)IG9Z^nWAlxH~bH9~Jd!zjA+{_4*zGV-b>74agrcCcYI$?EO{9_HTzD zWsg@~M)meV8nFku;Z8B{oEq!Fa;lv2*&I27lcnt8yRqq-CyJ+?b=?|R7{Kb~QHLrI z%Zz<7UsuC*-FkS66Iy?oYxF)7i}1@0UkizY_rJ-ezca|~E?+8n$G3X?(sbNp(faIa zDMd5wU)dJ^SpFvH>a2FklSIqg1|~n#^{=(yx{ej+PorOoKRNLVjA~(N)$14dKj|N= z;N)jD`YTpHBoOgH3_n_6Grz3>G}8fuPy{n^9E5e+X{|v1X#W6c*^Hhn(ii)pQ~ADV zp6Hr~op@*MGJH=yM~9zRZ|vJ;5W-MABwEA!#VkVPbmWh{*08VYO*F@7Q}{aL#NIxa z#U2E`jue>5_82YNV`&VE<2SGtYUL*jHY z8)%rm{ET^OpnR;YpO}zwgVTzu%}>aOYaU-=BwuW`TghE5H-RHBC09J0ROOguN%^-XPB1ca$4qyuDaxh&<4GvnLg$D)5Aed% z;l$n`()?vJYw_C0DkAC#!f6Oxua)a~B{vDOY+{$HD;Q&jeNz7!PLOb(y9F;+J;on0 z>ux^rM8c27vM|xKt z!w9A_GB~2)Vj?Mph?#vkr*J*U<39As7)<~(kU1kh)B(hJrs!K=X`7A%M=n0OO467f zE#rR?eUi>%uk#Q<8LZ}O4G)Dpb*{^GG^@Ovn!--S+e60%!AV+1JdT;HTPKv}b>}*b zwcWd%tg*6V>MNTOPukOzA5~+w2UqI#;Zi%MpWJ-yY^4>KICmj&{Oj`xE>_X|wKvUX zdM=5n+iCW$S`zmP+oI>?2N?N>et_bx6Hrf0OsYZ7T0IX|_-iz=CcokvwGV9tyqT6z z8!y8*UieY@*VS;{>CvrTTYr_?J{ycJTN8%ELw$c1l0330!x7WzUlmbvJD;M{e5oVu z&)EJ0sr*K=x>&~BYh1AdjELA~zN>{}&5CmDkA~xU^5B#oS$?PLx21jg`9PGwX+4EC zrl2tK{VDDPPG|v#y#PfZ+^oK%6d*sDZ`vbr_}11l{2PbW@MqRXg=>~%}cIUapKQM z2Z*lP=V3A2-K*R@bNbfaq12k6Z zSOby)=bU%sjMj6PNbX!?ZC=OG-Y>oI#*cB~zZ3ivp2p+F7K((nHLH zs{k;^Ae@8RynN3o!{<0zVDZb{c6Ys+YpQ+Dyf!MP7NV<1ba+Oi;~jg)-YB11@f4Ap zzb-puiWKtWhA_m1RqQj9$vl%+l4O`nhYql~H2H4ZZQZu|woWe>QyC{#uIJXj3v^=l z7V|tFWN@+_hmHPO4j29fG?6d-1o~IeMILqaKS{m=S!n+N+fA!#nw6|p+B9BNCV3S+ z`-jPQ!Rw5%KI|(x()%X#SK28|Pj0QeH0<5*nWcl;zCA3ZhAJpTaO)PLhZ z3;nmFAG@pApQXZojUkR2u9n?3D?{{|f5x4_a_Sm;$RSJXc9eqK1d3Y#;GAcmBoD@z z5A$Jc;#EJ0q#=g~I3WEfu*4#O7{fiN*a*tdJB%Wj5f$X)JkSTTmL{k|Py=&7k3IO2 zX>%@sbvrdJbEiL^RYprkj6dmv{{R81i{)cokCJ>*Ec%VHn8;WWkO87)#h)s8rpeN2 z8Hawg%O!JU&mq)g^4Y692<5J>u#ytp0W~tROuB2{M~&$^efF(?4YiaFHO$8e8ucc> zE^w7fkC&k80Dt6L^86j!jDH&dw8p!KB{GK8wfeU2w~)KZ?hlQ#PX; z@}|#S_=~3aQ{m^sI}Z!#I0Z_@U)lH%t3%?J z{{XM~A1{|d=NYTU)K-Kx^;>_L^2L?pa!#?UWsj$7`3Gy*{S_va&(!bOQ$TOB_@~5@ zNAiV^+BU~?$;bWk`q$g=oeM&xUy=Ej9pZVaQlPxq`Wi^*iu(H>pCBfI49^`YfWt+= zGe8VIO*??nd(nFV_yPNEd>Yrh7x4!3Qij$^bZdzo>dIA8M36fc+7EV&lB9LO2cZ=W z^c>^Nu8)qiE6)hqc+y+%76Nq1tfMybA2VQ-M;eg+U(LoGaoh@;s!!oEi%Ujt_#zJh z-Cg+kt^8|!;r%V7ab|+=?CmAF--aN9WFTN{;NYHeYdLeKw7FMIgGjK|AK=Ehd28c? z2Av-L`eBYTtT(P=E>87lATUrcc=a@Y%guq>+nxzwdv#@Svf0XGoqvb&cVhytf3l`!65)RXz_~85EfFVakj%dt3JFwcs zbR6;gx%Qwo9A;lG6j)UyPOdYSIq&*WxX-C{Uy0A-zX46~vfD)v_?r4CZ0(*Y7CT2& zaUo))fRBYe0m=NUozwPm=jdt8&a6w}O%GQ11Feq{_}(Bii~DJ9V7k(#j(1tIt+XjQ z2MBp10QI5%`Fo-8Zg97rCA0X0@e=b~)AU&EAi9<%@>2!pAU0j`#`f=lkEzK!(v6x% zbCu%R_qT%d3G89hG+jP1CbM!zNB2)8vw8qo*!@SPc1lVL=1_~1vOdSrbjY*~D%(x9 zCA_uyq$8PJ{pLSY{&=n@Cf(WH7^JL=>L!q%Ft$BCX%tvQP~52Jzg*B4u_07mjkh0_ z9HDe!KZ<-U6oxr`MW(F7sB6f_dm!G`9 z?DZY9OPHkYd{yI{Ng#A7iL=8w9a z+w%Vaf^s%mr-`&({{Y#0?WAt693yc50D%#aUkgVWQM*%T>UHw^DPFR_%+1t%OX7E# zE-&><$)t?sKG894r_>DMy-F3GH|-}bX)TrXM~#WYMzZ!)prHr5wVPj=jW(@)aO`fT zk>ryM#zXhLD=PJ8T256Stk(&Lr-zD#HDr#nNnbX5Hc^6e(zsepqtNE%i@E#F`!IM< z{t-Wf9vn#{*>|X^ypz`r_d)yye;WNmCByw+1qAnc{paEwNsId4V^Uofi{yOXwdfD@BI4aYP9(?;NV$Hh+$_zT273D(o%KAQ#KhAiNFsf?oy2t_A! zY&llr0|%a*=7y8dX|#VXJ}lDhb*~@zq8|uNacSYW?j@2q=3zIL9!?aT4acC*b5Qi# zp)FmXOzK~-KgU~74S0K68fK9;r>NR3+?qpNtQQu+xmA;P)mO$cyN(YPH(3y0&n(24NBSzyW7;xyrIqgS3ksisOXRCNKU(ng3*1S8c z>CQT(<&&Wwo++uspJye|=GkM7!wbubgj42BhO8jrU1Gj~tKgLmKsf2td!Npo z!DuT*aPcf&WMxzkph~<9lk4hD0=A{GE~qX=;C$SWz`pfjK?P5LLTTJI78catj_NqU z5!?ah071?UM?HTkX^4Bar8TS;QYkP)yI}c2896-lJo?hOSORJ$NabJ|kZl4&tN`@E z;~v<>JBd_C`~jljV*Z|&+I8Kn^_Bc^UE8|J6sadDz~mA5)V)=h z)`y{Z%f#L)_>Xg^$*WCnBD6w~+gQZHHD=}C9odg0)Wt>%LYi`SXRCY=_*>#Ty>>Bv*nZC=xaq&PeC!T2rW??&6=RGK-Sl#OtX> zpznere*yg~f2_m)eWO2RFXm)#e{A65-Ec=LTOj_K{c2}k5?Vna#+;MCGe0wbXg}GH z#-2X$teUTc^vh^$RxpC(ULqTT!5fg{X;N5cCnFs(T(8K}mgP@{KLS20d@hFKOMeH$ zcd5-H$@bx^LmMvBl>lJy4?Srjl4$)L(Xa3BbgedRTFq^BM}->V-55x*$$_{A91)!J zRdBVAV^Eyl;UC0{x z*?v~f`pEl!Bd6t67tl=f61e=Tgfx%H(*iO-Isjt|26~}6Cmkx=u!Q_-ZWj);(+h{S zO~g0xp^Tw@rfIsAepaQY+TF$d%cxdBKL!SqN$xnxQPwWU3#@!U_;G7veW_jeD@0_s ziRNN#V(6fsPio@DQ^U}uI@KVp6yDvH&rb!4#@4S+g*vjlnp?iE$I3^-+8SAvxU{#n z5kOtpAyM-Y&q3;I^Nbc7o+;OQrFVYk?6{0f;O#|j?2pZliMRe{t*SMQjFycn?E#3& zl5wBHzFX_AwRv*?a9_R3{!xQ+Q#vUBdAdIxPR}n*j{?iQpm3TTISj0k_>e0`c zVwMvLQnTorKcX!z!W}D4u+uG+2rVH<5DqY^pbzC=ti~!4QC$zf>P^&>o89VPra*-E z?@a+86ab!-0H1{bA?ZL3BAu)U!=JYAi}e`17pMF)@b%8)3j1yJRH2HqqY;@7R?(UPARs7AP%MbIO zPD+7{6I`miTeH}|WY(wL8vg+8N33|7=1Z+3!Zx{yQYji+$uJH9ZJj6n5vWBAflqLE(8Mm6`wZ;y8Y zqqB>{0Z;JBZF1P7+r(bVN15xMCHU{I?~eCI_@R0N=g$5= z_&f0%#}UU3{*T~&HPMR+bX^T>BtKS;5J>hWny(bCVLCEzR(UV{GDnYHzjvrwx31GS zANdZKwL)}Qr}jwrhk#R1faB4n{{Z4B_NYCH8-B^(5|;z}LI6)p$iw-q9?(6DFX`X2 z7sN{m47V1VPNJlLtGv0L0RI5LZin@!?NL6(?s^`T@L$Awdm+5|N#LvH2a@`(rn&zB z$+|h>{{Z32RNDUlhCOpb@P41Bl>2w=+u+$q9JG4P!+w%G)8~iu$H^tpeaExtQ+OK0 zp}75@JU?xY@EbdVKkuLoE@%$YJ%>s0w}EXDMZbYgo<~t{YiOW<-w#!IhrD%hd`Ix3 zg&sxRYuj{df%!E)Xo}3%PaJqkMFib41KpONG6HY-OFSsUjYl6!&lJU9k*yl`=ozLE&?0vDY;9f`~fsvL_*@hx%*oE05oVb zBT?}MzLgEsuVa06<*p)INW`W`Jusl>1FLl7rg~9y8=7|!>AI(fbl22mw3gRbv~xX+ zk|cxpS~*bQsX61+b3?Va7h4p30pc6Y5<_i!bWWwC$|H*T&&z!QA0v~{v0STXL|p=btHlX%Eu_AMh&qz9hy* zl?Y*P?^SmBEoJyCe9y1o{JvO>T(NC?w3Yt=?dPKWUH(VMpA`H^G_MY71~&q0fMHI= z=dbBs3!LMAr-PeY%SH1)R>|<6S;a>CM_2kEnqDoKNhG;BC%t@b1#5He>-;B@&1@wT zNKP<#uc*VTtDiB8mbNPCaVfiqzuX5Vw`}9((Vw9|u?K`sv++jXS)MJ>X;$)G5=KCB zHmB;t@~@%coIkY1dq?(DXU1`^E7@RulwPuFe3q>JkoFb#=j6ah>r6vQ>&-MVr?@l- zJ$ax6qyl7616$bB1Mz3}p7?<$h<|FP&~2Q{Z=%@C0>&He`Dun9_wdX4*ET8pwl$^k z9KMLYDVqA%RKKxEd^d8h@f^ zmNAgC#LxtMb;jud;QLg$CAbw~@laH7bPYps&pYjZ`1KsNOHB zMnPaY`Wn*g5={HNuNBZ{Mn)=-9*Ry4CIW8uq#+N|fD=EZ02BdM^7h+LwYa{#nPRnp z3&|s#1p~chUbHaO|Qg%rB1H{_x=ZST@j}ToeMQW&FvbSyw zac4V-{_}OO%qv%|nd2TlsAS!A_OFM}F^?CD_9^?Y{Q94Ll3^AehqP;1YyL;bn*GO^&F*VV94vNX zXQMc$8=YbwGJ}#mPo;a*IwR*X4J)&|@gIaOd_8-hSjQoIsq9kbl&c-S0Vu@I?ItrN08RKHR1j0rBLj@cXikT((ek@;8HaMd1K zGpPEzADi)}C)#3RNj;VR^Y3m2eJSxnNzFT01oYyD#3pH=3RVF)paebX0N=uZKcDXq zcve||ZGRVN7ak*9xn-W>*y?(SSQa*UFj`Hc00P942W;cDb61OQ#;|Eh=h(h5&_{zb z`_G4utJvQE0Agr%cT0N^+9r9mE0g2D}aTw1Oth)lg zb58fdH%W6mcCT#FD-fllVo3V#rR>cTuMx;NUh7P->Ek6Xr~s+r##jmt$0h{{BECbL3pe9Y$32z!*QB zE<~NtNxN!#>?HXya(?3f04mi1U@0LtV4nS`5Tp=yVE!}!2O~SPjMKPUbb^ECOa1m;vi$ZaoUx_#bmtmu49fYv$+Zsa#;EbHyw%Z z#nrvM^Gj_gSpHTdGUK*0+Nq|sXi2BDJb%SM74AGeccp38z8bvMZ|~N2NG%-{szemA zJF)%Y#Z*1=CoV(Gqy42U?`~takHI>l%_9XwNnm2co-y-Q${uEZ*6(8Nr|mW2h(`OL z2y07@tiDTQ@ZU{A6YUS8{2Ag68^-zuo8oOY31hLmS16Y#1F2RhLk>p;PkK2~YEN^| z{9EB2D^U2oquZs3c`rOD%*k#DX&l~8i@@q|0L3XqS|W>W%h39l!u}q&(ro@4+-c$7 zFYP(B`_qu3IpaqU*NMK$j`A8uo>YUwc;SJJ2s=(QFVgK(u_u+Tur01TX* z3T*|2-BW8Y6Cih?>KmRF@fXBPe|-KQh~~z~tK0$7S+SKv?4W{2sUDT_IsQ3fYrGoP z5Vic}x?YJ{zc#xcqwua*^=cnppT|3>`A25{doLvWo*Clnxh-vO0vucvBxjCs#d!Fh zXu;ciA6tawl-2e>JiKFfBi&ra;Q67>@2`6N)-)yUT9VfKpQA#mjWpBH@vTiTvdZ5x zfOzaH-osF7U7l7a6s0a+hHr%RFArJk_E(-DX`4;9K6^(BZZkOLQ`i%V_cHlXrBXAk zve(s~9%CBSsY)1siRtLOof7KT9xL$;_Oo=MC%>3{gOL(vYN+}s#cwLl6H8bH~^Cx)R}5GI#@_gFz{xQ3EL&W$t*~_x)~>_{{UO-PRMpd zqruvDYpb#JzP$ecEUXD~2 z6nHk%aBuA!ox{6a-5=*QE=Z2;6269QQsf;%?U+LHM$2_D!3&;4IR~hx%7l+xie+u5 z&|~S+votS~2GRlMtVoTeAH)G5{&cQ83hn}R&rSsl2IUn?U>>vqQb;YN`@@dCX#rW| zjRwWxI~q)A!n|1rA%Pyov%54&Gd9ZV;V+Q_|F(J14?jxSveQCZ~d@Pw$oj-{* zeu;j~K0MR)zXoX@8-${2R#7~Y+mLrg9#?L-!TZCfwL?}MUD4}$o~wPKd~xvBr=?4> z_RGRaG;Y8)*86qI=y?1nZq6fH$oKDsTK20qgggVMHNZByr-`qw=3StdVRac^eKJX@ zgLb!>q>|=dpXPnZis~>JMNvmwPd#dc8?i-zX(!f;0K2h{X;=!Ew@YVdcX=n=f+m%| ziU~i;v#n84rz($VrvBqf6rFmor5)tb``wRlO4dmDf5bY>uOy6QJD8GBt$6rqZcmw?L0)l+vE|qLgt9aI`5nQ>O802NqP2sdjpbvH89rKfKcRny z+Is1J0`QHBt^{^5arIr_*1uB2N0N*pyB~z(XYDZ+C*8BRu7j96(g8D^&;oX#1F4_` zGys$UhJZg3KWUE-Hi`RS_`dmK+YYIsMSB^>17#sb{{Y9MYUIQlQ{6H>D&ua6Xurkw zdvX5&k#0?3x_@0wA5)n4bWi*u8c_?9V^f@evb7EBIBa&-So=&}z&#BMaFH~2aja;I zJ-|=^A2NUOH9{BcqqWTc0EtijCV}cN*^g_fe;vQ!K(-_n?l~7P_<==+JVhpd*Pr|5 ziwBtCvToQe2JB}AdB^8K4vl4ykR-_rLD+?W`r!IviwfY@^C_N5r6pe8MF>!?FsGhR z`Nchjxw#IZh1~IO|U0u*KBZYnO1N905StCB5=V{Czv0^Y1{c zUi&~`dBOToa3Gds+Mr~xpa{(Bv0x!Q{o_fE87(L(*dHi84J!>XvBrwRc(WYJLoA8G zQVv1<>ReG*c08Lz_)XxS2Ka+l@kWQGn|(_3IAP|qM+jyN!ZbW6BoC%AFgU7{a$2%u z7{}p9hx}~2ojgO~ac?xRv)Eq7#wRFQ8K49l9)|~t-ww1n@gEXCPrtF&^fmh}wUoD3 zB)N`gNi3VQ)L`-pXE?_dm23=Z)aPvX^8O~Pm*G|xG0|UC?Df0s_PO2IYFeJH@b2fq z*FGJ!wz`&8kn0y%H!@(U#sUHd%j@5zDmX7=Q`#q|q1Tx4WV0N(;3rGoX?xCBdOO{# zEl;X{Wxs?vpM$O&#@AZ4wZ*QjU}BEmHDK`{FdUrm{2#4%IW~NhW6FQPpTN8yuqlV+B30j5YE zhaZ(N6TKz^5;I1?CTKt{Fb>p!Nhf49cggzwB1bTn=4ep-jp;wY`FBc{u5<`5Z9jWzmNr){B!4hipUx`B)0t2Zc?96|SaP*x=vD8j zmGIi)C-A15Y^{l-wpmW_M&a_V6ypT*oOQq_wP!8LhREy?yhKWjyT=$|k)QtnRV3^- zy9{gVgyD9a4z*m%u&n!xI)&Ek0GOrBhi1nA0BOu_E$vB(XPA(R?X(gUvE=d5Pve2y zQ%x~6%PDbXPYz&ycr=NO{u0kEb4!nn$z0Lxek;Kw4e0uIg<|r(t(-zMdB`r<=PW=2Jf476 zMfV1~9Co;T?~9s~5%R;~OLgS>+{}NiX)WXF`k61a{d7J50N}vJo$zWb^}M)zANu@Z z{VHi}y-g;y`G1-E7mDsVh7n1jo7<|aAl*fPLe%U6XEaz2H{vGt@Gpx30$c18a69~_ zyv*v9>t)!Abk*eHB$u6;>tr=yLo>tFsO=Rvw)<*+P;0Tu7D7V-&t5C}kLs0Z$;PBy zUuU8HM+)@n#Y&u$UDG@V#K#RF2R&=k!p6+0%iTPtB7e1QkNbUV>F{gbiSzjP?nvi6 zUVq|l!>~oKUTfYwN^jgUw712^K^+YUB=pqxzk$i;_|rg)sbJSpt^of4Yc<=JE7y;y z<>yrr!%tq1@;{;|@DUVnFa|61?uX)Jfbc1x4A22az!ZQ=05jTv4A27fqzB8Nwau-x z{{RY-S>QmrJiss(mFVxcCsYBuP#XK>iA1E^UI6V6fm7KRKI~{!YVGMAzsFFwy)M5c_a&h=n zj^$@AxaZ}^)_}PgG8{8!+a0I@Ni4@WB}W9}fEcpOq&hJ7??r;;D>PkmbRC@fSH8ZE`-nu_b=zB1N!i-!g z*kmC3DR5zbP64C$XH0N7p!;7&6GjNp`BLfm;_dcZ;xSDk<_H7pH5q*&u4#52qxOz{ zq&YhrJu#NszcAIdlJfN(@g;!6`9n(%H)S^sc6Jho6a1zDuoEBe?&%4;FDH$KNqBKW zGCSzdI3MjUGr$FlagC+W^JpLp>l!Dr9tFwbXmakV^8U<{roE5f_;82ZZ1jSV4xMe? zS*{HJ$!f^=MrY?UZO0zX1Eud({Gk64|6nN232X{G*l9KBW~<0{N1WGy?vtl~SCe!@ zu=A1CXN%r@C)U!^a#wWgwh=^zgSa2j%tJ{s#X)-qDQ#mZy`ARz47pPkc2dj-hNA=} z>}lE(E3*#>D{lDdZ53J7S60%{SvbGKhEzU~gw%SRZ)6)`jh9*Do0!p>L|NKA2pSaO z6*L=&wqKL_J(}^k^nsPHkVp3Yf<{q}B z-k_H5Yn*lmEv1{4UZ6(c`RJx{OvEQ%OSlpQ8aIW?^~;fMe*?H4b;5R_CS+_0tIlY- z!d3XOYKzl7ckP^~0)ux=Jza5vl^c(KL$A?`+_E|@ooUNBmgJJNWC)lzesVph>|{Y4 zUzDA(Nl%SowF}|V*k2Y;olUC_GRhB^Oo$Ux0&Gfg1 zuiDApWZ!`|3?GFl_?uenm*iSkXxPj{+4Q)3G~s)gymE9A>T)YtlA=DC=*W&L7!pqS z27fN@4I=P6YupQUPB|Ahi5nO!omgW{3%Uio?50R>p=~y6T0*3$J}i8hu0a}&U>KP9 z_Tg`rGPhRmp*H-Vc!?ZuKl;W9O}QC#tRYgmr6hZ}r_<&)N-NYkfV?BGsrpj@=FBc8(W_saH*odtlo3+OfdhF@q7zH`#F@o+b+}2m!Pou+OBe|{vKtQg?Yr@ zu@IWjzVQ#hm-%%Y2z|^u6j2{0JElebbE9d1GQ{ZR>(EF;%|F1GN{f9wAC3qYf!4pUmfv%T2$2zOpzDX0ag#sx3uN3SK}(Ez+c&kIB%5V*yeVh(p% zJjzw9$`6>-!3?D*2q`kDV{tFotZAhI-2AsCBlXaFWa5h4|!awR*BlH_ll0`Ef` z4*Ar;E%_;$*m7e4JH8syKQ$JxWKCErBQ&7)dC#uD< zNPB`I{{RbGV~#y<1sC#zLuw1kFDZ*pGKoO4$0M`%5O{?jk;uGJR;ZI{Mnj`7xW{~o ze1t1443tZS#<_UEVK|{oTm)YCkFGHhK)-LUqN0L0s^C^uPu!N!H-CsuIrP8C$Vdng zg8sUjWbF`#FrPR#&~-q6kHpt;UZxU9ENxlo8NU1;%6#PQ_PG>6i5Ko9Sj_T6Vz%B6 z0+s?VpH&nEK>XY7J{zSHXy#A?+PzyJvz^+Zf@TQ1c5Riu>DwjT-hNR=85$2Ql-ZLX zehGV=Sa7X?xzb;7(UU*zQwp410kzj94;p`}}s?|Pyb?RMBm~Vn19dd@+lwVKB2vzaI2(%q&TK_xM<>HuhX@H5!BPMUe8ufG*Uw2- z_qdrd8?(4p+bl*ak_M(eIW8fv+D)$%xhKDD$?8XdxXB3l+7C*Lw8^zz789oWj5S?! zR!a%Sr5e`a^cRJ)PZSxPox@}}Xst^)gn7T4y7w}^vy!sqXUYDsvi43gUdkEjoE9-^ zwRK2aeT5xuywx+&wN9v$SM|KT40IB7?PWc^wH0Yc1l?R#Nw*;8nakrndSSvysqzBv z)WH$mx4=U^&SSZPQw(icduIYkj`r~&lkjlVQHAdkRyeF)NX=_1H*t@F&%PD9NbXwK zjS03TB;T#s3guAJXT-E_sKAuL%uq@}@cw1Y=-q}y5rt*CYY9&Qr4OXzHp-vr5t_Jd z0nLLfR)P2sub2SN+HJHciu5caosxkE=KUm4-LpMd-!0Z7b(HH`{N8~*#y{+8S&DvZb|SsZ(NN&1;Sp0FQZ~0xAzV2V<9#bw*=(^q$vQqD!+xmHt{{hZ3w0GAk`HOn6o{9C+_p0?T ziR*LQQ$7$PMwz+)0iIG>l1lmG27u`AmTqP`A8ywDJOp;VqrjVO>vLuwwR8@1y)M

e}F%gl$~wTm+_=;vPDx7d5}Pvi%iEb<=WV{D9$9rgGn4m zf6uX#PR<*KT3JH;@|xZwYf8-@N9%}-P7^h;n??J!#KdDI9kfho_74KTwmU8+mcrS; zGFDQi49ttA=r-MuXwO0GS6JP+Qf_u=C7K82h4d+`2un)V)_fpp3%=>Nf8Ja9%Y0yw zM6*sH)j-pQ>swWlUdU`?QbPz$yMk94{^{wc1fUHqrw?7-$o6TC2^eomTb71%&7@+* zS9kYiXX%acCZI>N!e2+7W4P6)OGWb2)E*#A)b#7Vm`t%o9D6}&4zQbZsjAVc-;$;* zr#(AK#I2COQF&s=O}-Hw$YpYL2nz|gMYez~nHdx!b6iWGMMz%4H)@T!I1J=re~K|R z+~yibc6j;%osnj$w8+st20xIE{hA9#z zUB3$#z-Q_V_JdZnJzkcK?HKr?eF0&uJVrOdDm zr1TU-E0lMu0fMa`X$bzN&m{pzQvuGOXJGM1@>d*wjGs5&yA(f%wIn~q6|VD&?V_^$ ztqh>7!C+}uFoV>+&#{lX)a5>%^7c=XiBbw-BEJI|n<+kSt(>6A-G7_4a<*L+C5UX@ z>RJ@#GE9HzYAZ5$ICs9}s7wE+S=rxh$X*~4rGd6ByHCkQB|NIekNYc$-1R;v&>!dsRq^eI+3H3%I-_VpT7$6$!qqL6(Adr5&y>>I% zZoKx`cu<&^){T%&7&Qh56`!4NnP4dTOO>I7Ubp==dAXOB2m14R^ z0ZArzz}BF_(_Iq9QQ`YVDbT&KXbA`_We}{bs5S^aLKX7C8JkMjC`jE(=E|Vd8pYT2 z7A8G9P9DeIg?;*3`FoYPra)i8(i5{%-P&#W43SI9d zRqbG4;yiH#(`M7goWOy55@Js=4*H#WpjQ=m;;9tiDEpx@&{1BK`=iR}Nui#3DLh zDZnhFHx?U2a#}ua*IopK-#!QyKI45$8UT+3O@YMF ztOu-m@FbDJRNGZC<~{P_7jg>2rkBKmuhGCvu@NUs9{iLIYnKg;Bt(q#Ca(XH)g7Z_ zo)*?m5}*#;F@W9W@HdSE&p+(3?<=o3!Sw=#4oCLEOgEM!Y1;G3>=^Q>$#HaP(<#`c$RAq~zStN!LAH?yvUrO*N7;6gvz=K`9rr$qrth4Ne#|z{ zq1V4Qz~wdl{7-6+`=ra6FdHHDAvcoA=z^9@0~i|A=R7GlZUkpEnoroMGrbn?28%9s zPoCC}uT|9kV*14CdKUOZ)BJMgh*`S1S!V`?eVT=SYz&k$b#XoUBjB9w@Ml=+SL6>l z0_2``=b?fxIH49_QX%)J)`%6DcKnh7l#LZ63a@({PP?7Zr}m<5eny+It@4##Sb<|; zxulUw)yEgV!dQcnoa+myP3$=k-5tHj{?kbLR==w2-+5`2*dp!`0ZA{w&j9=6pG$X` zfN3stE(hA9v)xc#yY(~V0KUF&+_ZWG z{S$MpOiEsJTk2{ES6Z55+%XVn{yMfc<5yY-eR3!S;n~08&*bQ<-i3j?Y zRuev^Iv2K+tXTwKLPRXd=FnS53WjsS@YJ}qRcdmdoNlGh)m~Lt>O{!E6r>NZX_j7l z(H~LL$}Uq{^iL)kg#&@5AxPI$L7nJ1h{QeF&VJP?%l)0+G-{_X3(m2fYDpe=P#&NA ziZAn)g;K*dRZOzW>Pm9SK>d^O=&#FL*_ky$n6+7pw`{;6bT?z0CYM2#f>)T1NYi|= zkL(`b7WA`9ZzuJ1RYUPaMyXcCv;tG#Pdgb_!=oeA9=yHWTEnBzQrjL5YB})<%30pD zXMfndK#F%{?o_Rg^=9{xB$~BaAH*>h#8<0}FOyhML9*=e!X)kz9BPoPs!6U$URBMt&e2kdEC@ZFEf40N`7*bXAa61G ziS!2^K2!L_|6?0-GH>cZ?FY_A z8z|c+@5mck%_Qk|{Ry8%d)!W(cdO7ePhvV{5K2ValRr;=58olO852X&wfttYpzSZA z>-D(b-7iT0*HVWB`_C`el z>FbsN*<`F;o$o|?>GSMN$IyXG+KJw{SPe_t^|oyk zEWPKqK1q!%d0D<@DhoW2@yxJ8krT$+;gFy3VMq?HRb>YU7XcCFG`k5MNN_Wr0BiyC z*N^rFCD`SSE(04b{8krtIF{OWq=^D4nl1fkjwAxjJt1>Qo;aLNHqrTj|BsLUb6{zq z9PeBq+d&{uqJqcheaL(sJVV`m_`zCl+y5p0c7t5|$Q#iSuUJq%SG-KlTFa;gi3c}A z=@_1wZcf3Q7}~BkZf$rn6UA;-;z@h}a(Ys~o?@54!zG%DOGi8D-kS@RPUj=mKp8YZ z>FO{3#LJ*l`keK|9=b4EGG874_3ZW!P`d1#emP~MICpT^9ACw#L;RAj6%xL_&NP-4 z4~AqY30sn=`9MRsRH2>Y!khr_;o~n=)G@l@75caSR00mQx=6N2u1j^oa=@~Wo1(i} zgq71uEJ20;RZ zTJ2EY0qXW3i%U=Wj_W+xYyK^~ccVg0kKXC$E>)co!zG5D&_zz1xP1z6*^kDV7aJ0- z`O;dF(eAg?ce}BXE59`V#hM>b}7n^xp(%o2JB4nSlZtf#hkG4-NAk` z>7cmT+$*~vExpd7mUlJ{62$uvMH5^`DbUh~NxZ~f;-cU;sa3kL^Kf9=Xx!)M^kyTv zHn!m=RHy_FO_p}>rCzzDtv}J=fwCJ6T`X<=*Y%oRZ=DDxp(Ru1LvL$!_b}3GDC89| z1=`OzwTQ7eMV^+A1WsqOBQg!^psXr&RxgWQ63<=Pc2L+1>1XpbEALUdx+@NUsyVw} zgJkwQozg$RSM}Jh>XViEwSesRvtxz3%2NVz5|uMPntsVMZ~q+nMC5}zNx z2E4{o&C+YcZq~)p#>N}rW`?G>*>;>GKUyPF<;qeRFjF3e&L4_AEKb2Y=M8+mmRkc1 z_Kt|F8cDZ9b~U=JV{L@!{o&5(=HX5!R2G6=*9RkSbF#0?A2b8*)JD~_wDoK+w>L!t z2B^Ac?$^)Jr=0j(>C@|;;X2;2!s~F8Y(22AhAmo`e=UbZ6R(Q~Kis>yZmk6oZqgqy zF7C9ch;^LcE3Z%a)(aM1PJl>$?RIa+&N z%;cLovquu7OL#w`@BGuYQ#IA0_fX%|+Vb=0(!f${@UQ$8ZHuHY6!gx+J$aM?M>N^o z`n<6yM0EHKFPxkOva9;%r|lZMo_^$Kf_O`rI_iz7TV9eD(yHQS{ILo&uc7at@KW%v za}-aSYDK5Ex_Wl%chp_)mlLa+(GchL)RDC9snK5o+?C^=Vj%wq;JtPB)DF})Uob6u zTDlb!TdY+-2{9!Z*MPyuIoFsW7B8uj7*~w;#KXGR^i{w?t@2Jc-SoM+3STNx01cIL zGCgPz-AtWn-}C4nU+`17KYAxdH^L^7y^AE06l1xVTIwYmgC+<_z|REHWrc$1fw80h zH`k*VN&iYaSkjrHma=q=Jt$;c(=c$N=kcMcqZ*1X|Rsyfe#5KeTY=bk3jmQUbmmV6v>QMGD$L)Ta~EEvS)uq@Me!Jx}c&cI|eO}mN%T8wW?FVBk@i$tnabvU^x%lve1aCKV&Aq zd)o_Qt3x);3+|&F%(<~Y`(#=YME3~t5oW)$SZoa~OrJA3r$UekRWNiT^s0H_P)(zy zxR-A<9LS$WNEP-D6ViOXdYn7j0i#4)vw<%#GDrRIbn}ae=kIg#)%*fg-dZcJV0s@| zJl;vtzj@W$_fRr~seu7!$J^ipLlV2mKA$o%R`y#M1|tfxR3FGuUqT9=$4DMcIaPU? zpdOLOM{kcV>gN-FV*%2=Acc1hYV))XPSSUWO+#FpF1-~JR|V18BHTgyIAg*r#`3aj zbL|_s&$QjL3}Yrt{bb?|!>ImjiU9Y^Ww%O60PzM}q?|bu*&NHe!A)DgAJ&aTSFZL+ zs?W8yF2Cbs&2Z1&X%Ww<1d=^IbG%B+5Wkv*+#t*JQwNEb_r{k#)%H2kmPBg{8q<0( zFOo$qv{7NWo9ny0FcdMf0)@IQ@o$rLl~WJ@h)>otL82SZx?IMve0EN@x~M|O;;s_EP2yU5H1L!$91muQFLvPeZ-}!BPc^J<@miZ?e-YK^>gB{^ZA3Nq zGxM=Z^}xpHUP*#lnNn%%#_FrWa3XHLjP=RA30qm(F^MO=Qz(0gP>1g{`o`-W@hQA^ zap4`g{>Z-YCXEoE7y}~;L{Ek~~M_~ao#+Om%&!)Ruh|hGrnWT$8S`{lNyvkdB zIIH$1aBb=2#qU}H;2akoeVvLjwx#O&)!N&i*hjXjr8$z0((}Ocz@a#l+IU>^8UTp( zGEUY0Wz~~+(h7|5V>umZT~ogPEGhuhitSpM|IH2$EH6TY+edX2Z%Ni4J>IM6M6)n} z^8sy>AXzLnPNxuV{II1kk;W^EvxJu>J%>l(9_AjBA=F;SOdOthUMm4dkiHdBA+B`R z9mbR1Y38A`F76F2aK9zCNn(0T`E+1Y@zLFvFWWu%MM=(2w%ZJ_5#n|mL*(S7^tod} zt_OZk-d}`mcWRw1KO#iNGKcSczq%fGnX5$&P(QeWY@H7g9vMjgY>ezb&>Y-`drLk! zDovMZFY!f%)UH|jBi>8dbHMG!?jj^_hgyo@Wx15AK>%60X&}=f#Z-hj8wJT0>=`Qv zlw0a*y~m>JgHS1gX!s;mx`(vw9Zquc^=`hh*t+2vI=H==2rCtI(fmd!(IeBd>vD{Si9wd^LdygM+o>CRO2(hR9RjFG6 zoGeFfUy0knW?VPvGx9@u@86X>X=l2{6`oUnRT~Dq3}t_5D|V?tvhy`ElZ<7XPMs=g z<=5Y-+a>vn%==L~jpBc=S*CR!6RVSD{5fuvwj0u0ZBrq9-bnF#nUt`7HLnJ?+% zqYpQrTG@1C$aj#`t5Wq;LMOEk)w9M8HeZG0kRV2N;w5)VmP$ZJ`)RgG?6I&7#Jg5e zwKLnTbH72IK~MvOidvjP=VJYYpmhElzx{#k`JcFYv>=|f$Pb}=tnfU#V-0$*yvXK{ z7#q7Mo9F18Bt*D0$w4kBPYiz_$mgsAllj)1Tk*`0ZKjns#cPhrHV|kpgZfcG-6B(z zolPei(+Qc&K{IQZ_!(EN@X%ho)O`8#>vdyUk)^B)dt21`vu(euGp5Z<+~8gtp-K2% zWWx)RKJf(eN+AVKXzq)tpL&D3{g^G^^2ZcJmZ?X0YcLLimOd?YX5@*R_j{%1R)34a zqcthT70O^c|5geWwy&V(e5oGEH*3?z;p}Y|z!E1$&Z#v2>*%2q z0y0qhe&;$KD!o*f0WN!~C5 z(SLwg^5*T2tL9DXjkihg+M)Se)~8QAXWE$}IA%{^%&ts@3s^^2;GPmAW;((NfAd$Nkh*Zy8@g)b_lBq|JcfLAIuQh@amL3gEqn4Rk^Tc}a zc%qfQHd{y^=NERKf@S%YH5}@-D&VMT zxoI4T75^)?D^!pikR3-27$LGs5PL;E(b5~Pcligv)rG)JUCiKuGP4FFAA+UXJMz7; z&I@M6oQL*!jIgVUEoMb=SIZa@w_$%ETRg^`Bd2#I2b1l+nFi7ch>C`;lJ$SJQu4e9 zI4%Y$3k01XEQ)Mwyh}u`9C=>=`e6z$@%J7WvsVO`tL_{^* z#CbwCURWh{rK)+fZN8IBAF9#vo`+!`n)67d<2Knm05muY!@bu)IAe5v*f4$Ms`}hl zESJA-#cL33M;`)<0E2mdU zG9inz`F9y{+wDuCJ7ebRrE7j(Z8f(c&y>}`1_8Oo?Z`=Zr7-3kjM3>+wf0HUm@~87 zH1GQnQH1jPUyG;&8-5<2NA)eMpD;$2B5SA2ZLJdr!@tXw6T{EdxMNiBe$E7hhDskh zON=g=74_De-snf-#`dWIS$IB~RP=+0VzP1`lu>AvSO%@>((?MLonDXnS$Wge9A9(> zfd!Uaxon|Z^KS}|`pR3_?|>qnD5M1?Cgv zfx%y5vbp*--1@e)XWPwtdw-tZ&vRl}!J@2e;`$=WdPWv|mHx|m0#5?BVwd2dfi3A<{CveM}@AMqQCK0mT1(WV%Q#P8HxwNa#JdbS=WO z=qYFUH)&$)uH|m*U7%6A(0lD$!JnuEv2m97GT=FXgAaS`OV=I2F5$)TS<|h-z9ZNp z3pvqxD0NFd$QI@LWhzF!HXPHfunPkx(=7J64A}P`nb-S?HGQA*es%?~rRN-T)Oqv5 z%uzJ&Fuj_}oM@V?uv`9lSG01lsk?58j};LeZ%EJbZSB4rtDOShdOcKvgVq2y6qJt&VgiqzU2;qTz>!@t7KD zs~|=&KpCsj7FdjJ`e7c3-N$<_z(X{A304gnyS%e?*49{xe*x}du5wI;ynAwn*;4X? zgb}nwj*|D@Z~(WSgM6vGVPPdyMD@JXS#@%cra;J*_D+oJb=d$=?H{x`LimX`-Qo(g z1s(lkZQFM?Yy5WXMuy3k4Hu9aF*7$8mEN`bsA2}xP*Ebjk8?y}SFx|s4 zCw>lynihcEMHkpLua*=R?XpArF(?dtE7>iuRQK!6W7|TJHdy;Ib6YJ2Iol(x7VzD~ z@H>t>n^STF`CNj9?NH_G*m#Q>+Ux z{T2Pz9(Sr1MaM>UMd5P?Yk6B_&&49xFA-)oYHb#mn8@LySpyZv8_ zl@|vSXOFV1KDlR%BXa-BjoUDbAR_v4+Jdqz=!8X%&F|zU3I>^z(H=@xqK$DA3W#cUTk(ioebaU(LM?$K7+0wm-_Tc z8s;D3o9!_qoeza%Ip>w$ZBQuV;-+j=<@3o1#82(zil%tv<7(%eL2vWPgkGS9h<@JS$(?nwZ9I0J?bImxHb=^2t|nZ<=E9x zAyYTlz@ohNczJ%sUqWv9-5yw1mkQoCHfI`2+gs{$0DX2U`~zU<9eo3<`555%59}0o zU4sReZrFQ=GEbXStZ&wea%LsdwUfQa*PzEal8fj&&ZAhxJPc zx^$TNtm1jQ^CAI40nNL6OQ}XqZJol|k`r6?3}bz{$7ppK z6^^7+?@$^rf<7^S7lNbM%!e~+7h_4_&p1(~ZgHyVZ_xta0wlvRiNj;dv2oROodRdQ_Yi~ODymfBF-=6(K%#~Q*rmUb7F zhG=rm&bKVSYXLS1RCQw@JVNuOZuQ=I-Gl=3lYIx{;>EDT!Z1PH=bXI_<4*>ap-iM1 zoBOw1vJAWKgnnT-GC?<`uH|qzU>iZhjxCp5gPga!*OU~K# z#-DJ^G|aRv=;{scG2^LuUSn>4_LI3cxErzmId z=2`tne0oVdMB>hlY?d*iztu0jHQk+6+NG))55C5Uhk4H`yqU(LN}Pi|RS$(@pyxK@ z;qw>KVoTmxRAIimmwJ`g;HNw1)xNZSb$<*g9cx|k+N2W!+Wkv}DbII@SnsCgRW#>x zZEp&v-QDrwbNH_)&YR6IlasO}g3q~ zIA3vPHw$R}q~F_!-`Lp%6Bw$Ex`x-LlpU4u^s>yh=WUEFoS(yFo0>Y8jM*$-onw!!iCWX#16h;LMlMAWr`@n1GI)hbPHhHc6o$PA zy?Vi0weO~*&-|VKy?V z@@?U6CH7?fWpYge`)QNcvj>T@JZ2mD8S+)bRD8mujnHL_VeQg4X{ULhDV*JdXehl^ zt;OW>Ym)>IxGGwv%er5JD=_;3t5-6pqQmK}%tb^u$NiN{5!RY^@7E_sdc;cVs5B3m zg3o-c5Ga{2Kiz#a>P+Y|c-RCX0K(^i|K=xHY%hQG@6R$R(?~1|VoeI}Q}0DAbn~2$ zIGG{n;+L@7_`#iMo$%1H7$U1Yi=C_Kz=34rNF7*SivbG|?4jwH+Z1)ZRIhT2gsKo> z072u-yb4=Oq|u8Afo=1tJ7g+M8rS`qH2#60>9?$JE_yj&^(o+AyzIn#0ria^j^Cl7 z9?yh-F%2OfmmjN$ zq6bN-R^jrqd}w~ERjH($d%*@)ktoev97X$G`&0}SSjBw1=p}Ui0kt+Fa14PPBZOL~ z2%G#aeGTs;G*@mjm~T^9A3q%Hsc&3O0fiQG%roI^>~Mw}Yq!Xir?bLU2$qka`p94; zpJ~whq>mc4AS7y(CRsh#wj1NXVPRca<0GJ%7)Z5Hn*gNtk`uE)?EOZ%JY}#4`iq{2oNJ!r@a3n>QQXd`biMoJWLAu`7-ZsR`xE= zKd`pL?7u@}n_aBz9Eq#^IkEV@6+l1qR#5yd=Nv8Ocr-l>O|sIp`40Ie46J*O9oRz> zYMiPog3aS5S&TaW2e?8w`;<5+ihA(o$x9_5aQ==|dSqmDj+-7?Sjx>CJ@Z3(P$jPI z&kMh~KcmQrqDXck9Yh3-uLFuc@B9?BviEQ?h;~Q~Jw20R-T*Ptrr-7B)IY-fBLjFy z_a;Izs?~7gdN15}GCtgAO`8Bm`go>Ztwu4Q6!tqIU5?KlbF~J#owbO_;Rf-uL4UAG z+Rse)9vI^XU9-FP2Qy3#EALPGwj7DUWUi)F#YWfoBG!qpcj=ZR%{w)IUk$~NXc}F6 zg`4uuG9_0|&1Au>q?eSq=hFL8q=E3|5kk<Ai9Kg43$k=Yf<5yGYS7cE{4BFEpa0@WZR)eELe z)^3^3Fc*`Ud~0`R+$b)eu+sV#I=5o1(PY+Q*4M3&11Oc_K8Gh{dY8I-Rr+U|`lTVQ z1Qj=+vfnDX3#%Kt;sxtuUm|(?dQwkMiRrmIiMu#8T7NbNO|)I4aGRRiIPp5sHKECu zn|>7*K;}h8S5fw^J2nV@e7#r--Cy9~)5%tcL1Dj1Ao^0g?}ePX(1^@IWUib`gEoS% zTVp;$8%wvyzq9RqBj4?&j5@?KV7xJrBE9^`({pkrYlK$!FideGbgu3$!plLI81CKM zChw)L%xl>gDe}rac@FU$`YT5|U2p&UxRBD)Y)052^L~g)(0qd3I5dpic=2Nl8}|0_ z5anK+Fnzd=A;tm3r8wk|^*LjQW6r42pPcTFL3D8=ukaQka3Gk&lc&pq{pB^MC z)6S|fNXz#I!HHq6C8FhJdD_B=aVW`lx;|a3M@|pJ!+1kjN_sy|1yJx8+25)#t!hsr ze|HS@$JPkcE;wF}rwX+7zB-+>+HmeQQNAsPDQnlv2hfH`1Q1D{2>me#1^g`j0`nz+ z+n;c1-@{wQ<{><4GNB$RYO)I6qi}Oft%b|JUW&5>vQw7u({-p`NqVC$yJf*8!s=yC zwJz{-Ah{Wbr7ZVi8y!V7>PWjs4~?e8`Hg1hE(lEdLyiS}p2LBY|Is%1gJgF5kT`6W z9Lt{}iWEvBq31aCU_>m-^?d+Lm@#Z_EHEZ7!3_aiDu>JJo11zR2O~_~EOEfnE^5n+ zoCdJ(f|{G61=*`#M>i(HYd8;RnNiYo8|)ytq$tU+?QLr(jI%`X4`8KyAnVXEhP15! zz=pS>g6`lz$ok}wq?B|L-bVRiPHX8zu%-mw8QzO`64M|7cZTu{7))1lKTiWz!Z~s3 zcPHlmx}%a&Vg%KF&1+%O2miwx`rQN^FUC;F?-@ay+`d_sBzl#%(B4mH$ zN9yd_6%^@MUKO(MV6G+SAg<6@YDS+0>vWMW-)%9pytxi1INJP+SbKRz?2_6u7t4%`zyAxwG(Ud=4eoT=I`eMrJt&DV9?R%m8JbT z5#8tW@0kY;@Zs7|RaRi|5((G4RQ)dO6X-V>p;lEUo4+Es2po-~d>+fw_Au{Rax}0+ zTiw{Ak6s-^bo@d{!E&HOaiH?5tV+mn*uwFBpv);Nw-YzSJh+{=sJNyH?;oJiT0b49 z6>KB?W1aS=s?@zcuL{JQWCOqzS>Cw`C^L|!uHodiza#l$HzA;m-YCgwYIu*pH-zV1 z;XtOZC0;AZ=~hF)*HSazOn20g8qk9an+e_yEZS3|bP--tNoq%Drg0#=r{I7oN#EbK z?Kh`bR#Y2BKWDK)D;-AJf=Z7nV6~e`^eN(wquIjE?RA<5XMsURo_KD?-KFI&!(v?2mB$mA?v2S(bnZdRl-k`EC`8BmY{`OS$`e0?8^&^&6-LPwkN}_I z-sc-IL02hAvLYM_Rt~}3N=sswi*T`&l85M{Tt^XkGoj!wyJ_6JE^sI5~|C)2zf7GMeh5pzroq%gVTf`ds79-6=u^7f& z-R`f^M+Ovub}kF&B_8yJCL zz<+OWu*ZK;%lwktA9kl_!X2rz#_lkGVtQcbPOS*-o5L+T*?hD;_me&5)T1bOC{h}$ zswX`P%z}(02e-oEM42L8{Rf5olMDGUs)nM%N9KmSvi7RMknH-5Y4oBC*qaiVnY{@~ z`y8pR=Twg7lrsA_v3HYD4vThsH{9#3mVhI$#7^NF9@5mn7QV;s?v(V6S@vo)^tiG- z=Y^YcevmHW1wE_{cpb$Ddaz5icaTUcTx$1s#loNKAnVl0B~cU?lB)HFf^`xW?zUpT zLcQYmq_LB=L_=-~w$C_XZSHEpg7+wHq++>EBL53>MDhKn2Zn`4aiE& z@Vq>CPs$?h&ug}&KlHV-2XNV+$sFY2D_;y7vR#M|87J;E<4NqpCg9=`55fGV)?lL; zYvdjs1VFJM%7S8%VPKqpE`#F2r17PP@7kO$#hmIeU7ui#}s8A4-r$47#drch{z<24z@ zBz0eB3|k-p&O)J8(_r&xV#gbR-3$$Ep*Z)?+n4&^<9@=afWbuua%*!DL1iHhJ*Y|R zH_my8Ta?j+fQb4s5rq+%Zqbhf>q+b|=;1Y~dcq5^EU<1+y|r*#)NDeqDz94AlfMk1 zSOcXk^%CU4$G3*=-^Yy+V7~>$X&Ogh4Fk(uQ3IoDw`i_5GS7Q)Lx9DMtp|9{qKC7# z#18PCc~PmhG1s+lGjBQ(kNeV57-5an%jelI*)es`Xj4kivV*&8qw3%qFq6Qx!zW?8}J__UQfxcsOZw^wPvkIo4(h z;uo-YH`!WF^@)Onkw{!14CH~0xllRJu?;=+UjHDki`lPlbhFdKOn01Drw&TbLYCsQL^Byh{#*b0ej7u#)nygHKXsQsyS*=KgPsg_D$<q}(k3*W@AP`o9xc zSxCA5{{(hYuK)C+EGYQ@UH|WWxk=MauQRPa+6@F{!v3yZmP~6828E|NHizv5~ScDXNNVGJ=P0DsN*3^m70ZbtL?+J?FKIC0(jZK~Y{}O3CGkY;hkP9gn+kcEFrD${B2yAh8?Q7BJawQ{Yq1 z$HV(>yA8JTq_^t?_T~Nj;WA0VN4$w3ZRRpl7if{@NXTbiv}CoEmZ4H=IdM612K%`Y1`uTn&m1 z9h1e@7Fuphwx&ERp>(bQeY~2hCzerUF1mon611j|S77z`+O zVSNL~YfhsV|2!1suF4a;1oF4U5;WNIN{JqsUT%W5GE(O&zLvvC)Ss+3|C>p=5J>C5 zNKY3Ls=nq#YZh28bj~1nR8XP%j3|BLEc-m_AbmT?LYDDXMC|)yd3c-(5g#zJ=s9S>;;>b%d&J;H<{Cz34nW zSnD=dZ4CQaQNO+JpbF)#)zk#5^X!Z)3?>vEV5y)-2$3 zkuEy{1hnUV+4s24@s3{iIw!&}mjlqX|60IkkozN6Dud;YQVJ`OAs4QIBW4l!tzzw6 zT3>QV^4ssILOAKK^uOF8#XG@C*E+9%vUU4djf_6F$TwpDEusT}5>4OJP~Z7~xnr;{ zEPGF%Qn5>teTw}$P!0LwQ7hK4Iy=l$@m14UDfhV)HD*ynQR*V?=1|AdC2f%Uk0x;% zJG38zBZHF5oJUAt3Dr0;3emz1omL}l3pT0=blh3MGVO1U-@FoPjAs->3k6Z|q$%Gu zd3*HnIxOlsO3tFbx+?pRvo3mQLy~Dt8;y9hO%MKzJcndOu7)!kb|MO^ElzV#h&5eiH*g0@9vq2}>ck@b72t?aJ${agOaCJ1$E zOENCUwp`941Mi~3r2=aCGCLbfY|IngjUlxth#(|9#D;V^GWjJDwTp2mXCho9XVjC2 zU!ajWaB0P}s_x=3YMA^ZzJwBwa+HkbM#eZ5o)w)bXWF#$p!nd^tcVYYi0>uknNNn@ z4jGnr$)~_A5={Fq5gct&YeBD%aI}Z5>YfnQx5WHNpkV%MbnwrNi=i$6fe}~~QuQTn zG43QE0##bNoa*;_pg3`XxHX+KuBHX#Z>v}k858!;-vvB%)$V)AtMbOC`eKt9#SQv1 zv8wR}-*2b4a=#l7vg!QVWJ5GNeCy+zw1RXas+8bN2%0{Us+rshj{zIE!9zAUITLp|7i$8Qh!LOLLrhd-fPYT=;@WIIh zBjSN}9cDy)c#v4ZLGksfw~Sc(;uBqJLXrtF^~U!CkO|NpnZym+{nx_SzU(!vkjZUCJP3=@wDF-$KRMeQ^;16l7)XFw;YCVm|` zU^S~bCR#5{7djC($~4LZW=@BhhkKNiIn2xjjp`55LLL;E2i@r(t#`g`zf^EAAGWLl z%}=*joZSF@UGok8AZ&@>>yPibpb)J7v~DV}t~g^Npb@X0e4Vu%+J;3FFMKUR-I8tm zLgu#wV?>2^FvPK2KyZ1ZxS|f088@1cQ(TtJ`hudK7GP{xR#BuSIEt?EyHjyDHY6qX z27cYeRM-k9zgJsddzHql2VE#@|lI$~xYy zvVH8}!KWdYn+FQ7i^2)j)p6BG++)a=@Sj^GUO?W#ss|d_gNZde+>hI~>$9#i-U|UN zuMbbJSCH3hID*rKWXL3Y#uKmj!4?Tjg@%Nr_ZRKR$@Mh^)4^=!_t@i)+2o}Dxax(4 zW~Cqtjpvqyj4VvxoGsABxw+N;Ro#_rv@mrNCFdr*Nb=^aPgK*{3bUbp=(QesjRn9h zu$kZ3yx{)+I%L>|BFeUcV*~p`koziU>!q+H*DJ!2I|pI)^0Uz zi!WFuMeSR<^o?*4y3|5sdWWIpR%1d`NmK+WDBKBVWN8MF!5Vv&fe_2c<|pF4_wzwY z3oifK(vxuC0cxH^MvD}uK)0-5E0GJ7z%nqb0a_+jGaw|Z9_T+&EePPG9S~|ibVY+Q z6pD9e9XG6Si3qVPoy;sdruS*D=1J)9Q z{1L#-%G*;#e;C5A5=mNX=oG<;k;{j>fUuxCJVrzPV@R^VGpG841T@OpDp*%l(l`ny9v%nV{!=IoVH>v zwk!wVix4XH92Od~>qlj7AE*aVGx8&&6m`7`M^xa?Q7lDg&=Fk#D3R<^h-nEP=tyYE zex#6D4}Pl0#I|+dO>~IY`VpaIIUZEh`}_n{yl8-@4pi?BfU()*K9en2NA%jKUc;Omu2!vtLL-62@qE&DWY0 zc+jYRSe2$5O2rY~iElz5u!oEi1AB_^typ5zQHf(1!ag>1vmVMIQ)j6^Y;JCi ze$Nw`C|5Mrn;gJXG=`t7QavtZ%U%!Uk7dM8p@X$Dqz?&4-plFpN08nW7-}cF7m>oqE1UZX@{pNf9d)2YJ(L~6TwpH>Aiwa* zXgEDE=&bJsTt2U^Zg_T}a9!jyB?;DeOe>a24qG5Pa#N%bFHm0w?{<^YApl(iG-eQ^ z=9PfS+dCVI*TPSni1Z-W6sV-^ffS5!roxnV{&+VfUr@`V&sZ@>xWTEj_lrp|P*5i# zShEOBg+k7?n(&CeorVzM5aU9Cpr`Ohh@iZewTcd%lD|r1Nm96nAJx1rvP$bjE!p~w zDdzFQORKhJ15InuRPa0r{$c<`6qkjjht)(1>xN>s%v=8p6!~p3jq%oTS|&SNcLK~p z9b6%C$W0kQ6lakpGzQ}06j>*)X+IU(&;hpSYcR!f7XeAx^2H8C>6?8$k5;U&Rvin0 zYsFbQRvDPe-p>@3;B=iV{5;MZvX~sWDI|i#Ck4%+zHrnqL{GMaR=r-8sqNnG5hca0 z!$EjeG-{%vOQEjt;JxVmbX_5M`t|r7%Cdo9^A&iUAyeT7*P~Fpz5q046kECs;vgz@ zm|G%471)Jy3PN@HA>c0gqE0tDFjs<9GcqaxUiQo9u!>7pGR9dNgL@)&a)`{z$*N1+3+Ne{n`lvA28O z3_VM(hunoigR>F55{1Y0L#1;gcv6Yq#*QAnU@v~yjgjPTp~d=YK<5{ zhI1@(sCCyrDL?BA;5PKU)uK%9^N9&zdJn7psR+cHEy`hNW#gHk_)eci7)NWz9^ZVf)DT!7_ z1TZYw1PiSXvIon2p0_XKWp1iV{6HGOI$FGH8E&QJPr(g+Q;&k|LF2BB5s`j=&s^s? z5zgSu*$yCvdoihlJ3zzgw=8UNAT0Q_kEb#k`G*3}hQj|r`N3JX(izhC@T5P4vLyM! zx+-m$R7Z)+JQ#bxRVd*72N7s_QEqS=Qu1I;K*h!msUm8q4_ZmLSE@Ei`6)3)-FCyq zZUA_-*&M2z4nQb*v;W&9QAYN(+r9J&#mHi*ctg#>Ij0z#umX#x5zZ2lEm~brr)EY=})A56VgMl4s)jj^z8MoA7Plw z4;KjVL7~?)T)&rpPeG0eBI6(z_<@Cr5fsNVDJ6^olci3`F1)j>bTzoII~oQL{-F!3 z;@oCF0yrd2Y053e?B1W%KNJfy+7or#xD+`nvSBkk-Eeu-_hDG4l%Bi1m zyT==HuBU4vAc_gGScJQj!=zj*abe|4sI_TGIsfI3ft5=)!f3dAAqr(hqfdMWR^>(^ z`UQ7nw+k}@yQpc+*=_ov%>I&S+z-Sgks^GHZqJ6U(=U7^d!u`ewoUrlC+5=Q45BOQ z%^uX)N#YmtN?(fGe_PnrnhipZe5GD5YrL{hD?APl>48&(n4E*AKOJs}*kI^ai96Hx zdf(W)u55)-H&E}YXRvtL`9o&McAk|CmB%og+T~A$aaxm&ubdemGQPCfTJBsXY_w!j zPOVWY+V|bJt?J`-a8#4@faM?pq{0xdY@WC=YxZoOA|u z!Y-Q*fl2YhjH+2~sM#rQN~Zm&Iz6s6$XKNw6b@VQ__1rR8W3D92xYIoFA{4}@9M7b z!v{c{o;OpRpu8vN@gr%O6E4vs(#CBxypkBm>R@Jy$dYraQp&5VDYjRU7N39vz$rOePsRHfvC-JEcxQxwh3`cKigc)vXaP^~K>AOTP^@NVPr^1?k+ zD-cJ0>*1sU-b8wqhdJ$5?mLR`jWXYl^IZqY5H3AL2#xOJeF?E!|0#SnMeo!(|BpX; z>m|6^n_u&RRX0SIvpH4w&$PzxSd+6MC#p811?YdK+|{~@Ny@4fx^5m@m)AGX?SfDc z2)~}8$p&50rlrU}lccH}g_4H}7KHfM)mg@Y_)2KQ3$C6O=t(WT<1HQ9nLaNJJdsp{ z*BZ5Y$`)p4DAR#lxDF$V@kP$++}d-09vvEqCLZm(#QAtGh{jCWA=@Ql-Cug8s+jR^ zI~8XRhGNhYtx;;++c;}l&)+TrRQH%S!XM{qsBTf}K31s(B5$^4Ipn|U0-cu?ufcAG1)!&>;x{XLY>-OLg7!%+6JRO%-B7LFog=X%EFx_$hLzss&+tD{#T@RBc6h zRNT=&(N1P>pYFIcc{5{-YR=oZJ>9Z=5hA^Ox`B&C>c0MeOp9e>1U;jWoEnwOaf8Cx zMGhJoS4v;of@%^`)H6ssALee*Pb9>jRo**kux5UQpP=5t({YjYO5Y);oI9zyFGgiS zNYIaDbLqkSpP9`Wh_hhE0? z-dL=yL*XJvuaC>C_VcW$C)KFRT` zoA+4)LL+-=1xE(rCnT$cO>}t#+ZGRJC)|T%b$$&o_d#HxVL_8*Q|H2sQQmDhnsP%r zoY>di@C3AT3Nv4T1T5blG5?MkMWC#j!)8321>d3Mtr8jJEr^%1;mxy`;Ri?O0oAb7 zweJtT-d98U!_GK)D-;psU1~FXbMu(s_T|yZUNq!*P0_;pKCfhiS%|zATu10H zp~eYt>5u{Te5g2#*szyc8}N+f=pmd2nnKvt^Ta*AIXNIM3W~NVRV4VkT%$=LMJDiO z(eUod`AX4@FAN#hFek&$_zR4qdmt(lrbQ(N_w{R69Mn@RMq`#yWMi+$lAGszj{#%AxVMlC1hQiF)$J_ zo$5gCLwYJq-u)Y>V@~r(og%1zOp7Fu8$_hszJ=dBcoe{7v5#L#e1G#vymzfw#`~?( zxHzx8N|97LNo7`Mc{FuL8FRPxgvn01n7T_Rh5*OK3Dbkp@IrVCSxZGh9cx=NuJ0)* zrg=~4A<)O1;|AnzwCCY9p1hloA8lTp?K{8|KyI#j15|WI}w<$=D(}o!fDmL%% z1BwhWFEXj6!0{d+2QeTbmb6zxz=!||rCjJu-8D$+!m7Mb^R5hM$>9f%2O3vLi9EXV zgcKC!XR6{@(f&HJfXAYft)Ae$kO|u8dY8arYI?`2Ghz*$0co1~MTt7#2yeCWUBWHX z#=?$=D}YI9`6{5uZT9{nO$aJ5uUtq2fLDJlxhOROtC@tl#!ci zvN)M`TZcoqDpq4&9S+3(#LUuRApUltGv6Y%x>k5WV20U2)5<+;;L3qFyL-ud^a?q??wvsO3KLLO?I|UZZj$-oSC)x1qAj!jGF?h%8*$ohOqrGRkEO?j&Xga^ zosTXkgKW~dyS%&C0uvAKp0Vv$SOccple~Clqvtg_4cJf$YwXo{$uRRgc;uPVaV7J5 zRR{?LXwDO@THV`;&}*(2aP{At^!;ciE6NBxpGB2bx3M^*J|^ysNI}bm+45?*Ic}0P z2Qpl3w#QsB@62Yt96!s{+SO8XL=}icp{;YcHU4ImfS*8-_lR8ppg>~-VPCLArGN-1`u&JJ1BElFq^ z?<(Jk9yh*lZ#XM62D#s3T}lK$bWdxGto#{P zVa;S^b;6~&UnfldBYY;{A~zXyn&H{@l5StNlH1QI z>)nOdPQ2#*ARG$jYTjdQj8sx}f@@wNnhtti3?eK;cJ41^NO-T~aNfYYTM{UvS67W^ zGJi53N$9R_B?C4ogI;`15UgqYF49Tgvl`Im6;PT!OeXUGp68*Q(nFN$1tR*ocU^4g z0S^SIXyvxn_TfMsww15+EhjFqpmlR<0f!rO0gQ$gJl=2S)DGZ4B|KPyBs#@;3? zG1g81qP+4Z|tK zWR(0fjZW7RwI?L(^E^{=sJV_|q9`H0smwg-!d`QHW-eCn_pGZ~MIWNnbNp6YWe{?2 z+%XSUme<`_N2#h!xPanV?6G$BwG;Qd!tfa=hyB)18}O&r74W0BVEcgh*Hbv11BZPN zA~K;7U**=xpVXN)7f^y7j|?}OB-ciu^!!DLTa4KYA-X3?}c03?cggx;&8naak!o{S|WX=Ov z12BL0YWZ~LY;`1E7+R_{l3F?_X`i6gje~9%2gI9w9ZP2D2Knrk&e5@b-HS0OzkmNG zsKK7c92-t`m@5H+x0!#SeFkKkOt4PUcyW+T;7+ritsnu)Xzw#hy?RF=(7m6563)elN- z<}dF_bn;HW-BY`lG0;VVSLC%^=o=5EPG%PQV~mx5Fe)IE49asGK`BUKe2tH09hEm( z+3sa@&?qu~tJW`|gm8a{e?xlw1ugysdI){v878*QP6YqZ3jYE-{z46O@&=CI?F1}r ze<=n!MZ3T71OYvrjES*@!G8iDtlv-v8^<^BA>?Rh|Gyglivl5F{1*xFpPb3x>c5`; zA8?2$I|1uo_T+z}9TGMS90dPxAm5nA|3EwbVLEtu|Fgfpq5ltTg@J+N-%u;Oy#Iw_ ztT8Fm0|*L%Lh~pA3xVnoBlAc}Nd+HhR}0b#Z zFf}##9-VK%MvH;Y(7@4<(b2-p+*#+pQ}UOH`5!4^WMyRgH#zwa(1(G5g_WN9|4LBS zg_^g$@**nV)7Dc{W{@>2evw9U3pa8+NsyoTGd=a#WrFcYMjSy$nF$+yns^+9bjY*6 z)Ne4hzE!l-C{@xjbN&K5NK5@R*$AZhI^44;O&aBOS)3}C7+DdVQbL}mO%kMa&g{=a z={7UpC$}q(qwJqE-cQ|6Xb=EJ{3sa8+wxkC0F`@_!>7X`GV!dx-C%&?4q-3W?~fwj za0Q1n06b1Ynzh)vZig6=`2~C}KB}s4v4g%~z*X^C*hH{=H{0^z2<{*rYivY=nKnNO z{JgmyYpk~#ZQcgm+2JNEHa8H`TR*9A?97#ne`0qiq(^?n7AW@c)R#-F%zyePSJ>Pw z*%aiiPF>h&Wvtn{Km2+)_C?xX?0c%}yuqg#qJSk4cbjurc?DfC`hX}vyrDl2^lsF9 z?iCCQuln&Uj~4=3J2XcZ)KT}?uU3TaV`z~g#Ittx`;FO=at$jk9MuT_r1=@I72e2K z_U(kybNu^Hf2+!d5X41lsKU(tMZnPx4`UdwTc2(tZYbNc3Wf*%eV+#-cyXi`zo-R^ zB_uxnzP0d`H~aT5#g1#Y1OZ8js4QW8@=c2=ktj5g+<6K+b%j=KIn6QC`e1H91~H1l zNcvOL_RL55#2iDya%DW#tZ~C8)Ix;3)}QnALUL1Gq{G!S6BhibAL2OdetP zJ2SS=HlEj{EKSJYC~(equ3&X3^vr!#dSG}EdE-tC_dwOxRjEa5IPI0b4B13z zxYPtX#OU;6gu%b#mLDc(+^r9C56`U>fQ)w`k!FprGJaDQm5VQxpyT+)eS&Y{ID|f> zKSg<)4!%#fL7U1QugO@NYjP&`4&#-^FP_z$2-upflxH?g?m}QP8?JbU($UDd_VO)AT8GTGjA>(lU5Z5vFo&EAy z!9!W1S#_wqh-xB9)}&{yrn4fdJl!&d6Wb(5vvTQIm1T#gI<5lWLd=Tlnx?hZIjB9x zp8=_D&Mvy0OP}=hsPT~~21;VdzU{H) zp)_pX?WN#6Y+e)d#N0eeIfMChp@+es?K87e+n%uAew7uFhCgGMAx{33Ep~5NN_nV~ zgL2uj>E^%HXLhwq^taF4x3G#Q@|m<*3l z28|c`>&Co*@$@0&*?js|zx0q7dDCo*W6zL5&oy$oqfWil_HhA(uDRU<7s_C^KcM$C z58KSwtc{xxpdsg z>s?O%aNfv8V8Eu@9y34esa_atP}S{T&GUZzB&9zfh*+l5*--RUn3&^mPjo(M%2MO9 zGq@o~+p^!xSa}bP;Qj#6=Xy=+(UKY4&^v}I`bq=U}DN7%LY<*qqGhlt34M! z@TWkkg{6m5kFuC*dyPlAM1A+b2Fba*mzSqtf|Jo=U#EEGL^67eOX&5|^9{wYp^wnh zNPpdEuY2RxEUqXuBE;aD*X~#n*f4m9c1bDMg0#KDRInk-5$ezt%y_O!ksq;NXV~bD0gnWp{UKlTAuG%ILx({Qotez*Hv7M*FNG6#(j8qCDV$N9bQD%7o_0d5i*h0>uF-(3(Wzh$N7P0bxgA z2Mu9NVSEHzqMcFhh&Moc9>Vy05C!NrFot}44ueKvwu7|7z=mC@cOHoCa;Ul*gO`qyfqT^#ng4xbY6$5bX#<5Nn7+5K0m02xACe5oZWJ5%`3h39zWp zj8_<~Blm%eHkHbU;mdBiEWKi}wkwCV7N5abwu*-BRQJyo+{L587pa<7Gpcp+bxID+ zS2a^o@;O*SS%svQ&NE6VGl~>o^$biop=bGRFd@?dVG+ufr|7Jr0S#+3%*I7A8L|N( z7LrXeNngk|ZFmsDN8JPBz^~kHLU$bqjNdHJKCpK2Ow8=?&<-SO~$Vm33$UysKf~la@91}rOEWmufq|@r%sGT}w zE~2(E0H`+ev=F-Z5>3mU__+&*@(%s3?G$myUpGg87MJBJ(8l;j+9- zTLX&b00lR?pJO46qo^ny>>IPiuyHy;R$^dd%V;Tb_bBD0`o``jPkXFp&4p*SG9h|9 z2TkI1sF~`;{?11K9OuIsxx~flK+i=@Y)}U+UEBtS2?*uWyQLj_64umT|Dx!e4QCSr zyHuwp0nb;ziv7AG+I`}#A?@bPMdSuYW_i3>&^i<94L=jBEB1rcx0$$TVI^wTyfQ;N z`U3f!D3H1G0n3e+Q;Hjt5V%L8-9_s5e`W2?zs4oa(c4yd#w<_}Pn*eA&uxFt`hygD zslUAiorPReZU>}Y*4$HrX2j-kJNbbe&#RI7Z^Z6@PT@7F*hv>fwmW z&bn{)bv%~AUy_^ubitskJeMgW-!$M^9i(cJ;JxI#4MhOc_xy6zIORr39P4`tffqVa z@f3F`EuOqzD%^zF_VwNA#GcYfaP`TwmM*!^#tWts#+oE&l@N%f&SJNacuiCoI~Aha zSV)ctmvz~|V{#XaHRcs%O<22%kvH0D#D47)vh3z$=yM`MPM~{Rk!!d!cd~$M$0qA; zAfUvdFy%=IWI+BANUt;cb|#4syvO7LJ@c?4cEWrmZg2SyD{ z9ReRXvpWKeeZgSC7oS4{WCB6BjKbw@297Ej+jzfTyVG(^kQ#pdJMN0>Kj=%8=FjNXJT`rPsFX~9=6}<}lTO9t z-E;<>TNOMATk}}TxEU_;*?lq=uYWbOp9Zx^v2(gwsZQk)ZBiGc(BI z!++mGwurP^l(Qzt4r4yJ|ANY4OHX2U z2lZX@mlh_j1Sk}t*W%Uh$!g6%Sqp0bVSM^JgX%HrfA;q7F?On3s^Xa&Qz*>ROj^JfiFsMH=MN56udz=>ntRYk}pmtj-N|d zvcpMPUN;%T*3jE`yZ?hLH=KcQ2E&H({O+)yUU$F-gpds8zTatmf_R4ps+P3MxGpw6 z3@~=c8<4g3LoN=z+C%^aGpw6NnVh4col?tL$!DH>Co!)N*~3fc&Z4`92oL3u z$ZtarS+xAzv2k$ZqgvcocmDz5V_O8e5qRbU>W{tFAC4Aa!c_()P~mL2V&sVf<;;7A zg3RK@+c%85h~1M<_eN9|E~E@O4I`>U${^ zOnOt-B44*Hn3!z8 zFNCfd#9o74tE~wFa{eA+NYQ|sJvFA8DaF{JpMo1~|R0t=v ztDrUf8N{Ylj3h+M;nB|L6=qE+oofoo65VU;Gicr8-CpL3k?TTCw%2*M)4id>9C z;FURH*R{s27O$&PDNwDhQ3fO;O2o_+0=T8LAiN<-GQ!z%NTPPOD9hL|<9NvXNd36c z6LJhGwzanz=9H~;UFgDHg%vGiIXnSwiwxmk@~SCUPE94az8=W-@WsR)-S+nhl2a_? z7#dyxA0_c*JBw=kWU&-!VyVb}Jm0XSNADIy>tGt*MkPF*OYjCFG$6k0 zT9T3jI|F2@o#Z1ns}w(;<7l#=ImkQ9_x^-RL(kaQ(C8wHLZVcOOcfS!WIrxepxtI+ zAWLk9+Ys7TqZ_HfM+SA@;wV%-2sgDF-wEW;Vjlp10D0CbAO4GIg@N`^h{|Smm#7XcPuc-?;07vV^M|}1yC@X7 ztl>9Cp3y!~q<^ZL!;aiEp*7_W0x|}`l{qwj&Fq|<|Iyx%RGzN@#l#i!Spx1QIw~(V zm#dx1h^RpXyLx$wF+ho#e!`rI<08W`J`jB!(wN1souhS=o`B6TDch=@JX;0()?H-) zLY(p}vqHl3LH|>6`uMjme~3AwJ ztC+vfSeBBK@QFOle8(Q9ECoAwI@zMi#EEr9E@QEa3(U+y3H1E&dHP(Nw|KP%%@nCD z^yu>qjfwL_DUkaiK}bf>AKps>8etLs3B!q>hq4;L_o-qk<(GRwD}JdV74-@1qjZy! zJNKGUj2z6Zx$3ORWT!dxLx+PLdX0R{uZ*z5`h!((jvvQT39<%JTOJw*bQ?|oM}?VX z+@X|9Fql*l!(_IfGG5bO*JS6>j1qgf29&GPs)0~F8`yN|3BfA~V|@C-YsxTLAY4?bKleb47=v@*DYut=wp#i0`hK?28&3?yb6!=Bfv?>f zm0SmX>u3Ms_$-RTE$(&+651KAI5-#SCuIc2hF`tA?{b($oXH}R@0u?Eq58>Xw^CR2 z=#!Op$Iv3uvyJ7Ca`HEKj!cy5p3-PVVBwo*rkV>bN>Kz9*(yvY?D3eby9YBt^8gZX zQUMJ8W}kwTtJ?BwRgi)zAiZwEOuq9=qu(=!jKx7kW+q4ClLcw7HIZ4B3|_un$aimo zdE+`;CRI8T;Q`|}nEUVD4?(P@L2*&|gR3fg)E1FltY?%b;0DZyh;j5l#6T@LZc?>` zMoo-nhfswo*K!RV)lr#+bD|u!w%)GeB4FWj@jTKAGC6MSowV5Y5*HUdC8p5p0W z>|*qz4%+l`ksS#Zb|+{<7g|X(4(Y^T?l~|#JL@)6@p*Nm#1>*#a15e_!bbND$o8w$ zD>9O<27B2Wex8OEm=mztDdv4dvL|&AZY+p+8Ra(0I$0!KiMwt3*$VV-13MH2KNHK) zgO}q|e3-bj};!u*5Sjt_>MI=Cl>ZwiC zh({rgB@%gwBT!;fFfp$+mC_01kI1wila}em{nqm4g**y(We%)5Cw=NORWvPgs+<<0 zKiO9-NSupPdTn3$FloA$vW73IUa1#{OKI4$3lON3>pQ=uBq?GnMCAb^vXv(GPA%o% z0!$s2h!u=-tryVvnRM{nHkRt!dJoyP-J8;TgkEn|5x+sMi6#st*;AjS;QAgHw+>-G za?ZXJjh9g{60I6xY39frCJ=R*?nD5ce5WIcXxfdZy%)O+3#05#Jks)ho=5XaS@)I5 z(J3oEi4gS`1fwJ~~#2{hQj<8uZeK`F(n3JyWASz~0( z&Pt+sNu1>XOv~v@9TA0OO2&?*f3}hvpt@o=P!N-}8DM8dS|9Qd8bWXEa}nnW+KY;x z9ogF^phGA!Y{{O7xy-VsamPBOQ%!;J($7DcLufvDOH5#JqLXn)Y4XmWgS8KSdyT4o ztUIdr7$Ji0K5Z3fwhnNh#Trh4;7<4zyeDK!5h>C=o*7AHJNBoJBtFHTqOU6tU=nEV zwrFvSm)r8#-hJmZ5tu1j<6Ru98#lIypi}-ptC|k;>{gt!k1_P>rX{q`RDX`#+dFE8 zJRQ5DO+%RQILuh#6$|gJt->>TM_-sy`egoaxM_#})S^0XP@jeo9c0dsS-8WEMFEi& zuMa)O@$NNb`DXC7^){_{+S%*alg#yi{bddfyAu@9lWXt_Put6tPvvJ4q_EI4N521&T6i?wrbp z2^`KbE;Vix`)8lnb8G= z7T4VD6zEod?O%cxVCGI9K<4_3t;)f3&ci@2-FX2eEC z)89{5bjsYe5Iyx}S=a{i9oph8;$fpsjCE=b{2*q)dA+P*1f4`kIMe18W-`sWDG(rv z0&YOlkBGPW1V#7w4HF$?d~Rxk3nv-A!l+i%Y-WudttxE|LXim z=!V_JvTXDXHe%fniC&MOaWyMpFI4(IcVa%mZ`g@rob z4yygnkcf!}{rT@15tDUgVw-*O;l-@BuaH(}{`uBhnRokBwUZHhz29mPJdnF!3S!8q zFj65U(*=x^%ap+=;p&mqsJDVrd*UQXtW-Eg7$-|$Ba)9cCMcXPUqzK{HbgxtvB%jz zY=|NhDF+^52Hfw+l42C3`d>Lgf>z5xgs%N(e#XoJ^IOzf{++6v^;9#W(~oWeLyI;|0n@kvJe5zsV@VlY8?J!{L zG@Yn!;rPfw+z_~cU$6|gVMARY7$Fh->}exRL}NpRa-vs>fI`3uZHv)#4l52t$60>B zrhacp^Qc8+U|_Nd{~`!yqsa!}UAm6}`zPPv@l1s1mQh+0Z7ekC_Wpm@UDhH&IC>>k z>M!|>nDg<5_=c|5rIW20Q^UFAb4^oLJ8BihLJ}pV(mo?($~XIqJlb`yp9J?KuCfT? z(*1~1#!D)N_T5Vj3+(+3BrdI4h`&5DeF2H4iQdo*ZC5YgCd`(! zNFgjLB4OkZG(_`_$2{n_2UJ z#fkF3K`B@<{Jjv!h~I9l53K2`UD}`S!Z&8!G-rfkHoP>vUA`_%y%*Nv-R)-i(X+0N zovA`0`p$}d5Q0(A^m2Ys|Hs?!12q9v{jX6v zIt+RDl+*TS_QbF@G$n`@Kc6(2TGZgJ$LmO!g~`@{>cW>f4wzes+ofVm0tYC$s?9WOP-Kscs`0c;yS7EpQVR>*#v=re&1OsB zhldnH!B^7w&{vMp6aJ1?d^>1Q#KL5Xv+Ip6KQTYJdl2hQDpVbiR{m4+B&amEF*6@ej zrLUys*CTW!IuS`u8n!n!mMRK{h2{m#_?QEP_8i|-Oh~tbP@WdXc{!Wg}Q)w zx;MFtwB3>Kloal>xFvotX?$Nz$}2jP|8a0Wnv_ow{nHaTS%<{EvtSD}@y&0QKie{4 zWfq^C?D0Z$>5H&U-a`d^j7%MHK!kLJwLyg*fM;W?dihEuk)PHA@qDX#()L|Fa;K1K zd2&L0Hf2{pgNGI{in`OV{>xkpU_+hW`D-1O-BZOM$jFLC?SwH*bS13U(EYITlQc_N znt1$!`jIcNmf1@OR@Wc9E?GLQmoSEwE@_lchrZb@N9nQm;%ufQi>wzS@0~)9zC5=x zW}0oZ>Tvxs`kR!5QmJ2g;NTfKRUnLv#9x%wVfSR#`k*D~%T7XWSzr3qwxxWdA(X}B zY1rRK6-!gg_|QMS?Dbj`Fw*H`G{boZi4rLcJ($>bFw#x1{n>Qyn-|;PF@5=68|q*H zKiC=bj-|2WbIR0xZ=`@RPD2(5~2tcyOz%S~vkyQTVkIx;b&D0TOTkVQ8R&r9k8Pp}?7{c(#lj?pGaiuVvb`vbm&aQnD*F`|LUqaC4p{&e zLHRywCgJsK_2qhYa4~gkQGS28(Ss*Tq#!KCUltc>AglTf4AgBwyi@8CswNMce6o+a znB5`<&|_C+1siEOSpo#@_uaupx)VM9#eO+@K2fHV^uz1vr5GZ?@y;mwiQe1v?;5W4 z5KZJ*L4sCt9z}ox(#Rp*urZ8^;svVLJ7HTz#@#@%9=_CjqaxsrBpjQsA-8DyLz~&A z(J6(TpOaD<)zE$Dx0Gk|8&b0!*52z#zK6u(;y=KGZO1XJ3(vNY04=BNxNLV(pijas z)xz>A^E{9$iWvT;iDHrpV@+a_5utMuvi8~yjcOn|d-#oV15$6u#uNP8Qr4Q6Wc1L4 z8>s*-x7JP`sgnQWRXjdP7{{%hvO!Wu@Zlkj!oa~JQQea3_nrCC!~OgMrFA$jNvMrX z+L!@(#5DAM{R^?PFsToYoJEze0D$?1H2}LGo{CtTMq-+2=_K+GpmZsva!LqZpZ5UD zO)?)WNpw-$J;PdAjsu6`=pPAJ3tlYn)?;zOW^uqf$glt?<-9)1J5&Q1_6IpPT|Dlq zm|d2{Oh%;9+~8}iX}zo_0`_qA2M#6Qz>D-E7G$OB2DVQ6hFRC2IvF}}4;Nc%Npx(} zn?=sJ(3U;0XrVe z_pB=ipTGRxS_G#5K!y@|xIqiLtwo?vZx2rC1Uyi~XECFw^9CTPV8)oh40i*MYj%xd zT%oPZM*zaR=kv&{x7@^>lxtpM+yt+(5blztmTljIXBW;V9 zrktzq?b>R!*xKKpQFGlKc^cdK%DLrQV7D>UrPiT<4tYJKuX<-{(IY_g-twImaAxjB(#%%(=*3gO`A+ibSYf zIc4`eyh)@(Q+8bLZdGTywi{bic0j7@M6Z}|%l>?&n%|n^vC$YjvBlL8-|wr}9VF&* zsB7YY_U%azr{tmG{N#9LOSA+sa=zq7&I#EKkJ~C7qs^ZdZVqZ$JEz|%9Fib0xIg_E zf2v3<0VaV6eK))EIE9|%0_|&sM6Z|N>jEjM)u2q8rlyupU*3A*)W&6f+j#i#{Wm@N z;4Y;c#Z%qx0(#rmwsuGN!OKxA7KU&$b#X&3{E?Gsybz=v) zq@KK?Mr3fPz2$&I=f2&0zGv5aVyPMWdi80riigGb=#cjL(_5}qx$BTsX5RYDK>4-i z?oJd$h}tFrdx$iZ>|MDi(bY7ItVi0OTGe-Bt7`{)aBe%dB{wfG)6JR?=0>Uhz&hhD zQnF*|$GCeFs~feKmtRlB{MkkrC0nLs1t#k#96!Lo#t6eV1&(F*IfjflsD^-Sz}dNG zW4;y-!+pU`G1+ysOQ?Ek_ws!H>PALnI?BH(BzW>y_WQ5$Wscux$Nfro|Bu%%bNq4c z+@A%W&^%s`ze={AR3jBYoM&N+( zKsf(R_d%TnC~!6hwdHo#X9J2m*t*!+J3r!n%nqajD$7klA;=>R?&}{MoIp)FC?@!$ zj00TpN96{DgPl#x>V>nCxs$kq-E#-~>$;7{zi&}}Zft4}8gaEUHCK@q`|EJOUuOaS zLv|^fsV}wgG$(39L>HtG?Hsad?c7p&+2Ie6sr-W5k+~utWEsq_v!XkOaI^=6D137? z4tJC%am!W?f50tsw=}d)lH$D|+-NHMBeuAbp5NkG2gFeS;z)%{Qd84qxAAIcO~`vK zMRhuA`N!%~LB7w$p(d}`U5fVjm!X_g{@C+tN>G1nF+H-LaBQ()xHt?)?5^WWdI-3L z70X--T)32pxJ%(*ClE(W;g6jd^y{X*|K~SlXCcx&))?ZYXiG4!{3-n(6S$av5tPGP z*$ntP>2a3=mFC zw|t~AKUx{cJ~%iy+MLwMftM&00av zqwwHhttRjS>wY26DQb;R#Sxqw{R(D6ya{ zCAh0jT$A?BCf`P|&jNR*Ghe|p!*zLh+ zk#=lK3cC77DKY5&a(`#n#m_?~diuxDzu#CKDAuj5S9~S;mNb%-U&AALz}jM0$gI?$ z`TGQ;`iBh1p}c2Z=NkgrWhNb=461oXV?kKtTa&fhg{3Xlvn_&O{44v@1kr+u_38&l z@De&*x29m6R9^yJ0>YnZyQ0{c@%Wsd3>RvmaePD_6n{(X>b!f8xIH#GIjre6=PMmt zTwDX+i^H?y?S&oOe5v$);VZAsNYcZ#;rrXGhbseAoSaVkKYGQWFc^$oLr3R9UR(AG z67R=Eds+vGY&y)`!a{eGnGXSj(9zPOY;HI0_nq!9yKPRGFL#^x2Vy+T%gK4MI*9DH zFh9?}u{xChth0(cVAymQ+gvIf!>^NFt0m6d%dt9|I3`3<==8Q!NK{nkk$#~D%PzLr zNV#ceqJhUf(xZ*>1u#!QyMG?8FHmS<+>%dNGQ5^J-l-=k?yIb+IJ zj7cVNcQ+?Lzf`Z@sp~C;7!(w4kCy1SmFE>sH@Z1Ie_oc0DAOrSMY?rMzIDq|4qBt& zI{ZN$V$pYSe9XIfwbi&iUqtf|=AEtb?(0srxTwR{2<|}mQ+YUK2AC7GM95;UZrUqy5 zN5sU$dHu zy2{GY*!S$UHf`Ztu4&BZw;AU3@)Xk}gJ=~}f`_3{s0jks9C|obRK#4_k9htr$#Nh| z@+A2q4qJigcOMD7w(lJ1C~?FqBgK=z3|}6W`hwNeFAp6b9|x!8mci-Lz1}pARb*#p z&((zDGks>7o11fVblib0;fX<4R2yCG26}rXpmnJ!DFP<#cXODr14~P{f#DPo6dWLX z_>kZ8$adq>GFrlUgji{2KsH)=(n z?{BQ?xjv$<8$VEG4I+7ngLAV`)XC$F2Xai6MWp*lwbp(*nb+Z6&G*)|&B@y7G%t4w zRn4vgEWHq1Ih-dX1v_t3FE)z;au{>3LlzXUC^zq}P z(CFxK!^^$IXewzPA!ftyd8;(=FbOCxX?O#zxp3k0qcg`V<>Yu04nYY~IOg z&$3q2PHD`<=x7{b;(E938L5Z|o4`AQHQ5$~Q!=OytgnrqE>}UM5g;*)&onm-Ey`Sj6+pr z5cZ6SNP>ftvrxa0$Mt1_d0)yC7M-f+vBgY_&@($Jn7EnsF#^ofM3t4L?NnWPV&drK z#hD{NAK%Z3YMYa@!L-lfHKAuRHnF7vW;UpE_@_%DLX{T%1ct(^PF_!Eo@+9mx(7H$PvhVrmz3+&WK3J&D%RPlfU+o=DI;8WvVcxqOQWP#e)LAqF6A-s+Cso-XW?y4Y z>l`e(y~Lko@TLHqv3RVf>0^2&D2_qFs}p zf6FcDGDbd+U=UcrO$JSBDhSEsdu6Ixx>?HCqTADrnrdol#X8&!rpeqk8Xg`E1z<$u zo86@kih2;%=9E3*=SSJGU^?>i^1!N<2aTbF#=cM(-ry)^GFv7Tk;jTIn5J?-^F+nM zCm_&a*)nYqfa%D90E4OZ5mlveTj1O{cBhd0juG$(br?%V^2|SgrAwOV?7VX!r&mez zRRvnZcwZU1lxj0t;1b5Zy3?E_IXT0EgGKTJT+I};!s~iE-*MXjlZuo}an`QK&iga54qC_=TOcn1 zi?_k9I1#rx*_jKrEgm&tLr2dd(npS(pAbC4Bdf4@4myt7ga7n%+iN0XDPG;Qq{48U zgkLur?i|c3c0Ay={_en3JgS0v-8FQwLw5MgH<1=j9CHmH(a7|alqQE+p;1Oi4=@16 zJMZrd7JdEt6~rHU+Noo>4CU9?DU8?HO~x^(0*`$88I8@dIbrbAudD0mkJM-fs}X7s zV0Sq=IVWoD3J)1&F|JJ+N)(fcg*l}@Jlr^+?09Q>$XL?L^IEUi-Ssffn1JxwJO2HD z!&KC1vk<{ye>8!eTMVRtL+JNf6gUA#d_1*({(8ITdLI6K)IrpIk3<}?BggNdUS!vC zMi=&k3m3S$;7Mct?p7azoH-?70=2Bd*Kbac+{mbi2L@pb`%?M&=VInQP^Jbu=Vc>;Y1!S;(anz@zSRyu#ivzF zJO6ZtTqYtjGxOfPd*XrU(b3w|4K9Ri1_G8}Gv?>#PfkwC%E|^Wzbewn(9Nf;f==B- zCqoj4U7(l+dY^;XT3cH?D;Hd&kje+N5del5#Lh~{eY%XoSFdiE8P!b#3p9`|P4(Jl zyu#eX#Kg!b<1I{EvFfAi3N|ioOk7+Xuw!}89+FV9+(>l{PE6DUF((89X>{9WonX^% z@DF;VyEsEp`<&2eHCG?q-6DN*s3zr%#`rqeBtBz0Hmb zC=;4RS{&v*c;Wk?#p{6Ya9DHj43@Ca_2TIGSlIK3`8?=8F}F2d9~#T?_Uvqn_ZfgR zWqb9C*mSt~_~!LK=;k~M#Ocq04&3tV{HO$Ny$SQaJYD8@-FUBAN_ON}b?}d%yepw> zG(R`D+F_O~Dhq4T@#3e;>hzOUNae*1aAk zBJwB16Vb60Om7g+W!eJ43Aic^FIL|i)zv)?_Y*IQ+~4gapBy4KHLXBZR^H@D-bv9zCPKpbH`QN@7pmzV6aJ>6S6Ii7TA z#lJxN1vdf28EN(Ph5Qc7`+tSyoWi>_Xw+}kM@z2&YE59(M-ADUZ8bdToYO)w3&dRb z5;0llm~GkrJ4AoEPs=F`cLd0ScIfnEccG=FWw4t7AK&<8*VRagewf5_0Eg^pIV(N# z3JMAU7=tdvA^$B+3bT<~hgskXwm|&;T+zehXHPs+5CEuV;2AE!nx^u*y<;`no@oZi zjVo5$*0yLk4S2geL$^3H9>@810QW@Kq8{F-m4Af*{+-+ThrF+^?~n^+qBRJTmmd4w z!Ae;5TJB3-8!l`VJiUv7cDYg6uTy0?x3J)+3WviXv9MvtbwH3V)`$uSaxPaT19vG>{YH1xAK(@80R<*>*G(*a4fBubEoHMXOs|tf^hVGck{{33&p0S_m)# zdz|*F$o%}=+|ARcEHWL80-5b;8r^+;Le4+J-Q}>E4Vq4X#^sS~e-goG(x@7uJbDq> zyt56M9-9$+S4!6sL*h6Xg92-77D}N;@kF_4kULzbpNP#p__lc-2QaW~%?G%+1w!6G zQ}|py_+DLdaBwViMvZ#tuZh86^NV{-*JMg>CZfs$gh9R+>xRbFgoa)?55hu22R$S| zWb4A_)VsR6L|h-@;rZVt9Jf|c!L@G${{&An4HOh2OG`_wp5l>{r(dIhcGW_ zfaPRmWa>PR?VCLgfg{QrWXeUS+I-lK-V^>_l9)}|Vf|2jJ2xsU%=7Bvxb5@jGMhF^ zuv$;{!GwzcEK}+cmX|BMedmtDRNX+8fNX(mZBo2pw6=UDwAU;Y{xO)HH6gSwIy&0( zcnjdr0pQ=te*iQ&Idmshhafm4IGDcN2_yXO!pH}8w0?PGV`H!qnwpz|0rWmtQFg~P zQC;Y$2#{5lJ^-ZRH?iCUx!gp9IK9`9b_-2_Ws7yH*RmwT%*<$Iv$PVluSKDKihtT6 zBFx!g{-ZY;H~_9HUi+yrI9%==UHEtG{WV6=yNDndL@dd}<_m^7mOH$7VMoB=p~8$) z?%k&~v#`kK;N^9js&fQVbo+K3xFK5mR9N{TkV$||w=K}Qv5^i|W(w4du^1SAh>6GK zX7{n&CfhV+OP@6Zq%f>pJx~fSQ8bHoW@sHms3IaCbDqXB6Ee?AquXdaLUF2S*Z^Fh zNbaCXj%d4^IT8{Q;NJ{=FI?s%EyQ5)x?uSbl+Zvn`U*8mr8vzd=-D6x_D5$yD)IK^ z0J&d3|4UIFx&#PKd7Kty;K=afa-By~T?nV~$JycG=ucno?(Sk2*Il!6Q9?iIDJX8D zZVwlZ0{#UC!=VG}SN)s?W;{y9V@tF_vqdK4b*=Kgm;333>V*lhu~gQ1hcTgsn_lmkKa!MvPI=<|C5rqCv<>Kov(r;B zVWrl?AAs#ldF(h3Xv{MA9OgYvCiPVU3P{0u=mC{*VHix{WrbjeIUXEg{W|I5>{wU7 z=5eoN7(oOP$E|yM!1)>YoSN^#h{I2&-DW=pUwgUniY4GYI8xgT*>vCIxky|Af5?I` zpxWhzEYg#E?c6+SQ6aTi7B>epBl0PB)oot@XRkq<(^AjaeCKu0{nFjtKPboo3hjX- zisN#1pHEhuhn|~kFtBE8K{e3Yzhf`vX(UGA&vTVGbw-h!R!vRm?eb7*1UD4}7>bOH zyt6f!D>v+3Zkws{4d(*z<<(^k#dqKM`I(xSm|Yr-NI-Ad_KXGhhBg^F6FRhvD}uE& z_JPW@o`^R-ta6MI+Z3$`JMDgJTkOYGprPVb&`kxA-1k&J0kdvRQCWO<=eVM{_7xY1 zZLQQo`LcYkm59ck>DGC3cyGrB%cGufdhtK6H(st8%oGnwN=o|rRjJZ+Sf7N0)jWi6 zi?IX^EVC>Ln6daL!_Je3<9o6AP^bhkqa^8oa2&BR8q7`-DqikUl!}Fu^^bA9000L7 z-Dc0@gsZfN=2CHg4U*k6!pqxx>54Vs$w*(&i{P8AO{?@N`)YqpgI-}uye!f8&&iRW zpC}^3wSQ~BM=VT%waMzrg_DI2H%VVul}pC}cWCWijl-+~AHQec`>L?2{Q{-!TWN9H z^#MQvnM|n8!!Ms}#931@5yU1ay zYk%IQQJNkSQe=R8zt*lB(Fai}lQDCk5yJmq@G+K?srFiB4yYjd`tCz%>t+-0x`u{^ zdgp(_YFI-UVqxPirBDf80x}ll2)cy-c~6g4N84-8q2U1DO$H+en=D|JbPa@uMrb&u zZ7ra=f>dXOr+_I0PO7FoU#uC;{lgy$ij;D`Tv-By5QVUP=I;t$x0q<4hJp~7S@Ekp z)HN;oBFul%Na-|RtPRcGX_lQGgwi+Y;PRS;GgZ>i8rlkv3wcLDOSqg#pufLXS_TZU zApjZ!^sx54YPs{WLNV+2Ztpe_xk@0VTzv}kxo(Qi_LlQlA)Oo3NS|1=PUPY^_ncc_&^$q~?0DRQy^j`)@|1C82 z|G|q16JWCYxXZx&E?>tXC5#Y1M_`yhgly2_H9k41yI#GL>V!|!Uj7UA<)O`hWD|(= z&l}x$O^Qde+TJ-wLu1Lti{Qy@x*k{1^5d zBBM5YJPz1D32EsClvv2i9z`SUpkE;n>`QPJ`aM{FzJ;r6OW%_}kEseQvt}4;Q{%0r11U-#@f-Va4_(cEbdg zDAWjhjO?YVXGTo!*zKiqXIzw=H=#g``*j}!3Ln$Gx`zi&yBFFe_!zMWZ0{Nh@U<9 z!|xGeoDWo){9_R436&~=e-HHCC$Y93_P>Q8=YEd}IWFkqBgRj^rZiz^J_VH?3v~C* zul__t@3A|!$iroG{+!V=_uho#>V*Ll>@t?0zCK$*kq&{}c z0?CJdp|c`qC>KZ=UlS}q-xj-id%gF2d5=L-w%nw{(C0K4q>n&s2yA8X#6Ba+jQ0DB*;RygWK4=H+}C+w(?{8^L(M^;W78WYz%7!l?Eh8yovk z4E4Y@#0UJymoAV3u5z)}&>)Bmh{!RWPFpkv)DGZn0jx3ry~()=fERSc1XYchnZ z#&JQauoI9IzFSlEk83hA0Gvc(C;t|}{bJ?or^(4iAPg{-c7r+h+G(4!gIAx+fVKci z069vg=3Yw|dPg;oDt#NMQJ{hxAtMEleAdi;xj(rv`A9&7nDLAqly^`$iZWj3WOHox zIFmu99VD;6k`WTtdYw9%iOEbq;IRc{8Hl9_2QbG|gnbPT(m{$>UOv3o6!1`UIaO6v z08nR>GJY;6dJX^!uDlU&$mYIJmTq#VS=KxNJVb>30_IU5L~tsJBXz}|Uu3=D6OT*+ju zy*fk2{+;?O*7hDqVtAn|~7yLXsOO6ya{Sr?5>|I7HQRhfG(J9C}@Vjks2_Aze z&BQogG5vBSI|^i#zjqikd)Q4ks0%^DA|k5!)I>yHt&Wm{Or_c{Gg;XUh;q+^m21vQ zQBkpAH-dNOy=s0RNL+qUFQheB1}0fnQ8Cdh@WltfY1k{aSifFeooV(2>vie9a< z>i#t)0|SFNVg{^V)|FNo$TE8U(b?))IaOR4P&crk0CE`{9j*P18QP~G^4h=HoEQfA zkr-l?T9@?^Q69kZ_<&p^m|i0`z=%wNiVP0sNLg9gHzg9js-Q1nx67@D@{()-TbD)p z(m+RN0;mra6;i98Yd&xo@Rq?+Fr4h) zPMHMzp8rid0iSasx9CsI+7&qf{ns^vObXy%B@mbNj=W7x#h}o> zAmt@1-ns1==tTSFEwR%INd8f}b*7V2P*A8eV#<}o5v-aT6%)=I9o!dapHqTH<}f!V z-E;|N6jJlYJq{eZYk`}c)_w<3vyQHj#xJ$Uf*bU9tOxA`0Y$P)W2L`-Zf07B>I z=Rm(fLOn;86+cfP13ena+t;o@LMdR4B<2q~G7N61ZMnUVv;Zn{Ev=CFN(0YQnlxkVy+j zHkMea0qo>k*svI6LSW(OFW{uaa52~~Hw&DED5!KG<@;9TA3E$7E{RWcSN@!nR9d}Q z2Op)PsM~3GUXnxzls*70&MXJD0$|aAB9YF`m6a9XWJKjmP(d$n{MzK_?;L^}gvTHm z1(dEx!}C+C%)lel6Z}n5epld8bS$O%9mt3ttmAcA$`cwr&3toA%+HRf;vODQc; z6F?CsaBDvj0JhG|YF{B8>89*clnZO^GO zs{yO(7%&=pOK=k!K=H`Q%eOxQY#!*gT62~daVDaNTzY}kJwMsKZV6N)rKis>cE_^VRFFJz%8^hWr-CfL*}1NMDEk0xRMXG3LI4#f zTYX#AVIh>I81Ki)&b77`FsyP4}rkNAV~_bbW>!1L-`h|F(pvZ5`7a7A0Kwe zm4*tVFTMi=2+i^6zW#&1TH!2>UJazw(Nl)@yrO=DQn|;pHf$!^6X45& z*3-p|l?Gv=r!usZ()ADc5Bs zQGmw8|KQxfGll-(6aIs*mA^2O0WEm-N0+!>`3l|to!$G-W8ME&VEljiVm&P=W3OBa zlDSk0)-i_ZLJTK_NV7!GYOHJy6lyg$H&+{k&0NETyN;M~FjIF>1PSWIcD6yqz`y*0 z)YaV$xX07g{PZ;6%Tr*PzZIxTuj8-2+q+NXkDV_HdvfF7fKss(6mty?37tTH#Ly6g zpI>(h>O?CJ;Eh-?1T4Hz8Ti|Xkp1{A>t@yq6@^=V*z@xAm7Em0<}w}ar|)VkoB2{z z$gaOO1791z3wpW?UzAVV!v;;#iNhE=neY9Er-4}DiTlc$P{s&(JyKA*I(An+cAgfQsx ztK4@ycJC4rXnpS`VUqIc)jfYL1gdtcGZA>7!<=!&f_*X&cyHR_ot?{|B2dK%$_Rl= z-=pw3oCop>BoQ(-$weemy`a4u*u? zJq`lb1CR)VTsHykdxAo30U+5)qSf_$koO=sK=_plDlQV)43CbEMm$*ju~oL{V}F$a z-(d~FzIpYL(myVtqGw}ty^^HvfmqrHasVvEWC53XfDCGpl|hpJKmFsC4ZO%{;mP{^ zXOzQT4m+;{_=3fQ-qYO!er{jQjy2^Pz8sQ9or3wH)X7nZotG(M#DcNj_ej~-k=J-O zU^K`flw>z3*LRghhsVp&qbDV2Dx4wr9Xt(FV-zXP`?QTeAS$P^Urj9iClld;)%-=% zFhh>^R!X`-vkr}}_Xcd@-gRv>GLaIrqoehUuL}=z-IE&ALh126>1oU`!u~ZYo{9YQ zT;IBluS?m!1a8^Tt!I4hII3o(;dm@_(Ua5DOhvl5)-J3aVdd3iwRD_kp0=esWg7GL zBe}W@dA=^oTWzt1QPq3_x~rh@#`-!7Ackio52GPF5&Bvhz0(<@%3D6|Ib1x@w7U(t zx=7zD^^m*l>O%Bg?Aj+2RO_}J+-f*PpJnH3x=79})@jw#eSp!~^36_L;Y-{^YiVF( zuc2;@JG8$AC%Kx&zQ=e;bZ6UCE~9iv>=$B;e(v*%*e|#({3kw7k4D}y_?rsPl{f=fu@@0 zx!wXbU>KRTU+;3!?wtU>rO7o@051tm#!1;7ZrJJDTxZZlm*76mR?}TCk0W;KtS2XJ^0xN~KvnED z^dYJ(4}Zgtg-Oy};n|x!&Bu*hd7f#f-%t2K-2Lrr2{(8X;6qS{3#q<;Z4^-1D-iaJ zQ$D$)bg=G)WZqN3iN-4{(hBTua_5}0R4lMdKXR|bK=`sI$^0m16xuwE zvH6^6!mX4PlsqE7DZB!u)$|{`IL~Z5t*H6VYB32nvHNqzN@;vaCJ%*4Cx<1^ey~Ai zVP_aTj=KDhG0!K3F-?cIg{|c>46}FJycAO!#%W&Qt5ij+f=XF!7g6~r48s(%i%+2w>SI5PKBDS8#z7FHWOxL>*N&=$Id29wQ$txVT z^|-aFw$Fc_`zPJ*CLeTTr7j(t_~h){q+8pTk9{Hk99_evpjKXC|0Mj76G!b#j zilCOxeyou~AVW?Zv3IhDK*djsNy{qxo){Ju#=?K6b;KVCvyMP2L3{r7HbqicP_~5U zlyKCAT?Y;_IO@ssoQgVQH9_AZr<5BLwj)_7#VxFt5PFUt7(DCj`i;NQN9e4?{lImu zO}w*|BBIR>^rlh~YIHW^j3nhSz1uIEDVXeAvtXE4sdth2vC(-d;2X$iBrWv}te_lP zXIyLq2&BJSDkMBgt>hZ6fZUb`=0FcEF>(AL#7BldCn15YS*h4sGBe16QE<9$eGp8a z#re4K{_NE%aSP5!^saPb*)Wo!0}lRxat>RbM8AUkm|NyqA%-w)RJY3ZlG7Q{*l4)E z(QI>wT}yYgw}r>+Vw<>nzj1!6{rG+irU8PFh@n?~qT_o_@u8N_&BX`~-Ke~)=UX5B z&#*$@{bbQU@%g&4a|Em*W?I?i;P82s|A0w?u|t)1Ej8Yz?*qc9gm|={I)AUF=PzM` zUI$}UONA~Dl;kl7Z!b$XIEGx)1(Jt;E=^!7s`PXqu1Fo=F3?H zS*eEUSZC=hlxH|B^};j7L-upCrhd8GXSrmpM;hOb&flD2`;CTi*OU<5t$f#~{^56* zdzjCJ1B7mpV{L3Ajnd{DJm5HmHy)E2o6YjL@UlGoek$g|0smHBS~8Xtc)95%zyU3O zr(W!u@TaA(t3fP&BJlk&dxf)o__~8BicG+D_<)L14%BEwhsDv5cC)!F4K%-5a)`xe z&SPHhZglC-_Q>t&uS>2L*KtE7hh2zFS}#`!;{&|*+my6#r`BGY8l{ua#F z9Gsj_p8UHlZ2!R?FdoQ%wg>F`ia+;&asLnO0ozEuqlG7Z)u|})@m9MmwxpUGw&*=d zQM`C95y_4ctvB3^*c%jDvof})ObL%#5`wjG(Rd`Xq?D-%xEPfmY2hG)_h*ZQ-nsNG z>uyPGoHS+VWa&KKKRKD|?d?NsvhLT2F$%Bx>D=KlZlMm3r8YQRCZ=c%Ed zbSQ;{qZ-XvtzO!fZRjS8!N`!7ytahn-u5m;6ub(fbc zZGSvxWPvHh?Y5>v^L*>l-lV%BMud(Mvy$9S-Tm)k+M%g}Wj|pAh#g8Wu^(BNv~GBz{-d68>TYhHH_tIfPEI-*(dUeg|J0N|I>#n=Fz}&9%FMX(8ks3t!7q zO;^5$W@u&Pfro^BAR=t!VV`iAW*g|to6vqJ*-3p&)Z!UZyYN|i`tX6}Z2gtf8#hbw ziw5OPGRl`&@VMVy1Ikt3?{CHe|JN=u@{&7rPUx?vSCy zeZ$Z72BA{X*ViV)59u{9uABUzY5VEyvu=3-k4B)5i?wDMef8}>E)GT3d#_UdAKHtA z?Duk`Ft93tJ-90fDRm;X`FzFYXJa2JMp8~P)+c=yv+}x_>I=r^Vk=FL@4mSl1j&sT&PMB+D?q(ncc=8J&!X74(+N|} z?8#eb#QOFur`OLc)#Yq5exC_O-fiy{*h%p$dQNEFg!n_0fGNGQHRj=D!$*0RCojqx zo1dZ46Lj6`_;3?=8!_%sjMg2auZu|aSQjs(f8f8KbQNESSZ-d;GpY|El+Ji)u9QlzEV&RmkOT&Qte!XhZ88}(o+`ZP|c!RJhJB6&kFX#4G}wxe*1 zwHQ0B=A=WHv6kL87zTuMKMx@s?PSwp@6AF_AOpN_#uw0)(xF-I^$MZAo#kdBI~thJ z`SR_`nrAW*{RU=av)o6%_|ohJz;?Ekl|9|sGND2)z3}6w67yRS1BgT@ zk1r_vZ5&l&(kyB=%U6N!J=va#%_5WZtXu_pg_YG59&rHA8N2B8N!0D@eD*NzX}MbD z=-|$YjG`ay;p*mEv1XQokZQ(Qo3Y~%Vd^>4787*8cKlS+USNH)@|mb8u=Y8?6eyX3 zsA45)k*v*)ZP!)rabcqY(kB10p~4QP-Frh`#&1-c&lDQdl3R5LeFGaYB;T4Yle|oc zbA))IBo3}r`%P{s`|)`wmft5NC=Xp?47yrSKo=%y*gt${*wq_%)d4TsYICh-{}v|1 z6Hq9)s1~b;MBp>`F}&bV57*~tFS{LXP)B&J1J^xya(FwW)8eJXc^j__7k8+T*K@Z@ zRIRxwCBq;gKJvpc)60+)H{=|S$v&w&HIeMLBOUg4?5Fhg~^kPF-s`T+mzJGD1u6lc|tO8rN>y$2ThrT?W zKM22TRH%KOFeRO3h7%UX#brGpJRa4fhDnH*Ja~ooe1Fz|O1_n>hgwbh zcFEW?CjF^tW>{@V)R4t#T3=6h>;68WUUHmzIcQC!T;%aDKYtjC9EwwCk~@D{wjWYL zc4t;tyXV{}CiU1)*%o@PNtl(s_#?z~>_M$WoM8rHcBA8S(>F35Ir}ESeEzwLI{bNrh zoASq=YV_ugRVd)j*KU3GJ)U*ivU_m#-DMyM%c|7*vTl*#rJ(OeRhUQ7sqtE_Y!7t#y@^75Qp$Z_i#Oxaa9nVBulnXtN;ay3m^!_cs?s# zO+A~WTbg?1CU@rPGZTTjI#)B9C9bN%0A|4njiSS;7wGuIYaRar`fXie0IL zwLxo(-}lrMJG+eFW8gVduL&4B&PLI-HH2sZbw_JmA*${_Et-;zq9Yu@CGSPj0)1%lZn> zS18#u<#k803JNG{v2i-lsRtWzfYtZLNiiw#1TOi}^0X%^4mIJux1@$$=&o^k-l@F^ z#)N*xEks}_Jm2Sf^?15MT(|5dYAqh(9G`TxcdpiMw-#j=49u3Z@Hf7h{}er}S?(1n zG}=V|A_D+Bv*SQpALQ83u7E3QiUYszm*k~MNV2wLj)!~I)IUlX)!$uevN}K0a-2g& zHC7Tpx`&7M>H!sV2XqJ+flOk2IJXd|(Q-A-I$Pb76YA=K=OQfo+ygd@sF>jEum!46&U(VPT`QoNjFP_Q)>nq(&4l;u zbgR7>FS^52?(3y=&Df9&m9L(KEh_N&DvagbvKo9$E?Yva!bHGGv& z^`=n%{ypsu&T+F&X<$5B`uFbsIKGLN{wdm)PHwIsH+QMp2E0}~v{XM#+)qWaVc4@L?(;L>km+Uwcd|#zcdc}N>TrDKL}hgn1@(XcFbePw~Z2L&dK!8)kCtiu1!bT$i2UyRbeytxP1p zaD_tW7Y>S2Zb4B6o$Ok7DQ+^QaNF2)ks8XBGD(8g2y=TZeksU-{5f^H>A0^~Z`^&- zSg%tL+?NgCu1DSo>Q=xpEe@b2O>KSv9QRPJ)#QEV8ft^n@qy{O4{9B(SFc(*)hjAA z0xreWGqggFy7*pS`U#Ow2h5O#$z;?r{WwhHolaw3sy;wC;6SQ<}BzV%BW|o}Dwgusn0&?(=Tmf~knwmyjtto~usDc8->^H=*$)&%5)% zoS=S@HfTtYcx|iUD#YNLq1x!39JFp}1G)m{rn}(Bj~`$|mCN(z8MUjctLffH<7}w#6}J4mYb(O%%M~>*H^g)qj-g1)J!{W zp^Pikyni2z{vkV?Dt;f7`oz7@%%q4n@W$8Osu#_nCCe;cDRy=k%AVVmBp33so_+&E z(suR19k&wc;lm2~CP0S|ASx2TvnZj(NAHg}6r2i9rXB$R8*@KuLu)5|xIBmO=y_U zJ^&9DDPKx@NPRTL+>Mc|;gK)!+S7E*VkF5Hbwq}3U4T0NF2I`f4thl<9kkMPL7oBm z9eGxk)_5UdeCVs}W}R;vB67j@MA^YyYFu@+vmP&k%!&z(Rhrou7ye7F^OLe&fqf9= zkkQwWIQvoS?^_*O-QefAtBTopYkG3S%X^ee&nlMG1YA=QmJZ2ecR3s`o*xK-#}Do}jCt$oKs@Ax%r zd}(M(+UC4=jLrjgXtO`FnK0F76XHioKmZZJ^xG9#Z8pGe)@+6k9K?Q%jl4y{!)eXb zp-T+K7d44Y`>6QgS^2nPN#d_al4G_-qsD-(hhHBaa2^yGG{<{Fq+4398=@?za!t}~ ztj5=N_8{y5>;s?D!ua^aEOkqruc&)!(qA^mozX1dR3DEuYemER+*4j8T3L)n_cF;G zDKj1Uv%9G>^(F6VUrS`CAP0J;-!X_+!%JQ^Yh*#|odWrMr)6uuTGAs`C#T!%GV@I= zufi3-a~=dCEY-`UJhfLT3M4?J355k2t%WL&+R4~19A+xY+{pqhX`JTm(JFeex7OWm z6MOZ&^!l=MDGLJwC%TL##%}iOT-HSv%ef&>Iaj%JZPh_dh`|#DyS{fx%cd*BVcr5) zqwXB+A3WlY3v1Besrr!`k)DEM{XN@liFa^jxa9fL*qkQ@`(p$Tte?p7LwfQ|>bF{d zxGjwP*(C}jw=`TAx~5JaC5;u!-P{g%A3WWW@0_@oxUPdTYGw3{jnjuO8jQ*i8+b@5^()8T$ zLyjm)TV#81d+@;B^mHAe2v0>F#mQo}+Gg9>;AXHApXceZ;k4~%tD;YXMQqAFOiC6? zP_h2b?L$gHh&%Ot*0r()akUf@v*z+vNn)k4mp#+iy(UbocO$uM1RL)Ey~SNFlc%}n zxO{wgEIPTr>a9}O+u36!Azt=!wI3;U{9!YMWpXtmwzOGLtZg)%JMMb>uh*0>ejuy; ztzxG*+tdo>GZ|ffWM7(8qv=X<+2}=_@s;J6_e%>aHmp!_uV_3J2}w_|AUEcpCTFOh zbpP#~l3bZ+5=+Hvj*egS7~i$6P@{OU{>5~y1yj)^y>T&adJAhbbWLA2OmD22=vpNtA=p)^HgfQ| zWLp#SZ-hCU62wgb8^4+CmrP}!x`{+Pzg_q5mTswCV zzi7l2-$hmY%;nX5OOKD;0^}uquQ62xc5=+c#khW?-i6-Y^Y)83U%?qZf?>Y#Svd*+-~A+_HVv2dpn`B$mW2zs}Wh6*$DGZj@H0)%mc- zQJT5h(+18SP1b9sB~-?YsUU->^GL-OB?)F{J{WQxE`J}VS%vVt(ncRXJe%98AUpeW~xN1Y!dBoLZZWkMdFzw zZ~yddPkk#3*FQAFbE=JoSZ$lx3XkbLQ$oOJq^>{KF4rmRS#~+je7DfcyQn?2#{PM~ zWA1K?xLv_AVS>JiUjJg+SFYjKLVylG@roRw9eYq$ZG_%e^eYc?fVzqP94VQ{5b+6G^aP-T5a zhY!{X%3XDnsjh-J#rO2w>MH0HWfGI8ZHawMoM*0VT1&3C-XvhJKY?`MM)gps+2%y5 z(>-VEWO&8$DcVZ>EQs$8UrYcLdDU|5RuO(eWmoeVB?hJJj=@>`*#&-4oektUC;hV5 ztc(MAD59@^`fntc`kgMx(d@O4KY`$=1$I@_=A~b(m$i~Lk>iLq?uUwb7X;LRhXZz} zduh^CWgV?*GJ9M)8CqC9#l@!aNt-q!UgRaU8L{)cXjTmRFfR5^l5ljg=_vwl&J zmJP`uq+YfJ13b#FSF6MKJu@k~efL+P3F0EYwjSkRFSlzEE0v zxa#nXyuwPL7v`l(=+1oU13L6(CmF#D#(1%+nG@AiujC4P5My zdRuwKrdnxayj3w5srQhD+~5ZMO;JW4gNIkXUK##dv5G*8tDpjF(^2I@r{dm;V~@3Zc(SJGHc7?gL?~%AZ`1 z9V*6}dwf_Mw*{KPW&G)lzV_db_uV)kMdSZ0;W70Q7IuzwI@ARa0s<`)>+DvCQxrG^ zpUJwPLGzm(c~-v3ZbbFLan?1d0`-9%+JS}Dxk9?{@ZygXByM?FveRLEDq+N@5VDss z>cu856&s~7E6WU;FV2@sg;@PS^w07plap^rgrbZNzU$tz$5<2V>#t?!9MsFp>!0P^ zHwguCJ?qW+su^sEd|l@lM%qg-m^5yCYR|B`Eql=aO@m?i!!#6+l#BPt$L8P)AUY>- zpp3A5l6CLjeyyNoJ$wLkjkQO=%=Ab*B=*7P7Uan?z|L)X)EQYQtX%8~Vq56X5ey)M z=Je;xn>}|7F&eUv|IaTAZ#}NcY6p+zUl}*B$@$Np@}Y?3d4gT(Ah?E1GdB)hO#?WY zy-?jcj8a&*84!3b4vae-_kbY@n2ba{_5t!#V$5bi4iG*{OSh%Td`1Bu)6X3pc^Mi029q;0fR@=xAK>fWe0pca1xT1}ZCRLfv%tjsn65^ah|}zzB&VmR zCmXjk*=d(Y7WU>e~4p#sGfFe;q`m?oe(B0fAQfjtv{E`^AuFSI2!%${Z< z2w6*r2cFx)8T8RdppAgAF$Fa>vb~*#i)(a#-hhMj)3O-Hl`$D^!FB)>iYz)@1GJKE zV6};@tvvzepu?l19FaG#b0V>>pvb}(*!-T&A6r2)tRX& z4^L0UWS%faTnWY}$1<)m>x7-YCv$GV;R#TJCwqGZXE&$7HH^V?iiwQ;vAIb?NC+&Z z!st_$6|YT=MG9DCQc<-r1Q>;cgnl6b3`M|YUAG9Lcj-ItDX4at6LV!7-8_o64) z75X4H3Ywe1%cG#6pfQJ~oCtaw$hY1HM~*|0(T3-TYvRF^BO_{KHn-w1+HbzC_)OVJ zLf06dk%7Ovx3^ul#=31%I|Dp4@B-JR6dr&NWcmt_Gyp`}0D!Xc=;#m-9wDLA6pn&y z-7v(=HloE4-vEjWP@)(ahy-V{Wgcnp-oeB>lT&edY+S&cg^2XJO3Wj_5RnedEIpw8CTc4;Cq@`0Xtk<<@wvsX0R^MK6- z3{=(0E_yOQdh_Ge-G)BNsXhn3MnE~eI6X*U(*CqwgJST*n?Qz1)b#c1k4Z^7Tk!*` z5BWGj%t)*1S2P4Hi=50hH-Y=fehB*e=E!1U7qNEo4uT(t{GSXFlsGjvtub2y*oNYqlcX0HgvVGPs_e(iR5qCO_a`o=Yh{^HUS#U z9o(nSA1;e;D`IG1Ko~)Q*$XY87(8drZU&uwD_{wtqNI!!h)LIB=`uJ1W-jSAb>+!m zhU|BYnhdW@PcTrm@gPOI(3x8z4qoU0oeF@wA|otBd8XU$A#)f4{4P16~MH z^kO$~_Ph9G7&tp3B<{?E_H-i5&{w&5`io%|u+Flxu}wC4RPGZ8ihhw@XxwQzI5{zF z@ve`Eh}g`VjLBGU!+njs8S=@70GrlzZ8!+BvA$l|WcEWyQPyuGDP7$eFi9kxvQa^F1C^O{{QRzOJhtH75fc;37LrCBX;Fd?XmnhL zkDlF{%*lYaMGApS{ zD2Vayz7=4l{UQfb2xVjm%(6n=J`>8$ebS45tDS+ssWwg)N0`%}srdEW+#IW3-E)-{Fd4?G;1SrAVlHW| z7dpGR03+RO_U(e3QEaZ-Dj_Gw6!cQ?Z~5!T47$S1h zl;!)t)u8^u{Rs$pa}}l`STp{dF`4qM@Yp-|gHbIjV3Hpj6)3pRdQsr?S86f_rAdXl zrQZ^}l!uK9R_I<<-3k`RAdKEX?&DPJaHICifKmWy_9uzqG7;5hv4I#*oeiA|wG_f|}CtDhu=4<5DToh(b`hnwJ zZh_-L_)f770yh5|_Wm=EwXj#Vj%HXf>VoBoteTCcP=pW0w5QOm6>UnUfq=)Y*ohmY z1hOSMo_R52M}#Sj6qiu2FcA-zeGPXJC+3Y!I|ibL1=ZrHp?9&dOkEIt{gPTcpS7U0 z`SoI^4_O)dGxIIW;iRRxxkzcF*}5zpo$A2A;J6$dJ`(t6AOrw+OaQLtCaMgRh z5A1ZBsgbriYm3`vT}$%bDIz^5&YFr>sp%mJ+|AC+YyT|^TATp;C!jT;XE?LJj6LL1 zRb~o7MY8Bk`Ye9ykNyz$gzy?lfwY}oTHL-GPq?w z9<4K8T_t>PIT{ zQZ4?Y5wubn3jQyVV11+ZJ41K2*ZTpp!M+01NjX}7FP`}EC@=fzdj;+4?gHbE+)odY z)0150+f4*yK~*yX!7!Nf0`o)(rdeq&5%=a^YiQ zIi4-f4clNRi-K(x>pH(4`N;7$Rf+3Qw%oaA#q$uae%y4?7pM>Dl&!zF*pPrl>bcpE z&#v#@;Q$F}btT9SivPU0_)=ajVQhR!B`sBJUC?0?2xBCr(+tAASb7W8u2_&pN8fa0 zCF%Y?GM&%PZlus?GHtI{I+_r!W@ze0^nmLNQfPPP#o;kfZ-G6QoMiL2z4S-D(>$R1 z-+tLmXUP8%v^YAt$)f*8DwGZP9?3UvEbvg3i?RN>t=~fbAx5lFJ%Nc2e2e(#@N2T4 z9jFk8bOk3;HCHfz;Ce&njqv!mXx;jcag`S*E~QLJ_txp0SYk*k4JPX%ONA2jyOr96QiS%hTM>I zT(MtL=<^{3B$@Ozj^VwoasL#8QFb*qh$8?#M?b6n78OOe`6{m;`j~{78PP| zRr`H?cgwgP8k?rEOA7>FeE*DpxAP}uQ%>dfXym(pb`Y_%(-RX{r=;k_^Z;qBgoF?Y zUpeVA*ig7RTaQ)b7+70RU!IrIA6Hk~^b<&a$;By9H4~T3tVP2B7DOXX-=>_nxB%+~ z4#5|Lf4-z`mi8X-CL<#mn;->v>X}3hy%)a3jO5MP zSl_Fz*1~x_7*CQCr(u8YT9}Y9m&l0=2msU>g>$R zQw-Y~D~fCNgHVHd3(B*bTQ;=1b))DebOh>J>W`6{tg*yS*c2d0e0v@*A)+wx=2pA9 z>~w4I*Ex56ZOf!?#=)$UQVk7Dm4xe8<^nhE{n*KxEi=$HLI`O`tjN;en-6e^i+9X6 zo^%g8&h#a7c6P)nn&sfc#H_-fu|Rs5g(%t%zJoiKCipW?2&vd18QfjpiJE%)OA=u= zQL&I|aNfKGF)^5V9~M|k@E!0_QQ39JK9Z3UDbYcfkn&Yjp{Kt8)cbQ+!BLY3QXJHT zXznPpd!#Uyd68*N+OH|l@=Et=BW?221)nb2Y z!rq?UFUi$@4EYW%W#z|DugGaveL@I4?S|KRtM~O9!g=|<`E1V)V?cru z|6pyV_Ef7>h>BkIWg!%CesZmN=6%?iJjF&&Kl1I_k2W+`wGpXeAly;BCBUr;qs2Vy z6hrtwqKl{H)J2xw|6!58?Pq5Em5HbVrZ4osJRh6-DWug z-|vSW6)m`Ed0D4c!0AUn|F%lnQm<~XZKC#$&(a!^@9}1q*NK^xRheq>WK~s)>lTmS ziN4?2mWKMF(dHyo1ey746Mx`7AK&Iv?n0_mhN&s^iXd7V&r2`b=ZFkXROG(I7Cz(2 zRN~T7ZG3#d$<6>f$1py=VN0X?$#&0x=njXuqPyj~w``_}^LTN2v)3Fk*P!YSHge2! zQ1R~-%}YrNC$mv-QBftxTUZzS{Tj?a-g=Ty2=!EG9S{;yTv`Hb5y z$K@P+MoQ^WHc>~DD(i(*0q*k?MX=sDx(#3cFwGdhF-0WC#M0nnkYyH8WF^%HhG8%Y8{&1j0hMW)>6IFEToMc@ZXS zbmtS)bX<4jS}YT)tRDdLQ02sL^t;|MFj&~zOT)l8lB6ENlaLmriZC<9XQLwRs=ho6 zQq~i+)uW};v^W|+Y*oJLvOt#iAMOg_T8@H5_~k;dAYgO$1l}=#WVg6SjWwT_5-=aG z4Ah?N3mnYYadtJXt<|Rrpl?qu2)NsO9p5529yY|!DutJv$rjNUa*%=nPbCBTXXW)U z#P0Q2O|3<}acWV)-POe>CK6jbMHLUdpNy`$)UFIyKXc4$4om66`eYp493Rxto@X&W z{(z7GXKli$qk$sqNxV(ASwVGYbgEj0RgKOubyC`uEm$8h zYDu;DYzX?C6$IY#17MV{-ri*PuVx2kghQ=luT+o;%DPBO_;Mf?mHy3w5{mfaytu6V z-Tw1XyCtvEaewEcxBj=3Hon!U%hz|yXwS5AOv&ked3fAUXXiuA1tUrS!{71ShuNUI zGslcUlilw7N(h`xU@Tt#Mq8j(iG%axC5t8<=o&YfXp;;mxden!({k6-|o?B$?=X42Zq!JrO==s{OvbVUYvq(wllC5PTujDb( zbpvKHSnW)fDBK8V|%i+z?vU~MCPzBYo6!*@@7K_o(NR2X`rKQ!em|?=xbUF9Km8ES5$`9DcXpg#X5WZto zwpIXE0x=21KkGZb){MwS6=SMPsu^icLSM9#_Svn|VLfo9=)pDgj{ZNy+d;4*dezioDAPDy!0JlHDWD-Q z+4jek-m|yey$vqu?J8K(X-(;4+zzv6$Gxa=-^1B4HBW2q6l#%!-3p6m9C%wN$X`Vh zj8DUC{M6kj)^#DTtAlcJ`9?>XT?{kKYqc6T^;udN@bWn;L-K}Sr@R`kxm%#}V$2Rk z$X=_CPZvK#JE8T<$m$*v>%sbS#%B30w4|u0ArO`Te$|5Edu4V)lQ4B-D@NEY%kGP!l4Q`j;6sM=``s0hoAQyG)R zlB>25AHMubaofRH?=wW`87}s+ zGG|LyS9anL(-#atJ4>O8h~WV4fLA0u7AC7e+eznhSo}5C(eb1Xs1FoYasZO`JRW85+ET108|<Ve{A3s00?d->{l#d_X0YVOhLPG&u z7`_brcyC`OLXyuIX1=VQs{}IFlo5H0tRp%u9`WyBb=uUVhTXR&HJU8G^|L<6&>45y zEoNU=_p$2iRF#9UCo}JLcUS_*SCOy}rc}s`0r5Lk`ZC@g?)TB5QM$9;wz)orS3yqV zKBT3eAawC1L5{NbXX13j1?XKzXb9a-{N8cX<_;ve2rx2U_mlP;^=SlF;L9}>g0Kdl z9=|TzS1Go>0$~oNB(62kVCDM(=UZ)82MTrHoMfMJewYXP*7!Jpto!HYngQZq!B9`n z2B3ccN>=8l&TlcaO8x!)+W^oExOD*mZ2*8L(;OQ>`~U)}de!y@;Cfb8R}Jgz7eK}W za5zAeQZAk;^E0UPH36cK2g$r?#h&;mNHN57dv$wM#H53KCle>_APr*#KF8vgG z3tgZ#;PEkYMJ2Y$giapLvKc{_Zi!Df#A=u}=Nq#5DPOt1{cgFxzm;6Pp1l*N-=#pX z#1s7G7t3l-hs(pmb4yD>)wR1`Ck-++F~)=%sW5RdF#=|tZ-rcc(@TdiKqISItFNyI z(ZTFVK$JIVhIbT3-3Rrp0H~0bq5h*h0}eK}*Y8~;5LhkP1&9>@s|3frFU&&isy4CB z{Tvz^3M$z}nu1~(ZR2me5Pzm6u)g}Dh8SG{BTm8wv-v`|N^zJ1Fe_T^m9JD;!&w6Z z=Vs@aV`9G7*pk|>MF$6p%c(f*I)^<=iu@sy6svC~Ohu(+YgS)WO~%iWbXad07n5$d z_sb*~h=S=uqiGd|K&8V}W?j8!2ft7CGjI}@8}YY46{;1F2EpLc=SLf~UYQ?d%vm9= z9tZF0Q{><-pymNU?SsVYr$vnquv+V>hfklTMMnd?sUr|(g8U1MZcXpdkV*v+C_D&% z|2~6G^HZv_^&0S5ynl`mqSrvM8n);G8XrL00gWwDNwnciwH2@BXg+8cet<6u$I=Ri zZEflR)+L{4D;pEj&?GedVxqzn+;U_jba=JJ=WAlhvmtsl#q8|ffiC(;eXCSP&dOJf zqn2BlnZ_^Ed2Quut8En1uMS6i$kH*}rzEqSDJt}B4^zMXhI#P$^P*8-qwAaj*uQ1{Y<)+{s=p5AKeegqahVuL z&g4YyDE*RD6>H6SyFd&iZph{C*VMU2J84Oem$r;Yb&uji?dAtq4SLlsTo_6x0j$vC z_3OjUsTdECO|oM_4sU>Hb@Ui0{`k@hVmiE&4Oqp>zEjSCFed`X!NED&-#^=`{SJVc z!y_Z~>N!q<);2I$1t@M|XlU5IxwhtUys6!7Y;7%XbOn+D09^QMb$Y6DPNplz*N_hE zh~J=r9f}^3A+kuF2l=T4wBXFlJt`>@0axpLlKH{79UwuyU)I_J69M(ruDj#RAx)re zL&B!cMp6>7Bc~cgMNzdJeLO=d*BaFIc%rvvXs9cJm9{V4uIwT5KAA|01Sn+pVud?V zDF6nrpYpl#GBOlC0Js#3I(~hzD$1x?9H~HSbD+Z1e7w7xF@1D&)Kv^1e3KQX*xcj{ z43=Ns-UR_@P$1Mq6K>Vja)|A(h!6LaL4aPn^ZneyGX4rm1_2x3wp(D|CyNkTX83?Q zq}lgVkxKe0$XR)KUyyj(z#f*{X9kwp?JY|y4eVB$lTp)nM&X%)QRTPBpMGZ8#HX!_ z06WR{_9t2;j!D8ZJgiEyc}k!H3nZOiLjr+L&GmZFUj_)@$A=k8L*7bUPXKI}v~;jc zrnNk!b~z}-DE~4xopgcOS^= zU3#czS|OJq7pB3?I~x51h1d0A{zk3gJ$u|lj&aYg6}Rx|HCb}PLzsj0sG}IC3;#2M z#mBHd_4aNisQw1Lq@iI)xTM6$(3HJhK8nWihS^?6Eh}1w@v>{?BB;t9_0%&glgf&H z83fv$8W0z$dnZ)_r#lA8lz@N$P+>{FAulg4HI-B*1orKzuxFFswFnD~EvN%&HC~*V zB2Sq}Pfy=9IvV>%@dK*HEPDlx@EqFL3ow-Ni1D z7V#G7@0$t@)s2#py@_L|3^bmyIu^c6)B`eIFl+PJOsm`0%Tm%$0~L4$pq?@$K9Azk z&I`vV633{wDseK6Z`5gIvasMkJDU~|Xu@Fc$x%mEe8>juDNn!(Hq?vjJ?)}R2R*2x zyL&wy6=;`eqAKw5nX}?gKxh532kHa>f+-t6D99rMsETNTtrI$CkSC<6o6Go5pCn5K zN8DeIq#$+Oe5{(QEwc0}tCE3l(x&&LU!P0&yk=gc!Tx%XtpA@K%_O_HfPQmaiu+WE z48^7QMVH$p>C8GX#^4vd%5*Wid)Oj8!ve zClHT0T(!SE(lgZJ;tkr!PEnlh_xN~l_wFB!QgeOHfn0UvRnGS9i{7IzSo$oKlqxcO`IX%*@WtPD2tg_MU@2{(|`7 zLk__61PzVjrwN$3q{E1*>)8~wvnKJW)yF6B;;7+Z(7XVv8Y>$cAFvEOd#UayItdgb zU2A?5jxQ0?5j;-L*3~W>&v~N0S=f*|pH|!v4AOk{N?v`mGVqS{%j#gp)BrgI9v<%b zG4s`!7`(6dV*N`HZGHXXQ{m9W1tUlEb5$WKsIRZlTtkwzm0?q-=h-2vnY^pT`6D>` z7jXp4?;eQ<6J=&l=2IsP;9P#d8ew}U;=3_KcU=tNfhI?_v`zJ;^$V#hX=k>t_FT<0 zTb3x@{@pEXqWLy;;?41#{QJXL22ES$?`6c#+;l}wV5gy97sR$p^opz07_9GrwCWfb zgwlmPqGi(gLH)F>EYOv+bAUv~1>mhI#NS!ZH5`GuVX?q{MPL2JN*iByjWB)+72l6) zWwy@eoF|o^RKU3oR0q4%d=Mw}l^Xy3Kx!ig`Ev=Lt*H^{i{`j|XaP2Iu7QaCgz(Fk zhe~NA6Rm!_G=WRjhB^J1<1Icvv!s6lIRK3sa&dJ7BKrPDwpRdcUg zuC4;VD_8+%MqIU%R3<*vrz)awd&Xt(GSq(%!CVII8~5gr8E|Yy(aj{U`q>pPJm?I>~SD9+{l5BC5eEy;+gjJ={Ese z2{3xJdYvfl8x%tx(G<_N8pbAX(4M5Z!C+@AeG_X)5Q8^ta+kY$gfBX0rr;Wz+#fmz zTL3MN(UaBCKqzQwx_aov3*L00)95a8{u!+T&Nn%^X0_J!3-irWW@ZZC7Ab|B$6Buh z;x_h=T2DYa;H`84oD`%Sr3tK9$oA@vXAX2*^R}U@0=E4sQV6}Gq)P0PO1OSKdqwd^ zzFf7*@`VV9KrJnYh&s&A=W2W{7e*dzZJq5MSM0C|Oka9w-X@b)i;;?ET<_F>YrYw& z=vd2bTRPyELz?!9`G^8!Yt)|!4*ug@0jopBmoM$z+(2&s6o`uG&1@#ijZ{?dE_XII z1RWM73b4!nJR-`V?{w7ErW@llhgogi-Ei&Wa5=;y+S1wD2sH$RD*9A{y42^CBRNsd zbbc-v z^!8h+AsOit!I1C&YA+xU6~#es+2nhUrS6gw>m00>(QJTdv_VD<_;^glt zCB2%mgAHE024Tsnzh3WjZM=$uvRU`>TJx^d%wdS2aZ}i=O~C}+2Fw*pqQ~j2Qni}3 zl+;s6AyPq}WgW_b;i#?W^w}drLs1PEy78#!*-(u7@9(ec5wC~3k2WNuqSED9q9jN} z)1Ko|TpG_a?1(uSEpV)OzZz!M`?&dIP<5Z3?x7`k*&k%v9hjl^Jp3Lk_3@w9Jq|Wa zXQ;rm{}z)Bnbv&qdS#LA;aEsAGLTRk8Q(A{P}e7Wv)ef3=~ z6;EFM;R=scjqgC35m=4MDyDUqtRS*LFi{9N=CWVEx=d|MHvNoc9`zO`nZsPw&lJ#K zSMsL?OQ<4lqjxK%Umu;HYP)Pg4L)E(ikZjK@9|c4gIGtg|gw~Cy9?}uga^eHP;`?KNQ3QV|tb6`Zbzy!c?i?}qVbVv{Y+4>~u-Q7rt1A_derIOJ0UOum z<}DK~!&(G;EQ#6+Q&n19lWZ%aA^Gjcp{y;x7#OrQH7%)+LB7O^d8^-!umFnaenQwo zrAq|qY3lEJl$W;(a_tF8pX8u|(zrj#{7AHO z*B<}d)gIX_F=%e9ZW;QFWyvLwcj=mfgjskSIgq4(&~Fpi^=`q0=rXKlPC5ehECop7 zWYf^y9REyGe{ReXpV93e252X;o4L7RODtRcPSxCCD9(V=5n$d2c{a;p=$+uXEGd`6 zm+mPmb{OE6=o8Z$tV-K2qdq{5QmRJnM*ZvE-h6PCh@xN!BWx<@;Or}1}@g}Ig> zk8!g}3d0Bbr+>>=ZLV)@&G4?M7SFOjw)=i&X=&M6`mHo8tE>9Hw`u06qNaw5U3K!Q zoW?)FfP!4GWgO)L;fXS*%vbl`&BjgksJkcn!>l-znH~T;p3fO1+-pZ&_iKO6Y-e_+iO~-G_Z;WYFv~H90;R5fTOvy zgD54ax_SnZ<2Z%3*eHHzNGuXM0{>x;{}SF#f%*vm=FVtfhVRdiHQa&R2Prq;&wjoJ zRJA_cKvfGORlm?twUxjAxe`=mEO|`1|5D5n2QcM#f%X8{8g%G1Z*w~1>UWSW8ZM0} z%0%Esz(qjX-jzdYIN)*eDlQu+$~gc0D+N&ADcMm*qN4)r*j;c@D2myrnwkhqlYr-+ zGe`r#&3^u%Ud1q#N)d@J_B`lsstdTD9V2lxs2e$NS3Jke_rB{!4h3qM7gSI3WL?a` zxgf=Gi;$1g-@dD_50tz20aZIpA{oX~Rmg!{IQip8C=h6ARNIbVnpj1}d z`>Ckk=<2ik;}#P($^&BXJFdr7XejwD;B^naTEC0({0Jzl#O^$zLk$S*NClWArUwFm z$An2Dw0ytrbK->v|FY;#~4e((i# z0f@g??9KewZ=+Y-$UjBJpyVWfVNh?@Zv?0y#(N1QYv4bPTEN@`+gs8?s+@j+zDI{GY7o#A5f?ymbZ?cnJsKXrcGt zdqFObB*6FK`@1QAM&ZWDQbgo3S8jBQQZRhgcs&kqC24w>(HZZ7kr2t$Fy2$>6%R?bI!zpuJfqlHJzrc*3UlG{e3 z|JPKhp)y0|oBzCeHhe}R!n2ab=SKO!Uj6${S%`@DORv;}#T6kMGz%$dX|>vxalkNX zzGXY0%5nKOm-%bZ3!Z8cz}#pvTQ%%a7jpVF&(C%9z-K;-Iz4PoF3y)7u@RD>&1}uf z=JIy~y9wx4r|2+_skK*bUdaT@R`=FM{Nx~7UMBc*4mH>DJ$65RxVbD#a6)q@MnnH2 zv-(k|!G)c}dfcB&URLDvYu#12&9a%MvJ1#3Xo8Un^tN~859(lsP2T4KAm_Deo}9>& zc?gVn^f2R+8q27dbS))W+Jm_;FCxIHn;0AFa*CKJ)1?I}v1gs-h7XmtpGrRj6e#}Y z-)p0n)d5<*f}EWE%QhR^w-WAq@lDobE1V1s-O<(wn0RQ9eI0%+@K-sRHqZz=Gg zceg#6>wFI((mkGY<@A0RmP6qqyY+037I>~kD_{mYz`Ud)kQg_tv_(YA`>&@DTn&Hv z7*G{lcEITAn%rM=#3%}+)b5*)TTUn{R#x(SIt--UX5JT-wp`f9vZ?dcPbFPHtS z1N_Q_l7g`#0DAmND#`s)BIqMuU7pYgv|Y*25~{hh`rpbtoPhs^o&lyYEYtu-*VAi# z@3gby-=zroGoY-aTCBphNDU&c-u1ULORIv_v#)Tih?1W4eTSmDJz-jILa z2(tf$Icye*@1&Sr3G4Zj3Gwl}%mC>G3yG=>W?S@t&o|vLvg(9xI#~vH(!<7QuxweG z$!N@O=6Rm0Xlm1dh>nnL|Io1waoIevB!bCf!yY<&C`o$_KZlaj0GKktV}C7D!xW@t45e-AkC!lP_6@bu84oMMCj#zw!ClK zD2=oJOBfk`_vqQ4Hr@@KBYnH1wv4DZn?%ULZbd84b0#@uR#;Je@gGLkkBzCoc~6$R zqF$#ei>9nKr4>By44kT^j~()&IC1s=&JolhJ5no*&9S~Xbfyvcy4R3XgNjlP?mw5Ti6|(mU`}ZvH8sTQlDTy)bB zT?kZ9!a-M3tTwc_Ng#>1f>S6qiyhx$VB^rO0jCP^?Q(`?a)9nxbwsbTPj63OMI>XA z0qus0cr&_x#_#DRcK9D4GeeIlfYIvT1|Ui52vna&YKA=-PbW0}eeE%&Z1Tx=OoD%# zDt7U)3rYX?bLjv34ExV-102920lXm~_yW4pTgt#pL=N;;Kw*rU0h~_%!<3Hg57t)b zx9By;6i_TNuNsOlZV+W)`a;PNyCI2zr4tH@I_BS13Pzttni9Z#!Q$h8hy7K@{J-+G|L1ALpRa4RI&PT9D1jFx z(ulHWs9@KE0y0egL9kn|GNCB{zka;k0Ixs#pNQ04K^u{tWYJGrKzzqtC*ObyDl3zm7AZNoR5n`pHm*whJpl9ZjTGx(n>A2}Z%I7XFKm7Ry2kNcm$vVpJo=dWDkyf+`BDkAc)Prf;g zlb4*GRC%uU5v)lJ=<^;sp|ou$>B!KL1u z%}dUEb5Gz5aE_V_%=zZJrR*GS{`_%s7v$`$%IcC(7I2fMibgi3bY>Q|M%JuO&Zagt zrj9K3CT8@14^Rf*q3B`*Gj$~A{QEC5wq|w`7RJuxy#HL4le43#kqr)(dkRv2E`F}Y zr6oO&&rLW_P8^T?<(n2Kl17K0lVL)(nhDV%LoeeY8yywYynQ|f8GYSFheueED90GP z0ptU{`NMrg4<}Iq!Y*5R=SiofI>oK7&&hbpSf7dz;|}<>d?X`#dKq%QH*yf-M%b{n z*?M~G+UMYGw}^2>g)G;M_`cS6!>T?mh191j6N`gIfdro{#unC(kbCwGX9q#2PFxDD zU^6fhl$0xl`?F2hXPsETaOnBw*;iBAC#LD5BEB9C>I&a+W9Tld6)WtnosY`Q#9)}5 z4=aeK9k@pB4xYa4kgAb&**+q?s!m(oY>~dZ)zZwz`DvQR61Du;QHk z1&#CB;!V30pHgYAVz_?~#KiXT9d{%gp7nL1+VqX42ODC1$l)JQE&Sz0ydVfD$K1Ft~Q=Y zH9k1|UD+mSLGV$DUdXt7LEuOI&oQIjxsIdDy$(}{hH^RmDspS(Lz^K6=xj8|PZJWK z{{DSw!R4n2=aIipGPvAz@AY}2jG{tWP#c>?MBi-ki|a@qMCRfqX9Buaun~nH>~S#W zPW*>oQLQcEnq8tkf%Z%p%vK+bcOe84Zo)hL1hJZLas1S#1q8?0j+)wZ-}c=@qz!vv z{E(T{6MFu%Lr46QE^McZ^cf`nvq&YQ+r1m8} zmWnhA?>zNAmDncChoK3-wpcM@{7p&Rs@m>7Lt;dRhLk6Hq0fwX=)~1sN>67;r+dVA z;y9UREaHTw^Xy+tiVKjjQfPSJ)gqyY_#*aTp5&dms8~u<|B3u}i~%@f9giPpV_v|B z_in^W*h8s)rUxZs)Q_Z=n(yU3-sUH`8wu4Ggpx)4TL1OYH>DE!;Ep|Ir6+XSIQS>^ zg;1!<1MH&EqlEJDkK4uuF%N@2P7FpNSA*IQ$xXjy;PuMaRQ=dHC!=sE;0VVu43Vro zb;eVAOUt5VTeU1haPZCKYBc(1R8(i9)RW~yj>mdW$*%1ixO7&YNh5+n-}_oty(miR z3@60wA--pgmk^JkYr-|**t$fg{ucj!|8!cnFU0+@vL!2nsewg<+RP$2D31YcQJ}Z@ zusWtKvMVO>6OYFf;Wia-5Ny-^qvOK#P8W0_I1>p+m}ISK8LCGPE`CmB31-w1v4k>1!L+xGk3 zpqtzvr@k>tnm|wB)`Q3g4+TxWkb49LG`0V#3;jHVhkei9LBu+CmtYkC-THmA*5mg! zEx5V0)I;6rroEmSL`)>iE@a*;Ut>L(+L%l~yVrEDO0~6Z3i7o~I6W_%_cs^ix8~}t zB>c>UxP=IL#Qdn+v`YA+Osl1*ss!B~E54oJpQ4mWRYJ=O3m+%5Z_B9O!jBJ_)a6lZ zvMbHG=HrK$IE_>hD&)}yWxovVO!;}%&%2u~xirsmY}K$)?vzk2tce^;)>o9mGy=R` z^oM3{*nUhNcOJZX6@*SKPvp(yz^0>-ET3B&&LiifU@#1R*X*Q!g<*JlXBGI;@iu`w+2|@zSzp)zMHz&Z+`hG#Qs0*y=7EYUHdl*N+S{y z(%s#lG}7G-lG2;*QfbLeNrRL$Y?N-0ZbU#3q*Gc#iFa=9`}vReJ?Hs!#`$nQoH6*q z+H1{u%~;pGYW;rZH?;1~8=|R25msgHDK1XE-Q}ZIb_`c@$o$Qgt6Sn7 zWz=qDu$)jJX~9mM7?erb<^!uB`t(iWb30YOp9FI=x>MnSJnWQR;pue?YS+`7|o0$Q#2UgzpgDXKE^`p@Lsvr>z z#5cXDF1UFaxyR6jD@cXbgCQ^Rq@E`?;{)Zljv!?Ta&J23v-Nlf~ywN&*_MJ2(} z6=j14lw5;SQo2iVrBCMqh6stDOuj!OE==X|deeVSI($f@fd1X>X(5z;s$wh!7YLZX?Nh*LfRyijfL?3BHDwzA8sSRtM$@!dE^6s z&}^CKY(4o-qWhA8VA@EWt*`;P_;6=9+JN0T@`pph-#XLx&Xyh)yf@_qMJNVe5k@2v z^%F*FGHFIIs}T|7)d)*+hdaY0Qk$cnpQ|iKzo}*sYiQr$DEN4o%pXfX!=CC>VhMR) zDo834_C7=^@93bv_p5Z<=bNR#0oD1Z0otn87BU%j!ta)??f+2A=dvnge2Jnvk6jh0 z?b47(rmo6WB6p>Bhas7GZN}5goK-h)(an0$a`U|(b`gm&h^K8;kX`hwwsP^+?4$(k?|SC2QjYFO}>OyQ-{5wL=%i zfWTu90ZS8I0!Ueek=DM0&-O1vQzzvE zury0E5#;o{aWQh=B(l=$eJK{|r9&gA(`_8C(4$J_GJaStB8>T?^!&jQRhDd==gZRQ zS8w+$$|xe{BJ1sbo)Ls4=oXhr9hZ4Me*NGnC4p^7Z-h<1h7E}>MR=RE$`H0z zq5haFmfd3a6vDfkimrJ)F$)3xaSr>d*Oe(>*L^iHqqtkDWf=;KPG?06@Ltq^d-$`_ z;<;gx?4WL=4i?{s@%9M`%4zk4SqbGAUSg};QGaJlh!&4I{)omMH^q}2CmyqC7)4Hp zOo^^mF3^yqh4{F&=uue<5OJr+CwA3clW}o6H=XBty~>JbeKf2r^t}pIl;lyY4Ey}9 z>{AmyM}|+L_$Ibhf}g}qQIS;WXo8Q@mi*UjN6zQBkZFEn)ZgSze^pLOl|I;rywRVy z8+>^yTKwVhHM!=6{D{ZTAIhkecz-|mo9XDZHB$|ao)~G?wio2?@02id=cWh^nZNEj z{#Bk-|GdoCYL)gBHwn)&dD1m)<<4lDnJ+EHw9u%7_buuqI$2z1e@2@0qQTn*VvTe8 zkk=?b@#zecr@BzJiVJQOj*4P5za&m-_ z9QN|P(*tio9woZ^Flt(vABE`W<*A9TC9c*XYk^sj{>lmNztszzs=^LaidO4lC5;Le zUcp!w+A$S=+bDD}oZKXY{}DX>`s}26puaN*R-ZeXY;;bxOMA!GYIRCw#vps+N%r$f zpYkDTjer@oH`n=F^I`h$lx*&n7#-}_ReNGnG?E1V@n#mZ84I7w^RG;bA8zQAI+)G{ z^!VKzqiJ;}n4pxu*vbyhqQ_W6XTp2byr8bEuQ2M)vuwiX%y4Yfgo~A7QIm+sQ)ka0 z__(&5+lWla2wnANElN%%V6kqv{Xx_A>{Rc5*9$T?qmLI{*~~6TM+7}m?1&Wf@4^bo zl?sUi$&BJ765?vA-wq--xhp^tu$*~XKl2UZa1WW^U3J@Z~P7 zno9_ixkh+aD#mdeVGb}xz2+*XihkFr{7@0`?>@}8*)k=j=V`s6myiW7>tiNpHHS51 z;ZcJ;^Vtd?X~00cU8ERe3qm>4=Z6f@mR8&}7gpiNKi!@4HIW8Rth_QXI@P(ziF(SK zZH}#6Rli9IX%{euM$8Azy0O1VrqlcAFU3G_HXEs|*uYM!>7n4EnfBJUc6$}annVe4 z0&~QcU|x%j0R=^mx4-0D>HN&wu3&A4H>B-QXB@V*F03BIe8(ywnz{JZ#SxR`v*uNs z$NC#2?iJsyj~}@rzkqp>1c)GLe$8ikv4_z^m_sDL_rOGk1^sVw9*na<3HsvH1%kR` zq*l0cp7s`Ee8EmFQ)MU0|DC_p)81ny?K4&CO3;h-sRZn;3aSx9L!v38ZG3YF&H_38 zAHA=i7M)o~_sZ)9zd?NJcgQ^VbQ`Lqy}Pd{uV5%a77Z=56b)13R$6u{f3KxKR6G4e z9Tw-XUQI-nq(%GvC(om^1bQpPi=0Cpc^1)yzU?(N#OOX}pWYHh?j8!;bPNNMf$Mz7 zKQXa7?(>i~1mjN+-I?u5qey2_@K@2lNd>=Lw{3s$4b<`>2Yhp9MWV8y-z)d-+jM6s z6&Bf=kNYy|KFUUjY3IMFqe4c$z3Tn)D^84z30tStiz7ZZ_#keNX`$ ztmQLjs8u+%7>vS?`);7E8oKV2QSSAwh&fUiLFiYW<`Hsg<~%g9^7s%(`&bE+`X?`D z|KzIh@vma0BtPmBSv&%a1g&@@SDN|9Ta4JEb<+6wKXtt56chLPyV`78%tqVv(aLfq z6b9xp(_yUm+-HC8p3r7V&gr@|ojyQ*v+=E0dluFB0v4})%d3DE%9;J;T0r+N*-_r_ zuy(8J6+U<3+8jIyk&B4X86mO#H6QO(IhVGOHd==9rt5r~SAD)gO~yC7Q=0P}MV=3v z{}ylcLlNwdBJLQPzWNGocSwX+U4;HxKad?+K=xG&l)k3WX$%*xbcBYnJXyK%r%gKTg&g z>wuT!2bKnw;rYfHQp&XD58fsrQ|Xfi?TuAq9GAC*>I6nS+o9bj$dZFX9WR7JTtCj`>4_P2hU?)nT%j|W@u}emR_$&@K5gPRoriTEL&qCcS<|U#M6=0( zl!bbZAu)2}RUK}ThGJ4qwd$Rk(8jHhp!7s5N|ZH{5nkgd`wu@!FP;$%(Te1oaVE~D z<3rs93P_p63te|g#TV$dtrrAeg*Oeld^J((N_np7LR41V?8-WGrlPTe_Og+U#MMH` zm2A+RO5-JZg*pNRQ7o0Yn37z&^4aCnPC21XQ`qewuGE_5S7>D` z=fbdqv2FI}f-E~Pp6HoEgQ2b4F_G~`=<8Zqs8W`+!q!MNGI#QmSs6B(B8d9tr>ZWJ z>F=6SIMsU0hZM^1*!3!NEESKnOpQ(65J~RuJx7OSTohn`XrSrRvQGNH{M3_FYHSuQ7?D_I*@h}mnmnxlte#EFvhG2c_)pe-U+ z*?rLHZDP>34$ay|KTDFDW_;URg?TkK`JF5{g;f6-)m?)&5=&FikE!{fftfan2fw18 zO`(-Z=Q8zkY?t|yM-rb;R>-ef#(8JPHIKs+A_7ptKJ-!JEuL-c=~OaIxIanwouhh$?zvPl(x9iU+b&eWMt z^LaFsz3Me^hu$dG$N0-u21>IXe9qIGrDxz)lac%>!#_JdP4m?t7W9O4BDA9n&(MX&rJ)~zCd~t154+=&OiTjFt)7y z-kF7RYj+7 zDUO{I2@Jof{A39!{b$%1zbf~4iQn6FM+bBFk=4D_t8dk|;R$ZzctP-s*pp=E9SO>J zSJ`F@I`YD!u}YFvM1t%bhbF0~4S6XXr;{xODU33%Y0cGT^j06s!gf7seG|ec(>RM8 zUGdk~!&lK1%+0CM!lH0SV4KoiscvIp5vVrJ2ei!;UwyUx|NdUzB6{mW%!RB#*eYxH z!|_jOL-{;vPh%(1TY}Yk;m~ZYUeD4@^*|+?$L|w0ql#z0(^^}RxXkh8LZp9;d@CAb zWYS0R!rnV57=gOe{GpJTRnXK`O7`*i6kY{kPeNuyTooKkp> zK$()wliYnpYe`m4|C!sZdoL>5AUH_9X2WN&@h?}=nubD*=SmCt&n4qmy@@;qI)3Rj zsL4y}qH9O2f3Db)DQ4L@MRS0OpQ8Ahm#kY~KozQmFaFR~E{NnWj({#w3trf<8huOi zK?TC?h&{XFiUm_SvTKb6o>v8XN!0L_T_|!a!W5Q%+iM5^4ZmP|^6rES z;S4X8=O|bi_f8Z)i)e8U zSAU&ew9`Z(olB0jq%_8!@qF`qj%tJ1gr?6z?Gd8)sr}7XqpWPfht;5T994>`=iXbh z%x0yaDP%c$MW=^i{k?^F$Wl2#;O zcdG%8jLS!dS)BuXa%+mo(%J4KjKNuoL6MaqEIs3)=XZ! zeQ5A8x$fMlmu=QMJX@GLNM7GQt34}+d$qS2GNYx-l3_U`PqI{6lF*k^i11~&6hm)N ziz(c(*mbdV`4Vj>BhJ;?EjQv0_p&D5;*Gt?ul`M=5{F~1BHGrBb@yR{QT`L5_e>fH zue9I2P>A=$v%aCCxE7{ zQ1-U#ll-Y+N1qbV-P0vj1d=b%?zn>b_ygUIxIaDPRX=n)N5y)V(%djWWp-g*v9>{O zYK4467=_^zWpE+IU4!MBBNAHF?JXFqV|;q1i6jyx-~X~MkE*i?ojwp^cJOBktEcvu z($-+q4DsLBsk-EJE)tam85F8KgZD zymBVq*it-82yxB)MInPnQT?(xaHaU8@mCcg(rQ1eeyRL*)<5rbb*?=|59E}m%j_1C zQ`vosgyYO{NAHp!mLrCIK*QCBySM+t8)qnR?t|NilLsMk(dW$kdk%%#T% zT*XZf95Th6CrxLofZ#VfACcGGcr4$B;mqbRu&7Y<@zv6ndUGZ3aBD50Mb2cW^LZTR z+^VLSEy*jS0eV>>agh_u2fspGWj>8NtNjuC*cpx<6G$jT=&(A7r|oHu`pG#nTsM5i zL|OC9Wa1EIY8!(moB2BASq%MiCDSYPGEH3G!sp(#f)gEPuR7Im2k`EGAC^8zey@e3 zCer;PH0e#o<7d>HX11|Jy$+9O%MDgxr#iNR4y~Ra`4ZI$GE-xwo^sWYY=m?bJp(*nq3C$CCMoUh!Sm4n+GFMC!-zqGt{Y_a3MjaDVITK0}`CPQ7= z-u(TgN6u!>tb@N`{`gb2+wAD*)nVprgqcZYMvBg>$|d_6!8cHYs}-Qfm~8i2*8tVDV^->?KlP+*{KWc7o+G8~ z-fqD1!{!AhBy7)IJb^kXIuzNHx`=F^`X<3>@;5fkuY}!WUv%SqL)OeO7eTkkk!O$W zkWq0LeeI_Xg+!e_`!w93>vkQ&XBJwA<8Ow*HS_U$CK`S4L63}IRBx%zXOlKe4zUoU zn@1{^Y8pCmgF1yZ1Rd>19E~5GtKhp6-F%WI}r-+9KI+Gkfdf4S^JB@ifhGc_Xc7g zDmS#l=nMz){!-JJq zCdx+|(p%HNo(iIQT68EEcDrs#Ief(=Kzq`4cBcD?-y`&^zz1&ENJB3UALWj0rPQ z<4;pBSWGIL7p|=Y76Wm=SIzQ;^C*oXzkjN3g2!%WKJhg7Z};l1Z{q7QZyM@}jjyby zM;b>ruvDFH{famu@^zj=!($J^k;eAnIE$c zS-*_DI%JV|f5RQNg*@!ID3K!!EqRvhsf~Ta(A%Ox@c8qicW+88*uz}dNrf^{Zu>HL z(TF({Vj|J#ZjISkFRvTf_LP|ioLPxoDmufqmdo^-deLQ!#B(f|29@^NYj)%6HJ_;+ zbIdDKTz(P!qI$$;x0jqIsb$SZBfkNc8!pkKnGk>oqw>ni^MqF{TAz%FMvg}Ac?>7jq2kJbl9SLzC#kIhi z$)(eud~TP|&W;mzUJbGD*`HkO*W=cmC_88Vx+QV*f7yWIw#3!(@SL>Q znL8R%KK32KE69_UJChx&^6^-e82#uR@I3VsjYOKI!emz|eQ)wxv^9&fbO!xqNAq`A z2;~+2p%5;S5yM7Hc2$|E#}Z>z=ydIS{BO2|!dtkWPai_@vuBzslSwUAQzC!Wc(OLB zQL4RN8^XoAz(q4^J?Zu?lS8^nE&553C*a(YAR?J-sP5PG&@Ihce<S`R6_c{_;@v4P~VQh+U0a3tOdv%1W_gKye}7RA5)ZQBnu{Ez0-t6B%>w~ zaewnJb@bR7W9tZ_JQVp5t+fB!uPG;{Q$O=bdZE6OEr$tqrAX-0`b5np`^okN9Gqvc zMTy_68CQyqtHc_^XTO57_iMZ6~lF)fhJK5@fLyJg+ER6AZOJ z$|FKb!;;gG=_j+`-Ix?Xvu464wytx<>p%*^c5-R;lR+--nKy91zWH*8Xjsci^WUl= z;57>WR6|IE8U|};4|ghV!TVB#`|<~PK>(+^xf}R_ivOSMnh<#50TmaginW!U`G3kH z1V90UpfD(lkamN({NFDAPpt$MsEfESRlu@#wgUZP-T(iO0RI+I$O=&j{Cm^?RwJR{ z#KTPm{{Bm4#C=JGnArcc2p9987XK~q;O6;ngyUjj|5M8FomZO+K}s4KQ&j7rG_ncp z6Hz54rLcA5Dk%=>yigAL$Au5#(G(v1$!U@e$Kbd!e(hqLm+&~*y+6zrdIN>xXXuzE1PqaVjEp$aY?cIjL1zsLG2+fAOgD z&?FNATk@oPsW@KmJw?&L(IfnV%&Uk$IlzG;X_cme)Zu8f3GZxp%xvADR;&LoF)1k@JFT2H8P>V`GuuIifS^CD(@Tob=@%)85Q2;gK|sKy zSwcV{e9?-Cz!vHA5J4a37zLq*Y84CNr6l~uH~)`r{8m>50H^U?&5vkn$gWs_-*F{BxU~qZ8zt!EMYu1YEu@3qi`ST zNhko88_zXcp9Y^6Tzq$^PT??lhV%{zp&b{(^d@)SCLt8;Hq6}q@YhqZtn6YJ1s~@gRd6ACAquGy<3rgg0Ldf+Es2noQg#zq`ndc zkXuN^0(?5tP!X=>zz^W_;=+;=)>fCZ?MX}`jz?#!2ol^lkfYt=OlO`k2x}F=8nD&ykf=PYB0j?fz(1i?uj#wYFBjPjxVZKBmBG3>W zqf`r3l1i-8Ed9hJ+IWDIA1R1W&CI+5@DeUg2d{TgB%bt=MsL3AR;X{gJ{b;RN0&hD zCA|j2OV7&M|0ROx{0c)t5L^Lc!N#Y)(NW9W!VgizG$6z4KfW^+%$j<|NAdi;?A0KQD z581FcG^od|6iK0FpJ^Q(NO@5GgnJXijCle3#nHJA8i1fo#$#zn;8ycIijq= z+GW~14a-5iC28zN0vsG1?Cg~QGT~$yd~<9Z_-DL!eFo0VPAo)dCvQNXoStd{F6Vh@c>NhfW(9Ad2=IE~%uB@KbnE;&lB{sQ0ue9*qI!gnv; zxu00u*qrZ7Z-GVuxVcwcgOPJn5dbBC>i12@EHB~V;jO0w=w^@H@ess^>&rkR2xF`{ z0YoZ}D|-$J07L`eTigI_6ZmH88F+VIOSH~Q)vh{yt1#ewH74SJ?pUf>G~)AjC4v%A z?==8GsK!R2H9Of>1$=r2hM}W!@D(`6>CRG{|4f+<5vS=s6U)+)?^d?plFu5zb^zbe zc;Y}19=!IcLyl^&pDCLu)#}gU0dU_8Dj7l;(?vSvx_z8Z06|6A_hcQ&KsO#!%{uC1 z1VC262TQTk+1#kKOKxs%bUk8M>raTwe|Rqkf)9-NH|qd)H&`FT;*0Ic9*w6E*dw5g z`G_PoX}LEqy<0y6E(Zn%S)R++s1#I72+3r}Hkf$q$H&Ly&%O9c&JKP&fA;LV#(NGt z_E-}BW}jmVfGG}G)WLqzE!SmVvyHl_1KUf02o7JAIsh!`JUi$j13#lz!%Zg@_qZ z>q-DVkxbvhR-Eh*;x4F#!fWk-;%xg3*I)5nnfe{sZ1t7OmnDK);wN2+7IGS^6M@>8mO$8~!&F;9V7i z*ZU-*H2@s0ob8vZJ=o&=*GQBQlXa1st-Ar`ob>na8^K`kRMX=Lh$tyJ%P+r{YW0mi z3rL7LK24Y5h&fFhZ}(kjRe~X`5GW8}7)CYvuwJphrqe52=(t$&*D2FZv{hDBO%)OH zJF^W6x&^RF+pR z1{#v-*Db#QbHmV!+zR!>0Kd=15P^8^j#2IE=)$IxX$0r$3(c@Mx-=Y1ia|LPs-tW`mt30*n{0 zs?0jX7#Zbcwfla&#WD*x4%^3@0nkORYkl+c^I*AL4N%f)>c;oMzjdoSXq@&-T+k#NMS4x#P#oF;A3GUgHS-w>81hLle)S(7tn2|RT3N` zvXcPo9$=Hy`<~kPdY4-FVI5ujI#8aT$tlD|SUu8nJ768V9@3C?JCPgD5v6als^Q?K zlBS>kT?!~TVy>0~PE`zC$Hw<(%G36bo#F@#43aq>xr>)(dcc^tFkN zBz_oN^owl(TR$m&)Tn+CY@gt(jkLaCYo#jn{BBIn)}Kx}K*a*ejg-lf-keVdfIq+i zz$0{uuh85N0lpkQN>p+yzm3BmlQ&xr6Yh+_rde8wXyxLP15Mp?C;aaD_x_wlks`qw^+hxTHT6TPog+=2^$u=s?zO&HINsRt$HRtmfpHpS z`+b@2loyG|43ZWBTI}Ve;3ViXm*ep;Y646Q1gu%Pc1yDQ-*%oKww~^kKP;(};*62dA!Pj*!d-$A>Uhh8`i`U#H{ZoL9R}IWR7~DQINZrS>~|C=324JlA90 zZlec-6D+K(!%Y)g>+6eN3r?^Ifbr^K8SO8V5E~r=`83 zvv6HwuUTe2d7cFWQzXKrDF#?1URbW3J%xa*2b%BC*Qi0@L)5kK&c_Ws`pO)~n_`sU zrFUMM$^s-r+FoDRg?Va{_Rt}7|jU3(sC%$=`h)TDLdXg0=fd2>x0Vx8p#bP$wG*d zURt*8PTMBCsR_$>CC;|9{krjHd~#-*lWGlvfY#q&kU9Pb!oJIZ>cQkepU}6(hMy)z z?;y+sNc>B5BEabI21c41fKC8p)#nk4DJ(irANR{zU$rbDjq{NVposk)A2%eOW~Hf| zuh@*dr+&vcdI**#;xW0E<>Mu}Un=*)bsum3N|gZn8Ll^{PX8Wu3uy9W-X$O7FYT z!?)QIJi%8?jSV4pZ%7~~7l5bd7Qm1lE_aw&l!A!_RzX^pyFs|c7o$X=r}TzX*#Yy0 zv+^1DIAEz6LO1|MY|nSSx!bKY~PUrUD%S2 zk-o=rAZ+umbWp@}#6AkJbM;`SR@dIZmIDVkZ*Vj#I%Vd?>xZa7@iQ>n-lpznikt$U z5=*Iu*wHXw-K{>h!R46HE&tjnW_g9r6&zy#Ckv?cLbY76;Jd%e)brpv# zdNu)$C+Vv=b<0xZeEn%C)xyci2??Jq)#2(Z&C4;nCi=%B0XFucm+tTQbJ<)KuAegQzh7kGc2H+i%s{*Ap-Hy96-W z>FEB-zpaDI0L||IK5yeP#tR$mW}BCO_XWOAd!7`}!FSg3pC=3C03ckFldg3eg`x3% zPZg(gjQ2h5&6Ljq149_KvyAPVG{OCJ6^&UoIP&V-VRe)5&B9w6_Mq^$$?TDGz@exO z`UPJK*{xcqdf^Hf$_my$w_tiuJb#thgXe%FR&#&LyR$LNQ%Cm~wA#)81-H(qkVHcNXZFdTVbAO0Jp&i8?=R$nSLwrt4_PIR-V_&GNCfk`Qpw^D zmhdqgMXc+-MZr2h_~E}6E12=bj)z83edvLu8%8peMPv5ssMnL%E;tC+Bk9I$(3r zS4zNxcHu$f$t$P(3AuGA{*a!{XeBKOW3Ty7M;dHn1$=d8#oX2th%TxJrmM7S6azO4f$c^4`8u}ikqAUu4QUSlEEPpL2M5xVAIOT7XJIVXV_WSIr%ZL zNw$D9?gYpd0D3PBHy5C|E-K;6gJUS^@%#swcL3l6i$bIkobD^8G<#G_Y_bu17HuTZ`}A~X zEVAcb`v6L+rzP~8M5}@FTs3PUY5id&U1Dl-GTmCeL7fdf9bGaAhXNsJfOdgffRA>7 zv!@T@t1g_XRwpr@C z#ostO9%ujk+I|7Z5?Ra|0qq!gwSjqX0?ta_a4qRp1I>hD|mkEZ@4hX`&WMuBY zN@h1Y2c8=Y1DJ&@UreAvRKo^^0GTcLs0$SwxCXXMW28~~rOZ$#nB)*DDJA6{Fe;eI zuHC>+bEshHGsE&JMg0IYZx@ILU0t7!_q5rzC(|u~+2jY9 zi@=eVvS6mdq&-c{-jk#7T`w)k;bA=An>_?383m7(yz82Z*fj`&fw0feF2L~#-)DbJ z!pB54yb}+A$`z%%ed(RmZ#mz@Z{&FXcMh$ogao;?JfS`S~dcG8w=^Wr81niAN&Mm?+ zc&g84fKhB=X}Qq>tWPLiLeBJO2R+LR_2y|{llfg7u1;1jNhjbqNA;U8=3yg9K@8_~@s5kEiPVB6flYyMp0T<*6=hmL zO`my{_{~|;zOny8mhtN7jaEv&IdHn0UW0JjK5+R#=#2Mv&tJ>KfCvwQ*U7OrO!ts& zel~GTzs^Qw?Sy-YgeLb6EYuQ!H80aC=K%1}xAOAx2@PC?OK4oadleNGJk~=4!`YcO zeG7nflWLfu#kjqJ&o{0CIlL~bM~QLNqFVM5XMFP=rY&A@6=(gDZmkRu zIbNM+`5(6FJ*%TLGc{cT&Lf=#K&6MY)_@lkSn8=$w1<~V{)dB49oK_koZTeg=ZigLgsVN3Bp3}rf281r8V?7@n5EL_ zVTNh&ji+x^=(ig49tPE{ZA+7ZSC=3uqIAP@AU|0E;?4noc1p~524R2UXPY8FDDY9J z8BEQ}%?)1ZM&_+0yAzJ|Ue2<5w0pZzcv`}Otq>Xj4g}@p9YL#cblN8EdRk zZ$xrEV<>kAG2}1JZh7KFq{+@+{p8;A!bg|<*)a)L)5|U1)gIVa)n`aM!mvy`5C8d& z93JavHH~hyqv09H~ zd`>SFf`A`MVYGX#6@B$1@zB$JjE)L~@e6TKcOwQZ5=V6uEBS`3o3#Vxb)eaJJJ%Fi zl42MaqYBZD{mV-uYQKANm2XpoSf3Bl|iWsWz zn`BJOM=SjZ(RNfnGU6|Sy`;uwkZyn~* z&3Ko-+f5Kk22`ueZ8A&U@0&aTbykbm^-<5`5>tB*`Q>p}{2&?H(=;(oOD*EP_ngTr zmL4yO2^829xSszZwE2eGmWiVheA734`9FkyfY;NAp2H(sAx4@cje+fq}w3ied{wvK=lH#9w z$3su=XpV)2g@FabFFio_ToESD`a?h5;G{wL24r0fTf8cfQclyTr_ceUmo;b43L!)+ zhxU2=$ubC?DvifSMI}B>2y+e2pC_>9e`Rf*9;R%_NZ%*CbluvLhZN68U9%943-SKp zIqNxV(%`fpppXqzOi@u07BNq6WCJ)#nuDQGN?_i*LQ4Ck_FW%uHglC*NyzgjE~dDK zh^sx`S0Rt(WbC*(H?oXzhPobs6DlA;nAv=@UHIw=1gP}aF2Ij$-+U4Qh zErb}_EZB>Se%uEPho&lZrnoFNo|S0-hsnUw;B)wLAVK=WIGZcvn3txc~31oGWqF`pg`glxv%z%8r8GJPi;+nQ>F%@p}pSjmY z8z1He@Msk)9|x{ieZ`-@!rJ#H0SSrrCcYY=Bw=QpxkiBRcf=>I>*tAx4hT!^@R~Xw-S4u;hsO-L@oaC8 zRf^Y*L6D`$6Rg?qIh=@bpQHnEw{`hbR7Sgk05Q!!qZ`R_!G~=Zz?iD;dje97Eg)Z^ z@cfF5hI^^8DnSxhx?$VB2$bk0F7BK=)ZhSB12I|!g;Jmf0^&ew|89-)jwxkheJ}}1 z%-MR>4H7<#{{3%Jv2Q`*47e>uRvuuL!6Dqxn}To4EDG{&4j^a)av9dq%-NeVJFKBwLEZl$1f2 z=F`P0ChdFY@Yw~{=1El3$b1dROO;N-uAx?-G9fNDHl=M4*q{E6kv*?k2RmTWydc*H zj83yY7z~qs&GD+bDN9x`QSGp{pCZX%aKt)uWNhqw4(DoN?SaFaJq%&Yzn)=I-be!WPm{#Z;NPonm?e5BDt=4mIAL>sk#U^DkMg6onE~=JhZyi3CBX zI)NoB_GI2H$pn#@?n$twtTo1a3VetEb@=9Bky1d$+mqH_SIoZJP-B;w&u>&)g;R#8< zmwBphycm2L?uI^2-lfTxDRBP2VQ-C3z&!knNFb(AdRTrHtzCx;Q_f)?P)iHyA`R)FhkI~N~&6cW!4bD#dKJe-^J7=IX9vXE!*3rdN_ZLBK zR<4=D#O9=ArKG%0t=X)}L=2z?wI;|3-#x<|-4KgiO!Sx@Ei_b2f~3AMh9DYjly)n@ zAGjls<{gG1^~4y9!1aMdfYENiGxtan5v1UjK;#vWr{D#(D7F4ynz;bhKY(ftPFuL@!VJ zG>?m2Mk}f4v+x&5`0a(3Wp#DOf%9M-_r~+8TKwYlQS8gbv9I@yjgPJ2_D~#ZFw?eD zu?HwBDu!VYbo)5D%@LypU-djYW_V~{>Id=|U$9u1BY7y&6b%9TxCDC){vs&U05l6r zS(;_q%xi?nV;3_XSJm-g!@Kl- z47BH2-Ncws(1=$@DZfPtx&kBpbEIZazF>Pt79Xd{;fWa~5c6{8;9a5DV6KHmOIN9g zAK*~=ry;l9ucdvTgCDROr(GjH>dh2qBY^x-eRN2xAFB^%qKsJMd|M zH~sg1ki-DmG^RiYJ7`>s`)M*G3t9vI_K8n#O~1c(M!yxx#9nm=M-!a#ATP)r^HQSq>a7nZMtq59 zJgMM8ik|5)F68kc5J{;uW!)y~RviptpWf%6#T(P3#EyitUlmJ7Jcc?U=JNg&hl`RK zC*>}v8VpLzK;lNng0{7x`Qq|5{Fys{ZNjwmKyVu8`t33k%b^5phTMT87L>Q)uS7BC zBw%^$OchCz^vFbm3JcO#WyQtC;r<3My^Zxg%BQw55j_B5bU+0HEDm_AM>N!NEGg8_(9jTM z7JJ%+I`4oPDZ}y&yis93?_Po=jZw|ZE`ZB#-SZ2)9*&L``$J*3@6+<2H`AcRZZK{O zxXOB!hV=glV*L_!49fwYP$JMH)T`{PHz0ZebqAht!l+@N`_PY3tza4j}Qms|Tq%V9_mx;3tBE)EBOKaUtsXtv*Q{dSJIVEcvmD zii$EYgts`-(zuvVdxO&hltapNy=&;W`2_*Ri^)sR{m!<*yaWEt-+dT7Ac#RmPy`~{!DkCA`i>PJN;v8IGPo-M*n*%i$1O<8 z)RbZ##mUu#n!JkjMXRKS`dTGO)$_b?0L3@gH+`fKHvO8Hpwy*H$ch+^qKXwC)F zND_q8jJBdUw$KrdK(P}%G4L@PUX%qYcE(0WJ#SxsU-Nx{AVTxcV_sX#OiV7~mqQES zqA?Bx9)%ApKXu7L_=&wb3ep!aE-#9)CkW9mTH%Qq!oIN{-v<(jk%I7?ME8QPkQ%~K z>_6S?XGfeOAy9TNN%xGwAFT0)KNx`KkB#*lez(WANERc4Pk}Tx7AO3FzMcF33l*@j zXyN~#-T&V>T@n%g4xV86;{ktuac5e(=RPA-`3xHjisRF6zPUL(z2JP`-z&iEF##W@ zasynn5Z)htw%c$~i_N!IL=Za*&9Sk#@0;I;clY#cKR^FIO;vyYctoElpA~!pr|a(r zJ<%8u9s}?F*}e202l@H;oo&MJe(9cZF@XcmTPdHyJF5{M^|wWXXMKu;;hoK;--`0h z!CQM5dH;K5(g#5K7*6AdUM~`fV?K z_6Bz0;?)=FN%!reGe*Dzb9V8C16{HPe-RNO;rR+)_p!^4!#)YxKW~fHTNP+ z+=~!}_A4I|K461T_(F!Lys*W_qPiEM;a&tPH-Fo_dl4q@MexP_A^or$E<)r1T!i6w z+Y}@?_agYgMbI}YyqJLAC(a(+KVVL{olk#1rTq6Il~qhiE5RG!akw9}jzK|0YA9U9 z)cX}yf+=I`*uYmX<^F!Zim%c$|EA91lS;w*Tb&=?pFsr>P$F`W;|q~l0K7H^_;FWv zW&cF0K{Pgn(@e}~*anMmFCPOw;yP0x-)owgj~Z*>WE|51A>j-_crru@)dcQtrf?fj zO0KT1c6N3krkQs4n3(5<*bE378^Plw>wq6d5D+Q>bv~TN2@E+Az@`U?CQq_rVjf)x znt<>jh-bqI57D16>@PHMvaqmla#jNs0E2-*YwVU#$6w0ZqX^&v02}`fcompq{W!!G zv(oQ|;d7w`pZz11Rdzrn(i@38_9Rx?jqW7~vI+uXCCgP1j)X#?bZ&t3?eG$~g%wb3 z;7?qD@D9!7`>d>1Py<&W7Y`?5Z1vH|sj;77QGfwYo45{&1P*6#eouq2kd~I#Ml7gN z1exd7fU6V0wI*mc)$4QdD#zDmB2O}|8#l+Qq&IVY8I(FnU+mcSK}A35-_M*Cd}WvE zmU0446ynpV5l=y>rx2qVs6_-uD&3%B8pkg(2*|(~!K?;Nynk4W{OS(F1Qjtn@Cwhq zWRQS=`Sqg))N8ZCxoLyYS9^8niu?&4p4BF(_&mEjc!=^SAsCc25`L_gBU3t`u((eN zm%+DB0F!Pj@ID=YUBM&9s#BKi-U?^6%gcKS$_c<~Q7nI%$QnKS3RXXc*o&g}1-`~!jHeb-v= zTEFr<&u=YoN~q5C3YFb3&kFQ-Zi`NW#qfpmKPWwEw^kd$tYJr%TL3NsWXQ)6aNyA!hpr}-A=s}I_%oQm0dh>Pf0BD%R|Pbi67^gm zh!Os}+_M*ZA4utb76)ZA^<{m+?`WYj43}N(Se^xp&syHnVMZ170adfcbF5fx45 zQbR&R!DwaB23qK?0ug5-Y6`4YaUzh8?g9bG!QO^z!#9;_u9v@yMR!5^%*xE%(%#

mNLUy+Uj7}iIIiDPPcMpg)|_7InNrHOKJTv!40hbb zYv&KQ^>HIUiCF{?PFdOL4YT z|DUIN;7UKB0RJ7+xOi;_o0yW4^7gHm1Yox6+S&cFt!!Yj7v9P@&`&%Quzt#Q}7{KUArQK%(F zM!OC`;<}q(k2UwSbF1p1Re#kMOV6zXcCKMAN(qQCZ0i=VVv}<&Amjyrsf^~c-oEay zU-N;z7fkmZ0RHeV&358NAU~C!xq{YBtONRhMQ1ysxTt3bcOc&>L64Z2{%nU6ul;ZA z@claNMQ~e@v&Zup=sE59rXwy&N>73)1RQ(}J@}CYaO;ilC07G`zykxB%CQE2-;`ZH z8G8Ce05L?)d2_2vn_Z{Ep&t#fY=5AUi`43YO9h!rb^~u6ztv?YI{Z1tr;c0I_p|zQ z3Sc`EaUTAmr+fhE9{Z`gv-8IF>z8=rysOtMCu|{dK7Alb_uH zw+s9x5ol5)+_HbyZDzSaXn=Lm2Q3#K0r>VM;L;S~m<;84E?1C1I)H==9HDdLMwoIr z&?$nPl!%Q+;6dub_0mdD729(9xENyTG$*Ie+V>K$@;U)Tdu*3w_KWMxOONFkbeyst z%si17w~q5*0VR-?y-G_Xd?97%;AAIN4XpyWWy*{-2R}`u6*b8h1eh}{BGY=Q@~2Lp z2DJ{qi}>pS5(ktC+M5X%4Hv-?=HLjO6eaH>{!~z_V!j9-ItTlEJ9~RU0RfOA9tV8n zY%g>tEGwf9wiB zxkbzEEkV>iGr9^T|Ap8Meawzk10^_+8YnT*2hf93(1pxko;c+c6`x84 z5U5Y4Lm<}I>KY{^<-#CvDzt(|TiO)$b!EJs}{907GAbCw{E;5r7 zLI;XWDVA;~v%AtxK^#KhS1-#m3`P9z;%y5-*e{6(N;R~qj|ODZ=cDyLh?1&}K~e($IjQhfLAw@^E;{2XJ41#b)ZUz@W)Xhj6H5{Re-2|Z zJ`Vi>x(NKIvg1HDaK=x3$3Z3oin`pldgPAHBfz~p0ULI;E)_Bx2!AetBpf&cQztNe z%%}q|yboUlx>Gw$=QGDH12FokUB1u_U5D4+#hPQ2CC*(q#XGzm(E>jhF{UD~dKBCMYSIpKBlL7We% zx+F;hp243RgTAte7^TWMCt|IlPcEgpw7tsC&IW*ZHb6$LLrG?5K;5k;=m0oe{Ktry zt4!W!{#2jJP*9%?^7mt>V}0iy1Sbc|b&u;Hfu;!3`{do5N2Lp&?Nj8vf0_eDJ#hM0 zYCl0Ryx>xH)1QW3@|y!lYd#vp4o{T7w@lEGoV69Yis_vD(Q^~`))s^t%{q0LpOR*P z$7fkh++BQhP_Ikag^Mm6S3&lsesy()G=+o4gCr^6xHxU=a*TL;99%hZ6HMEh-Err1 zI6Cy3#3jgUa6#JIRp=TY%FVSb+Icn|H*0A#IrFlG?+5C8@Y6OTzDSc(}iwji_^ zu6DPN2BKlT&p_M)5{Je8rF4d_ffE6t;Aw%KD37b7(w{7{?~k@?R7bq<0SPP+D8wWr zcmnGFC0v2z3ptoYv^>giKx_kr+)WS_`YG$4#~kz8X0G)zAPLkL)PAe zWSvLWfR?nle)kwIo=SHIaRgA!90BQjDhNSAg!ty|+a5YM$O~?8Y4gvI)X^(I%@5e& z<;m*f0)n?OF@UG=0Cxi6qDke0HxU>faLD~?QEe~$@n<%62w2YR$5)(~AppWIKQTSs zs>rUfAq@*WE z$tcLkNJ+^k$tlPvPEvvOPenyVO+!yhO-)BlMMcXT~EeBr5?LB^x zfF_btP*RJN={Bj2L9^@{tqELMb32YvO2}-o7R-)-Iyhx#b#3R zT`6f~G3dweOWk`Mc#@ix?F>7Izy(2}i^9?}vU2hYidU~`Xlh;8zF~Olwvq826H^;o zyZiPIj!y0#o?hPYCr_Whco`HN5*ij4|0*Fd>GhlBcUjpvxq0vNKa`f0S5#JguC8fn zZfR|6@A%p|FgP?kGWvaN9EF~nUszoFvAlxa+}hsR-NWr49QTU^Li$^`{@k;_=oc6S zk`v%bfCmBkMRLOXxZ|hD$j@D-U{b$HY3+9UyyP<~<}0z8C567cXyPeGuNBYeh*0BVR3DXAhv?DP zVosby8{q_oEufA(6Bm95%bHNIvZ-5)3-e>;y#C<+AWAq_L?kzMs)GM4iyE2B*AAA2 z`}_5@iGeNmPCGVOdG$=?9#nk)(QKU;mhyt5zBvCYqG|Lf8~Gy?FHM9r$G#^*HiH_x zkNmn2OH;5KC_Z-TDAH;_X^x;ygwR;+#t|X!1Tlj|2)$+&5z@&49i6Nq_zfL`H(x1t zWe|&2(fgEmF~qnIAtb#ShF9Q-CPIW9h!CsCGy8jnKfybG-tWUi$Qys?JTIn#2yv7+ zIFF!%V&SN(-ZR_QZ&gbWhbEpuOt64RI?qH<7hFC6K-jLr`h2~PG=^Bl~n#Kx3jMVryZ^a z)7*5rZal0evS_MeFC_ofNFJr^a2(QVQ}uiCC*?1HVJ8`SimCl4(%I^)Q3yI*)h{@b zSzP(l!={;=RZ**GmhsM5U5<{-rXMX7BtdHY_SMCbxh|TilN{c9Q_$|i2tmmGJKZYE zx{9xc>{$f7MaBvW4r^105X`6*C-g@kjt?vifej+$qA;}50U?5ic7rJz;+9N=^mQV9 zk^2xLB&Y^AMuc2rYvjebfyho z)Ca7!8-KbW6wP%XxwV--BSBDuqKX=15&h&CEdrO$48h>$QQ6gfD-^++2w|L)0ZZf+ zVIQ$cLWIzHV#^325`j<*+7hgpxajp{-cBNfVT%D5%no)8%G>J#ON{~NTpXFct?qk@ z2nlA|BSK!iLOl3JFvcNXBU+pW?CbAjd zOgPu(OoTu$9&HjK^P~ih)j9hkMk_J|s->O?SrFizkcK7@co%uG^io#)`>>59BIGRZ ze;PX>!dNE07(;|y`q$X~Umm+NJR(O`suFN$6M-N5Fb_l8xVc;-@Ukt-jk~x-q%r{= zBpVw@0cv-yq@Gagb2Em?W*Io0RH}NIzUYp|kxDkAR_;07%AKRCR#LG1YB4c2c_dK$ z3+~Zhtipdt2t&HS8wTe7V=FQuWK9bjOi02xHSk3v=FMP)28p8!T7~fl9?SF(O2YVv z1AWk9Res#f!(VU(b4JfGgI6$IJe=uhyWLouB6!<+qVb@wgp2HT82>K+;FpnMDUqq&x2aJ;5RbFuvIM?^SD*X?9HBd;ZWlMqNO%WtFu5HBZtQadJSt z&J3kA%`oAex%_D>u)X;xL5{xA#eoOP>L}cNT6@c`POka1=tyT36Q=^HSx3=@Cv2<( z(bRJibL4sae`7vq2PP*gC6|M5A`Xt6Cj?mM)S73QT+Up?CS zFyfrdRdeyepo@sMNclSM;EoP+p1dZf(zag>cl!%}6<;N6Wm(pbae>|s$O%X38u3g- z_LQl~YChu>pULF)XBS9F+{*DkXmaPtgJt-|K>5UtQEamA({9z4JEcmBs#aqyv$GrP2*3i{S==Q6p z3GQj1^eJO}?_wLOW(#1Xkqid?(qo=e{$dyWbXr(9+*}<`o0)f;zw2R8%Fvgb^=%)o zc{G%DyX%ddou7(vyz+x3Zevmo)y|vYsY7OQE&^SGJ{Pr0R~}Du;3^QVb9C;_1YxZA z3zNo!qT zlS_4z$_gpadlbPnIh%a5?8bok;FLw-Qx*CFhKMw39|lGzHv8Ly@md2pqZgjv9{A}Z zkl1udr;qvZSxKQbD&9+?8PBTSAk6~Xbd({H!-emMOs70(=J*o@y$?)_lj12mnh`}5l4{bQ61XeZYi6qQ zBR)T;WD{_l5_f)l1CQ)3$9YUnjrfb>BsAluFUw}VFHiP;TAu#B#-(*{>|?r;U{dGR z5>96p%0-vR0I$?*k9GtW3M;%uOX_{+Xw-AOB|LSe!V})@#+Q1*%sjokOt~tfv2)Gd z2f-~`^v1ZuP&Yrg}Dhb0@Xom(VgRYJ{@~hCGQ^Eli#s_R4DKwPQUW!ffvYC zx(pMe5LdFX^o}1q_FY8edb;C{28|};!i-%^3j3~Osv^r_Y}y~p9J_p6@|O!arX9!M zW>+S$q8c5>vSLo$3~>1y7 z;SB{?xmF1*4VvxcEG`&x*v#P?{8Q{~Rd`DxQ=glMKzW##U(*3ez<^|gp!%rHAP3{_ zqm+p3sa=1swLYdI#}N29&eJkMXwXe3O{@x@Z-t9pSueST*TJ?-i(^NFid6aW^55c{ zU2RS@l;r63_-}r1bmK30tEm#ZANTooGfIv8b)e2J^FE)zNu?S4%0k3N-tpJf_nh?; z&qt`F3-7%0q+7L9FD*Scx|my~Zsy^v@&e9tmIC zzI_{*4-YeBpX*iMxy$*_5`^7S9oxL?7E>Y~BqU--j0ZM#w5ny_&RH>!;q+XLTlN}w z#cQU5((Q{KFW0w5mAJUMyHJ1S5|L8Y>rrYB^19{8kfcYotls;rp=a#p$MmFb5A634 z>$ksL4Q@Y^ulZBb;MMH`0~a}OZZqxG4??);x%=@h`9Dmxg3#49i5o46joJq^%^vvyOMmgFFF)e ztk(F9y}f3|if0qAtPwW1df=zFeDMRfs@uK2#;_DO_o^<5I_A~L*<5emiuB>dteyoQ zD>Ltsp|S{(g0*-An}nRm!s0|y@<{#m&Y&N|FCQ87g-E;n6%b!fOb ze=xi@Xis*jG)Ips(J*@QFz@K0tEqoyjcnd5GE~tx)TP`9#_en=I^wJI4u{kVklBso z-y5(n=`1UEBG{V6NS?SA@HNrEJ+Q^myrm%#`=c8zrrjf)}{1**~hwXZ&fHr+6* z9QQM-((G2Hz%6CM?an+?j4W9AS{g$ z`9bj!mr9&28`Vzh?bT|R*YX$JR^1=UlJUN|a`+(13}xK73ZrP9)5hy&|BxGRD@3o` zx3G@JOoXP%ix=~!vDm|#PqLV(lb$`*$d^3B{aX2IZoYQT8BH;(50Pno_k_ObFD~9# zui7h1ir;;RsR~oJ!V)1yxLDK_<(+=~6K~sHru}mpVAE{f%JK&{I%p+N-u2duj8Zk~ zcu3JDUvMRg0S?Cwtmtj>LkIuoKF9#+sXFwpNf zt>cGGD)wN^GQhZdFChD>`l^3`qZqBiyg7=4caXu}92EJv>aOng1vsfzDV4&s01xa7fA}@DGjMJh3+xOyT}Nw3>W9580#Gk>T=wU)XAe!UEaa> zk$i*Rhn|Ym95fyhtCK+0auOkDbkQ_K2sQl1lb2CRP6u>^ME{P(Gx)B2{@N%L-p-eL z^dxrsN2b-os>W2+y6+$7-xzfr*L=FN&K$38fgDVeH?jQLWj6Mpex!VBv||jj(Kr*n zciNW&(-%R6pcum&5e(ZC_2+g}cnFI+Q}-35mrBB{AMSQ0b~6`9``c!TKKgQ&;jMWy zMZ(kaC)F$EYXjvj;`fWYC+prO<<{JCxa}L8P{^%3ow%MEj`7}g!5TlSK)#GwJz#sO z`DXUIr8Jhj2w5;Q<`WW`{TC)0ipw2sy2Y0kVowy zX26GiO5gd(dvHVLMs?pEA<}MtejJk(Hw=TNHT50$3PqpUF`IDF&=JLmRdj3I_WE>x zMv+UFf@J9|X+3pAS9+}x{^r7cIAyd4OMJwI?7@|4+gg=}BTH$xlv$VI?lkB(<#XP7 zj;bWsqF8B;px5v99S>skODxQ;6?`g)IBC;qfA152Vqs>OPNLz+&8MoXWk(E3EHRyW z^;}Z=S*Bvz2+@NZ7e!2ta&o_JxThfk{e_3i5!~wD?{KbK!=4f+S2)ODB_1s1e0U=+ z9wTynQ!jkJ`PDCN`FuPlU0;zROkdb>$_~W&2vp^6{8X6M3Msr%`s&=t8>zE}3VkMG z6LIDx{SNW|PkHL!!#NGAv3m7|6J7Tcjnh~ysLym=vVE;BWgGDM6k21R3j;6mye%Yz zT&!NZ^+oSa=y14^$39!(#CjzXL(ivyp=?P%alOj&RCIH4LT@H&Na4DN>9BKG<`o+S`zO?vSnS(zd)t2C0i(Tp{S6} zW236J@}TTR#Zjv7)oh%NDaIuzGuOh=x}5WnW}+Y;73W;9$mw9po)sy@Wf1=OT5N{} zO~l1<5#z{+?A$?QU4tGGl5oi5EALd#ak{DLrrXiby9vi?!<$BqV$9Xv1~m=iJk1#7 z7saHPJFwHMHI?Dn%ifBqUL*acjx{-pA6A)Ft-Gt_NNDVG?!7O0e>3e)NxRC^&UX=p z52v;Lsdh_0Ho#32L~gyfw_qFhD(_vxW=ut=X$2(QE5~-6TGD}6W^n;@?rfE30kb>wc6?$ z)2lVh?j#K-e{d{?_>0fr`mPPga7(p%vliZOIy)*Gt7Su8Yu!nDI`sT~g9x|H)aPH2 zg*PteW{kTb7sq;zf;H7He*jB{b}&{~~qE_~PJ>h)n|PT5#L8)m5qCsmHoY-bK}?77eVdF9SmJ(f#FlG-vtIvOJ5z02CUg=4vI77nZ$ z>;36yTKdCX862vTXTqdiybmcg;$Uk>sv=6Y+ICda25iaKDj#>B*RU6+IwS6#ctKpp z+je;R=Q4r%s82Xi$5h%$U(S6my%-ZM)pIV8_Cun8mSz0Ihxi`TDcQ=sBTB9^ zZe7Es_V}?Yc~F@dDf3<?_1 zQJnS~b!OXr`V8{M{3X-=>;0>1VzIYH&25XleN0Cz3LADeFJ;Bt&bg`HCQj{(?=`Hi zt}gtV{V*+cw93r*w5&=&KsMnuDg{q5t^5gi3=M2O`Q z2<*ysR~otrPJd|${~@fQ>P=iR5h5snfe~5|XAsMXpaQh~9zmm=2w6oFAp^Eg$K1$(BmnXQI@ba-Sj z{(Z)Qhksc5;=7=Q497V~(TC?8PmK>uCOrOf=2e9IoqLzcFT2gRsO!2q@(&-bm<#Kr z)N#T(PzY3l>S@F`EwmMZTY?pUscqHJlG2$2iaa7DKnowKT46=-ht>zU-6_!EHmGX)a@$~)amU^hg`9g+D9fQV!O>q>-(IuP2r5I;E5 z2_(Fm428yk!HC`fWCm?MCWR0PWdcOYGQ5fiNt8y|*de#+U_=N6FpeVyfM03f`vl09 zTR0FGsPl#*a2|Ew33YM&`}RFwy-kEH%^iM6GzTmSggDS$ad?I8Pa3p6Bh7tQX!Y(hSGyNp;2Om}f&_7Ax zh_^fv=_478dg1D5&Z&h;+nPG1PvvK z8B}g$I+WB4HCwSQL zvz!e)N%4VQ5A10EsJT(*gVQNpnPCUP&_V%wIaeb;CCg_a{{ij;EB`Ai^wZMXLe7}U za`OG>b2PfL1N?#01EXl(P;?Yk4Ee2VW*8PV2!sN1=A$J?#M?=hqf^U+y=B7sx0caP zLOHgt=Hqm16L!JFY-SgeS2Lm$8bX4ItPxRBjY6u_75iI4*d+zgnf&@jZlwbpNUK1-PHLHrQUBTz~J zM(`dI5R`;x4RWBZ(dcx-otrzRyj$yj9ne2e`}zcNG>2loXK>FkQnT&Rby_xaf>?%7 zU%_l=whhV_D6?jyo0~oJ0L#tyz6JFYq@S`@%Arf+hcO7(`^arJUwcskjueh3WcNego>Yh-H0w75L^J9(v@C_I+=b!3F^?(5WW&y*~ zTP^ZpS`lSL$PuY8uy?_{tx)`5y>l@Bveg<9(8X#qAbCNxV}Yp?6*?$n*xzlK=bacU zJ|YLk<;%h`)l2)&-9kH^jqmQekB3EzrF&rN*q75O-lrSg96hlNEt~Dideo(gGW)dI zOjLYiT!wd?E_>@6Z(jqo&BC8N0GB9VaX)o_5auzwt6EhUed!+(!Ti@T$*(*nX*8xU z2rrkpYQi9~N``Hv$;S z=lFBwHI=yMhlaXtE~5HV@XY}So@>Gv)KQTnH0PjCyt9h5*p0Z=GZ^51D-ucCNQBs> z=oB!FMejZ?X{bybKbZLPluXL3_azUTg({@8^9e20+2$Tfdl%mc@weL(bZXZFJoJ+TFEA)XMqd#k{roo%S1`_QF5D^}+pM<_@Z+OI>4MA6S_Zyz@PZMkwZl7CSS^W;A^KP*A$%WUkSei?=@enBAFmWahb25)s27FHN%iC(iJnc{!4(@kn55twuc4 zx%>w>yz<|7x!YvI2S#ConK2QjW>vu+I*F0cF{#Nu!4b_228X|Sjsbnc{Ud}4)_x6( zVQW?88?r-U>C0y8PwOKaQUmvlnZ7sk$6Y3DDP2}w3{ZLZ$5@uY?&HrPC#)EeD7Hhv z-I?7M1Sa+koJW)jR;EEex~TE=|ILdsoX~SXQHFw!&CN=@tkcTVu|{)qHa@+O zj9L7HM?6=uOS^g=$ zWsdt9wvV1(@>3rqjnK@?|9dRW6J#Tj%feR|cNJ5N);)?aGM*O2Ous48wI^lO@vfa58bdeTb~OqA@>e-t0- zMqtMZ2JQ4Xqgj(Oo68I_yCpm+AFE>cwj?-Vr8P!VM2Hx)zi3@^?q~|x{CC(d9=1b? z8FQ!fGOe|Ze2b1vizytNdYW;ZR_vPz*t1a4`7*BfE+*JxU5HQ4A7eGf;}tPMWvF5{ z{L_(&YoQN(P0(F_HhPyk&Q#Pmm}-QxfsKy*BIbCW!Ja~P!hWmKP<@05og4<>VDy&YE8RyB zUQ8?jWQg0EKx%>N8iwwtXOI$@pyTO;keQ}pyuwrP4XJGiqDkuz

qH~@_WOWYzt z7X1SlaMy_tC&U3Cf*OfgSV_nCeIp@4PV%mUB=njq%9y}a55Du}0P@e@!Xnj_NL%#f#cIP! zw@JSLK_X>nb1~bh>hFLgJh{EeU$m-!8^vXPW1`_@w$&wfyzcKvWCp{X-^?cI7gah? z@1b$@5wVtGLWHb{pjIGRa}47JvjDmBBtlr>h!*ehd0mwAp{|_e(E2v#YB)EC^ZUYu z%0rEAH))4bn$Kzq^7qu+q}15%9_6aCX}`l27}p{gm-ke8ktKuT<+?DnhKixI#qD=v zS}Z9o0x`V(8!%k-EcSG4TU%)907jD*LjhCY?^TUWk8hc`atV zO}X{6bGRA2vs9M!vvA&`K1~T>07^5DNkE3P&Y8`qRtW~7ztM+2Ir@0;fx^CwRn;ol z_LgSM+uCb)JIwA*sWI`6OQB*ht$Cr=pGR`jmP`=z?I@hIS^F@uf=M=Eoufr-@nblX zbav^>&Gt97*0gHptj1xe=Qz{R7Hn5h-6+Ro8fSQOSLQUrS^GmvQs5RUnPGYlViwWIW$j;m_wF zW06^8F;sOjhri&3uwn^>j}jG;d}>wSagvx7X6b2kBZvjEX#u&0<<@XpLZQ3M``UTUe4Sxn+OxRFS)OOYnCWljD>WQ(pV zMowH!c?#*IQ*YL$D$=jaJ8R*!sltZZ%|zq2xoxgC3{>dqEwbB~Ib@g&duv^CWVEJn zJtHq{6mZ#}68{hvk3DUO@h^12ilF3LcuzWYEVXdh2cqJC8B%7Nv6mFNQ8x3-V4J}0 zAPsotE9nm?uOJP`t}CT~{|rr?`^O*Ss^NYG8m!gKTR)x_EA#%@}!=f->fZ=Ix;v1}RK?3v4_b4Q*bRm`e}vm?2H4S=pU4>R07-Vr9FS?{r`j zgGm}rUO!h=lgy=$Op{6`%ghe)KV!hX$XZykuE&0p)dE1kXG6lmtri9nm z>nHk(X%a%kKIiDM0R5D3nG#Mn+3zJZ>OCZ@~}Z|oL+fK zEwJXW8Y5soX{nkWW-y>yS8BC=OR|IQx&jH zb-(H@wX%4PFG<3y%`=SZlrb6*pVmJ{D8P$Kr^C5k9ceh{l*~1;17%!2wPM=2kA{h3 zJq|@~TOc?4jyMK})}hl=_*;K+1|+k*6hLtNjxYk<)fXi~c33bw5VtfD91Z%d_b*3T zVq&fyx2ti_=C~QG2B#ebPKcO^Sg^A5eLgRFHE~e<#)l2_>u-cj0t2MbR$q#lab>r0 z!}+GmX>_B~8*Eyr)~av52BRlv$_MA))V?^h zMg;^DDKn>5M)ZHEa$?ugE|g;``a)%Rndlhw6v=l}#nyLdI*c4sr=~t0a^K`LXgsq{ z5}=aRnnsQtjjS`oB$*APF*_CMfpwmqMO5oQ^Ad{6o3ova^tq(Z(iAHmT(IqJy>*ZO z-ia87bYGW4VO+EMu&+A0z)_kTW*CjO7>(FIVp=tB7(9pk^tr!qdrWMxt}3L*Mc!dr z!(rt1{%x~!--SqRj#5=c90|;&mHqd=d6ebD8(h3w(ip$_+7&JLuOwb*UyD({@R`r~ zt6gMPpw@YzxZCQd^xxA!G-iv(iqU-mh1)YMj;C-kc)LvamH}4tEo!b{rsCzuTfba^ zSCwU!UmtFXwYXF#x-+NXKbaWz+C`9#5t!j@bI_Nth?Lfw@QeJ|q)-`M_nR)_n=A8< zZe5NpEFbkh#%PMOTe32-Z9W&Gg^1o%Q*|Ch+7yS>6bJh{&-zqhmVmmF$~o=SkhI9U zRO9sdVHp<*qoLeQ-|+9-DerB9b))#WUbK=bSYM2&WLAQ>bRCNNs$m&|8pKRjRM{}l zpgQ#;U*!>B-dtUKbiI2Eg>x4!uzUdK&E%Ij>T&ZlwT4vMnd0V+vzylXoJ_*+92 z9qT&<+!9(yoDTvepR2ziRXM# zu*s5Q$QC2E@v^*jhH{0CqqQ|LQ>;ZwZ0|rfo63el{M^~tD)NaZ-$^>1W=IGkcq43d z^SV1a`Z?hY&PE?I)m_C#ki}?bdU_VDhK!V%Rg{WWJ~~RChADZ3Y?;%Z)j!!BKyQVD zt%al0>0p?d=4tV7zJff@W_wi8%>*VtrIzH8OuvG78-WPJt9iZoE_n)J_Kvc3bBU2a zAO^7njsff4L{K@3ZQ#OR8SoW!LorY{esG9cIp7}dX&G7r7W81 zhqP6PN=hOvVjjN$`q*>+UwL^w>0oogFF>Ye;|E1STYV~Phg;W&<8>S!iq4iIx5Tms z>=PHVgJ$M0TbYuJLa2@11AGs$6T8O1aq{}|VuyDlvF|S8SupL!!-NYCYHAg z_Dq2T(Tdj4iu$1=nv=~|Nc%?UTqOSlBjt=2f~3yadDeoh8L-ltg#HR#vG-hcu8G~4 zKt#j2>Y-t&h525w#YpNHwx=;%?`hRkNN3Xne9bV+4MNL`2aZe*$yMPMR;L`Q_EkCs9&c^#$&0>IJIQ6MPwDozqA>rUoF6PX7xBV|vxK2Rb2A-gIZNg8WXf3T z&=|Ol+LaF2w8f9r*tXlj`VOSizav=~hUbXQn+Rv#Lm^hgK^X37fTD`e+)N{k1|H{1 ziHk?42YK|JZuaDUHSV&T!z|gT9NRAHc=nzwn>Jdcma{5A5}t8VdM1hpq412R!98!Q zv2OuomXmP9t8c`1xD8aU@X@6fS9NJ~DogFhu5nvEUGLRY6E^q%h9v!n=VOQ#Cy2oB z^HO&CTu81duX*9fHo+IV=<`?`ZOyDlFloN)F>iY!uO&UIff48Ij7c&db}iq)UG;VS z2#{1nle)WqG!OxEo`kct(^-ORD0>&mt4tx z>s&kdm`RLL46R2Db1c!3GST#YaTb)0xK8jiKKx?t+pw)@2bX&?N&bcNSeD*uC3Cd-`nwNeSC$_p1w1i{yL;1 zeK!rulgIl^Sp_8#d?1~Es?Mw!S8%PgY_#s$h~fj0%$XiL={~Q@V!pZ@K96T-MXw^e z$sTNztZ-1ax#z;oT54w6#i%Dx^*^6~h`g|{L#MUQ;g#_-woY<+FPh8BF-l!HgU7Uk zUn?TRZk{wRX-=!j!I#Aq%K;0ifnb!kj^f0QM=NpeNpyz+gXD&hm8dW3RfH`E1g&gx zs0BaY-eh_KiCIJswvQu2WIF0(GMAI-@MaPfav{C<;^q=w@;$S3G!MMVh%)(xzwctBwfWA|X9xUB;$Gzq?2E^G$_LdDX2Toshyf&HHD`r21%mLfe*^y)zhqfpd-?S3+^k zlpxnnqhYkTW<4xRLR;t)ltr>i_v1R_Q4A+MVf1Vf`Ipzv18oe9m2F9X7I04J-sl{> z`RT1-Nloa5ActO~>)$Dicv=`8P7MDR5AwKTT)*sD(KayRMQ|<%KbG~q7kIf`2X{-g z90Sz4i_Noa{U_9Il4{Dc-zc;H7`gW&!f9-4ak$JzXboL`#3$X^p2uSJPi*gM3^t@# zzdy-HA9h;*TI15?k{=on@84M@IAtSpUkF(dee{Y3dZgj2q6W5aoq5(EisgwuG%*u= zK3n%0I}=%_@P4_!N2P=#@vXgMCV#|4IyIAy4yt0e+j=b@tU&CUMi@9pna5;0ciKfYLZPARxsGS_3^EeSaZ z;gyAt&dRmEkvXz&Q@kHpBvX`x_1bGqtg#A`QBj<^*)S;XA@o3X@cyW{%ZTk~$LJ)5 zh|>LRmit$}kXJROM~urpxBmFUpC0R(dNA6;na=2RxPh1Z0RPZ7T#hW!@^%$yic}qc zVk)iuLV_>EqO#gM9>R#@MM<=|p47?mRUcO621kl51rr3Frh!WB#r;E*fuEkbhI$SC zBRvwV*1~3fr5E`h^-ISVpMG(l$55UU=}R%_e;)3%+Fp!?zA(1rt-w}A?6~+i43#e< zOADvRM>~CDX?to+vb9M?E$@$!GPT~Qg}`5qe&G#O)cV5k9jP<0&3&Jj2`?7d=7MNW zV;%Cq$()i}mNGS0$sVP3;ejuGzOOVXlBHA9%)(Eag@HAu^O}JtVwTcWvy-r})C$L2 zydTG=NFwr++R2@cVns!{$^HCtr=<&=>}~Ii>&NkZ)+d?5 zIio0BifMFEh%gLZ340+g|BkOZ605TDe5c-Br)ES#?5DJQPWYD}{dd~EJ{w;O4ST(p zF5S_hPr>^_SzvC4r4fw`ouRGqu471nhJS=ykx@K!I|qoGeXp$QozjiNR*!ZlV$7W)sc_QE&N^+cH0h zeF{4JAos1t+v@UrJXa!2eLvo%;3wrogZNY0*B$HiylBOW)RUJ1?myDrJR)bLxLcgv zCEZ6E=HYi`Z=tFt;TI7{MrfHrb zG4XMDK()mMlcM6snN<|mZOk8%dXsqDKuEVMn--nBI7Mp1Pp&-_e97-4lEta>pqu1! zb>thGi}FhBNoQwcpR2L{_zlj)BF2zbBfchw%D&`SSjY~$EB@+7oW!*uiH*Fo^}{Wd zm%j2xAnJO%Vb%YE?p1w+%OJ>&5~O`aaqg(%Fx9gd%h2~YtCr-cZ31WcKwjEUAEkPx zGc3u3-i6yIR@nGo+~!aC`lS`(fM`m=g@XXt1`A}JMncGIziL`Wzf+~YP_qVmlAcuiI`&lQ5Mnoj10PG3;8xccMt$Cwt3NvM9o|$d>Z5E0bVML-F0;iTnH54S6`5R0lNPp|F0nO**oOvI;31< z--MRcy*iXjNb`DPCc9KAMEdF9ge=OWEr?AI07rq%jnZ*lM2Md1nG9OsYLXYLtPijH zcPEQQmH4@4Ic2pV9)1c$4RFo~cgjZhMsOFGgo=FTIt}K^zQpd8JIZ#m$UwpctWo^o z6-!+1$~5O;F{@LW{D{@n>Nhmni`plLx?M?`X%@=KIpu8|rAf4!%iu|0jMM0bRi&Mw zY|0n0%Bz(K7u>t#*3l4OHnh+}Ekw=be2ue@h|Y`n&gkySs!P%(pB}4=lB`0R5H9e# z({l`=$@kyB!}+gX#gMOgDMm)_7AkYJl@hK=O>!%axlD0(X*XrWX-Hj~i*b-#0(eBVCCVr42lzF?o06QQtyW zz@^MDm;E_$980?q{dga&AdvJk)_LZxGQqPf`nN?GXyIu9ehqILIq=(QOJ@};%(sN|};BK>ZYbIh1Ei+g*GthtRK> z=8~gNWyrhh6!<0e4QFYfntUkIVI%Bd4Lt!;t!5a#rA$?`9~+uw?O?h}<(jE$5EQC$C9K7m^mY)M$e7KSokX=qq&QeV8yPD*HwFJC zIt14tqQ=P!K|1(Zq5DGp&*6NGaNg)60guARKSz2G4Zn@|PSZG`tL%c%SJuN*JLiiO z?**t9{@WD&-{|Ne84Qr49OV34xI3Yf@)>kTc))?w2A$OGVrW%2&~O&7(oi`7_9lBO zsH;erzf?Ia_BtqD4@uKC-l29bK#VrUPVcHnfCn#agMcG~sa&U^;^(0xV3bHpwTZ%2gW@zUy3Dq;I} zqx$_x!G=tzsl3P?T|sS};|B+x^TRuSM*Fr>tpd*-yU4r_?@&l`jjAppXd7C_j5e=?>>I_{T%o6{PXM?FH;^&U6BOhg$O`*6}=Ue%#LO1dWXNNv&saOp0 zyFY2W22$fTdS3YGL*Xl_-DJnjeofUZ(y!-#$A9-{$X8aos=?7Ke0I!mYzsCkveAw-sk!TD6;rg8ZPz{U-V|}ZqYAfvXl)l9Tb6fsIpt_i#p{vpr{0k) z5!E!?p{nzjggmOqv0rlJv&nk4Q>uIuJ%kgY4ZOB#Lb2&>jj!L-C0Zpm3CjG+Q>EU( z^AQ?#oZ*w;DXSw+L|jBVSr<5|>+*CqP9Dr1o1H&e9X3o~6$mMW=e|zrkJ||38EIqM z=f-j6K%%p2IyfUGt2sQdnv-L4h+EZVpKyW07Ch&B zAVO?CyEr<6XD{r0fq*Tt$MEB1QI<`uD|TA$K{e%}iC>L0>vaZxoig*w(GVZ17%;e$ znuHZf?G8tk>AO}AG<3L~?S_){yOb;ZC z9!m*>L3mSDCWXwS{7ASXU{3V4US{iYkXXAnb|A@#9PLtL_$o2xVQg>gfg0dt<9h=UoFC43nUy1CH&;9&`s|RM ziCHj(1>*mlZlI19$hMtq6w`h3wEgay~Moo3ISW<&sUim;%;UdRds?&>GZ!iq-g1Goz#T0ZnZk*)~sjY z*)c3U7R@P}-%ke!=tRlLO$IJ46T!stivjMJqt0AA%kJoYdrPiV{Z5%gPI{2{cj>Zb zGpDE1njQB%S(eZ^C!;73{_%;E9aG8o*VT2!BAuAyb$Nh_?u}yON%rn58@)v*pHSUew!fvkO>%o zzwrO4k1Y&4R$u2IeF=K}QX{b3WZ^uy*th`1x%Hf|lcXg&OiMyP@2}+8!_4Uyhg>u} z|6xm@8=gItBlR~QJ5#kutEsg=9k+6LB6Mt2wY6<;q&iP*3iB(Lv>c~gSAMLgz$*qB zGN${4j3Ug$6U_ywSAiE{fnmZ8ON4OQM=!<A`t6hzp=Hh<{@v~lh6v@| z#2NJ#2mqcp$k9{ki=rfa%&wf=j%sM!assDxX3gU2LP-L>>#I3)hQMnDxw85?$IJNb zkqEv$x1EKrrU~5nY=YMI+3|C2(Wl=FKZhooNr{XR7x^4Q? zafEgJi@0a{mf0~eUOo2{7Op-(rtZI|JRwq=+si{j8Z6L!~Z z!r*gA$`-|ulow?O>v7^kRuM)(*fZOG7=&fb`6ltc+@9fFs|lqlWXO~^$GM^R-ecpR zPp@Y}qHIqx+XbFJmZM%?X5&W67@9NS0FnJ$q`tlnv6kaC?Yj+Kq7UsyL{wZ>ml)n7 zS9(XXCC@^F76kwv0*oo|#>P=fo#Y&fuLR&XZ#3g{=`la{%(&F+dbo4)UX8MHXR2GC zb&0-Rh9uK-%1m~Oq}moDGaO^kY`~q#t~!@pACk`uciTwY!&R2k$G&1o{5)|SYfsbq zAkUjJ3%zihn-g9~z8$%n!3Z>ROak9HuT|Mtx7jOl2K|!@;%#?6`Mqw9L~7aGPi%S6 z;bHO_-($0$%BowZ)z>dco}}sX|M{Q$V`xT!^6v19cF)8*b)hO^|d+~GtTQKs1&JrCPF9bluw&t^ADuh`(O8%mwuqzxZjI51u!S=e}S@~ zz4elxLwgEnk?8JL*;6`F*nBHGR^_Y8x>#Nv^;WWs5o2YxjG&KA(yIjJ2r1gF{}agk zmynx2T#U-m45X6lmg;(i5T;{+dW=ZrTjYzSBQbS61)>j~Y7%ac`oDhFH-%?D{Z_&N zq51TLh8TY=4{SIC!KCH8Q#z`(pm=~S)t72eXup*{a`o49C?$-_Qf9{4J$Sh}=eOz$ zoI&e3nx;lqBwe87_Azmk4mnH|pk5$L3`tB-=Exh>A}q* zf0k6Aq!=&A@$D~U&2nkBZ&!$F0^D6j#0xV64ulTRuAFR2CO(PEhYk*|+$y{#tLJ_{ z{X4C%uk>q`5Bu|OprWHUf;NVCt9&dlUqGHd?D@g{KvB#?PgT0qs394MXYF|ASVJ}T(;(v|*!@2N2getPtd zlKs3f`}!gr))4oq|B$&xBQL7N_0Y$mDIypP1w4=MBH0KXktkN(=Pn%8Np`#NcK6?LP?`vmKk2pzdV(k^l8 zkYf>9;5a33d4FtX@4JBZQd9in@kK@B9OE~m5UUJt0SmV?1-*I^1p+YNa9yMT;TS2` z&PKlSyXUT%tHU%*q+`O7MYp@(hNUs+lUVnSNmm)zyJ+Tbw{*Yo(qci}fw%}n^*}LM zsjgwgMrg8;RWo+NJ;(O?T%T}SnXT_<5vBWoo0LD&3;G6X4!T2x?nIFiPGJdX!2><+ zbzQz$U4G==^6hDnn7_DHqClIyOsD}@Q@Xy3BJqdur+Cxz8b5RoAaLr{le|+d)K!uz zQev{pj^#8@<gc#g2rNbwt;sHUDJ~+ zyWe{;-{>cR7vN9#WJ2(Fc3zBg?DLoz8}_?_T_sBW${)_g53245eHKK&RFn zVTn2%6}-2nJup84asHn-!a=ZQ$JmMKBbuTAsF5`KP(9=tB?AaqN>(N&FC|*es={cT zz$}2OVz0C>e)*dxJL!uWs129o&mB?Ecpf}V%NsI;1e`L1;R9?Oo7QSzt`uz9iS~yP z+nd(9gx>*b%{c}lBHf*?Q}SZ_yx5z+nD)}z#0?>O`}NI zl9MOR1HN+d-%Aj?c0(Gz56Z9aiM`-E^mX_o-ybwz3C_yY!`Tx$yAd&tEI?f~i}`)h zXhQ8{xyHCZ8sO0Go?yN#^#>vBL9$o&>KD32g`Zo{ea2Rm4ty{uF{!Ytt-8V|`pNtC zt##!rhIeUQYeLD8kmf!_QaCqYwp8QUpOe|K+SD3Au^K5xhV7JgH4(3Sq>NX5P!(>3q9t{ZWydFVUZGXml1c|?m7fUxOWCgbyPhT?$9ZywWg0TRSR^;GR z)i&*pJ946?`7=N4ZRS)=sVXCZ0%lNHO*oX+l&0G~Wvl4(shF|Sy z8*hjDE{Ayx5oNCGE}Kj)+W#m?v8k23K1)Btk;d=GafVTmSB%zimQqDpsTP)+((zn! z;zT;#oJ2`2s(xylvcd&TH_uSb`Sk))w0RBMb&KWEGs;`+9D?gBl(gAE-^R%@lMl$b`^=KL9t^ zEzB_69^!GzI~@pRLUI#joH&7$ncw{ye+K!b)-r~h(*yID44BC#(h16qicB5TufW^Y zos$v*;1pIfzlmpVH_?k!u}`#z?{e`~*Ia)6?Xvjx`+T=7&>~FUMZQk%nhyS?6v4{0 zyt^YwM6d$p%OX?-l2e?#eb-aNQalnj{n&B#_LQ5A_z$_&jBk0arf*OKHg7Ek@vg5S zhtQ+~ewEayCM+ut?lvx~j+keC484uv$!cO(Au{-}D_%TsPdgo}3KySJn$dVx1w&D1&1|psIgH_ae!T+V&F-IgUb&WBW2(W*X^olP2>%hC0$}D~QS}>3&Z$!lEvf_KnHy8P4 z4&ZNPAMZ{G2|WrC=h3Rk%1SG0`v6pz|@jbr&~^2CPg>?=0k8C^N#uE~`6$L5o_ zr(!MorVD{0mlaR#qhaT7l9Oju=0E)YDGKziOesS=-{I)oG& z5@bft8kCx`=D7#@7xjG@^~r8~P?YKMG<`6FXu&qWqc5Dfq{j)w-W@xY*n+ZPHIZ{f zbYf%2nU%&)769La3s3eqdT|qOxoS}QQ=2;-CVNWyV9Wc8bp|5rNeU&d*61a-vp=dj z9Y5Ncjjz3wkKh4uWHX@+%`)Fx;q`rQgGnffxu5SYgSi?}?d8|GL-|z*1x6b_tIJBx zs#yB^o2p#t70ye3$HSv5FpCjr3vBTf=KEV+&R#IiFkx0ztzg^Z3AOzGo z?_(qI;JZsmO~JACSE%Um00riWz5J3dBqvo4N!#4dqH}QH$*12AYeyK8O#B5mhqn7f zA&;He49JKbbyraH2wjxyN#*caJV!da;Y-AGd#C#NHpc6`St}S$FtG}K*&O5b>uquB z%DwBc?jUG?LXQ}0T6)<hNl9ADgxMymB=6D7h}VpTs6hbK|{+H$*h%5^dqh zJFFCdCuU`mC64>Cyr+X1hUAonBHN2ubhdIk2=Nz|>}^8pqKw;5_~K>umLX8XvHw;3 zOS2>l##m*P10a3j25z;^BY*N$Na)Fb-)jwBu1nNo(dAQ(L|r5Irxu!qF;C(QD;8wU z1702ZIl~k-n z=`#^v$xigt5O~cZpiMN24TN76rU^!?=D+8ZEB(xT(G0`;G{AGc&OJirl*?|R8 z>;RZEK#HXrlTNEn(jLPQ*x@j~W4Zc;c)XYkXMMfoytcWH1)bzlCk_UZ1-%9FX-HZE z1yhQQ={Y_V=I0AHo#K8(E8fd4D{-kq$df}h_oM#Og{Kg0nSUTjc!ocn{9UBAdq8ZV zJ(B2M)MUmFU!OtiK49Sza|clFYfGlk1aNdlzp}%;_eP1)hZ~;o7U3IN zct7;4jDeKm$!=PTg0j9~L2{=zA|{`Qd^38d+&VNjtjhvxyQYcOMKsd z7!+S{^%hvs2W02v&ADjk60lm}Gz#4gSTxm%tlZOT6z38zk=}iJs!y(T)ZBWf+@Y%NK6%c)v*<(EATR5?EFeq8ymJ+~^T7AUweMOA--P}XpCr?mi ze+pSaMM$IMmtA_fL}W3sIVPY!qX2`krUcwdd+F8mNdE6GCqIt}W`W$UJ_3XEYC|D&0=o zy{!k=OB7vl%s##a@1)g%AxK%iT5=xS-dOGYwFj7b51Kq*w+TXw376nsmnFY`u5|rE zHjCL)b*jl!xERU+2qnc53Sv=)&z3Z{@ixLDWXttg_4J2xOfOUV&o&kye~P(&&n!v} zaid%Duwc9O8JJzVO53H<>IAvOr4cvCkRGVbh46e`MCnkT2`}Nb27_lKd7cS=BNo zb0BSXC@;W-kje%;>$5xTMYGug&w3f5x27CVMOjO7)puXK5HV!f=YAN`4$5vq%Ic5x z=Yi~AoYRX=&mB$!GCoeeF>6*{6+RO1!|TXBE#KZN-}H@hONdx{XlS(Ya@?@Yf}~Eyc6Z@i$>?@;kq;U%WpCV^GP7g5c;Nf1Rc%FgZ5(pZ;J6T(dbbc$Ex#E52=~-X;A<&!usoDMC*AJRK zr)@C*P@?Zx6a6E$5WRtAJoOpv`~?RwQ(Xp_C;E140uWtKMb?Rp?Ky$Mgu(AruYVx* zY+d-HCuG&|S;7D{p%Ohi0LG+#*{?_Q|Iy8=8)N;~yr2JzpQK`dK~gJa|NcpRqptwr zdrST$G9q5*V&w*|DZ21sO#4UEWIjKfz&i1VTZ)&wcmP{RP-E#6CJVY&Q0YYnj@&^L z;8(2&9F>}8Q4f}Y-Nv0@tJay@L3e>z^YoQ*f#9q}Nan963LHu!5hY`EZ>UcJ^AA7Z zonWDgbz<@JZI?btCAH$s>Pf3fgWkDLJop8N5(dV{C*PE+C!(Pu8bMz)3)$qz_-^y~ z>_rA3lQiDWP&<$GByf3}ksdYIXSvUcOa;P2-#AWPDNx?#e{ACQEsA#Jjqo)b%}?qz zQh0Ic=~&KToQ~#_khvpS`2Dg2&s{C`_;$L$P{Co|`lL;Mrv$mC(jN?|guP)eJRe9UvWtJZe}OH!4to)q+lS>N`4tpX1@mX`caY2zRJL}Yrht3J`uKWw zFu!{rA+n~cHp(WC*AB^X`l5#eg^;7sThom-p=R|n0ax!#-W}g{ zwXLbE_OKyNVxtZ`#C7XdJw;$dd3Iq7E}9x z7jDiP%-sscf^K8~X5g~w=xCU%k;kxH|1Dt8m6qxpWhav$SooU$AUZ zeTP`R)SfKK{${H|cZnu4-DmEt39(ndNXEZg z-=P%sc}_)8FtTIwasd;{9PnQ@)9%5lPpAx!a6GE@=J27YQ+SlF$;iGkdgiw!V(Kd( zmMFE<`q3FLMR(crSlcJjoh%(V8b6C$Y*^N#u|tApnyJV4hZ+p!Yh)HLe1bg4wZ7~u za9x(MZ7%5k83bSWh@E*#VJOS9-dUzH(5HkcHh*Wptc>=+n<^Mv-G9OQ zvoP=O&jq8AMu;=j9!|9!I=Ts70eR^>Rk!=*nc4Gh*_%{mAN|Byz9Sl`$LhM z*uiI%57U?5*xz&zmgePtRa{20pdHs0rOJ}mQX8cMKBN2zRnZPEp_qwwLju>dO74#4 zvYV;E+|3rNx5X}kchdWVrH0ruF9~zH9&`2-ZiLh1>XUh1*6NrM`erV{!ETa+N_UN$?NYMTbIq(4= zOh5WOrJBdJ=$(H#@@RYEYxDDfU`3bvuOtRt-tvX}N7hD^y0%mQJEQ9D;9*Q?FL6 zJ8F_n-;xb(ki`e$wh!c#yYJerkH_!WeK!>?Gtg?Y=jA2jtdwy;P9M>_L!Rog0SwD% zE^xzMEl+B<4lG5PPKHaG6Y*@w@3SU0uJ+Ll&G8-yBfp#}$pZ8Cyg4`J_#Ukygxw)Q zIlJ2{%X$eG$WmQRs-4**#2u%G%s0Z(}(t&TsUS*NXA2 zhYO8x^RX&WMYIEQ5Xl9c)q!)zqvtkH=_j3fbfH>0&%>}~^))MVCE4l{_T}6Z;BvYu zy}tRI9LNADFZ6)LEvk^YL5LLZ#P_Ge+4W<--My4VVO&G{$v?SaPGh;IdXNj-=y3L`CX3{Q#D+c`+DNHN@7`SjL}^szVTnu zpJ|dJO8mf448_yncNIjODt2b{7O?9wqO{18$-DQ|rVfTjnQ%JUla*I^z7-kKu0Ujr zSMJlaEUVD;0mBrRs6Hi>^D!(j!wf_2JB+SfZce<-+G@8xc}*&b=1Tn8qIvlz`HsI+ zlP<6owj&7kPJ)15?r*Ok3=`C#b-+Dj=?v}>lR z5uk;~AH8Jnl#J(5ak_{!?G7%#hiM$AO5v{lE)BSpbvAUkI7Delc8{ZptS?mmPTnHo zSphTJO`IgY_A=na(utJverc51X5O3P@10NIG#MCnkEa<9f|*7POv^x7?9S6ML%#`K zp}`g7b7nkC_`cM$RKt_ED!!)uX~;T4L1av687?eWA8wjxdbf1=TzgLDC{E0zl#%1Y z_`sQZ4{?)6jkGSal*hpPBBavt(!k48?SWz{o4RjNr5Knr8h+t5$0?|pO_ZGeglDEylKf*=kf#V$~=Yh9t@L>MtpK5>G zU3Y}db2IYVD9qasq2TV+n4Iz+X{^YcDbduy9Gpu^2Hjh6+j5q7;NE}MI^O=47s+x} zu3jE_^;$%usqU=01lE&`c)dZ%Cs ze*)r7KJ>;w4;M{v@8bFC12j$&>;$CFn%Gh`38PHNoFU(9rAY#&b8X4IU*0nz#EDJq ze=~1IlqjCdz9h^9sv?#U$vWBu=ud6Kg03v9JwT1+=~bTz(?tJ^Z`}{@ z4K$ce|Mu&|sDv4GYxT8zd@~CUa}Vm@oB1o!e5LHWf@v31tfot$pmhw|b2q`xqoxF4 zvLo%L)cvV~#!Ud#$VfeQFA@?pCuC=KOS_(1z~b0u{=?WCN@MPe*EgnUws65+2!30D z)^H-bdwig_u74QMw{Yom^C%@CU#zv&v}lfGQjfHE*7acRZhK(|A#P&@Pe0>iSEywk1%~3ttrZSxbPpYpQXh-E()4resEcX+U6=!?tn0? zos6fHZ}-lEL1ZQQdoU)dCrP6DQK887@BRIuKl|o`$2(eit&Drs=~p=$6?_Y6bI8Hl z`{cK^Sarbk!2}9U+(O441~r>iBSRg>8*BL2f(kr6^(g5N&$mYxg?bB_H9lQc=G9N( zk5JRqTNl;@vFRM8YOGF|*8!Q)ldm%EOupEe%t7h$-4WrYTu@pZ5F7Si`$7px9Eve? zcKKV}lL%{okWFjLloNRkIis)H76x6WB$8%0ymnw(%3=xGewSYpJrnu)z{E+DTZK!<4MHi6=1QesywC)t{Zi<`u#D1A-RW zJ2Gr%cb6MJd#}dj1|-@?-_F{CjWEBrh>VW78U;3a(0tzNb|;G+1g~@=Ix?S^i) zy~jNz*NI79sbfW+CyvUagXUspd}|`;b%m){fII@87m#(>c#chjqe-C#q%eH^pZGtY z@jcH=6X(AkFXxqTa8h2er}Hh(#|96NKmza_*z?po?Z7p1n|>oOz6=wBgS39+K?n2> z>35qaVOUBYCNH~^0$rT5vDa#%Ff!e`;3wX~2jLZl06au6786vrv0@NW;k+SKPNIyx zFKpnHTkEC!QoGHmS&*jWD+Woc1);C3qe?1|-{UUv(ss4Ojyb?MAj)$e@4Zxst&vBNe=a&#Au68M3*>nLkA{&hl8$ zG?4ZQh~CsF>jDN;Fr3t2L#D@!qYTS@bh#U5{>;^w8Wh}{7MZ&DAU_z>lxEXEsMP;O zl#BguTCErDi<7sY!>WKKpoW$RRvF!kqeMMcWSvRt*a3*;kUppV0wdg;J@(TjP3dzx zPrI1M9%J*l?}{kwExTI{LTKmPeF>eZXs&Q!2RK%o zL#Ar8iE3wzIw^c3D(D&)N8}Pi5iw(ajq+ZgNkVd-;;*WOYr~*VZH&sXLzBIWE z6gSQC2Y!F=`GmsniVXTaf%9g*_o=aH(=@;>>9e(1@_5}Feeqc=7s_NZ&nZw@sSt6LndkiTQs4DT7sd<&w`NV5#qKL;|Na3__>hNJ7zIxQe62^riU`?E|MAZ!^{ z&fN-RvFra1ui6h3_;FI>`Z@PJZu;g@Y3Xa)wkwkX8@J#Axm4Eq1{P)ywHW?lALVy0 zI~}z|1p9V$Sf|I$Kx zaCQB7CNF+yjEWP^ejv>YXZTKyJ8iTa>9;b$`|9S4(ri<2G3QF9-`~E0ePuJ~9N6g1 z4A)zQl3A7N{{FSxO$B=vVLy+hfX+UwCLmr6U(_UX9qq;YJ9eED{lUg&WG%PrNTB#jDD6GY5I6TyNTV2VLls)R-b_7qA1IJ&w8! zW3J@G*cw&E@}cY~vwU002A<1EkGLHZirOu{3pAX*HHoN|X5%o;QdYg=INy<$;0db#Yhv@0D zH#;#Pmno#Q0J}7;x^Qm{`JCQ|oIj?fZupzw1NR z8=Y{j1a9zi3^!_OeE1z=qKlxMX6V`t_2*$7Gq0Fv!+gcYKjbjiE#4*#>0h3D#jHnr zI`)cs4H&2E=@7Uvt#ZPPyyJA?cD~ryZa@`So8XbW4%|;(6b7U_#@+dKDHF^^RIsO1 zl6GUTmr-z1Z0e3GQy8oZD>C`#E5=v!dS`1>eM9S{%G}Fbi_eD0Vu{r~0?ps+B|f(L z=YG(Rp&o#0dl(537udP!S zSVC9a*>L%j5^!h8ILxY;Jv!L9JXY&leNf|SK33=V=Y-pPMlxBxwm7Lj){WHmG)T5` zv{7)3j_F?zl(gH!!bFr6=5NMMQJn|@kphVsMNSSIT4CGWYB9Lqo0mjWj7*BOQD2O5 zxruF47ueiE!&Pt>o?c~_%|{oeRs0XcZ_~hN^6?*ErR95{J37?%=VcXp&L}r1*_);) zzM|tRWQEy)Nn97#wW3#2%GEl#_Iwuq!T>h zcq8qk;u@0Aw>1972ch^u3$`L1(_>?lA}Qr_)wTuXI;~mq(NIIItopV^VO}j%9baAZab4wx+Ses8?8W z{C8ma)Pac{p)J(wQq1NLL#`+D`odPhE)$ve9opi~&qD=v+o2${Ot;a=3(`y86jcm^Eu%5eV$ zAklby7sDPR)HB*>D9Em@^@eaSmsYt=iRLr?B@nBSz%OFvF(x~n>v7rcvxkUlP}Yc>IKw1@cT?uZgak$r}SVY9v?raPvRkGINJU z9ayU1OcDLX{2_eshy6=~{jBGez|-O`5e5n}onqzh@wClgOz%(ls?N=w(B9~ns`*o+ zwH4C*xiy{l$BmTwTRnOTHb3K-K# zEl>Medf?4?gx`cRmsm+!n;&AKByP9fMiG+Qhi{DS(K`okU5&5S?GV$tID*N?RC^y? z+*vFr8qw+{mrhUlzZu)k=kdGKmuX9h%7GBVwNIx`g@8xzQHD`HR)@HPM5_EN1OKN1 zrdu77<{fWtj?FnN+&Jt1bwkAn@rHiiW#0OEB+VbXR8$zDE@n{(&50}{61CYH=YATn zWHvSj^JH6dR4ZI#R;mO3;{hT#AG!!k~ z(RStGpm^m?_xMM_#`td!L~h>ia^Z?V;VZ&tbfvLCAW5&63}kdUGJu9g$E{cMR0Hyz zf@f-}#RJ~{VpeIq$-UZs@)qYURn{YVU}rOLK@QnisJ_!E#iiA0tm3>EE^~UdMJ1KR z2hUoVbqeJ#?v_X~)t36zlA{T+k4{$$rk5+pKxgkmSTjNMXbhB;WDBIr)VRPCYuu@t zJh4UNwR2Wlm7=#OF$11CpJZ=My!&wX!oK?B%W-rJ;ED}4pH*RF1$`p*r;}vxT48s} z@Tq~Unm1D*oQq~@SXeX(VY)K%3AZS1o2D28iw)B_FVr$X=GSv_xD0 zg`&yG=je+Iw#Zohj!8eyiOcug{w-;^%8eiRC7KVwQ+XTGQI z+%1vM$wg_jKEje30XkL8OHp4z#m%_NzjqD)E0#-`fUewl{?J#xyu$8h?*}(npi=Ld z$Vz)zBS^h^$?Hu79xjOaAD_>_Psa8S+q#NO6Em;VDo$(iO?(%Lfs(kMqq`3eWF$29)4YzePS154>V>7PAb{m z*c%pf{#238{*m!paS)AY4J6QtzbUseWZ4|s+>(BtLFLI%?U=4I=8Ggelphk9QcI1u;J6Iv_{i}<0x@o$fU~+cSzUfk)33SQtbP4i*U+>H%(WbM~KtN*vMrE`q zS^N0r+_8Svnc4473Of%x{yxjUI98zl1$3r;2cibBT%_4(l;yJai3iS%u4iU)9zO!V za_bTM<>1@2ha?5AJrmjv2vR=x*bb0)Vn$~7Vns;72`ZdL>p3^uj{+xtESd*%SA+(; zKVpWueSXVNw5=Zc>z?hMqtGivfM^%cQXhkd%3wGY*-S`HM9~qq@^pRe%^S$-6cm^) zn`R>Tv{Cuz!+FEin;uc9J44GOXU{*xKthH7?_LvMup^9Ala*1q)vPNzX=yYmx7OC) z&LcHGXF$Io^O-LC+OY7#I_(;0L;@QrtjL79o~JDx2*A(Wz(-!;UyIB}zv=4-8nEDfTUpm&ljZ)-())855sRSvA?URL`1UazA;a{#NT z&yl#r$v*_Uw3lNEK`TCSW4>SZ?6CQa;w%`+cuy$!MoY+Y^Ng%}IjnD);EKV2N<;a#@Ic%xzJmCl()#~f=a-Qx|-(t&t=~N78-=QD9WI=Zq zUEz&;@VR{&wo|=B!|2(X>7s9b?QOrb`Dt42%A zs}qN<671a)_=qo-J=t1JvF_SI%aC7D5&A5&M9&zVYarzY+~doiv?4V%2*+yS8}BmB z#eQt)JpThByLq|urC_vnRFd;~XV&jwmS#=un915e0WSk%+mbnx@PM$( zmrPa+BpixfemZ0N+2!eZ6ESdVkx0lACK8@oQ5=I4hlzdq_`r}>4AgS7{-H5bO&0%y z-+4VPCt&=;?fB{U7@^`w)VH1f(A5ahT*tAU9nmStna8dl(_vTT-C7Kji-(d4@m&vF zng0y4-PPxG@M(2OZnOq-!fHC+l|GQncfauzA8=msZ2n>+&Hl>Tjv`?r06{wsn0{H5 zCaWjtJkqUVO(pm$%D!)VtFn>9RI!pC8n;7?h7JqlJS@;s;Htj@(cXPY`JHwP8j_X*wnw#ISKBKXE=4Oh?agl3ly?Sg5LO@v649f$Sln=d;Vba|EyN?LNTf zo|s|Uog*d`hMzuoV4$s3lm!u7dvU5-9#3_b>>0gC)dYvgqaIT@d}izr@qJ0d6+ewc zjKs1IxvkYNG~Ar%7FHt6j#xHUEa(e2BWl)XgATKUT036PG(8^nSFxraq`8~L`h{RD z^lTzRb|lOlA!2y-7yHn0P)Yigtl_h~XAeCd2>$|uSTqoP)cYh@1XWZoC2%Jkf6D%$ zPOh3|y11H9E7_8=s3KtQq;#L|xL9oIj2CSLsW)xp_%8KPmZWw3DHN%gIrd9ID>a^U z?Kc<#bLC%lDK;L!p%AX64kB|Fqx+MkP4%-VZ}>GYpSr~lP(^zT%YCSjKjqz)x*5sZNAt#Q0HHrH}W;C4gGJbq!QuO#0kA|$pO~KZ7to_OO-g5Y>z3~SL8op0(%Vz*M$djlZy5h&#mb&$F+z^i zDN?Zm_ozzsEg-vgGwREQty7rsc5$RFqE6nvH|MRAPHCn{vVy*$HLOiMTfiLm2>rr* zJltsi4%mzZU5qEFg45TdjdHTGk68xmKSj>Z4^58zx>>P0gb$gc&C=kL%t)BuOAPq$ z%OgAWCP}^51`M;&18wI5FxJf@Y~FhxVS&yul-Y-oGQ+EwZ^Ly(64~6}$-Lbz0+SQXT9gVrn`@VDo;@t?d*3JM zLoJhWH;;$Df6EzYoKu5i=kl@SgxGB3iPn%)j3uDFb2lWto&QDtj8_?ZCe2P)llBXD z4>~_hF^HFUKIcgZOjmrEZ0R(H75M2B!RZio}T5Uwp2RQ?P+w=_j;nxt=~)| z{MIoz?L>6L09<5VM&RLqWG-Lo$fe@ADGj=2pbFG>lIs$%99z$O9idI1NY*KS2lYZ7 zQ+t^2Zvw(@_0z_@qzPPey7BGpkIJMQN&5F__VxZ>KjT)u48TIHfm;9>{@@F}9n=cy z5vdo60;(=8DKZu5ib`gAO0gQfBTr#LX?ezbd+9W+LO zx{fdx;_)$0|EWStOX7XfO2@a9b=@AJ+>%MVc(p#UV6~N(ce8LmU1)lci4+ZT#MG&n zH@`!63>d5na%bkg{_1g{(9*$UX3bpBwW+a{b0e$jm(S&yA74vXBQm6o#2=VII*#>G zSAm8lXiR5gazRwJj%p>SNJz%PCl;L?=gTTe8w|V={s^H;`__js$5LLuyqBd{-&OsE zx6sZbbm++0Aiax@7ghkY%Rs$>Fh6;la+F_O2$Wm5ju+gXc4_hnpi?-1fCbm@1w`k{*0ih10}))a8Mq-xIYWl7Ht!cOR}A& zYB19L-`$#8o@DLYRX=jP{=x$}Bwlngl9WH3GQ|3I`DE=WDf=!5tG`xK{%Ixr2(k<=WCy1OimGAGtC_$&%H z=qiC17S&{3X}=w}Xki;aKTmyHrSvTUt)!i;NSc`~D8s?IpvgAg)iWdkU?&QL-h;}uF3rx0O!pcveE|vmMhXR5}PzX#oO3l->jc z6qF!EK$>)<_aY)4q$i81PH?tj;uW3B|k|`KKqTSagIaVz|Vhpl>*s_c_D3Q4C8fY6B zci4)KKUy3@17=8W`B?obgs9QAPh18+0dmfrUelAoTBN*vd-4cL1QV^Sd~nEF>{fj5 z8kKvLqPf82I5)3R8AnGu$sEhbM)0bbp=Q`IIuLeWNFdtAx77&h!?eQdFI(csju)z@`t`wMm4 zKDC}tS@Dt!El`AWI=Z5s5IkxB#eR+#Xp*V6a{;Fa`tDUsd{bVnl7)~?{{I7jqP zmf2^Thuv^^GrIF}5!|~4w?lH@<0KWSLPHcA1JQN>W-N_hLcd*fc)XHRCY=bc|8j?tw~NOCcCu?@--6o z#*^~^7X|+phlG1;td&TCz0HpC>YQ$t7pH1sPvfQ2XNZ|#iEj9bri*BA*!c!>7Frk| z0C;zG!03nFDVOqR*Lr2XmAsTbsA#AjUlKJezs3qG3GzL63-Ddw>%@Rza3F`mHk8mT zXpM#srQWU@eDv*2j_W~P$k#^=TDfaA3Ox1|(I+e(ox2hJU}_qCg}I-b)|2FhlZb6_ zQ|Z2XeB$T^m+b{Z`ho0rjHja1eyrfHl37{H2cEpT*M#g@SyIGNpkSX2rhrwrOMKLh zYs#SYnmcj5)!@mgqJFhIH@zWj+a?JK4Ec|OJK0~#oBD$wS^59dRF?>00qEuj zm<74x%Vadjqb*W)*J$4>E0EpD5X6}#-npr{IrNqBE%!$h^~@fj zQIFh;lo@RRKCeLN;-9|#0%*(t5i>R#bD}{LKa1${hiv@9nGZUQ!_KU$nooQ2U3!>W z_tw`8;}E5vY>KF=ygTRjXal<9(*t@*v(h9;^vTPcMBgRRwhx4>QVX1D+xd<~R@%m! znYV+WR%;bkwH7Vm+pL7;HF4|M(nrjrDWs>lSoe(bN!pUqDf7 z0N7y^>3S(-@KeBEFNvZ;Jcsqg>su>4tSJ!8E!NM^%{Wnr&`4!?EMjJ<))k-ZbWKC; z05KFK>6XUTVR$;|>(oS7bTjQ*5Z(BL#xnAImx4)vO#FJ#QZskXwM+-)!Kcurk*I6x zli1Tr59%4Fa+33`hl4JZwlVP`Mm+M!4uM%pv8C+=O;Br_8MOp%>E3r^c?~!8U&T3( zWycr_$y3%f_*5r?gP;^EQcWi$9D6E=e@&1E3-HU7Y}lFf+f`sZarz%V*TkKlnsd%} z+BvwOcOhF!>J;(dMjvW}$7bhux2$Sl43(t09>)dak(4?QsxdsTz@7J9~;-0T{Fj9e|YMg3|}@%nTe zx7*-kb3tVcyGt{_oYGNWGI8l( zA8mDuDq24((r68MU2W{#7@TQO*5esXnfb`_B^Zu#YO%T6+QfbQV(UHmw%05Q^_0-p z1vndUmvDF}YP-1a$r~w;JS{6tRnalMXHTQS4r8VE7cUr2{sde%5ctw|rmHr@l`fxpE;u zN-|e(hU3DpxhP|eiK4~P+>sR(nD7&Ka1VcUrFI!olDn5KO_BSTGZ@hY1*>W0xMT>8 zG@V7AS5&vu%`dSqm5@vPyr#Dq4O69laHgA<{l<`SJ{Ys#!H@wsT#(Y;y24oRfD<7yzXxT2~m z$Jy?cOmSUd;WhHCbo*mkJ<>$WzPa*z)#+Hme8`+A39y!7U9X-Be}UG_MOked&wePb zN^JSG#?sO2TD{3Jn0Pu-zT>kgM(s4{uzCMYSbH~?8T|k^xeMX#6^#ApoNCVH4-HSh zOUrfXp4iY-FWBhkZ^_1BO-4I+4VB9rDYmjJ$ws zwBl$nVFKq4?TfyX-sXAbZH{@E(gW_PZ_!W7-o1Fq+=m-zNw*0ATF{UxC?|^H?pP4_ zjSQtxuOlQYS^7tvcg{$2xaf7xbV*Ek=haS(;*;BDJ>M$6*sLqUQIyVemum{8q=K29 zI;c=`AK@Ke`^cIn>SqTWL{VQD{ajv4T6yj`R#mY3GxtkYKtGRN)bh@_z%{K)zsl&l zSzkS2Ed$L0X2@N79LQMx(%DN6LLYW}(`E_$DcTy|c_lV-f;j}rv9yM5#d-wOw zUkZLQXA|s`^L9dlHBQ3liRAFx>41d|By6e=Wrtts+SIpBY9YFmy8C-g$MRe1i#I+G z^-hti2BPhH%uVh-1LMzwXPacu+T>VLeG8Ty%|_J6Z%5xB##edm2iiBM^k%E*!;!qPLNzz$0*zx!TF=y8Oxv+An_b=lQ{P- zU%wb-erH6!yYo=&;IW_Y*=+2&DM@?ZGj`t-FFq7~nSXkq3ln0Nq71DZPr@T!z)3oN zzBq%YBf3LqwPEWyJvYod%}trCm`F#?m!aN~`pHu{0xf4D1?bcJtkj|3AhyNfV!;W0 zOxPTqo13MK?NDaKJURU#w}5Gu@MC59f_wLawa&{TH&q|IH`(|Nf*JxE=e)v6lx9 z81@1rw%ag?ObF(0>zO48z(i;O6DRf)$r2?LZBlnQMJme>hvBx;%10#`KffJfIR&`F z-Y%0)k}r5#R)30COqBmVFK7dfFTyy)A6`KM4$GD<7>YkYLvw>p+EL@I0dHnbE5vV* zAizT7?f%OUE#;3PT4+k@Z%}tWz(Wfw16-7TEHwe9&XlID{81BhSKN^4)||-8~)2Zb4CHkp9e=# zk!@6tJi11as7$qL4!nJw)RpFPWH6E?s_S{BRf^pX3|?B*;F~9o!^^vm`D*~La_P!u zsybjSt`z@A7_1}n$L5?tMh=)r{_!PevOAK-4E6o7AaCo_{|#Cg1!3APsD04gr}Kb+ zc{xA>Ap?NM))KaW3z4_DN$vgAr+y+pxXsEuTuq1MWHGXbskR~Kb(~$B82@E_j8%29@_rc}r~R-z z43SQIF!wqWqVdmi(SN9p|NZg-Gd`|@FV64D9r2=te}f9nrCK~}er7yG)hPse#-0g! zplkvEpDVhkO0GDxI1io#ffJ)itUR_(_nxnjDrK_d*5GeOZi@HEfuU%Wv3u)YWwqJ0P)!52_8J@Ln!3!Q0! z$>EWURk2kJ>Z(g6?zq|uDn)n8g}s>GvSubs)u?5A{9QC(!K5kI0A?RzN*|X|PvYwq zgc3_4;m;@!TsYqo3~n>2(mS~UPe-+*{MMJ;FI^k#{4Zmk1UrL2{dXur|K;Ak|GxXd zf4N5i#LTO7$bl#~k8_%o-I|$!k;QKihx1Dmv~@pmO^|OCH+nzHyO|_aX&@&3gih&C{CtYn86GA?o=MhU9q?rp=>+XW{2c1D*Z7Lt8 z3Zd^44a2;p`WzanD@l+D=_2vknulM?v-Cw$V#+Tvo~FO6(3;6S&@L!Vtcl&_gR+wq zI_k`t@zI0J)8<1+k%p>Tx{dgyem;5S32oz$$0pBv6luN!7IZ+lkEcf&-z3dPQpL&E zH;HBiyao?S=GXQIrx4j6b}!x*!(ywNxIhBoXD(>qwYEB=VPx${USI+Hy_9P3 z8wC6-%LB+dhl#Gq|4!>WL6tx;+#!{uf0!jZbsWI>N#o&H8iuM~*XT1Eb6gmjwe~Qr ztx3?+iT(80S5z!2u0G>VBhDS!VRaDh?m@A^`zb~qL~0V*?$X2{?GhI(@r+*=4_IlXgc>pd0)O&<+)N%<&~v`XI!@r-NQ1) zG*r(UXtL41?dpEdPBUXf%ds#JK|M)+kfjpQB!nuwJy;n_5KE)pk9{J1RMvs@w}fa! z@I>Ok8oWUe0K8rpphqFP1-a_onwe1Hx2wmz);~lN6s8S%``BJR=6M>I$4JAocn0(% z|L;=(p2u5mGHL&LWysdroEg!!oS-kCr9JH=^=MHL>e0pBYj#-(7Ys>8OJz|E zs*W=ir6A#|0I6qtTbQhbU+~UHtxdUgzvH_z`o@RPG2(>0_LJC5-(DfXi4U4Us0_T) zeLGyKInvkPFq|TaD`j@`&43asIf;|5Y03Rt73}q2N%|LS>?@4!*qh;*H{vwZ;QKZc z1Ci8o6akV-CtqIxmeUOiID7cvrK0l}A{|n$UtKqNlzGasPx-Aq%d?|wD4#R9oOHVe z?*c560b1&}xeN8gGT?W6y-N99snA$KzWP$Kj$FxB;^YTCA+r5tYr+r8uqO?afLOGB7*+pbF|b=}~eZbQ$)v9P`mIHC38s zz}2cbO3gDHElPezh>zw?TvLtj3J4T2JaH?<#m>Gu?JH5sh5wKYo49#y3pQy77dr5T=$o*&k4Jt`^CWRijl;hoU=vl%U|lU3$ud# zbN`hJ?f1F$n>VlG^;RQ{H*H z=S4@3?e><}&pZ?1h%3@;-R_a?6G?KbsqpUK2GKh8N`%KqhKN8*%t2b=_Ak54dzri8& zQWN)FgTFb<3la-sIFh3X&sRWO8W}dm^*^*9$1kK$8=f1o_cNPCH#5iF5KA$qgBcB9 zwUgEZ&Bbl+zYI5PoX8?G5&e|<`cRLyl-PkcA#zJ7G8dKQ2geJ}^u(%de7w#6Wf5dq zPSb^Y-hyGHnBxQaS_LJJlQ2%l)~$8dbOZs`6imJ@W5Do+LBuDGIey8rCN$>vxxwHQ z!ODuoYzrQtc_=rXA-E&vSzS;PeloTz-oas^@cV;dhfBRIiIZIInb*3mEMM!PnU;!+ z(F9fP%f-VCCxM0bwu$~1bP7H#h@eQ+Ob5+3e?2mT;{|~8X7kF=AnKN98fbZm2ua2;*IDsrNHI?|XkRq2kqlc@^a63nNgW&{yfl$VW_;xa z>D}zx5J^U@g?VT=%~Thi{O8u4?19;PfO3K&h5ihR$HnYsRMKG1*EB&2|rw!%#H;_Ej!5<5w8`00yR$@_J_<~x_MWP3y` zcGtFn1vrgw9sCBRdM{(_jHpgzOu_+_#PSpI>%edeK-JDY22?c7PV+Hvwje%$^OR&q zs%Wh?gGmo=DD^yAAqSuaJW|b8Rl7ReP|{f%^!)aBj$^O?!s4l#fbS4g={E@LMP0@0 zI88UxG;tx&d}N1Q6s<8yjCVg5iTSvu!dqPY+=XNyv;W=`-74hbc>beD6v+PJH77Nk zzZb5cRr67De0V3pDW=1uV^r_v)2BXDo3qnB`@9uz&x8A6;^Z?2U1q9|@9_g?4Kq4ILw~E%b5gyEYN;)l9nWT7_{MdjFZHb&5J5u*@Gy~&*gX=ksb5svKy)=SR}hc@ zcb_;xc(<1qQ5CDau17kKaa4zQQMu~^vIEf_yp z!hq~TJZfoXR&*;Yd3_=BcKDtg( z9#k_R7}6Oa7i@H_iN_sgX)lTM!IbO8tuAUQ#93(rPbUXyaZ2=Su?ze!#qI^8GS5JX z!}H9|KkogJUx#74pp@c27`HWk;+O#o#0Za&0d_!gB>?^Dqk*pYy(gfw=EZPhcB+BR zzy%qO*p)>C8$`R|0)%QdNCN;+6oX=tVq2G_GM z$%ZS02=TbJ?mN0EsFqPjveY39!2C@6kN68J`Lgl9$bSVCChcT~SzOzkV=PO_=BtX(lV37foxv~vuU`ZI?+yBITz^hGmL6H6 zd5D{7YZ;OlesaK#pSbEI3zA$r;GLwbT&h^W=onC+PKOV@l_;{EFsAt+Ndv0WE%vl4 zv15&NnXx2X_}LFYJVCSjzZO6IXHX(KUH+tJ+Zqgimxf+Uc{e4UYh&p*=%FA`Q9h8R zeig!il$R1YY7-FIcGIa;9~YmcPH0HF-irp@IwY==vZ)<#TFh#D$Jh}f9J+G>XyFi0 zY7+QcC&g{>(5hME$~B-;5h2epJ9jW{(4+I5n8PTtf3SL&yP-i%BOotQVgTetFK;QA z-z*es@xG9=R5pJiSeQC96g21#ui9uD7xlXZcQ(MYMAf^0dt6kMvwQNazY(~(+ADrz zeiOTC4c`c?r_QeACDmLWc=N7y06j>13D+FK3yquZ61@@iLn3T1(#!gdgb9OMFQWoi zM4|GJFW+8EoP3Guq6a<4=XEqQ0`}%kFVx)dpXaU`vN-SiFY69$KQPJ}qF>Ot zUtHDoxWnnaI)KI0j44jn7uNIHXivFKUpu)^x>ZDU`mjeUh4lwHRF~$=+1jj*r{(4x zhL#>4IXmejLJvmyOBXcwgGvDpY+juhH9nlro2|W4mRTFi_Wg5FH!4yXoIXE!@-ysK z&ZE=piBDeAD$-2;rC#bx&fU*-Lwch+W$+meI`3-n>~G5!AFDglI00AT)@P%-a;G}l zsP1H|o7k6fgSdM3x7F(TC$4zMiU3qgr?E#1jVad|eYRDl8lIU(ostl*E`RIY4hFzC zVUj4I27_^-tnZP`BR=>&7~ZrZ?H-+rELn-Tc=uuKtnYoSk@^qtH?-xECgvf)|IRo| z3~w{!Bd@Ku>4Q;G>utSx(*DK;#L}&1mL$grPrbo=V`2OqdH9Ic;%h3cBp{j1EB!Sf+ ziQPA%P)qu*bV3iQyeHSZ=iO}sQGu0+_F-9=^BN2Br_?wDJQms>Rv1(j6hGR>vj=2lf z^$jC36UiBTNU5*xv$P5w?B0*wI=Qsa0zq31G6ZNC9Dv6*evy*!K}oP&Ckzh4thXR{ z@_UK3RjgN^!%<+O7vTJp$+56`DL;m?$_9eeQ)CEO2x_{$4j!#0S!lf$Brqmq9j(9a z_~lmkdXLZ|hY*KQ2+c{O)5joG^TvFp8;tEZ19pOJ-Qn+5Ehr2)^Jlpn>?;HdjuWJ~ z?GlxtbLM8Wz_R#<%IdU4q!8)U1Yiw-IpeDABX}-xO6ybOsC(KPox}wn#RRGMUQ99h z4r0EUka!9YNfjeN9fdPhLfD)Q@!OGeJVdVO`x6w^Ee8u;1D$qT)6U9TLGK*G6<$dV zp6@?e?c;73K|ZQkF9a&InFpO6-nyT$Z9!5l6im+hZWSu8dn9OSe?^Fn5F(lDBasuJ zZIfVeB0dJl(6DRS`C(Rwvqw7AeqK}UZTOVW1(}=9Z8%}r2JRYPhE@Y~o|LZO7 z>nrTzGteFnn7($Zvq3?s;pFaI=91^O2J@(rx{6-4N?OT#cL!%WWA&Lr))W3rUp0C& zPtUH^*@SdWOeGhW_oxVGIA|<9EzvfFD`Xy)#}R^|f%&V4_EJv@5YtoE6%idZ@_Zu|8x8gPUiyxo>h*QvjKpQ?bR3=crDS`i z{j{fwXui*q!zPaS?u{w3^KOp6WA8u4<_@s+srBT(IHP~ck~=u_(w#(kjpbmrHe1O- z$`d>gE7;v`9mtV4c<(U4Gcz z%60dmNm(sGy1%%}9U5ZX!FWR&UBRLO`S?$BdGH@j4g?Jb%t--G&U>^r5gtx4&C&!o zIX0bn1BVFR@*+>E^N-6_!@xpU8F6WUI5|np04GNo3jhY%s~C!7u!7z3 zn`V2-s(}6z(8(j*&-L*X;@mx#0=$9PjONK=5iP0i#Vr$`5N|V4#)psTFFd9J=s1k; z{%{#8DSx;OD*6DIK@m96NCW{~26s4sWX1mBGW3HSCxgDumviQN7k*!zuQ+I3FPy!A zcbD7TY>>?9*;lB%^R?`27OR~n`;acjr<=O5L(hcxRbr{UfVGV}m1o{^70aqdbEHN# zzFQwXP*X{gP0n-~9^kyWed7&#`6A29OE0xR`gmk0a2hn6=fCdai7O4qRLn=nY?a2n zIazluA=9?#AcU({`G=i0)5Q=;@tyAeGM=(ZHVwhpf9o^Qq|0se9|>y~TKrI;4$RYL zPaxfw>#Ij{h#wLwW;7YJ%X<=D`^t+Nf*e7i@|l-seWnD z0M2akzJGWk+9Q8}8oF74Cld4L!1o`!xBu_&{g=Fdv;&w*U}M4_De4hFFu@JT5S$FJ zjd|xB%dq397lhej^&nx|h8%5B{qA9HlsKxdT`}TjLVLpCAgv`)3V+ZJdENv#J;W~G5i??{+_Ij zRQWo%8z|49e?_e|Qbm*Z#no`8gg*^o`czOKyh0#!tZFZQV~N-_bvUJ!#uuR`{2{w- z?P*bwaL;`Wp*T%;npS}1wDSm2k$N2APfJb5l`a<@QMGHE4}ZarB{Lf3LSPXGQ9A|@ zaUzuRcDpP7=qv>QcJm-?=9@wMn4XV$$7syqEyz_aQt9OJ4>P8B|$2g=>dx8$Wi`Z3GX0HNA>6p;xMlN;VK+m|SDja*;onmWfZ(g0WAfZJpB zPK@u!sGk2mGu0g^_1Pl(ak|V1--huZe%bV2U(u^q+6sBy~1oDCzf_AR0>xYYcQGv|LE3P{!0l5haDJtm!SA?J60tZ_j z=c_3m0>H@L0KbbMc%mxM*OC~9<%kb&FeDNVfY8^*vXb1mVZM5!8eRcHLx=8;9&ds3 z;uN~t0fdKLKr4~DDi#p&l7wvtDi}49VT0e2>*$STE2YhUDkAQT!VnnNZR5)1zAX^lkskihCXR2GrnE_O3!)gH%R*ScLtFN5J;dVLXE=(Z=eFW^o1S~CpvAfByQtj zvDsvdX)TdbH`|%JRLO;LuSv7^PL`JAwUo&XNJ$WV`u@fI=P$v&h%=?gCWsr9878?7 z#2*U+Cy}n^Gip-Vy@e>GR{i+$V5t{*ON^z@-HksfLL%-rNO)M;h$yh+D=EZ_WdXo; zcC>Ll*?pl|fWl1zqfZPrI9%<=uQzh89o!u)>PnaPnR>SzQ&u^5%XjN$i=B%J-3R9h zM-VMjwsT$c^D1>P!7-jV-)ZI4DsXi{Y-&FlUoXdO%Qq{fhi&Jw@;Zpj6?0tX79W!p zOYJ=yZu%zYQofxAZF_T=9U*)Zf&@4@P_*#abjv_KYUOTabQcVoav74LCMS@S*r|px zmVP{|<{|`nor6=n&3kOrtn=Q=Qlb+{y;Ws_{=WOm?%nlI33FFY6h`uDKtBHf_fwh3gmpmK0u9BmA~znE zH<6secKe^YUFI&gZX7G}taLRLH|f!k0IL3O)ISFD;FV^U>u0EASlSX!F}CLRd2Uf% zb`J*|{dTbv{x2DnX^(WqgB2)2AEx)Q$8Yx-c0F?p-=j)zRXx?!8eQad=(s-kxvF9m zm})v8=7M3O<3Z4wrer*ZL6aEX0VR(3VA#dSO3}X1P>;nI*U#mtCAdNg=^6^$nHo|u zuZcUxh!l!M&}%TS;0~TY${xqq&%#@pX@P79xyT^M&+ra|0Au3P_}g;pck%?OT3ID} zQHwp5&!e{E4yc^;bMVW_UAnZjl&3?x5lt#+6%wWcFl=A5l_P7p;Aii4@c~QL29>BT zWtkFSrng*H6XkSH-#$(3^^I!}Mw5Sj29c1V&=U?54W>tG?Iabv*H1Fv_2DL=`5%YS zNW~#qDD@$E%vdJk>yAV55*@FaS+q(Oqw z5CRfH4ub<-E$i;Ilzy#4W$lPl-MHds85yxRwNV5Mk<>ov1)nbOhwPs~`e-uNpD;c%RGhBtn4Gh@sbCXdjPazhi_GZPwY(&uDeMyHg6@e>KqsdB&%FuA@yPF&5>7Ku+?406fjHemg3NhXiDj zhCo?2yil8HsXQ0eiSV2erK5LG^#f(8HrKc}R_Zc_CzqU|w_Z!Vl75&d?&zcK13H}h zn;rabNGh=8?2oAI4g`M?KSijVv{i`PW^%RV8{7L;S}BYaST6Q-SAQkx&R@|f@=-hW z?ya@w0S~Tx=RXU1vs(z^Ag>b)J1}Qap8FAFd4Y0x!RMDqzM+*zQVONBo%!U12epY; z9wwiVjI!w!{J!Wo12Xssl22bS?1o0E)LmOmOKHxrwn9r2S7IzFa+s{u_D%m6Dy)V9 zp2t~v{ne3~CM?}ApbbA^yC~4E0Btvxg(_|9`h;A%pg>UuhFlK7cFR%K9op2cp4-2) z;T!LnUq8SfLg?bG)JVuad10U-vBv})LX7Vy@{kp~ORu&ZouW=TILT;0Z&PP3-2ha@I-B&O9kC*0+n9mHtn6hn}Q%FN_SfGW-+4%zYQ`SWjT!&iASfrCr%ef&To3CFoMHLcF@EV{kswiq< zfwm=&9N``$wnmj{M22x?NFp}Z_4P!CtE2+*g#%u*(mfQJy}O#@Z1HK@tZ-3K6OgFNmkXG#T3v>vwp0|)VUAI{Q-CjrFoT3O5wIbb64xmMS7C>42QgqP@9i7 zq=U|*%IRe8$6gbA(p48>qGiN>9&o+oST^Z>I#uC);X%P?6`vWAX{66=jf_d!kg}8W ze0fc%&?wqc_A_B1qDIxBD>Kn~aGGL7LL;3VW!%TI-!xY?`Km~H3q7E)W&tgv;XX4k z7S(tKob~B`gI)#zEx*FifGIhU=+=T|^fo-Z9>f`Mn`$*7vnhitrDzds%x(Wn#e74Q z5)TP~rea$b7dTFS=~%9R{QVY;nK^^^?E}tj=bYrDNpJDqKC^+lCC>o<77Y%18sH~o zQODu?M$*4QdmO~QzvDt_RWeca?Q`c-J6`^<3ZJqc^yX1~r{Q;3XFs4)chQ;Z!1oD= z8tNv?_;+5}JBBYdQywX60nxf6fq#(iIJ;rA;d` zt+{l!l{=VDjpIlUEkQbn@WL=U`=@+%FIc~$2aA~kriFV3f=oVQF}mA!>az_`W`f_K zwZHnDz;XP_2haXl1L;-2K~qTFMXV)ptAfCE4GAg!nkJh^;I0(7ZF6QA_bGI9Wh@cw z!sqcc_D!(%DT~7UMzqb&Y07W#{d~H_{b=XvI^|S1j(52qS#O-}dd5N{mUtqc|1C*_ z7jS4geJ+$>K-)3oY78`@HO*mdhYJRu6DJRfRE(~~IY&}=E?;ObJL!EoSozPjfc}KK zigWGX1`5(Mzu%zz(gewAZ%+gxh{A7?!u=^ zQpO1z-N|>^4meXGpTCs$#%x`nqtyWhO^)lT264?m0pZL~gr($^OD2}A=A>E?1v zCnS4awZJDoXU=@y4|?EMxBUW`P{^)Wj^%`F6A|H?EEdz#^*T--&+eFtMCwhQ9^^2= z`D8L=NRp7@6pq~1VpO`(kzl&gaop=9zq|T%%R6gQ`u0;%-76UcvDw(ddg*H+8h>2{ z;FyTQbT&arx8_8jYmUOkWS{5v=BzO+=|LyAhC~yxf4%Z(>*JaEj7TrhY@v-OKi|(L z%i&{vEryf=15B+0dAEIE~-hg#!Cek%TNA1f8fGDdN$WeVfJ0IljFq!?KC z3r(tk_2vS8zoCg^Tu$koPA9_AdesYYhK#v8v9&2<`GtNZ>I=OUccfXnF1vCULv6@; za3j$-27QSHZdZlJpm~a|UFUelM1B^_ZR$y02r-G_=WqbN?(s^xz(#I2 zb>fRpw=Ect%Bkh0ZtM?g4}Up2t57|vebt2Xa?44QhM*=s9(eDzqxQC$$*$ez6T8RO z2yw+^lFEy{;xjS^`#j3l{ef(a8*Y**3@plUj;AkWZJ1Oy-IBY-@? zxQSHklaH<{O(u!Q8RK+QmiFJHzD?iZ-ZYhd5=>7BRv8+J+>ghu}>zS6%J-tbpB78Ly}zFFn3_~tIe z;S*vf$R8OSB!GsKlk==sp)6{UOjP#GnpcKQ*a*e%a)hW`ERAU3!x?;S zpiPi?89mX$7pHLrewM;cRw1m* zF|9UTARFK|?QRoy8QgQM*3vj~zxv<1z+ookh3bg}-Jmg|3AF{Fm4MD>dcd)Q>dv{) zjbH+tU8Q10shT@(Xz&vw!9ae;W#mVs#-R(BK)Cm8T{n++lf&a%6+ zw`XPDx3bmm>b~XhR&PCN1m50t7d5FJ_SjRu@NH}TX03`3n~g?dLry(FtH9Jnr zh1y;mrFi>#l_O$u+mo2+OgJ589`4&0COqYzjP!2ZZH=OfG;pq9XnZ)x;KUMT+?D|lvTN6WxS46dFVQG>ruWpK0A*b zC#iqk3AA?w?f-rHRs-YaDX$Py-PA9qu+*$3!AwYMgC4;U1USOSLW#9OV&n=fazP%d z^!D>sRY>?=?#rAqM2Dxyi+Y|V2u>wpCe z@3|TRBrZsTxH(guac=a!aaKt|afjDZtRvmaghwyfO}*6$B|(FyfcYMVNm}p>DL$sE zUtu3T93<;Hb-S#<*6rYNaVU1*=yQ2xU9&v>!wQuOnv_?v+vk+8TDySufJjY=P7G6# zOppW_(+*Rl4vkdJNAUI%7i$i7Yz;nIw>#KxJ;=B=pr-r6{bhwmjHt(b-?I=fnF~J+ z(4hrS9zUy^2d^D2QqPfULY*o{-S?OrcL?LhI^pLUt0SiMBttnRi*XkF7dACo?qAAe zgiLmKWeBGO=lfIMTI2+~0@Qw>^5IIit>8$5R^htU*n)UW>EpDNH}c$ytAs`tx}QrQ zKkbOjBt8s2j}{<&w5$ zpgm>D^TZUAwP+o>@(y6y*e5~`7iQv4gJ7n|ZfslpzaRjJVQ@iJ#Kx z*5@f%jO%O75FaT*D$UboS5Uu8xzYh5G z%X&d0Rh6?z507q+ij#c9CpzkyiVNoMMblf|7~5S<>KPG>0ucP~hAAI4LqzTX9WAoW z0MnX=je$G3K~GceO>Dzt-K=c$)jU7gt{?c8w->~oGnQI2yQ|yh_Jm_Tja4Rr$bTU@ z)(7MRh^DEkXg0Fjku2F7w;hik*`i92k=G0v)}gd{x?A3{zQ#8$_A~mUpL=)s-re#} zb-UK9yff{4mZlADLNa@U1X^rg!aV3OHxSq$qP!qHYB^@H2^_d3d)dfHOXTax(c(T%hxCRk%B2yiKa3) z7FUOhuhlYj@4i*0>l$mJtqSVqMZDN$K*Xn=jz%>T6D-j>B)ZYcNhL{-yo$)}l>qHT zm4uiedqx3kP!H^(#ZL{WBT%CRX-G-bn{pfP066Z%&)=Xsh_ioUk!YV&`&4`Z_Gkrk zV<|AuQ>K4!Ab6MlL+!i1hHq2oQ*U1HSS0F6BpQGMI{&dz13}pT#!l>a&^7C%NA^6@ zL^F^-FC67mkZl~Y)(=lkEzS42;5Tn?Zis~tmJRFKp8_%SK){riqp7q?Ot2puaKpqf z1*xD6yUdyy7p&LMQ}h5DF)AiwEOKzBg*jf(Ma~4ku+-IfG%}$n*pTCO4dV@=Azysa#|cuAyr55!%>)A}zVPk>!c^sof&K z*Z0C``HWreKC?T29*pxPg}3)KJ3(39Y`K6N>b5;4f_%{=(nxZMEsc=%$SE65(sz*+ z8{4#*K7u(TX>^t8EG=H$>H-XrTM5wTY3ijNh=?F|BsXf!fKx7%NDk4Zjjl5NS%rn| zz&Baj79OX&GK2m6&fH}Es6qRcdVz!l97T!O32_Cadcy5echa{2bryBjvx z=hE|T#=G4w5v>bxvE3^X+nIOstDi(CpQkwh!hY;N0v$gvvQ}!QS#1)(dnG>f?BsnGAdQP+k=lu1SUk>Eqa`lbj&C%uG}G^t2s?(AS?DIY~6 zV;-lJ+8JxDKjEDYVR2<}aB(_*CF^zMG@9%E)@8t3@lj&MN7xT8*u7`Ev?I{+)F>(+ zDxiIyJ!gpGvR_KK1`IFc6#K!(quY!1?s`jAl{*ik2-gNwU*>2prK4SoKUdTSqYoCa z0w}rGlxDtx5SX$S?l*|b;Nv=*YjeeXN3r~XMGZ-Px4gI3auSae3%>(zFm{(NgI2Ls z2)_h9L9hVfPK8)5^n=t+TZLi3h7~rvZ6L@vxCdo(9iNIz2Y;VztXs9x%2KpSRGOX< z%anSQCQf`emsFV6`j}_YygA$wweDz%J=cgvQV?)z) z3!Wgwiv1;0`~C-e-yPM|m+u=yiWCD#M|xGNRHZA@L)!X~t?NIBbolCg$4bTfsi1JZGcGl_JxtBnq^JXk#VWNr8A(Csg z4fNFRgk)O}UU{-L<)H)wC#<|{kzPSMiqV=Vdz$XsqS9#@kq+HkY_GN4tvG$p+F#rt z0J|lBxZ~-2)?2nZ%PomTsz{T+gZ+h)1gD$NA9Bt!y6!m_B5W@Nte0zW?UWLBiu zIsJ3`j6|x}=lf~{>26HTP|-ah&23rhO0s(x-(tAKIMPu~sdGUHe-p(vuBw6u-*5gc z!4x$*dw0KPURK4SVgIW>_;pogQO`>E9N9}vj_k@@<;#d+OQ}3;0;A0wkWp!sg&eCM zPt^P2(NhBe2RZU;c>N8tmzUA zAZC`E;Dx^fJ3oa&pO(8~{K^lptNKqAkHaF+QXwfi=3&Y!%)?X@Xm(XV#!C4#9_{Q- zuG=*3F=0dwi`ZTLW-+!~!?EkZYnU;R*y|}+xog+-I5GHD4L~7hYX!uo)J0((Mg-|% zqB)_rz%`2*SKWw=^4TH3jw>ADG^j64dvv1RVSVTG%O6d(A9@;IKUrRR2afaIi#}4~ zQ2{367{JF*z8YTw=q@elk%q?Men@1wUR>cImC_>dT|Jat{NJCv$)U z2Vh%mRY)4Jkl335teIlJJq$S)Z*5zgpGLVm-eCxh5>uS zFJD3DtGW@=gpcoF7nT*{mfaE9{^b_|3nAWR3meDD0A>^&y4Dh{dMeSaI%}o(L5bnv z5GU7jpLA1?$Ct@E33>8+j6^QN2|Iowyo@ON#W#V{g&NQu)+sK5q)TiS-GnYk-VJ*H zYCHd$aJY~|$g2T7rkb^97p^)`qK^ z@K46w+%^v`_wuG=Ugv94MZi+6hck=_JNa;aLcc=!_74}-g%l0u!4enF+Bm1;mV=)l zXa#8`#$G~Ec2+oauK8Yg@SGe|Q|?`|0bUME7hrC+8~uPM#bOr08@voW^Sj@{+%Apf zq0Ks0`rp)h*`fsZ3u@|^G~Ng%ev0+w(v9pZ3J%&ixkO0UU?H*$LzimN@e>OtCY2FZ z^InDsl{eVtG*$ycotwIiReWS;%ih1ZP9_=GNxt6q`%Tr~)q-kO)dc{`Mt}`55O{lm zK3K-YfJ*Va-5Lz#C`p*o(qcyoR1bGLP6{a`q#94wSYO?|{oAaOtNTR;tLP70=>{!B zf=n#-G?WizgW(ej;P|6O4ur^77B4bCy$DQ2HxOE@L8it)7EPpNyH#{t!zsr#yzhEoy zNagd|(@kyr?eaV%F#vDguyr6zIv@lz9PrH!v$?WK&YApfImL zR^LJ-s>2mL&0%R=vimT(Cq)b7pAdq$0?V2`d`U>d^&3QV+(L4|W{rSAjf1?G&Bomy z2=}iqtOZdB*7;o`B({lvL4@vo#z#=9)#-b68Mxdi+@cINVN18w ztI^?y?@le)IEGK0%eOg)joeNea7-M8W)ylWjy)25)=I~sslrRKfxIA}JyUhNj_?w@ z1MXCk#;xuf1P=1*2T64H+^zm*@0 z$#}3Bj^ai&WLS>y-aWZpu}BDi_x$n@>!;bHrrA{wW~pm{L5nqMY>@@-8I&^%S05D_ zNmiwJN2v97#n3KZ2r4?d9|6g!OZ}9lKIjokNqez5d=_FWwhL;->+ZPX9pGw3ux~nw z&%A&DvLUeM2;FHG{OIBd**A2DD9o1?l%&MWEUZ{!we_%44_Mirb{k26JP^YRGK7zK zFra0v<^92RfoD{mmmqzYhck%s+wByqmfN~4ZztL4{no_7zxhTb-fWEuc?=&mCg0kN zCy5b4Fo1GFL=~=I$J(gt@$P4eItIzHidnTzS8oZ{L5Uk!*ph6c)~eK@@wJm&@~`^8 zsJuJ{kpMosRMgDSswZIbh2yYDvn{#Hvl)PE#+vR+#b(J|R#`Jm{ovNM=iTidH!2y< zM+_}T_6*wI!GR+rw@ZAGY`~yr62|#YHfv#;GUQPs=n82C;TCJPHM1CBnX_U~E)UW& zK2HRJ_Nd^G2s_KjXyt;|Kqw2$%n)xDQKstAwv6D!@l*h{;zRR;4D8YM0`m_r-Zr=-? zsH`_17;b#Lo%Eo#2J|dIsVmSZWRVsnwhp*xt8;8FoX4-A<9y<{QM@h)oALsf%i06Q z3SFr*?hLT<;L9wGdybD|X0B!h6a;c#U*tilZf2=|LC~=$b=<{M=AGFJ0yMNe1S6=E)5P1L!&=6TodQ7eay7#^8`;#UeKvB0e+eAaM-Yu(}rl&;5- zk@guzk*1?N2hq?{cL!UAOp5Wo_M~@S=Wkm$*w>Sfs0%@m6dF%HshR=V{FKOCf>U=k zF2)56UE-$g9XS|c_`zhg)7VfQqe@wqWIi@0W@^5BQ4v$;OsU%iev!>ZqOc$=8{nOy z;BweFN81R5Fg`1`aAQWOF<@gR;uUv85(h?!$v(ed8m8bT;k7q-S&+jewbOQ@M zqH+fIzRg9_p#6Ke&}6f_i`08r-ntoPhP@8DPCrGnP|q=As@H&0Lr+iKg*NoXW)3Wp z)7h}l7A`mex3w!==e#*_!8w(6NoZny5#lY7oOaXO!J2~>J_jP(%x3aMvcsT88q+yPlp9_g#(3;N+&j2;i{nrp;ZA@J@3|y3QomLw7x7?j3h|$6`E^ z9VIhE1P6`vYLc(5dT7m?Rnp;2XB1zRQdgY{Lo6w#LVj2(AbCM$5no8 zDuP_phQ)%rW;5@2T5yWX-DYTBv@3@~HcQP>q-0H|h&Z>1t4>_W&2;V8n=CKlY92h{ zPZXP5$qwx_ri^Tp{vn-R>vtN*$xF&fcL4d9qI+y(fdpmLdN$A6nCjIb~ni7K@# za1Ka~D8u|VwiNAQ(+hw`8MGy8M?T}*F7z_@bJ?xZ#Mpy^4RK1?o&;dVCr9bebEIgAsMZReZ_`w(I($6o8|S?=5zg8Y zBz*Ys-KKI+1g~+5miR(h>c@FVuUx~*{KyyXH{Tsag4K?H$2K~T1Qf-e{8AKOS_Blu zvx3z~zd#h^3AiC5KYG@d0gYih5j|Wy>_p;To@T531XUvebd&!yNuwetjGaWE`Aw5M z{P*z$UNMMrU1xR#nhBvk2yT_;1SIb8W-*cqElTFNh4+}Rq2_EiMkLZKq!m>BlP3Z> z+9*{St3$89J6}(HOn7ebkkp&aLR+S3Ur5jpR70*RX`TnN=)Hh-ahwW3sHJNLtc&{_ zL9Xz}gow>gz%x5_>6o(fZK{L$5{TTxX8;)1S3-=&>L}_mV2Iq`_7g;GdPniMif|@$ z;pyaLPG6~Cru4{lQ3v+|n8eQAU<%+oy?5Q=Z9<`}muDeC^$BqPlSeQaJ{HTF;_&PD zXL^LohU-MP?FacNNej^){5M}U8`q#N@Duc<;1|8QEg|eD=!c&s?cb^t zB+xd%Fw)8VMR2CH0Rz0{d64IEZ7E(9Yu1?^e9sU^+l^xRqAHG!ZGqmMP}MJl`7gy# z4%Y+{ZcR`2oyp}|vl&P{MEx&1O}N?a03egbzSygjPH~|0^5zoxN=00hDd@$=HjWKV z?ic@oM46n#_ZG@6An zPz&XzUK<&D44$qb)A7n%B z{&b>D@HIbw`~=_9imnT2Yo1B-Y*Y!^SxSyJZh8=1%(82t!&U^xJF?`5piTBO)MuRl z$UAueNl1_(H7v%Xh6;n=mwa9@p#@4M8;?!TSzxoL0<0ROg07@ zzo|_f!$PGED2{Lg2_6L##v20Rnlj9EWSaE*kN2AsE~&;f!CP`X)UIr3GWq-=(E|qI z)&OnYZX-Zj7r>Q|CPc6QQCs(KxhbeXd5OX}-Oh#smBkA)E+(7DSKgSr%&=Aj<=D&! zwcY%ZH~zNbmSCa))Nt17aguD2=2;s~f&y-+4Zom;$);&5xbFAf66WH(v-(DSV`9h$ z*A+@QtM+}CgKF<$pMe}hJ?N_ffbCnFsItclsu4AcrmWV}nbq0ql-Z(c45joBqRiZ$ znaNr`)HyOP{LJb_tja2z1~p-`r+a{46EJ)#yYny^#bPBsQAG9M2!UqkFFExiuT&&F zm`0pa0v+aN?Ow}*c0pus80cO1LTqV#=`|jXisD|FOuNirlP*hK5!t!xQJ=3boCM3mk+{@0UZ%C-J-89%qi*qfx1C+Fvt`#|T%hwSiVHfa zre0lQ@tV;sO78A4dVL>395c49=x|Pvv{L6r-LR#q5x~2~ig0UxW&!JCQC(;_s!Ijl z&zwARb6|h@qO&TAIha0hF`O6dd+BU?YJ}t-8;NlPetCGlSLlm=-Yw%^H+&VdFH}<2 zoVB(4=^f2$U|P~=+jB&IWUKSM?c994j9jB%C&|m?t|&K&hXX}0u3i?ROn^>BG{K=jDBl-nkW%{ zQ6~JQv5ZW2>#p`AvZ`g|bn((!r=h*&M6(%S1iL!X95L>;{eAvc_t1kRmIo15#d@N8 zPALj{?fL?8HWfo{Yia@4ZAr*FgV|HrDg{MT4#ixqvS&Q{Tv3 z-^7ueZdw{a{Dqt0I}QL{wEYd2(`i=6SvnE@(ZcoBrkQfF%P~(=;fCJ_ELQAs{j9gU zs#l3uk2?sK{M@PUuGv${V6l0CL`LDED!jBvF-y3!eCG>MP_lF8?6FiivcP72M@4S% zFmPSOAZmO%euc@MPfU>J9SCB97(!B)G=s55k-&mqZ8CzW;qd$ zQZw15pL4vrlFTer^xom6C(vY+yrCM7P)cVM9U%t?=+auFYL>Du5I(pg768+MO)M-- z*S+Fv<4fW~t4+=Fe#f47zG$ zdJFbmihyB#&##?YmIK&8Z?GHt)cD<;&i zy~VB+O+%b@82vm5#DP)-gzapjI2RJIwhWe=!-Uw|HCf$@_l9c*wRG!GB)T}wc?|SF zKm;6P6sNuhf1+*!yhP|&X3 z-carkti7#5Y`zS7CqMxjHJV;q8nC2n!8jAC98o+Ia5Yzq)htE2=fxR^s<~b|^Tqwf z-asFc7xwPHhtw@#a!Us~_aF}1d0hIrycCAKmt{3pZFuJk{Cbftq%0`y0iV0hxW`$g zfnrXnt=BKp9%!+G0NlNy9A@$P0rVm)11pv0;0wi;Gqh2l3NE{_=`3vDD0YiPF2bRVgZCBx(x_M;q(g_Oga-9<-G5py?gO79T2)W7X=gqK3@e7L1 z?$QFWPh;3e`N{bGdwbu}i}Oy`EgfcJU7;+N1h12wXESLNn9=-+?;Jj#Y6O#@W_SDt z3mYT`NPfv^f9XshY>mh`xk}_8X*S@E-hr#Yzi9>feze+93Yd8Boo6vW7k%?vTfV-W zrM6)7TECEHf&xBnCy|E4MIc{-M%X$}qBxyXWnp!9Mm*#f!5vsAqf2^tN-|ftxVy)z zewnH|rwE4jd9tY(5dQ;BDkv@ob6U{87@5U}6E59aKxL3~mEO2XJ$dBSWa#bHca>gZ z-+-Sy_+bp_;PNl(m+G}&VMrji3GDL1kO#}y0MOC#ulVJEoBieQ6d=gH{sfW1`AdlE z1P+{itGb}xt4?)bZ~HQ5F_-Baqle@+HbS#ReSc4<4KU=K_yb7g7gF)BmHWd84X3Zs zHQ?=8(S+uZr7QVcIXbR8Xh$9~k^b$bBRC2<1?-^UZ;8|26u)Wmh@WV~lAx48IDdW_ z9CrNtnYz?4i5m9G1n+S8wh*vZ11F0_11_QYJGVB4&jx3UDRFrMi4HEPs(n687mMte zLR@i0Tpez;tJl}wt`QmBYvnRN}Q^JDyRQ;7kwUB+EVHgnVo<|a^X zf+^Q+)S7EYr2reUNh2uBVh2R^Sk@&SRqpQX-`p)Iz0yNxlE#vwBi3a!RDTA^LMXsa zM4xC9oDRKlYu#vud6>&L>o2*Dcp?0h;YY|9>kS^ktYt%g#L!BGpngq5+>FK*RZOq- z8_-MxA$s{#MW>1IXpw>FUP8#%h)$1;@TnUvIVj(0dDc!ZZ~KGZ&&#g5Zoe}vFf?B$ zo;xOQ5e8}}_%7SB5<0919FS#hm%V#qs&e>#>*4nqCiT^gjS=k4;w4uju&xixb5j)4 zmL+lsn!-^Mni{tY{{rUor`Gy2?9bmki39%!Tj9Ui&}SAqjiPOUh%6Fg6mCneDwpem zkRGoto`1IbtyAfn#Wdv5bmTf%L@d`|ILYeG_|ty!WCetX8K zV@H{*9~_~4zUd?3UME8A)pmg4%%W?t#IqqNUE%(m#FY@mu^*Dl3k_t(m=HjlhBVMSpKRa#t!*qW)^~r4;vzchrm58}nO_h0#!zlbw zXBq~G@6r407+b;&ZsBd-gJXRyXVL00z z+S2S9UTj^PxRq-xnir5_sYJ!<;VD1doozpsCHUP;|0;ONC&^abDlTQ>YvjxPJPls3lujXyDUCMRQ*yt@25S2xae#-2PENYnliWyAlkc)7q4G@ z+IRMdmf7VAzowPLd=m|bN&yR)J5fqrYb1O6$-49_uvGLSD*((voe331Fz{hWDke2@+Z`^r6k9XwLA=?xeP~&1 z{k%5Ce|tGz;KNnzzDx6$o3>Ng+ap28-pd7@aZVWBj-~{5ATw^_dOSUT;4U($m%ctz zI*@vtTpGpWtUH@f<3R;k@zmrM*jlVzjBe%)T8;%X!<^a#jdAn?&y){e*_AJ-?UrgJ zUj(2jPdX=DS0y~}gxt)dtIUm31XapV$t}BEVV?t$RD=|v@f#2_ZPbZdhJu_qbq}SZ zzw3=~an0N7I7Lmxr3^^%WtqtR=JaFWQT3CrfW7V)LUD&>51{)^ypJYyw8h7+Zo? z*{%;7JiRpu_$>RTRZl4x)%c^dTN0Ab&ZZ?%K70A;CR3++&|oz=jnT|rPnICTZ<+T6 zKovo-Y)m5QRTa3C9(I&(j!bR78dS(D9q8gS=TR{54CIvYCzsP!9G1ywRn8RcsDdL2 z75Ggs7on;vMV%SPQv<=2a&;g$@!X_fMgXX@y_bv5+|G-!$Xvil1kQCAQ(tb1y#ku3 z1SoFVXE$xm6DXE;Tn!1a%Lk+1B`x>5Y^0i9nJY*6n#>=?d~Ho?KJw4HYCvJQaI+FM zp~6n?gaMG>8lASxFmQVn!BD=`=>91D{>)%Q^U3v*8a42}iqSI3oTo7&ak)*&DGx7Q zj(Qf_DMlq~f1(XQk9_yqgQ!|`Q)$x1@AI zQtahd2SMHeR6sO52F;)@M(V!@Nq?4_1GDcu){WuqRAx@yH;ipj-<+7ZcQKT4Rl@D_ zW6?*R;%qbzoXK}LLAXob2hBQ>)ww)$@tdpQ^Dxo&L|7<5>=a7{zPO2K5NW$sxY*F7`Pwj0{xcSnqiT8zbEnQu6d9s%JPlVGF zig~+()s68-J9*2q3DmIuJGielpxDky(gi&I_t#l$c>ReoRdIg@JIRIqp7{CF+&8++ zIgFqBL|#aLPJ2qWxMf>Y7fs}rid}N;*PuYQyXL`+j3#Sh6BxE8O`qEKdkOEmyUn{> zXX)tC_DY02pnDn2D^y5j>v?h;eiLs!w}|_Q;M`zKf5>|taAmwZh#j;HQZ^s?Uf%kf z^KxCP8=;~bd*kC`;!{~NG*!=DRF+zcfkx;e{XwRsf%G|uy2O|uUZnEa^Y!K>`IHIP zfkeIh$0_@)$$cMK6C&oiG=SU3jPrjH1(>qUF_S^>JS(-=nJq#!cDk z>irpH3ts?QcS?2+ywjsBj_mSeGeo6{@75~I;2v=J? z5i8%v`criQzH>3)d5d-_7G@AQ=nqkpGr@l+ef$kc4lq)?vP22J@8-Jfp_G12JcTU$NzX<^v5DCD39|ov`56p)ekGJXa@)A20p< zAnx($(hHq9PfsW25f+mpv%p$FwU4Lb_t@WGt2!7}6u|e{_!ae;*1)Hd-omeF0#GU> z4a};0Msh8p*$LAkZG+pHI1jg)rBD!Q zF)eIufKdIjxI%~=vRx_fy6Z)HUk{u->9!rq9MzEO+ehi3O<*yVfkB44`_3AjgDc~@ zer7- zRtK8ztX1fy+^mI#QaC@@^R9#ug;5hXj-to;HI#c*qPp~osFMvBNm>y^~Y8|BeoV{ zmVPx~H%Ww6p!kgO(nZFprLY5evR@c(j&zn}K8W$1O$&PoCD|8eG!Hm<-@H5bZ#^W= zAv!mSC7JFM*%P{R#@?a2ZcC*5WWs;MF8;N;+doY?@Udk;Fcf11l;*|nF2J6|Wi7CA<;<0`U)C{apc|rwli{GD8P>0EjeVb9 z87Im)U|bt~xw;yX%q3UHL{F|iGwjCd`x>M?6Z-f=@k6i|Sx?W2q;r5;LF5jR3a`?m ze!j5+SC+jrJG*lxNOiCjGI6E)S@+rwYf{k=dy<>cna<_GN7Q6Df+4W5L$~4Yv~58c zXq1ftE~slLatAJ5)Q>rtg*=%!*s|jb@epnb^*{Sb^eye1X_3y-R8ffWIVlZC>Bu zeJm#pkwEynE$ApSW7KFK&WA*u-lsnfWPp=DIC?$Mif#*++3cedqFV~4%cesN{RB;^ zi;Oixir}^Y(+zIriP>nr0xfct+vqzE%J`H-8O~Q7t@_=EezmdbiiSFlS&Yiw6_=_V z_7JZTwd>pBcw{k2lrDhXIbPj0*H2j(EVmZ@VgK;XPT^;36sFx>yKRna)r8b<$&&!V zoB$rKckn}DWhDR!nV@)hqM21H}3E1^huLyC8^pmfGn2y?N2+r19{ft z!OFZmr2Z@}{P<-2vTc-&JOI^-PzB)7M^UOun3Gts9R-z7%P|V|l9JW0ZVsg2sLXS3 zzUt!|uRLj0lj}m$N~pRt=Al}!aR_VKE%V{;h4Kd}^LC?aBYS);(T`3)FC`7SbG%l$ z!uOjN?^)1OlmMWKlIhy1er3EmAzEDt_c?l*wh-E^i$T*bSX#}v95MDV1E_4Pmcb@{ zW`-XA+AOBcFbzfXU?0o9Rx~vs;;3tKGCiXFB1!;H8G<#)3pEez@y<1bC{*gc`7G#I z5v6zDJR+zh4Y-+Q!FFkmwdf0ZwF}suPTupxtM~`wR3i3BSHlFviR>IG%`SY8U)QCBv&hPISxv7<2<=Q{Plg_U*HsH%I* z*Zpc7=EA^7d7FnZm5lY6XTkp9uDxkRtD(qjhHBgABssiemhYC8PCYJWQ*qF~)W%Bt zEaQ-;TBo#ErM&5I^sR?{uRG~NV%2eACp@$@FbLWmfbIlS5)JT?!SH*fmK{zdb1;*G z9|99h45p&#w6j)Gou6KqIL6&ItiLH6FvwmLAm+qkeV5rpU`ag0hJctt~-{g%Nrgs^t~q8@P6 zL2;}~#=O4owVe7f`n8#z)fm$(tk|mL%11L}<3hkqHHQ#*q7IY8l=gHq#nIlM^x$nv zH?7H;LPF+sucdR}*`L|R6hI~9K2=(DGFGaa2F>=;fi7<#tI**G;)~%k@sU_0qxm9? zbI+{4I{liYkkas`8Lx9wO#|4Ywf*x2N)0J(#xmY(Lcd6tU3<+er4TevH8grgvV6uT z4%$(QDfK^F80UHj$!)4=Ad8v{DL{oMd(D!i)5 zF#G_>H`GM{208Lp(=}qd8g*+=E!?r20fdK}cpp*{iR1dqtlsFKhMisocwp_+rpzD=1L=kDo;V(tq)H zPf~@G`VWs-v#WHs_gwuR9V$H~uw9S0y2SXU^eqHO z&SCZ=GApdc3k1I{+!6^Lt(2{PZ!y;(o*)qc z`o?>P_!zHNw7i zgyJjLiu-_a2k9~)2ipO+Cm7&5FlFfX&b7*i(PdkfwRt5F>5r-qJI_1;i7O?z7wFmf zb3#jsOS1KRylOD}!wf<%HYm^#eup@B<)CkL;dN+V1L~(_%-jPAzp$L)+t6xKF+B#Rf7wDyDmLH`+Z*A&WHsJ*%@1_ zPwep*oGB8F%B%ose%>CYDuIif=96S$AtZJfx=Wp-r3L5o;$Zr__?8M#ryIW!{OMn$ z*6u(H`^AMf8QDWJ9`8X+@6QC6g0z;6xJbjlBJV9&qv+$vPNTC^kOg^yYY`!I@%CuR zS~dEMkh}cCb?)%iOw>d__)U`DO$YOHugKt)WZa9urZi63vA_w})4^7*o&(sauOHVe zR5>lV&OddTtP5T0V6JF;s^0Gr?LvOV(Vt`Lqb<-LSP~!cK4AzydFV?RUw-N%4LB%i z#|+&< zhzf4m?ZTJ?h55w&x4-d;uR%Tup2Y$Db$Mt64>L{|K%H*gg)`u&wom*uBBbSiN#KWz zRQi`ZPEnkf>!oj|U}e*DXmexLR&^f)!6w6r(jQ1eJYodHV%X6k>6y$ z`43(ECQMNbEu(h0OIJDL+EcABICBzA(c zE=`i856i|f>g~@CHY8HiZt&_ zh{jr3Il7vLmrii&z@p}!z~9d_T?pYUG)a{E#fG`8t^u&pRj=o-2lPD8#zMO^q60`T zeV47!bnfXRleY~%=1JBDO-l4Lo3xRC`be_}eS7IH**YfxRG4Aw1dQrO4+DM!@RM%7 zXs}^voOf5GW;&Mp#>|8?cz&jtbu?{r8Ko&|}!d0wmK-eoI?g^+&YV!xEF8 zRlUv~npVKgJ7XE#HN;AA!rUoG0+tM!1|3LtscP{_LrSYl3W4VGu}z=ix?Vlxl{|E? z6!^+UO}LQ(SS^#N06!v5xOWMWdqPzkvsIjZj(EK$Frx|9%paIPOK{V7JbE@nnIlw^ zT0xAZt?gQPVsX#q%xf~y_VRcn*UGSl6K@nRQw@~f1%UEqW12GWtZ9Amfw+r|3dI^I zKZi2!c#5XA2s~Z?Br_s4awbtz$p?_~8ROh*PXH5*M^p`QyGQr%+0XOvlrJ%Y1w&^i z>f&7LQc_YzeheLsJ0EF_Gjg1bz6WCeB?ZSzm=x_EV%xIJ4x5=Lu|O7hzO1oHa>xx9 zEp{AEJgIYvd$^7Hk^ zQyu01UTN~+|LG4p7}wv!ivEN5ioIlV zLae+By%*QDDY@Ca@y0t96&G1e_|C@5ijmjq^qVNq0gc)s=zmOyqYo zc>Nd^Ex{v%`+7Xb_SAN;;PyZ<{r4Q5^_j;YgR25MOMqaCzeWOy4E~gmsva4LMFM)b zg5wAFGQW*iOH;xkby}+RL!)yHiZz)25{1G*a6R-R)GZPA_;Ew=D8`Lp>vhvC&U6)I zq~);LXld34CYGub_V185zQ}2E?D^jzaYzD0jo<3N$cw?HJ$$5TVL1j#K>{qZ+{pte z3u1A*?@iuHto(3N1Gq`vT^f~solrJ_dl_fY0|00xK2(ed;*L8odlZBOo%rQjx3??m z4U8__teTZtouzx9Nc9v%*Bb0bnW(vQ<o|;T!P`VH$7aW%X|lUGb+Y~QrWXLTW5amQ zD_1|^>Qu&U9)YRZg}$*}2MN{YO91=_e8p&51A7x8Wy?{}DIKwFV*QX1;BwHnhDpZ9GC_x+$M-_Wb?&X<9MZ8=KI4l>q(G|nZfQn^m0tjjgtxDzXN z(~o}i18f(T2nqBk@&4qg>(^Hu?z7wlT{EKkm9S-kQ_a#fw;o+|rL<0jg`)*|m$hTiH2^TV^P-8n($1emQW!vFc3V@D!dtn zY(asdy)XlMs$u z5N{FoxS(IvjPr|@cJonq%P8|(Wd>lC>CB;j@2k!moy#)7b!+m-sT1tcb9fLS@3?Rt zfVUhD5FT57b9ImoZ`M-F%Ag-?>KvZ2Fv6aD93k+K_cFOhj!X6%fjrPd^yv#YwfNd(c15&PFA-Ov4_6P@!+NnNu(K{1mbKEX{L9%96EM9@qdGT^g0snmvP2`~# zAruZ^MbE{;H3?q6+LKh#AF9V{rX?{E zuHg4tXCh;3r0L*h1PDYax`t}pm)*8C{Q##noAe|_Ob9QiOXg*8HQHFkt2N7+JRK0? zb_6URNwJ>qZQh7olnwEHjU=1xZ?<(wU%$y8S*y_(nsOxo=oJ+l6h&2n0eiBG~yZ?&c z8I}i+8qS_s>jF=oEE{zjifVsB@WD+8P(MIjOuu*v1!(UwY}}if&%N7TnR}Qe5@QT+ zicaPFO>6%uI|%Fk6J!s-j};qjGV-+WPJm&Z(mmyt`1gtl%je3sJzhwX%d?eZYqR8? zGhgOdoONSgx#N6h5WO9XryS}Sg*_euX1Vk32fgqcC~?RmTx#^l*2%-06VS~zpl$C?MI*ypcutcW+?EiGu2yQ>qwL2Fl4BFv1KGxW#pk_^BQzq@Guumd<_6^p zljuDpzv$L$aqJIAeR#o`=uAF=#9Tc6_!G2V2?wy{9grgAx9fn`w_rBl)5Z!Q00{01 zMkHr35a841{X3tw-e2cJt29O}ub^wf(De6dJ?L^ynt4rQYVxf*q3oGM#%>Oz8+wDf>#g|t)7I)n4_sf z`teS#pSxijeD8?j%rTX+GLqgI)$Lha^<}WTzw5n2>t1Uxy%X#kf?8us^ zgL#MM5Z*M{Oi=Pj?cNUvDbCMDiFbF0#0lE|(_ZCo>?HoyM&uhZ3_;aMaKJ@kY&%>} z*2|&IqL>yrt@M40%c)>jAlWGp_Q~{064@H%e9Ns+3MSmCC5 z%N`Y--2Df)pP%t>eFxV2Q`q7kzr+9hFPDh`J&ziC2yCwj+N9poy3-0?z$Mt}Ga%Q) zyL}>=^$eM?ZTqNOBg_f#@UZ)5`vDaY=xIGf)1iKu?7G_rN$w;(KTx4R&(%97J||q- zs97maaS(q33m4-&1f32_M*ZiKvbFvL<9OW z@YessRYul9Fls$SU6@3PY)u@E3@N?%{;8%H`%;s&EZsdKOYnyBM?*DU(YK#E-ZB5V z4DmlU-T#A~@BeyXWWaWg+GDp2!ABY!o_p9Yp@>qgjyU_WpW2vUujy3?p10oJ3F)>- zxa&;5@Q)AKf3aTzb26YNzm-1ODJiWL=~#f-d90>n0p-(OwNcD=@F{H~St4_+XX1KJ znvfB}D*rD}mj9)iSIx#uK3B-5hoP4zYKnvm?6E_vR$H8&@tR$wqX6IEyq?7RZQF_c zfF=+~4F9t;$G^;&_zHx{nr#7iJ|JVmQ*CX6b>%%rs9e+?eeM}9?s3fe65ck1SIQ2$ zHuT2={uM{)|8~s(mW~PjIZaRF;PJ%U$IHRa zogVlL`q+hDR)$Z85BNh>RrSPZ{!bmG z_1*299MskS?XhWKZ+9{S%^y4<{XBXkw*JOCVnFw*fDI=Fi(JIb4qcJtPj|JPnpg5n zUePt@UdxB2X+F)`HdrO-Ij>3@Fb-T7wrAciW4B>om!}K584aUOq83J=kKV3q?~$^q zhE_pTQ&bD(8nDk6PNg+$PJ7>`%Ug~biK{- zLSyu=;|)%hO}1Z0y__4T0>F_Pa=*~_*O5Pt=6md~W3I`2#P5oczx;27=!E~b6p|dU zF$qO{Qt?ZvfC;Z_+nw+4{ z3)oK0_vC@~(x9Ixe+_czSxyH~A?^7xq0rcfqpGBhHP}e`I7NkxF55 z1zjYpILEs4J_|=H^qk=_n|wXu+)=um)14s`maQy-!?Qf@bmLCRMN6Z z>D7*wf6i3V`d+{NIE z)$WU*7L}FVxpU_{4UICK@YKY_1dTXtZf;J*%r$sVt(RC-iQIWRRR^`r{kpQk|D~;s zpO0?|-^0sBK?UX^4k1ZZM%n6O;dLP)A%RD`UAjZ+CvK@y*2aB887>bLJo@jd)f}rw zC;#D<-XR*AnzRg4q-{};+RpqC^gfLN{=Il1Aub+PId%)ZJKr>!Z-A*ig3U=;%*!KI_IN=(qG%^5rzhnmUE2OPb#TTuy?R#D6t=#kGfv;pQJ~D91IA zzjt#%;Y55-US8hEj~}%n=w51sBH9o)jmkGSH-YNF-Q%DmC%(#Rs> zWasVMx2GpZ1~F8jO3;PvnHpD1%b9oA!xDKeTp-tK^w~(Nd{^kS(w8i5TEgJ3=r)y@ zk>Pq5?ebvi!(nY=TW*#zJiGJOum0$Ep4_0St+uH$t48590(iCV?ruj%$KB~Fs>Wq3 zRzN)z@#FYd{rlLxPl>NzKapX_E-%l|&3z56883e&Y82zKH(Li?taYC?vkelybU+&o z^bnP2+YAl{w{F=4?$i*8L@DdWw`zeCJw3X|<%szP?*jXtc$k%`>BM`jNGSSrVtkxs z!%K0zh=ztH%YT(4&YizwIYFbWq~QFbXa&=+k&w~RI^yQccwFN$Uep!K_H(~q+DPNH zIx>>#wgEgBPJo>px}Duwv?G)ZIq{aasjc^{a1#3AT8<(=p1J?-r5{Pq@n{rqgJof(U?k29bse*z9O zFmO8$937B1eJL!bt`TKT26;o;!~uZc2iT8`3h zyL^9oB+p}t2s)1adA~(#6nuJoeEcTbV-dBpv2iXeIxdbSv-|Y}?yLWYy!Q->D(%7m zM~Nyqh#-=a+~?lB0+yp+Qi|l9M75B`Q&&p>a=x z+?NN zn!`zH{C=uEzMjAqGD44kl3nupV>y3hW55wfatXJqc9%DX1(81i)rC?>NlOUxI>;S{=W_ z0)Htez9Kc|Etr-GuQz_nMKJ&L50#Xn#_W_wM2SIO3XZ*?;t zfqp&1Z^F7E_j5xIUSIR|E`G#To)>*w2-&qKPY_Wj`E+DEk4(vA)i*@3WBR!I$Oi1% zPI|s){JH&(n#X|GtnO6I`}gk|<&eH^ZdY^2V5S}E+#hwyoqHvkAC)E_Srr% zv1A)AjDSO?n|FnlC`|d2>$9BSm+{|)O}?Itdg!0?>pCntdWMe2jvrU(?(5U>_xG2O zc%cpv^QChxcAppAV{+k&h-vSrFnVSgMKL3fSsE@&)-^YWSMU?PRQASOWG=P*sTWJ^ zPN9gT0Hdt0Cv2T5f0Wn8+~ac|t6AwCom!|?|7|!GG0j5E%<>xjmljD$RTUz-Dk70* zhdnBEPze`Thx(553sOk7!!b;_f1jL=&U?OxnUplv56D~X^yb3l@uWGNgB$7XDZ6*(+-vojgoucUPxU_PVkO@!)KH># zZHhlroHk$OV$)C7H*dZ+?CbB>mg;*Vz!fo;ladtP z*4B3agZt{|CK`lqMOM~p_<7H#yz1C>g|V(@Rg2MuNOpGiLF{WYRR1!J@DEM&@%Ek) zv|Fqe znO}w{^`!LYY2LUx*3nEwMHTTA?*cBua}rM-ZDmUdFDd+(t;GAjLJ>`wwUBD$pu@q1 zt@rnKMn^{pNa$?_3-xthaKPSStBP6xGE-WlDMob&`a3IQ_Bb2iZs-ucio>-SG@ ztBZsXurasHjpQuVJNwb_)PCZL%IB|TF>vhto(jp9;kjo0q39 z#z%@nsUuFxS=JOxAaJ#sXtakRzjLPT0i)lhc3L;D!)r?&PGXEO!VSNSSuLM3=B3-x zNpT2%k$Y}tH=i;mVef<(R@C$RsI}bA%!A41a0pN-oH7t?#NTnCb4@4ST*By_yg!h1 zjU2lo#AbOpIT{(V^>uahc93s37Vq>FE0y4ktE;P0HK4LLEiDoH zNAxAG*CQX5Ne2&Kt-j@j*&1fP4w3F%_2-mU#0#sNbT+mSJp2NtDfVUE7WL>G;6&U! zad;y1%?nlvxrHxYytsPmLBocdQ6?a2??w!_eQ4aa@}zcE_U7A zR+7$p@DctslQ49y2Rs@iI!_4noavrf1t0o4Cy%HBI3nV8zoaO@*WZHH|5C{ZAdLu; z`_tPOH^Q~Cd-s&l@_l6^lQ0j|X7_u!pSLztx|OIIAi4rfu<#J=?h^)-&(L_V&*8K8 z-WtQzF1F$v>^~BmD8F7C^$sW=y#DxgQx&XqE^yN{%%q=xUH`iRs{kJal9?mFp6w04 z&0ek*)D z2o|2{1I`b7fwQUkfERm>%K@?;ak5u05?0usGIG75%lBXZ7y)HVAMRhj8yK1orOrQo zFM^xz8ftxg{UiW~>1h%FeP2$_yf7OLhqGtTwsm&W3z}beAQLl`Syd1_LV{efO?295z>1UOv9d>gv0gZ~n2Ha6oCOsJL9J;UpFp zFHeRu?!%6pX%TlABchiSVJCqDxB&d zyc07@LVDJF+iUO>#o4&m*6CjOD_#JWF1ABC(>n(5pB}yS(dGRUlUrXC4b9XvG?YY; zJF_$~HBLfls z7_pp7b@h-z9}3<09E$MUN-Rc<%>S71Cmr>ke-i%o-WdQ8AK*z@F`t`);{>slt|}34 z%TYcC|ZlxBaThf%!xx#Mi}!@J*5cc$)N3JFI3 z828xzL3&0S_b27TC5*K9CKq=aAT1@OkYWS`XLlEu-R~dn)VeMNy#P2N?eR5j`z^Kt zXK8L!(6fDs*4NX+4UD*VufctVZd1LXfOSwAm6esn!phpw-cCe6$b2$`kB=`VHkJl%Cdg3g+&LdF zFJ|o_0nz1^7Zdw)fN8gPmpOKOn_}Ykcge~#Gyk|GbmJ}24)dAK zB0!&CzkYS@J_G~JZumr}m|p4Y8yeD_Jjuby+5DpA845i=ypP#ciJ@b^ZG6_{HF<{T zRHOiE&l$i^p}wueF?8t9H-m%v-LdF5I0o{t00yO|Qhw-7_-^7e(wlH1w%@To3y(dT zi*y*Rw3>b!Lngq;$hg+y{^RR-Ie#RUh&X=A2oA6biY>b`no+Kyu#lUb-D<4Lc4?^O zK{Oh#ZS}{GHR$B&7z!~nTmG|{X+sV z9FYyH!33m98|Ne?ThF{%6^NymT8G5Z-QDfE1h|}ln3OcRxTmZuRf2T`>ae3YIBVh@ z95=gC#Nd@CVP9WX0QTJUZJmf{K=k14VRpV`Jkc7G@eQ%_^zk7eAh{oPJTZK71%k`0g}WI7(o;GiIG9-fkK-go-gh%ww}&j#KC_|^7f@b;%VTftMX zC!!#&y;R0XyUY>MnZn|6aKiRm{P3bI&JepxS_R9=^i4{URyS{cU+5=z8Xq5j)Htvv zO~y;7bJ*N(c(>xlyL4$c?sMl(GY;yadKl#7P;C!5%Zw_HTDZcCvg$~B;su2t^|X+F z?`?`rdq`^>r2GKv1|T4~!6%HLDW~r#2;LeI+zY)in2%`e=;)Z3@NW(yhKk7_-Jby* z#0&qQ$VgJgW6VlNa879F&MqcfE;ovLd^H`xF*{9!KceWsnO@_!Tb-BprN(L6;>L}o z0z`aoqk@70)NP-Dz<|9IaYaKTS|&@2dWEClO0D#bx6w5ty%F{xrjyK+qJwa+JC<9?MY5ilp&kKO{ zbh;G-C#^!;#n|WpV%OCr@frv5(5}z{{p2`qC2SRaOpKpZJ41{uqWd5bxnkm@#~%{m zE9PB!e5=ydwAbWrqMPh>QKiRYpHG-VB3PYlex58N{G~5f{pa2nxe31?*A{6C_`G|{ z=I3pMj$Ae{FtD>*T%YamSRP>}J!z2Z@}>J5>SsgS7zM{bO|+8VP#lwV_(2w}6aoZd zRDJ7_*Q*B)9>^3FFf0z-oN2wk9rf(Z)SD=KeL-R2^??Fij%QJivfq2=yf;`#0$yfj zW+pQ;GbbnK&q_*S`$r-V{K1iLU#F*8E9DD6lg-Y~mX?-U7~^R>LX9A}B?~cO<%3~& z!GJ)*`s(WZ=(9Xw5uMI0_2;jF^@2N;l9a^7#ch=h&(Lvq7dP8n8rCeHwaP+p#I83t zH%mB-vE9_u=DT+}`jn6b5CDK}sXmCkXC17HRysfY`+-=9Lp?w1Skw8Fu9p{3zfNLe zEO(e!S5{WGv6+W+Zmt^l4bHsgV`*yVjZTsGHMO;{NaSWDe8HL#K|Rm0Ojhd0YdQr8 zN)C+xIr&1Mmhw7@&I=C65>1?8(T2~g@mm?hGq}LiJIlo zi&CKr+_;<~dX|@0Lo8OWUzlRcR53_Y%AIB@f*})mKP*eu=ZV^PCel2~vpvt>`BZmW;x^kUsDkg+_~;oKouZ(qbofvWVKv)aNvQ?4Ko?I4vgw8v zeK#&6MWpl1!SGlPug@CSYTW_9oEEi-vrMBrC63=4$cC+SVV&dGs)v9?`tfa|tOOCi zmahuDji7meos-(yD*1=!2`WBZPS^##d~f`XbQVEABIikYZCp$9Qv<>Uwab^OW2sc` z(bJNVl>?91Ci(PKdwfEI>&n=3C?}f*m17w&Q&9rP1<3KV`(R6!ye z=I`0Y8!Mt_WPmXX|FSYtq3CO(qq9C{Uq($umHE1`uu#Oh`vNYuL|9z3tJ1oPip$e4 zGFVsgo_oXotN~HzRkc-=Zm$~0@$Rd|nO>ZMvY+e_J11X9FB*t4xySw-a!kMMI!FR`bHtV|iLSL@^a4E2OoUT3n z{ge(+5JGAOBHDXvF)=;;6UyIz&mQhK6gm0D{A?@~qAtY8`esJ16|;H=ptk~ATU+z< zxq#78QF#XepsGr=7jv|NI*-`u3hq*6rSR-2w}5$ojg1hqD$wwk3j&y%tuy>?rXzvG z&dg+LlVouDJCbZ1eDZFFD`iizYVpIUYcW_ zS>b0BA{jbvzsVyZK_f?LDyOPUdRqLJk%oqbqhom(mYO6Onp##Lg&sPm!Y9CCza_33WxOAIJ2yW|tuT zvB@#vdwaef9zOtIUrrT|VK`66N!p8}DExNlV${h;t^`dx`1jGlq_S};In$z)6cj;B z{BvDp+9G278;lvjtAHk!Z*mi;m?$huWm4qJl@RHV^%Q#|q!mEI=`z%3(C>;r~27r_rcl1#A8On`?M*pkTWj&^XlcA(95~k8NGD2az?9)l7+bWX%$H~0)}=oYG3AZ%M5#$l!X7%xD=G8CPz%VS=UF}3_@{EE7m{}f zy|iN&nY?(m)B|+KAQXy~k`y4iA^`&!`9Sid^I|5De2|@;z5c_ZK~=G&T+eh=N=Ga< zu|svh;qRyNk2SVZ0LJlHVC+Rtxp^Y_$uC??XgbcKL~=^-!sg~{YIi7foSlUSRAlZI z$0ApNpdQHAp5jjt=A>VX^MoNl_1jc*rk#!RPHSQFX8#fgQdzrT)-3H2%j%_W;eV!6#VPQFc z{@Q$UZS6VS{6n6wy#agtdIY?@-+H^(GeVLI4}S-sH!)IPUOq7~amb@SdFzDx{KCR$ z8A8rfZ5V;#C63orQ!6MzGM}0>Au|k_yB6g6BZ|yI;Lpg)2vL7`a{ zbShm{qlqo#@<_#MDg-TGJxz>)59l!*n(5JqTX3|YRDXVJR9N)e^5`=QnWx-Io9e>d zII>plR1bh+dy0q;m0y4Ey`4`Ut=Az=5*-{8CvEOgac};};xLZ*oli0VOSf^cuyk7q zU@4izqqi}qX-=QMstEuN|0D&4Gek^DU48w;Q-J~kEk$?3kZNyL;^Nd(=aUb1?b4`q z#uPWqJ177&hVy~@(zc3x*8rk=C%oT$ zgsiOWm|-ACS0?hgqsAPy?!_AvzAHhtwzf3}HVLJ=P&6p7u{q|W{(+SG+i(`o|!cF)h=E-al|pCZk(^BNiv^j zu^6HC2r@!6tq8uiWkII%<6HBFuC7&{kKu)-q`dOoSwC~mz17}iz$lp8&Fq50lq=$U z*e?h{+!}gWf{M|JCyA)y}0}F98M`IDK0Lqvu6vcss<(|Cc3(a z&5$6Hz;i>yi?|iXU2_q5&!VEGIA+C}ASms^nts6M1V+aBN-pwALU_0e0FJ~*_p=HS ztvGL*j+{+#g%TC&Y$OI98Fd$cPt0%N*fQ67jv^#H{LWa_0&Ke}KBOy<#GZk4ErkdU zv4_@iixmMON|;KCW&R=Z^A|7xD#t_F7{s^aM<{Y|`*0ZBTU!ZwLRJ!69Zo(%7ay|J;e7W>P0IXWl~jfZi`$pp!E!=;afMXJ=M zCs}1*M}gux2>~7oQ^9J`1gP{c(goHZ;>Au=)M543(oPA`NJCAn=_C&~Hw6X75F87i z@3*XovDxW8)8LIG$0E^IcYeLji*(0pPpHYyqU!34+ky{)^O@SJ^V$Fu zd*9p=K*Ut34n#Cn)mDhBEm>pagxS{eM;6RlyuUF5~Rp$pjJ;{?K`3%#h(qbbjzg=VpqO~5@q;(f8>P@ z#32X@3SyhS&>`hA2h`N3(b1P#Sx3J-92qfMVGh@N+unZZ<@sQIVg(-=8JQU(v7v(d zM-rzegcv)mHkdcjRA>CE+s(?AQO+(dYr#RA>i>-k6{c5Ki0x^mU2Uf4X-a!Qz4gJM z-A?J)*x0zcyF)C!e{bGts^wTNa+0M*2fO@%z|q=WIUp6{kh5RD)YjHoTUy=%R%dg* zSCTzq|75&SJikd*Yt9CNg80-r0i!QdtlYacRv;WJ%rqhZyG(v$(mQrFFy-SbH}#z9 z;(#E+2JiMmm(CA&P%)YQ=uKO%)dVR)wlwY@q)|82Hp3-X0p5t=-d?kf zakI1T=@Ixq@?_Xrrq8-)84vI;GxL$k^)88t3kG+iqL?u?o~LAeYx?pXwP!wm4hX(% zeBIM?8#EJsM8hrTB8>vX9G=+biBBT%-uB3}aOFa<_%3mooKoxkZ+us`(R~hZ+eOSa zX37KzG3p@p;ebjwPx@V2U+~!2WPNX${aOs>Ear5U#>mh!K3j|WW@cs|3Rawsd;KCP z+w#8*e8-CWv9X%BZWRj)2?~-W+Vd{kSg3}RGBOBR;Ie6IIO*MZJVsmGE09X``>}W! zWr2e7gS-vG1Q#FQV=?=arHmT4Z6$s9yPyjBQAn3hZP z$@E8Ze`C1UJp3uYG2DZ5cpb|hUXV_X?8!$*M>5xgz?3TPKrvbSRvPtl-)DsgwLAXJ zZs4znNnr$0Yjx|&V`;H56OyEqCu3f{^bhbDI_1Mz$fpiZ7B^lM4WThezh6rCJWhX1Orjt)>!)wjo`+wu`TgrGG`T?HASwEGF7p`qb_ z;J8bdE;0Bl3prp?&iho?__=-iR1Y$)q<{bxo{&}2Emh?poWrD-3?0II4!Ql7D+M2p zQpAS>bA)+~<(k2Vpfn*scx3;slQNd6)cBuFWxehk)p30j6TAH!Me|SRi=d{}eX3#n z+)h8n4fzxEV~iFSCGyq6Ul+rQHiv6|A~_yX#lpgZ0_x-V_#_LkVPteXyGV96whO44 zwo^-^TgaYFc?JdsDD(|E@bU0~t2LR}G86v(lu^dBye7u*VEfYVaB&WK5!TC2-~Uto z0Tx&l^(T2thBZ5U7prX`O$ zcN9#H9-PWNM0`ayln7)z+d~;p3aL*wFVTNJoz;yt|9u< zb|eF6Q8Z&vq@ER4$+_5s-A#ZfuJW7KlmkTGa0NLHh<40?G2<=S5VMRm)r^u#-NK?G zU=4wKhL8aT0tSNtYgFd6VX5iDr~2C1*w|Kl32Dz&^Z!6@HUEy>z=+Tj27)QnflSY2 zJfba4)t12v2el~)Az|E`ZW#a`8fdmd+@{u9#X{?k!os#*07F8YjCQAmELsk2b6oqZ z8!|aBv1j55@;=9fjB^LK8?xCb#WYc#1T;iXPmf|aNmJbCDKJQ3Y3(#9VgAH!qJZ5B zC=Rh(xx~vmxxca7+97r;ZjDD`CQ1FtHkK6$fJhUV8@&4LCUGfQOEC|a*c>IfGVQXe zk>hn<{pNxZTWp~HJ&KPH;*j6^jop@2S;<;JzlOL}FlRe+Mv0CX|6~>zHbsx1Kgy$T zB|c_3WCMk;Y#{Exuz|L}*+B7%eD}Y&KzW4L9;iq?O!v90hdj4yK!^rcjjHnO7%=8r zOT%xpY`g{pHwhQWls1$`604yo3FZ_MBG1*@1HT+tS(2hX-te2%afSWSLCUC|nk$oI z{NF2?^YrOmmAmk^Kxi^5HxJA)3cOmZhuPbBk2UDLp+Qhdvm8%9?_+?xP*Cg$buzdX zJKw*j@sqeLY(GB?mub=ZI5jmjf%)oz^+`a;gm~#a*GYT-a>BJL8*LMl6tyWp_;B#V zHj7@pdWEF|qXQr_=j1&`dO&b9_IO;dI!Ck)AFTH^@mVz>+ut``~>cGKEA>YM{O zN`ayi>=lUlmjx>B#Y#yLtr8QyIOJe<_`bdlQ0Vjl3<63BRLOLouToZ_;CcZ9sK$4v zvaLio7Z{;5VXJl^Clb|#sZO5!KHobH={yynM&G+w#*E}-kI#)qHd;0}T^}?cpyZ-{ z`~$*T`IEsS!zj*JtTzMbvP}C{@EGwyrC?}iIFe{-`py2(n`aaDZ+orScUuy)10b~B zfR?PPqI&xb66=H0CS`T&$3L;eRw~qm6-DBm=3PiuYXUye;bV<9`dd5^KR>_cV>osA z3CYQ<5R2Y}9eAujmvc}_9Rl^abGv9X>~cxKS9gHi0syU)Ax=13RMzkcT$YuUmEjED zgaROD($doty{SsbvvsGoHUH;J?MjE@1Cm^nF*BX3V$WHd2Rp?jum`kwAY9T>mbCb; z5FFXpC19oVQr!qX5M2J#w(!>u`ITV*+u88{%tyKmP;^-)7K*N?Vo$My@dm5^^vP^R z#Yz9^6v1xSzkDPA@Bj3@5MgT2`lOEjc5yB9NRH8VzK`tpm`%2F9B{o%t1@jW0Y=_ca;fw#JhQR^EU z{7)lDcZS^0K|@3vIy43gMORDUB-#Lr2eQ|Ay^jRlUOP`2w)a8F!kqb}O*a~kG@#*Q zt;aVg=vty6EGH%>{{R#(e5r3@|N9Hn-mCz}#Y|!BH51mslC{~VE-;SrXAHZZi!2y2 zy)oM(pxOugO{V-*KYWWU$WP#{4d=66N>+Z}QwC;~2_=F=LN(0S+Hb2EdMJUx^1^bh z0HG4ga4{5wr`U*yxUD5vu-mt9gN@GtLig%-V533iZUW+wwrk zJ+~juM691bT_BDI@JvlhYiwXJ_xZEA3r5F)1T)s)w+oW1Cg9$5x!a?apyTJhdS&91 zJvKO$j{p@T;HG?e&m4qlKxFqz2LwD5p?phDrlGLHi~&OeRWSzE!guWr4c93$GA4#) z9qeiyp!YP$hTN|~u>`ZZIg!ZC&bW*w`FLsf<@v8)`M*R*M9h!ZO6c7L7jf1wRb5_r zxuBF3?IJ6~ig5v=P)uD}vo9a~M!;LLb8tXTR!EN%zBN(~XbQqJNcwbx3aB2ofwN!y z!M)Q$Y4opt5F3=`_f_r80fCW8AWWIffW@3D_zFpx*$msBavv*#i@E?nRu)F?Z9{~G zmuB1l6mZ}b;Y$?suO}uD-6yH2V2L>Mqd{}f)jY3nZ2ahN?tCQ%kOZFJY@1i3OFV%I zI?ZQP&IE4XnwlDTXK*-icng&=efcNRc(im-kfcpCHOYVF3j1aW$~W{AxVpQ)y{f6H zscPrxSz{TB1Ya)gBQO9_ojMiqLP$u+eyI4R->&#?$3_u zhaoRscsM$)h7q4`$rJb8wlRCzQw9c%9Wa9i{zwBc9Ed0|nu*=kt2OzXPvnCBfA~Zs zth%^)d41R0IKeHUtE*dpH5OqFJ)+jwmyJ+TQu6kG)gu7v8kjc$I$v-tUOq77Ct|%| zPHj)oR&Z^BI%Q+Yeo&F20YuhyzQ<%C+3PtST3<)!=qMDPbddN}UwUmkZ88TEPQW}+ zY>~!9(xxX9@*t3dQx0G$0H@gX7htEuz9X2TNT#3i>`$`@%TeZls7CdJO6|sfRBE?A zZJ8OrEJgr(fdpgbH!yQS@^3r-rN8tfS`0``<8s``(r$~N>UW`)2ZVjrY8H|I?Gfpj z1FP@GB55b8CP&aWOkTnz(8uiHed{KbZHsnn<~HV?d|R8u!m~3=3#FsGanyuvKo-D z1Fij;JZfa)2ZjAUR<1rvON1}9SHAz*ZcvB5YOpP{?FAPtY7&A838O519^;Zav}G(n zs`yg-tw9~bGL)%_xqI*4$p-_LR#v%Bp8}nQ6*Sj9uj_+JZEt_~TPm->b%o$kHhI?* z2TqsyWQUi~<5OwX(b*3y>5P>6ieHrZfgMB_YX>P2fLH|<^|KEO-gNdJB*#q+h9ff}*Z57?_Xi&BKel5;vlKo%ijKA`*~At8Y(zViJf0k-g`0fbKJvi@j3xvhV1 zb#)cw6A56>cvnHXc*7*D)bO@fhS}D>k0X}o>@o@TcC#f zl*mmDZEbQkNGmr$>J#LQAly669o+J(E={!|3L_{G;^5ekH@-7TR z3)yGQxI*`pF=leva!QFH9(QHwhvHd!zlRv>~U35|>aV!!)75c{ug-E9H3|1Rf4IyC#2(FQ*s z5F>ziZOMb2S62VsL|*;~cX45%0?zRhCw}=tZe9D+7h?L`7eeRCeylI#K>f(XTQD>; z`}8{W1bGVBZNJUT=)G8}*3f(Rc34vI(^mzG>CCOhELrepfkE*s<>glnhn5hI>-WWY zfE{OLRs3E8GS@Az@tUGCS>L>QgG3^+tss0ek$i3fwt|BE?|3s@@*M> zYk7Irfa`$Yw;TA6>hPYI6Ug%0*Nob+2Re?U<&f{c_-}lF-f`T^rer)WEXQG2oh8V? z3E2X2|LvPMk%=WGX@6)yPLos#R-V;r21-9I3#!Ih88C#wrk_eUt1BvAcq`F}kmCBa zeOHLq)9+$ca8;_IF|f04`%ojWqd$E|R?v)>$5vMS*J6NW>9b8s6Vs=3NvES0YeQG> zKpvMY{REX7Jatr1c@a1dT`;d)zK|5-$sM6@2HvD37%9IDq{a@Q!n>Ml{pXN-l8Y^a zhVJgwMurSRNBF?I;W!G$5VI;;Zz?)EJ2O+A`DEpE{A+4KqRa=*C+KEN%*gom^()Df zQP8`=?Bv8jhT&$r(PLU=b6-u4G);yqNN)Qxj#s`HL>N_7!mMWxMJJ$7pu|}C)qQ0^ zZQ#L7Yx_IY9QMX2gi1!$t-U=xrE83Gd>Z&Ek}4uWX6gJDIWDv55zoQEwRn?n<~%>N zy}hMpPEm7H79gYvRPKYG9ud)aB>!MUXPeMi0lKz>>^Dde8T; z%$>gF8Gv>dpG!I`q+$cc$&+D>nYl8=ui|lS6%J&_9+u4$ zO(&jE25Ru`M>ry|Lczi}r!dc7LcvP;&gPHy_9uv%Fz9KZs?zYi>(cx{Q#NwrNH^Kg z5>1dNcmQ+NlVMM@g(BN_a@9#x(zM4czKniNf;8wpW7$vpjPRmgKz{mINttc6gefX z2Y@0mkatS@2lhc?-`xCuqD54#CPS(oA%%xhaMGjB}(ga1y|5ku;u$2Jqwc1xkSn=7fG2Toytir zq)S7GPk46%7hzLSf~ZnaLgOQl-x6cbULLZ|=S#ZFQ>$7y_qTu-2>p+J{)|;%S!-kl zk2W)@RuJ3dRNrsW!2q`bD>`%=tumx>ukHqpMsS81EGFA^#S0bM>G7ZR2fLN4n_K7u zwYOH~ii(O(eu%4>*P*p}d7Qkf0Naa$k!LAG!CP@kz_esoN*D;T;07qPRAk;k{S@@nR1No>Gu| zQd3h~Z(wU5Ud#(bU2c0Q@;vnMojA$c+SSDeeJ^19fC}~xsiG1j)~a=9@^NzX0M>yK z4UTDnjiL+e|8gTB2E|wG@0UhY_Im#IX^*wd3>EUR^}+> zYxaSijW3{P+I`F~1UQw6Ffl=60o7kP@ok_!Sn8IYHU&2MpaRbw30c1@B}rHd;}k{ z`jT8bWn@8?5Ke=86INd+jbLw1bn$~OQg1IWKI2Ng2aN{%Iz;lXtaha>TRt z1Ik-6e>wT%$B)o4rJ|xzb54WsXox)q#LRg;TiXKYflf_5Es6n_8;X!0YisvUD5!vQ zGw$J|M+GGaK??BF17n>v2YqhM+u$V%rqahKFmRFFQ|pb!w%bxu18UPWHB39_ar-yg zw17<8wTtshmCz^zRl@t1nPl0ILo9!;*Gy4C_`7sDlJ;2E)xQ}^RuBw&ZX6sO_%!(7 zGzgr!@EVZM93(`Spv(&apOsaK4jm@9j@|p^Fv+Rz_?R#!-$dx<~jzHTF)z~&B!f%mKbG*>5bz8zu zm4ap&v-hbI-yp>~CO~B{Psn>II(Ths>v;}h^)!`~V^~1vd}Wx5#ZwT8kJwr*<7PocLJS3yG3WB3{>Ezi$H)~EW3Ok8u5(R zaQo>n6cQC|(?q-wfc{}M8O3rDJ>AeI39LIVW2AD*CPw(ZZZ>l8ue<0W+TuC%BolT4 zHB{Dosj({z2s&snH?562t7E@akZ42tr0h%Q)_{P|k&|06(E+;GH6GdYIh;U?-RwNo zTckEr43!P+;n5dRkv?-my|;dCHi=!M}pQ%Z2}@F;nK%11}hBX=Qds)dKwze zq2_95_%rS)xj)aPjMq8mU$?SizasbP(WRTZrzDA3p{%(ecyWn3zNrVLSi3?G?5gO{Udn6v{Mvd##H$H5C+&-ZNVETl?M; zN$Gg+#V79~Wz6e}&F*vGOi{>dR3X;@pQJ8f1tW8j?MIC!VI*h9B+;SjHGnL#90YTq zV#7L;QDDksUj{ob)CJZPDZX|J!XnNp9J!HSh%4=84Bb~7ao%%*2}63J;}h(00j$##%WGl zHB{#byLp;AYmiO0`7#NSCxHKeyd&91F8Vi1N+Wq07?aW9at!UDK9E`}@%JqCHU{z$ z2NBi%IJW3FUZ6R8@-_QZve5_fC(wyeSN-e*D;fnXDQH{aiX*=6kk-h~7Eh_bd}Q>Xh6@!6nM=FV_*1z zoIQ%Sns`?CX=7k{GU&#i)f`jkw$!Ph%SiYV2DJ(Zf*OVyGnbW3SOoNCJdwV8;8}pBI~}`Q}(B9j5T-uQ%R)FF*z>U6GvO*CzAEePSD7 zU~68mktH?PA@gw9JpCPX2I+O^pi+pj`u)vZKy*jvIv?q3Y5lJdVv&_f>6e zhZHLdi(|oEPYE#I_0pdB6x@FS{K$KXGD1~4C_Ve6=q9~v=ZfkZ78Y4WMLcOlXF+E? zK}`JSxlasw5QrA1NTQ|JgYG~Wj!gY(>ib%HHtK=~wy7^snb!{uJ{KU9KDLL)I$Ml~ z{pmA77JQ%spNSP)#Nz`x>NcR7i`cHz8t%(#YL7sbfRn(M&DKP*hr!I=Is~3U%)bVw zz}^5Z3_qAzR`yd@*X0?QgMhtPbgni)vxhy<?{ppd|&Akmks^Qrh!EY*cLi^5`FpIgo`0bR+g5V-zFyd@?cVp zjpO63A_K+wE!x<>WGGt$bSTdos3bxDe1ZU0$?-k_Qm)Y7fYkJV1Ja%{I6L0ZC^aQJ z0ds7iXoF_sQeFxwDm`Q4oicxn`mXL^JKpbOM6R$*hZPl`^_6vYb^@K;ct=M^CsXX7 z&~yX_V^~>RPqU_a)EgS`FAYQMJ!maku&_`ks8_z;(Q^FLCFAhRCBys}ruvW}g8pu< zQ5kp%CJ9|`iq9G>^q=gX$(0;P;qky+8?y^ zTP}yg_@9>5W;9s3t!%eF{1jf6RvWSYekac@T}u&IHm=m=A02pQ&QI>PagXP)H)35i z>Hp=b*`BL-L-+gU+L3KtU0toMj;^jD&zlW@TWm6QVc+fV?*kc9zQJQy>I$=BV5AVg zCrr2iV8sSQi|m$$0lGp0_Wr&cnF59jqTX-)d89hL3pCX}z~aJgv`oqiAisPb-VQ`A z7_X6FVI6-PdhD*908RtjW5;oo{BwBPFQ#<~#GpdD-?kd;G^!0Eaqv@{VHF7IccjdG zKc4sAVDv1OR1NtLQk9Hpo4}MF|8Jz~-2Vls3Jv^BX27W_viS1z@SN}_;Hk_(_-{8e zLTM6$pV2HG=SGWLMwx_2IzMYN;-%CFdbdIMvIhp$9 z^@mI=v|D8>5KbKqvg#D+Og~@S>rQ4X`j?vj16t+36Ds9^4^E4pnZ+>yR1YMCBeG1a zfg0yIxXa=a|7M^*f(LHGwe|I&i;?6ahx{r!hy})s1mH)uL_`qgr{?UeIvoz6ii@^; z?lk=t%cf2Ctv6nuC-3V;4sHT!A%bx7NPH+?SEB&?u!L&A}k;O6YB!o*oys3YxD` z-!Eo0^7Ku|vwQac$-E|@t}igPQ`T6)KxJPalxi%b*($6l!SN1NwgJ zUtlH^4}e=3MKB0%pOWFSZwX2sG1ohP2SMO1+L-HO(@EN{`@C0 z1PNda%f*FI-5!6X|B_n~%>AHbLDO?Rw0JT5LB57m3ck(41*o#22M0FX-wZk(nhY;) zjUJ5+dCU9-v{q=8F}-$;*$8aoSoQ%rPg9&^Mj$5OSP*P$YF(LW^}m6iT|&SwFJizJmJ3$*lhnvFiT_k;onA_3jODZQwc#S!GD`@ zs)wC7YNTmlXLZ9>KtbV-=T+=+S_g)t{<hLQ>MVSt!v|>N3<$ULcu9fRm0WBrv!^x=#Ke zNr)bPJ^ap}gH)C8I6J_7J3C+>lSxQGOYfo)Kg@Zxx^msYitDEB?d!J$TwJXj9ITxA z9W8I3J^X+cOkcg?=3rsv%p`jFFKV}M-cf>auS^mmhu8RPH0$8CuB0K`qvb?gVLU~l84WzuJ=?RSY^Eu>&yb)BB)oN^!~7`B7C{< zl9+1$_!eSNjvjrbRq@Wx@bFX*!wlI}k~05SCjPQAyAnTFry^#bbo)V{WOh!ft8G(uDMCM zsavkAs849+;mIFM^6u^X`zvd27EIhRlEjPK`=ag-mS-LJKB#Goi^e=#@ZkH>plc_M z^hl9@-r2wQbs*IpdOD|z26kmJ-afB}Zl0eOJcD@p?j7NNUVo3;sQu-p2{tW8Q_kGM zwQ;r1n|d3YaZG-yv9{f1Jqr8r9Ms``u3b4tyx53at3G8`w3@UL;tquy;1DK>VpbMR zPW@q0I4$zbDJp(?4KYm6OZrap%CI75mD$^sHG*oK*_)|9ZhvU8^#1u}!ygsj+;jPv z@TnIp?Xh|GgE84BDHohIe;D4YU-392ZFXXmcx(%KhKBYtZx9QG)U|b0@eo(_`Dq%t z1vjV3idQ>NXimIW_@c|;ky1hP7sgJTi9LED zr4&4 z`X*w9I|}awt^_aQUoUXRU89jp{bVNR)2(15LNNGfJi`!4ZSpB2=}MS*~`KeR+i_SlUe}wQc5xq3xrfAyjomEZUe`_{=UFWqaSAT&-N8)wbXPJCm zek--eM{XY{a>e_sbax!+12kqk9;DUYZ)Teg_7g{OtjfJzVctzcY7n2U@1VA2Uby=) z@UE@6^|Q(x+xaT0BPtBK9m8wOtM_)E(PV!}>!lDL`^l;97((mcW^EUSxHlYlY5vOT zx#?2iC`t&J#hRMGu`qmM7xhEXC)j#*aGZ19s3M}%P`0_dmSY?CY$)mz=)6ZBN zZ_8k_td42UK22Bm$Bb&Y(y#2KPtT~GVt+S(-30ge*276k!?9=9OrJj;v{aD?@vxi0R>^q=E*T1?1jXzudE*1!s2FJi^$I zl|<`&-(w@XO@ePI8zsSyN&33~?MCdxV~(>p)W!E*a4x;KY`C8#P!ZKM_eR5A)>J*) zBeo2;_OX0!O_;oi6Q14$E^F_4F=1tMf8( zJHwJpetpHKe}exK^HvMDD((e!diMD7^Lod|)(cNxI+}R%)cmeW&XF1vvvbWXTA1=>+U}7+!Zna&0+fZgRrY4}K8GGek0)9rglxb*w z{DbERg2=aAV@c7@c(eH2PtL_XyfrQDA=LA<(~|NNWkPdU=DB>I2Hx8lFNYFuTTXRy z%|2y{{n?x#=n%O`C}wg?zb0^Gu#WK-H?k+6*sVvhM?OZ%eb_-Uh!JsWXIr|^VB4H> z)ZB2;cC22^;*TN{TeM=!fJ#6>jppl_Anynrkq4NB0%f%Ycgh@9;J~Lk`_p^k6x!D~o4zNx~iSM{g+`?fmM52k59?UGORL z7uBJE?*8Pf{zluFc~YP_5$&AvA1`L=`)gxXMU^_p#qGx%W4K~!@E17=*_)ZD*q>ZK z{U|l>xRe?dwQ{ZpV zYE_IJ(l7NY-LuUdwAP`t(u`5Q9;B;`PhT&9|BMSq)<2=P-=c6(f^nvnVu~ zzA5K9JJ`e84H(#kMe-6;4)+gBqW^wVkE@#=7Cd;*JQCW&TkQ_(?LUF+kDoX zZ7v@wHdETBHZd|UEP+`nDUXK}ijW|)#?r$?h~tazj8N3hppPJ{rOOC^9oS1i+d`xt z&$}e_)J8yVpj;Eo4iS@Gzyl zFGwk*0O8yo%8`Q_e*%xYpVg+nDBWP4)T0NHgu7Ke40O82p?L`VCHk+povpD#|Wip6O#wVp4ZZRIGJ( z2fX*d#`0@TJ$|B8IAVykBvt_jUsQ0_rc%D5XPvO{V2z~OJERiyM!gg!Mq%Q{NpDsV z>yD~>zT4vwWkQt{u@pW!{52daR~z8M=r@Qzu0P(IDm8!7+IV$28ff^lM0#?>z!yFl zw+b&!`ZLV{lPM%8V=AZERFsJJyvSY^SVRMgtQEJTk!Tqt#48?jq0L#JprUw24A)oN zd^m)pLiK(1BBTPD&6{j+V->gR@*=`yMG)}Lk&PhXykvknh8!0`$CiytMuW< zQNsB8uLyqpo^7o;m*f~)Tcfmf+VrC6tmZc0N z5_ZDV{Ghl`j3;e7eoLF|Lk$eb?9PZq3bbFsbYX0HuBH>>N_lz<>x$v*CU_4R;VSKZ zi%%(d@LbCEUg!M;abaa*xQzbv>@I5Ec)GyzGS8Bxw2=^b!#3{Y_qFgE#AN zD~?;KM(tBj)UWiu`QT*Vcvg~6EDzW*d$M4{I{;~BI` zd6?+0L{$pThq=}AK#r3KgrWKQ>?#){FCz*W3WM zb)s$02~ZprcY&WN&hRbhFIDtdR6jw5J<3O@(OruZoN$O`FrSrxwNWB2bvRoh>d9ah z?Sc!nlO3I{tHp#*_4(Y%XL0OIDJ~juQV75H_$0AIq6m)rf-J~kiZo`(scJ4~o!_Yx zS2_#p20L6(jVs^~lKX9xxx}B=v2asdzQ|5eq|bgOP7qW0CBDCijXQQ_>w7>lLAwyU zsEq?)E<`r1Mu?ObzA;-C$a-!2ov?VHRxw-K<%4hA$Q=|VtqO@Q|G9F2IU4I)x3ugS z9hC&2nlCD67U~7X_cp_D5L`Sonk}LKv)O^=EAmBh=JhoK@5{|yxi(5DVHXG^nO0LM<1D(0@6|Kl z0>9;t)qZNSuth9Su~J>vUBO^%I~1>|wT*K*l#WvjXm^W&pr@duXkGx|b%&x96)LnLi&EQklf1@q;YOVO+E> z9O$L!+`E&B!og4+dlvESdd^ZL_K{W7x^FhwnjOz@yTt=9V`wGV>hbg+1Tn)#0o2OL z#`xn4aVv=D_XeP!_`UPdS1KxVjOpPo>1{WpLfkmIB|^zwSSOl>u(um6Pe=Z`Co z-fHHL0cWgF^7IuEQW;mSyB2{Mi7h!ty@Yh<16&DD>C1vdeRjCsgsArJL=I#yoP$5i zecWo3F%Do(&h_P_HW9PNuf%f4KAtZ_2sbdr38^*-?(67Jzb6iUx13*39G6qlGoyht zlzaP_wkk=jj<~*wnr^)&&Fr%w)LWq}7{`ACC*82{`(o)+Iw*KS@|yVP?O?v&g1H^A z(xeUo#?IwiV46u=DX+to$6wG=B{i?8cKxIEYH{* z-;!hgsMe6d`W}1MC|7o zD?BBiB}iPN480*;ER<()lmdI+yT_71OJEQpiv@iu8wE8g$7$LntX zVBU-Gn}$lAfvCb&#xIcj#VQQ#OgW=8G~QZhQ83uNB~7~~$h2-!T#6vlxf~WZ^moX} zQpvaX%4+bqLnC6_a`ulT?NGX(yctXPBIy;2Rp(@JJ6v>ZuqhSXa$r>03h+(FI?slc zIp!)=8&|13)Of9-Rwm~+-4>@E8n@Ww`WV0lP1AZw5BWgTJ&;h zX9=p0qq3U#%AKJLXQ}#jEf|RULxfkBYP(TtEtFcGU{RU)0|b;I70 zFXJ5xB3fy|HVfUew;WOJr1FYqUsI2aqQ)W`Nk#Nk&b(<5XfOs4qAK+)4QPoPdW@_$ z=Pf7b;jxH1=<_g5%Pcsv61l%QU6EV+Btua4Ri?354c6Esz%!5>%SxxK{gMaao?WZ%@2=B0GBn~NG4vf%BbMu6y}Qs8&8$Evau3v3{!;je z0Sm-kMuYGdwiS(7z*%fLibo<=jRaj=uPf|C7?v7JH9T-kbtHgag&Od@@C*wF%i?Pj z6TD{_yqqFS;`Q96fLpLK)Gm&hUdV`s@*9N-%fVU6I~u73H|zzu)vH_O@xX7Q+yJZr zoC}E$PW<5S`R4`7g|nFw_Ng$Dbk&=lrgA|2MCGibLJ4CCs)(@PNFxVNhimV=uUi5< ztSFUP_ey@D?rEQP9gQxsy7r4zmsJr#nL9$d&2tcw^!uT6YDlWKUM`-Iupp{ypynpiwLaa9PV(>P_D;E-rL2JD4 zDT%IKqJLn`k_=tsnp0BVHfR5`M~?J8u-($g2TiZ1-yPds2f0*rcj#A=+KY4;lPfC& z8v}<5I#2d6YSm|GDz?Fp&t-m!YqT&EKKTYvH|-sSdn# z+`tz-BWkR)`KwYA1iz7vfFj{lEm30^uOxKNv2fBu7)mSvWsidMd_C~=IZl4b*gKa( zb>;u;hqY0EVMpc>#${Xr$K^DeFIUap2d!rt3MUsA<|vKVs?q_w`&tyc!dUqkyDD>n zW#qNUn$$dJ_t02c%KEY~nrt0(vh79#2gv5%2 zx#!>q;XIC!_^os6*QKaep14&7L^dcDXBd}Dvv03SRVQc+S;UwNpc7*O#t-AMCsrd0 zge^kS=q)pSCb^0&r05KaeP%H8Ajh1c{%2Rj0Tqzgi)LQ!D9&We(9mG2SRCGKjY9pW zy4XE|$w|%3i^MKW_)y>u&L{jfv)aJuTXZ4Yr;I{gF8=hM;mOYanlGz|6OBElWn~4* z`D+7~G$kQoQ|DXC_r3rnzA(o}@mLL7P6t_Alvl5u*5tI{M%aKpu!*S?UkeNFm#mT< zj#vwu$RvwaPZp59smbVRzS_ww6qDq4luUqar6`T~0D`mNZJbW7hg(+^rSdx~J7aWk9?3TmiMFq9qz>^c6^1ntn{fG(iJNP@ z!q%XIsiY_#gRBiYeQZ4fQjdrMJ2Y3D0gUw!Ne=_Orc#XyoDB4~poR@|36qK!Fj@*R=KP!w9TzP;B3v&#MjLhl30YCN7g5L z__%8U8hsR>8DBes)<#p%J-p|4_yW3}tgW{ZrMXMd>wI|4sZ?c360eQF5#vFP(C9)N zmvzx~5647JiMo`&g~dsDyyJ#h)A#R06{5&66ue-X51_T#)W4-${cBWfZCNnnoQ^{@ z)GC1_)6p*;rohWdIP`iLv2D8ek>11j00WkIFJkJ>U%4Y{ftfz?mXZM~Kao_Eq@A+N zV2+akBCIM@3Km;quoP6kzJL9E9WfvgR?)9dRvkIuC>tUPB$`sv2X0Gdmsdlj^E7Wr zi5CZl9}tlfmewKQ)K#?Vx%oNgmV|98>-XCi8p~EmIez!bR+tr`ch&?+JG9hybkOUM z&OjStaaw4;cPMPIwVu6xW$EhqIby-$*3_x&IYTS`Bbut|!E*cO)CH|F9!WFq?dBJF zB?z<}iE!N2J-s?LK?Qc-0k~i=@RTwN>o%UK=z1(+2EkIGmA=1ssTq9 zJS}c>9XR?5@F=wPSt_DY)$I{$;Xw}6A`1q+r*vT`@29R5Q@aaGP`?YAv-I@h3T+S_ zocQ8{+S6I7?#hSK7E$8rg$S!fn#8HSf3!N$ES~lqTz~sSSeJ$bdvsTl%)!jfo)!K+ zldRaHwU5DxdMtc(%+`h+^Z5(@AykzYnJ$HDHT`2FS({hg=JcH@>~XA4qb}4?+%mCl ziDa{EDFh+MXg5N!dMFse+3a;-qf8`I+lgUy>@)vs4#TbyL`Is5Bbrr9B3ah zEs(Nbo%2b^WdwxYwnR(Z(9=w6@1g;ZP4EU%uqE~ATxNSK zEq*tYl!)$6+R79TXW#g>dW;;=8YKx3v|VhxY$)vsoHQ0}%7uqPObcBmgun;IiYmOZ z&@R$wg@8IU92=-O*?Kjxv+y>Y^mBMqp61Zj(1E3mDGbI_j7?^}^=bPol zK3xwA9PV-oMnQWWf4)w*?V?J@-c;oi$p8r_b^<|Q>=NOW~J|gZQM(yw$-*#am&Q0ydrK-rF3T%xgEiKzG3okZbjzu0KE4H=>+}X`Sj2UAxgP7|~BW>*o!6aX z{07=BO@iDWf_{Ff0sl{IDeDKR_m6^*VjmpmM}bB+V%ERNM5e#!(La13(?=1=Kb0Ff zxc(4;OsYJpCWVhOkS716O*vUuiMe<_Xj3s)C+Gk5=HFZ@G3$S^h<{h4{ImTJ z1OAI-mEL3h_uq<4 zuCb{z14P9j-~`mb#2^gF&;&jn0~m3jUnj~aRv6AGjaUMj2rUEpl;0sK3Cs9fKg8L( zFbOfuZM4vY*Mr1SjC+bETyA?xv|n{*esWBngj}J2rB8XLZ&tN`OnzpdPo0EZf<$+4 zR+Wu&2+lFf4jK#4`h#KWKh4J<%J?6~{}q1;$B$y1HjY+Iq9$$@e{X2nIEpyB+5EjN zZewX_@i9jqWVId(le>wB!M}y$Pb~j?I5=7U10DWv;rMKz#DX}$48L&)`%cV2Oj1%M zr^6eJd>yjrQU&kvg`EH>pfJzM{JHdQbKGk6VL9Ic{5LeB5qiJ&j}Xf?aB^(xX8Kbw z>o^xPpS_ZANt+74e~qHmK(a<`FNxp!@Ej``u>NG9G9-Z*CW|SnS{upIL_QO;frGd7 z`r*)zqO{seN0Y;QP6d*Q9Bsy!6ITM7aq=t9OR&^90tgCXrAGUo;`V1{{5LPzdHyr& z|Bp4nLd?R<%FO)lPG9i)`KJxH98dZ`kC~+^fR0m!_-`LgFeXifokOCD66cOWvP*!% zcwqUE3lo1M$8Hc72~C8Ji+u>Gr?n+g4LzEGbOsZ2U1}BlKGSMQ=iMD!t6D2D7kdah zzRb1_i5~Rp@iEcwy}fsW>rYV{9yYg+dyTW%;DQ0hVT?Po+{KkEa3h&~nP0CMb(hvq zs`+{gYb@tH>@d178~rL@ID;)-QxZz6ou_yCKx(D{Wn^+%j@qcHGxUJI^b3dDxFD82 zN4UN$sc3H1wqgOk~29@@jh3eOelIhY1{QaUj6^TGk_cdjYs%%5tQt?Ez!$r|yBo2R!+K z6TxD4iV9ijf}ARMy+H{^=x(#YH_kx#?Rd%uPdS5u_rVE;Xc!qX8c6`-F0k7+8QGLJSkTaI9ABhA}T~_!h5vm_LL}G#!hgQQr0%WxB^!{P)%*dMt8(e zR)7=$Ez^+0z5&m-g8+ozzoFHi`SKD|L>thtRo*LIJ7N8qw>|WJ3;x&qIbl>7GvHm6 zlP9*g5#?%FsicMSYUfAMHX_0D!ov)4wtF7Jg)@SE$VD?J(%{`S<~JlOWl_4aojZGe zzc?xxq+C|_Stk@iz_7By4_&0TK2F)!#XYQw9qs#F-4_8l({X!>u6&QC-s_8RneQr3 zsfN{8b4J9uLExCmG#w_GwWpT4EqTqJ&pR^Q02ObTH~8`$xUUDU8zJ4^fcFu}2C5aj zd7cH81)5iqSA6oM76WC#KF#m3P_eAVYa9|TcDQUE_la4jaAxPbp;Ec8v9@RuHt;2YSL zDlZ7p{P#fn$rJX^#XLO9!>G5Jte@lHTwpwRB*`{|f9<{kiEV-Sh&yyZ-kun#8}3r3 z8z=9`(y#2Ali#%oa=%+P=-8v!nGx8-btMXn1&-vKMy)Verw7e!nG-dT2*zrX_LblG z_zUWogKd8&I#jv|I&``&eh~}I6%aPr<03N~Y z%kPdjZVMn&Rw1MMN{J%Sfki!_h{li?6`ZeuYj6fD!C=i%8DBZhXXbevsgME^iO70+ zMErWuy|RrWIwr-oIB`71c;!nT{Gm7t2V#v8H)h)AWcf(YZcEcCc?WOY2t&HUeX0pqbt&2&M`xTbF_Dmkj=5JhHHLX5{7FKS)v7%9l;W<9b|RmR*TI~8 z&dI^gkka-ja|L%UjX8#EjI%N|H(n#D<4F(Z&fs@bW|Gh^h~+Rr*|3gOpLVj*9VDsd?Od%)!g!8 zKePF&duo=Ekp&z?H!q_5xu!6%kO)rOvgDFaBg2B)2E={o&|@F3Rm|0-KDDJo(d`wn zoHGNLc0VTjCfZ7eAu&-9m@CrZ6HN)qowI)BEKTSfpG?@@YAsnJRWf2$`w&apjEVj277^j}_+#RhhHKrzaGelhSXBAh9rH38ZvsY_ zHBR|kIK3yhI#&7do$1xYIq-WV<_NQKUMQDoZk3~-3R@>Nwo&WKi<~ed-O*D?MFUvU zS4!3vgA1GKwVJtGBpr~LoQfXCVC|Ug!q`&M53iOJ#WaOsxS%x3HPdS&bUy}Fbd)R8sME6>t(UM_+j z;iiAhv{%4nN0^vV!1OYpDhDUStH^SS1`Agg_f=^Tu}d_166%wPEoK!pWiDTysfL&M zYeN#P?((E@OIW#a%faFsP^mL!k^w?_Xf=9kvkx!iLWf##9opFh!hY?Wjqo5ST z8Xdd*JJfkAc5ji4LlzHJ1^58NV5@_5PX*?FrqK>UW^?lz@r>mlMaC2YqtD(3+`t!9 z`9*T9*K7nOL;M!)aSQ}l+J~HO3tf7oVZOX~^Wus?*=E++<*CS}MOuEWWhw*pUg_>3 zW~vAZE<5XdG{jM(q3UuoD*QUF^e1Pzc8)4926c=s+{h^h*jFOUe* z`Gh8#VdzW$zLxuAhY_`pI#G58J2l1LIi!II_lQ zUhliBivKPet3T1ON;-ODE;VL@8ogkyp$FF~@38ebGW!|Wi?b2&&Vv+;Uo1R64&U^; z6Z6-Nt-4e8Kx|L6d*pAD#46=cB9z82%x6Wx!j!vj(!Q;8w78X(IE?z5gmm|ZSiak} z3CAkHwBQ@+tEk3C%>c8wZ{<~J(Zucnut~w9Ag6D{+qjiUsnu-WL@P8^%FwtlywC|~ zSu)vz-kCdUpn1Zf>OEAqQ5UyO{#SvJ8>084S! zOz+|+VI#dCsH#nHd=R@hfoPV|HxD2`&}eRc7l+5fFG^XmH2BHG^BJ)4%d$9&f0D6! zBJ|0b{DOjSB>>f4z&AQ4T<}YyoyxD^h$|W#LzA2M+2BJ5uaa}TF-(3fQ&2s|6anvz`R2 zWsk9kuX3y%jAV6f8@W0xbzi=P^6BF&?!GnFxn|z8509tySwQp}C}u?5-uh-!jO_=o zSI<0|o2?m;hRBPO9e#z#AcWHsE@GY7l)80!jGr3ClORQ?hcoL-R6MpzhOmRTR<&B|J-MW_Ie!#Dwe9qZj@O_YEX6Pyj#)$YvAa(i=5iKi>$ovGol)iuOM zn!Z3tUdgb5@NdUZFBoogHA9JpwTg!%B$CO(&%PzEdh$N$Dpjb4_Rg68ab%BBx6p|V zscG!8i*Z8L@Fx6EG)EHAVzCayWMR|Mi|Ez8ydePvmG=oPyXIs}Y`6A7nw1V#l^12I zdVZA*>b7=_Eedok7-?%G8EaJ+_MqJt_VjuO-qT}7%(s$cOxIR4t!l9sI>VlArt5_( z8Fa0h!>z)NOEj&vc#8e54gKb1L{10A5(#0?spV8+8*bdvNJMy76blL9*`MOuT3Pce*q2IwfKRuZ#o9;+O-H4%hP;fja3op6c+bRzevj@*$A9O}{MX%72Q7nI7 zqG=BuK|k;uV;cfJAO+Pz;8G*wL7Grnc&3Pop*{C0~ z+Egi7gBtQ9Chav6

IW8BO_hD3oTO8FZY$%1`}15+E+P7b{B+RF5G6maP9YH$p^_ zdD~6-ecOE*b=YMZ5OoJ%gg2hG`NsYmGH0ImA)q6yQ>Vs|ZYI%#Ly3buD`234BUv!q z5(vMS?l|X?!{1_Fseg5uVJDX`rndOoHA4PA>~`qeuS3=)>}qL_oa5u!1L;&3+cy5P z61{wbNA@>VdTh#TU>v<3y&e4oy&OFPW^d_+Yj){uik*wDq_$eEr(Fui9IjJ~?v&>E z_ZnjYl%>RHfjvZglU6wM3~@#r3qG*@D75`p^ZT`8snm=SJZ&+xPnt(I(Yp6Kx*g>r zadzK$SK_?=pz)eRBxW0w=X&f_i?NkJB4lbs7+OGZbL{ZRYZ@Kg*|?yJE8;M@tm0-r zU((-i`|Gv#73Dg?MG(Js(n@KZrlrL^c)ZK}VEydZ^M;=vCp2p9pe3fJyw1m4;v*qK zL|{8x#!2HA_G-`e99URa;DAbvem?5k%EK%-+t|bCE)tJ#ix!it<`f&_5Q0x4xz#<4 zoJ)k3TFDX90gh_wC(JoyzCkuLHWjY#)P`SimTn;?c^d2}R;G6vJ>CwVjkcY{vbq~i z;x=H;6*<8yetRojLar2je{_^A>||KipZ}Xf?^7e!=t?faBZpB_0L$YRwjWcYz`K}{ z-c%43iuMonFoaM2hIEVJ)JYu9o!w@!yHGSxlwKA@11c}rUW<@-u5#FT94udrVrvtYAq+XacN^9g<28@HV#v!fNC#Glxo$_UZYaG| zQ9@shAGNPgcTtcG1-Ke9l9+PATUH)L(~606)B8GDbjsUbfEP{<@s`n{<#(V261{m} zu#i$@il6ubc#7loeg%&nJNx;+KGF2Fa4k`Vi>-8MHkb973b>E>V(@+T?2JL(%*3o% zo4Jl(MYWK7u`y1Wc8+e7wnApDwOqi7<-dvTX&>Dx^Z5PMwc%Fw87qAOimoX3`=eW0 zdc0Q|x0-(1oC)YLx}fv4Q)pA6G?;r9@E*wr(Fjauc7H~RP=mk9cJaLZYJ`iDJ>hd+ z<7DS#qpy1C67JQQdx_ru{-OJ5^u0S2@o?7LxAq}b@zlYbY@6gM%hc8U&-AOZs%Z3< zZnv_-37&rZ;w%e7pmVk!L*-V99xFkq2`48wC#yFH68U>R`Lc-tfNq)|bfX)YP#>y* zVZjR2;qO(l&&C$thho$p)wfdA4_F*pd&g=XW$C71j!P@mvSw^lI(!bG3)&{FG~G7Q zWGCibr?d_&qJ9{K2~7%h(=c({4XlhfzHiWBI)2Od;H>?%$%$@wQ4q9Xyzni1lvxWi zF?L?=MD@u?5sInwqtlu8MnrMLvQK3YjDkKMe8Y5XDb1eG5^WeOf2`k%)~PjGaku=|`ph>Z5?gk5i4>W%zf;Xs>AJlY*BTEG?yenpaX$ zc`Ih6A(hM>RQ*u7>mZz!-Y_TN%WJ)m%TXhmoL@`67+eaSk{+8`)Is9mPc~2@Z=b7n zx3Ye{S|i=j1s!~^xA+&ns-A-O|CG`DBaQjDOz5BNu(*YrnX8SnyOZl*ikv@c7FJ@` zf25`V?Eg!|^O3%0U|}KVWc$b?vvL^x^~pb)7bZDnHEB^LI&~Wd3pYgzFI6W86GtXV zdlM_S53P%Wjhov?o>j}n+}--)k)>QrY9HDdO=2DnCNUFdX$u=GYxh6HF^RaD{mF&@ z>He|iPygd+Ofv2!_BLiBj#l;`nel&1zWx#Q{0}FX{+YHVX8ngg=uc|*kM;it18rR0 z+{LU-Tt75C@+N2A!!mZ@@eJR zGWAKR9k{F##KTeXM?vi}BuE@oN$}~1O+PB~uRn|0dIo=A{tkGb{@ru82?j|_^ow|B zFQVU9h@BN4t&1NOZq$SR2v8G1o}Coybq<4SKl>RwE^)MTH8rY)Pl=63(8o%?4XZO| zGhT9_*vYUoU-g^7z?2GVmi{-)ohukE3A32h$w0ax{Zuuw-S~IX#PdRVaRj^pWd9&OedN*&{?xK zaNL5C(fsr++ci~F=Lr!ZujY`{!+TvF}h%4yfA zq7_rDJ9@|!Fb&96inv2YF!P^Ww(O5ZAa``4zLzCnyJlR8zBHAP`Hw-9Un z;OHF=m!!GtnuGa7`b|w;{v;T?NUC@Kk%}ohKHA4>V-d9r`o?>fsaRiD4{XBAi^dqW zI3aRofCOiOy%W36H*SGJl?$cEDlhBSFQa1hafUoyhE$U8C~Wfs(eJt9>bCmoXH63o zR;-^Jo~E%|G)R^b?V`87hsdeU*qid!*z^(hUoUqZ;zx9?C=j8TcjjJLWP@dm-}`u~ znk7x8+&*o73VpmX9(aVKxCSbBw+pn1ysHv)hhgYS>Sw-#8mQe~{|8uP`xjyN*U$d{ z2#ak0kR<*Mi+_IN>>tWPPEM}>jfo2CAA&+xlmCo{9L&uBg@&AL|Bi;7Tz{kCNB5s- z$ozl8LbiV~eScg2FD(2Ef>i$koPWo{zYY7pM8W?a4&uL}^)Jw4WBYe-`d>UDD+?zN z_dnrDTufcu;t!tw12TzOd03hL>pZ~v!6%B^xVtG^xQaPBI6FE1ISX(zi8v5-vS4RLV|^c{do8PvAy>JP@n-DAmm^mC;(6t5HJ*w_aOk$hm8;)4+Q>bf9(C! zKt4=_fP{jEfrb0{KnpSe^yAo|;9w9C;NTy713vZxz)>JjNmxW6(Ns*JNL|obLz0W2 z$wV9bF;wTS$=OU@Lt$Vsv9NJ)DJZF^X=vFwIJvlac*VpeB&DQfWYyF)G_|yKbj{2y zEUm0FJiWYqe8a*cBBP>XVpCGn(lau%vU9!^mz0*3S5#JgZE9|5ZENr792guL z9vK}Q|31I4xb$OrWp!CNrk{lnug;P0nDet`hM{^8c&p8XHMK7s%O z`Y{t96Y=2}2&mT|$5Fr`NLV0IMO2_nT+m2aL!i+`lZzVrVaV82uQ5zr=U_3(*>@>! z{~F{Z<<}Yj9t`AT^1x64LV(v*O`+l6%R1ou`DuVcTrH43(^M}I z8vr2>JHY)+_>rQYjC=n_`gd_TdV0?oxDalIK{Bcnwdr8bA4CH|w3*~!OVY&q z-Ev-_#WVbk(vQNd#N@J)UdgMHJ}1lECBcbGI`#Ioj+cZ-Jf-n$l9T9_qhw$qzZaYg z0F^$awuQf+3>*1f>!r&<=H9-k_$9nfb_)%sNO|XIMKeUyo)I+4_nwvset!M&DB!1J z?7|n^7ZUa(DZ()gFiFfmkO2Nd}brU71i?g0*kVBlVbkV!J&xBzR2 zM6zUIBzSAUIKMJLG#|PU0vss~EEZsf%nV(Y>IXpPCRS63`9u=41~RN_Eoz*=GFI*a z^VMkA7^;Ya>lP=gFkxwy{7d)k+Cz5Nc zeXjni_$P)R_1C#WoVe+=x%67jA~2zLQYJ}XNBUTgp`eod&?FDo=g!q;5K36}^~W0f zvFWEb01$W~q@C@W`o{Ny%`jbrN;g7#iitaRe%|$U#5xpW^H+`e_WWR5YbrW5rme*u1b*%gZWoUj0eo-}|1fzn6+z7S9` zZ4IDHK>*MgiOhU_(eU-8Oitu$TtvLuD8X5U=nnIsbASXxu!iN&!Tisv#@wC3liCm} zDMP`4r^W3GA{>9w*AfmSI%^DN_##K?ev##W^`Q>X8jGBh7<4OYi|sL40bI2F@!KaJmN$8 z`2$@*;&iv!Fqc--hQa2B0>{v#p^Rlx*VyW`PR#hzQF!RtHiHaZA(kEft(K@{A}2nKH(muXmp(lbll^y ze-O}9jQK4U>6f*<5(-mG@Z~Z-@6s>`73hc^|Ed0@8a6?DQz}@9H+O?RkS=iP9e_!G zgE14s!F_pS$3BBj8%1KANE;Tv&rNkxvRc~Q0UWF`ns_{^`!?7q#gJqxy*SylxUqG~ z(+3{1T%chCem1W5?-}AoACn`e2Xnp84|M7P(+0mp?7CHV9^sCS%f3c09I{$v5PjBD*{$pt1(U9K5>30`diPFuiN*js0Xw zxRux-^q(N{t=57$Mimu6758RYSdq{Hgdl~G_2__ifG&U=#J%1TA=I~7L)OJW=okE@gn}Ic9xv~v zky#elhFe^0{2h~q?>u-7O0Yafm3%)Fs@#|AW~PkR2EL7P@l*HeXrI1og#ns_Jz*gh}*jx$T>^!(g9l-7UBJlLL)}+!0p9)X`BYpX!FPbYQv&Y2m#)%eVg5ka4me*lsrlXX%YM=Q1Rd?TBm8~GnL$Fs?ylKWV zFRSaAX-=xJP*N8ZnxLCDnf}v~6vK~Twi1e!q!q$6kUUB*7J5J-e9Q`_qtvc2iU=QE zmg~^<#1wlSrN^Vgp$uMXl9Dec`Mm+}9x6s6zdO3Vr$F^i_s2ZV3C2n=PW4xBRT;7S0ThdF$fI(V~tG# z7^y*6F0DbjW=a9ZbciqXW=5wDTh&A#mw%0rKDm7q))zY=8rRk^QRm7gj1dcL+#X5XYq;9Gni5K#mRZ5_( z-YIn+N^c#30{V1;U8@svn|J|bRSPtI?(gB4yV6}BV75gWuG5vky@+Q4VN5fN)Hg1W zSG8Ts5vjDEDRWnlw)OSs9(T8C{Axsh=mlUExhDhnW3Dn6nDQ^s6(xs42UyK2gS5|r zUOpCrZ&-s2mVTfNCB%P0jWEOq;u!lXL(!%1I@48z-DW=S-dNV&i0u^&_O31rG!<~# zwX6P=lv#HXWSxYv{<5*vm$P3_*G1-w($&RJ^ahKtA0RY1+DFuM6^=K4JsNfoENhSC z2UuD^4%9$-L}LnF$SV0NNfdI;@D-$CdHLze;0MQ+*Pp1)`4va{7)pA&WxAz`z`(<5 zg!GM1fsxs4+u-?tvCmNnxlR^sO5v12nrEA0$KwLp;OWO$wt^Yps621`4t{}^Qo^9E zd&{4?T^bmDtRr|C_NVl*2o1LcC{3aB3d-ol_Qti^t;BNhmIbD=rRXs>F)$HAw-<^Y zOCn|3n3ZuQ6x(Z5_GdajNisr{c)rAdsn3DfA6P}!(dn7-_9#Q{D8r~|-A;IXt+)4a zt?f4whLqb0a&>Up>}*>|JTJ0 zHCRH=x7LLkrxv+o7%MBd4cVdVidgM}G2D~XLoKSsmx$LC^cVTpFM@P0J~xbr1-t8Z zaiuwi;%fSsJW#LED5LxOD8I_x>UYW=j}Mne3JCRI#BYw{{cXHR>^|8k=bwlXwZ{)h z_J)EJMIc^mOj#%9bJ&26;*-aBj2}0Y@z@$uF-(C<#9$=KD?`wzp|sV4H^EB44hiv8 zfucB;MuR2#CP`KL(*V`>mEr`M=l#)k0#E~#hH&F^Nm`?V0ngLt-r_0~EIR=%s#miM znbkt39#=q0#mejA-LmZccL4M$<`xUE@(Z2eX&})ez3Q=2Pa=->#TS!IbDZam9@Z`; zy>uSe4VBMof^6+Ti|gmd;5iS!?T8$Pw#Xj(6X)ExZSc&g)>7=}d7JZX)+CWhdGC|H zvxKslEkV>J_qaH_+-kmxlGff($pkr@+3JyB0DGS%X8G?vzOEv*SXq0)=lF1=Jlh^ zp$(IJ*5N#rCx0qfy3$LeS#9O>IQER&=@(aC+$F{m`^17C@)L#K8JwRz+$~9iCRO0` z4_IK)B~b2YL>|sUAXh4j?LAQ)CtMR%+Pa%*D3gQs$zi|9!6S|OL&^i__DZJ(ys5UmvEt6xpT=@6+$1k>qxu58|h!)GwVV;>+{b7K5CVK%vN-8&8 z!qR$>e@+Ip^GS z9aI_2!Za?_*0TY8O8k>w|N1M!;VpEq@wAg$Yl4Ch8KoZrBa?hH$kCy89ttL;fOb!zt{ca?tlN_X06g)Dl zq7_3--p!P%@v|~fOh!FaKx|0$GeScVrsn9-N1AfDZ7{*BDe}JO7ZAnmDM7sk=;S;)6 zTklTH6Lz!2qs_rSFj*Z?SbL7GS!pnyD>~`A|7Pk3HTm@G=1PIl@xZs06TZMs4HDcttUVGd_2hz8iD`Oo?Z@I%-gB+c2Pwv6o!i!ypO|R}h zRVLVuY(l4bmRc7y*e(PJ z^j0JTD*0eNb#d{ka8P7`z?w!xH`87t_17D5hUHk(_B7{}i-9yQ$sT{|~Svw)r~JF|<3oNzI2T5Z+)smfT}b#qa4MO_i_ z9`}n3{hm5kV#jZUqddqP&=8A8o^2ZnQ}#Z@IkD+wn%>5-pVTe$fdeY!>eXF-$7Ay? zBk@i#omvC>KgRD~4MPi%HYkY^YLD^4vKdU&j8!iUaZC(iTEcd~`1pgei=%VJY08kT zDT@McQthRGYVK5J*4LjLN`s0`1@`I91mSWeMFxye3uP6)JMgN-g2h&npC+0cvY`Um z^_u7s6KJ@ndVi;3*!DkKBx1!d`_k5Ox-kbx!(9dz*pD1RR1azkzYOi)Sf^Zi=M}9M z^N6osAdxUKa9-wNk?hyTxibEg(CjJ2Q+Y@Ry!3nQz;q1aB9B$N9jpd{cwbT0ny!kp zHu|@5&iHNLDRp0cD$ZYkm(CodArDg}(~w28>0&#LZ$9+${xu*7ph~9^zQ0WwNTQ?> zql4dqfCC6zl}PAx?wwKrASX&B-nj(0_PhRnh6@$mwZ%WceSt(}R!i1P!Qqc%Cg(Qs@l0kR(+IeB6_0Vw^XauXE$k5 zd*NKen$3t9dk&l{{ru7Qrsb&IN)-nm?K!R z9`EKUt`;2MybeYJMpiu?1nUH;!?!8aDZsY&9u|2koW8#I(O=vBf%e zv51Z-W<0)7Or4Taj4gN;vip5dLbAEc&_H(Ia;<3vkJWwmYhm7{^KmrF8bgm>+|>3t zMHWZ6(_(+kYREtIj?~$^8(dm{H5IK95<3gs4^(ZapK8-CS!@%&^#^;E5^4fzp->2o* zH|L}C=Bh3qdWM>4$o~{G&XJEU*s{i-#8fF(?%O*pEFP`8#$`j4*;^;^f_-%G8*+Ao zNO6$$=6^f!|7Mr}CK=#&AX3jkDs$5_)cH-oDYNDmC)p>D2eH9+mL3v$D41Me_ltN7 zKgPREcX7O2$z{Bgb0d=)?Av5mOF9HSF~FG2&!4m`-pHkvWU5Ip1;MCY&sN50>YEFE zXhltZKmGWUDNSI4eu@0Ej&5#-;}HG(*S=AP4=F1{2VtB@g%Z6c+LMz4gBS0XJ>TPD z>m@4~a+;C1{a8gbq|(?cvzvu`rcI$zsjKiZY&Z;Bhu0gj-v!lGZ(UanSip|KkouWM z_1Y%dcllKxq%s_Tj5$>A&)JO5th-onZV)FXQot;6hP+;?mB;`uB4shYQ+xCP@DOS4wBAM-4l<%r%A z;!+=p&6UPoL5KKJtwQ-qG(1SN)ihe`QzXv?$TrP+?g!t}kKMavU?4WRj*pda44VJ#zat?C>^^){yVri>nOxb+wy{clojePaA~Sm3jaOQZdZb?Yam zPg{Z+%RR}Rp9v(iWQFTJBf{_|)tt{vJ#NNl%DR~(oao@1s*>kNEL`FiCTou3>QwW? zXcK}xVA>l$?>H2LqvevJzSGt3XDTYIPZqx0#K?xs*wp?dWW9}I3H^zr&n3i*0ucBA zuenjo3kPmK8}(xHnIs5_!hxQIyrH3d8Tu*1yNcW1sfyao6Mu*u69UY2_kQ+N@#g+{3KI7$=K& zpfvIu%%@I85qHgO%RFW)G@Qfs=6yMnRaTS%S5MoN7(dO%#qbzy&Emm2u{`fbT&vHt zuSh;8;XeJP{ke{i(1QQa4DEX|wb5?Pn46gf>9rf!j7?AHqk}*KEM<3za{e`~qXYTk zmy&Qsx`%f5gr7LSI(t|K98^WQ>c+0?zScBm|C59zkwbZEqWzJup3b_!2&c;YIrw56 zd<)N#Ks_Pd*iAAn*df9b|27g%{*&egmI5RA2e1{?+Th%6FWWb#{4L>cV-Ux~uxCUm z+kHvWz7>!h%%Z=8`(L%VO?{SdV)|MhA56M`=M z;!*#_cdNUWB_X+YJud!a)mz*_0ZizN<*_X&sen)HmQzHZF+oD#U%ZxQL+MfOH{lb1 zOMhhp6H55VUORrr{$;5ZbCD(4OQxSJ z;|f>{=*uB(MS_oaHlh_&r?kw#dQuE2eNTARVhfT_9+9&izZsHnG2btft2@k$2WUM1 zldWbNclqO3(?)bNLiWo|S~$nGL4W9+FLVtapO}vYEGIDs8Ee1OW)8>O6DQIgUhray6nOCa+H7uB{pgSn^4#;$u)!ri26!jsLKn-H`b0j_ z%!%UQgW`0yWJa|Vty?$D14G^ig%vA!1N&bF2Y374oaf!jh(5X6Ml-TIN*QlKMiet# zKwL#d-+g7+>n8sJaN~RsmNk)%6}3&{Nm=t2s@IsYo`n5vmXDIq$dj)3rzMy)Q=z*0 zQ&6LxH}!6O$DN%uST@S~36h5{q!1wFszgCd+YAZ=cun+o5|cAwgi&XqsC0Khp)b+$ z*h^LPKLF~I8m_)3Nz^KK&bUdIZiO< z5XWpeURHLXj;=GrJ#j2~+Z5~E^o&kqqG;%OREG(xf&KAy2m;*g_^>yCYDQx90Wo&f znN33=Nqzj4^#;-lA+uFB0MV3Gd;xD@-IHvsm!zaBGc>d2DYA(?{wuCxu5l&{W}TBp~WKi=6o#nDaI8^ zh0Di>_CM`pQ>qGmuL{O0E9>3(Jm=KZjz+hYx3<{101`C$d-3bN zXnjSFkE0aPwHK9B8c^87)!kO;tuyy+i+t@0U;jlfhuE{nc3k1Lz>dO*(zVX|i4fyjPS+(!Dc~`7J;OSqGa_lrDM>M%xqhRg zxG22&o1vZlZD&UoOMgeQMIIkb%EW&DMnwNQ0mc+b^KA=+@74JVb-(3#&5Fhc=>&v3 z;%}tOFZJ$TfPJ1#bKWtkMYD;+rs=Y17XFY4_{}MAO1Qq=RECxTLY?h8+K~7dcvOE9 zh$b%aT+uK+`}<(&?N=O``dp#pG1&=5CCX__UhFCeW!QK20L`V~xfu}aP-;K9I?zaS z9&g$=XiHJL`OOk0x8XW8_s{N!mX^Xwfes_@h_B+*v=d zScPUeuu!JIN5*gas(y~7+LJj?9Saj>Pe<-_M_j2Hl6_V)BpxY!k;%HuwJC2}GZ zgwt!z7^Ard8bhACi4Vttiyx}-Ksfy2$m%P{yJBIdlY$vVI(x~ecg`?VuSx^am4v6m z_|sI$W_`QqxB1BPS2N> z;|)=xf`cyRJ6m|rcfbQcKLC=y!x|)gNj=Z`g>Yv*XQ>uL_Eko zwQ^vfDW}Tw(2Q-(;=gBGGhJKO@ESL}^7&-FIW%rkD9Du2M@I>Ciw4h#>#2^MQzQ%q z)VHfIMi&~d9?9k;{jigyTt|nzX^NYg&~6|YhRD^tP`i6G~{Ri&tiJ_-fwUGC>wK9RJ`*EQ>qXQ_-)wV1iq9b&FV>FjFwToB8 z1G{&#V;F%vmBLhdpAVc}1o~Kg>;!e_$}B9_$S8 zntzem`+F$OflBqzHn$-;=#XkB880gcf+^*6Z8~&UZV@) zcQ?6gZ=PNL4e!eD-ZYgf*yef+?cmx2WMj-G+`)SG7}5NP>9G}uo6Jc@YdS+nQq*zF z2dl01WwFiEa?j1`M;Lpgf2#%p9RAlzcaiS8svfiJb%%Tw5LOPQAanMb%DSfScA)X$ z?jvQ_LN$c3X%rq_C9J9*tr{uQ|HVEzg^#xHK=N!S(&RliDL*DIt&L@8rx5GN=7gZS zi$YhSqp-Mja$zAjKjR(cg5-}X!R=VJXT02m>x7`M#Sg4FPW_q$>dWmie(ixH!Hm?7 zi;oyV2xGHvMzA6rqEL-_GBCXb4!(c^G1@4W;!S^c^GH+MIR^J7!P&89kYF$S9?|L> zD-OtO!Dl-U8l<7nbtD)Zg+svI9kG-!Q&eE+ZY;M}wm7lSaj$jc=~McrHFzuO`WYM* z*6FC7y&!pTuI8iz&C*U*5aLtuC)5cD$w{3w1OGHJYk}r;J}#$eMd9n-<+kZMUR6Hn zjhR~#PXZV?zJO-DWEQ2A0-i`;RI+7qwz5xjZj{36V=SI@@R|7WA{%l!kr7|hr*_pd zMc3><15!GdD1_LV8=ZdWwbtb4U30q%xxL~unZK98JZh58REqb!8h-DYiOgvL+!}hn zt~-}F)sTS2OQwWD4o29XX;HUQBE|>fkGKL_wTA?tD8sI!YG06chNx z(AqkoOCc=`#lJ2=j2Nvg5YQGkxky+%@{{R6ox+P%TnTDS(ZTGFvMZW}tMBe#e|;bJ zOzoGtMAwwwu9{oG33UHSkLO>X>Tr2bi9Ln4=e&W-uuJ;*A_-|P$aFrR)@$XQqhcby z9uyNuDXhqeF5f)+h9QS+w9B11+x$4Zag18g@Oq~CYv@gIn5tX5*w~AYyjsbN-EQaX z^YG^C&+@OnG&b9v%v^6S0N$=qbV^^oH;I!eI`buAC{Gor-j)r|iCGV@239)!5L1{O zD(myf3aCFR9QG$iOkcs`wNVHJQ>e=t=gd3ctZd`4HNLo8_Lsn!$d@=L5aEEUZXBNzaEZT>dYA_SUj; zI+d8FaQJg>Ko^z=GbH-q{p&FpzJ4+f75VW1m|JG=zM;&mJMzeaf%a<~f1Z|=z_i_* zsEK?Dk>N+(#Aarm9gV2@nG?o=SPa9Pg4;a|&yLB841Evg#cXw(_6C#|?Xomzn^BbQ zYX9lG7=d9-DF+KVL5%LOE9b9?ap)pqBdr@ufq5^w;>R(m*zZVei&-}P^y2Nvd&%{- zg0JAka#Ov`&v#)Bjltt znJ>&USzoFZb+=REzH3XTw)terLIxhNK|6$y>H*&PR{dJPTTtZvwvaed3+4|7qe2#WvJb-^0jcEQ$S zRTLpPzIT*%Jb}u@fqcvunaxgouO9=xplEZ3-}h76QJxRpu_`lpN`{IM^O1(7(Mxl< zXn&BdKlSMG+rMEP05uv0chGo!_me<}ZFbTQZfSEp46JuZeMpe7_Js1Q0MAL%lS^iq z2k?+xD>LfdjgnHkLFvjh1>}a1?UJRmuba^6zv+XKDf$bB z8s686P5FKC3ARRH$eYt-lMS!9naiSc!u%b}y@ejwf@Lg!lN+KJ=tV(jQT z>4&M^@Q0m|#^WQ|zHgue;z525DA@H5i#kiiyPVnIL^dC+!&?Hs2G+Lm7O$E*1b$km+rP1vlzjMfr=f2mJ9MvP#lPi^jF1`0o6A<4oPY@+ z6*yV~O5x@FE^6s)AaM`^$+y?~zyvW-gI>PgNa551kUdbn|B6TAx-9!NY(VY2{+FBIHQc76NTukND z8KJNiBI4e}y&%ybRd4Cj`>%F$tKQIx{gk)q0aAPcf71m;elf_g4KMU`nomTgJ$=mg zJ;Fl33XszzAp(-$OoEHUF$mA*6qe`*$1d=7~c;!{v;NUB+iY zh+Jz}Pqo4=YO3spGG!6t?q`J(U=c)rLsU~4hg|tv7__!SUAh-JDvoX_-f@3&lqggC zf$i-A4IX48HNC7%KMr>d!4d3vOjrqnpUvb(@9yaC%Gz8Joe>rQ(5HU@3O~t?OqDq} ztg)feye_%PKhCR?@3pJuXqk&1xEWO(7HGR3Cj~L7Uw?AhE0aL9D?%(F z%_{hjFVSE5CHn<*3wQ!WhHO+tY=9qPo+FE6CC(TR6@m40LPFxPua~VVs7l9$ko=KdiXrRhY8veY1!X8uz6k;H28)iz0OV|t1Cwc*ovk$Yf?AP$PZLAwoajZNtP z6a_>Fc1z>fZYbg`GJwsiwJ(6BzINJAl!?K|TfZ&bq*Mcv@&UsWw9VqFr|{`^1 z6C0S0i#gENu=UfpeQwnwn^+V3J&UxGkU>^EmH2F1;SoXT~7WFj4^T| zDuBb@Cp^UGXJI8gE{iT$ou6I(Q2u8@xi16PaYawEw~^LWcpaJ_Mc8f7AvJ#@7`XX# z`Z$B1sL(~|{jJ7Q%?Lw-*_MkDAuIE0ETkpYKJJ@d^XYnx=W&T(eY@{g>2z3V8cH!b z-*o)}_wn^I#I1B5g80SsH3)M)VMfo(Ul&)l^Bb7Hj?@9iGSEUhL{`0?bTx8fS-coD zJ_{BYJrumdK3_E>TUhzQi62y(sCX&kI~sZH=a7q0L!E^c82L#cv>~rP4y+&FJ-1cD z;J@L?;C=VE^AUEX6HXf@Uu%VO&})m8eOaMKy#=ef9L5|hRNMM9ZaSm+_6AouI275C zXW&Vij27UgQJcATB18Q`uocRsczo(=|e6QO{~t# z-!g}!a<|!bB6Y!w(fz#49hKe{wgVqVeX^6o2zTkhd*E!!jkr4X+PnA;*>w%)AAvo* zTiU7z=K9uOG9A)`OGX}3sBDlGGrhqb=X}~!U$20#ewT%V!l~y3L7SevMlY;(pn8+} zY8b5``x(8JSnwC5VYoc!hDqU!JU7y$`^JAmFZifeGTvmk{t_>l5|4?+u0FnE@$ef; z@z+esY#XS|*e8h$31Sd-<$2bA*5CdZOxloCWKTO!hA&3+O80p|yws4_Fl*3**S5Pg zcbOnYknmVEi4~J?_{|J9>J^jMgqaezK$m5*R4V5%5!p~dmn?gI1 zca3lkFpK;e^HS+LKHi?;W$|c0T)^P7Rg5HZyd9Nh+Tifp*Yz$luduJx@8IcmAs_go z0I}8JuZ|1EX?bkJZ2F~C>_5Op0n1~wUyF0ZHgdG(A0SRB#q45PBXw0^^1>man`E#g zR#}=}dZ_%WtglStlFtqZSL+pCitfb;p=1!1_m(wLz;9cr)34HWzX=^9vb+DJc>~JJ zzkGK8+Ygq_iSg?gTe*aV2i|Xci3IgxnULenTUutCzjZ5*D=YFu3uAN#0+hf48lO{T zIQBA1RN|d}Bpjs*z0NNJNYjdDVI_V{jTW%4z7$Ur3oOe0Z9gp_S@6DY_wCk&x88x^b+ldN(NKb_IhBX7t2PMj4E7zt>1Uq;KxCrJ++o#GqS;}a{?S3=?~Z& zL6U`oB$BbFleT9=en4?jc517j*F^osvvkX)PDO<*==#EvpVGa{4Z-s zVZUJ*ip435uzvtrAxhF%&q||JF(%ATB{kUM3n-gISnP^F;ouD+D8URM-ZYL&1^2ox z?|gqZFjrmxr|v)nok_<)@O z5?~-7^H)~{BU`^br*YsEWFEpV^E9}OIX}qQadGuY-Od2Ppij*0|E{rToIZs(3EF%N zOZwu-7!uqS^LP=b%1cS-JJLUKUQ`(fqzmA{fRSt85EkDQ`DZ$4&~8fzowyPKr*cOe#fKP{3!wF`iDn%ELWc+>$OsXB6KH) z!c=#T>1;|Xuf1s^7KH_!c6_zi$s_oFAR24RW5j_ zUDDqIu|qiWEX|Ma)ST2}%c+zh)}l|*T!fHqZCSp8B#=fvr^}APuWTzhQ*EJcX<@Z$ zIrH5o{Ta=u^{KM)E3sCYau~kX^W!?j2uG%f?5pKGR-Dp6J>OBa;CH%I?=oIev4b%@ z-$U1R54Ru^)Ff{7vw87P;0ZAjHaPKPQKP`C&d7q;SetVeHCb$;(Hr;>WRc9Y=fuxY z+Hbm)^5P=l+WXej&k#i&(Hl#+aoSvAYEM~IEtGF3*lpuJJu5lDpz=3Mj9T6epm0c) z$>$2j^}CDno2mJz@&On!@?gGb*y?R_Yule!155a91E#F((n4g<_$qetqC7w!1MMaV z(I!`ryR>>{zPVrP?=qhgf3&(nyAsFOCTdtmN{x>qT!&dNSmXG1s8WJYV8Mzso$V-= z%4)B=w@r4J4hL&SP9}+?gWN3HLCit-e)>=|=JeY;UuaaEB2w6!qd(4o@q;b-Q~(P* zrjN-KQ!+e1RSEH%LHGamXB77Tjlj|z&O2$Z?j&TGqR!jPWbQPo()i!?WI01}rp_Q` zcKl7u^SaQvtdFjmlCl;{CRe^VCCABA^6Dm0XX4*#$nM)&$z{jI z^3#|GxlSd%|9xrL<8B9+)9KA8Q|`Cn{Pf09{}Oif_3o>?#gb=tCy~7K#u@#A4`I}o z>PIGaQ_7`A@(C6{b|%|OJcTATzt(TC!2Qx*oVU8ca-?vqx+YE>G&Ows%PX+g5V>5- zGsm#v-Au<#R7DjRa%Ppt>n6@0@283@j>ZAAvQwNPA~euU~)W0vQ~nim-PAu+gX)0%9h|$vnio(3FC+3Z$FNLY`j*1=^dcEBt>bABJw`8?+()a2NZn9 z7UeC$Nc-e2jFU0{R+Bt~Rn1L=oXOze0Fq;@08YmQtE$P{u($Kqusv?P{}piK@nhp% z6ungFixJT!LJ#hm%NzY&CI3LA=an*QzE8$c!kK1;J4BvA_1w2y_2uf)*F?ceFAr&; zcSFhFk|bV!SlxPE_TS?Jq}EFuTTP77wX!N{y+7j&=Y3(=5*oc`CG=;sH{TMJqsqZn}xTtjq>=WRlcwhe(AXW$l*N&a8 zEhQXemUXg35k?dZZ3rG)VBE@=p1LUxtN^L4o6Lq;vUwC9={rqqYcm}<38|X2qNAxA z3|$X>F}$mi2X1y!?9;UDWFPAp9Y9)4>~%mH zoi@q%j7Y_gOR7qza)#`Qua0({xQns9FoFx=2&4%{Es#>B;z*G_y&nCsW-VcHsfa#h z^1MCUd#DTGvs;xF^Qi^sh+S5s#hv)LhmPo7qd)(MqAssoh37?{X4*bY0kbB`LQJ%* zcuoUl*65I(QEd!Maj{!xWcC>fTffX66x(n%#ecar3Mb#tw!V~5zkzOW_r_Wv4EupZ zXtp`kL|${L*6d}rr2(-Hl?f%P$Asl1k-h10Z^dhGcTj1=Qzsa5N1CC{Z+lS^^7nPg zCP4xuOFp*Rf{R-Wf!{u#xK~oIow8>?C;ByT+fXO1Ltd<_OZ&+b;Z=9We2C!did{e~ z%r$lg&zCTMHe%maxQxXNu^ zv*Ja(OOl$l0`+0U$v80nCz8%@+fH&daD}?wv- z=2M%O9|$b%T7^7feCOts;<)utT&?!%juNao0q4Qj*c931N=QmGN~qRFgSILNbz4J| zvS{$CC-slFhS-Yw-t6~`ul%OhnOC*b+$dm|aAXTj7R4ohxmRq96zbV1G~}S?vLvfA z_u2?8_+$TOAOry=87{M%TF&%0|2>lOYx{L*ysDZLJlcn0`u74h38PiG;FV$p)o;+K z*mjHE4LV91n%L9Hz7)chBOnWQVEta(n?GYE=ud;-8Eg3!yQxeg;>)LAphyXOg-F*| zy8$fNFp*h9r+rx7}DqYQ0QyLQ3Ign zA3*iz+>dN);OaxRGoa~i=}U!lUOAXDn*T~2ZGjA*T=A1fJLKX1y5}Jjhc~y{u9B`Z znwt&&k4auLM|d(%h@h&wz|m_Qb5Bgt`V0&VMN=1A%sQ8XhS-z%@o(P9YA2ToMT{(^ z9T%gFCv;mnGA({~WbEp*R~0*5Eq^;y;bAp!BBd$I@AwV+sB!w)kt}a>FH?s1U;b*#k|fz zIvC*ik^72jlaA%5A65c}eF}?M=Ex%rtby%Jl4DHFYenWqGj=Oxfmd>MsMO|?B_ltb=8)d`Y4Pa; zyzK?c@sqFWzffUI1!M|iAL$^p6NS*WfG23Ro`6TlJY+*c{_@fh3vl*i(>Dd*eXOp} zuaU5Xpp?La@BWt_5?Q*2wU`SFTCel2oO`wYS_3%(Q{pD?l83bKre2`&L3}n4;Cp_9 zt>@8ZapQ4ygZJ07( zr2{ni8cyB=euTE_mR!nAcjB1*GUT^N2W{W2;Q$r^PISwj=$esdVk}TIMB#Sq?G$d55G;>WI zFdIudeZRZ4qa(0%8!~ZGD2c4jy9q?D58$9B{o5DoUgUj^jfTKSSe^+;#r{JtEy;+| zGp^l1?wWY%!B@$wk1|@}{Pfc2{IGG06RulDF^q8x(y-4b2;gydJEOM6=U7ReMXjar zXD*aEE~?N->~Dl|V*2G-k4S`WZK6sH_0VO-P7`7VTiikOtg#o0|MPCTaGByCz>j22 zj$UE>rbPKa`bRuOOG-{TXLrlgB}Z5!UT(V70FIbTFyy$QeJD}-;z+hK@nrTw#+)U` z|JxJpnQGnZH)~pM83vO<Ilg&sc<*(aWkCJk9-5j}nuY8WTu@TkXv3oj%!9aVL^zE1Yrg;;c>j}MHsf?IP zG5tNrNr_oa(A9z*X`3L5V91+MW(#nVetq-On&zskW^541qw@=bem8sSxofLJU3VwN zN!!cKA@^!hTSr$%7b)WrSK7tV-r1-3NL@;enErmmr0&62!a z9fN%yJ$wolFx3A#hXHPZDJyKvC7VJ++U8cIzMh0iX|C%MFgA zP14zb@zS6ay`<;Kzvp}1s|fJi!!wznjVeqF7C}uPZK_IZi#!>H6hl=k}e} zp0Nx14=PE=q%SYUIHynkaKL&S6Ijmdt+E0|?DmD;u2du*%$>kaBH+VY{I^Dy_=gMp zDhAJ8{mGzUwp~dtr~0EoLXw6?o*irmsE7|y#@w1})$VH{e5<0;5>)3nY}R{T{PDxP zT|f6yFR`~%Ctpa_EHc$+s;xoqTi-2Q>sPZjJd?Z$>84IGH-HNfSAt>Uv6lYMeY7s` zR`-khB!#{`TRap|qn^fZ91SyzctprQ!!$4MWPdr!l5evGBwhBZGjx7@sPQB4y-7tz z;aWalKb1Yn&%{**(bh8?poAU0L#d$H^$z-Oi)%hW#P3yS<0T>L232~}Bb`F)IO z@_KA188S)X|<@1jHbDXiNR7px4aCp9^PhwJ?l6vI_$hpUgM z+y#kSC_UQk4-K?bD)pDp6O?T<3}Rw_Lc+j~AD2_1WfR$M`r`T9wDW#{d)M0W?L+BhP(M{Vy6BK&2C*Sr`!{-akNzLNPX) zx@BSb)Q3~_Kl^_=ghan>;GgdshQ=iH)8NBq>dkQNJH&kP#VKf~M6W7;aX#UCM!HDP zCe&+9D^}jfq<$Kn8Ij2Dva`(CVts41p0SrvTVXbl-sW54-JqY#&4hY4oC;S|p5gHI z{moVuu{sm8Vc;R)=Ofq{2OpEuY;EG_|EWd?i79o?B%EI=>-vpDzk~_w)~J!Y=>-SK zV|b(4HwORN8Cy_Mbx!SaaA54kF|Z`3^W( z9>4h`3bD&`6~9s$Ja|(Yc52&?&qELwkYeZdwUmgRp013(6d-L*N|2%1n&$8b`kV(} z@(AYvHA76hB$&K-XiiOd&NKz@mW(k#`~MiwI`G7KjNai*!|C6uVer0LOocI0kKUvk zc9O##YS@$dMGi%{GzY5=;wM64Tn^x03pNUyW+q^MR<}U3TK{vkcBD|U6Pd}0?1M^$ zkfhZHb!JG;V)4*d%?U_@nAFXE$j0e%l4RnY^dVSghBTqWYCEx`maaY}9-)Fhl33=;-Ui(bP z)QcuNc@xGDdZ+<4ebX1#kOk9rYaCNmANIBKp>O$=vB`pi%oCrRP;#R0D?C{;y>H$u zOud>y8iZ_hMq)Xq{e(B8AC|WsH9wc@W)x|Nfn}(%`sF^#y4Ba*hS&yddI2}Vk$zSP zX!uP>bKyvlpBVZxN~_S=lnGpE&r7o0&ug&}OgEE|W3+I!+YlpLtEsUxc)ofICS7My z6a!gpIljOuLT3E)#?}TWbZY1kKw|-p@p6rL@e;r(&x2Ec3*@j;3p`+z&t%3HTZpBM z@e@V+feuOS{sDfZHmV9-$o@}z1?f?WxfVd&OGa(32XFg6A9lO8GT|GIG?{K*#u93y z!sC|w2P{*FiFxq9kl(%3GVPc88chsgZYJB+M#mr}RO3 zy|tfnIel2Ss9SMP`cTO%b#tG^m{%fafBE;~*hV!08wXzIZsz@(YiPbAbHKc!0J2ZS zEb3aGU;DR~jT|of37yNy!ygo~s-v+)zWoZNJ z4Iv1(kI_;7QCDGfg=MdKVa0AKOG`1+)7caM(Kj4MP6f3rm}>-EejefC8E|W2uig6I zup(d5vSGEd6%F`7J@6bg&sLC4EMGsU{ML0}Gb+o9>d|C~E$ifisIOgv2qiK+HFKUC zvX%UH8k*qKJz#EO%@d9SAux$-QWw>9jZs$dw@Y%o^#zS0bb}+;Y2P2ms;iNZLn`Z# zi_)Z+daIa^%(^Jh$;T~NcrA7U%Z20)uYYJ;e`2LO?Z}ZJm~y{1@s!gJL9jiVn_Yk! z9{a$n$~QDcqP+@B?2x=m3=l=D9&R~`^%!RS14JlJerTMnSNFSw%n-i3PN;dHO!v0{ zrrYTWneLzt=(V81XtUXOu-7*r`=f)|%wE45RUR<;^(x_lL*KZP*zt?v6&iB;03$m6 z>FZ_xOq*e;kQh^EQ{%+#w_%|ETL%B(;NAHrpKzxcWDpQxSbg#kA zm8fZrxqMURK%Q#<13tuh>*ou=8d?S#Uvm zGx-U*H}}I$+usq4)~%Lm`@Ai4z@JfEAZCeX)%`DWbmw>1Ot3wTxzA|?25AWL=w1Ag zs9!9B;cVbtZB9KE4SG)tN{p2Y-Eg_Qy{}SPXQftV(~9M|?B9MLIL?iy*gj1!*hh;W zcoZdJrO6W|*IM45u(YtUq8S)Ylzx6qBEg-}Kc==}7^ld7@U2LDqjYI(FHUd%_Px^E z5d8DUUaTz1zLLG!?1yI${2tATx3eG1W}g(6dcUZsIm`Y!AQvwdGN18VCGSb;SnW}Z zMXxZK-7>@G$M$45?Op)!KfsswZwpfUWF)^p4l~HY%k80$z<&*v7Txyt%g2nhqunyi z92gpZB}isluh1l8FC%U{d#`sxTcfS?2G-{K2|RuyAf)5q(LDu?GW*Sr!9TpWMgvc- zBGJn^Sgsk_!1+&A4u=kM`+k+IBk$eInz>F>Mk=)<{K-odsbA^q{KS|0TfL*pacZb? z(}cFYhmk|_;6smnL3fn!mWAHR@vZMY|FOrxhc3oJ%mC~F+k4H*iD1Q%}asbqqRUZz777qy^M3M zMqx836A=xN6oQpK2Q}@kfro#Jp`)lLmz$Y7L|fn-hilBUjtU}`=}|*@ zQZar{%S(f=4#$;$=XJc5zKNjEUwz0_RJ;KS^TBx`5!upmHm@_0(BZThbkstkR`o3` zkWvf*TEm5|IGm&L^FP1{e6;lX(N>=u+_g|P>5d%FYbz!1ziU4ra^B! zbnooF>1M`k1IXvdQ@aWt9E*=2$O3{QRni zW@b{id8&b$g@E19^U+;P!XwyNPhp(ecIWMJU%?GCY4um}IHF0;q{Uv5qTC9u<&}NM zFM@=xSgh=1%}SV!0|j0G0sI-@bOkgv8g>X${8#)`#_$}}6#pZ2@J7%~F@;IHAaN+qoEPeoUl08efcg!hhgAZ`0&5=1NDXdn! zW(KK5N1dMd_B%&=O>DFwP(^93lAn!@4_e%CRy|umjYd=-p|en~`WPMl)Yy5>^lrsu z4Gt}psXro%f-#VoO9`PN2bF8vyJie=wU-($AoGOagq@0S;5)^84LKv-ijQkszWr!voI0^gl%nJ5;Uu6qGFce7SvV@8 z`|qBfn_A6fRU;!{O2l4=Lgq)`O4T)2cm*x1!l5zq5E)pdpS5Y@o%JKDCIwP){@UdU zC-O=TIqE7$L1ERABXuD>1T94cY?MKq!I9~1;w$E3xv@jMB}Sy`mE6524%{rF7PoeV%6FpRWWOCFMP_tl7L?8yR+T{e4?wM#D`c&z z$m|swGmPMO#h(86O>HHiZwRz|rHjeHsKVCN$>8}I%cxLvf}cVM;oltjS#|8O!PW17 zfa7GIh-bpWy(2bs%_y75BIa3V0$llA=i^=Q+veUh40)CFamhXn#|ndevU{OJB2>*P z*%?%RH*-c;UKAeMh7t4Nfr)T3XcVCt6EG_ptg~T?XA_uqc3%y-1v|jvt z$_+Ap|EhUO;b4U@QHg$g>K>QJF?dsndd-edhAVigIUVB9#>)=U)c)4@2Nr1@7=f`X zPz*zmli11b#`ocf1h`44>0i@7#VZs>6FTZ>Pm8;6ou4Y*c8z|ZA&RNvo)r0qX^(ks zo^p^3>}EwaZg!%%*N-O~MMoe7UPT`Xq|&&WZo%8RSa`+zPl!+cv&f_?Pc${MMP1mB z6gmC+=L}-lOmiQ;+LN@R@stzX)bGGxJ8r0$9rxU&@3N35mZmo(>MQiWh6Ow7%&uk? zM9X;!hXP#By^plNCB#3o6MZZ~U(gj9L{2Sm?>mvwZmuVQ(AZW;NbC(QgA&#E$t4*b z(E`NRsWj!M#R=1YiV|xUDWo|(3SGl_njQvuu?0Qh01yH-mE<9F8F((TdVsFn2RTJS zfCr=mMMk=RqDW}(1yQlp$m9}baCC2dT}>%yhz!>JWBag<Z;Y6X?6Js|p9u0bef<80;p$U5{DfG;)FEYlVMnE4s~aH{rR zPtFW(Wu6EB-{Sw5H|_sAUig1qUVJ7Y^Z(o${C^v&N{am7eyY;a|NGmiz5~erA3N3m z+Qk0<-%fRB9)3sOv-I++bIZ(fM04^u$$ucPWISHw-ZlVtx=e=E%_p7*e@Cu*Ic5NQ zN0lG|V{%I_b}+rDxLCfl-?CA|l>TX&lHgaL*=2r8&sUdAptMvz&_dWHmVE2o)2h-o zknsIlP9hD|IsNXcE$lDbsT^}36a0Ssk;HF3WI2B zxq!hY61FELKV}lv6PlJ*plGMh^J63VOwN2@*qTRZVa@RuLPCdW)S<4XnW5A8OTT}h zIS%kYkTP-oZgcj~&b!lF?>)FI6#aY%uEg;VM4hRf0Mq4|h+X4wIB#(JerM0iw`x`( zN8zYD47#}Zu=GKoqV!U@Yucfbwjts11K)SnALHYc*}rH$zqn^lE|Hbf*O>j-Z^OFz z^$(=L&gW0^L~3l)MBRYe`{Zjkm~zX|9zQD`FZbTUl}9jEn~L>K%=GSWpKJ*Ki1zD$?dbeXJe$Nr1XFk$)^p&ikKO;Ohwn$6ddSr$lHWoVF$&BJbd|m z=V|JIJ;-6D?u>4uFEg{;F+~mg2WlyE^AF}6ng!PwC8@p4gRz|cN()XpePRC|`udJ7 ztQ&P5+fG=2fGuYpaH{`-{u<15odgv%k}n_HM8TF`&;eJ2G4wLS{v z#t>5e6m)GC=lPgKy;$4kLuAenC2$v?&zDkCIQHOtfp10Wh=8~ot1<68w-7ee_R>33 z^IX|ZY@|!<@V>`1D#Yd;KhF$z#ncH-ACgmeeeesGaA)ob=)2`s@eI?we85-8MbLO}>d#yCL zI^X9;A6LUZdVEC7=E}4EO`JR1MqZfVv)q;4)^ZNS|Fkvr?qdLP{WrUx`$5tbTLXXD zOa7>74tBGi4NpRRGe2X}DXT?9CVCtjK?>F);DHtBk5#9rmu&`ZB>G=Faq7Oz)r}BW zdF|b&uonB-J0oB$iTb37r4lZlrajF%uz6E|co_kZW>p4ozIPGxsr)b&UTo)Sb&Pl5 z`QVVR$lt%D-tIs>J}Z+45VDG@&|{0vB`8@lxR-(b#rXe$Xt3yBnwhSEE3jUK+7Fam z%B($6`{~|0yaVp5c7xjbrx(Wn;udOrF>LSQ1sX66T5yNfR(EIBS6fnFXLu7Gm~7i9 zC2Qcz-%2IneJ=LPG=9%YV1L`xG%hpOg6SI0Cdy|+A?TJ1^~ksJci*W{l%JoykZYfF zB%>ElaiDMZ5=dSDo50ie3X#X(_DyysBa9Son+t3_Wc5_m;xC^NyLcOtA zzVM``a3T3@_q*5U1YUIFM9kCgSqHCz_oAFd(tpbHVH*y4qQ>0xcYD%225SUBByOPg zC+<67EF(q_C9_wNIWm&6*JU3>6hM%dw=im1Sp4>eTaP}RjWfA)5MR?Y&bcR?T8j_? z{sK39P7u?8l0b^X8#+X0?WT|f@+p2or1lp)J%K#0PNo|K#gTk-_W{$ge~y-v;0ZZ(sh?ZV4NZtvKF1?J`Eo}41l}oB z%HQE>NM8aeNQUOdnuVA7!wPyjnGRY;x;TT;A=Idwg50%^V1a-RnD+9Dmswwm`R5)} zr#IpPgZYoz!&r}iG0CejQ{Q1p6rx!h0bzI>6#u^GmJlJP6Ajv$!d4*l`dIQrYkbJ{ z{q`1C6`f*4j3uoFfWWs@l!mjXm=?3U3+)U>|1(r*@Ta630o0wJ_GA5{?u^;{@2ViA z>H?&a|BJ2qA4$spqCENEwko%P5I6t-4gH^6Sor@~t33Sw@0+U#h@heWZ?677Vy=FE z0yo%pd&a9Hl3F8#ak3y_Fwnd;A0S4=PYQRXO~U@mo`gWb0Q#u08bqocM8_tHN0e)B zUyp$CP9GGUSOJpKi2y}afIf~$;u4jTQE(u!4%Z{-4F=RBAXO1|KZ^C88IWOdt5;)M zKbIoBRtCnGT?}HY^;La^nH2OhB@VaNa{%e%r+UmEg@6!JszXHDdIU0kP;^RgeC;%{ zhdwCuzaKrRzLK{7?<)$<_qi6r#BrmO9bUO;Mm|~yH*>O42UkR;@fflpLwoYU6pX&= zh;4wBx8^5uXyhW2k~6c21k`(yL@Ppfxo8TiuPm&|X)SWik*yJV>M?uaw2+ZQ5aUW!fdW_HCZ{(q|K0?4?6xFPMg(3n9 z-aU~+KMl`jMkH3Tm6RL-gs>nWF*P93uuXDH{#dalLt;Q$|51Si2t@nko{OfdN(%@L zP6?thl{3ezM~en9>dR=3B#E+org`dOkhycT>)mVOkr+Ta31Hhewxqj)SD%s)jArAA zvX~K36aX23zz%CN1pQZ%W0JVF)2|qOrnQE3eN}mgfh|c1#;wIXNC%lQ=c19S@}TI0 zex_D{wA}#-1;$u3(l*FEu@(9fYzAq`t0J7Vb%h`u>to5_gdo=1Sws}$dIY1yD#D=3 zF-f9zkW}X1Cv`+(V`juQ4v-EofwVvo6hP>(9su`)Sq|G%x5>J5$~%0 zcD?d_E_y8oGTlj|LQ_jT5>rVo`V{q^l4!72LLAWsGh!Ja(c(m*TXIYeeG-^hqS$WE z|J-Dv6>G${cMYKbX2mnjLrjPn918mQzy4q(L<Jn5>UOfP z&}b<+wh9bv4Gb(AthYpnpp_8BCUOA$V#Nl*C?)Q{VNpzMNr_gtv*jOW5!HmhMF_j$FRei-Ss!EH`OokLTyzMY#c%4%S(sG%g0c3qbqq4?|tv0eav>&->hN`q> zz~eRppWGy;s()#v;Z_e9AX^b)miJX)qMtG&hOXDFNnOilm95CgO9c7MDLf%ulf(uH z*=3W>>yJ*ouhT>g@ftsstt1Qr>$@7}3oV0fG1{C>bfE3{z4@GriS-t;ZedtClg%|= zX{OerwXr-g74A(2RLz+5E)BckZhNjC%1b&&f!E?lQqOsCq{<;W>c%yB@{4%-9})|< z6!P@`$lfr@f1uYfQJECVtY-!Wo^x*V<6dS|DU;kKiRvE8k0y1UOV`t9_CRwas&@3> z+Dqf?9@Q2-hO1>}GA6svHAhD)U-Mf)WN>?#bXEDwHlE+#Y-nVqh@M$d<}1yx&@_E(=bZ8mRa$#cUh0wg zf^l<%VQJs>G5kz6cMWF)=DJfY{Lb|c_=dpP-%+4@E-_lD#h`NdmTQxG_fL;P`MklA zU006E_*D+!%bGyCxhocLFVwpXt|Q1W?=PwK;ywu*bnn_Y^uKsP*uufdQ#4ejJ2%;1 zxmE@^6#SGgk=O4;FdrRL9mrF&&nZ6lzMAAsU6&sLA&f9K=EY3Zk-7FNV2n82uSXec z#r>UsF4P^(H(=t}8XcO<7I`ia^DmX>kA>5>euoL$oENd5`fGlDf0`R0Znv2iRE+FX z>&~#L44@CL_{Co~w?is)#-v!2eBT>f_;zK8dHES!ItZca6hl#r zO7>u{>5?f7t}x9g4SRC-X|CFjJZ-Ilx!=OO0!D7;7@EP>_y`96E1-eVsg`Kz|Dv&=+{C z9Y3d*e>HU%cd0l8DW$EqPZFZhb~o487DK;)5QSF$^u2@l?f=MK=2`nOgw$oC54{%q z$_4Yud`^G5kw^@`YW;O;!GIkNZqu0f`tGN|D(VluH2?v*gpnId3NniR;kc z?z+6To=bPt-KNR>>8p=K`E#o1Sn)552J3lwfy#!?GOZbEO+U~aJKU}aHrD@}B)g{y z(_@Cax4>X6BxZ$5#95rJ>G&(R(6}@|wTD>chWJUFU;WinEIw%~Fs}Ec@l$J;iO1+a zkhn_eZC7YE&TJ=z^=f-MRlZlaYFpfMZb*h#5S=yIpvtJ*5|;7x*x~2eA%#r*yQ<9_ zBb>AtQys3!jzW2Xk}A)I+m|-F>x^BhiKg&(e;cbkuA+RahlGUbVqlOi@&0Wa^#Nw} z)uE$hL&Ia!mSaah0|=Jwg?h@zYYOX;0e@oRi0^9KW^AJl%XdJ}s6cHkj0plJw~MP& z@h6;JWfoe-CDIx4SVto}#PGR%6i^F|W@l>f9W#l4Ai;&~nGhds$=O^V`x!};Irdka z>`ddBoOb z++;ym2Jz}EATbNUEI}&j7D04=eX`hUGaD_(Pmk@0ul&yJmhH~{(l~GT-SuP#q|c9)3u_L@~n)KlJoUztDnB`$9MY)nm%ElvCK(xEN%)6X?x|5o2* zKOvy}u9w$1_~17RA?Ej}=~tha5$me-0j)o!fTHu67tpe4wo$`4h1@)-l}5`5RQ)qy2l6x$)rN39wE=Rkoo*#sRs)RBd1c>!==x&`K3&;uQ!cu@)W0CIFUZ# zmjksGx+B zThmyZ#qo7!%S|4rdsZ0V|P|5>HR&*<`<@}dL*?EM*Mh~d%ox`E+uI!a>E z)TVo>7xx>l^{;m3H!fVB^37c)N7O8-7UyBUKl+sP>I*u+#W3pBKoYE%;*$0C5zP34 z9A_c0M<)dii$YuGLS;a-Hg_16Mo332-b=Sg)?ca3`HvYy=()$fiN>9DROBvmA4d8< zGYMY2nYknw_?aIt>G4AR!)OiEy zIs^bl7`dP0oCKyHe*@Iucz>v0g3+V3vrCfd#tsp2pI_X{8BKW%z-~rp{XMT$`C-oO zC~zhAE^~%&F=J;a+)udlc#|m6IATj>u`t6ap^1U$%jfqtloBp;tgq>j8B0}_ISWr) zy`wc3K9oLwlXgpwtIh=!8xQfDc?6?S!1M#`llE!elRLthG^237?%+dwHm==tGq&mi zAW%x#uJ*?o$)I`8$rxqz0qGS!3d;N4h5-MZ{a=}_?zW~ykXyJ|cK9(|FmZ>MouBke zX(?8T;eRYD=%rg_Q=(g zh1tjHzC%SFCJ)6igf+SO5@*#?7zj1-)k1T#LyqmL7)MVI+!@FnXJR!{C8nI$1!Z{t zRI!}KDgoU^A-fJ>#T=CxxF~&-`X$HxuP8l#JgsJU;IoMXWe!2A=>{deld#jf8M^De z{$;;4!ZNe{d<9XdrKL8902An)1mVm0KM(<*-P)Rw-TM>{#!F&h3R=b=RU7fH-lkJ( z!}OjL-fBCx%Om_hqZ3c+l-yq70*ZKo3XrJpQ(IOXrIl5cDk9Su3f<|!1j5b;YsIxCzr z(rEfH*{<=#;io?Du)6vB)QQl4F**758z8j0gb6d?Drzy~XE?|^R^N@PEi4oglIRGm z>K=hQorYf0t{zcn8qxOB1lSlm@dw>%sd~f9LZKd3#`>e&M)z>+6_+~=sW*_ME%ORk zZTQ*SCt4MhVAEY3tPh-B?q*1`1$8!PaT$m3Nu#Vqa z?Ej)W3CqLP2`Ku7+vP(V(eLuf!lMB7py`aR1j(+vHa!xQmF-$5U(B=tX4vM3Ebod;}A8S#2TtsV$0;mD{n2XJ)@i zaE(98d;6rW@P~}*+d0x-Qkp2ljbS=nO=l&}-$|NH;$f4$Q=jS@=IWnxE6N@6b@RR< zqs7xkA*+gjK&1{%9sv8vY5gz2A4UT#s2{&nk##83Q6!}i-_xRyb(;igZ0-8c}h|JX&l4yMZg06H`HIaDTUU^;K;L7`@Dh zv{nG+Oe3D%sM9zv4FOF3{4E8gl~q^ZJeW@^>;7r%cY90fRq5-^_CJ@;qvEYR&nFTy zFb+sDbSc7*qeTCcUs;&kL9DoD;~*;Z;F72b+pI8oKZyzTd`hOnDCZ$tme2w^!P73y z8mU_}ccWwScWQx==ouxDpJ>@l5|?X82=H{&5%Xhw)c=brAaQW9)lQ=dL#Xj#PQ8tR zs}f9?C>aGd+q-8Xh3g(O2hRsIn!(q1HBX-d##h-doO~}M-+L483Mg@`0)-B0bU2Ht zJQ!Jl!7t(f*mSCEqXa4}Irq3V@p%ocGDS4(9=CIe?y!FDlW%q<;4a5Y{#bUA94!~- zLjW`~X6OJP>cY59oDNe3HxFY0vd4wwq=t6Pm|j^#rE%#|EyzQ%FA z!VUPfeQgqViJ}qJXD0lo=jv<1+6(IV^H`W$Ik6~)t%gFeZU=p*k-yp%M^yOK)`hW= z`?>CYiRgUG9n&R7nK*FoPM>-RMS1x_n_=bB=s>p?L2QkZK~?1W93Z;jv7%o{6` z{rEB0^t!GNhS3h=@RKt1=bIP%w}Ai4m5WWM0Sn*8qSbS_b)tj?jCxIyi*_h)GHM)t z;G#{QKAlt!jG;!^`9cpX-Z2KZl^HZ$*>Zl@0KbvIAPBxx=_C6Gs?G$%wb+6cwVrb& z(2mG0?kfB*HTp2DY$z0IBGn`G&|^l(6V5jyaua;e`H-&K08n2zp~+xt?^vN9(QF|A z31Jbp7E5T$#onYt6`K_O3qm?&G%>x0LzwZUA%sGxN%zs-X^`{{9V_W ze(ce&#$pLR=#bWrFGLl#kG59JrY*4f;Bgw@@iI+KRtSwEFTC!ZYtPF%gFrOVv0r%) zDx;EhuQg>iT&5Ke8H$!1jH&w+&l%9Sx7n0F8mqrlXsJgDm%i7lY&B}E>Y5xIhi^2) z%A9tw?CqKavC4Ae`1?Jv{bpXq4(O??3cY?&Uh|Iq1Fc+>UJp$*B_4OUi~9v)?vb@V zPU?WI_&XX^CPnz3+1q0xRa&6Rb-wPN3>muTWO8QOYR%beuKBUHNA6yplo|cS$||*X zSFLbtTQ5h}G4uTJgfgNHfYhK+?}h0&_Ox&tOR#SfE09Pkp<%P8S8PL@NW7VnU`l!6 zmJ*z_?aY^DPvEL?{Nz8T0wjvnvMhy@Ey9NiNmNcNUwk?OtQI&-KKhj+A;{rGcR5i1 zAW!`+LB0a>{jgv@*Wg58%n`e~<4{FNWlj?#OPxzwDg$v!76?EB5T`DAsd&}qGHr2f zQ})kA{rMXD8!!I`R`&j-{$+kMDN9P@1*2R{k*M%d`~Le#G5MN}>1gYP>~yBXp6^fw z-&G~eL^-?IAQuK!Z-zQ_>@9^X!S*>wEv>O{Fw?p#F3PhbqiqeA`cL`&m?B zhL5SqNLkz!;Gwf^ny1l>;C}^DtD9nPdAzGsXtsrU>(_fLu`Cs98E3SF?*JTswpVsg z>pODyth+K-oR!|{&*LH>SK&MUsM0?_dlil{Sel<^e5s4Tpswxg*86DSer?61=hZ=b zzc)8R7c;06Ii|&8h3`Vhw|7B~f43{$43oGtOPZKDo*K6x9y$Zs{q$u@qif#OHTv3- zMb_lnS$T(zxGOfqxP=`Jg{{bPwC@|VWIuz5RulB;vhO)~G{`V2kr}^hS)9mOSN7%D zewG}yuAaF?q6F@ieC|g~8_dh8pT?};1~(NMlF;%V_Jxl(QlTfeLxq0(?lEf5qdq{T z!Pw(7PQy-A#n^L^olb$jNLS9@ae!#RtTAo%<=*W;@>u6v25m2DJEU*ihuw%?G_j7! z56OlnxRj}?A~;#{cUfMijaeIQ-iLW0U_vIzS|eJBjlMkgpk3Mn*0@+B zd`fUduLk*bri~1WXzp5smom5WnQ%0;9b1Hl(Z=$*yxZ(@44)4mhsLgTzVT9cF;d?l zHxfW$ZtioGToHe4v^%~!eb>fM=^}@ z0`EAB@o)^lK#wBr~o44x>$DE;IoA*?g9kJnVVm1ql=<%R`<=B}KNODBQ zWj#1GCJA{|xx=eq8kYyipJ3LX@*aJ$i5u4IutrL{6lhQ9NaW#qGSB@ne|Kwk$`(!? zsjJ}Qr{Z)i?w8Nu9qQz}ZSW72Iu3`x&Mui(^w;$a3@!IRMX$9?dGJ5T_@)U}S)g8k zj}Oisi1nzL7|yGXhxR9%D*S)n?wfU}{$+U)ILp}&NZ$Qi!pv#ukHT3c*c_`2qk{VO z=a9DR5hoU9{e0=XS55M3tg%XwDECEw#B5?KOV|Dzwqatn?^b>srWk&gxNt_a0X&A= z-Th8#Zx^~BGZd~*5@z511);ek4v7P({p!mY8;-|q;MviF12wKjG>Bpz3^n`6@1$jMUD5$joF%Gw?29q+R}yu-~bK?uO$~R z4^~)xxGy_Bxu+KJb#LxI!%tRW* zA;K@@7j)bqV~l@v)ozV=Yo3dyFCn7JlRxMU2_`b)QXwoy_E4~(J52Cd&`oG-*0MAU zMPiIZIC#U|G_yD7Sb6)AQ64uMBBMcmHzY(f@uPdX-(*$h?5ItglF=%nXGJYJVR6yq zC#>d4l5aKe2WR%;?RovtuX5!rAMl+4)$`M}N#X%qROem)lLe=(>&mUM%8kFuD$FE; zdB538N?xko-7eo~>A01eQ*Vedzl2^61HO$+dH%&272;JXr_t~`_DiAB->Gsj(aPh0 zAPmPF>r>8&_Te&DhDKM+D4#|E-xudI+hR5oQQvZedSp9&Vv|hvKM+66+7HsR-CXrr zpCG#Uwa`|%{_3X6pOexj0%+CX*d-EBR{xWy%O(xe?R48a!dY3=3JAeg%{eds_;NVd zA$UGwL>;-y)xgDn5LRBn+{QaiQRo=+g}CSy$0wY9g1es!kof=_`1{T_PN|8 zWR`u(z%4%II}hO+)`ENnMMz_+P+-`_SD@)VTHuGD@N>prfkVIdiO#A(N%)^3vO%BA zIPsHo-=T~^nm%7GY1RohAQN&W(NqiY1kgga!oIHf$y!kjWT)9UUZx3a%i+nv2mH@b zNu&thk}&wv9n|o#iqzV^bE7>0)K>DZK8S&M!Dp=7)taxyb28{rt^Ipd{LhT4r|D;T zKo8Wn#D0xH2Q2l#Q8$kA)sQPY?Tiql9DbERpByKg0~2p!AkfbyY=XO~f0E4yjc%?> z)M=6l_s{y?W1i&Xs-?@-vnwt;?_QM&A+O2I8{>?+t!)+>)G?BVjae1xP3$yOL&JZ5 zl^1*9eQt7{8|KOPMHO3olWBMbca(by#g(l$k7AmOp$vjYC@Z2JX&=* zf6{N>)=bPlH$vOpVliP~4eR)amOo!(xGH+v0SI5?_f}t4C@_=4K8^ty=T`Sz3#%x% zPw17ues}w}h}(WQv(u4UQ%+ZR=7|U-MtWS3b(Ro=9bHl$-QnvRj6C%U_mm$i4A$sV zXBe|*xkrm?8hq0~-XVPp?)IggY;SibipUdD`2+WP6QdK6jY^_|_a+v4+_~E$M!_c_ zl2y1qAQ{}gwQ2rMR?_9gyK20Y|8=Pc*rmcJX9 zxuM%p)>g8o<&1kZsj|Zoc*EUnc=&J0zSk}Cd6UY;o+nrrh(VYq2jKCxheG_7-N@+3 zDCnri$)B)El!d>3c@#9ep5%8)abRI6Q|qdN^T(Dc`Qu%Elqo?or)EO{Qls#8*hoPR zWU!c2KIQ)|wTa_vV?qxYxYjz6nbtXH)gij)d%(!Zx?GS_Tw4DKtUJOo=$3enMI`d~NI z=X+$0&(+q<2ljSDcemu-1%vn!9l!2cbL4014yC{DUqQO~d~9h0Srm)$q4c_TwE1jUeiwf1jCx}gaC5R-<5z`wZZ)by%=JB@n5;X{`D4b~N+n!y9 zZ)3uv`TVl~AC#>|uHsO(q%lnYzMPJ}`rG<%mvbLz1=@4^D+0IsGn5sBQXbz_?0PTQv)7vtc;#y>!A+2%2}`OmCuhVwk~4_Q z^v_Udv}3fJDq=RCmpNszF0H)<|4!c*S-Z!sg~umFc)9=76PK4#RTW>Ew~;A{GA-wU zQ|cSAkE>UYq})Bov#Owr-O+p6a2EVo`(8;)Gv;oYHVE-22`IpQ)C2p;DC2AEk7r6X zX97QV>=CujC@diR{UVJ7M6-gEvqUs7-i+#(B)-$BQPNRrpWBrB_LY_1SV7Q|`a=jz zLmv}<0+3t*tnSy!RSxWKh*G2PxhKw}r=LY)wzb`b_1gpsNjQj$d*0BuCQQnQ&~01g z^6x=h>bamv2lNTzhKy>F16t7{U)LP&#F}L1{oduT)u&IUmTqo3?h*ClG2e^TfKzX) zCabUWv^M3t#$H}Oz2Qt@O>#g<$#DD!8ljMQdpRz_yLh@k$LCewAux+p!EtK#<%!Oi zNB3%6o<4E?3BA1!w}v2=wf;+aYJ8Z+x5s1_Us>;w7WsRp$LZ(o=bUz~7krrbwgaR2 zipQOuJJ%qZw|pY%ItmiBYQ{Aayil!K+Hn@xrEz)s4@6j#mTX&Qx8lQr^M$d4ZitQ# z)VG5mM8xTD6cFJAnd~n!6SSQ0qh&<>P4c=W&#Me>c zmN(j<=COT2fz|BDIdJe_gy?T%$QNyV_mz7`v)+Vk;^ys}#O^y!3VZ4nw4EGl=I0!m ztXnfW>Z#zT@cm^evqK-q_E}6oEzDI$T*R}2Fg`NUAo*1tGNM3Id>DnCX|uD4uSRn^ zBW6G8veI5M%S(Zk)27Lgr^)-1*{psR9d>~s#?9h;5U$)q__W7Mk|EwAOtHUpD2($W zWov?5yAYwaGgOVJsL8b9TMDY(857oW_AQV6@873B1Hm1a0!;;8I6cIIQ`>S*DaV8@ zKP{WR(LqD3yiqCLl-p4U^*wCG9HTZ3<^c_GKBy<0j$Bj2sGp`Qf$Jx#NuBKTtn4Mh zw=GFgw+e;K3#Eu+m3X6bpYLC`_O@KEJ=u9bni6*$8C-CTRK)N70};a=AOMnc0G3(L z8w@9+t$GO4+-GmRyBr9zS~IEeFwz!15^t1QT{DaP4fhKfY)tcVGv2S06G{YtaeBv% z@RwgsYMxt8GI~vujBE^gJK4`0@7emxLvscySSNOrwBO&IX!i;rhEK}T_y~>R$gH;r z6_Yq1+>3V?VQKxOF+cfK;FE3BDEB>BVfzD*G!LJKOs&j1p-Wsq?({9y*&hi5*o0tc zeHv5R*S1$mJSzpiq|q4j?xCi7IOOLZi0O3iEm#?BrJOz+aOWu}34d{dqeG)M zgDc2)o6I)k>+pY_~R>R-iGGDd_$+B(Jxcn@9@emg?vB zCCzx$Io*QhE0_z2L_Gy>Z+t-RnR;&cS^DI`Aj5p`fV$IA6+UjJ(ov7rfn=Tjc?ePs zylZ`Rma8mNH5Tm~#C=BjBG}ewLzg7)uD-Ri{{jJODa@DS=USxrHw&G23 zzF;1-cAW~jJ@VN;su&8m_1(++)Ao_rpYHf*z8E}ivB|&G&fp;{oqM8P_(tWQh?y() zXdu!ImlxlJZ;Q`TKi}Dhy(3vGDlIZlxHi)rHc3f1UNtg8KozV0#JG5&v>^tMj zjV^Xze=FRWdUmhFze1Fn6KyT%3fCpa^qWd`6_|T)2;u$wlgh`ot`nU@pEMZ*_Bq0m zs!%(omB1Y7{Q#?%>1?L9#_E)bbNU3xop#E;4M%!(%e3m6Qn3VoRE?X`u@e3< z;PcE>Gt@2t{hd^^x3STJt9Kc;1d6j~OzG=*%faZ0hjRW~8YZ57H+ec# ztkuTH%3A=zJOnPSAZ*U88E}){wf_$^{2a^_@sxN~Qxt?BMCxyY0Q-%w|`=&BD!@M6>Efj)h41XB1e~lzu5qrIlo*c2~uS6i11D z1}K&}%k1b~_4wkX7Dov9dgeepK{#XWyH#WrhWPrph4iQQ5}hzpyB%1&4y51i!<$0> z{wRhBqF$o(aZYR*Pu^-V=ht+?18e|&im~*NW=f#bH?)_Mvegd>m_Bn zabCUwdxq4?1lLISx)DkssQ8-y;huEYh*Aq({y7bt1?l>5Gl|qQ*ht=?-LN0=pw~4I zPla{uc6{g;NeV6YFd9&kzZDN8hwl>|Tk^N;pQj9+IOkz@hO=w6!JPl|bFR=*_LbrpQ7>)Q__rtkdzov2bUdHRpQq)r1=`@9v+9 z$!M_719egI?a%?lGVXQy=eGr@yG;GmIMgV9_OPnLAfn1!g9$Y{D!;O1y?cbCYp$s$ zrrBoOD*r4zn6hl2a{hbhQ<)=%1DUAzAgEj0Z5l+ODIbHFJ1%!B z0@;PXHEkVpXH4yL>ti-zGi7}Ec;ALqKFq}*iX$tplGq*lHC*Cs2S&iPAXo;vwH*zb z*^<+8iE+bX%?rWm&3^~MZw>S_bMyF}^M3SyK5lLHzG|$v68WEvILPi)Yy+$Be!$JY z?e9w0>wbOuo{1P$akZxk^0L~i^*-P)uvHzBz6Er88&+EDm>aWV{v*;-0_jL>dlH;=Bk^+6K^IFS9?E~mN^;O{RP zQ;XJY6>Y>j(`WbQyl93cC(-D-_Dsn7;Y`@{W#|!I^hXsHzD4&N{5AJtECY!4k3iKcT zf#UCkV)2|w(;Y-KR9-d$OLyPULuD%Ry{Z75=H~hh2cPM-{7m9?R5GNfY*>}HFbb{G z(-_eCMmLg5`gxZyiT*_qKD8JKV>(Z!O6_w9R3~}+x2rYkfjv*3Uvit^o9k;PYK2Gp z91xUn@3q2N4oN>*?Zk;pf$3<1oyJA?`j?KxgFZfxWpa?=eJ;+})au6KyU3Eupvte! zA=Q*QDau_zL<4#+(8KUMUv2ZG6w;LIfGs;y+#WK6njed)z?UiE!q2#=C+2D zG;7V&8Dfq|AXlZgX?NrkDTRUMHj8yB?Q?JVnpM$OjXdAcV_s%wC)q6^&nmY|+*$9coS0BhPp0QO;u{!qU^J^+O3SZ=O2o^tJ4^}{gg85;`;z-#S~6ld!T zeC?+M`Bg4f)<)%ch!N?MhTQJJa<#-n+6w|_DSdO>ixo6u>RIgylVFC6T;}wjvGs+^ z8AOMu)O%ybe*W{(5eXBKEUrlfQpjXUSa?QLxPH`b19Zr5^{g%=*oj=(th&O!8b~c& zDp{_E{i&-*(UN@#w)_zK7q>eq#6Fv46i01GAq1b-$ zH*Xlz`Sr-QSq1$Nol`e8<~uRpyoo9!Snq*yjPNR(0fl+gTmJ}^Ri4*03GFNzLEaPZ zYBq&S{2p$a zN%Qr~w<UNtFu`qrJ zMi)$psTMysxT-P(sIn^975lBsM|tjc@nfq?O0VGbUndi-TeNy>#r2bQMS*xxfFGK=|!6q6O&x5_h~ zRowVTcm`hchlQTOYk(s@)DVbwlHe7q+3a9^I(GNd^~KGiMO@h%Zg*H1)h_@9Lf>`d z@KaVHlNOZ>{R1J$o`B&5tv6#kf#g!>`r0Y4v6bb!U7qcZVYbR&i^tE;V}o~@Wr&VS z%Gh{sLilgO2bc9ZX>yVHy5Y6Ym4E3V3sYj8S!j;|#~ROUVQtSlbI9k^LPsLLN;@4$ zqshOc9d?AHu!CiE;-{lZ@5FQj)gQ_0)?}T33(M@?yguC{77LQ}d{IJ_W>mKHm7_&Tw7(mL!4c$DLFf8g zYOwGfBbjZ!5T&{8rJXFMZ`x?aB} z7VU+HPbHZqLz~u_LuZk^okHD zE{{`>EyAVUC{_UWv$P_nF1KNn@5GI=tJOrT?yP6h40WxNdy2n80->HxNPs^ zOJc>5kI`gA-H_9rDb+wnU#c}HVYS5wC_Xwm@%hw>X4f``r#_x=ts$)iYWoGS>rdmT zZ`0>k;O?5h9WHqO2Ra!h2Gsi#pL$yZ4_L?&$j1bGIrbU*0s(%sk>`k7(#?AEpzR+l8O(;Gj#!{5OdXkjO}X`Gw5)p0<5^Xp_o&>&@s?W4E~fmjva8mk<8EfcgewVetog7No(pG%BO@WI7rFSs~H` zzN9&iR{;?rI;P9+G+@quAiFF#4KQv)EcSEp3;mcA*1^i?yT^;#PZ>>SU;rs{sKI5? zDSHrVd^QzdAtw8r?2w0%QMOgH3iB~oDK~AzAzbs=z3}${%J3HBsq@?gwMpuA!6lGSt@g|`IOIg)PO{lkx z+xB676|P+%!L8oS2z@NBcw)fy+YCF(ZRhZ%;zGVG#e$fK<#I7PPvs?`>Y2BF>6R^$ zEfCF+vEw-hJI@#2JK=-5(z>6c6sIH2vhvQTlj+o$UfZuN2bDh(L>S@(1Nsgd&*K7% zDNq&qB^_)$ypIkkmSP}OH$^uke9^Wu9;Lt@A8_~?Q}nwAFs=%rX{^$ONElt^di;by zEBZl>7fH`!PM^xRR^U{^KSDcOik{Oq=<+hf@uy!zf zPXKOKYRu|6m2lagZxzej5eH8V`Fk))aTCZmNw>`?3`o1X*IrfB3Y$doe!vM0AZh=8 z5u$`VBjI7P-XCx{GAZg_kP_mgF%&Y^${$@FA{v4;Rj5)L5FQ2)2Py*GmI5h4#FJkz zaLEPmhbG_O3^B##7SgBJa+Pe%%)rUMh>7$gf&-odHxy2u&_+=k;3x~Z)OdVY;y1qX z7Kug{PX-U!pSS+xp@t3Wj0x?+)`WM-r7HtZT9KiEjc#?iqklt^76BHPkN~h4nfjG% z`J17OiH!LUsU0m5$T8j zR2S_lR`$Y(yo=%n+dP85d42|Qz204lI5_a7eW0@&K6L6N^OD%uMEKp?EATd+Del*> z(AywKG#aRPY0{tfD=}Qf;_7_BEW~y$OG`jlo`_jswhnNdP_z=h{)4h;v z)Nv%4RrOn&G+>b+d&!%7Ev}j{3ijJOG9uCJ<_k!(Xl5E^P}%_16F7C#Z`+%jzYRi; zDpIMLJCpEEGMi>gmDQI=o|rpKAUfpgauck!O{1d{kDFcSqE_NUL=p=rd1MX`ne(YW zA6F~dQ3q1fr0ID!cx#*di%}bWw65h7t(lrt+zJgR7q_6<$6t;=u>;I#L_fOeF5c0h zB)S^pD&Ulgy`j$dw4narZueB5EFWjAP)>S=V1OVa2Lj1&Yql8KTIX5i%~dMYJjjdf zc9>0+HnD7*5NE@VA2sdrrb>D!u|k{THRHxb%2+U6gP^ixlRnzh#b?@g!fZ{%<&~Z$ zSbU<-IDG;&$7<|4p5P-|T-O;k*64~M)R-KFO;?4P7Os$nm324YHngU5-ECKAmxsl;wvw*O680o;<@htO>Y)wWjKHbri+ys>_y_t~CHGgts>6+M ziapJnGUbbkhMxFDc9>$WeX11bEO=_RFqvd}$NfR9DCwiFZ19Vc%OvOHn+f!v?+u~P z>MMomN>fXfUcb3(v}_Ic9PJ|%NGUJpP#+dkgj*^-Hwmj_?Q8jH%%b8m=W3#5JZr2k zH%4AzkWA5)NEUokb{5g7iL~-GD_b4gy}&;r&cFAt!78W!x`O_y8}3Ox*h=HtYs}4Yz8_!2h*_6J_iln3#D4g+K~F` zBn3*MuUipK*-FLdzo%!+p%$m%#Dk7s!Mn*(tX&*)I*eA$6!-XAT zG@LCSbck!-uqbq(z1)(f&S!s_g|9}$%jVZRNI$Im&PQk+hAiODJnRXs@m~ zO$j>1l+vtrU33Y%XPvm+&j_xq{5}P)e@scXpOnxqus<3pO*Hc?t#1YoDhiAUPrBH9 z)$WFlw5~Lg61OX6D3NPIIG1H|C$i7nbiu~q7@1d2QBsp&FQ6}pyp>2_JWE-qu&o=p zPx4e>2fF2><(1+~LP^#)vpG!`{LW2eA?=Ux!Ykd;UOYj1Z&o0T$wVLC0?dy_2%?9HV*}X@oGQLjxpNu$=C` zy5HboG=9TEF(Y~3iHl1{@jPgixMPo4rfC8alRQ>fv zBy#`UgFkSV|18yx95SyiTB?K~18UPd4STrdc7LZea6QhoPZLf{XQEOPUQdV8%;j8; z;;w2t+SO=A!|h1>4iLk2N=ZfXD z9dc>oQJRPQfQCJQWeNaIavFEQuhXCbciO_Eu|;3CS;f8-q2B$NPKVse^;q8r5%XAR zgSDY2Y^HmXKa;&HO1A|d7zgeR?TSi;WAfQC z?s5CuuMTd!uZGqQISo0zGjGkkZxr~>U~@M>fj)&(s{5D0yD)U%bbSmVymKeqJBY-z z6P@j@6wcwA#!qqI_2M<9^Ijc^eLi+tF@s6H%d-`Z5xsn1^CqJxt?l8<>5!bo%e-^p1(ya9Oa;%aE_AG# zV1BTut*f}rmEL*L0V;odRC{Y-zs|FT9&8JzSf=+D*(I2pZo^mVN1S;s1nS0!5P!<( zMS8iCd)`$%WQvUKkNdNj970h5iLez|tYk=&O7sqrO$Ahs50^&H7UtmpT`Uj96Z;wP z=@U8x!(o0_;H1&u!orl9eb-O6LvLf~PL)^!1G|zXX0HXdgA-KXA9#*JiB_8;3o{p| zRi)k&;5Y`E=eMIdPQTC;S}?9_HF%ih$B)H-%bntv^eSJ4W%JJO88--xmssIifZCfo z-v2Md!9K+(j}&e_4p#F2*wAZlmp1WXh;h&VWaHi`g6Mm8dj-=b>2vkXKWjDKZ0 ziP--#U}7X<|J#6ti2ZlfKwDO3A|}qivaCeR%)hgIe1Es%_a#_4iI`dbvfvYW#XrTw~1*#(~WN zDQrPo2swk3hgn$pCwJ%9_orUX-CizGF^J)BaD?x#(nvxFRjY%| z?6uP(9zJ=-C0DO02Wr4qUw1=PU*FE&1YL)g1Ty*Q?OdPXSwUP@Sm2Oh7WWQ*bRK1% z7UhfB-D6>X#yO%~;va4voxv3MYknrs5A()$`&L$Z-EhdhcW|crD2vqO@x&D15$}T{ z4vVp6u2chGec?a{mRO^*LIIF^hB#vPoR^>~=VMe-?!mh-Uj|Ezr1p~w7cGp;6OYSB zy7y^&d6B-yH2)5|4(YHJ;*puuHYKmvCd&nw@@efxmLHb<`iA_A-F&9vCTCx-y_1Ev z$vFADYc2#?vuWqfKSZRRj zEqBaj!7P2ZdA5?^Eh0*SQzq-7L@m$tW<|JtZcOj@VLnI&3_(&P~ zc+#6CU6ZVD)q`KsmC`Ne3zL6FkLNWfdrv99y5&Wes@`L?|CD&8pBIzo_>jYcE|e_# zt=zK;<3re#&~<&?Kzl4{6(VZtB?qiON}j3z!4K>fJm%XpgQ#^BXxE`EEs;y zuJBrbJ;$kj^gy)ylxr)c`^b%j;wH*!g=Tiq5RBuCHvr#d`bP=`h{Z#j=$e{z(oz1#H5sEn5r#^GEr1z7n#)JTyTzWf}Mg21U!wa8M2z=O5IP7^U> z1?Gz7X%ba=@BZsZ=?3G%?L<)ToZytsWDDM~u9MCpuOtIFtQ$qW>c4 zBN=|{J=UE11_inT4065wEsQbg>gD;XJE#>IsXGjy^pxX)$TK@_fg5LrrFCxO=M{W4 z^I(2h8jfHKu66L$Ab0dM1KmDUhAcwi0Mh!%dxYI^Lq%`8W8At~;J-lfRT)p?bz#G& zvtL>D81MY|i5XVpt2ibGQS!`)LnfER&uf@lS7o2Ac`ef_#TXwa&nr*b_4&QS3RYcR zeA5^h;vcm*kxUmSe%`)T)`rnhKZ96>iTp;|I}ckft?4Qn%qu<&?LC2I@its%WIFDx z5YjVh|L>zBv_d0Ci7fGSV142Z=atSL%&W&LX0MZ$0X~#MAhmcn{w$_w{2oyoklanEHK%)>hbm)%?ur(<=yMDSS1sR?C=}GkY$ki^LQ$e!NgnDQ7~2aM(JuBL zX=Z;I7W>RR3$bk9;phm~XfY6@lahQK;L57M$6o-dC1S*MbXkSM)MaQhQ(WJ}_I0fSGp^90?0mDpR-lK{DJLVqEnZNfdEE6&;L&^!^g4VGPjpluoil15Ua{ zpTPG9>8q2zjDr$Kp`jl;t;>-*d3FUo+-KhS;RF<-i|pU9S}97(tL#qtqFC;lgYvk67{?3k)#KH76yH~S5Jkt1H9Gef`Z9A;E#|4i-kq>ejzjkvA!Gw~5nLhhLiX z;|ROm_tT@nu)O9vctjm>Wy6%SYGlzM$P_Vwu5TYk9SIh_eI4kQ5PH$vrXuBZ5*AY1 z`ihLCdTv#f>a#gE zTcrVGU!T0dVb>BVvf@n9hbpegUe88%yJra{>TohH!t1;rm04Dm27aXw3A882o9310Fg_AV|XcDb{g2V<|Iq3Q}V0G zTapYBW)IKeA-SMor`wb{?({n1@1SztBn`pvEorMT$~2a0GL9L>)Shl!T5B{>QzE)uIQNd3(&LVaS*mUVu&d&$ir3;;0+GBr;p-br7XWU8?k|( zqd?tJ`v$-fDUcWQBjYcjYbX&LOd!zEpsx%1Qhj&qA8}?oNLxSmoB-n`+Os9F_=qd( zUslIZmc>%(VTB`IwrKLx|A;+!k`(s>_oyd6tOcaQ(iQHB9=I_sr2H$CFMbMVrP*nwveUp6g8r~@#DEUR> zSu8P9qLEmO2hj|TkkTQM!CWTP)vJW~0zFY^`b)TwKj$-AT88aeUNOq0G2s5|eqa6J zGK-zZF^I}suUe+dX;Z?Ss!)f`2%X-z6E8iyZIjN^rnl*+wIU?W$rP15<={T$#55n=i+w*U-==jn}FQ#Jj9m zvmPmmQm&Jnof+-fPVIK*tnDFLD2?~{KLoY9svn=qIVwiS94_H5veoq^1daucNb*0i`C0Z6#f{k(QTr5!O&V*$fqGq)FVyD1pkH!y>o#8a~lD<+?|b zjGJLqq;Z#iNhuK;Nt*sGQf;pX6}@9!Vp*CaeAv_}RvwNu_U~C>1O==m>?JwOovodK zJz3aB<_+|IQ8n!M?ekeK|IuP2WMtE6O9;yl-!1>DH94tNH2?xExlW{4Vt=>(IcR%)uRnr zgr5c6rfGdxK=qgBUGX>e5iXw;xWz~<*%}Y;gk{Ekur0fmqkj(6xqf$osSbB92Iq8w zu_5hR{#cEDM$H* z>!|AesCnX$-Ko`B2CiRWHND(7L(VJb9^%!FKNP9S_;oGHqXuq0V$qC;Ohi$5NB z-QZG3mW)p@!zPe_lUJJxn^BC*WT2{~+QZzLqDr=P%<7gL%J0c`wr;?sCppRZC5PHZMb(UWZQV;R zZ)*+pfRH>GuF}lp&O>l@z0Ry?5PVnh*XeVk26U13d12g--R1tNP@E4#tAz?I&dCzc z>SOpz9XS329N{<(nP^&s94@gG#DjeoI!r~Awe23_QXTzIXvxt_--k|Ku62aSa!O9F zjWiWOvHd%y^TAhRf*<|9tA3viCh0BeQ1Oo=#^!D zHGFL>+sn}GKQ8o-0BsYTD*E-w2UWBHzBDVxufL8;0Q~M_8EhPBSYyMT8f4q(z&9!h zqj>o5yKlpSt2V)Sh9QN4CtS;V+}+;l>%jw2=(c=p_9QvN!6e2krlk92FbbWF8GNUR z!(V@@T#uznF_QWm2EdPC<3UZm0`@3Ti;E}Xq zo%tawVs3WT1w!uY`bM(H@9SbWvOWl^6OM;tH(T1-Tclq`nzBnd*^v95FMS*hVOd?_ zSmg<6P@QceO0P?uRE^UyHWQB^N1YrQ!80Y9S5e#GNi-jH|H9EBxrjC|P1R z-kH|H`yCqEVGwN7DPx;$cR1pzo(1qC4vnu-Zdgb?cxudSgV$;YCeww0_vOib6%sc| zk*coxF)+r^Os8J{Ky0CL7Eio@40mB19Z94}XGxDqZ?0?-(}WvyJ@uG;$x*U(94b0F zy&dioYNhQYjU{}>$37J8`X6_m>lQh#<(GMhkuW~NV%)aU@TeEA*7b3q&14yrHXs}2 zeUirw)sWg?D)}0_CS}Sk)N;&r2am9FW7Q&dOUM8!Ns_$}k2b@_4M-uJ7r_XNj1%-qN>qc|<9|q1wG+{) z`u@;pGj_8Z58F8amVWOeto6V(GJ9FSX6Kf45*rVR>r1#V$wnB?)scK>@p z=#ACy1)}b#6Cc0p*Dw!NU_QsssR%!ed7~RnlCiu3*47)H@;-{zFZi*YqrS(~uJUci zX9#7{Uk?@{HOhTda?u#L!k-=;h zJZKn(r{d-=^|KZ;rghW~xi(_B;CCo^0eR?)FEB(t)#T`unR1A2woza>N4`QZKzsKhF15dKz)%ezwC6NTu|wgir_wmF2T{jEQ<^ILJn5@}?X&UL`bXhiGrvK)__0((5n0KoF zG788_6*J5ZRM{A&ss05z*I;9|SXL#5dB~srkrQeLVOkzB|A+X)qaQ)<6-q|hd!2ge zeb7OZCjt~aK{YnTMfWI7T!4c_F&>VG-?LSQkRA@z0l!?%mD9KQTO36#MiHe4RCb57 zhKQ3G&oxa@>HT5PHIkW!{g=gO_z2Ov1CZ_hAR(h>o<-b{G$6^#BI1E8g?K5R9qQ^D0;8{NclYc&NU41Q z(^i)s1Rsd^=xNSPwg@sZ?lN{}9`7!C}{>EKa-Vd-gF}{9!V*hVM;!I6CY8bFdjv+Y~UD?T1+SLUSOb!Q%aUK zg`TEb)yQb>xokE_0#_XFOUy;YzWK!v;^cIB+!~(S57S}OMQc5|=ta~o%^<}N3zGbS z(0-KOz;Oz8RbqO~{Gd7sWuIQZruj;k692|BIN?OnkE6K1yh6bQrs7-4QS71$Rbylc zA5vehIf*=>G*6* z{gN1l%wiaB4a3B6M+YPUKRRq6TXCF{7SfwoIr(_^$cXOOL8LB&gj6OMRdzCUnxN51 z6#n)CF;q#I75hCJU5?(M2cp|^5N&M92e0T0?_p$;)iLb=XGm+dxu-R9)f%E)wnATT z2?QEjr{*c9gAC0M@Hoi;kt7#ZB!JP-53rP(ii6B|eJ#JVtnQd91_^!(nvqDf3TjS= zbb=Tro3_o{NZX8MiyTv6+-HR=A&P+(Mgxw?0w$*wyc*0MUF%F=ibSIq(leut{^ z^r|>mt4*@$j_tNS)^JopI|QsG@MB-~0}L?@5%+_+8w`<7W%7KBb-GEa&>D{DCE$c8 zsg>@8SrnG?7!>ga+f+trGrJzHv+r0Ak;pi^YLtfT>d#Y>mlHnx2D*jHI*Np{S<77V z__3sS)vg~Ie$*O0m*`Qh-7D>G78E=|(yRp*I$y2|jS@3`$QPW|;eY`-PM%h>hZdI1 z2N)-51Pd24zZBMnT!BaN;^W>`vw3gODAWj>E;{8rd;m`k86@pq%s~cSMKsIlG)_It zH#XL|+MaN%Kh@w-igGQ-M-y6>y{J?s3vBxyq>k|Ia!b8yTWuxq~)YKOqnT_ zr!S2-jYsp*{91pZ*S4)5hi(DYQ@KDwax}MW{(ZmNn<|f) z=0b?le7Y(1H-ae~Db)eJ5b~V|gsZ`&eX*i-^1^e0c9~qf;3wl~C+GStuDE1wXkWX z>*UNhOM+-A6Sl0+i*@*=gz<6a+|nm@qX(P{y9_52exh!t6UN;v@_y;-RfEp@mdJL8 zv)N9TBVfn}rI&F77)wppzLg_et#AR9XlgL<>X1WOE*7>`x;8q+lhh;$yMtv$S$|=y zImQL4;y%Ki*u66899nxb0jnK6-Zpd5kl!R3X{EQigB)z7pjyVoGD47)xp~@lpEru0 zpD&$~)6wb3P6D)&q4&;hIN(aBg8ek)^K**i_$W!0@N>Qa)qp;msgzYo*=l=yYrdT7 z=){4p^Hg}UNn1)(1|elX6_;g#66C;{Mb%!@(PeJtCWhqZrqs(ZeR*UbVAjgc-J#mj zSU~K8zfscKe)F6f9s#CN3R7SFl?RT=6UT{WRdI{1nj3UYtC%c_4axx~uS~l9erK(;!$8 zBu57`iCt32jZJa*9_Co>z8y>oFzdZsS27k|Uv3{L;|rOL&e}y^H7>Y`m!HjYAyf*0YBnl zpzz{9&$VPJ5zCe{TfLj00Udi>ih;N_w>@JvsZvI%;LI>On*GjX#`w->LYtySHkdX? zsWIaN6Oz`iRrjS$ok1`7?q;lhBg?Po=Tny}flsQzx7Tma_akYuniqlR2Keje_a7#X zvXFOnA|5F{x%n&&4q{rrsX{3KIzASQc$mZZo-nNactV)j`;xJ)2Vz4Myj~xJK2>6- zm)ZG~lMX!QqjZd`c1W?1--#Aa^75JYy;-X7B6rykizDP-gQB> zU%JT-{pzxtIO7~anyUsOPJD<_3!#2!W&CdbcegVio>1Tu#2`$hz31-K4##feJ})%r zr1r(2F=p1=dl{VS=D4GGT6Pd+{rO_k;e*Uf6qrIP?)r`*mJsLM^8-=fhwS8s!JjTe zJEQLsFGYufUSEs7Vqix2W|{nDVgTC(DolLAeNR_M%Y-g~=DhWlZT-{GwiD|GaK*Vz z;`OpmSySrJ9aQ8fcl6oRK&2sDVY#p(+ct-57pSCK-)|VJ2+zh)uGIYhU z&LcCxGusH*g7Zzkxqa+M2+QSUcFX@MnMM;70UHE*;$EpzU8!L?YGm){YINk3MoO?3 zrtkwf6SRn&)C^Ida2XkH$g{T2r9C`hkc@dCqT%{08IO|Rpuf)ar;X8H+zr^i%=g|xz6_I)Ztxd^lx;Q{kU#c(BGcyV~%eH;q>u^LK z?ZGhacDJ_WVsimJw6NxS(2WtV)lyh?Z9%v%jB~09KVdPI9t|R(?|DfC;5#gK5v)43 zJQEW;FnH;228m2bh~-=Rv=6Ut*)wu9fwiK>t|zR4FsA2si1W06mUcP2H;i>P zgNsEdwDr=Wv41CZ7;*ILl{n7RH`mV+LO?p37$$hwU!T%T6XJ?%ouiA#UlJyq=sQuk zz8ft}a36&zaxPV?FVT`5xDAjINFbA9oWhKT7@zz_95-SB59q ziBgxnW5e__IF)Hh#D#QL#+^K|c<3ZKgf-9JWal$Y9O^3>ln>9XRrv65_gM8=EDQD) zN{n8L35SEyIv$koSWrTh*S!0DplP6fdM(XqLtHpl;b2q9Pmudi8^_V7*1@!F)kS%g^pgMg1hh z!WcB7B+oiwgPSoIlDL=bQ}xN{no)x%M#__NW4GfT)>Ab-)0C-jCQ-v`0@zr6$svwO zdX3Aa8`XkEJSDd7Tt(7m<@11_iVLBE+8v^_-&4tzmt$^H7FUtbt~;kK7=~RX^*@al^#$ZzxK9eE*=;tS~DxfCvgf!t*MD3qk6Tpz%sc zNd@g{R}0b$_AxuZ9e)>uIb3tf}pISOQE@+D^$uG6=FaYOIB&jAjq}{R{Cs%jNUcH`+WMj@v8P5t_{g{hr;YZqH9oaS~587);{Ts)eR;=ch8&nWL(vqxCFr#zfC7B2@7s z%G7#k#pEVbRM+SyR&h*{*#b~BltGGVSyCPl)g)ipY_9K(0eqeqX%d{4Oxnps*DM8s2fF5vV}&N5`NlKFw&yK_uU)xs&lx2MD(~AcBzv#LBsdl z8~UXpG=137kEW#<$6Sq(`9g{hevmEGHi5+!(<0Wg*mBeKk%t(NV%FEZqj-4m!*}IK z5iLZu--90FhbeLWX;B(9=^KKVNoq!m6MPu`J*81h;)#?asp5XIN_tR^{W11t;czOZ%Su2(w1FK#NcPiK;MgR1G9|T(c$`H3j$xt-XYA>u@ zT{v)LLg}uwx=jsi5MEF;Y!PV=Cj&tTyx*q(kmZ(LrMYGZydoYC^Zx0NUJJx1klmpq-i7T-x9&UZy{G2|YuFOW#6Ync%6x8N(H>PE&D zGvYkUT!S38$@`;7;Yg$P{qihu{3+KQC!R_5n}Y~8j$~G zOEZ>5PZnBaP!@8j$@UWPxtjKosb*{14 zE%nL1;;VA~gpL8h6l1J3V)){UI!-%!h-+YDrvlG};_EKM+^y5C^6?`%VuZvqHe?>s zFxr;P9dlK^{+5Mz4%?&%wTyN>mE~o{PSRb{o#D_&zz;1h`6`_aLc`ycg+M=(_WbVm;}Fd3f1f@7@-wWA%AL z8Z(9#UHwq>Fx~NC(i`-dhvz$M04#Au*CS}dRb)Z9JEaJeGAFVWs48o@=a-*DNpmb> zS7<7r9gp!>S&SWqS*%23+ubUtv(<-#P^>Y`+og*R6h)Jywf@4li4)cemDitnGdx%- z2)R|3E#&zMfD>^j=#Z0vp>16+37>4&6)?)ulS@9DX1o;>j137dmyE_j-3(*46DXF~ zzZ#2)Lb8ui!GRK+2-ske96ABUY$)YY&`_eXtSqm#<`TH{(XI_NuZ7}iL4Nc}_=0Du zb)i0~Cy<|KE2AkOqTrrqjCb?WcuO(XiYIPtyI72wcrtn$|Jiiwz_Fq!rm98Z_Ul}! zt9T&wsjoUe0rxlPGhzGkuiOYonJI`#WTu-|4uw*ch4aZ zH(uC*9VcdW%yNZ)XV*Tk@eb2^pd8AAK3U%9Ed=eW$nu6u-O=lrfUy1S8<6l>>^(r2 zp7z5J6KYESFOJ#xj~xXCo;_>cI2xhto}%oGE)|{Pqp@E5X!Z@FN}u;2hCie9y`^O?Q4`_~43Ow`@NP2h2O@-MTC zIlHz_zj?aMM1SC~;vWTnk(TLzeg`Kb zkZ;VwsPjkpZ!#}HNklBhPSDQUSkBPe!rmFk1GY9W1G-TF84E{8 z3tKZa3u7m9A|`eYfD(}Wt4hSk%mxrL_#$p%VP+2G__8np1RRZiJ6ON7zgzV?540pk`q!VC!h{k7GdtN0Z-! z^FQ?0!okt$ck_stnE=uTf8`k&+5go^`D66{Yt)HY{_y62*8~oaqZV*{fRydut^0Fl zXZrp1|35n$+izF)KkclnY(#9pJN`QbQr7?Y{B8TYg@30U9GrjH{I>gD#tc0EZTY(g zz%reG8t~sd@qhK`m^l9taPglh^MBLG|BXkd>?y6JhR@ebcZP8NEfEjBp|i!$cN3ft zEi4VG6s&98Q_EC%W!5kcL$WqBS`2w>GeZr63XQNpD7B9<>GnLBvv>OI~Z2Cj8(G{Q%Kdck10W6hh`8SC6Yme zR2su5{($a&<)t`Zg|6R^<8vf9saeV6kx&mYH2#M{w766QmqiwO_B5NPVC&AHnB@j< zsnbZDt9O-sQZlkDZtDx%M|2xMV(yrjV(5wmbEX5!8z4`_Va0|8x9-upV4@PR$;^sd zHN@V;`J;4wqyj-SVA;CvnsLnNX<)hjfOJ}J8&~K&x)01-$W#}!JN)75T@R8NJ=0{i zS|_E3e!8Z4*IIf9MN;4-7I#9_aT4$(N;O+%ck9>5j_Y1Q*(<-4Ju*(P4E+g)INo9yoxaI z3&D86w-O{jE5*1kWpwk#KLeK&&zg1b7akfoR3<(~@6&sI%wc6O`6d9?vAP7ygI}Pv zmHs7-L}Dh8xJ>wr7zVSqPeEUw%6OoIJVK>$Ag0|%+JRvE|{w_G9qGCAx_q@>S+eJC&{ZA7x6!5p>7 z=Z*FXkKp~sNk?UEl+p$;J09;%E1iav2aw)=A(QPs4i8`N;9?A8kF!gVjBf!Bvi;U{ zuzN(0y-xAshFBsAAgHOQd4;G@yvU_+*OPrV@}Le3ewnS%_VRMIJ#aGkl}Un+JKaQ3 z`B;eYZWyi4a`Xcdkg|fF?#sDS-Nt3IInt16k*k3txuf+VEq+K!Eo=S}c#aB5?Z)A6 zdFSVOXm_m8nn?^YstWCdYFi&Vh?!k+D!z2aD`-)^nS|#EU-{e{XywKPa1&9unx7$j zA3pxM-4zuGqw7yu7*Z`80`uu1&pj}}KePhsXw4f{Bq^uuv&_IU!jNi3xwEU(6VhO8 zhe^C)OMOFa0|SqkQet+NYvoKatwpJI>5G4p6cXAyMTG%zS40iFD`$J=ncAfaPi}YO ztf-*xGwp44o$eRe zt$#c#3Yr)dUES(bpNbc2coPikAf zun6(M1}!lJfec=msz?P;n5G$AYwHgYoz+9T3S%^`(>$ot1tI9 zU5u@NhI;$>uI{Ab!+6kFGEu?Ejmdbfl^=L6m+&<}PBn|x00SVGJhz9}SKBqNtX*ej zH}iIuir_!oH)^my^SHy&PZvztmq2+p?tNY1)LS&pk6(iHk-rK*?yRc1l&Zh7x+6~v za)UP((oe{|b|W7X@zKkDG3g!O{ zIj0F1u1r-Ge6_`i*T?r^S@EqV-5D?Hva4>Md(*MKly$1vZ2E-O5>i-2x z{=Xzx@=Gq5FB}LZ2r%J^*uEI%5B34~;`0)@A{XWG#SJ~%Rw|--B<9xv)jB&2AlbPY+hA2&0gLTOtn}nSLC%$ z%}O&OnBLB|bVmn}Z<=p7;T4@cUfEySX8bf|#*j_{;Vg#F@KCvjg=Im*0GR#V=fArC zkK}RezVo%Rga4V~(Lfp&v0&%b0Q)FiI38`14OZI+LQ>RmEfNG6wiOy_m({U+L26B_ zdwR4=MTT%fZXhSDi~X^6J4KTIwdXoyIP%SCkoa#jOSozihh$gDI`4g z8#0wKM_=2d4OOp`hrsJrLLo1v+Go0^a7XlZH}v+JuzhPp|KMSaY!EL} zk&i_;;fB`RL=KV{B0Y{+Xk$dgQ-bS8_*z?e^D}oA(w0sKpn2DAoa>Q2R2`@Se$w%Rq^8smQKx8u0h6G!czX&PN z2kQmnDxfzVE24wAO2pm72ab*1>u{G%p#|J+X<43QSn_2UCAcgor@pk28%cxBcJNil3+b6etdxE$EE#L}uUuJ&cD4!KmBBUzk%`eW3cRL}4 zjmD#raHnrlZ;W1QS8793p}LMUT?+xTzxz9Qe_T3kv*o6w#ZR^;ck1I z`QbG7eaNM^u?hH`0>)lxZcf!2)YImy9IG?xSbeNut1IsSL0kyKBUW}>ZuCZP7iqNd zSZ{(|JO1`4L9k`KvOLmSe9|7z^)HD{*5B5~-=vCs3^r5sb+ z+)hM`2k{XB_GX%{tkk0DAo8G}Awm91ys?3Tld622BV{Li*pC=_>u3fBQA%oz9G@hj zg%vUhH*v`1T<&Xryzq^waSzSuO5JhPI@Z_TfeRvDT545B75I;ft`#*jFm#)&95JkjQ5M>zLX{ zF~mkX=3^bgd*)YQ;3?kVs={FdPm6tumCA;(g|+GPr#Ceiq%mDp8az4V3=xqWySE>D zwG+()8zF!z+%b&|$t$sd1|!^FTCKD5s%^+|Yml{?_%Ca(++kz2Q_wUNEeD83m-kqt z=p?cBdgUf=C5l*ay<9Gs0-5`b1A{7^)A^M?!u*#q7b{>l!y9mPUSu_vJI_XaOx0QT z2S7y=uDO^siMa1X^b^Cr=m*7OdpHX?@>O}OvTFQF6$5O4J)gMeaU>%o<)Xgz%=nPt zW#s8H?L>U4^ZYg&%VuI-?LTU~8IJfZn;h}|VM@|m5p$V{p)bih!@c;^RMdhn-!5*L zopakV=Z9a=vF>G?+rl^AFasS#kJZ=6q9zCULMRcv{TpHsOyd`qx_dsVR~KId@!Rk( zUu=`NBL(xo??5fGE=C<-GN@})8Oxg z{oC`e!7^SA#cQi{B*z*2(B@4|V|JwEN|`AXW}9F;;Hx=hWt0($mlVOyI`9Jocx|;l zr&*TERd$Ba7U&Z=iiKu8sIU+ZA01`5x&2b` zFTSev>IiiIT)^cn85Xo0cA_(6R`#A)z!jj^0Y9 zyUO%hV@3o5hQ|{E$Nac?pQqj}bNNa@?Mop-#y54$i|p2#LyoyOyrpt%Wvx`RVuS}On^t)!bcBD*^EtU~wYOqOsJ%_a!2fj6a|RioOg(bUTQ%f`C3*)O$` z11h!h+^lmuSvG#)GqRb*k3iD+=+H&k(!5^!n0zmlMr!iZks3h_*su1%eTwWW2-p)H zA#C_b_(L?MxF0r>^xFGc9*SYOcJ~$psjme^bRGm9^eX49f3x%ss6I@xZfw7NoQ4ab%P@0E;x?P zR&K-|-vPA(sM)c2JX?V;3n@rHIgBSdJWvzG>~^q&6xc;7Rv=JFm$a83N^G-R&gUxr zh-26JXxJs$q&E_j?#LQe2Gn}h`f(Q%o=wtK-xjQ{J;XlvsqTD*=Je4FLo^x{y@*cM zW7;O0`98wu>A3r0{_Fq8-dnZB6-8U3g@-^OxJv>Ahu~IN2<{%-J-E9Cx8T7cxVyU+ z5}e@fP8C`}L2jMX-Cuugf1q!_?ANvTTyw8AWy~>P9GSe&dW87-IqwBzkhS-Hb z`{rDR1(eoe*lkO<~c^dSYVz%iX_8@I z{N9!mMSdx*8-)aCO2OWSrE~h;hX87DQ|Q{T%Rd0*^dgqa@@0Qa?n5O!zNtrx0E$+7 zMeE$^xNQjjy}Tp@8MU>g?uxfv#LCIP5{#T2z8{`F>S<+U=uSxH2_%I7#=Xa4{c?icus7sE->8 zh3!rX!~fW+Y3{kjn*W^?#e~}30~)$pLscNTd8|7Y8j9WytRq+V>8A8Y`mV)s2U&+q z$4^WTgK%xh^oUxkdH2q%2;S9LWTLpLz3&0?nqd>Jg6oYX%iRs}KLR{qco*2P@BoUy zKDXO{fIauWFEQEw0Mo4x$rm`~MbO539PrEP*6}MVm?w2T&|`OX(5x2rMmkfOcFJcy z(98F$er6QY zx~YT$kvGSyOT#%1juBgq?Oojq_J<*xjOI4HNEm4&KL2rW=|YO5e{Xl@;A>>^itq=_ zdKi)PQ2J4TX{j)7r!fqmxXUY({+6e@54MqYsKd*7pU%y%eV(4Zc_m{D4ZYem9k>?% zL@kJz&cd11T28NZgaEYBn&K~q3?56MqubKZS~|KyK?b3`Sw|RN!fpbLRuln7Q`A+n z)PX|hal~7 z(_>#u?)}Y@I=_)6P@*FhJc)SU|AwlKV`x2)u-`~;kmvYCjWc;+q)C~2gDM|ZdHmYC zZ{@*u{DQ&`FBY;*uWdo;R(fV%DWI8;rW(&4%{025<;J{UD)a!cv5joPmDih`!?We8 zF4d|lUs$P{v^<%8ZS1@vkCR6lP!c^FLbyVNDD8IRLv((}dliS6zr&AKO@Y4z4YImo zsTo5+MJIzc)mDbx736+eP<`0>#@|tTfvbMLiApFzc@QrS4SA zCp28ceUQMuo7en>)9&rc2wSE8<*{E*!pPOC#E$<%|5ofP7g+N+bvu6V!lM1i>OwtB?uW#m0VrI~r*qYr9Thc-Je#L@wLB0Y)J+ zmHlh~KR}ak-hgs+s~}M1`S66ZO!hE)*y^Hb~%@ebErN8)vQP!SQqLY<5ZJ>&v z=7M&Ied+>J4B5!%dh&|b60+QfqkG4{MEAZi}uCy)jRQl0yCNyNquIcNAX4y5I(Ohw(#L z9t=PHWrs=g{GIS_TvrSTYJY`1+VvIWYUEer9w-cpf|VRY(incEUO z6UqSV6_;=Az(%e+P;Id{&za!V`SR01d*6R%p?FBdAj%X3D4c;EMFq-C6%FM14YL4m zB&L4@7Z3_wrR3vSeZo}Zb0Js>qM?&m1Vav@9MUEE z{!fQtbxBhkeAmoRg+~ci$ZMLVpSxvU;ZizqaT6GU!|KD=Uhq~QE8^vrMjJMsSC+OU z;s$!3*T>7{%PqHiVY}moDg1Jsa#O0&Da}r*=%mxE0k z;)9G|ceG2#_$K6-!kN`74rtps|LTyd%Ry$XNTO28lI{jQ3%W)Qm;^vf9zK#bm-+#|yD2*t}I(HVxW_%2|@Z4IST%H`?$J|PFTCBGJ<|jQL*wEXT zH66Pt)Y`f5eV-C-)OJK~}Df6!DpXsC%3XSr-xvPO%G-)$}&Phv} zkQFsawNM)e4~EfKa)<2@tW{{q<)u62gUtV2xB?R0hd}AJd*i9F?;O#gyVUn;f@AMa z65KlM%p5b2Fzt;4OqIl6+0#osj1tPzwKU5cEC}ezVNYHO_g|o;VENsLFt-aUnLKzR zRO7w|3^{!b9wm=&IRO zdx+t5MGmbChW(NQvxjtQw-OT0EqjUZ4KKC|ngCw+MYjSEHhV;QrwG`?vgV5d#q*E? z&`v0kz?Z2z2^c5!x@+Qi{=XE89vcvnS%%!l01kK5+QX*xM*4qq7+vxlZCY?n(o}RL zX_Hut4`uaS1?Xv$@95)0^LN|B4gZ(YA66Iqu!yQUCL~=~NJmIA?L>wIw_%3Hi=&k~ zk0^0u0)xQHv0I34wNy|py_w$&H5WWNx_@t%9d=^7JT^@USnC*tr0EY$#ty<9r5cNA z`}5+o;VI)Z$?C?rQB<1i$qI@?!Ms5X)(`^yU2WArfUf!8xJ!l7Q45R@esa2cp$#sn z8bMopx884j@oX?M#W42wE4ZN=N;H&W2IknuX$nyl2cSTON>8-Xw9*!FR!&qZrOGko z->#htIVJAZi0{W5Tje4^=;&E>%5QnX^XyB-e(IHOsFX;J9D!T{MIGhD4E~qT{;!o0 z#vGBpF_w~XB$gr~SK^7EpV5V(0JXYz2@3NCZO`UfgeRVHJuX89kdti7Uqog9L*?{; z%NNM~-{Hmo9g7R^jljEcZWb==|4RpjhxfmAP&m2%f6zfW1Z4le4$A)>9h7HbKp%ZI znz$1ybFeeMlUNCIMZO!k3UUSDm;rHAavCw{lWHG7H{PEp#2I-{i?CR;M6oDDgc1IH zG-SiUOu$d}R&D@<(1#VkFMbvcKnC9Cqg=oA$^n$=dqm}|QHitKDiCSjQw@sqlI&w& zX11L(lXJ!{uO#2x4J+)j;6<6p(`OSpoAcAcfxH7D2Fph8saJf66;QZS1cQ z&g0BS&Dg{*hyx>>OhHZc+4G2QG1O+Y)c_f4ihg{+Rim#a$XFy$5{)NnMo)7}q$%q| zqc{=LW(IA6EPV3{fHNpX3MwdJUz8XS`^4a8{7exB0Af!Cu~hka<}2iA+~sT2zwu|l zv7iA!G68joR%Nhb_-d}vMJPWbgt7M&FqmPaxBE-cA37p5y#PEVo#PBMtVpWijf9=1fygm3S zDu_=1t^FwTKdhaP!AKR5@(n|t66G7A+Q;?7AXZv0;(YWZmRxCk1RLYKYO#iLkn&WJ zh-n-r$7cIvalPByH>^_a0=M}Xa$I6~|6xB1ZSveEgwIqt0Hw-~Al8o__~^+@uWq=y zU#VwMezu*75z>hD;fxBu1L#T8H>)9zOXn4TX00%Xh!Os<`WVC_O?>q9mo^h|JMxIT z{TCs!uN2dK8x_kCe-#F6H9$WS7X_fBx;%sOgW?(P929W?xk3sC#MK&+6a>Lq;EcE> z&!ylDO0hoNW5%gzx&b<0k=_s|ONZ-;} zoEzav%mg$b^i{_9`K5FVpW#VmvVM|-h{Z(09a^q!TLpQXLyWLc-*q*Jg#qsKGq~0S z6VY6g%+ZSrO%>=@3ZASCQyfd&vvfuJxi;$2Vtr7R_rljQnZTT}O zW%Fp6fRTw6Q-C_e6Z+ovn-5rg` zWyWCd08;*{epe+UOki)O(SCqS|Fb>JqM{LWK*+Z>3YrQY zq&J0h{51)IU3Z_~PdHzz3=PjGuYfeBf5S+gJ-wKRa6m7`JDrtM-z};y3H1Yz*>7s; zUu-pcHyN5w%C9DZEi{cV3`7mE9p?W5Y-%IY2VDlsEB2@#8C)NQ9VKEKP8;MDYZC_} zx4$p`AWu?c19|T_#)$wRiUX^1KjfAEhOP&BR>iMY zsoD|FGlh4V&gu~l2CH{`S0YR>;W|9;9;SxG0<}xlZ_`a!`}x!XJj*x0kB3UX{W_QT z<5lDRT8rk>mVi%J_nBb1uEgWjfPyl7e$MxG1y8uLFHD~Wa>)B-Xa2I4WTYt@F&)Iy z%gTOt7eR%tSnQGAm;yyzZKYvNvS0iBr4V3^hS}Pjz~rsp%+#2rOj6<$!|%Rf*rMbyjZoZK^2yb*qvKnXN&8x$MBepZcIyo>RoYnsk6PIhi$i9^dI<=l)Wu|)l(Ve;7x z{L4Zq^Tx5$H#K%xV?^8C@^*!7qTtcrzifTQNUGJIY%QrM@*A%>0N#P_hY8)t^mAl+(6)UP8X~Bv7VXm1Vy0NFbtJ#X{?5Qp6kbn{ zY{HPGC~WLxCRPp646-1;LkI#j`-!+l#IY!x6yB{z5DB&ky4UXe^MJXuS{HeI?cN#V zQNCFoO8DiIaBR0nh!s6Tr*3v}6kW+elgd~A6wDq3WMmKNqN`f5e)1!lbmr+Ens{5A zH)=tfunV}WZLba)+y$rDDltLku39B-s(5)@usMcQV*DB&s*e_6v(V-}5+KeV6{Xk5 zNvstfMFoTKV>jbZ-FBKim7% zvOx9XwN3h5!NXoC%H(Wy3bc($jd?M`L|e*(R3DWT5zRXHmm{vrCx?m=E||g7pU=eP zcjd-@NimOeEUl!$lK@@SY#;bRs_+88izpcIL@Zw_sdnk|2AdWFsO(xh%%qvuwq%VX z=e%7%#PbRTKOz?sL>_z%12Jl&j}RScD@34c%#r0q@NH274eVU2p=cwz{!N0kV7An9 zy>HTWjz3VMo$|LQNL2W+yRuz>^sDJ7q(ll`dT}4OWQJXz5`NrsV#pdZC~bUuWG@_3 zzX_wNUu>EtI0>L_X-&OoYEP4WL(C#*uYc#@h5speq3rlpb=v|6Fts2EX(`%6%4g0Y)(B{ zSiP9rp>o2JGPiOZTFY}bhW~qJ48HRn`(t9vUD}#Z!w)M?z<-9(XQcg=HtOTNZ z#m^6EH7J|^0ZSzY(;)J}g*t9)%Lfke8&O}v>*ZbdxL8VBw0>8f(9hQ&zvVJ0P1B2{ z?1tZG@gvEIP8@PeNc%%7%G}=?2G|7MicpI5gX5bJ9Fb>`W6s1G(cMc|ZM8go0ty@{ zhQt2YW6sF&u|y7H7WurF$uGP~AIbwOvtvT%cf0RvcPZp9*%7*@yA6paO~2PT z<*_2H@)t$ibHrolP){rxu-u0YlFa#5Pah~V;wTzBX9x2 zwVN66q1a`D2~dPG`bc~WkBeNR(c!c}JTDjnPnw6_y9SmMaRD@oaBSwK?f0N!%J?lUKU%Dk%D`*V5=c&B>}77c6Pug9wP2s*K=aog`*| z|7JEX1G0&wX(L;`*vnSB#yr=nBuc?54Zma=$BO!zh~rcFkPf~chD^NukNAo;e-v<^ zpS7OzJ~>!vQ2M|TMnE-aD7*lp0YB)>nRe#wykSLFxqXDPwR82Rtc;cHR$zErzFJilK`moC7mtLREop@lwn#k_I6J zkJFR~oI~oRaUq@Y3A1_SP{(WuY^@U1%7*l=Zq-M_Rm)ocvWk^&iY(c6s}aapuDPk# z#N>?xQ3-T{_FJPb7@w!=_yv6BQnhk2o=Bc)p@jo!x>}WXyY^B>7r&;~SVcJE&I2P` zT>GD}%lm3;#~NTFV*dcE74)hX80%2XE3RQ@whVuIQu*C1QJJQ9YOH1oE!}aUT<>aI z8?oN`-;?$(GBU1C*FTmBVX)A7Dt6W+w9ga>fNVF9J_!DNQxI(7qp^>|~ji*ra2D zAB1oslQuE?NldsrUouqzQxo6n?14~Am#xsbTqmXyheXFdLvv_+i&2d%1j|XhEH&xV zRRL7pN zGI0mP9%HCuBqslK#x^b8$5)cOgET^0qLqnM(-hl98W=C>aR7CXDIeo@-aQ-tf&bgX zHSc}XP1L6)LLEwU+P*lKnV+VjOxPV_Kp)r4`&^wcrOmOIBYfx7%nkpMzp3%_<(z^BP{f+@r>3>;@CrkX#Vy>S!u@c@{a6THfws3h7i0uLB@E) zx=gicmfPKaM{wQj#8ZFwyIkX7-_x$++!q5!8Cy|c1hz`mX;ilqQwTvDV7!$~_Pj?e z6mF8uYe(Yn0`1#1=#Is+9Y1S|Q3T3KZ~|2eBzGOL?MN|)P`X>aLUD3prN_5|`(ez2 zU7M3-mv&OBvGci0(mQBFLJ5RWUxS5Py~mQK-uX|y-oWPTt9H@ zL!@ivK-hQRg(1y(JssTvdxgaH-y+BfP%ed8np(@B3&BJqPDa)pZZ4ZFzfbTvsN88m z#7__ONlIR|4P%YbUaiw8m!mK^c$1UqmygdGLxA)G$4`OUN~^v!X;lUE{=H~Dgd1Hp zF_2Qzib7qavaJ?vH@THHF^`yz%oLZ}47t_NVOZhfXp)$X!DMu)~4^V=T?l@>iGP0mYYXkQslTqU{(M2UUED$gXBn7JCi4lPnQ(MKjFv0B-BrRYN-mBA=*2NA zJ5KW9Gv3N;owV|P2ORd*^-&CNTa!T`#&M zAn(0Hu5c2E>x~81PSz89_m78JSSGAEwPkAVkxQbvO;-n6IYuj&Yz!6~CMdQrX7SbY^En}Rk*3Z18)hR?U)4aTL~u3kJaT)8<7vD2eT?>YYVy*I%LB_p*!NwTruBe{2xPPWDsOI~N}G5Ur<300<_e^`m8K9v;?Y9l;-4>j9m%knN0TlG^muGkEy|5O3`XpEj1 z#XL>s6X3pf*)+DPviaOT@eafm%K;P*v+YrYrZ>^0R%N z?>BztpT|~&w=5Q5X3!t4n;dg&K$Ae%!>x=AQXMSwRB;kh-=IIJKG*)0H@ZKoV+Xt3 zwW~6oSZ9*hgl7=!MxVPOIwSrg_sPk| zy)dSsr!@V*c(;8A+tDScpRq{*##K6D223^@B>r~aansn2oxuz_Y(Mk!S13o)Z_vEQ`3q4}6;kFbja%2s1&D8nbDFV#h9KXQSo z&3wpweZx|F8CQsJ6>PRfW5%zh?*Y>H-?<8NTCNkJw}#^xOg#F0zQf@HWlER*cG-Dx zK$9Y`%0a=J5Vy0i%w6EXr3S*s>vrl}TH|LtB~IDOWV!-qIz;|!))#1UksOg!ICJ}_ zIHMuitZ(rkHF6JQS@v*wiEA{-x zbR}2L$Rh^+tIGmT z=az9ezWfM2xLtORH3RPPlzt=JIsKPDz8X|i zhW$v!7Ogf&ZFDn+Z>L_j<*A-P_3xHk&dC;;j{kIh4CZxixTi$~3qdsxo%B+!=k zE2&PZi$*F5C#G?3Ve(>&-iN`B_UEq9ULOnG_}@WRpskjJ*mNp%)@FRgSsh!|jL*sl zvkO$u#|cwCR?#-k3UB95gq7>Jea3Um>{i-3sZzl!r@HB(zZaVH&>gCGy}z^VwbHHV zL?#lKjrEfp5kF%4JQ`}NqbPkgdN(ifBCGc2^jX>=Kr8Qeqd*=&aM|z-o7=+5v|fH25%>d`R%Q?~|mDJ{>QdAs{vhO9a)is!DPTZ)%R$oHwnM!@iL*g+H zNIxdRb}d{s_)Pt$$N1gLoUGAI^hULVYgR#os{%G!cIDC#x_X{+c@q_yU<?k}lKp}<*k|56%P)a~Rn%Z)w~%3sBklzRu?C!lsaMgTv$xmxZ(l%mCZPp-%7 zC|uc7k|b+W9o-`ow&2#KE{w4R(^ zhqSwU-^!_NzCcC)b^>jWA7E|_=E}xYZm#Q&yQ{zUj1{%$H288*Q{^YS>w8ug9YuGS zf=f}sTefkZ$`3%8OK+A*m+ZzS?0rdpWt3*LCt*EMxL$JgMym-7%gerzZjBPvPK@7b z_y-u#B(^gkHg@BiauW2QycL9y4vtYK?@X@*NQR?9!diaM;ba6h)NV^o`*}x#>dw^f ze&`m^YybtoME9O^zeJu<$a;m5_sM4%L-`&Vw7ZuNk8>q{otZ7rr#6~f(vqob3{ zs9km6xC6XPM*`m@ki%FZz2RSdFWIVS?cDzXN=ErW2~gZ%=n|G$#M2aEFZ6~XTnZg=Csl_sHo2tCWOc9l zd0tR2np;9tBF}5#ZsoJyjVr#Z;~K}?tr6D{=Nr!p18*!7_0@5Xbd5~lCDV9W2Tu0M z8UAYPen0_C_$3F(zHJ;QQt4TdB7n|GtJ?b9XP#H$e9CV8^3rlYEZ!QS zKs|S*qx~K-H&-F0;X-Rsi0RMVD5kKfO*DSu3;nJN-G=qd<;O;emogrq3m1?=s6<1& zQ2N_yay8L*&@_lVNt!Y|B|oWyu_CcCMOS(B>2z&G*I-cI%CSsRq~7KrYl1&scg>5A z&&L7qQ%6D)T_gO}YKp^lKHfUg;;*@x^m(N0;NjMNJLQ z{4+I4v}hu#k+1w)W50(#S=bSMIuh@)2)DBVcA1P{8v1}0xtq}{gqOCFY~-KSt(glX zoUKT}_Z6)k$2g{mi}J=@2-)__L)o~`2@=s~1)ZPE>z_)vwyNDSFvJi}Lg%s){39r) zk4pCT^JeAVbx1#Q29F0Re zpYJFqX{W_sa{bhK<7#wQ97Qd=DCNV1#g7A#UhMXr?wCyK>s6r^g>XUWa}IDgJL*-J z@+uVq^w(LYg36{GnMSjuj^3+JjfghPdAi3J$EeX9x)k-hd;vZSpO*oH3<)?cII}q! zb*5ELj9w1n*xeHF>Bq!qi`U(1kKr({A$1}2#7QWb7zs(DW&36peQ0U%_B=Bsz2WBp} zd|`B;G4k{K^J)?^-9z;v8V|e62_qd04u5RV z1AaR4KhzYy$8w#P1Ngp2;}#Hl1LJsUuO?E4ZtQw!0t|HfKkt=ufRZ0Wjq;o^)kY@Z zg2rA_t-N|f{uwvQA?|t?Z2p3;Wa0YbU+n3bG!h`Saeo+H*x^z!qT&;0BUL%{jiSbZ zmI)NfyYFlVR&6qBCmnsE14I*6)u*3Q!{VorK6$tNYqGN6H;GzXS2N(jUm=;iRqX$nHji)f)SI zWQ`0XR}xp#q|oGk()7?SGOL}dchwP*Y>ESMTEq(idd~af=KLrt#nf?Y5flA~Z9Gcn zSMnLwZubv8EDca+@byu@u2fD1G>*qEC1gUYjTbx`Yhb}j{ahraAM1$}I@d&(WBH@U zBfUggxJ#a!5~rhKKq{!n#Kb8pO^O9+f)OPZ`;QnhU_{@c-`ZQcpSUZKFHD408NwvA zzgU_(TRjQ;!k08j^_@P5vr`+8I{=@fvIYvYpZMWUV8DJZH2g;60! zvJmQ68T~KkCH89)-(M-$oLfstrv2u>SZ(Fi3mvZQemQ#8(`h}VuUThTC+)`Wh(heZ zl%S~wd=N>QnT2*g``D6_!OZo1*QB*VmBTE(g3O$MR-p?Z8=HIH)uvBY8mBrad?oXr zy>G`N+|7`dlYIh{sS0F!&8#;o83GF1FwXEOvfKh=+*2ZV}kk{N&wD0c26oUs+~K0 zbCOMYb&hy!gs_7w5bFh%OU1p|Y@M}BzeN!`UE%&3zFMvgyURw^B`>Yo8=N@Db4V)naRGu(3!_f*0@Xk*s> zs^0!GoD;lmpB+~qJQ83gmKr;au<13g0uGEVhWz0KmBpyFjC@PuwWICrcu&r-{~Zaf zhC|GtF&nyP^AQRf7L4n9#|<9F4?!_5QP3*@;EEydkK@$1ra%DPZ^7rB?n%g8$Qm$#A^*slWkrp_iuV#NNdbFTg& z<2zOJ;Yq=h2(`nKuM_iK)t3706k63i+ zQlhG5=X?~(%O^b=Q4Y(c&ZeLyfP+NMIlh(v(v`QKI^OX2~ z6<+)LJlBUd2w^hW7B+?LlYfzG=)QtIsWs2m+(IIo?XvA?iNc1dF}ZK2`=*( zyJ-_E?&zp7lO^%@8Z1w9c>CKVt!kvf_RrHgOfwnk<^@`G3B1=mSFI0A$O*K0M>PQN zF(dJXb}8<(nJ=Ix-e&#HNRtB%+JO#GsdU_=g_;1QN|k-M<9C-v}TKMln66L(>wTi|hdfK&p~IVh&5(EhX| zU-Taf)MgEv!^c+^emq?IFX{~?4w&pnxz&!h8hiy$4+i3ZfSjCPO9MXZ?_*!Nofs<7 zggX3XfkgI>Y|~h7Ijur@BIV7?$Hbs0fL_5Jt~J zb&S2}R}8dji?1##ZQ*k>0#Cy);S?8+-nRj=l-Rz{Y+hD6i)`*$1?5>2ah)r*YmVa; zg$Q5v!U&$oKb-$f7G=hk? zGCWmwf8n`{>`fhx#-6~sQgjMH;zJL3Rjr7P`zj8QDoO_uAeJSl3A%XPn%Pt z4_Kbp&{t9iol zVK!}gAg$gAu1g=}L$}>e)AP3ck$nUV&L+Pt|0Y;{$~0f7mDiX#Gu+a!z}=bJJ_}>^ z#jhN(=t}ITJoOTdtVnz7vax(rfXPd$zp!gJUE!5>O(dUy?tMPl*7&D_D~MA{3~&tT~p%-dJHD~iKOFxfw(v9KZ0z{UeVGH1%`QE+%_Tg7=5 zDtL5Ts&wk1%`99OHsCgJoxA=05^92p$^ownm#47BeNZj&)ebXDL`F#Gs5SLjkjhf) z;I7mK3k!b!j6IH4!dwSA|Nf<41u6Sky?MyFMw;BR^|OflOLRDtkac9u8RDxxgtC2F)i*38fH^*{kKU!tDw>z9RFpN=6%}i8|n}=SZ zZfxvYogQ5Mo`RGC;H$!|@t4)Cz11RBoHG2kyz2Ume}L%v@e=Z(RP+0KVDbT%l&BHKALUvYyn`1_75 zmMnd+9=Xf8b@f1S5cY{i1O?9j9(n&CJlp>R?I1TV7svkzc+b!M-*ERF90LFMGZ%RR zH2xp%{{If#{mXx4E<$40UE(%+cjB4373pp#%q7)iaI8Am4jFHfV3Cv|l&r*d$lq2nREE0XQ7v(q8$1z0s)o<{eotQ8Z4*Uam>h9NrAyQoaJ0aEJb?9k#bN#8r8&Dvw~l z_cF3C9abcvQZz)1=@LRt(nC0Nw@FW1+gO-<4`}R?h`ub2j=lBaLZ5S9e%RpBnCIyh znbw+ZCewRiy5wN(zDSwiRxjA+6igyfHpOBt8twisBXdYPsRTL8OblbDPJn!D%)bGg zyiM0O{{U~fN4vxs=%|J~*-YnH6TYaK+!)jy9R%Tzr+S<6#K}QQ4=3QDG7&1&u`*ka z9vVnbEnk$MqQj;|*Fzai^Zc)bN7rT&8Rs-aQPO(H391K3D;=Fa^k%B}SLFV;A^-TXSgu8BH)93!wPAR40yh-#^0PuCD7hibXS_1^XZzz-NK#eNuwx?{ z^(0faw&x=L)!4iQw$%iLvY-&^DFeRGvM)Rq)GWy<)(iRA)DUJG56sSH3PP2oeM(Za z{5#&k0}MTp4B6SIl4BvlrhZa2Zu3T)i$NJ26-oKVW@W3rNUDIkr_v^qTnB9QMOau+ zaxSU;q@kYN0F)jU#c9R}OInjuw{o1B3S6wa7bXH9ZFXf#2`bC^un(P;iqm`B`uzix zcaC1m(lp9|SpK-k-hJxQjlXE|{0dutsSw>SI1#-^i}?qTo;KW6hM@;Wy~=El1mgHm zm5UF0O7j5&knw=QA-`52K&9EhW> z!9mk93zjWvHu25oZQf1zV93hD`2u`IQ_lYfpc-$tT{@UUohkL7CRuc_>P(ZpwDhKP zs5<)8Rng$$X{C>=M~+$u(;QaW6v}2R*las>=Z$*oe%1&alb8!U$0mAB$nE}<2gQXC zH^UP9V_!esimW=~`l)~;`l-Tt=%6Os&+G(>CM73xr>n>fKu^!KkAFR5KA}10VlBSy zZw2(d8&V}6a6c@$sBGO@AWI5y)?R+t3K1m}q40y-y>Z*#THe*RpZzwbVBhG3D?~hg z7uQp2Cm5mUgvq0R#LiPrBd17OFsVbNZjPtgkU(bjYgeS3UXmv0r3nDJQ&X9_zdP$DNY&_u&+^+#Lo4G8nv}>? zUzzsG>?x**RIc>h1+%`wHvcCtIQ$>HApeyFLRh>*6>NwN5y{v&o3y#zz);BaeJ3Ky zYZ*EbW^OL#GOQW%zTj7wkmeMA^xI-@xSe4AV*W3$~qx6|5UVNtb)w5cQI)L^D0npoT~txVsXq+FPavOQ6(>W^{tsW=`l z?V?6k2LooT4=G}^ZrWwVZ;fjzm*xhw6jfKY0dj~+~@N%(2sOVainSW@*jXR zsf(y!uNOXyZ)tC+7!VkhhjiDOhv9W83w%y4H6ILkZ6(|;ON<=7p<(1DBQY^dB^{Sf z)BOi9z_RHtbrTw(YHl444BK(5U1i=$J*f-b4h6*@PNF)OU`Ct5L6p^RV12Ddd&BVOf}6@ge}mUUUbMVY(m`^^I5r@&15-VC$xa1pfg08z6{Rh*L#VKwn?(V@oL4$VZe`d~}*?acQxjpC1*Mov*X7OPVA|&0?+YpTvq$evjeGICQ>^85eq5|&!baM^T$aX7yKM9I zc_qwI$Vc1C@&Dw}Hur4Yv33yzo?s!btQbD8{>=4cyr&U>agb02Ssq)DH#L8ClrHA@ zBlgXMM-z%-;@95l&p>v1+n&u-zz!XFEj-RLz`TFLMe~=Jvpur)e(HbRKLvaGmuy5p>R=xHL*zhpDM;Cf3b>)T;A9bui zyUezCd#Z};eGtkc(KQmr_fkH${DGT_k17{(nC}p=lTShj@qYl8g{_IFpcCL#p4f2U zKz`NZFsQqO==9jx-qV^JeA=!}{<~%&!kr*N5+@HEym?xelX_*9{5k0-gu3!)5SfMv z$^nMvqK?nRC4rnC2`;^(jK4RjsR&qqky`+$0+5gZDPip2|ju&g$|6mV||1OmM zReg5L{61m1XN^Lx($4_rfH{VXuUGjGXaoNMMf*(zCBMuYF)?ZR`K*#|w@nPi(zmV&>syP?fUN< zn7g<<-2DS=I6YtQ4IPcA(qRWoo!(EkxJE8ZcIolZ7T$oI=VK$^46&}4*c#aC>~KTp z{q(C1yxh98Xz!o@prN-YYQ1nQOZod?ICRIf8L^bY`Ien#o2(J9vx)nmatgUXfInA6 zh11=heAml=B-!rWc)7k{jHuYoHSsEzX1b8z+*w)H?|)%R`EG!DxF`3LY3UDWtxVzG zfE6{5IRBOBk#}kxaTSkMg7ub$iVJL{dwz1QqwzW~-QJN&rNh|;&z`pKb0i{lYHI4& z2Q?AXBbIC03*;52Bfo*}Ewk^>I@G4gj(Q3a zWo%n+ml|HU<$b8=$e569ZT$!MoS(n#yl-SsQYAJ$8F?yoEz$SOzid6hq%NPeu1l?H z()|x-hkk#vV&{hJ^v}yPOM`81)qa}en>}joe;Y9pJ84pFMO+menb&zn0Fu-^Lv4=inntr1Hem`zh)CWc5tP>Lb(j= zKM$p7_Q|~kNm0|-2a*|VT}u-0wpS_n+5kjN2vgii0jz+k@E44X%mYI)y>c&W8~$Xg zRUdXScXKta&>0!3eC+z2HDXXtZ&bAPq{l=zR(cYrNW{V~M6g8K;Do7~;bw%Pr};)< zMoSV~S&$6+?ty1-B$rUbUgts2ps=;s_*NrvC^(4BfDy7*eK)gOqwipAiwOnt)toq- z)>vlyKE+5w)q{lV-XMVrd=mgyo4q;RaFB3Y3xjRTKY)K%t~Y;L^|9hd4kQlk_l!)} za*343Xb6q3m$|J~+mEXR%0!B!aRMR~^F__+GO>%D(wYHLS)7aSa=#I8H--D((s*mH zb7moJ6Q<9mb|IpTzKyq7?pl>z59$D6Qs4T%Jm2Zk@@}jfJ5)KB8i1+v zZD2l%%~(vg(-nRw>v{KrhYh2or9BbPJ7s)l=-qbw^gCJ;Yt)VdX@LbUvZU^vowM=r z@(=$NWhgy}{jL0v=T|HGGSFN)tM-Ofhih?L`sIuM9E&~|Dq_}e!f(WN@OVuJK5bFQ zrr901q{OyKIW7cXJ*vP~6!J1>heiYj}=YEpg?6fFF8=rVsdJgUR5IC=bGZvXHJDoqvFp zHqns&cYX%&##ObCY$tPY45&+EYQ91b1A;=1xAn`DIMg$)p;+h!Sg!*587WFso%I#% zAAt2>k6Mck*sns>cyts98_g4=Xo2K73FIUlB8ypfw=1$no>f03_-IEL}F1bc!7@)c-)zy7yhA0Gt0R^M#0cTQshFYFTR!(-T>44@O9*MFLxG9JxI z>uLW4+8i9WJV1}K5_OORKDeRKl(!?uPc?wls}7MD;$&+elaGP8G)8j8@udk#5ooHg z@PW>Rge1G>wEFB++YBeI5INP5YTnOMb0qBaeXO;mZ20BNweyw?^97dd5+4fXZm+Az z{sDZpu&xVmToJW>3aAW3wlOLOYlD3Eljw4TQbaP#e(J>lN#~yo4}y%M9oB|0NtkYA zth;6_sK~#QUas)294)B@P8hm|&WC9JgwNE29B~MfAVBut-qVnaErgmb)*-0=$ZL>42bL4=*t<;kF10!ma}EV zBwTt~Vt92zgD+?j8WpX`rJ@kVP(!RwaOc5uETt-aCs6-bjXs%Qv|}xJE8TUwoCG|a z?;)6zd-86{&%DZ(x-8hE$kO$78r8|ljv6mmjG)-(^zmr(Y3ECm6vrIFDK7Lc8({g% zi>sl$w&E*(C-(w;IgHbENIwqD#zV}b~6N9 zi&p7Y$S2?D(AEA{>(^?>c~+E8HHnw?SM;2lB%RayQ;{oynGfc%f#k~ue%7$rdRw1r z;==&Sd6Tpy2d5pIUHe>MqD10=0>>}MqDX^NHqsS&9YVsHN9U45hNiqo%c@V?eMY?Y zU4&}`o;3ZsPK?o{{33WjuX0f|u&q*bKKkPqgelZHqEi(9Hq?Uw|1-FFLy4Au#3XQ< zc`YoFu8W@^!}4@oPOquv3Ty-lLS1kDZM|sn?5wt=NqmkS9z*5oZ3L zq&xE(F<)qIzG)(zz^Y^e(IQJqClPZDVP-}iCf|s~KL7_;_fr-^=_W8#8;JFc)0FgW zdAByy>G1E0c)-cCT$3!tCCQIJ@;*qnOmrD#n{SP2| zj6ON>074v}NBTtJI-?v80)CU#JX*zF3z^|^+wq*f_`E-^i zb?=u>FNzorwWs&BaG#*qH~#>Uz1p)Ze&ZdA%?9 z+5LKFRWUyHAQ)~{URbnF_xR>P~f;(_oo(~M5k-Pt)0bU zUAe)^(T%p4Q`uHUt-wP#--x4Y(^)e6iAE>B7F4O{Qf4Wi!>i~<0cKS1!CJWW=6Zr) zEv3~o{`Aa5{RI5R1i1OhSBoc1v^8zNk@kUvgC{&N;BDuA?9oQuLjQwrdcJf=eXjhf z-@@nL{w}R`S3}kIrlh5na&8OVaK#9+%{o=rP^~Wgmn(j+5Kmjlhi;pf-jv%OC8KJg zXS_?bvLsW6OZiM{L~3>f2Nl9S8}WH>a$X^neSx~pr3tT%$9@N*=(SBX70U{FO7$V+ zH^~r&1(F$4f;4MBu*i<2{+34Bb`=PNkjj*<@9Tc=u!Anv)SX2WgtVFn3bjiI2w7UD1QJJ=mCiqoHJ zA9gfRTv*TvGdtd(ZD_50?qSwyns}&vCYv&I!pHpK3T$+oc*H<@?9<;E^-FIk8Guej zuy5p$dOH^%V#Wt|=aJbNRyN{dV9c!Oq+Af(;n(!D$5oX)DNd@iE6n=Q=9itYQ%wFP zDUJV6q@$~R7dMW?>$}kUa+1gi6D<<8I_nx@MgFJufWqxV*d4QCAni9i7D>y8ny`3caW z1e`^iNTm%ulVwW(16Ura#?@rnw9pl*KCv%qQ>Hc9DRLJx=6^!F|BC%PmiTFL(jP#I zmmVO#iG$&q%y^k)HBM8)v^pD%CIkcn><1`OJ_ADkGUrS?GD=~?Er2Weu&-SaiR+MT zf5P7B2~?n*Yq|lbFdYcP@w{~s02Ov}F54NsfNRCWS7d&t9YJIo9fb$T$^RND#?xg7 z=EX=|uE=M;r_ES55q(u6en3M9iS^Un8mYxH{9p@SGzhfsv6l==*rHtPo#}hkZZ2xM z{4QxFtId9$RiA8(8MeZ#1Fz7+PLONZj%zi`0n93=cNf-Lq}IjW@<>|LBY-#?~K5IL1uU z#MbdSXXi$n@%hIOJ-y)lWy7;ou$aYftzz6pEY6ye(N;TQX`sdj*z1GfProXR%^czbmgQD=i3o|BMB{u1%02++v_S zyiBqO+cw<}7j~X!Qknr#KR&DvldGWVkr? zB7UQA%!}#K)VyfKdK>JtqBWPir^0iCtwjgRaa^yuh+yE|ZhALv_iER2tShaDW@UZ# zL``4YWS1GQJ%U4|if-bsb66k|4b=KHA3ign`o&_VaHe>sdfe;fM+v?f$!O^f7)Kw; z)C&jyOZ2-u9OI<)pCes<&z$KcxcJM`^#g5VymL5}(!)iw z+u@(sA1f?8EY6~OjKo5I#DoTD!Drt%$oFji!ortQdg+P3E&T&XHxB`?M{&%>8d^jd zvn;a6Z!7ENaJjN`bwkl#%km}a;GzBPW@E#m!qB9ZE)f)FV8^G$JRMImh_WCDTm1vhEf z6~!E6px#28jHv4COM$=Z+dzm01)eILU5T#hqis9m6*9ox+Jy)U7Z@2H)N<#0>uLRb zw|?wDlSf9>o!21uVTjG7Ae%~*5xEoLz*{_`!>2Ci|HjeXIYwRJx8XW&aFyQfz(t=8 zWVpv9bs_^DLV}zSZrmHFwE*ry?4r(=2q!$^h&snU6VewP&*wk7#uhY=>b4th=IZTj zDE~&(ZLvGmu;>(qZ0I$3vnEBMXnx$OV*y}^3b0CP`Dll?ll-?No-~7*e52*Ym}#?U zYa%IE)Z3G~ri)D1-#rd|kjq?anuu%rXq_n`?Anz&%632d#YIx2Nh&o{Ml|QD06SD2 ztX$tcvOiT{CueELbV{xES-PaANxm@jWc#Mi_pJZ9 z3|l(CJ6v?wH}f9=A836_u@xCBVO)I7XD60WRD5{jGZ86h>r_J2hu6%vVjw-mPIRvA z5LYog0^!VB#&2a7b#SnEI^61tQ|k}U<=W?H8CSOMM(c27E5t2{CtNz-$UA~9Y zm)IBBEjM+Bs&zHM3F671Rv%NSJ3sPF4W7CBx71K4oPX3T-5&rpPQ-Q6E+V#dVZya z-&y40(dnGa{n*O8kp{AaQAyPHF)ptd0N6=>k5*AwEU+_t8^As1;Ji0|HnMWW_vU-> zl0IjSla`uhgx6+{yMQj%J3T7B4NxPE5}IMI<uJt3yQ(j=y zIL5ez&?P~ns8o*DFT+7lhP$mr_E!F&{Yvadhs(7V8{JUHA=O!8@%#Cx!``Zea8Su3 z31xE&!uchd!*{ztPFt+&>SO(nnP(G$A%3HfgouLNarGYc?Ve5=BY1c8oy!wP#(0ON zD5c~9n%%N`cY#%}BBTSro>or8ka_-okmBzcBZ(*dEcUl;$}*Q6NDOV%NjGzv`NWnw zBj47KAOfw#co9oBK=Tg!U8LI4P;jDN#>9RCjX~JkL2=&&J>`BOCGu#3OD<4Lsuf+` zq*_y<>khTq@W=}znzHFC$FO|qnI1eIwby^?AU;}WtRtK}Q}GcAUpb0dfSH$PRwFww zIp=-lp3d^r?O62RZZeUb$l1QW!3c(^XFxVB1iaYf&-X1NobJ=o6ZJadRRvXu%Dsl- zKfsrbJ20SGVnWlL0jWb{)8{!wm$U71w>~%K4D03PGMfZ)gv7iZLw$*7o`vRuOY|A5 zUuZXaXOiEsZ$5~f&-(ih0w2N>UV1vv*5?=DeE>-t)STudy$>E026aRqX~b!*af(<| zzH6i5szo!x-bOh)Z+`$At5_uue^W?tA-PisY%2tGA2&&~x z#|bAMZgdlU+2H;d#8^ig`94bD?m6YCjX%TxLmua66Rksy$4?2Be< z#KZz<>72-q5MdYDnH3LdWo=`wn_#Pw#Jv63K7Z}cv#-2hF;mN}rZY9|5&F%)YjESu zL&pn-Qhe6518v_|;Qff&tJ;@(c0LKMWCQ)*YjOJMrVZ+yEnhDda$pSus3yuOcSSnp z`~Db}7?TWXG5xM{&1`ZZ)~$b;6Y;NpcWQzVr0wMdT*>YWS#jQ z;)Et~T~Z#zTV$HdUWt|fcL+8bctJ;bc}>P8E5MH`$9Yv8G#`99mwkZ2m$ocj)e{KD z7GnruuvpF>2OROcWSzApxz3B|_I^34BW(AVg?8 zKb?IoK;Lv#X+)!N-A4!Y#=cmMkyU;Cgai1qCEt$>FDdS61*ta%4r>;^(gzkF575Sp z)~9Cgc7#5+c3mp?W6WL>5&_fU&RccBiv^{*^b4WV`b-x|A*~^Z-RMsovzIw)D4DB$ z%NfK@5Yiy~7Tmb&0`r*yN@&o_a$0E6E4K-{12jUTL`wG&rs<;_%D>l|Qs!tUTKquj z=p*dQuBcA7nECzQPMW+Uk$m+z@bd%_P_Pf_w|y1-JRCK|mLTWKsbFSzaH-WW5IMlg znW||Xyy}!z>AXg)SL(ZeqEd?x?+L`CFiv6(e5vSBzGNVv)Xv3sM8Q*Jg7S-AmtXmW zc#)ABUZ=X3n=Q`XP*iy5h=hxyA~Y-62IIA%p5X$vwGvFw?q;)XmAKJgt0phdQql1t zdsu~7v(zWOTA;V}&Kj0#1h;bidTgPBj%qja(~dkhYjja*wy#WH(uZqPvCyyGTX@to z3$BjI)EB`UAH15irq3H5C=#~S#kE#w8&;TQ(db5lwvWe1=Nd347AJ66qc`7Td+GO5 zM>N}G>}8hqII}o2qVpFFF*hkId6fRFb`=p7FEV~6&c}Oaf`}P`|4?()V&G~k8sE)Z zYd3tVa)#owN{Wtft}1>%=d$}6WDas#JzJUGrm8ifT;=brRR3c?qqIvj3R} z(L?%sRsUFzcv(Lz;b?D4CzDNEHu;5ls%V^PY69QzFK9b$Z&AtcpVg~_63+Uoi+=zW zM3G?q;eB8%h0;thrLUv02K7KI{jt9(OR~SjtkiWMbz&g#6MpVI1o98iP#gL9v3SKc zy73b-E`U>#;)}l&u5+5kccQzCH(a{%i!c3(V$SwxpxR_&K5IrgBwyvPAXNd%0H#Hb2{96M)--Ez9o^dCvE|*FTcCr z%U8|)!JRDC;DgeP`F#>IS%_jeIJS$H{)ZE~j1BO#Hin=q{>T54QdoWtcdsG-ZApCxk zFK7peLgnzC%Jy5W6+vv)-Zjx)taX*LNt(@EPA8y-TVaq zQw>%RHBZUg{t1u~Hhg4t{D3w2d3jxyN#OX!%N}d;^$_nV`rZ575T@m(gkJ0Uo3?j$ z#k--6IUdKIR+DV?!u&gViwe?rFX9tPiGZGnU zeQc5Y!Rzgnsk0>k>NP~a8^?$7u?DEk<)fTlV@jXU?5ja4Agx#B4SI`J3GGd@PLqNY z;hWaV$?^^_7``ODQ3bhx38Mv&nMzIRT@3>z{cUzj2^|&entZx8SCMwceyn&AU=DkYt{yv-LP&~=`|RhJRly5eWv8f;^V`h-0P;3e(@0#}te+qh z%&FQ00}kTK>S_y1y^+lt=6c!P$*9y`PE$YVk56OAe6WG7yZ$JMSb!Ia9j`Lnlp#-0*Pp-|0nVp!&BoK#YA_F@|wsh7_DsoNH zyU&s@vyRGZsr1!nww9AhvQ*vDIh+eRfgZpkg1zl|`r0?_~#y_9Qp znE`XjhKe+sVjaMno)*=`86^YysOLB*mes;Ym#hfYF++x{azg(aU@9NI;x;)m)Uy{; zs;x5M8xt}L(;oS+^prH2mmx~#wLyQcY#X%x!+~E&(iTuDT7b(4b9+y=8xUG!gId(| z?ma^WLsK(EQh7zI84&$+8<8THpx$#wM0(c9R~s1gneXc_^)tV$R1mHpD#wmOIcquiHaBB3b&DSv=BHA1 z2qZn>c{DWPrl;ceKyxf@aArLh5L$RAoVKEZg+=S4GndYy-!vd&SP;3H5OhHA=nMh7 z%TeHN)9Jf07_kBZH1~TOmY4h?iZN#j0l3E9We-3oL;r}0nE3$z7a)7{e9lEvg@6B& z=c|;>+Bm0Kq)~&@3WG*4w$wxU{^4-Qx;6F&UX2vZ%H!8$d|!iw@ZHqV zKwEq5h_fU0PLl)53oP7lh|g)E;G24!q+8HL(PowCvSKVK97s9(oA0}epEp|yWJz+& z-EWE|b`vZN07c|erL3H;0WZ`*S*TR)%%+sv-TBlc5-vV37>uv<-1JAUgV zL@d!DGtd4mC=3@fKpCv4Xnns<8axS3w)5XNC2iT?slR)Q9p>pn|M~YpZY#y;yO2Sp zkWkSdNpX3EKgM5UA;$Qm2(rD3p+C%pOZ4JMo*9sw0bS7fCDsSF$lB^_nUs{=I8V*-~su(=LV*G=E)LEL)P9G{tLqK?R)J)m5R|T+nk7ezfLqn zdL@EhiT~_gyWzno12$ecCA;soa+;KijmbakN{L~5Ns#lHH?Gwg`6o+TH;p=tUtvy) z3bDhik&)!9f<@r-YVQ5ba)fLq*r<%oHAm-&=q zGsi`M`H;Y1{ISteG3Jg^uuM=JVc>LrB8vIOWpN{J9QWdNnF%dJnI4y9^jsSb&#P6( z(=Rr6f3}&kH|YHYrartjRuxWu!_b4#UJblp9=KQYdp%z`vtGiv7v&FqD5+b` zmX&o=usyZ#J!>K4{Y~=QOVsoRnlGa*GpCcH5xp>^*h^dqMNJ(O&|Coyv9M?X_O@)E4%E1V83W*xqM$tVOYaZEi-4uhmvyoI`FM}) zm5YMyvi>RtU9F~jjcX;py<>t!`V{&$1g z3GO;p;&rS`bj)B^FV{db1<9s$H&K_M4~n>?+t^J9omzvuf;v%u7%^n3w!U;K+1NlfUE}OMs8Jhs%^oe^&V)dLe}F# z3wtzzn}>Z{q0tBn4b5T51KICH4o@^Ss9?WtOaK)ZSG*pJqc>Rp7>WH5&6qUkT?-`g zZb&K?_#?@t1RDyMRgI9e7g7J}ljY>bK-G>$5%)~wCj+Y=;N-pmxyIDFoz*i98|V_-pVJ-5OCMM!=*~_B#f{uH z1&ZnOkMr$7hupkjOoP4pj7nC+>u@#J+$;FYusb6UPR{rKKN z_8SH#iWeV5V2}rSsHR3Mh^)cV(*|Ib2w{Xtich1iT4$L{S;6~aYZJ2YzUYAS!aW&p ztkaePlk>;35$~_CUu>GzpSh@E_G1-nOYLP;+msIzr5;YkP%ixfTAv3q*Y@V)Gk{~L z59_$TAy8m!UA@M*3^ln#&p-4wMf^|^#K65IuP;yT<%G{8$~~2|QYeov=%fe{BHIgc z&A5Z%mwe7PJ5CnbOicO%at+rcn5 zq*sBl9@+YG$2qBD>tP5n>?HJJW z59~9#SE+Qtde-ns2v}^r|=+#%qXqd7bLRQn}`XNZr_y|88j*H zc|J-)pb6Q5F1A&EOt8jb2=kys^cfSEX3Q=3Ds|6hp|4>U$H{$tAF@veBDK49w)BT_ z4Dc{DML@Nh7ouP6IrVP#EbK@=%(k}*7sqO5AcyJ|Hi}cOnaX3R?z&ZApm!c?DA0% zicNWaDNyVXxWQ%XFWv0&WJZTC0<sq3JpL{MJh+v{{TM%mh)Xz z5XM~qDxp4T6x3+A&2rQvfL^EgK+D*IOwaL5GC=5&DCJ2z&J^;L=kH?wG{zx_EY^?1ppl(9m!7rSZP|27Sj7QMg93I9_@t#^boeN4i=X5>^A=<#(S(3o;PlL^pp5@gsi_t-kZ&2S2vI7PSFoWlVK1O#J;3V9!WdW*}Ad)sO z9~_--`|9zvm1ktGS4}Frb$DEPmF4NG@MJ_aBe|5yl?C>_9sH)M9^Gf9D3A%)p->== zmjZM_2JV4G8tYHdrby#AxDLY7;&`=2Fag`*<6_z@u*TQevW;w_h6khg>c%te zpUNQjE<#z3vs}YYNg9!vhB3$Sn$>Fn8>+4*8Bs9HIi_C<{;;Utb<>&p zu~S63R)3fuY208{0yZ2gKGuIV>)1Z{nM>f%O1Lg~iWg!ZQg&|o+2xXFBTM5P_V>`+ z(Z^>F^y+d3wtCnB+Umdd6d2z=-DcI3;%bLwx}B%(-4aFwyiUdl=B z$V$<;LC%&=Z`C!2OwW-y7NTf=m_Xa;nvX1uA796y&nUpJ3IG&F&4QYN;p9{u6PV`~SfAl3FSUm#f0<+xX*|s8+9K@x&(a62SQSK$ zatL?VY*6^IA?$wTKV`*+ezLxaLQt$gArXWRZDH1T)I1@h;axWQ!J%aXKthIFr`f4* z^~jH@bZ@jtu^k{yS@lwZC1`cAwO+^F`7h5U&?R0&eI=D0h5NM@_+M8MYkqMpRhIkG zQoT1hU3W$3B&LD!SI1(KpC79P@QwXEMcXG*p%VN*BlazErv$B1 zIj1WV>Z;Mny&5+j4e1qUmhGaTab6HrC`drP*&1d8-cHx;ZZCF=V-lN9jiN z7o}axFlgzl@lq=BDT&8Jm)lPfYG`j5vm)21TE^&kks&<9__~F%&vTzOL2L8J_Y>K7 zytUC!Yu;}9R?}UMw^ESwfdGma8Tm)&(xP8~|T6(toMmb6)dNlHIlT?3v;@rAsN2k1y-VV+^mf-8o^l=1C#sPja3$|!-F`&8!n z71evKsY!DoH)_=#?K$RiCEt-_r*Ka>xJDjM(*l^S?N3KTYs~ix!yO$n6In9vze8UZ zq^NU5H-t`Z;H~XNN?*I*S}S=xAZK*4>H8ie5A56(jY%Pn-j1X@<0>T<4RT`|IeX`9ZW|2)@_tIy$pkXFKl2~X0^t=$Djz4om^i^R^AW*L z?k{(q*mdxuM9!}YC^C!ay{-xrc6TMQN%6cGL3WtpRFe4EFR#@@vm9`f2=W@LX{hH9 zCut|Kc5ep)mq|WOKC>Eb*!sMF%$kV2=FFz)Sl27rt?*L_3eAc5`d^clu`2sLeU@Ky8ey1&`)?6OwP(_Nvgz)~ho_+lic#~^9 z`w!5L#EdemsLrMuM{K?n6RJS6>TRp318wMxnNLy?_^>2pxnTE=A<%V=vWBB?8pWn{ zuLl}E=JY?n`4n(I;cKhdBQZj&mAQLadmA9&S}>c7jIVxcgcaNnI5?*y^|kd4LJ|gf z4s)bIM%wZ1poN9S`!=? z^QgGB5}vs{(vPQiKke)HCf@Rl%4J+3CuMxCEpMufI>m?P1^s9Cdlc$_LgJ4+DnCV>ZWJ}lIS0{8C)I; z3ys#vxQJ8kJi$>613pCc43n|sh(Lq{AxGz_dfMwxVz&4B_T5K$Y=T9y?WBbS-b>)+ zSf5)xZbGSg1PyHO_Wkdfl)oV5{NX>opZh4=FG)WXFFpO#__g+CEwsB^WYCx;>$d}< z?KrErIJahF@0%3mQ=SBV<)S?rDrc;I)nEQsS}S$?*sji`L4->PDoV=LB{R{xj=fz@ z-NpNA>9WwitpoLfGL9eHtk+IwDvu!1&@JxjIy+)~=|gVE9joRQas18BZo<*e&Z!Xf zNjKw4Q+_-_KYW}qySwZF1Xl1stLl!kwr4=)ivNv7_JF5ebNHj7V8Mc5QgH(( zcYEEMC>t}?ZV>Y~Bz4IrgCn_0UO_)U89uJ6$TDtcYQrf#Wj|GW*?MkVPXJ~u0edB1 z_OEm1p13;->24`WpANOAhL)q~)^+dGUSNvN&+%*xr>pPfD)==i>g&TduB0H-N(uEa z`(Cj}Ppt}1Z@*#7KYdPjyZsLGSR!a>qMO>7uP=s5YY#X$!6O?>Ba+2+s~ur{WJD*# zSeNex0gUFrc-NU6_A!xx=KaaT9|qf2bL|QC-2q&UaOX(VS+FBC*ep#^>$7OAyJJJf zIOf+)B1ogJ*tNt_w5-wbY zz2(g5NoQW3He^f|+Ms-&L?t?YkI#vG%{;zA`Qvr?K78pt?QIMR^+(}bCvMQQtU~mO zfOE#g7fl1~WuP6vI`#DP3v``QR0-)sol3ZeKzEHP8`8Ug{@w#K*vWgLpBwe&%n-|{ ze%e?wQu*N%MVkR0dNXr3-qrQ4dwdMMocjxqriK=a<|>~*j;5O zA9P92ma#QWlUohUc??z9mZfgaf<7DZGLjGHG^53MkYW;a$GE9^ernR9} zS+8;S;+ZyUkkD?C7z2j!%25|?yGj8~Ci#A!Sh3F)hq^eJN0r-|K>T;ZcRZ|Ht&fka z^BF*An*ra$|{AmlG3u-{CcB8tf*(Q6+PoI{JFevpI0H=M*Ao5ehOj% zo23Ii?QW6X`0rE6yR&zXUz~yN4}{ym0kEPbLcAJ5zTMmOo$rv^InqPcBO|+jXV;7< zGNaEmBS)B$%77$mbFjykeCpN@MOA&gV7HkoeI0zChg;yK0`-Q`r$EIC2{)9sqR2VP zT4L3sdAD@lo(-QtMvF?tE@$Xe^V>iPU<~SHBZop*UtfS2BDBB@anL4tTCdwNSjgQ} z=zZfYpXsWqZu*w-BHNSEa;DV#f^#d6-4%&~*2ktvb(6B~-Rape%}6 z7ytC9?ZACTHAm2T{{+blX!oV>zz8!YQrDdFo0ak({SL3%#v>eUQKM-+khQOP?HHY- zVcd4+lO8F>b*$dU^>Kh-HtpiaB1W-&efi1{D#~r<=~VFK_)v~PKAqI-!?wI)M+t?J z(QJBEdo=HC{(`4b_p34si1}6MRu@vC+2V%fNBT)Cq<1#Svn=zXxAcK}LUAT!3JKk2 zH>n22zGANgE1~#1*bD+z^5^6Gqz`O<;7>C`Do_*qPSfOX&l!!Y%AXtV4EtQlw5Ps8 zm5hc|9<;H6U~*G;;b-Ev_;MqNNF}4dm@~d7+ojH+lW=27FEM^$M6H|}a=>c)AAr6n zO{Kt%*{Tm&E_4QRK>Ecz`ZNA2`u<3K4x1XDKk)p5z=hVHJU^quuAW7xufdNCdLe~P zLdkNVcfQu1S>BXaHCgHvYFf@8Mc>E@f4*Bsa$o$_dVN(LiC2H&lUBWBOMi6%4xuST z>u_&mjr;Kvxe?LR*a+tG;DUHQ*KV(-zvSB!)>>YaT<~Ow`b$OSzPD1pnw7Xa=ip&q z;u4pXkcru>QjrRp1R;z!u+pEc?frc94H%xvj8s@aA2acR4GcYVkVmb$0CG>Hv}`-G zlW2&ndzm*Ux1UK~KXUQ>10d!Ia>9xu@|WLkE^j|`K-~_@kSi0sO)@89Ckk}R1am8Z ze*z!IOCA3M#7~{<@OUKwPuXC>a`cR?uHroTE>CJ8Yeuy%;a#@QVWH3F!jXrj!pK=I zx!)-S?$R3#klx@K)h?hS)teg!zmbX;Pi39tsHm%U@mIfr+j8}0d&mO&C&Hiu*o1v} zu>?B0@)eZ~&15Dqek$ptx6{+ONz=-jSrzXere7lU`^`!3d5@-`k*&qRFRXGZ3OfO% z^%(+hj$b0r@eNNYY|AX#fy-{)fj!0c;C}!ICZzD*;LElu`IA%lRC4o|loFO6P$Mkx zL9`%o%|X3EQb~c@v%y7U&tn2ZDSeQzz+KJXSYSFI9+ny5JK78^j(- zWimKJF5kI5*pfd-X)M<<;>feS`H~12_hdsijf#|HS68a4GIVNxQqE$(lnLsJGSK5Jc1U`%imQGIV;}8+g_0{Ch8S6%nF{{ap`@xI1BRafsSsOi;5nI-qTzmf0X19dG9%fS97@QAxH zU1}FiePkyge$x^1m6cC_^w}(L&X)J2Xwo${g?l1FfY!=3LA4Re_Fa*ah+cvWSoZ(v;(jYFD4z5b1h{_RsuG zZIb8hZY|)EnUNQ17*zla9N+`^=g8qU@444s6tNguG+Nf5GQX2|{O);W--xHV(jQWT zR!Oc(&2WlcLq^257jE*|7>skz%hJC^!tqrqc^CF|Pmh(y<*kpC{?4mQGg!)6T1sCv zW9Scv{{SAmQ{pWXz#0YqxuITJ>9J2Jg4az*im*fjdn}|j0As*jK_lDqT9oHO14!PNbmjr6q4fzu=#Fe#t%(@s^+AuZ*4{@pM{_r5D(uxYB|}aVkq0hDRS} z+<-Pl!SZLEdsikhqUMYs{ZB58UhN+B@eB5UxBZ|#5qviArl)dEQ8#uono*@bAcD&NSy z@cOKKo|ECP*sH?d2>d^DHRhQYk8YanS}5l5@=q*blrPPRbL9dua0%q_Yo`y6m09xC zNiS0x*nedk#oY9JU)cWu;n&2=Yw`a82wj(j{>vjkP-DWG z<2{tDmHuQI~9^cmL%|`4_(!G zd}64Zvir%zP;}Z`n0_kw0DKynSl50wTt#zzZf;|>xU-r$Rx#AFnRw?T9ZopSOmXg{ z-8jKrd8EGbo)XdLzu~P(?_R#F0^;ETbTar$k)$7`bSF`4X4FUNP*_@cqT<@l<+S@fVlTBMSL#ptLSQ^; zA_532vGTz)hUrOjDc(!&8%j~MPX2oawGp(ETS(22O{LURTL%~E*52l_%j$IHjDXDbSpcTBltTC?f(EpTz|Vum~T?(_)7~bf1<8H$Qx+pvlBp{ z3S#YOy*sTO!?uN__)QrDHi$pqG;;z?77xN$NBp{{;p8A+an(?eKQKQ!8w*_gs<%t6Lh3tV8Jbz&YA!bxW<3Ygnv0zWruc{8Z;5KeU-Wh^bP z;+Alw&@h%DccB78LlKXZ;PG6zwQffCzvz8e3(9kbDxDAFsK!zM0JmhD{0vVN{66@b z;X7?lN!9Gky7Jved3ccO5lFG2jF|pl#aOW1a5KX5SVcwE(?pl%de!kYX=K;0H7d30 zb6)!L!$to9lQ*Z4@BaV-ycwhTo8Ui+C=Uyq50+}wMw;|=I+^z`%77TLhwI=bS*OP;%=v{cn(M{&9#oRBw)VJkpyxC4B=j#TP-6Iw0y8&`Dk51>@P&*mg&-ygYAXwVaf>v0^-@slDNyBl1Gu&e%nqsl3qiUKX z_)6Bs^H+k`QMbC8{JEo$?nVoPl~Ov4Q4q2HC42_gbe#kCUHDz%>xQ|xu($B-qdRHV z(oXUKikVacap~#Dd{==wUeggMr@K8!$y21H*F(}gC*$2e#(!wGg(iaX5xB%vopxbJ zA@+fsIN!{DPQa1Sqg*a9 zLH5N-RwcN;drLX)r&3ZRErDGU8^sR2*r#-c?w+DwT zKp(na%8QhuUysAqN(b(T*A#OPm9$-tLbC*775u2UxpdIbi$t>o{^@@zR|^_Y=@z5@ zS&zz#g}NJBb&PP_p+SS|iciRB^8WzZoH_VqrlPMWRfi;h*Ewr^KgRtDtMH!)TI{ur zq?-l>1)YyTG0tnY>1uP@`Wz+xrQ*L3z?U8t(4m6D2~y_P=Jrw?vY)*gDBu+&5KkbU zD;C_>x{a4C9hte|zZ3ZL#F0+cw;moBw(YXw!dPaGSR2v4bHVI!gH;L6UZhSij_Cb_ z8Xc(V7{}7M`L1r_NHkke5AKFOlyh7;M}K774F2qXRIW5L`zqXL=Th{{Sq-JBKP{X2KAE)r`?`a*=;$!W;cqqTyo7Y4DHvW+=Gq5?Mre^2Sf7 zqT*<#_A%}sBGb57Xt9i+^=s)$;;}HXLxHeNnNX^yQZwy%@p*zF)UI`(+5Z5= zch{1%lK%i}l-$|rm_Nq4Q?fi7i<)<5(_SL*XT#4I+1hA75^m*f3T-mk#+K3|!*oZO z3!I^3kutkwjgi+R5>=T@Npoxz-L7)}4ER;>=SzK8!#)SSI>Z){!GCLQe=Ji?B(R1J z3$lP1NdS1VRA-Egn(3vid0CxXsVN*C&+Lovh`rp82Z+3%Ez&!?I}0-stb=k$j3Ngi zSP{6Kcgd_8QI(mxmomCI@%twH6|t4f-x0h{uH+If(%2J&o_5HY;to)5d#JVSG9Jl59c;>zyMJ4BXEfXKW2?2*q=w4ZF|p(NdtFPQzB{hlZFjbYRqIoXTIN?i9Py8bd?TsHaiMsfG@WBi zx^LXuUzn~@&pF$i1XQk9&xn&zu$kbV z6KxnM=t{6TlhhjaV+lznx}5e)M#!W6r~EK~)%Z`uE&lXSum04h?4}9Fxi|bY_LYz$ z@IJPEH<*Y1%xF|*K6v*Ye`%%r(R@AC9Zy1MLH!LsWidHNxbgc<-}Q^(t>OOwdi6*C z$Z5Ph!`ef*;rmW&V;ephOg%ShBmV%6)B3#7y{s8#587|VDCM_Rb@LjYTL^CDKQd#OHCN30=Fld-#=05!^N_crw+3G~9!g?N6 zCYhwk6wzF1`m74Tf{~;bL54j`$NZ~b-bba#ydP78vhcp4;l~kZ9w)W9(1U!MZoh4F zZ!`lxb~$2>WFy&+<5_<44(d7@zDe%&Ht&21rg)lbd)+?nJ1-L;+ZD!>s6y8S=kDxQ z-orn_$@o=!NK4~QGF)X9?&^=GhwU5jbc~M!=t{orG5-MB>VByrzOe!m`$qg=EJyqy zo*fJ7eDnHwl>VnNeP#ql_K5h`CPMf_!zw#&ON0LawP^aJkSt6Y8-CCq8#D9xXTu75 zWJ7Vs{zj(oa$Q5~FziI%9)3EKf8s^qWK3s2XSgT-07p^vNek;RBL4t|>+#XCn-2`8 zdH(>9NwPkG!QZ)*qqE?S#W+y90RJ*Pu&4j55x@7^(fdrx8zS9zs8qjNxmp+v6IxL!C&P^ z)g#m%ExnF{!@%Djb(V!~z99Iil2h`__Sxe@{{RBWU)HmgIuPBJ8r5gCPb~eXJ{kDi z!=DQ^``v%zO}@T#`@282czo-RcPxHul}0e0oT)iJhOwU`Ug|fCo&DqUVj;&$#MH6| zO#mdA0)ZJqc5q$s(H<9 zyM|w9k_!RUu10ZMQ<{qj)8@wbfpE#SQm;dBt{diJ4jr^4+$zSU`6P&5AH z?u_J~z#8Xv>Tk>DdN=I>`*~=72l0QzPlNsz@SV$Px-q!XUsAMqAs3e_hB;+)+0Gwu z9Q0l>LP=S$YUhAyf3`ov{eJUL@bMrrvl{R=u#gw3fyGOiaaGY+bl@Wo!;XVmgZP@pu~8 zims$1b)nru8w@-YCeF84{k*;pXf~D_hOy&)CJQ_0)?0ZV#_tlN41xe$_BF{ovb-#u ze-o-1j3;|Fp^Xpx6mRx>Bq;cYq5WFY^+)QJpZ0Zrv446kW1zbltN#E64E>&N01|lr z0K*Os{PY(K{L+{9eRcL&eR2=6axdH8_H>W}zB=%(eHQLS{WjJ8O1jxGeQulVc~-0Y ze|#|UCara2;k|Fd`c9t&zEkTOmGEhi5LNwY- z$i~=LtCs#}-2M{yukdHWP(qqLhLR^ypR`S=q>>+ekz6$>V=Ff234O;+I=FZ%MX$X4 z@A%~27V#g%?-=-tLAHiFElP1a2-#&uc2T&70|zWv{cG&`;3~N}7CdtdXQCuzd&fp;PG4oQdMHg_k~7S=$3VfIgzDl`e$2x1n}DD$$8PSQzX; zB9n?+4N1Mpr_!U07Ply)c1X@~^rA7cDa!1o+HfQWjdv5!U~%|Uve}b+>{ORcB}f+g zSZA+8QOj$Tq-C8CPq;X})2-$iB>9np{V7`Pw<{ym7fSP^V(eZl_Z@q2{{ZT)g--gI zx}5?mD=6~5QFk3%frHbEe3o`4%KDNR?N@LX_!#N4Ii>9GK65>-pndBNvtacKrvvbz z!?^jn1;qMAkp}wi($^ffoghs6oSH9AD^?bqpSq52{{Y8-53CtQ&x$n7xX;TVlOOla zYcFd>ZzE4*RsEBhx%kWQqTG=FD}k7F5yt-jmP&zHyiFCeEn%y6GNt{ZJ`mZeq1CP@ zkx3)$@P;`2NU3%5h4?WD`O!Z+4*@imMOj9!Qq$lq6vR#F9bmRL`Ic*~9e$qb={Gw;lwI~7TWk}Nl=*%gsbUOpVOSwk>0QRZ)V_|M5hfUQdx&G(~ zs^9P+TlrA&kXocKs!jc)jnn@CX>S*J&i(8@9eg*E_E121Ct}gS4?`rRqDH>#z*aNN zA4F>m6jrUBWS%?Kv{?Sv@gw41pKW#5{t>?g#rCPe?y_A7-D7ZjVS)betYwL>J(ZEP zaP*_l=dOM~>+{L8!G0dNf-pj@=BskBu|M7}T5FXj{+Y`f{{XT&RH)RR?5n~%7#g0X z@dw96lg2+2TF*{#i7a$jCt*1BkjvQEiI3dV(2|9fb1=){HQ=hEBcBq z235-goMM;C`^{7?nVT2vBgx3D$|mei)*+3S-75I@?s&2>|J z(Xq=>a!%;{<@kHyi=TymwKkjJeP(4_?Jrxn(POzMYMG>2Ac9=>Qu0Lk><(+1O3dj_ z>gdJz-{I|3#Cq z9sEJ@_2j-)-nrsi-9lJP0vTp>1sl`=!~XdcoTRjiu#{rja*fg9{{XZGmvy7s_*YCi z!(ZA(24Gi>cfy>2rH9@CU~)6-ny+Z*Zf=Ce5rcfH*FIzz?msGe6iTZDb&=QGZhx&i zAQiSK#6bT5yxnNqU=kRbNurM*d4Tav1wA5sWOS`fe%#6x> zsTUm?NWt|7pSmm5#3|B@YEpWhZXL#_H97gU0XLS#Wr!>-$GLq zMi5;yx9$Ugb3%f;xZItX>wA+InDIocnZp6d2kA<2yRsT~+}eg!bR)`n7>}25;~uzo0BN$ypzsyy2F_KluL-J|#eUz#3v&vK1yhw)_~ z^!2RXJ*^`RO+KgAQ#qsYuj0m~BSWHi79`$IB$8h+kN6U{(fH!0>llf@b|w275cs4d zjr&RXful#d(==3mfQ2%1=v04Nr3_t7-HGPH!$ht%J`sFK)g@%{U&Sp=;UMmg$wKGY zGZXx%SPGNYq{Q)%hLC}+W&1mLWbGQg_PeN_GAGm-Hy@&f;6KE z;mxCgABC+Y7y-W6%`y7?%zmGRZ5$mK>&j;FRb{6!*;)K9@FkM%hr*gVj?66LQa+q# z^{e(2*V#sHwMM=sUN(LO&?08PIz^kOK6jSmdztr;b}v= zA%BIRAGMbw#QrdkN=G?scAYJ@{{X;A!KiYS*S%1yLLUqXBK?~5_7TtGFCC@Sl7G)R zq`AT8sJHV7=Zq8|N^zqH(Z84ZiPnDH{+YHh}P|Fwo_Q?kX*?GFk9JqR&nhC ziBO6njGT{`0OuL&SA?fZrqS29u@b2bT#mjU3PBXSNhGX3X%a9Im(cX-*EQUzCiOX8 zW|7!i=vq8c#=cWaJ91uk-?05Vb*CCBJ&ARs_B!1rEi%?k&t-2Ss00O0bN)wKa)zGj zB~IGOoDc0UCA{AUwQnlMIGfM5V9}@;9$@Nl4RhloY7Lv=AMcU*hXV`@*MyntmW!xk zx1}&EPWb}_5PfNZkvnecM-&12)B7xcXIlQp-YC`X*?jwd5sV*WEw}#wUZuTkO|?Ep z{j~M#Eo;ZxB3MWs8(UXR!`=S?`qY)}sM4|V{B}2ztW6cWvdO{_KKD4LGw*NsCzi3| z4Flulw}zy$oir~IS=?LRG>F19Xrg%)$;Jr_<}dxUt!X!4a}hnoU?9XSmmb1h5rB)d_efS`$VjM9Mxx+PVnBD zwXHlkXCtH=zrONMA!#2U#O%kgz@+4$9%a23;pP3OhL=T>Tg8oBv56;(Yh|;NGJDiI zi80t;5qM8oR)+Egxtit(nPYpflKE^$814Dylxm=qPn|D*9eA$WP`I#UmgZxuxcr*pyXe zEXY&>FxjrloVMs%NzBZdV(|mhZccr<M47{JjE>Z9?i%dDt{jz( z8JDT~PXvBc-*C5K%5U(@nPK--5skywH7?yonPmmj51rYzjQqrL>F-NKHu{n8y7LML z`IoNV^gdm|U7B{x#o}P{Gb-aP$R60N?bBR3Y+ z$>fGzyQ4AWk=HHTwmbXL&8WFsE6B0ftIsvuQNRWnr8pmnH8YytOt{6p5B4 zk$$-V0n@%~npoGr$v=~Hlc!Jz&@~nQ`rrG8kR zrKR`-!n!z$OI;sDi3SR!8dacfNB6{g&*Ig*a{3ELc4I7ER<3rovtL_4VY9x}A+#p~ zA$cfI`}PQ5)4go4cz9~!j9wgmBBy4^B(p0wCbhKC6_Dx4b9eJ(Hl1c+O#8_%myyp@4k`P2OGPn`gtx4a| z(3*SK^CPo1+Io-qXxO~C&N>H`e6ic4K#t8)=(?KJpWUHKtZBPKA2xGmNVd7Wmh$>( z^*ge;`(~qb*Ah3d+;|-H99Hz{)1<8wWm2r?teJS)yin#ykVJ<8a5oP1q^$NPD^rbq zD@uYdvsu{1Ya6pMNJ5|_^&~DitkhLMheJ!bd_*zZLmWsQnMvuBk_V^Kv{GB5T4R3A zHtp(Db8-UwqaWl{^Zx)UA1#)pyLcv5K_%IWQGzx$?sLaI{VPl9sSD8a@7fv(<@h(^ zX@==m*xJb>Zoow|#=Se`n0+gQFq%}YbF&2-)lSFe9CBmnUJ5;SYH3y%`rf6d==xQw z-0GL}$7^kGA1ySl!Bs%@B!N_w*qgSe=r)`C6ZiwdHZ~XE9{xG$z8{|CF&cK96fi1w zx`}1wh#-TA@sYtJn%Po)Og*cY!j5y{{{X^Y+44^T_@~FQ_>FJ%eK*7}Yo%%TleD)N z7HZM$X)S!Eia^1eEGArY@|+CvROjci*xKi`_)lH%K7pV=hV3qIWzw#s6G^ARr6NMl zkaAPZ!6O5lb`>^zj_T!q8u$yqJ}0r0QMk}V^7&_JlSxH!-y4G*W~16Qpd3%buYe!3 zcf?qsx4ZGjjC?=hm6^lnS{{WKr367+g0dNRoxp-Y=t%=016`D(&mF|ww?5eLkA}2Q z*-OG+IMlDaZ*!`6Hc)5NbonU&d96JTNV7URZLA5B=T(3f9 z8B%=FIt%aE!@<_t4BjBq{x02Iq)fu%#?QkN-A!%>K=H>m@Nw5D2tBJOLTTE@(XAG> zJV#9M{{X>H25PIR!STjxi}>?xK9x6x?_n|q1Ywdwy$^6l^sHw^+RyVeQcq&HiEO+N za{mDFCiul`rL)JCwx7dOgl6lK#JL}ZWT`868S$r#J|lRmPL|Tv3)swZ#>K&i5ZvP; ztC22(z0N)_i(WiUWp(Mb$*y$~Znm55$(t~Pke@bq2C4}|NTD>EvFms1FU2ni+Uhr2 zTzYo3Jl<7^UJ~umPV#{CQ@}XmIIG`LCCYr$A~aGwZZPU_SGXdiqoVMPVs8`pZZ2~7 z@Gt&EQBDiqM9)aJeyv_veWu*Sg~4F|0K6Y`gOGm$GhXcA=L;T0CZRi%O_HDJ>^!L# zC2^7uai40(2VdH!8LLV<8e(a3H7M-%Da9PbqDY?gM7a!(r%PtLP$#iUEE zc!$H<3{5Vv;tLx$jC`?N$~YZxsf_pRD_WJ|Pj*ZxPNvB4?+|{{egv>9W2TFZXH^7+ zj>0mka0JE=vG&3CUq9xVH!SnBTTrobsF(7^bS4BK68hb?NsfnpIx$IV&4x3^if-N>A zi3b}OXaITuJ!_{(-p4)Mw=`Q!dHlF6@)?*YSjI~e(*m=Ulr?Wc(sI%(QahU+A4ikQ z)^&I-Z+bPCGtZoKFra5&_z+R=Sbc3j;io74bvOFEUmHmlEanmw8b^jMZdhj%Ych*y z`hU+T^2h%EDfX$8uTx1i73Hf7QKzcZjpy+^m|@~5EETdmoeBlFZhwQ#Ie*80de7>~ z>pQpR%lgCn2_gt|JwDdw?X4f$Zrow+FC;R`-OgQ!HPucrhLKh|s!nw`ZJPpRb!75f zGMp8WhzIojYgnu7WZkS(xhn*lJe4gk%&3Y^IUUCt=i4<72{nDoQfy7KBFH0zmLmZj zGRKa+f2}`u;O}E9`6h}aB$37#p&;}1&#fHqpww4WpPoI;sJqTO5IUc);ri6yxov4; zlcefjc`L~qww|=4^|BmGC@v&Bl~}POEwE$X6g0Z9L$0Qb%74+;DNv3_=z8(eswyw7 z#QBi1ctb|`nWXF94e>kQe_~x)nP+=BmN_Ewon#Chm4IBw&PPv5;>;|mBz0i!rq7;r z-+-U8=8=0gjX#e3M`Nq3LR4FuxYijJmvXYZT7Xo7IStKtsWz^9O!=8%@F#^eiw#pj zyVj%DG~2YfwYrY(Ci3KsgDVf*VDbU27LMtI)mfigYTqAz2>g5&7JnW79hv+=YY?}# z@g9+>8ylZ5Im2fWo=HD2Bbw+=olP6Di-h6up5fpR348|8ye%GuqWGJ~H<~Oi(plK* z7Zx{y!DJ0=Le}PAh?QxlvD4{#XTjeMN3%rm)}L)}xVpi0;tQM7r`juh z;QlT6(^xuf-QE0%m3jIPwfL*2_&(YjZ-;&l)2$WQW#O<(7&`O&v?bj2<=^nDbmI{z zIc{rsvrGM*Jau8I>wY=5_?vUCeUehFb$d3qv^z<}QTa-tN7FbQp7kz=G;b-TJg+24QO_QC0+Qcpvkv|_bqxO`LbH-o%4p;_ub8FbAy z<4Tt7S;KXy*o|05yt z0?95%Ay^#XbHUFUygjyK_VVi!<=+)LLn+P=GI0k_h0yEsk0pQWZS0*UQrO z;L}p*Cag;u+`^>1sNf&GNA;zBbt&qsi^3>n!?pu}c~;2B)|}r&B#EF#KoZ?X(Z?PC z03$`+tihy9=18jQ6@zsnM|a~bYf;v&ScY|;MusqZ z{EN@#)ueLzYvOlg&l@>>Iv(+${5O(ph0 zT#(6}p5Mxkd94L>i^(JIM2}+y=gc|Bw?4G>W3okSsU#8Q?mv7<+yE!@#Vv)aFm7a( z%A?9zNc*L5J+n#OvXV&6Yk3G(S(QjUU}FdTikBTVDL#f|qD6l-uN-sEF^=Mzje+Vo zM8h+Nau@LD>r-Uiin~P#?ijgjG?~dR<3E_kG}J8agPP}E;j4{)*2!-49VSU`Zf112 zp3Y$$>1uXGHH5uq zwwCtFK`O;@3eOYztD}M$PauLj(YPObcv9oVI>w`6Hj}1V_G;}z(~MXA9pTd_{w9nEHhZw$lb#(NshPUS5P ze-Oe`!k#5^tfe&TpZyfoGG)bTekwFsW;_bud!5JMzp(ATC-GZ=GS`+$590p-<6T%) zsmqGLE{D(`x0^g43N!^r*v+oQayx+x-{W0)sQ&KfE(%wu*OB=kb`Y%Y3m!QFyuPQX znfhh%GA$3o9}m0=kzL2CS!>gMf*CD@J7ImeExiZL&Orp8YN|poq~?rcIZC68=y*Si z{1M}a_)D(peh~2VdXI;+$)jy-Ljuh`nl@P`QTLSxmcf~O9&js@5AR)@Jr9#K*x`2b0m*6^AVl$ zG08aX*BJJ$+7XpC?{3a&(^GnEj=DG^c%mVQ_2(J-3h8aL1dM?%|qsczu3 z>RxG{MBuLAa5BAqyi>BcUix(#9Hs!OEzitzjBtLG?H-~;&c-I#@PHg~u;-7$t41wt zVg6T`%2YBD&m%dgOQB7dqB29uIRm&WNhY@orb6iK%o;t6c?Xbl%{#X2fhA#qXNiVz zRP`L6#-`m0xqr-(H7w8+Pgfjg^5Uk;alNd0w~71}s7DDGP8@bE)`r?ES1sk#xg{0B*3ZQf=A{0*J5hNF2(yDE^CP7k_$pD zV*tG6c1E4@&TymgHJt0ygZH2Lml{*3v_vBBLWPQ*N%aX2J2Ys%(a80gio^LxPqkqx z)hF;r@6glO#t+|@>Q|Fexmic{eU+}7h&i~p0{-BiV9Ft1#T@!IIMJzBSx8?zyqfmyS7^Grb0G`px%;F2mB99{igck*NTV55olRuMBoZXCu?iRt zS@PKWepRAfh`({g;(1(dKooK|;E;cv8VTJk3)c3wnZspQ2PFqn^w;Zeng_E_2Dx?#lzk zTAlV2g^y*|{wDZi_IUVl@R!G0w}vk@TaOjo>M>f2d6pmyE)kTg1INrc72@Nd-DcbD zdbmWrnm;x?PorsGBk@m&e0h0m4wSd@wanLdE>Dt&8&nRPumHmTKHP^!$Io6c@kWL& zS`QCHC)ro!H#2i2$Jf|VvpDlb7@n`%Yf3Z);?LyY#1@RTGw{N!2?106-(-M)hIU{Qy$3B(3 z9jzoLucJP1vHhz4B}S z8~*@l9}#?W@ZO){&1*o@EUm0A#ps&GXC$yzOc33^e$}m9ORFAMXG;$nPU!jP!yX*C z@h6D1JqE(r?{y3Nk#7yG54EO{gSA(KmL~uVa!3`-bUhLG*T-!(Ed#?Jv-gE9^whG7 z&r%{wWK*9oDl?WJ-YmyGD@v>PRypar&9mG;XYbk%{u$`}Wbss99RAg}O*csr+B};h z+HNLBR$um(TyE?~L(;Ir#amsCT2DrNQ}I{9nlF#FPY`@X@Gg;WW20(UEi`&wn}Pk5 z#OKL%A9w-LvGaB7n$}voqL!K-9b@7v-wVjPSBW&Zuk?_4hHQYtxkntS{{T3t+-KCE z0i^NW{{V~abdT9<#dq-dpTr2z&*59Uh~s&}qq$&T_fiB<>^JZuyNJTB4zJps;h&39n#`H{nmTBdpQ4IW9GYW5ol z;D3#G>AN{K*%~TY@#W2kIKWVH-_nv!`UZ<~c;a=DhuRr|##F9$oOU%<>Q0Q&wVk6e zV=c!HLBRJul-HO)BI4Xg&I?;B0CEcSr)w({)Uc8!!roe;1dthjmlUtut0l2xbfpx8 zj5kuC;GX@35p8OaG@j#&859I?N$Z|J3Z%(e7hwtqmY}P3>yUWuMZ1;gOCH^&*}y^a zmdC$yicJF7LdwLY)Bp+*wC0q(0bLQwjEV+ZvOi{f-SgOI&d1 zpKPD;l3}yo<%v(dC54p#0EssL00cLPj2)pL)X%sA?&2x6DQ4BKBR{)+Mpm0|Ir#$; z6niKYr8*Sh@T(Cz)g{!GJiB zg^gX9DF7;-06&MJr>Qqr71ft29g=a3bJzUlhb3!`EA$x1ujT||!G<@lC!c@M^Qn~3 z;})3HDUpjtS|kH^&ToJ0@9HS06RjRsK?TkZO`^VqLnHTQR5IR${-zF@gPP zZ?JNiGn5i~ z@;;PW#i?B89PCylLqAm`2OnR?o6`3L@2T$IF#iCBVd5VPd@=Bs#oZSA<3;etgYR`s zD^t>L0!gLn7c=>uWU!Nok(Cs4!j0T=3i#N$##N;o+g11@*P@(grhXUr+s7L3inR%? z<&>CGLaA>CL}|}q{cDNn^fo=C;ZMQ4FYNF5PCRrrX%PI;to$sDI{|@M~I9ags<6(tq23z<06!(=*4V+D|>2 z=o(#`6;j3CByG)s-x47>^{!lWZyI*%f6Qx3pB;FAz#8X@ygTuq!4lY7=#n<43=l-+ zgl{A}7FkY4?8wlUK8)wJbU}NzGMu?&nT4nR$~weS-B}CE7J!X{_DPjN1PqV6aW72+=) zKD>M_rxuS-i_Me;a2Rv)j05u=90QEvr)|XLW47>j?CIl+EpJ2ChlFk~TF(9lI&=Bf z@>~Ghhz__aFsCdS73)-*TCq2EW7zz4<2!E_>)svHbX!SM(@VCx7jiM)u{(%>k0j)f zV>n}+Yu^f9>5*Ufw^p*#bn98~5kRt$;<#&f zjj&rQFjs6IaHFx!W$~t(bsxK_bCs5e{Jhe2KO1~4@kRcLs@cnDuUI#ceWqOSv!`SJ z(viqv^%XZObG`9Cli|OJdQ{q`krG9y?Ivq1<1N=C{h|8Mz{&lZd^xFUpBlU*+I;uo zXs!nHYOTIB==Ls+9YaA;XLn0~A|PUD$Gqc-zYf<*30@81+5B`qb0q+#kGBl4&L`1_T)( zwmAfM7^NulXvY_APL-ZFRZ{^az!+n}_xG-wEzDi*V!X1TUC_WjUI0Vbel(q}s9D^v zxq!^RknMKH$|WM{*tHQ+XN!$}*&X8xTW%F;4A? zSt2;D(r+=AWL|Om&Iu#7C{gY<-#}s-Xpw`f;Nu(y{{ZXIm9${rV$vy?I4r@F_({fT zTKb`NB`YCiGDo-$~+J}1u(K&|zFoi?57$`W%`c%8USk=?el1P-9WRqga{>tPZ zq5NoC>W2F=q)Qr)ITrvNHdi_N)vGNC)gr^(ZZVa0X35-kmBIEty=kol@e@T1?Ae7k zsOlX@Kar-|>WPYd2T5)BcgCfD_6A1J*QHJ3U8Kyjr$Wrc?N;PuHzV`<(^g}=i~j%- z{x$q2@E?S3VDaIPP}h!;{f}p3q)d-9#$Yjp&maN_ExV(185kcmiH|*by|q2c7xq!P z`AOkT6GJ!B>iV*n^w^ll704{!icc9nrnBE;TM~Rk_@k(JvP)e!Tnj%ASpgNjtXv`> z_8m#4fb@^qpWxP?@q5PxQzZWY*jiCZQYKIu>Oe+IVDJI$>558RuHf1FY4OM7j-jsn zW3-o8mrTCA(-tWFhq_o6M8~NtelGC-y)?R>g=J$N zrE?^b-_0GAN+vBMG7`ISkO>6!CzHvps4Jr?j?8AKsOsXv6Nhn~eX z26B_gsz+UmkPCD5tmkfsxF+{!LGfnx+u{3Z4?TplT54zaGRhEz1Cp!)j4|A&sqfag zsmZo$Wb`xid)q6RZS@;iAd)8e!pRULJupReD5j2kw9HQzL3gOnr%$G6i1IYc6z^kl zEKD%+T0_Y5Fn@=yJXIv4u+*;gGOj!{Ln0kRP=8~6KOgx0P`R3CnMv?_!JZEP0EDZ@ znp@m8{q?c4yn_s2ws(;jWsXMX5t1|4E$LiU)3d(EL?v{OPW_*}X>Z|e1ILyjBuxtN z*IW{os9bL(mV>j{|&Wzww9cUv=Q06y2Ru#d?2=)gjexMkYuWBxMAgobv0E z#~{~M38hiD*_dJ-qhrRQS)GxK63fmBuIuw7h1nYLAyQcE$sGXcSFb@`TTf6`M~K7$kN|;3M$_-dAN_jOyD~QybFS|-Vn|oe5`UFFI*5&~gieJ3Ku9

A=q>PoV`_4Tut;Z*iGZ^?(XhR z2=4B|-Q6`n2rj|hgF|o$?ry=o0|X6?dv1UKJL}HNJj_fz^g64LbnQM;b@u+r%^QND z+Bktx66Y8fNv06law^oH#TofX;Zz2%@0)a1Tz{~t+<);HFK&Z0)&k$M@L(A=)h;(v zLxnr&cgmDhV)mx-7oSv5KOX|xwO&uk(g)gUn3X#7%Ynk5BN?c|P6;h4RpK;Ub=7kO zybWN7<%cbBW<58rt4}(XR#wDGAO8Wa9)@dbPRThMmo7P8sjPpum50KLfR`B3x8z9U z#ZN>%+#i;`X(YsA6?6g$X36y`>VtN_pM7s@8tAFjsE4`SPpUKbv_w%^v|VKfsqW|$ z9kY#*L;3eg!ToQbxBOnNAlgTbqSG9eWdi(9JW7vzMrv5KKO$4qEtGh$-E@`F)fyV% zUc|i}*T1$E#MD5h3>VqNg&i|Cc;p#!F5$WiG{~t(1@HYu-Fgj_BapVc+W@mIq{O&% z)AdPmk1Pjlo*Jv7p3Vns$Yl7}i${p5gNPe^+FUU8xM>M{Uv8f|z_Dj>Dl|lNThIK@ zMt{y-=oX=3KNn~+dRzuy!JlVcRW3g?Ea$oFHQ{$!;M>Y?=uc}VqsR_pf9V(pHRh>2^*NjSV@yF_e_U0jPwx)NjEKdHQ;RaQ!SbMy{|N9i!Uoh z)Y6E`%3^Gfdd^XoaQ)h~*kwy^7n9h3^~K+z2xr(L`szmVeU8tbMu>NN7OD-Xo;q@l z=e0T2&@xSJ(-JS(j__`%Fo(#=EgKNaVNU09{oP-H-*cm&C<&_dT<6I1_;3I_L2AEW zM=$SG@oihSY>w8RI*G;Sx&!UTc>{6OQ(spvA))F|%G~r0&#zv*APrM=B94}IOMcUJ zNT!cgn~(umoxdQc=YsY(YGQN==7Z~6B^{Ab=hb_9%?|Ko9x^N8E9#t*DhxT3J&JO6 zm_(VLa49!!qNyt5c7>JU`}>vGg!x${+?H=keS#H>hzKtW6vkD+Giv{wdM{xS!V|>) z^UAxeu+Go3|JgUHm)KEvWd=UqoM)20TZXDExo?`ZUPv@0J}-6`F|{C?FzK^azeTu4 zwzgSf=R|`F@2xG`&QTec2+W6|?Sbm99;CZk6W<+q>1rno$pK-hfo^O-D4H+sO zp2s;!Q$NDfFOxeovYB!vH6{bxr<#eQ{I$9&-bQ8AtRH4WLPO#0XE_{=?L72)+!y+j z7XwfU6SD5Rn)tLo^o1V7EDq;OA4g0@c#{3e{O?Ns27;6vQw3#V%VLQzX4+fz`0koS zd%DnXBEG4grTW47y)m6;46lD$#o(Iqc!Ul06_iNl+sZXMGLV100$OkNd3|pG{2r>P z>C9b{W?Wmqo5F*Ytw8DCEi~q!G7+6Zr5&-IHNkEz_(|6DJv6y;-r=F~E|v7D+NdDB z1kCFXUCevc2`K-rlc@ozaI@r*Jxu-n-{>88W*Of^VAygKt z6VDx?Kr#l}ygP_fDE`E>)?KZHtKq`Mj`S1=94o4F?`m9X7WxKv3B$Pi(|;%)vUyVm zc8)#jJqmAD!1l6J6eMJohy=gB>xecKnULE<0*$ZchWKNu3B4 zIZctfg5(sFnTCmzIfi0Zswl}~PuW`f6Mh?vT90|^0L>%gC~WZslJ~usZ9~zbs^yN3 z`%f)1y1%HEo)}W%OpIZ5F&b~kY3wpdLG5BQ_9mmw3WW1w9s`3}`Q{olodKFOdE#Jj8_R3-Aft`xRfs3%!ay+{XHOBX&W zS8fSYG(+(k!x|TaThz}O9dD)LJSMUhT@XhVqP^OTNPIkWqSYx`(~EK3lY#nXmR#@Sum3(AJlRbEh-d$5m`z14(pHki1qf2nHK zc&&QTC7-2>daHfsrUxvaX9Wa*3r!&Z^`$v>?Z$B~ZijWbq4jLW;@Muc#*Mu^f`5}R z)6QfdbX$i)N`uMMj*rAC_~eB}yc_IHVc7GLX+H^mIP{TJG* z8K@*)MQ%!gZdu`zuPDX+&=svIMvwn~f}Z@?ny6gyrbBI%Pa|8(_+39jfj{rF32ryf zQ5FaOC9GebGnrgD=#J0J75l6gd$lDL$In!!Pz8dY?w0A3=~iHwj;;+ZMIXkLg8e*D zY{zpyG~Cy!lXOAx!sTaj=ZYR`{rEnmrSH191hep4{@uP730KRQ<+Aq%(6YkhQ9!$P`#evaI6+YnVyqgmhmdN~sT;C263O97I zXcp~yo9%=wE9Tl8!8-{`uo$|X!+>|=NlDfZH7BZMGt5dFi6ljzA1JrhVb))1Sid*S zSCfX{RhBGgG&IqlpmwiF!q4K~65ZbwD~RC_*tAj-_`0h~B373Qje1CwE2pkGyyWOU zP&lw!OG^7fjRKHWjOsska>~fjb8`xfUiSQA@WS}u*1+)B12^w>kJ#P>>Cz}#K3&Ua zm#bs$wpzuPs$#~{gR_o?dM{|5tZAc*cuAVg#Ri(yF`PUsVh{<256#y$t5q($q{U4-QWZ6o;4UZgpt{HHT9iEN912u;2HsJ1v?cL+lsDM z_Y8J2-9lC$&7+QsX~7Ld#WJwDO>`v@CKQ@@p19~W;7$bn*K zw(&Pos;5DC28q{|-}gi3@YK&grYA*8IMy+T;+z^f?_|amKFVC^ihW=V-*v^U>k{I6 zgBB58!jdrzAvcH(_Fe&N^vkU8awCOyvAF8He&_|Q$NA+*y-VLaG~Z1+PZ6|aE)iCt zlER{)rG7YrIlTq%G$s`4Dw;dzjk+A}uI-N1;wyj%VXRp>jXXUL?s*&sBf9{ES6mFe zD~@4~4USI`iJ{GI6(!Z42>eX-W(95KK|YXM2nrl19bgtFtDW}Kft|D|aBY%Dv-?lb zr(XOH=Wgd&k%MOK-4C4$!9fgE>W1(We-LZ#Q48&&`yy#k`X=^n%g?1Zs0aq8pJ3=& zMbMXjW_&(w0{O{W3%;;MJ_Du8f0O>H-NEf(?SEWj6bn;cD~XVJ=LN`tpeXWQj-t>$4nVHUYryvE0#Bc#K zMBwYC4aB(VAHc3mW0bP}K=5D#IqK68Eb*Yr|i_4I++Cm}HNn0=6RjoKeyQk;9y)NXh z&S$ov3BoNs5Q&GNDCAQ#kzhr=|J^Q+W|OG(@9a2yt2qh|wR)CPlTE6QTiLq&X=*77 z1R^+p*!Of_suAM&%8*AXME?ypcSC9pE4u;OK!yB?aU$eSw7cq#I**widYRCs_ALod z7oL<8m9dX%{NJ&ou;01*`Dpy+!}@W;rJ|04(5qCDyE zQN3g)naSs`o5coobZI_+R#Q^ut>*76d!x$-c{Q4=WYkB#ZjKY4n8YgCSS)d8*tI#` z07Pz<2uWYum^#}SaNF6X;a>$sO1IRerCw!}obXZ+S|T+2TWI{pnf+hY6me1m;nMV+ z5-g%Lw70y(U@qni%LUdl$zwdmOQ=Kr@HQC@+@#3AF;%qC4b)A+<1&v%iUo5 z&Fw!e1iFX?;N*T(?@axWupm!a;LuPXcHa!w5^diO?3{;k%W)M;g$;~=KeBB zg>1!^y0!O)z{}t~R@Opp-QhMv!y0Luah%w}a9zyFL|fKmZ)J_F`k`SaWvOs5wVUL8 zirj{31v73YAy)VBwa~j$rxozRMQ16w>>+FCK))y$QnD@e z!{W~ucN@=mF3WfdhmL0chQ>pkJPdy4x&p+#Jf9h@IKwo8ZLAg)9DEyNTTyam!`^cG zzZSX1w5qgTBx6Kc0}sV5ZOp4%j}7+)^DaShsD^DB6=;gP4<0=fG&5M^8^a!QO$`EM z3NxNE4!(OwRlT~m;%I3@0mB&a{GprhJxR8-0YT$mTP{4f!imF|s54o}X4trghTXHl z@~`8U0KG&>|KoVe-K&aHhVsbYDYxwrEhtO2j&Ef_XX%7CnSXMbE`REVL8x=QL$?*jQ&{qs^1W5J0 z_VUmDK!w(#Qn>{iYNJ5;JWL{aqV3z#^)VxA6WQn_v=ahmX`^cSvOK)^mUP5Rz1EDO zqN~I#qg<=q#4_F3NLIPFl(rqxM!S!)BtGU3N~jdGHEX9Fb}N-s?)$-_DwL@koM486 z$Ux0>x*xnc}gpV(hGF}NJ5e&TBY5yoHjk)GBkhyXS3-dy^3&cY_m*0XG60*+N}q? z5r_Il_-I;bG`6=*&g*adgc6xOg{Lk^@kQ~@ZNA0DKkI8do9Z=+pJpg0TD>eGR$jqf zS4BpJi*vo^uO1OHeeMpTDdA&=XW}Yqi)8&6Y zM;$Ky4a36!>z0{mQ{&!eC7zbS!5%ap zyDAfBq+E13=a`RGV;$~BPCP!GBQLmH%+1K) zc9=c4C1ndM@odUus{!T3g6CZ8>@G?_7+&fo?)bxM!hwWX zW4Yagy(|ABP2iV?8=76y5RUhgNs4z|s9z%0SA28Q#nut};2C}@#$`~)Yw2=t7t3;j zx1BOM%5x334P`ut4V+XntN4n>>*^Dh3QU$k#zL6cS7K@ys!HluGP$ZR!H36pl|C$N zV?f^{k51VsY*h>~CX*>yKIh4Om>Ri=fsP62^RS?0XRx>aC^h}#2B`=90avP+---H8 zl;Jf^29mWl5fJy%q7>ovT7pOA9(z?2$s%>tV=%U8e?TKbmK)(r%V$ZxEOj|_gPj`q zOD`|JowQ(RsZKm6`aI~GwXu4(xZRt~A0a+OyjAyH=5MF1T6+t3Q~DOy?+nYtf^?N_ z7na_b72Rg}NEViMT9=T~^7bFZZRZVqWjwy>lCw}{j>7k!ngk{WhwqGwwd{ua)?rF6 zQ#S$cCL?@gWJB4NR(`E>VQi79(`M}%>;6w)T-ILCgv|GziAQ_dl*c5{U&R6jwH&d> zzvh?ih0t8rmPdW|mH(xeGe5udN>n7nn83!b+Ue9tI3@~uMAj%K`81TSyHcs)T%^C* zlwuB4m_7VWG1wZ9OEzu1)xv8PJ^9g^ZYq%*fl=gmr|M-|gT~Hz^-bGM;6=ItO2(No zXLoVTsH+QFIBJIfr02iqzELd0P_&h6nA^8rTpBNbYVN(4vUzq=c&PH>c~kx9$2DVH zI&n~E3>+bX3)f2BqLP(O#q*DEZCb;_MzZ-x+*l92>4gj)m$vdt)ED1?dDrL)V$7X- zAG%Is$WQm@Yvna%e#`4ozA>!@5Vh;xm{bvcF1j8rKto459ZyQCeJ5E%je#%To4_H|PvJvL*Mhp!dq|@7E<9&QiwSVw9 zzjF%DpFE|{dC7Ugy6^we!O2U98h4NIrqXTIreKq@j)4%$v6};N>y7mLlbkZK_HN10 zY$ql!_4sZHo!EYlo(p@?dK)^LOl+Dz$PZJsrz1+WhEG&0tQnnZSh{Jf`TLLZAH#;= zKDi9^4qp*|#<#~KjBgk9hR*DN$-V&}*toZPgQ9M*q6I}lnadfPsV8vYI<>c%Hj2VK z0)WrA)oTemrE4lA#c@84x-ds|dBRaF%nFvW5 zl0?L@6WJK*)^3*a^ktSKQQKKTacWmCjg2-hHw1kMb$L74pf(jBQfJsvIv7vo*CQmxtADKH)R5QFoSS`S=2Y^& zc+xoE@}l6jwECeGQy@g^o{A16d_CQ;VwfDKZEBs0kz2 z-dcgj?ufLmA(8_sNeUC4XC7$jM2Af0lA(0XQ-w6N2UDa9oYs%~cRrVeDCtmfHUSX} zPb7lh|KiQzU=ugdLQB>`6XI4{gONcjV@w2= zoIZ;sd-{*4$<^TrTUQcebq*Vb%{c;g1xoPh7bRI>5q=U+Tmb|E3CzA1E=$}QGCT%PB*F5M*|{X79$+9+3i#=APzR|@oErB$hn z=NDNFj%?ARNd?Tx{<3;LDDSRAF+?;=#7{7gwk;rZV|H2jtW?d+bK&__9qUzMU)sk< z$}#Ch`$c11Pe5{xPYT8R?5rC(XDZ*bCgrfi&* z6i;_hD`ux7vwasgeY>kJF;1)=dKaU54wY7Lkz%NP8GF)&T3b$vP(qp1#^Rr!m&Kyn zxhqdY_avTy)m9QQyPw~bg3&1KI$lwZ?6*S4s^5&Bb>w{1EcwrBccovWlpbZ@X+0-i zP1PXPra%e1*2;f?Dhg?(qIFq{$H$eB!WTNL2iZBxfYo==v^VhU_e@R8Cg!)N&@GAC zNXGb%m(0S;P{r~t0!zDGPzo%0z3@>M!Fh$aJ?If7jZHZz_^tgE!mwWmAtob5sicHuC`OC5YWvejB_KNo{tB)rRH~a&z z^|oeyv}c=U>bv(;E6O-Slo+y-o4~D}ZBO zlSuV%-^=m=JyaO%SJK0mYd$e7H6N!jsM0h9>Z!*3oZT0dH!K0UL3r6+Osx3wZygQU z+QrJ#%fs5-84bGRYTY?RkZfVW& z(b~t}(pppQ1BaHkg_pmZHHU(;xvjOh`2W=f~^2EhEE z1_Hr=VBuk5K_FNJICxliBt#@6Bt%3+WE6B%WMnjCL_}0fR5Wx93``6pR4i;P3~cB! z#(xI^f}s0A_kx8*z(7VshJO41vHj}@U?BpYfyp2s761kd2*LvX8wOB7`v?d8pY~sW z|7$>K7vbO$5Rs5kpc}Me0$`xO4Fd~;gM)>It__B+2f$*%VN-EQ!Q*I{BT&2Ja)+lB zBhq|m8o<+BxT58;@Q6S{#wQ>oBBrBfU}R$E<>MC+6cU#HC?hK;ub`->q%CA08e5IXQ(~-`w8aKRiA?{}&e!0Q%oyK|lW=Ps_Vc z2l+3w|B3AXU0@OazaslTf&JfcZ2(X~KVF4rnFL@jRfGjWYbs6YB2M}L1UI9{s zPNQH5wQefisH|zq31H}FKs1yOxBy^UtUOW9X=t1IL%Zu6qUI?X2KnP}@m2RLOX*LB zP$7tCulRy0mo($T6}Zaf?{~H>r)-DoCIapxq0C4`P6Z})J)zq&6y*SUSvz2NK&-ht zf5Dp_O0*apDm&pAZkVw;OyV*yvp#g3`R0$rEtTeILRiZ!=2Z&-xRQ(xYIgv91BJ^Y z0d6Z`i^!QJ({TIK;Uy2k=rl&?VH6S)UI)Z^5nAi}8=D%;OMp_pw_In@DnJZp-(hbjr0 zQ8fNh7OTjGfbtz*(I(4G4;5{u^{g*zh zmwW=0F+)3Fer3WD_4ivNGq;G<6q_brCV)JAioF1W+ zEdD_iaCR!9VMFk-Zv&rXI>ZtI^XWIHph|c1>S7$%HkyjGN_y>};<_e>VgQ~e6O}duGD5r}S&1}l$(0qq!O)}z0kyC)IL(>ks1U3; z;PyV3g&Lfr8oc^yzs7E%TCw?QsjggCFJr?-vfl%*bdKh2fAyKzM6MIuD~#|?u-k7< zlhpVa{$+Ktm0~5aoGtr2pgIlKA%I9d6uiu>WJQ_-Feh&T65#@h)Pb+xf$lQ^K%hD( ztgL@}72d16;Su9Kk_kE$;_EN^0JQ=pX9TX5fqpUqPcaa1fs926v66}{Vc*nYaq{+j zd4YIe{&ILLys(rZ2d6_buk-oUx_dK?0iMd}a)W4@5KHps;eUXVqW5oIU-J{)7qeUh ze18I{Tm#@`XP(qyot6Q)Np&!2JGZEQE^cT5)dWfG>3wGxqeXs+azGHnen&H+<#yJ4 zMaD$}&(b+f|0kx;0zI|g#ZDW{)@o?|7!nylXLV{r>JAwmYg*Ov*h3&nATKc$dQ(D8hI<^we~2?hVGRWY`gHXi3{iZz@f_78sSdhaev_y&kd(A2;_4t0elHzC+ zs9K#Ji}8G3I2*0N!;Z#D&60PN9%i$p4*V<$j|L#*1pp;6K)Arnx}?Vp<6y0SfDd?L zK;k`hP=6WMG9vWm#0654{eh7bPFxOyE;Eub0&m0WL;S&}LG!SNLi8vVVwd$23i_dn z-%vN;Yl`aK-_a!)zUHnPbiWZ|oM=Y-h;-{9B{1wH56?l}YO|YnW8r1hs)|0i+>QVM zv4CW9JFGwI6A4ve;imW<5uGP>3>!r zzGPU>?T5>To2R^fYEHpQY&ENOPv@4qe!edmYP^AbnrOuN)VQ7J0f`Mj{PwEUE^)(c zZ~MM6^3H2FWd7wqrE~68+tBpwE$-EB-V$Tj2s%XYz-NSB)P{m(BcK+#Fl#q&-4&$I zN)(R^MYIC%I5p5MxPC(C#hXxS?Pvnv*yS=)d$pzJE=Ne`AP*rXqB7$Y|WESK`Q zNpaQN3uhHHqy_;ZEIs&q!*8=~cR(j5g!jKmds?*0*b2~s!S0y{A%jmo%)=Ie$QS`d zpp`IOWJ#Mdns>UTxBoe9tahs~Sy3aDWbyN`vDv4LL@ZD0qt@9gf~z$`$OvG`s8}Va zwC?g8Y2hWO10Z*5guRG;QaJ3QOcNlg4(BJy(;R>du*oQ2as)i|HfYALsWz~1swISfWaA|g>|xn;kEq+MMM$v9!13oKMFF6Xph%d6@-cOKJqa-vRmOT)EWaFy0?YVoATj$&c;_hvqIaDv zo3|IyWUe4M)rveajJr4NfxPr4BRVm2^auXq-4$)p(-j2p4=}FV(v{I>+v>p4%9ivd z5FgT#O+P9HlZ8gZ3mELJh=c*otHZ#Zok+rqF#?5cW0m1xl8H9@XA1>hCZJK7{Pb zi})z5LiT31E0SBuRcwW`rd9lYp!@UnUo$mEG<(GLPY2vV0$`4|lN{e+kvbCj1=~dq z+a%4_#X9_Tvsj+CeQUuj#gC)L*pggHBNOeV=AI{Yp~KGv(Y))eb-o%AQ?fB76Tu?R zv0~?VN&+$@S!iS71uAB(Yu0EYW8^q1UKb4d3w*gyn~G%@nKFScuPV_G(%sS4f~57k z#>q@&hhAMs-7emv!qQaUP`mf5coB72-7h%1GV9i0h>q)#%7^XG^YeHXo#TFtP$)*X zuIpci)nllKJb5|l*^M?eKW~^h11@TOVF19~ffdGTq4Bf(>vzJdWgvHf9Y|!@!};o{ zXD34|^bdR_!ptYK7!=3Q2O0VGKRz}6)vyjl_eDr#K++}9kk+7~4Ulbkkc#^r5$aoX2Mb^N32Omk05`NZrYXJ&*zv5H#`mscQZ00y5l22p%f=t zyec=1-wP_eh1v%2UCqQ`BU+o!%|rpTehzz!!_7ONzsjMFdo0G3X{5}P+CCvG`;b5o zNz~%|nzvuvNi&IOpu<?`sEH_z1iJvn3R? zD!}FzvKc)Sz#hb$Yra@9dc4%s zp$)UtNFKKBMd$PrePdA!*84!8Ye+>0%dNop=Y)~U6$llU=K`8_byZZ1ykKq6rm zi_a8vDzK6h_$gQaV#VHqd$x=KM~-DOb% zllZv=8PUZ@w&jz`O=ek<)f~rwA7~Qe?P8AtQn%YARPVN_U(~M@{gf_#Y?S#xMsQb> z4tvD)$qi7&_!~Z<3(a7~Yjv!AejNJQ)%D@Co z9M#HbE7oFu0WrXm#x9J$VD8EWb6vIHS9d>tE|vD(KQoaq_M=Z_>9((QR66t0iu7q; z8~MRWVgt4Eb06{S(C;pkwIdhqUNIfYgnG<+*liq4vbplUbXqb0DUbc3fQ>cSAw>0= z9rhgOjrsDTT& zrnCrk#rKa+W%uQQsOAWZai6KoB~dAlve0G#L}kS2T9P7gC0W7*6+7o7IIfjK&krh1Is2z-# z&_Ngj%9tX+Wk?boD^*1EXP6egJzxkwK*K%m5NjihyA{glkxVOSfL^w(tirieLe*Gg z7cF}H0?BGLW2jBSBBO^y+7U>o!lb^%E(n>ArlxVjhAMRz!)3~`RJI-DMna#Em;kq`yHOuORP%zdY#rL`X@%WNa0W7 zeGlr(4$hZ;Wov2bsaYO!M8Bg!@K&lCUKwnD8pWZkbhb9LT1N1t_@aE>^hNw`X_3;9 zP4lDvH%XQy8~IO_q*gvxg!M;>{t%q2(SmE$ww#J=;_a>d@(k%foGBJkx4+r?DT&5l zm}b?BMls#R?FUTlbn#XJn1XVGO#U=V3eN8JLW`uarOHEvrc&+EA-<0V)>qM&CQ1XG zpA@^T(lnNTh-Wr8+!ojH^DGCY#RAM@p4DNUkTtb{F9Gt`K9E};;#f&+-vh7Ez11yOMqZ^tB=^zoXWG3j7%*w%Lx4FT=1$6ir|O0+X6Y7z0AY1l9D5p zA=qBs=|AScsD^qoTo<89Y=|g!E{7ln$vSeq=T@$f>B0zqWg~OZP6`^5((tjnQ$pzw zl`7Id&B)t0<+pdon)UcWY5t5Q#b%IkE|oF54w;a8I*4k-Pvu4|LQ%|yUY}~rVO)G# zzPvaaC+#*Hd-1_l+FbE3pn;Npw?(@GR)3VxLEljF&`6_xx%bb;cZ`8@AvQnJiglz6 zM!0!O{KhFV#~v8SawchBn+)D``r0{q`dle~f9whp=OdUO6_w4@P3hoKU@Oubda3y` zb|7_Tv{Z3YBM_=ZoTlZgIObjbdXH-0wqs@bO#F*mql@TN`Bg;u1vmxVpC+i@z~8P=_-7AP&3YtQp$;=(Fg*zf_OuluAvbiHR8@l^1+8 zrYK~hqWVWSsX5XT&+E>$>dGVNBjln*(dE^?x&j?VYzay+p>L{^!%{OCY0wTJHD8d|1wL6^!Dh7d!bgf`sA{4NpWb(sC^-h zI9)bsW{B8|ChMWpayg7@fTb@@t8h!{f-&Srm1dQYs2sDxlS4>k5ZhxEM0%i$KD%af z#+@M6_15SsZ{LOBwQH&Kj&Zkf5>KW|y+;pv5tiX%F(1mLu&L+F?0X%lac>$UCLijP$B>GHwb(?KxW9L-#yI|5;y!v_tIN;;b) zD&9LI3Iq0bi0^2#zFM_i2=;uBm}T(&l-bSJ&i3{>DvbfmlU-a#%_VHAIx4`^_>TI? z@N@GmJ37;j;-A|<6{WEVwvitGu}&^y_E5-;@npI$G*tsC-B5p*d&nkk|0-%=#>W2l z_6^?MVa|st+A;Fx0~0K^HdthoYnQCL7Z1G7qCisO-Q4t-5<-HEPYMtQkR zrOB2ots^vD{82JKyfX}n^21y9Y|el5MKA zviwSFzjp#dO+2d)VSdhCm_yoNIXDL26fjX+QuURKL$MhT&64K(;7>R1+xNHWp|d_i zmA1lAz7}@#_HM_B;Ud~LOO-DSmkDd{kXrTGl+tP#36700Ot}krgqS2~9*>5ml>n3t zDcan3w%p;A;Kv0Xb}8#8N~o8lf@;Iv5O7CLr7k3~%{0u(6)7oEWB(ALCX-sZj|B)| zX&b^QIn({LgK>A^4EeMSBx)O=MNWxjiw2JUx|~DEE^76o&90R|-nP z@o&51wuvuX&p(FR=`f4V%O7u~!Ho8SIdD#e#cN7;H}ofLgI(!rix_qiWtg|{$-Y)C z*O1Fyu^jx38yj?mvtQhV`X#40zNIjwh@0Klt{nT$3cbxsB+za$D`|C`CXll%-6@eF z+OH@#57C~{$OdvgdG=9^C|=m9Bs4r4?XXhZpf~;l^kP6kSE}c%jE`dnBmV$dE(LNg zl~DG3r4JINYy1uiv-XJ(nQ)ZrJA1{sF0(WwZ8$0AEu}Iq07?&p&QC3yXo5^3NXBIN z!_Ps`?BvK&Hwxb7!TZl~VYHSKA(cqXeJN_VO<3(-Y**;!T?XERFz&vvbkMVm2;)I+5cOLKH7nAv3@e+@K2 zeil@Jze2?p19$*OXn|v?J8LyL&3N0I{G!e?q=XYoaobN})hH z{`)>P=_H(JzsS@y-SZH4$AIaLO=|9Q{pgFZECe({&c+}YADuXpq zB6`yblE-C{&#UC@wOq{krmc=jhb5uBCX9-t3xN#9w@ESLTu`QU`_-ev>wonfMue7S2kdN#Bohka+ zv&v3lV_3#>)NK=r(ZXpOsMUz!Qb_j})>C(LXVC7P>hWcNsw4GaWk-SSH<5v54t1?q z;%TCrMrZy3Mm#ZoYsv0O1XHPF6jEnd9Owx4)>TSHUdYMozK=AB#1&N|*XW!%>M1B~ zK6F)4QN`Z;daLyx0OfE0t4sT`+S~NWsKlITcF%=R{1{i zUJ7sSoun75!dDa0)j#-D-EYOc#QH`GzMkG8R8kpS8`+4jxM^~H&v3P#rdO+lfCZbt zKEgOE!l~e1{C0`3Als{wzm59md=xS7xR9i1D8)3==hE?eLusNsy}mwejAEnNHm4kQ zYW{Y_2n*sb4Z%Om$z-UMVNBuPGQbYVPF4~(%9!h9JK?Iadn~|WY)o0h9eHAtbg=^~ zW{xz37d14)?;srIFb^4?+yERdiHKS7xtt|N3#)>wz~EA_4Bq6eJ*Sk0H;Y2_Risq~ zXG{X`6^9cUz9{Dnnh727%MLDGuuU|7j7_Xa($4-Pyi-W37eM!ox3{D5rW`x6D5F7LG`yQShzbeyOA% zo=b6$`ecC}ej&+00qE|Wu4hN;TZDin&h6QrBbm*(l-5zQXB?-d8i`TP@ZBMVG{_#p z)>Z@I8N)<_^NL~PuxZElWxb&Ca*oUcMyzcohPkIL-^w{+5AClG_Qi-Z6o_m~3 z^9kk!pv*qD8*PbQ9PHZAYt(X{dv z`Lrn!uYX%GYYL`rxCGC}%1OEt@5Ml>^Q$WD`X!=KDCv6uVSotoFBZ5#D2P0Kjyp`i%FB1RVMx}#k=d@m~7{KFDYNWz<~U$h0SS?^*XDn zNUr^)o94h-npU{|(r~6->05NDlH>Gv*npx(%~>vZLOafU$C*Yfq#Aa^8%&E$`*S<%S^I8Jt>D>Nx|Kd z$8>F6fV8cP&A9+s4>19y_OGrb+~@%uE7c+~XB%tbdAi+y*jibBR?R8e!%Y_csql1Q zr+!ft@Ry1{4*=J(giEY@ZpLDxe7zU%QKw3I`<+N7w|4-A9J(i zT^G&w?Kpe{AS%1_t>2Up+5_ObmizUBIUCdy5?!L@90t-LI#J9t`kSuZl&AQk(g_x;dI#@4_igtyw?6MgI;p zOfO1M`w^%E{~JL?nlTr_jSyU10Fk^lDW_fZZ6Xw@GK&si8hyaF5-(DSTpxD$mdCPcqX7(%T zm>}2U-Xj-#S!gSjU=?N9pK*n1=&Ze}KxyXQY(rg<$sHdz6FSAqa2{9i^0ycH%j!yn zOfd|}G$%NGqrckZ(5h_4GRx~N_3}KrEG7U+`oKiv835(_Bge-wgio4XsrAB zYA#!7W4K_(=iyIPCyQMTzvHX*FH8kt;dw{E+Ai0`_Oss(yGe1#)$jOi#O58@Drb9v>= zu|9?3AcjX#R4mj>R_;&7;S1n|Wz0x6oY`6*O+CSD-6S;|q&I3r|o|2{!6ZwltSangZdFamLRR7tPzv5WBTJPod z*E4z5m2dyEO>Ui?UI^Wl%I+6etJKrWU4u5=_U=>>Bf0z%4ndDIc9>?IF*<2X{2t|8 z{>m)o)F>T30$ZE>!trNut}htN=@{pX9W~;PRdV%(*m~jzZJh!(coFk|zrlb6+82Ko z1hWUxwf>M078iUhe-(gKt6}&>?+#--ZluJ$FkRf)JJ(&9b3{@LZuz2OkR$~_YWACh zbd2`TpzcF#KJNjAfng(V1sDjbg43d>D-PH8Eom2BLJiTOxK@wd5T2n=$TvOG_;q&5 z>J!dYGtSs!z#F6Kji;=AlD`qELVW4Q^u7u;7S!NiSG;%m4TCT6E9Jb6p7H1BPx%c? z7ZepdN-muMaWVH#7v~`X5AzjusDBTOsG3qzv~$eOe;87zGDXFD7-EeIm8_x=rEdJb z5-LJY9n6^DGMOHr3=f(hg_aK*Xx~3XhV@-hPa3&KlcT0uaZUN!v{&#zfp)J4)|-$1 zS+7ieUt=EZEcZN>Wqw18xo(0dIk2J>4wizLeY0(tSo5g1JE=gr=ukcrt6|IPl`v1W z@{vGaQO_}+p(9t3LmTDKDFb4Hq=8!No;ZEdDtz`*$-Ky$9^!f+!n@xKMN?;?E^JmE zJvoHbI_!sKgb9)ptZE?Aql9RW0JQ{BP@Tz`eaR#ELvMFV^i-h8qqUD%M0Jx`5@<2$ zqZ+rXXWMlJ0q|F!Z(?+%60S@p+go%N>HgiH+m@bT)Vt@p9^*L5&vB}p7vDrdh@ijsfkht z&&~9QOEgESu|Um<+^!Lk@(-gO==^u$H$b5+Z{sWhI;V5rYI3&pcVKqX=Q7$SxtAKEN+-Pnj9iX{#Q=;2+sL;?=&cx?hQ|EbTlObYhQD{{Tx_UgFj{l5ZtdbIEAalYjvH zE1@)<%pR!vHGgMG?mjPTJ}T62Z6x@8IK8}wNKM{hzPy4vdD)j6cI-wV^_Lo=aa%CMG2!RiR;K*m*TI#8WNx2)cc#_j-M5`g8W^mS=rfIHkuGy%@hhG!3&VC22|vZ zc;df7cv=*x%h|z3{gOw48P0NC&9n2*#Qq@hCZh^kN#Y$%>{&ditj*K;QX?{qux0jMRoK)(l$=P>39^=5D4!#2Tk4N~YrhH)1{A+m@q^xvZ1IiKvZOrV< zWh5>E1CFF-zIP(xJi|V(EIuzTo*p*8G`79gnFslyVtX4==15A7$~ZMqKw6R$&jPO9L{X9hj+Cr3I!FmUDYOTl{8Ex@ zKZd?JdvmtxeKvbo5B)Wje5A*|=@y(f1Km73VHTgJ*jPY;V77%JMFZ}tr~~vBC`{|4 z7y_6UR8STr6aemhsi7P_Y%(bbPz@j_FUihvnz0zxTaxzu4X(s@E$06Kdahpz)R?_l zY+vEzR)Lpkz&nB6Q)OY1YF5Wu(lt#j7)SQYX)Vj}+c&9P<2>U%D7E^G`7^;kvV`6U z@mGXAQ$LQQxraizY0NLDd16387~E!HoqB;=Q=BQ&a7$OdyO~N3bvfJ9(_`%j_Q;Cp z%E;XrPC*}9=QT3J?kCeVBP7Ac6bLbaKndGD>2v`yPktyF;$IuB=hAe~4tz}0VRK| zJ7BiSdG1@X#S-P*`zSRoNoX||_Bb^7k>ky0_ns2?F|AEte(mRo?;z3xdx%)H*!rNM zT&`5NW5>iFAL%=#@n^x^PCEtr*M1zogH_q}glv@m0KieG_l0P^nJ4@&kA*vINBkv` zeXiD;_D80qX(YQV+_)UN!9}yA$&xUnV{{Xi2R${or z@jt?u{{T_q5&rjvwL$#t=(7S?z9#r(iP>r5NB;nG!uqlPR`e*ofw}q7@oUEa0JKo? zw~FsPJ*fER-@_MobDc5^J8PH+*_4F@MYJ+t5uM5oPdu9F`n>jVe{k(6wECV;WAPvM zp%;m39=-7my!jOmpZ2T_@G@LsM?RobIx3pGi04vOTIM~6_H*%Gi{P(|8b^ryNvI{3 zmkrt7Jb<^&w2WbLbCNrE9<{?>oaY-TvuZDrS7)1e&hqnI@pO0o0=h}OO1C#RmJb`E zvdb9r6pi>BvY>!^o;ji^!8bKziIiO5ySdC-e0Tk$?QWk^xbY8(KePl(Z!D5o235h% z-K92zka+_=YpOJ0-!em%DyyWh?fZ$|+HQLNolT zmI!A!D23C@!!RcRxXB=Kox>Xc0J~R;*SA|6<=9$y%D&2^`EH$`PHu_%pLuGZ8TCH} z>NdU|)^xic6zVg;w-MR+Mk&_%SdIvBX5rK>4oNp1J5@$el1@ELUJ|S>=B%RZ-%IxO zJ}LO)`#}EGaCpY|{t=%B>)sylZ1$h%ws#t0&fZasqs`|kmE0S7;f}(%>J40D%@xj! z>#9+kRAk(HwQs{y$o~Ll4-jhaeq+}z<~nhm%$K)sxqQ}=6; zBz-P8^hyC)6L{*bu&!H?+2&1)1Rzhat z4hKpAoqm)6{yiuGc*QU{ira8FZ;1XRyYP>Kyhq|o4LVEf`x|GH3rM4B4AS&LwRt0P z8OLnV=p(j?WtD?5O@wj*6<0yAn+2`JTAjnSq<%|hWXcZj#{{ZVy0%JK82w=$Ly#pI@ZEt&Rac6Z3OKm)D6p_d>uB-?kj^KhtEyDIZbKx!3 z$AvESAA_3Y%-5O-^K@I8j!vPZvwrA<-QoWLRKvE_Jq;wR>|Fij&W~-4e2cjvKkDcC z*ZuC}`qgsS&gI>m#TE;oDijiM0Ob2ou+uyvQuu@7A06sfo)`Ex_IHBXLk6YeYq@(w^kML4Umo5%KH{hiOn{{R+gFh$}7@kOSeE$c-VxvDIS z41yN(4bPdDEh|h)nF;44V+OmNVv>`Io%$o(yer|ahkAF0GeRn{D)T=xO^gZXD4yuKMY9>FrN+uF|lJR=<^4D{{S<2S^Tk8?WcCd%B^FcYu^c( zeAm)$@&*(~VKiHP#@I#;OsdLTq$L|{#Gh60ys?<%gIOz{fo5OR$*JajgOtI$PXb-T zb8mGHxX|1#$xyoh;~3{Qr+D)tKxAMz% zEC}JkyZLLlZ|a|PXT3`Wb6ayuT>noo2z z+S!@${3ZBpH;DBe0c~xJwswtl@Wpo^od@prmr(pGZg36<-Q&G3NZR%vG`pOJrSOA5 zytlP|6{OQ{w=AY)xSff>I8qDXu1;`!fn1ehq^%T@wJM&?-QAo-{{R5BNh3D)ej&Dj zNW)x7_NirWekDcE;77G`#|+cIG1Dw+mX;>)ufabO=(^;W8t0F$E_4`7ZyXTi8e%yr z#fd7pYf~Vr_ek>Igu@An6giBd22^zKP-$g z&`3{EVPmw%x2Yv0a<{F|pfn9`!^HYkp1Y$;WwMlH7E-Mn0z)II%pUOo?r0{d78Jvs~`FJ@iat_Q5~h!-_9XRqZ2*$&l^&Z zjdY|0!12_6GywdcS^!>YusDpIAxse-3`kG=qJSZi!qQK@YY{%X1p_L7W?2LO03K0i{<(?((24;X zfD`~a0mcOZVnD5uM@j%u9y?G5o|&QQy2Or}eVfXu_nZtW{Y@5Z8?mz|gLN2&Cv;cz zT$-*@d5UxRa{AgCCJE+*87iN6k6}c;$hkg+(TBIG8fm24wz?zC{7>Oe5BTcR$o~Ln z%Vn+DIh#(_EF4F3V<{LV2^^{D$iS-(qku;q8!^FSm8jHD%KDzBHzLh4r+iHbCEnLx zdeGz_#Gev;B#UL^e+S%nhQcHJuM&7dA2vqELp6y$Vz;lBU41<(yOsK$L*#vI{L4%6 zyTfl0ir2%QFTK?I3oCC9UaPZu67j01)tCY6Qrqk`4(%DU_*>!^#bdL_Xx101)8 zY%YYC`kMa$cJk&kwkXedq9l-TTy&}SZcg$oRE0HY>ieF{VW#OG9@A|!tt!gi$4j(~ zMFpj-Vl;_IMO7RD^s41C=5JOb!7c9-10AXV0G55<>*@5T$#CYeX<=B@A}CcI031=u zJCH}K_t*B-+F-1&@TMjD78zRnH&!Gt#-CnMP9OdKT$4u5;3SY4N*& zA4Kq(`f0ZV{{U_cbvo^lW6V5%`%m6@7U#pWc+XAIG|vlPywFdqSy(trX@aSZWiHYM zR~}{$9H<%Qu&*l9h3M|T6jXUr_lmk#?IG~@UthOrelOE+pbjH4TF8!y=c2aJg(u$? z=1Qh1JIOO&ajg$!yz!Q=27&gS6T`YLr>#eZYg_U5e>H!LYa*YV4B!!hc-%VIWgKH_ z(leB8vFDyI`0J?nI@?RW)I0&8$z^kW6`b>lo;9;q&Sj98&J}j^(z=yfg*tAdvNQfE ze$ev#Eckt{{6W+{9q8JIpQfxVZS8LgG`?i16741uI>-;uP^WSlXz&d~{t64C+4yE} z7caqUJFN&`{{UvgaR#dnZY5ZjNeaec-{q)cJi@zJsllY`rKR;Yh90F&Qq#Xf+5Qy% z(D#2CJUKszbWeo(MxPWcr|dWSmdTtl2aTCUsUB0SWn2~q9XL2Wqv}NA2)ij<<@Nsn z+NR^f+Wp6cbr0F*=HtX^AxL!nCgK~(FEEQCFocKZ!a9;TARa)Y+UsL~sZMldUYq8O zckaDb_VYO341U_a5%G7#4+(rWpWyBOjjro=k;N0;&um)IiHZ{53Z-O(`_}s5o=KC_Q|SEVsnp4Vs3n`apBgt zki(_;8{!??05f%^c-~m8Lw5mYzm3K}>y|w-E1pra)TG8k;7^L0jEcH$qj}-@&T&4Y z;=A2aMEby}fc_KGNp>46-Tur{_=*`L@%P4mh?=}o6)$6DtF@h*6=1;mB*@)B>gO2s z=Bq`}NtCru*%#sdqhl_fzBTxT1TqyYA=itRWg(QE=-DBFBR$0{`3~ofTxowFzh^HN zYdXcgyEluz8*0}v%{|7cXk>W!2wHcG1{nYgx>5=-T%VW)EyXpUlRnt+&xoyjPoZi4 zAhJ~!_efY6rCFoMBrsVQ<#ot7VZo@|aop&D5)I07DTT`K5$!W|wU^SCHO&}&1z@P==-k1&qb>@ILpa%mr zun2on5TmYW0sjDn0}Ojm0)fo{KNlk+oGsygN_*RJ!+1E{Pr(CPbmvOq};Epr+R;eR5BP7{C zvCl9Wjx{XXMovDIt4=g&%B1#5u|hJdIKn%&e3PzdH+EOeE}^7dX|Hn4ENLP%dz6#+ zeL(4v>0ikChGCfH_{r6)2MEqh$I|@|>HMQL=EFvmYAL9spI)6p&}uf|c^Zs?dn58I z)xda(m|--HM{hk&Y<69f<~RDz5-q-|S^fmtkBGG`GREre?%o;Tf;N@Q4ltu9radd| za^Dm&73T_5jAYwOw&#Ic!~BC08BUz%PRje=^SR?53;m&Nd|z{-+QZ>%+h)}58tx|( zGNDkaPBK1VH-VMUJ#o^$?;FKWFQ+<{V490b+4npwCx=)}##G}&6ywaVs!ylO@;&h1 zn{5bqiS&6yP4`1SNgKBH#d9Dgo^iR{wLDQ!+6uyc(23$35$Q@Jz0NqWn!EAxfvrrjd|5P zO^jgqVvOU#*a}kpHGn4t=!(~8jhG&szYv=W= zRGarybYC;V;(Qhl145lVEN$;<`s{rfb8tqj;=&2QTa*6)lGb(ivPa0H;~&}X&q=@d zX=P(C%X-q@9;6VBb1(&eTJZ68Cka_>bkj+zoz0($wVe-FUkLb-ccZuZ9;+YRyI=0V z_az<20kM(X4hX}WTN<{G!uHlDhjpBpk%!8ol54h(DaGmRC9^}4{v!A%L8!f zBIol5t$GRdMkR>6H{t&P?906-4I;`tChRzx(ijyZlX$~rKm#YeQ@h+YJgZB%)4U(? zXT#qPZhT9u#iMIlbhma^*X1UJv~H@vQ2>+9%;wy`_8#_>-r2 zb6%Q%3ddqD-$}eVFeDNr$IET4z!C7OBkowc9M-98bZqNJarfh|bMkJ^&&67{kspaP zXCp~_`+We}Sw|>B-bmPFC49e}1|TzKm^s^pI8vsix-`S%YT>4(3AC5bPe-Bp-KXlB z$HFfOcrRPL@VAO&@vnt6!KZ4va_DTZ>l#9qA~@%_4{zpLg0772q^ir1JiQzPYcP$LBv;x+TC?Mj6MesR}UJMDmcmC zriWW;;m;9WyCtrLc{8EG7U*0259wRb&8gOQP1jYtoHnCYLK;BRZLNT5xmbi%YbX{^Hf&fjnblDT3p}H|Zt;z=V;HsH&+r z({^e6j45HNR);)Vx0^`juWW9#;>&+;CA%rX^Hi=6y>rVShNmuClI4DS8!WRIC3_622Z5`ad`KwK#E2q zfj|}7Qyv#iizf5`ZWHz)%FCeW?JUbBbU{vF3msJ)yX@xP^FW zBV-5aF-;;IkBqz>@dsGYwQWyNxp@M?IT&+*26}yZ*FV01I7ws}UO&IX+ zgruH57k2Bb)cIQEgOI8^ga-tZf=C^QKMTaUyUeLP9vk3$zW!c^?%p5xcm16;nP#bb zU$YJQeBYnsdCr0H)5LmZkkZpxGHKh)g4XgSofXKzWeyI~Km#KOfnS|f$*1g{6|5ge zX1^Ve({Wh_3cXKk>DqnMv-~&tp3$KG&>Cd$#|E$AO)BVP276g$x0n9_LMi_Mj#rOc zB%qfqOf+AbykFj(zXRv-JTEmTDj10`CuuLr{{V?c#y=7)b#DrIwjC2sxi_=v*D>1K zd85pE8YT##@CJ7fGlBH48!pJ+7c-+$PnMFLTfVkQ-%~tRQHh2QqKCgeS8Hi^Z@}U{ z1bA~vxA9e>xlgi~G?`-a=ChXAJF~z7$t0XR;TYs_IXOGH`@SZ{(Z^t&I#pHN)|XFf z>aDWZsq?vZ4=}*ii>Xc7M|(dlJlXnZ;;#>Qe&687hn^o0ShTY|L7+0kFiCbi=cg6) zx%DScf#}eSN!l9UN7VfH11gocy1iRBE6Yy1SozfH`a~yd>Xtw73Do}pTK;~mgRd8@ zMe=9pbyZodBFtIk@Z2(OI;Fnu;1gJ^HAnWpGtQn4yLaUz&~+_7U3A;&dXn9F6Ga&@ zHsJx1Kec%x&+j0;5g$#+TZmrl^yutt zHFyh_+cK#k*BQ<_A5s2&s_^yYP1;(aP6_ODDdyV9z>E-iUZB^d38|~an6+ce{xy6) zm*O9UVY|?87fV$)7C*^2FIj<4a@##?U` z_)kLAFXgkb)Gw_doz`-y&xOd@CP0w}TfRY5xGT z-;FhY3tGGhbs)9XWR+tt1%$*ax&>l3o#7afxm1&n;v3b{hk)-I?NeCk7@Zx$Y6U`V0T=74FymPDR+BMrPi7`Kvd0oae&-Aa#_`3(~anh+7 zIJ+&6+xSn1FnPv9Ms?%wd)oZj_dmh!+FQo*>GsyQ9wO4AGV`}ljY_GbZh2Xs24S$x`zT5JA5qKkBjTmSfYfX?ZwFpmE*-wh_JH^Y&>UCV(9ZLk z?h}n_QjOK^bnSmr<|mY4>0L?_O!R*nc%R~KgLS3JV7dr~Se(fV38f4{UU&h&i?w}E z6Jzrn5~D1>QCGeBze^q_U517$omEdwtbB>_-^X4dnhf}^$4G|p?L#m2e(+sMINTWI z9>0ZtN5q^eh$R-U0CjkK*fyt@R7_u~IiYxZQ#5JN+ro z#0t1N(WQ+_F?wFi{O>y8Y8iE*HEPg4AO^eNgN_Y&`;#C{u%k13P z^a|hi)qPG?n@=^Z318jU@H5W%cL|f_6)WNW>0U8!dv$jF52XGV#?x8DdojdhXD#Vp zVB&sl866+Q-xb)ljcsQFsyqt&q#a);Bl4)WrCj+lz&)Dx#`l)#oP9rdUiaR+7TgQBSfl zMz?V^r6LJ|{7yg>+eCP#^Nf_7;erakz3m zmF8mddenY6pGB8(Rv#L&4MzxoTbsKVx1<5G9kD9zX*a~yqA5BXgMyk~9G~bFk z)r?cygoV;&2+b@J$itA|D-|V9M^zx;kGCS2EInyPZR;O4 zytQ3^XK8!;P_-2M3 z?e6{;KMcs}(uW-5BKBPW0HKrNkBFL;{{V{oFJkNzT@UP#zDya#MjnwcxB-8rM|kD zLmVnO5_yD;jHCh^Ac6;RT#-|wCnjp6?OKdg+df+HuZ-xffK~A8A4$TToK(7}ugUrMHN#?OfveBToR#!z`q=wl z!|CA*)t25}Dl1E=Kvwct$ASg{P!8PSdRJWbsLl1udaAb;>Ib=ZRhE- zsY5h;6$E1pJ9X>QyCG3a)P{Ng0KspE>EKTQ=z10Pxf4W)?QJnx7Tv%fEO`C^N6X(B zuQ9bMvukE_eU)?BwY?`v@n?ngzYObE$#bOYRRl&k@04Jgp?QfJD){9l1kk9FoT@P+;N2r#Z<}z;tvpbhAV&CYfbRSh;>^n zTKh|rOa9UOVzWVu^`04HSeq*vD3;tRjy`2BOBord=#xNv*P>fn_)p`sUNrF5ivmTW z+S%$8*x14mW{9+{F$%aFghwF%0JBQGbd5#2J^mi43bkrw^?n-bl|It@FYnXleyIGMEaYG{?=JPhQ+tz~|JXQxh)d^pA%WYR@I2rxc;9PWruF^f~Kq7hGGSs?8#( z>9q8(n4VQiqiv(~8DOB+#?80HJJ@E4zSVVrz>p;OsiTt9jYzb*qk|WhQuZ@#EuT*# z>EDZA9wG4${3DWSQ)+@3;c&}+a+2ia4gdokIs7Z>xbFiTd?-V;{{TbrZwv4d#eHsb z*3B=>@e99+*O!cuNpm4aJgXin^V(cHPLtmN?fQZs_v!Oro2kDJ9V7 zr19n6r{eVS1>!5k9KlR602D?rxBzk6^RHh4R#`OZxa-UK_dLvR4${mrdFA^#E2sVK z(?3Z31>!v;Q1JTd7CM4SWU!XPH_RI!bdJY0`qm2@M=+wRP?gjCJx}IL%Pz%a_?cmG zaB-6SeAje%C&aHDyGt|)FUkQOYobxH#-w@Iz`s9R_?LBhnKt@;oR1@V7dupbKR4xE zwWX?xI$=%ndq=VMyL(neB2>=R=|B$|7^VjtGg^QU4+r(21X!0nC=p-)1_dAipIQb; zIO{-$?j+`#Kt=YAjn7J?wI#D&$!>3@YkfZ2OPi%bBcx#BH3KD>j)UI3yvsPFmqn{{ zNh{fOUEgGSxqeSq9KEF9B|F=h^?j1+bNbG)t!WaFiD@FQP$Oo?^cqC&TIpo)6ekP82 zLDHu#RQF4%^f@Pn*jxoqtaE!u()~VPsle+$5v+bD-`Ky2bZ92FhBbgY77Zj|^kN7< z#BqW!e;oW~Duqlm-Do@i0Kn{hMQ##?2AiG^vyDsNPUnJrNcexC_;*%@Sj6W_yo^g3 zw7ByZ86bdOFnA!2{DaA_q~Xll35bvTN|I~S{Ld#9{ke(4wS`c1BKMY`f;=x?zVPjZ zjqR?JrOEb|eaUxp$0$7j_3fT3>>-VyrF<-H=FgDCaQ(qm%h)4;-6!OjBu0{lGfd z2l#Ks+Em&%iZqLR`v=YzW%;8&-bU)J?hSQGDXU3b`D`XD5rL?x;pF1{kAi+Be#o9W z@Z|F9KMk%ww=_fZ3mKhK>H+D_1cTgj?OrY~CZ|*0f%=9^;sQ}n#;ZQ-W_;gw;BSn2 ze6JPH!+#MYFI?%`YfbVx3>PlkGk3+9QX`z*1_ z-*_(UVX=`P)F`j1rG=$i2Tu!#S4jMKGtH}EbIe9R15(aiRi5@O_+voT^q&@ZPgA+@ zuDAY$soT!h@Y=h)in0PiDLkLYwRl`X!x(H{TV93@{{RH}&p_1f zCiwpV;{N~*n_Ig}y&lU)OQ`OUE=$}Q0bCQ1RIfi;{ddFe9mH_X8m$aWlaqJ4?0nZ1 z=JYd6H3dWL$-Q*wkE-=qHp%1WC!Z$l{{ZBjrG3<$&x=aO&Hn%dZhSwi{4daaJeu97 z_RMDHLvIDj8;fT9Osuc7IT*-1j1YO?*95s{+!>-xYL8^lHFu8k=StK_7uM_+PB0iB zy6Qi=!|Q{Q)K`^S5~VAB#_?)O=Z<`0i&XGRY8tkS;dne(;rqE_xs$@^1IZoekTMmF z2Fgg`Pbxr=4$Me(Xj8}2bZYfhWzerz1yxp}?AFZo?+JL5L-BrcipThNh|0R#DL-3bkcgPNd!2I-N(uu*%HwX3@a`yQeT!}oU{Xq0XShO+}4mI@kT4>Y5XQF)@vB$nYY6&l4t==k9zFkE4UgF#gg>SwGF5e0BH`k&}_Z1ad2p zVCwchm1p>BvF4{yHRLsXQxr|V8-g6;*Y&MwU}`zVSo8Bt{{Ra|2U?`%qKo{E>HZ`> zxZi1-#yevfF@%ipN3UO8{#DbP;j7l1V?At-ir_p}0}X?#Qial#y7?n6CYaX955*Gwu z=cRH^g_CnfsfEpH;@oJbcF%C|?SW_^G7e89``5_kHGSt}uDeQBM{RfF9c#jtiZoqP z;?_xicM(1VamGhO$FHqrm16NYYMk^Y)^!y02qxyKc#(qGyKA%>c+mW1x{+8Jx6&n@vbGs(5;MgFp*KEPehj9Z1;vaAYj*7;394S z015^!N1??VfyjZ3{{TwV1kMcrIdR<3A?K|ji-3J-5g<|5oKr{xXceMFHeK-l0Eh2< zRjnN(PJMwCz18b3VzQ6ByB-Ds>Gbs(;HjD6Y1VWlEmFLi+AGcMk5ZOTi+E*>X(+d7 zr@Xxu?Dt)N!nXPkhAs3Th4;r;X;Gxq?%@E*cH;yt;ny8}vD^-)0DNx}WSFeeE0ppo zs#k5xTe<%L+umJ|qRTUSG;#2yoWa2)lytOX^7HO|%F6T4EO#<0I%V!9ob5|w2Mo{X z2TxLP03?B5&wo(F`$1vFwsDizzKR<=RLTL+FS^yyMn=`A%rmUxIpT$0_Go+RuN zoZOP!nbe_$i>Wq|$64qWl3iKr9y`64N$|m*DCcxVmgi&R43HKKR|I_BITiXoLBjal z&K}zjP0AYTmDZc;w9x#Qi#W>-MaqsHr!UC;v+$>cbUy@W8h?iTJ7~80U7~GJIWBv< z9_&vf{{TwvQRMeg__b=)F*O}pj_sXYoDtm-G;%A#4^<$7eJD(hQ(2Ub1zp9;M#S_z zDK-iwe75kpCuR@(JW+7vv6ZMnX%(wH^La6|qIs^KV2rZ`4YYmi5)M1`qUze06{=|T zE4@!ry8g~fZyae!cBQ=Oq_tAAf=)h9HE;kUJd$>fDP9)P=#Mq-&xCZHD_EEIrTF8n z>NoIT*_Y65BEPdi98Bo3IY67-j0YU&8E?X_lUmrqZQjiKQ&*Jj_=d-|wb}mw$vaxn zi2Qv0kfC{hYu^zmX4wvva{F_~+=Y67z^j@|scGoZ`p@F84qe|Y8n%iRb^9=UwKxLm zKCKHL+3F8w_9n5dNmY%ygkLK>r{K?s{1th3<1Hfhz*ibRuG*IULgQ6dX>}R4t2FB) ze9VGP@s68(vY-qRTr{u{!_}2rw<%k9wYnwKx!GSER}oGWr*2qnWWTGQO==nymZK8f zKoo*9u9euO+~Tp1Yjdb*t{|OE_Ic=fuhNE-19_sg)S)xmFk#$x6+G5su@$`X+7knk zW9{uj)DClBvA9LK)pU5;OT1>{$xr-!C>>LnmPcs#iO0C0SvBFiGYWH<*KPBJ;q71csKsSw%l$H9+{S2iCAd{OYm z&q35RT}xHcuPmU4Ot+S3twUwtR*?~g{LgU_=Nlon8-UI>YfwHT(R6)l!n)nIi>zom zg^!G(x`;uh+}n9_Gqi&nmATI=x8*t957yqoKSjT0%jMR;Xj!jhwpEi&(`|J4Od;gBDtD7&O5vGj+-*9(37QAh_3;ulZ+bN>Lc6%^A>UZ>D;1z6Uhg5}*(N&W1- zr+&)62|QUVc)P_G+K#8G>Y-5RkZqCF8&RCEWVOSuKphQdP$t+pX?EWPt*z;PgYGV zUM7TjX;f)>GNgY3eh{GypAPgOf9upy$sWeC%`xx(UrX;MpWrXS>)6a!KMphoL+NO$ ze=&nrp&rH`+L-9Os?z(58_<|MerYoW3llRif%8A7c$6^MtDWo%s^ww z;~W9&UpK@!nsjM8lmL#){Bf>_ss|nO|#my0f#v_J!n8ZbLmJ2=h~Qu4sn_ixUNjTm84M; zXFacYg3n5p&c<7T6!%9N$jUFM_dnxbFU48w$*{Jk@yqZ>+VE!#OFXGORY=~IKAqoh zPUpFuR^HR$&XuHiR>9%7npqnD@B#jpC^=Q!IU!VogWQwPTKp$I<0_T%>Uc~HB$TAo z<=$J{zTMBR!C+-qG?h$aUg})2?7a>L!~QSTJPoQgqicMzLWDiwoaQo_?mxZPZaL4k zMPb4`OOD~}Qgmf{Z&|0czt6Rge?G}Dx#k&BsSkhbG__CsyWd0Qe~;fCtb9x2jZA44 zG3h!y%m`^F{r0CPKfRNnEI}YD{nD&4$Y%YEIm$3xSA>RdfYMvaHnsg%bbPM~<~8_N zHd!upA9d*oJ(c@E<(J^kj66l+>11{bFQ~w;4+EDd*;xJg!W81=BNa675?pv!#2ztg zJC*Q`j*BJ!q7>|iGb$>Mer6?tSHA$Zs+D4RmRvnqE0Y(pG1p4 z1HL18O8)@Ix*n0Ccz(+3Te>7I?}*qGw`C;nMDpZQmHrKdfnFP&54z$X3bO3OEcOc@ zI&%A5i{f3kPv?JA@odA7vn*9fRIeMuqPh3C#GeX$B!k1AH1WsA-4+d3#y3`PZw9Go zS`X~>Ff?&UVqzY50EPgB1gfYjfnJ{tMes)t!zIZpN;D~{H_c|`|mIr#El=On%S$?}L0j;S0Zrm#w5)i)(w?b!|HO&TU5C6j1TYAd6;P zs4hc*K_eeEe4C4H$oA7b+gSL^p#7Iu)V>btp9(xPt69r!29aywok+!dt;r;-9@#C_ zBxOe6cF7#w@KlY$e-e+P^l#b^;!lO_+HZ|N2xikXduEOqyhWmFHrJ7dVg~6g)wf16 zMoB%#130L$Zru;4biHRy*R-o0b4j^NohtS@M>?|MWgd_rz6x; zOlKS8KM7fQvrn;0l##D=o5=NDIHa!{rR*V$4#7y=70R~L##9nGr1og2zE+v^G@d8$ z^!^eaIhySu(S?WhoQ>wLVUNo5N|BDBagMna%%tpf%F9#po8iC2zlZvyS}%+IMXTuA zf5d-@I^5GkWVriP;zxQ?7|32iqDQq$VS3`apxV&lmaO_4T$63T#FL(umxuoVB<-tm zQTcoOChHy=PufGrlG%7+t@R5H3gY7DQb>_KhOO`ywuw2?7 zq#BRLPXTFASYBQ0c5uUVL56FKnB$63fq4^nRm_`=Dw-w{GG*0Q!^xlj4&3-on9+>VB_aBy~e7TNDGYC3MQ5O|$Kk;DoPwtd6fFjkSEqvE`;P&9t`S7oZ0Zd^|TXqK5)Izz9jzIIwJ(}EM5!vRi$1% znRs~25t&qSFMJqJyE2HRthnJWBD7E9%ENF)>0%+ zJJ1#{`J8m8aIqfpN#}|a3l3R5>X8yT?;3c*$H3kd)_hN>Uvt+Xu58buQsU_)8D%AdEXQlGMEM*j8pYT8@Q=g(L9Y37ihloNt$=qc$H z6Vk*~UoALNOeOW6FX50DW)$EAO&e9?Fk1Tc6H8A?7a^ znXEityG?#9`gzGDjzb)ZJ2 zwu`LXjqvH$4u`(OinS74kylZQO&wA7Mf)l_+O0pz3G~flh{Vvrr7H7LPepUH1D4}6 zNlF+xPNRyuNnb#=nj3`=1gRpP=)s5PE252BHI?bfKSpz6@Hng+<-}5yUz%(4J~{Z! zuibyb!8UNpLR%ziqdgALf0;G;hZ)D)VkD)qRzIe^EW*Nv4@PZkHrxBpRrq`HJ6^Mf z4G!Y)MQtMh&o1UfIL6|j6Oak$3G0gdR=!)wUi7ES89jHh>3ex2+Qwwqdb5@$5WJG< zyYj!8=UzYYw79ufz6Ds47!#QePa?aroSyUMdikD(93*Mm-Lw3Ukvv=CDK484G8?4G ziR3&)PBMQ%`3~S$?A$2jm(@`F649gMyhP#ZS-w*`@m8%%-iz{Eub<|7Pr&cln_cm} ztpO6+DF4W4wd^f`0vAdb(B^b3|98B`Bv++M;N+?aqrFnIXNWqb6;JMQ=IYi zp+R0+*?HO6{GStEbtLN7lWzLA>U=lg?}C4`sPSdJzks#-zYyv&BQ3qR_S|VKjgClB zZN>m6InM)%`8>-%@jC;8olMIC3K6=z?3zmd0QK_j{j7a12MLzqv2^L+pSNvm7j>?? z>C=1NA8&Z$_HppvjJz+VShc<8g{ebum$PaXrWvNblpsu8dC|X^FgxQXoB~dMJ2CMu z6-JC{;w>qy_fh#q`hDly;CK%QQheBot$9bMmowk)K62K-Vf{45v;0RaY7o<=Jiqs06UBC4a9N7>(LExvt>v%e448k?_{Rdcu5mj3`I zkCDDPe!*WAJ`P(yiRaeztw&7Cyi@7vEM>_cDNu9CIOuEiyGE*0rtX>fwcH;hm6|@$ z@E61jkBeUm^%n5vo=}W|(1t&EAOR^PW|Y@aCVq~~ zZs@BdY;b)l21{=sa1n{${OXe#`HAtr;;qG|pQ!%JdXK^A@4Qhqw{@x5>k!Qwtnp0J z%AQs_bzi%vP#Fc{1fnZ!5>PeD&r+o?;GC6XV5zI{{ZNJ6PR|gyZ->vI6uO-u{$4> z{{XU8y50P8`2Ovki{RVAk_U!fWR*_1aXDdc~`+>(Juj91UzV>B6iWd9_|?^+(j-umq6H z;BOctQS4~7D`aKvNVSc3AFkZjwS>A&U#Rfbq zPR|?mJviul*JD@Fod?R=?yKX!gLi8Wi{O^~!<&Lzc#h68QHNnNkGTH;q3xcvi=}N) z9*g1Mj5Oq80c#0u4$z$g8h$)rSTWVpNV>&kAJOeSJ8jMVCiRVcj5@QSomW|5l<^X1ek_N zmfYN(+d~jSoEaqprxjVc$`m1Le~{EyE#&n+n(#&Ujs7x=UkCgYS$r?>Tf^}toeryS z8C$(VIDkRrANgdM0|a5uQbuqpFiTgtn`hR)4*vjVUx#`ek2bmCYa8k1CQH3TREcMn zW7VEXB*`b#lUhsNT+P`cQgf1wRogZGD1OM_vPZ=K01oQcnn!~4>t7P-F^R^lpxDN) zt(*erKuOa*K@2c>$6E3!@eW^6)Qvi-e2Vf*TOPB>aqx8GRveCcE^R;IzGvbei~Mi# zOZHCqqj_X)tu-%(x{Us0nst@CSy|sG<8sEB@+VQ)aogrx8ruV!V6#|rVJdT5?<+CL zGaR8Q;^{RPw6{;@v_87{EAbM;UifM8SH)f#(JTb*tx2p$6c2LWXxxy@9k;n6UJ8{T zC}r*sJr~iUa|}bo`zLnPVwS#L54WO~E+UHJ7Yz)m9awZ=MnR}N)W+W3t&NnoME%x9 z+!Qw5%onHQNMv^R)67d52HtQKW9dR^j971{dEt$MVa^E0Y8K)&lI{XXA%O=Rj8=%w zO!&X{yzzn?PYn1j)?%wXhVJ984nA1N{)BP#uOmD5(xL3>MZ5MtS@4zR*i24&enXhk#M7yI)Fp35ew&`> zIDCAqgv3Rq*{AxPf5liOwAF7QhA%GNocUkhxaCe8{?(Q2peE4t}?(XjH?o!-~7Tw$XzxVypra3vuIca%$7do-7{-D4pX~I!CjPqT2WNl`Fzpo=rYQ$YTqdmV&40WSCKcz}GAE?@9 zmeFQ4v(WV*4si1D{7}8$i|QXc?`Hcmx+%c)8FQ>V3vv}}96L#lh>{UXyEx}FUcFiS zeD#qo-q`$Ca?+{ZejDq;?NbMG(U0OWR2HF!3BXhbihyFxBpo-wt<)L|RkA;WgpB_Y zjX(4c!MC{E-ZlR{`xwO0<(X4%2|VuqwHxJ;CHGw4m4h>kEVnuz8SP75;l74=o^M-q zo*_S59E-ri5wWj5Ts@&j>TA)J0o(5~^}Sq@E9z_>Ea0c~YoUfU)pNbHvEY3$2NO8H zse5MB9i|`*9nXvyHYP?^;4_VXP<%gnzOODEZLviTPdd{mpH$3#SiRq_6Y}H+bF-By zsPsyR6+GD6bQw%(8ifdd^!sX&KHt~&1!bGM(w<~AcG%ZE{O#U|H*V^Bk&Z@E*G=Y* z|C*@DJ~G65!9l6q-}j_8qU02Sz7qpV#}*-FIDfJo@M>vxpA1wxz4r2((maSXqMB^1 z#({je?SHNgX05oq$3#2j(K&Zu`I8UR`vcxM$y^FW!q?lA&{Bs#`WlbaoGfE$+shOJ zhn~IgJS3E)-;rE>W~*PhYZSYU@(#Ok67Qwg>%$VZTuSj`BMR^Qw`e2nD3RLI=ZE5+ z5_wvhGa|v!JzYc!^O(xJ*-__1?502*BLA*FhLRX3t~wRt#bqUbqr;n0Nf+Q%=~`=W z8{R5_eLlsW>+t^4Bzx*c!ikuEiCN(I?LqNjCSn{ zt_bFRfwTFeV}?TN8ykY-U3!lBwnps%MTw^Y1i>nyj+fH&`G=anVx|!JwKhOR7n#cw z(<=gIl&T7|af9}oZLC^_&*b;AJV)V)1)YzL&)(e%Q&dBSOtT&CyMRv+!%ONH+N}3v zQ!JBr-J_2#GCZ0nl7UBg=P=dB+bFJUPbmmh*d5;f8IO4D4di22S{4C%LusUSC#r*2 z(*-$?sRsNxzq0}0U_T7VCT3&}r|V{u2U|?(ihzt)AGD3oty)TM3Zl5<8)>A2 z1iu(6VWl_$OLJaiz9)uA&&vNUuf85WU?TZ>@cXwnh^X3`R`*8OuHm@hXnsf3s^BAv zjNKjH*#1lMDVHFfRJda*j$b~UTg5P#djB109eFgBgB56Y6`X_Bm;`3NXeup$q~Y7A z7sYv*#*>TFvl}qUxa zi8Z*Mf4!|#CDoPWDTGZ8#lCMJzZ}^1q4-yaaM`dYNCCMcDaW9`B~CHjI{#a%M{}%T z{^15!U33D>Q#c*4dMP(~a<`F`;;}WMo;o^gkjssqyY2L1hw@phKcDpBuG)%J>IU ztMyR)<5dtO$Un4(k(XzK>1|~)e~(JfY~g%>mBZXampgirvwTsa4mE6KsX97x%O59G zeB67y&@1<%8mRp1rPS}iol-Lp!#q`BHeQduq9I8LgSC+D&)CMUrX{%~K&SuK(nY(m zCS_?0-O%YvRT(pIP`xO=*+e2V2+4%9qFtQlBYl6~c1H?***cqGbu$X%QwnXY5eIIE zH+uh#l)P%&oSk>91Chn3+E)Fo9e~8?gS!V5PwGX*&+e0m z@Q}g6yPr$b1IdDh=Y;qmvsJG$5VaydwuL(@LjwjmLZ*A#mIN8o7(5W~hEEbx$M=sW zY{z?7jJ3M!fa1Wq*v>pJKySKas5LG<@jxjBj3r%ZWkP#vblQ2&CqL_aNYO!qKc;rG z9KQ~ik^{z4w&=o9p0W$uDaVOX6eMcko{hs>@k3o4W5YA|evbLVn|Lt0jIl{ABvN5a z7VM7=z0@aC#f)+~srXY*tT>x>vYpz$w`sBx3EbNifs)>#R{!22i z6C>;1v@l_`d>y*WE9hqV3yQWM7c2ZV&p@k1rRB4C<;3)Ad4HSZPXWd~M~qYFfg%I1 zani`Vu35Vi?A+m6c&z*CV}W{({Mf&R1Xu1-J00fn%cHfiEW+(|D*nW>(4Hk(ESM93 zEv{eP+}^O-Z5aJr7c$CO4Ij4gyOn5aa?^)&xf&&4PQO`h0TQkjZ@A3a-PqkIz~eB% zp~pWk^{|YBEj`822-Q;XB&za>uS@7Ww@2R8&x6Lg7hke>3#>weKI*wk@Ygmc4CM4* zSNUjJHBFvWdBClxC=DH%V(Q0gvBZZ}p% zjy}}S&g@K<+cB-2dlgV&gwzGpvm!?gmH{h;oL_SO`NTMC!)tdx;rM&F+Sw2RFoYK7XDRiuebUE+htlvi?zqhu^7}@0CyurT%_)u&PXkmlnDI zbh&ml%532XGT53GGbhldwaG4JJ(EuLG0@lK}A(dLw;`@LwU1}i#NL;?P z6?_U;JxO^O9D`}}(Xps~KDa8ATtW@bK+FMr>6?~AvU7`;T`13gP`21=c+x!y@O~xw z-i_Qvrk5gQUlnI-%aH9cifh6R2&Tg9>uS>FiW{6e^^pa1xDJYzk!s(M_{tl{45_+(L+tOl{@sGtQ17A4bY$_gfW@R|1MU)~0FyHr+R zpcmHpwZ?6^qFCq6EXc4 z;$w^0#f`tD8#;%eImY98D=P0?|Cnhy*MY$?LKQPmw$V1mcs*~_ato2<1QWTP6ni3% z8o6CQCFj_?3BC*l65*&tpci2E-~&ZI)0HTrk|riNC$3ZPzz+IN3IU=|Z~1JvWOVF{ zjkMZ@f?^RkQyCL|nyWL`59$Q2q#+TWSWEldOl0TT6iO6{pSgr-pm5y<9s<_qs?P;~ zD_R59Zk6yg7RKfO_t<@DKFm(|@WZi?)h$mT%&)=r|jBD?T&kdLl z%fai?Evbt2k&J;DzltLA(`E8PDViC^AUC(1(TQwCcJ&?tAYHCv&xKi=>D7oTmUxu) zk+I5=L1%+>s+3N?`4p_p5zH#-_;2m;~VM3%ttSK<*z7W|2ehW?q*-8Xi4B5*O*wJ~ex`6A~hkfEI#rNOg4oSQgQZ zoI-%5gHc3&*nniEm+PQIdsbEGi^Pc*zGez*rMAK5dSCn``$nGScNiu~FX~$rLX8kA zBAbcRDUMS5ULCHBgMAMuy@bfEwMWh0zEj%5h}WeIX|z(k*j^=hCh>hi=wn@rJwqU# zbyM@{mQf;09od@>W#dvZ5*ro-O361)6HE97X0*<+;fu)9EirKXplUYyf`|9Tan z_3wfI=kYeH*GkB+>#m^Oo>D}02c9Fm5Lt=_8%?GdkLS4xWsFFV>dUWT@=UFA1-W=v zBEgAibUz*_GMV|X{kl7}QBZMT*1JZu`5#n2A=JCR) zT2D5GYrVD{(jo3$>=m>GQe3Eb5LnW3PIAt~>V5bg5LSkAIWP)^>|ApXX1r0(8Yg!d z_VWPS6+{~(zLX{BAubj^))l3JIaHckZwoq;`&%t(eo-eT8U*HI*S`qG z8i^$nss+hVCp=LVEp^cqJ{WHMA=ipZxIBGFkP+I)fh<$Aqv(&8=sn+lPC<r**>2JIA-hEUMb=ZAj zYJQ|W_1b)w-Z%Ruq%*{okWn+tpBCryOz6y+J6DNwvk@4IBdgl0(RLEJ{0_Tnvv$zf zmB_Tj{Z&Tr%-b4S_)N}8?Dnzgh|D!Mtn-}QIDBYm;h@^|mT8@Oct62;P|e!&_}!u_ zv`T_JW!x7&rlB4(+t}c*KJHvc5?C*D+a84KUhNqjf4RZ}q ze-7NY7eFPxfC-ofSD6^YQO5*CJo1$2er?VzdVx>1l2@-=#oZrC=p> z+w!88>~+n$TLg!TrvA^VqiZny+EsIyn^fJv7kq;70Q`>(mWMeM}dab{*RaV)QayFWWk~QdOnzl$JAy4dxZqnp%28zJ@5N7&SalF z3h92iC;i0MR8Yt6Us5wLE$n%lE8Z)VlS}}&vkSt+IS7BH<|}^xIQq`{q+(JX^{NUB zrBQ^dLjgJS8=3D7Pb%m+JYH*LT7Az+=~;yXqj{(7*kjRwuJrrC$0P~DSo%a+J`1HT zb8~M>jXQSvEECSLMM7H2i{jnYsqsJ2pNu;=*aW?+BU8wltB$S~U9EO^@)dNLJHkfy zFe!|GqP{=so)#vzl^ug^o%Krv!{P`AVF%)RhJtltevMwvc&T1`C_;S z`xLtLcY6VzJiz@u_G0use<2*6{=MaPX2m=KSrK@~cjok4^VFdi@`SR2X4chLu|=ly z%LaZ0W)}QMXAT0&e0UhItCi(7r*|?F_E$-S=T5Er8)0HFaz(!2czxq_Q9dh_p-%e_ zN@@Y)tx<8xmyu*fYfY&2x{MCq2^+*Rgi4o|8VJTZIO6JuQC5w;&=22K9e=N$i2&7H z`!r~fe@Xg{zW&?Sfwo!4?w~>5Jo|g;tEzOAUf9_{y1`)hvn+p-d%Us5nntjTAQC*l z#8#KkdZ(;(G=NJW8UzTPasqz6D_pcmp0h5lzOTt9Y;3$TSmkqqy?^HIo?ad2+DY%z-=qIB()VHD`^>C-(+Wb zpaCVZTFe{-;w=7yiHBGcIy1E-5)okTs?7=cZ%^L{5ap$I?H%e+}5Nq$~js z^p_c{Fl_+?~C)PB9+E2V}S_MU7rk|IX{U0Ov;`0MMP8~ALK#6=)ryO%ZH zOQ!igJ?K*zWB^Iue$4sa$UvgGO7gd2cIW9Q+`gIV4-6^1;g}&M)bM0!iP5TX3q*8M zi_f^`G`P>5@z9AX#}44v9V3|-2&${ad3K>XNAJj-TOYgi%|k?o>^EF8Q~zyA7_)4q zB{LvLR4f17Mls3UEvu@@66pNG>Iajdr4T4lyU<`SW8^woa7Ms}93ebVxI*68P(D;a z+&Zn8p0A?FsO}`h`SzoW2$DYJ&522PO6<`{^SB-h^*{5h!~4Dt;$gc~m8Qs6ul7qH ziz-#j&uMhvYGzeZt0yreY;y`KCTzKvUB2hv4hGZ-2&25J`#4`YYyIj8ux-%$Y9?T}ZJk{^WMtHQ0mc0yi6 zk1Exym<$}(|H16IpVI)15Nry2M{e%;nP6j|{>-GKa!d;NzUaNefKz^!A7go$DmOJP zP_Pj}*AwjXQ}9p8$f!?|RE07ROJ(_2!g4gdEc?3gth!J6Cyh z-csKa8k*HgVVrm{{Bo+UVjgCA6)0TQeVw!}`q!KEKNwr0A+IS8{T5y4VojC?N1WB+ z!#`yZnfX2i$$VYz`FBjyF#){Ymv%B$>#KpFp(&GxGXdGyxv#vYK`sb;+@69wa6(#E!M<>f9XTT6%iEJ-P6}qHx8vIP)3OG0i^!qbzQYx7 zW9J&RD9ziK={iSuOyrZMHi2gRa$Ed7t9nrvv(`TeBK&&XD6spkJr_oK<6L3HoLT<3 zbDqNKl)Wv{o=b*CSF#}+`aY|6%TGj~kNO{Rg6V!$Rhso`m==%py1w7fYn76IqfL~5 zqE}AlM`l96_Oemy!>L~i2Q2$p^j>R z6k&5nq7XF%)3GG5PlhF)TFj8q==mA}rw_ zk`eBB`x<+#Ch$D&FXD^=XSXwQ<6#{FS-> zW_+(WxIy^ShMcQlS%2BZTI$0Nb*^Qe@IcqF;MoHP@!)cQ-`D7B@@aK{Az|u13*5{y zMg?Z-2HV%=`1|EPM}p&Q#OvZvC}=!|dzLzgaIblR)fCm*?_zqKFQH`c&ufC6qr&2I z71{fVTvzd}qCJb9yI%Y1`sK{scAZkOpH9#Nqqky4wUq@?u>=jaFK@6UGAV*vM+VU; zy!mBS7mGus05t7>L zcXc@9W|!Q2VPa|M6k|j*Z*R!-PVr2cppHHL>}6&ge=emgiqPeXmAsr(Da$Ran?FQk zZ^PhT=F(MOda*?UQLwLsUl5S-Maar8+1PKpax~d?N9>Y$sOlhB;1li~Qa^}1aXq{x z=PcHFK`VqVT~v*aGC_$+)Q@VqugVn!>;kbha{B;hrU!+#tQio%wp>LYZ#T+^`- zQ$I}_IYagIef)Et>-&__grsD^-%b>7Kj+^^k@W(ZfjCSF6;@iMzEEz*#4+b1nA5YV z*<%Z^U}^P-YoIYcI5xx#10=Al35Tc!YoHN#7l$J}S)(udGX=j=!m`XieKn=A6H)nB z<7Os~-ulFPXi8y}H|4Z4H{g$@pkO#~J#w60v*dJswsUr8KhsEyHMfRm)IeN%)HZL{ zPXK}r+K#C9bkCP^#Lsf1h}A3AX$reji~IA&vA&cnfNR{w2lg|U^6|7>e#d!BYnc9U zoZgjJs&8OqEA~NCPER9o+;~cai75PqqDsQOAN69nHhO`y;n0^=Z68dk1T-WpyUUUm zE!xShYZjl<6Un;gHLjVx=cQ}VA$gItMFzcm6OAl_|ABr)*|c8+3WG`C>vJl?PGMaG zmA&|Q)CbRTU%6NB`I3qbL(Z=-`Mh`qn0X7m25FZz?QdrKmS0&*PaR8EPuDaiHwQ;w zG{VygHVp(Q57ze?rIPj0C%A7zNns=dN{5;ALu2t{2>ZTjYF<3&F#qW1;~tPAVC-Dl z^0mq5b6$CdWaSybXs2D+H;g#WP0q8W`)M!im(Z)EM=!yB9_Z z80o^ADGqxyY-?MtqM{7pmNxm3<25Abk7~N0K2@IB8f`qDcTerKsjE9^jP_N+8XE}| z#M8&{g%AdI26jc08z?)R3JHe>3V9`4kW^7Q1&%=i8Djm-0<+4S;dYbp*t6Cj0g4zH zA~1rBf3)|NB09u(5%ITJXKBJNKHIbYHF~lFXW3}K6};{d{O9KjGT3NF*0opesEj5 z%cGcoXWLe2*$=cj@wiDoo5@pJAWu%#RX>#+7b~3Y>E8tmcwvDWAfW{Y2DC`A zw+dE^?Qv-U!A{1>(%`DgJm4eQY-R9#dd3TMj3v9wxE>#rf%9H_>s}8E8ml7<$?kM= zeqJ0#{&G2`qptO+((9Fd24ej=Z@6@yg{mO*sirCW0NA|nY3PRH<7YF~iO?sQ_*j@z zX9HYzhY()IcuYG0b%^+AH zdo|_cO8fc2bafY_UgA+;1JA^ez<>N0H=NLQ8?z?%bHoGR@exDrV;Fne?5hgu&$QMK z29qzs{?0QIEBrP`c6%fd1EFnyuE+j_t=_a2*-)yXX}(k2GSOAskjJ96F9$BxoEO0J zzfKb(wQYJ%N!#=1V_YvabL2JkV2B~!0XM!53M#6$m?!P(*(?j5`k7`r(w9F|2@kMC zbvIt7QN2YrrJBuZf>c#abdZknVB0*0cMTmlm}1~F4Q3zxc!!eNnu{Ye6HX&lPT7aN z=_u}iM@krRGbI*^(i^pl{dHkH!c#3}v$dxxgY@|e9c=E*n~Q~6-ILDz6;@ppiXXii zo#rZ4#Q2*83>kR%a0b*pqSYMt{e{7vgGFcbcSH^Se zIp@;=$y0J(f)Ey{35AqqO}bY>dl(OVqFxXj2gRF5eEMtk0C8k$OWK=Y4<3zH=y6-; zf$f9*i>*;aMF55kb}hxmmJ~|xwwayMdl(~lLjb2=w)$3G?o#VbiC#vDH(Kl4_7?QF z3&;|p3!hvt2`BCN8OUK&e*NB2@}j%Q>olKg2IT~vlT;(ix!W-BH^tg|L^D#)4ZsrK zZP?!b5&a_J4H!)>I?{FV*L$7JB6^i8mOxLGvIQoYeNO3$ZYy4h?TbnNJ;y)P)gS?t zUxNc^r7FA5AD0(Y;fO{$?L%iUuYmHOLDaRCPyY1Fp%7VN=#XvP>}`B ziViQ+MM_{-57;hdN+DzvV0RBR{erzejEP`o9q2Td8PK&dQnAS?)L4PSI9}c7EFkek zF%Ao&m=O&v<6=wY2T#YmY)yPQ;>(SeI!Y;bn`tNe_fAQ*3_NQ#%Kpy)!0{GcOPh+L zzc*utB?+yIM~*ys@{LZkGalI~*Yq0uGj9NX4i^Siq<`g8MzflfGfoRh?Xn~AV76Z~ zsS>IAhOf+m(1yOP5&Pbn)Gp9!sgcAURlWh!m+^P&^r6&uK?UCx`RtAyppv_H4)Y&y zicyGya%w}WdGnV4`t|ex!8WP@Gh&#V+_-Tn$Hp`h7H^6PjOpzM=N=dj7~kc&`GQgj zNq#_zh4%Am5#=7E19TGSlNCNVjV(u-%B}Sv$#FAOv<92F@wS#9^UWDjSgEh@NkMgr zqF9*etKX(zyRwkFeiNjzLYy+p-eV4^mcmbQbP`GiUSIlgP|E}jb{nn!ge+cUx~p3KEaeFqTU^Tr;4$$p6se@4TcOUVaPLi#IU zl)cKJ9^eOFU+HzwDussxEq#JPsNaRpDg@?hJ|n-g*&M(%M_t4LoGn6dWH-ZWGXvPp zu;J>hFM)Q8F)~WR!H5gBoDrRM5ICcsU%X1b_@{ zf>jns`XAz$+Zv`&27V3Zt2DsKh`CO0J)78?H=N1>?aNlv)dr?;H*w#VyT?rg=^hdz zr8V{54Cl5qnBw45`+bs4I%2w3D`>*%H)Q2ca30d?nrL>HE)pcE4qrr!e?t5fXu=bc zFKO?XreBP#vjH^=_gPY^k*6e9x{^UlB6HH8a2iF2v=c-|;fgs0IM-*Br<&Ma{lTDj zg1`_zqa9(i6$2@}>9U8Rw>Ll1ulwL>h8p~@f3e&S*8Th{h;V1qWEW>=Cg_-A2g z96t(z{6jU~mJ}L=WIF3==7D5-NS-Bg=*5Ag#dNBk_vyOE%Nye1<-WFwN3P%9uiesq*W|A0oH&h;2JAZ zqqJ+^{P`gv08u#>;TYult%-p{ZLGh9Wpy74;cBh?geaIMScCzs#Mz2X< zl8hzVY-$m0aTgy2d_Cr=(ot;skW@Ce>2d08vYWhjK&+FMX}6|Sl@m5x3OVXeM+}c? z$$oxkToyUxWQk#M9m~i5upgLhyWVH1{Yp#DF}$8Gdn%|^E)48-GDM9mUq~?!ohu}; zZbJDe~@u7Su~dvwo2mCKKl8CK=2x7GC*O7r~>S+7ysN|EdHfWoTdMj z6XXaH<~ZH{^}tuS+#iRjWA(tzO>@|i@-32GLs3IgNipioP*N%0f~W`w^Ilgq{V>DF zsBZ9I~vI0pTffdoQI9M(;GbBO$fubqh!28~4= zN;(oe*R$7{9ZOJ+be#(~AU|i+eyA@jUZ_3K=o7?S zF@Q*5MqkjW?Z`s8i;%h`4+;h*bz)p!tDgL#RO|8Y_bFk-{qIJ*apB2==TxI_434hf zYy$g|Au=Be*N3m;`llb1$7;|S*4@@6MZ|hAe9+>jRrzK%F{29>j2QTjDD>*U(p^L9~@T(OJbmft*x4*&(w59US`6El<l4Os1HeP#2A@?LG-9`I zmNjOe^kNNrnweW=U+RP;xR*kIo7|^@KiNa!zb+rWJVC^XSX@pj;FV&19eS<>~Opj-lzBD*St(;PZS>7mim0grX)bMcrHrX&+HmMNPz9{v6If8y{FOKU4KyEB5=WxOZXyMb=Ij_ZG_3r{w@dL7r-@w z|M9x2rbLjy#H1=^FID`;aCL|m?k2Bpe3X(`AVBOl20PoiFs0asg6ZCU=tn5B027Q6 zzN@q zb|8Vx5^^~raiVU-k}_EWCn9VFO&RzWOV% zg7G8v^!~vF0nni6AQbCmE!}iOB4QGajXuE}vmCn`Qt+glN|HTIUPJjp-mhd`RqJgx ze@hVHhfnGc-KzoekM#|UxSyhmY{qn@AAjdcuJ#9MqZhzUZvhX-LV*?Et9;yU(;-g` z+Rr!2H_dx~j^#!+^yLQq6(@nKsmJH!<0D^@V!dH8WpCKn1~ik4Jpz&whgru@j9~3O z{dF=tODD1EQg0kzDtwoedv2<%^N;B*lG#{ShjiVAvLO6mY$Z6WxKft6UmJ`&DGsf} zXArF%t*wfDKz-?O_D(=osj8z+yMEtt7q!h6`%+b7r^SuTRh71br`?6}*D^sEWf<~B zkSUdFL+0USKzHK73Y0U5MoXs4W;Fklle=Bl9cnKimk)d>b{Bqd?^w_O8B3KM%l+|j z*F`FqtYthLB1W`Dvv>Q^M>*j1gzjj+8wZ?&-BNhal2c|({7`B0TsVKU^4z_L&}dAa zYF(r&7B6ny!7>3Ge_qCz2Hb?v#a7242cS~^{!ay>($RF z8QEM3!%Lyfv=vX0zUVQvJ-GKTMAkhiKFpEy`2cZPCwd{}6?{NB)FpjrZ*3$GwJZ6d zJHP|zV~C;+mJeIAJ)o?n!;X-}HQg zHG$PEejMb<9|r9ij6$HkAQ= z_XKBy8s+u6@;!L(vHIhQcl>242@`nkjsL+QPZj2X=Ipz{t5w2~vN7MJ*wCQcGiCM< z2v)E?tj;2Yy02QEngJTonl}n04ydkFL#^kYbiBBX?r^&#aj`~Z7YPVTgQ?UlgoddgRZzl}Iw|G}8_B?gQGFh5&8D8U&GQk#7*XMP)2 zIg1W(XD8vCj(R4^$O%th%Au|`uwF~39Ep(}WiA5QW*%J)grK>@fCn|0iP%@bF(x}? zsC%n)aWxxGfft?ba;89gG{7p(0Be<14t58YtIuGAg0_L49O=*WFD#yHq9+k1IkD^Q z_X4V0hsDPV)xSD;ZFAZG*vmf>%6aR zDizABuL|8wym|-+@h?AC(=I0ZYz(v>Q~LqN5q@y6NTlOS<}mRO-@-}$@PBy`^b>+I zLNc!9`T|g_))W|(A<=Z5JUzDB_NFPy{_M5Mp!bz z&8>};G!4lC=kZ)ZngB5*>QAB+w?!N`hz}*#(~);daocDP4g-&jfagt%vBjM*8R`WG z8i63OCR)|;_HrLA-EWqbmZkE|MkELE@k{7}C`2kohgJnV)Ul#GJ7BFt1Ef;*$Xh|V z-SBY7S5eRFdZ|ck&Ut}mzMr9Zc+B}Giia?G`pG+3Ex&oE=+zz8h^95C8$0YdRZo_i zvFNo;QiyQbMo|*-h=e7od^e9RKpVr5(CZfo@I#hh16UNH`XJG^ zVNiM<^H(;xmcn|OFr^U1u_48EcQgbyt zT7fS~{rYOTjRR8z2y(9E$hJ!XtW2y6UFxb|cF%l^8upcoA}F6=5N#&v(kV#PbKXj zlj4s*sHke;BlAd?`!mMd+b8WWFN?Ag$0Rs-UCNttr$sMB8BNn$7a9qc=McJEz6upl zSxr=E{Fd&aCpv~9Bwv`rC^iS9TwX2-(w#4>Nwn}f(vMyC>RXbhakAv6ifxBlW-EOh zb)}wKM#r5px1fnKZ>6j9KTZKjA@8)GoplouUS83q1Dg{hbj&PaqiD51_`J->T!qzh z@<4q6;}4BqKGMC%`b40U;k<#MCczgXh}Vs1D4;hjkTfRe60(BJ9VG)X4K)V4SFVA) zrzg??za?TP1%W8_Ffw(5%v3ksk?APmoq`+bZa6>o$aAb$1;?*WZ;d>NvLkrG}=QJ-Y8C=T?~f(1W~1$siw zV9rm#;qc8ou|pA5Jfb1%I})Z%>;Se`dR3SF{w+!h^5K9CjR)=c9o>ZTSChB=e0Ovb zFIG(&=@H@M>xc5C*AJ)ukb$S*oISi>ai1WkO0Nvt#Ax8RV(5rcsCjSed@n4-F3~;AjwvKj{T^hq zG^~gTnSFYf>h$AFw`yb!r6;Y5pc<BYB z=hD|tkXMQ@!H45Eqt~pf+%DFWO0uVPA5iH9aZ5J9Y}(`OuAe_G=w|2tgunL{0Ri0e zy!2@v51@AHs>2<>-2MW{yGIP!Tp}^4>bW2dj(qt7n7&z=0$1GP_ojiT!Njc?bbsH+ zPwTvnj1nZ!KU@EUVf;F(-!g@11FD``quT@w2sK7B)!BYSFf5a9)+hA?JrSp!Bgo6I z3xSXMXMW6tB&d^1bqf73j7D?IgZ;OPj$-a$=IZ8RZfuVZO*xv_paa<{zEVIF0s^e^ z<_?x_RunuOykA)*t?k^*U05aUjNQz?nVUMAnX{^UJDIa;E1B4so4T=zi8*@deTAM1 z?R9RKoxF~pl|4njpP;hemFZU}2 z58MBeycFF3E6dJC!TrCoY@8I_|7itU12-E5C)a_n zO3e*=-~U%V1vlq^8-<>u=5FHlpH7f;bg}=xm;ZDL1skifx`Z|hw8zX9jqT09SXet4 z+p)U3ncLf&yRbN!Sa~BG(|K`XzSU7&OHg%(bcFF(U*#Ev76tBz! zgY|^17U!;Mlg-6lI5!LJ-FHrJH+#KQ{%voUegFJ??&5ZLH!lX) zQRmSwN5#>IX zDlMtOPlpYxbw}o#lI@;QN>})5-qIR1z}zc51JB34vWkRC;9}eh>W?f~5jBkDb_@SI z0avpY{NCh2igG4b$ySlzGDXO&bCt9n>D>Hs zhxH*$r;|6}a?s@E)$bwy)??g6vFPeUbzMg>PNH%5vATNk^SZvw0fK{G8#^$vYxRxb&gnc&%Hau0dp(1J;o=XU3ri)1b zj&}cLMemaZHSWZ0OnP_3SIR~Og8+&huh`$ZVX#hSleIE&n=4VqBpIi6`JoEDVrrHV zEp?^eRk6OWmbKpPh{{M>f3;*a|Dr`HE{0i}BOBD2`J&zBJ|dOxtuc}I_=|FWh903Q0dx)mx?RR5Z|PsVP3v z;8f);ZYwv^*%l0{U(lvdYdhuiw2bGZBl2T=ls=@ zH>5-rX3;M#-6Ar03S75n$>nv4?)$98s_S~wG68j!<2xCLN(REN9>a)fO zjZ>9PY;IOF@v$n3Y22srEIH5L>ihIm9)yWBcr95!#AWl1!w|(GoTbF8*94z0Q*%kC zKMS0ELOWbsUBW!~Arg})GeeEQ6SVMUKsUW)bKdSusTC`OI~;)NL8Gd!k;24GL6%p+ zuwp{fR9J&{SES3rhq~{Yx4DC|CF1xoBDFH~nEv><{B*%hhXS67pDsf_6fjSneuWCA zISB|*lwy0(hS)O*)1(VU>k}L|xa!-6KZoi!_YJ43GA7sY5mcv*c+az-{M6)4yOOo6 zz{o~y`l}6W9Z%86n2VtD`pP@3Q&v`{Nft?&Bl0`!ts|;Ylo(=DC^i{lZmbrqH$SLv z)+QvIuA*zFw~$~w0=Kh*@F3yhjlMRzqiXq#6p>s(3ZZdXgy%3XQ9TqRPNQFmpPsx^ zhh-m3kD!;)v_B;&TVm!=%+gU=ok7?mlk6>K{tNkR%9M-^*AMFeM@zZ^sjOI?}Rc07#r1`q95aZq_|7xT9&i)GzXO5dLch&5Lel1qAY|b z;0VJzkA}}Dqs(|cToag_Es^JQlUgsVhW{SS*-F6mG5w)G9!B4BH}8&IP|u^j$Ki`_ zrAJPusL9p6|J)Ay$2*liq0A(n7E57dhK)rOOyGGxTSN`r+jQs;zoo77`}q~`Wg)xY z{9uL99ja~Ta*_(NnWvCJ^9@H4(eTuzwxm`gp=p(1N1!aFVAgq<&!8u$di*B#k*wQ3 z5DM@5hAHyJa%cPVJdtf6C$UB4& zU4}o~DEmaA-G8w_OmIuGxtlnDx{}GJ2z{l_uPeylWb@u8nl>n zszrZn>AfjXPpRFe=q+m5cR3<$djI3CUp*L|1WeU^;|;w0L@ZWO&mH!r94_Zu*oBC( zY&u)r)6ICp^uGl1f6Rh)irtF*z(VAAWS4`u-8PM%k$19TNfEy!+J^KOMhYVB)he*6 zt_uk7f7`2{w9KcC0Y(Zl`KToQ` zZ(r~`%S}X@6B!Vq%-0{}WVv~q(@k&8aHB_{E}CM(p4lv0Z!*wARiwHOTfBnDdzLUO zIO!WKDYl0@%FFc+IO-F1fGlyS;b)LFY3)fXY3AYe_8$AlT-l5?4im^oH|kXf;by`H zt>`JPX$;c7f99b`vj7OxE&OEZI#qm-<#pZ~hPIl-cCejyoFE=9?YksJQK!vOElwMsXp0pHS5lvr9ejX zv9c}CZ@;SO7eoKF^y^F7dz^z+foffWImiptB(#(%u+q`>4*G~&N&H4kRVY&i7Ju>$%5?Q zeeeFC+`GH=YIpxtTlK!8sG0uyobJ=-oSE+Pb^ivQ_<`6XHk~tp`BIg2?A44%18ZaB zYuxXpwGVKK#56lfzj&Uaukvi1Nu)jljthT-t1tH8ImTGvACsGA?5OBQzT@(Yu1C-= zOn*iuJvG{u;WiL+rd`^l^V7R={q+;CI94))ly6D>Su++6@+W&ad53s*HlWT!p%+Y> zVsD8oG-caCtg21!H%xKod*GYzoJP{MXa>-k~TK)X4m&!D~pY>K^>*{4%VV|0rblE9ixbAoHz)7bt&$CD$0{v#$&HM2w zypx$RvJ{lrNnZI&cX4LCkuuXMSxPHO#4@p|YJv5{*X)bDt1*7*BAM2->S&6r}}wGd6G(57Q}v4 zX>OCUn(Y(jDJRPd%?Cw_8Q~3&^g_nIlze9#zZp=x;W*XYmz4j^>EI(Yx@?E9rA#g< zG40FutB|X?_Z}4`l+cObpD+gygP)=ANvwcW^%N%J0#S&NbV4uCM){_$FnJugrRLFFdeCnl7bkcXYR50tD6rqq zRl3_p+J%^Io*rnQyVmo>$2Eml5bE&yglyfx=MdgybV9fo%__=&x^Gy4lxS`{v3LCE zbjiam1YG-ZW$T@(JssnEpAXmjIg2KiDg>rZYi-MmZaF7uh~T};HOI|eM!JnYSCQpq zbKx#<6^DFGrwOkMZ7y=%KyV(5<~ z5xCr6sUH^+CTS6ZY(s<@(kK|mdE211-$>cKDwkuZWRH6rL)kWx*0N^v7z@7WM`Th? zCM$SA#3L39dKy${IPo>668iDQ-L051TkF7U6m;A-l7*{idxUO1_fKlhUz|D$i34A0 zW?sQa>_48;e3A@3k==RRo0_#wnQk&FZD61s6cQ(G4K_d7WAqAMt00>Uo3HA8kYhBq znQ?!<|1Cx#AgM%FghIt>9o~1`WhI-)fRjO~qjWWZss7r&1NfvP?nW{)*nM`-_fZB& zVeRd}fv;uR8Lz+hPU&J}?n`PzDg)xjh0lv_?amf^LKAR{ke0N>mAs|Bv!qPn^{WOG z&nXTBy7}T2DM*WtgN=5L#cksDOWoi&6V znQza&4P`b&A}1t8g<;E_@POk59ill-4Q{6&drTT9VxYk{) zD*b{Zb%b8mug$6t_eQ_%CU7olp5rR0CZQyvZ>ZO4a8Aji8Hgmw^2!u$^T?HNa5W-f zEo910(y_8FXn#f;t7cO?U(p^D`MxQUHUI1W#I}W{FIpssEO zP*ijEwckE}%7oc^Npxh}_M@msIYj}Cv~m75Q_VHB*fmKVO$Ca9chYY|lVyojJ335$ zyhyzHcwD*DZlpP>w3+eeoIH7!VwNz6zZTknxPUtG(^^C(Y^lny1ggq_SRixO) z-VCj;FH~*@2057;Ub~5cV#crUdj%qk_kK6iz*l&7 zoXk@@)X}OD_pAB^lLY zK?JuPFthWAFxNFn3onry2GeoO9xkj2M?zA?k93QKSC{Abx z_3jZ;5Nq7(@+zYr@9aq@O3%Ot3^?TMFC5ciGPx40Yw|ky&S)^TY z*d64o=)+K=gi~G(CtBTRbyi?X0c91t)UYL9KEgT6st2y@PXw6(3r@W`=&st~GM9?D%?B0Wl)E06hGiG) zO<0DMUo)^HdOp=zF1=D0Z8B$#>8Xn-v`nRF20R(AO_&)}JF_{gYl+Vte))OCEXcEz zo>m;4V>Hj-QQQ4YfgI(Pu2G;AruJwQyshFD6KeB4JKFA%AU=Y1nz92;PhS6E%x!Vh zg4Ud?V{1uoBlUHkPI(gftolRWLGp3(z`#lplcg_p#o5(pZW0O^@5n@}HOp`b0{RWi zUibcp?GSG%Uoz6e?NUDu=9vOM`{bwYI0U-e9rfNHL^MRHt~ z*v8SlWzmRUl^bO(Z}cYGm3c~gZT&sxc8JJT1+!NVq5Vlrg}IlEPI#aTI0 zv}G-H=_H$lBg%b%K!k!%3<)4?#FX(F68GkkGG$9u4AQX&{WSEt({{pt-z+cQw6yoW zZv9PV3*&ppOiPoZ7Pn>-A#Ou@dgq|sc=|W`#dVu#4ZL;*bTwdF*-ulJ7%sA8w%4RN{DwGF%6|#I8^(aI(Wy=J!Q2eO7e%V!ubFYBt^E=K^m`EgoPbLoc z8O4+qt9d>_U+Pt0&q}^gt=mB7X7k5 z&Bghe=7)`n!xTv{Z(_{~%_!msLM#0;G^AoYC+0y&EYoGNNzyPMI%{h#+B1q{yq33n zdim=4w)$j^Yx7ra2d#m!%3XE^oT|}&e)gZaUwooqPCuATSDC2?HSW;q#N1mYXjBu5 zZA{+~CS(3wikMsPK>+KdD)-Hkf>R~Ye6~C&&~Rmr#`5EbXhwW)YjrCCqX&}dYsRDt zbG~~Z+K!@VP&itjs3NUfP{hEN4b0LL{86z$i3n1Pum-!lMu1t~_ET;d@ZfWl_k&qT zVqW(x$IK=5%H7pKn5GTfBzhdr8WVr{DaCI3gU^(2QEk~@o}9^7LJ>qkp8f1oBvYle zQnzqCzZLg;Sd>qe)i=eomPd=Rp(or~M!%(RcU;p3DwL0SZ`VGFY1S}F+#r1OcvzcN zW!g=u`tqT}s$F~3yZHebw_z>UTx3kZ@ zhYDct?anUhgJ$HhfIHkp-#-?IODvk61_zxvfH}ZhTz66REQrLklyw5XTjcKjx)4*D zyhXA?UEM|xK|K!D@yREx)%qWFjSi|~zkLJhh9|Zz9_Sw$T-A?q1ky}b%(OfyRvuLp zQ-{Tt*;}q};K2h%T$4L~lF<=}8i;k`8l`pOLcSw#s3h#L3`f%|wwX*X>|AlRx@8}5%^dggJMrZ5dV&7I#IAatUWXdqH~Lc2 z3=gC`zmGxZbYg|vZ+S?~W8pgWNZ;d0-^Qy^P_{Kxyz*Rr7AO6_b(=}H;h3e6p?R)J zsXJd7?>9Y5US^&XLPR&_+0)!CU%wZg*@J@+Cdc*4?tf*(#SRzYKEIoDWSNp!tl?aaZkYMKmq>=~g5yxhQAEQA?hIU=1!ydx8R@?wTbR zNesJ6kT#_pt9xh1mu$DZ7$UIk2x2Ow=!EBUTY5+Fd#BiJh627|5nYlwh<#@XJ(Ygw zw#D@jDO}qWnfFCrh*<^AlXk*=2d}v-<9w1X%^Q5tk*alc>uijl9?}Im;UV8M7`v{k zYt)+vBNqVv-mJF<*EUFLjO~*7vr(-_?C=JV+m~B@8nWWs;z^rw3Hgf&4zn!l44&#; zZ|GV|1nqqz2fyCCQva5Lu0!D6ip(@`$}R(0+3w!0F@n*^j%C+S-tf+kq$(&E1~(po z+8~8@+I={mt3>acvO>j=dCZF*j@2P+Z3N5s&9*rSzV-(2FOLND3f#$M7o!WM|EW=b z%yoTNa&E~$Rd8CD!Y-^?ZyR(EXVGT6Td!+xnQx=Rl|7PMe`fI#p*QSxQQ@LcHc0Mm zpH*ly$%wNasJXkCVV&mUSmFyog=UO?$mrDy=t17Rck?J*M$okIn-N*%?Zb(;uzCBjxwn z71o-GP{j$Yh6=>h+<%>;{j<~JexQ2jk_gLOPU;O|tvu?1WFOL2sZi&iR_=;j+$!18 zMPIIc%-woay~2*`G$Q>H5kv5NCm^BCAyd5=wA?E@SCv41U*IQ?PIr!;Rjjvzd#)1Q zlkkJ=%b`L05!rj%%J*LkEkbrnen4rS_KxQan8E2Q)z@g&R6rC7`Kcpp(+XC1zSBum ztN7@|SW~d#)18rfNxv1UB(Y1k;`KA=@vjYP41cM)y;0CX1jebsQ`~>USdFo$$*q%@ z6O?OeGGvw_Ukba`b}7%;QAa#zKWIO3$aY{SQkYZX5JupDc$68-yoMm^0_D-M)LV*@ zSu!1P2};9S1aG}=9*^e#_;i7LTnSZo8p-z3L8FOdB<`jn+CsnqFJ5ya`HFnQa^>yk z6I0N~hTl*1t)71GndXg^!y7X-H+^MnXg^u-B5Pu=P)^}&VY}-Ile2b**6T*=J@Jh2 zJ8=c_lzL(-qkH`^#PLN$-}@)mqL*~vRp2BD*uUhv@p;XN%D19p%;OQGl|Qg)x&d+STxF;%BJr8SQ!Ej4hzo$JYZ)=-K(49rTObj zI>zN%&*7KbpcU++O%i*W&&R`4UwTHDW{ir( zJ2_~t&yv+jPEua3*Hz-<^hQR-G#CSK2q}v>aCZ04Wq$m0<+L)?gYhQ}V9@$}b){fS zout*h9iXyLgn#5-#C$j2WzM97yGy*l8TfSpx>J{kya}Pts7jL*biIy=HgEPwoZao< zKiRi|UoMa~?p|UyYtouCq8O3+9%!^VW_A!2HD$M|e=-fHNHmc3S7nrT(;>xqb@zz{ zsBCDI8^2pX4xv4|kUE zyQe#Nq6rLZN)A*^y79Co0Kfdo56Sw{U~3#!o+P=paxI{a|5lg%GJ$X3P5 z>`t>ONf9e?Jkoh(mya&T)z_DsbR?Mtypt!oMCE7sL0(&WnQAoAmG~?*GQTvvE`(SK zHQ_B!@ZLKsvXX<979(rBNaf# z*=|N4O=(G%1u<#*!kEi@facZ6uYP<}wqUfb$1s_t;hn8oj59H#`BukTVkes+yoIQH zS1s3Tq`@-Rx?sIu8-K%6EG&sd=*LVeYd2?kvP4n%k75dX|Y0f_!1d*jb^m-F|3DDaOY6%}y+HZSC2UWu9$7zz;mC;hi% zkzZLNGBSVmc&`3$2{a(^-{sH9$o!ezF%8iN;wUH*l1uC1D-xPnvtN|lEfPojo*oLR5JLneG=8th`5{g5ir{Y^Gf!jluDC_ca+sxdd9(5^c)^0wzD z=T*)2_iZ{uZNs|lJvWCs+VnZEDsvjY?$Lq3I>|994kS!CwOT?we>WfJBm7Nyh?p4c z|6TUa#l)Ncwu~FG|82%iwdu^G4>hy_>g@a1zwom>2h-!yFg+JYsu125Ef*@bDsVJZ zH&$z`$QxHT?yboBPFQ~3JcU{QR zjEWr_$<)U+8zubjmEAFjkYyV-m!>=w#QxL+vD4&u`;md)4(X}+lg(X zgH?nhYa3eLL92a6gLokBSikB_m&mOsl(#w&dI z`O=hq;k?w8$kQ6ZGm^pMLfw}ASt3sJSSg{=FyGG2xy~&C0$w!PXO*jkD?G%bPk#`r-*7Mm@4WsA03`erBCxgvYkI6A1_Demg2a)L}ykppGGL`~F= zm~Zfdk!si10(dyQJ;_(o+Yr|!G-6-5A4XD}ki2fQn$I?pPk(YK%+9g%ZlP9T0^Zrk z41|x=ZNfhw;C2+3q)68)e$aOumnOZOxxKb$)}b(I-}p0S(sV@Tp0h%6VpvcBUmF}S zGS>Ynwg(bwChmLeN#D=>FvOo!bs>`3WjLT#0lmCPLaPp^YWpUD0uzj?I_LNNu-yZ- z?F>s(iBe0;yM~7JM@h9wEmK&U;XG6fYO6gQlnhIgxX&K0nb18AtYqMvcT(vblOOo{ zO~u_0YOhy2VFTq#j9MX?!}C>3R+=SMM|bpzqevm3s%Pv~_a`@ISB&9%KSxA2a;{D^ zOfyH5lvEZa8_o423A&?>Dz!%s+PzpC=*#GD@hrCmqnir0#1(mIA|4qnY4F*bLsDri z!htVVb)L<~CryA7-(GFM6xEd{aV!O9B<{R-Evipjjl%9TiMsiAuFntoeAR|kqTIX6 zFt4?tmo!ldh(I%^$gf`0uTX)XGuTps-Z$KK(?QPH_GGzc5}FG4Q!rBb6WkKEOceKs zgn;OaS|)FyQ#5;cTmAKjGPxX@1lxS^wY_JUm$ulRZ?~wpmPF*{kSsfPFQu0<-ppU1 z(@#mZqUQfh*26`>FvxYPvO*GTl*+AQIV^3V-%{s-Gf0ztW5Zg|SDAq9C`5PqQOJNw z2h^kEYg)Z(^d;CddwNJ=yV8oQT!U=Tt9PCSy zOAOoqF)~Hzx~|-k##Y8~@IxJO&z8h%`1`jX6u=OBWz_OHdXSZLim#C=wO)zBJg$mS>4jNF4IMF2ix$$KurI_%o{gJKNN=W=j$?krA`*T+8YgYJpEUY^DWi#jJs_MnW*Zwcc_=l|!Uu!`*82;f{lRIJQ7Mma*C{yX@txf<m9j@f*8U3zw~e)l zu5T3lWm@YTA<~`c-3Ip(-n%5N$8970Njt1gb)=Z|yLCp~=_HpPknbK_JH*W2O?2%u zaal%ZLR81tB5ZsV*@@HMiU$n~I$M2WRi3D|eNqRY$M0+(yrcZivc^sh)Wl%<{2=&~ zc$h=ay}6=JwSe>+v;0Z1o9fr}e1`aJToL?H(c&$n?hi5on3V&aY?Uee+Jl!y5}yT{ z=Fx|L(aX7iJiL`WrI^~x5yHH@=tNXLj`EG3=v~n8gtQ^l-7i_i89hL#s~C4uo8ord z?jFP=aA*MzOl3?(3}$>MxXo3ok!UMiDY?8_jCtP$k+i@6RtVkY?TT9ZBtzlk{q)1p zZI|nba9$QEDo2a(8esX1n&s9NnHV~WfKDcy4_cQbJ`3b+>kmH3sXe-dI?@-s#^&$k zav0%!18N}He7&$LzAJ=NQVAuJTy@4)4`Qgy@eo$8M}&{F48;n*6Ffk3rYJoo*q z?mlQTY~eF*l&7nH7Rn_=7ckjZK3aZwInJYKR<&4#7w9ruvYG0}aQ(Vpix+cv&o^Bl zF9D0;Hq|7%(Jc zf9AB+>;%X#Sl>_R_iO$s^98pfaCMX4kibjyN~0#JRRcR5JsSQA@rxU$B#*=KbYmxc^9?_*5H4u? zY7{Nw4lO)c-ma2*Dh-48U@}H(-fre`QTzI_KW(dvN>CQn-|<8pv}-NW?^b7aY&iZH z!^2dy@s>4rFh>Fhqm?{&wn;B?kH zRhJiZ6}-JBAfM)`IUjXK&& z`LQg&ho=~3l-XOz?uvhSXfF#+@nI9vVdLD;_Q4|(rHba*tN=;hOZ;A?O6|WX%VdiD zz{W%ZNajjzAMG-VDd#YJUi@G+Es!L~hdYa+ZB*sBDDp;Ap&m0kxN|xnBUuKLJ2fXC zdM(Z(HDqV13CKCCU1C8Z@R=+qLDDm53NiHbau>wWul?%BM<;qHcEQ`4=sh_#3~1e; zF06;pMx%sJAI5g+r(}Re{Kt{Z&@v(!zdM#9eedsF7i~4t={mH`TJrHK&C9z!q26%~ z5H|$hb(HJ#HO1>2Co5DQdX=#BU7c-R>BDipQstI-4aI4PY^iQCto4m0F*AXVnl4~9KyPv9Jy%BZKj>L zbO8ikLXqj-e8jEPkRu1t(d8+=bS!=-OrrnQL2@t6i=!)5GX^{4l%G!A5d6=iy7|=> zEkgNzw8TDA7-Z^lRDH-NVnm)^3Upe;dytWFnIJt>rFmG!nQ$c7wVk`*T2lro*$l(U z?V1pV6H`h(f$F?umq>>keuexwgTC=@7W`B}*NMw@OHKuh;aR+_!?Djg&3hrU+;X7@ z9DtusU8%|C%7wNW-SohH};9pNPdtk`xO3l+;dJO&RMjm+FA`OC4HH>#3w5UpNdh0&*EA0Aedm_&li(kgq*GP9lh^% z-z*q@6^@O2coy?-M*3jl*9wQulLBkW?Re zn^|{$OSV{XjCJHTeQEKP?F5UKHB>xBocoSaAtl7tTxbb7~ut)uig|g+u*{4A-#in2$jT} z+9O7%mJ_^w+^P_Q^mr2K|ClbsDY1Oio<3z)2ExhlcA6V=RzCa~X0;a9XJRO-<{7-* zpOnl*dPH##aa&HVTycJn5ROh9937ilB{3(my7Ry+Ek*-*$u+Ue2tWF{n^DVBMDyz{ zk7BXT%SRE--c-~rd9r83Rm7aze;3=IpP&5mti=<1pdu!sVTW=zf&D5r0sJb20sJbG z0f2rT!2rPLwLrQ6$gd(Afaotivp?#7&JSkX|K-r*oaOg(10Wpo2dgI91BpU1Ssxdql>^!XV2QS|!$|XPHMa5s>`>CYhN7B4O&3M9t(~f$8(Pm#OW(@R z!3vJzm6airl0{;xmC!;yNEadNU!_Uz0JOW6G?$|8O%*O#8A>uK9|<2P7bmQ2fRB?S z#$Cckn)g>53GC~0vIsBW7mJ63G%rF^2jJoC?C4^o^*TMrKx2@w%*Z*O65h_JJpjR*)1hl>EgB4Dr(mP5$h z7vq8S5yH50V+H=w#18RiGmN|NFQtU7oSj7M5F#L9pva$+l&~XmvvcvVbH)J9B_l1J zJw2p(Jw5GE5-2Fp(h>z06+()mK|)X~AW#SnwFU}_!BKFi7!Ya+MI!$x4_k8d_X4pu zuo59yiBclx0{%tdKS%p7r2iuwuoLz7I$&@7F=_zzm4v1<%FfzX346dN%?k#CKte#6 z5D=^n6qgW%VgIfJ!4g0qc3fCiMQqg?wifO0S%JT?{&NNXPniGg_rJvqnwtM>LpV8| zuS}$irly3Fvz4b4_UKbh=^wLh4M8G-)|O&IP)igVJL@o*khrL*m5>+|ZV9r6SX;p$ zFkX@W+jEDq`cq>UPdCS3iyUPof_6loE9Z`#J`h%Al$C@vwhj)7U7<)97e_lQLJ&yvdSm_jzl&bZBa=TO46KuQ?#b~fNu0ZgKo}4V6c>g4^5S^0 z-XTBs88Fs0#5x~;!}ZHC{DVv1&chMSr>3YY55V>V1Q=pHeRo@D7Xa4XR>NSNy|8_F zp#i$imd+l4^QY5p&W-?iH!E8^4=mz=ryJTGfOU8PN@yn}24#n_0hsb(pEIM8SPoNu zfc$^?K<@w0$k~nWCQ=`b0C?MBVHIq#SOIQsXluZE_=An6_(kMBJ#4W&N=S?y+7Y1P zY3Ye=iNzQ=2Uy_4f(E!bqdcw9ZhTmm3fqeiNEiwf7U%!3Aj}8b8zmVK00UzG|9Jsm zqM{H{!1*2Q1p+~#P;97oegQCl(nMj{;P3(sc8;TPfhG>YJ}lx$7(2xm<$__@ng0tP7>hpfds`?F1jYugzx4-$K!6u@ z5d(=~5hZ@-69d7qR{9G~{G!fcV9;OMii^X}p)CGYE*Q%P#|Fy3(clm`_<}AFAP55g zD@_!9p)HmVYlPqX!_vh5rmgrzT_8X(2y{U|2v7`k4$ASb`eA91i{r)8M9e0l)wN literal 0 HcmV?d00001 diff --git a/lwr_hw/include/lwr_hw/lwr_hw.h b/lwr_hw/include/lwr_hw/lwr_hw.h index 06aaab1..9164c6e 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw.h +++ b/lwr_hw/include/lwr_hw/lwr_hw.h @@ -34,39 +34,36 @@ class LWRHW : public hardware_interface::RobotHW { public: + LWRHW() {} virtual ~LWRHW() {} - void create(); + void create(std::string name, std::string urdf_string); - // control strategies - // position strategy 10 -> triggered with PoitionJointInterface - // cartesian impedance -> strategy 20 (not implemented) - // impedance strategy 30 -> triggered with EffortJointInterface - // gravity compensation mode -> (not implemented, achieved with low stiffness) - enum ControlStrategy {JOINT_POSITION, CARTESIAN_IMPEDANCE, JOINT_IMPEDANCE, GRAVITY_COMPENSATION}; + // Strings + std::string robot_namespace_; - // This functions must be implemented depending on the outlet (Real FRI/FRIL, Gazebo, etc.) - virtual bool init(); - virtual void read(ros::Time time, ros::Duration period); - virtual void write(ros::Time time, ros::Duration period); + // Model + std::string urdf_string_; + urdf::Model urdf_model_; - // Before write, you can use this function to enforce limits for all values - void enforceLimits(ros::Duration period); + // control strategies + // JOINT_POSITION -> strategy 10 -> triggered with PoitionJointInterface + // CARTESIAN_IMPEDANCE -> strategy 20 (not implemented) + // JOINT_IMPEDANCE -> strategy 30 -> triggered with EffortJointInterface + // GRAVITY_COMPENSATION -> (not implemented, achieved with low stiffness) + enum ControlStrategy {JOINT_POSITION = 10, CARTESIAN_IMPEDANCE = 20, JOINT_IMPEDANCE = 30, GRAVITY_COMPENSATION = 40}; + virtual bool canSwitch(const std::list &start_list, const std::list &stop_list) const; + virtual void doSwitch(const std::list &start_list, const std::list &stop_list); - // Set all members to default values - void reset(); + // This functions must be implemented depending on the outlet (Real FRI/FRIL, Gazebo, etc.) + virtual bool init() = 0; + virtual void read(ros::Time time, ros::Duration period) = 0; + virtual void write(ros::Time time, ros::Duration period) = 0; // get/set control method - bool setControlStrategy( ControlStrategy current_strategy){current_strategy_ = current_strategy;}; // CHECK CONFLICT + bool setControlStrategy( ControlStrategy strategy){current_strategy_ = strategy;}; // CHECK CONFLICT ControlStrategy getControlStrategy(){ return current_strategy_;}; - // Strings - std::string robot_namespace_; - std::string robot_description_; - - // Model - urdf::Model urdf_model_; - // Hardware interfaces hardware_interface::JointStateInterface state_interface_; hardware_interface::EffortJointInterface effort_interface_; @@ -86,8 +83,11 @@ class LWRHW : public hardware_interface::RobotHW joint_limits_interface::PositionJointSaturationInterface dj_sat_interface_; joint_limits_interface::PositionJointSoftLimitsInterface dj_limits_interface_; + // Before write, you can use this function to enforce limits for all values + void enforceLimits(ros::Duration period); + // configuration - int n_joints_; + int n_joints_ = 7; // safe magic number, the kuka lwr 4+ has 7 joints std::vector joint_names_; // limits @@ -121,6 +121,9 @@ class LWRHW : public hardware_interface::RobotHW // computing a fake velocity command using the received position command and // the current position, without smoothing. + // Set all members to default values + void reset(); + // Transmissions in this plugin's scope std::vector transmissions_; @@ -130,8 +133,7 @@ class LWRHW : public hardware_interface::RobotHW KDL::JntArray joint_position_kdl_, gravity_effort_; KDL::Vector gravity_; - // Get the URDF XML from the parameter server - std::string getURDF(std::string param_name) const; +private: // Get Transmissions from the URDF bool parseTransmissionsFromURDF(const std::string& urdf_string); diff --git a/lwr_hw/include/lwr_hw/lwr_hw_real.hpp b/lwr_hw/include/lwr_hw/lwr_hw_real.hpp index 9f4963c..7fe5c6c 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw_real.hpp +++ b/lwr_hw/include/lwr_hw/lwr_hw_real.hpp @@ -12,6 +12,8 @@ #include "fri/friudp.h" #include "fri/friremote.h" +// ToDo: add timeouts to all sync-while's to KRL since the UDP connection might be lost and we will know + namespace lwr_hw { @@ -20,6 +22,7 @@ class LWRHWreal : public LWRHW public: + LWRHWreal() : LWRHW() {} ~LWRHWreal() {} void stop(){return;}; @@ -31,13 +34,12 @@ class LWRHWreal : public LWRHW // Init, read, and write, with FRI hooks bool init() { - create(); - if( !(port_set_) || !(ip_set_) ) { std::cout << "Did you forget to set the port/ip?" << std::endl << "You must do that before init()" << std::endl << "Exiting..." << std::endl; return false; } + // construct a low-level lwr device_.reset( new friRemote( port_, const_cast(hintToRemoteHost_.c_str()) ) ); @@ -49,25 +51,40 @@ class LWRHWreal : public LWRHW << FRI_MAJOR_VERSION << "." << FRI_SUB_VERSION << "." <getState() == FRI_STATE_OFF ) + { + while( device_->getState() != FRI_STATE_MON ) + { + std::cout << "Please, start the KRL script now." << std::endl; + usleep(1000000); + } + } + + std::cout << "Performing handshake with the KRC unit..." << std::endl; - // perform some arbitrary handshake to KRL -- possible in monitor mode already - // send to krl int a value - device_->setToKRLInt(0,1); - if ( device_->getQuality() >= FRI_QUALITY_OK) + // salute KRL + device_->setToKRLInt(15,1); + // be polite and wait for KRL to salute back + while( device_->getFrmKRLInt(15) == 1 ) { - // send a second marker - device_->setToKRLInt(0,10); + device_->doDataExchange(); } - // just mirror the real value.. - device_->setToKRLReal(0,device_->getFrmKRLReal(1)); + std::cout << "Done handshake." << std::endl; + + // wait for good quality + while ( device_->getQuality() >= FRI_QUALITY_OK) {} - std::cout << "LWR Status:\n" << device_->getMsrBuf().intf << std::endl; + // wait for FRI to start + while ( device_->getState() != FRI_STATE_CMD) {} - device_->doDataExchange(); - std::cout << "Done handshake !" << std::endl; + // debug + // std::cout << "LWR Status:\n" << device_->getMsrBuf().intf << std::endl; + std::cout << "FRI has been started!" << std::endl; return true; } @@ -77,6 +94,7 @@ class LWRHWreal : public LWRHW { joint_position_prev_[j] = joint_position_[j]; joint_position_[j] = device_->getMsrMsrJntPosition()[j]; + joint_position_kdl_(j) = joint_position_[j]; joint_effort_[j] = device_->getMsrJntTrq()[j]; joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j]-joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); joint_stiffness_[j] = joint_stiffness_command_[j]; @@ -86,66 +104,137 @@ class LWRHWreal : public LWRHW void write(ros::Time time, ros::Duration period) { - // fake velocity command computed as: - // (desired position - current position) / period, to avoid speed limit error - for (int j = 0; j < n_joints_; j++) - { - joint_velocity_command_[j] = (joint_position_command_[j]-joint_position_[j])/period.toSec(); - } - - // enforce limits enforceLimits(period); - // write to real robot - float newJntPosition[n_joints_]; - float newJntStiff[n_joints_]; - float newJntDamp[n_joints_]; - float newJntAddTorque[n_joints_]; - - if ( device_->isPowerOn() ) + // ensure the robot is powered and it is in control mode, almost like the isMachineOk() of Standford + if ( device_->isPowerOn() && (device_->getState() == FRI_STATE_CMD) ) { - // check control mode - //if ( device_->getState() == FRI_STATE_CMD ) - //{ - // check control strategy - if( device_->getCurrentControlScheme() == FRI_CTRL_JNT_IMP ) - { - for (int i = 0; i < n_joints_; i++) + switch (getControlStrategy()) + { + + case JOINT_POSITION: + + // Ensure the robot is in this mode + if( (device_->getCurrentControlScheme() == FRI_CTRL_POSITION) ) { - newJntPosition[i] = joint_position_command_[i]; // zero for now - newJntAddTorque[i] = joint_effort_command_[i]; // comes from the controllers - newJntStiff[i] = joint_stiffness_command_[i]; // default values for now - newJntDamp[i] = joint_damping_command_[i]; // default values for now + float newJntPosition[n_joints_]; + + for (unsigned int j = 0; j < n_joints_; j++) + { + newJntPosition[j] = joint_position_command_[j]; + } + device_->doPositionControl(newJntPosition, true); } + break; - // only joint impedance control is performed, since it is the only one that provide access to the joint torque directly - // note that stiffness and damping are 0, as well as the position, since only effort is allowed to be sent - // the KRC adds the dynamic terms, such that if zero torque is sent, the robot apply torques necessary to mantain the robot in the current position - // the only interface is effort, thus any other action you want to do, you have to compute the added torque and send it through a controller - device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, true); - } - else if( device_->getCurrentControlScheme() == FRI_CTRL_POSITION ) - { - for (int i = 0; i < n_joints_; i++) + case CARTESIAN_IMPEDANCE: + ROS_WARN("CARTESIAN IMPEDANCE NOT IMPLEMENTED"); + break; + + case JOINT_IMPEDANCE: + + // Ensure the robot is in this mode + if( (device_->getCurrentControlScheme() == FRI_CTRL_JNT_IMP) ) { - newJntPosition[i] = joint_position_command_[i]; + float newJntPosition[n_joints_]; + float newJntStiff[n_joints_]; + float newJntDamp[n_joints_]; + float newJntAddTorque[n_joints_]; + + // WHEN THE URDF MODEL IS PRECISE + // 1. compute the gracity term + // f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); + + // 2. read gravity term from FRI and add it with opposite sign and add the URDF gravity term + // newJntAddTorque = gravity_effort_ - device_->getF_DYN?? + + for(int j=0; j < n_joints_; j++) + { + newJntPosition[j] = joint_position_command_[j]; + newJntAddTorque[j] = joint_effort_command_[j]; + newJntStiff[j] = joint_stiffness_command_[j]; + newJntDamp[j] = joint_damping_command_[j]; + } + device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, true); } + break; - // only joint impedance control is performed, since it is the only one that provide access to the joint torque directly - // note that stiffness and damping are 0, as well as the position, since only effort is allowed to be sent - // the KRC adds the dynamic terms, such that if zero torque is sent, the robot apply torques necessary to mantain the robot in the current position - // the only interface is effort, thus any other action you want to do, you have to compute the added torque and send it through a controller - device_->doPositionControl(newJntPosition, true); - } - else if( device_->getCurrentControlScheme() == FRI_CTRL_OTHER ) // Gravity compensation: just read status, but we have to keep FRI alive - { - device_->doDataExchange(); - } - //} + case GRAVITY_COMPENSATION: + if( device_->getCurrentControlScheme() == FRI_CTRL_OTHER ) + { + // just read status to keep FRI alive + device_->doDataExchange(); + } + break; + } } return; } + void doSwitch(const std::list &start_list, const std::list &stop_list) + { + // at this point, we now that there is only one controller that ones to command joints + ControlStrategy desired_strategy = JOINT_POSITION; // default + + // If any of the controllers in the start list works on a velocity interface, the switch can't be done. + for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) + { + if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) + { + std::cout << "Request to switch to hardware_interface::PositionJointInterface (JOINT_POSITION)" << std::endl; + desired_strategy = JOINT_POSITION; + break; + } + else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) + { + std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_IMPEDANCE)" << std::endl; + desired_strategy = JOINT_IMPEDANCE; + break; + } + } + + for (int j = 0; j < n_joints_; ++j) + { + ///semantic Zero + joint_position_command_[j] = joint_position_[j]; + joint_effort_command_[j] = 0.0; + + ///call setCommand once so that the JointLimitsInterface receive the correct value on their getCommand()! + try{ position_interface_.getHandle(joint_names_[j]).setCommand(joint_position_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + try{ effort_interface_.getHandle(joint_names_[j]).setCommand(joint_effort_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + + ///reset joint_limit_interfaces + pj_sat_interface_.reset(); + pj_limits_interface_.reset(); + } + + if(desired_strategy == getControlStrategy()) + { + std::cout << "The ControlStrategy didn't changed, it is already: " << getControlStrategy() << std::endl; + } + else + { + setControlStrategy(desired_strategy); + + // trigger the KRL with the new stragety value + device_->setToKRLInt(0, desired_strategy); + device_->doDataExchange(); + + // wait until friStop() is called + while ( device_->getFrmKRLInt(0) != 0) {} + + // wait for good quality comm again + while ( device_->getQuality() >= FRI_QUALITY_OK) {} + + // wait for FRI to start again before exiting the switch + while ( device_->getState() != FRI_STATE_CMD) {} + + std::cout << "The ControlStrategy changed to: " << getControlStrategy() << std::endl; + } + } + private: // Parameters @@ -165,4 +254,4 @@ class LWRHWreal : public LWRHW } -#endif \ No newline at end of file +#endif diff --git a/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp b/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp index 92bbbd0..8d576a5 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp +++ b/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp @@ -19,6 +19,7 @@ class LWRHWsim : public LWRHW { public: + LWRHWsim() : LWRHW() {} ~LWRHWsim() {} void setParentModel(gazebo::physics::ModelPtr parent_model){parent_model_ = parent_model; parent_set_ = true;}; @@ -50,7 +51,7 @@ class LWRHWsim : public LWRHW void read(ros::Time time, ros::Duration period) { - for(unsigned int j=0; j < n_joints_; j++) + for(unsigned int j=0; j < n_joints_; ++j) { joint_position_prev_[j] = joint_position_[j]; joint_position_[j] += angles::shortest_angular_distance(joint_position_[j], @@ -66,17 +67,22 @@ class LWRHWsim : public LWRHW void write(ros::Time time, ros::Duration period) { enforceLimits(period); - std::cout << "AFTER ENFORCING LIMITS" << std::endl; - std::cout << "SWITCH STRATEGY by: " << getControlStrategy() << std::endl; switch (getControlStrategy()) { case JOINT_POSITION: - std::cout << "JOINT POSITION STRATEGY" << std::endl; for(unsigned int j=0; j < n_joints_; j++) { + // according to the gazebo_ros_control plugin, this must *not* be called if SetForce is going to be called + // but should be called when SetPostion is going to be called + // so enable this when I find the SetMaxForce reset. + // sim_joints_[j]->SetMaxForce(0, joint_effort_limits_[j]); +#if GAZEBO_MAJOR_VERSION >= 4 sim_joints_[j]->SetPosition(0, joint_position_command_[j]); +#else + sim_joints_[j]->SetAngle(0, joint_position_command_[j]); +#endif } break; @@ -92,10 +98,9 @@ class LWRHWsim : public LWRHW { // replicate the joint impedance control strategy // tau = k (q_FRI - q_msr) + tau_FRI + D(q_msr) + f_dyn(q_msr) - double spring_effort = joint_stiffness_command_[j]*( joint_position_command_[j] - joint_position_[j] ); + const double stiffness_effort = 0.0;//10.0*( joint_position_command_[j] - joint_position_[j] ); // joint_stiffness_command_[j]*( joint_position_command_[j] - joint_position_[j] ); //double damping_effort = joint_damping_command_[j]*( joint_velocity_[j] ); - - const double effort = spring_effort + joint_effort_command_[j] + gravity_effort_(j); + const double effort = stiffness_effort + joint_effort_command_[j] + gravity_effort_(j); sim_joints_[j]->SetForce(0, effort); } break; diff --git a/lwr_hw/krl/ros_impedance.dat b/lwr_hw/krl/ros_control.dat similarity index 97% rename from lwr_hw/krl/ros_impedance.dat rename to lwr_hw/krl/ros_control.dat index 65027c2..a2a695f 100644 --- a/lwr_hw/krl/ros_impedance.dat +++ b/lwr_hw/krl/ros_control.dat @@ -1,20 +1,20 @@ -&ACCESS RVP -&REL 3 -&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe -&PARAM EDITMASK = * -DEFDAT ros_control -;FOLD EXTERNAL DECLARATIONS;%{PE}%MKUKATPBASIS,%CEXT,%VCOMMON,%P -;FOLD BASISTECH EXT;%{PE}%MKUKATPBASIS,%CEXT,%VEXT,%P -EXT BAS (BAS_COMMAND :IN,REAL :IN ) -DECL INT SUCCESS -;ENDFOLD (BASISTECH EXT) -;FOLD USER EXT;%{E}%MKUKATPUSER,%CEXT,%VEXT,%P -;Make here your modifications - -int i -DECL FRISTATE retVal - -;ENDFOLD (USER EXT) -;ENDFOLD (EXTERNAL DECLERATIONS) -DECL BASIS_SUGG_T LAST_BASIS={POINT1[] "P2 ",POINT2[] "P2 ",CP_PARAMS[] "CPDAT0 ",PTP_PARAMS[] "PDAT2 ",CONT[] " ",CP_VEL[] "2.0 ",PTP_VEL[] "100 "} +&ACCESS RVP +&REL 3 +&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe +&PARAM EDITMASK = * +DEFDAT ros_control +;FOLD EXTERNAL DECLARATIONS;%{PE}%MKUKATPBASIS,%CEXT,%VCOMMON,%P +;FOLD BASISTECH EXT;%{PE}%MKUKATPBASIS,%CEXT,%VEXT,%P +EXT BAS (BAS_COMMAND :IN,REAL :IN ) +DECL INT SUCCESS +;ENDFOLD (BASISTECH EXT) +;FOLD USER EXT;%{E}%MKUKATPUSER,%CEXT,%VEXT,%P +;Make here your modifications + +int i +DECL FRISTATE retVal + +;ENDFOLD (USER EXT) +;ENDFOLD (EXTERNAL DECLERATIONS) +DECL BASIS_SUGG_T LAST_BASIS={POINT1[] "P2 ",POINT2[] "P2 ",CP_PARAMS[] "CPDAT0 ",PTP_PARAMS[] "PDAT2 ",CONT[] " ",CP_VEL[] "2.0 ",PTP_VEL[] "100 "} ENDDAT \ No newline at end of file diff --git a/lwr_hw/krl/ros_control.src b/lwr_hw/krl/ros_control.src new file mode 100644 index 0000000..31a448b --- /dev/null +++ b/lwr_hw/krl/ros_control.src @@ -0,0 +1,194 @@ +&ACCESS RVP +&REL 3 +&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe +&PARAM EDITMASK = * +DEF ros_control( ) +;FOLD INI + ;FOLD BASISTECH INI + + GLOBAL INTERRUPT DECL 3 WHEN $STOPMESS==TRUE DO IR_STOPM ( ) + INTERRUPT ON 3 + BAS (#INITMOV,0 ) + ;ENDFOLD (BASISTECH INI) + ;FOLD USER INI + ;Make your modifications here + ;ENDFOLD (USER INI) +;ENDFOLD (INI) + +;FOLD Contact information + ;----------------------------------------------- + ; KRL script to be used with the pkgs in + ; https://github.com/CentroEPiaggio/kuka-lwr + ; + ; Author: Carlos J. Rosales, cjrosales@gmail.com + ;----------------------------------------------- +;ENDFOLD (Contact information) + +;FOLD Variable definitions + ; ---------------------------------------------- + ; + ; INDEXES: IN KRL GO 1-16 / IN C++ GO 0-15 + ; + ; ---------------------------------------------- + ; $FRI_FRM_INT[1] + ; This value is used to read from the remote + ; the desired control strategy, i.e. + ; + ; 10 -> joint position control + ; 20 -> Cartesian impedance control + ; 30 -> joint impedance control + ; + ; An friStop() - switch - friStart() sequence + ; is used to manage the switches + ; ---------------------------------------------- + ; $FRI_TO_INT[1] + ; This value is used to tell the remote that + ; either friStart() or friStop() was called + ; + ; 1 -> friStart() was called + ; 0 -> fiStop() was called + ; ---------------------------------------------- + ; $FRI_FROM_INT[1] (not used so far) + ; This value is used to call the remote that + ; either friStart() or friStop() was called + ; + ; 1 -> friStart() was called + ; 0 -> fiStop() was called + ; ---------------------------------------------- + ; $FRI_FROM_INT[16] AND $FRI_TO_INT[16] + ; + ; This values are used for the handshake + ; ---------------------------------------------- +;ENDFOLD (Variable definitions) + +;FOLD Init + ;Close and stop the communication in case it is open + retVal = friStop() + retVal = friClose() + + ;Reset FRI values, although not used + FOR I = 1 TO 16 + $FRI_TO_INT[i] = 0 + $FRI_TO_REA[i] = 0.0 + ENDFOR + + + ;Input correct tool number here and restart + BAS (#tool,1 ) + + ; Stay at the same position + PTP $AXIS_ACT_MES + + ;Setting limis for impedance mode to test that the model is Ok + $stiffness.strategy = 10 + $stiffness.commit = true +;ENDFOLD (init) + +;Specify ip and port +retVal = friSetup("192.168.0.150", 49939, 49939) + +;Open FRI with datarate 2 msec (ToDo: pass this value from ROS) +retVal=friOpen(2) + +;FOLD Screen output + WAIT FOR ($FriState == #MON) + $MSG_T.KEY[] = "FRI successfully opened." + $MSG_T.VALID=TRUE + WAIT FOR ($MSG_T.VALID == FALSE) + WAIT SEC 0.3 +;ENDFOLD (Screen output) + +;FOLD Handshake + ;Wait for the ROS node to salute + WAIT FOR ($FRI_FROM_INT[16] == 1) + + ;Be polite and salute back + $FRI_TO_INT[16] == $FRI_FROM_INT[16] + $MSG_T.KEY[] = "Done handshake!" + $MSG_T.VALID=TRUE + WAIT FOR ($MSG_T.VALID == FALSE) + WAIT SEC 0.3 +;ENDFOLD (Handshake) + +;Just send some values to check communication +WAIT FOR ($FriQuality == #PERFECT) +retVal = friStart(1.0) +$FRI_TO_INT[1] = 1 +WAIT FOR ($FriState == #CMD) + ;FOLD Screen output + $MSG_T.KEY[] = "FRI successfully started." + $MSG_T.VALID=TRUE + WAIT FOR ($MSG_T.VALID == FALSE) + WAIT SEC 0.3 + ;ENDFOLD (Screen output) + +;The infinite loop +LOOP + + ;Wait until a change of strategy is requested + WAIT FOR ($stiffness.strategy <> $FRI_FRM_INT[1]) + + retVal = friStop() + $FRI_TO_INT[1] = 0 + WAIT FOR ($FriState==#MON) + + ;FOLD Screen output + $MSG_T.KEY[] = "FRI successfully stopped." + $MSG_T.VALID=TRUE + WAIT FOR ($MSG_T.VALID == FALSE) + WAIT SEC 0.5 + ;ENDFOLD (Screen output) + + ;FOLD Impedance parameters + $stiffness.axisstiffness={ A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} + $stiffness.axismaxdeltatrq={A1 100, A2 100, A3 100, A4 100, A5 100, A6 30, E1 30} + $stiffness.maxforce = {X 300.0, Y 300.0, Z 300.0, A 30.0, B 30.0, C 30.0} + $stiffness.cpmaxdelta = {X 100.0, Y 100.0, Z 100.0, A 100.0, B 100.0, C 100.0} + $stiffness.axismaxdelta = {A1 100.0, A2 100.0, A3 100.0, A4 100.0, A5 100.0, A6 100.0, E1 100.0} + $stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} + $stiffness.cpstiffness = {x 200, y 200, z 200, a 20, b 20, c 20} + $stiffness.cpdamping = { x 0.7, y 0.7, z 0.7, a 0.7, b 0.7, c 0.7} + ;ENDFOLD (Impedance parameters) + + $stiffness.strategy = $FRI_FRM_INT[1] + $stiffness.commit = true + + ;FOLD Screen output + IF ($stiffness.strategy == 10) THEN + $MSG_T.KEY[] = "ControlStrategy changes to JOINT_POSITION" + ELSE + IF($stiffness.strategy == 20) THEN + $MSG_T.KEY[] = "ControlStrategy changes to CARTESIAN_IMPEDANCE" + ELSE + IF ($stiffness.strategy == 30) THEN + $MSG_T.KEY[] = "ControlStrategy changes to JOINT_IMPEDANCE" + ELSE + $MSG_T.KEY[] = "ERROR: Unknown ControlStrategy." + ENDIF + ENDIF + ENDIF + $MSG_T.VALID=TRUE + WAIT FOR ($MSG_T.VALID == FALSE) + ;ENDFOLD (Screen output) + + ;Start FRI again + WAIT FOR ($FriQuality == #PERFECT) + retVal = friStart(1.0) + $FRI_TO_INT[1] = 1 + WAIT FOR ($FriState == #CMD) + + ;FOLD Screen output + $MSG_T.KEY[] = "FRI successfully started again." + $MSG_T.VALID=TRUE + WAIT FOR ($MSG_T.VALID == FALSE) + WAIT SEC 0.5 + ;ENDFOLD (Screen output) + +ENDLOOP + +;Stop and close when done +retVal = friStop() +WAIT sec 0.5 +retVal = friClose() + +END \ No newline at end of file diff --git a/lwr_hw/krl/ros_impedance.src b/lwr_hw/krl/ros_impedance.src deleted file mode 100644 index f4b1837..0000000 --- a/lwr_hw/krl/ros_impedance.src +++ /dev/null @@ -1,73 +0,0 @@ -&ACCESS RVP -&REL 3 -&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe -&PARAM EDITMASK = * -DEF ros_control( ) -;FOLD INI - ;FOLD BASISTECH INI - - GLOBAL INTERRUPT DECL 3 WHEN $STOPMESS==TRUE DO IR_STOPM ( ) - INTERRUPT ON 3 - BAS (#INITMOV,0 ) - ;ENDFOLD (BASISTECH INI) - ;FOLD USER INI - ;Make your modifications here - - - ;ENDFOLD (USER INI) -;ENDFOLD (INI) - -;close and stop the communication -retVal=FRISTOP() -retVal=FRICLOSE() - -for i=1 to 16 - $fri_to_int[i]=0 - $fri_to_rea[i]=0.0 -endfor - -bas(#tool,1) -;input correct tool number here and restart - -;stay at the same position -ptp $pos_act_mes -;HALT - -; Only joint impedance control is implemented -$stiffness.strategy = 30 -$stiffness.axisstiffness={ A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} -$stiffness.axismaxdeltatrq={A1 100, A2 100, A3 100, A4 100, A5 100, A6 30, E1 30} -$stiffness.maxforce = {X 300.0, Y 300.0, Z 300.0, A 30.0, B 30.0, C 30.0} -$stiffness.cpmaxdelta = {X 100.0, Y 100.0, Z 100.0, A 100.0, B 100.0, C 100.0} -$stiffness.axismaxdelta = {A1 100.0, A2 100.0, A3 100.0, A4 100.0, A5 100.0, A6 100.0, E1 100.0} -$stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} -$stiffness.cpstiffness = {x 200, y 200, z 200, a 20, b 20, c 20} -$stiffness.cpdamping = { x 0.7, y 0.7, z 0.7, a 0.7, b 0.7, c 0.7} -$stiffness.commit=true - -;specify the ip and port -retVal = friSetup("192.168.0.150", 49939, 49939) -;Test open FRI with datarate 3 msec -retVal=friopen(10) -wait for ($FriState==#MON) -$fri_to_int[1]=0 -for i=1 to 3 - $fri_to_int[1]=i - if (i == 2) then - wait for ($FriQuality==#PERFECT) - retVal=FRISTART(1.0) - wait for ($FriState==#CMD) - endif -endfor - -;Wait for a cmd from FRI remote -loop - -endloop - -retVal=FRISTOP() -$fri_to_int[1]=4 -wait sec 0.5 -retVal = FRICLOSE() - -END \ No newline at end of file diff --git a/lwr_hw/krl/ros_monitor.dat b/lwr_hw/krl/ros_monitor.dat deleted file mode 100644 index e7daf62..0000000 --- a/lwr_hw/krl/ros_monitor.dat +++ /dev/null @@ -1,20 +0,0 @@ -&ACCESS RVP -&REL 18 -&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe -&PARAM EDITMASK = * -DEFDAT ros_monitor -;FOLD EXTERNAL DECLARATIONS;%{PE}%MKUKATPBASIS,%CEXT,%VCOMMON,%P -;FOLD BASISTECH EXT;%{PE}%MKUKATPBASIS,%CEXT,%VEXT,%P -EXT BAS (BAS_COMMAND :IN,REAL :IN ) -DECL INT SUCCESS -;ENDFOLD (BASISTECH EXT) -;FOLD USER EXT;%{E}%MKUKATPUSER,%CEXT,%VEXT,%P -;Make here your modifications - -int i -DECL FRISTATE retVal - -;ENDFOLD (USER EXT) -;ENDFOLD (EXTERNAL DECLERATIONS) -DECL BASIS_SUGG_T LAST_BASIS={POINT1[] "P2 ",POINT2[] "P2 ",CP_PARAMS[] "CPDAT0 ",PTP_PARAMS[] "PDAT2 ",CONT[] " ",CP_VEL[] "2.0 ",PTP_VEL[] "100 "} -ENDDAT \ No newline at end of file diff --git a/lwr_hw/krl/ros_monitor.src b/lwr_hw/krl/ros_monitor.src deleted file mode 100644 index e090477..0000000 --- a/lwr_hw/krl/ros_monitor.src +++ /dev/null @@ -1,77 +0,0 @@ -&ACCESS RVP -&REL 18 -&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe -&PARAM EDITMASK = * -DEF ros_monitor( ) -;FOLD INI - ;FOLD BASISTECH INI - - GLOBAL INTERRUPT DECL 3 WHEN $STOPMESS==TRUE DO IR_STOPM ( ) - INTERRUPT ON 3 - BAS (#INITMOV,0 ) - ;ENDFOLD (BASISTECH INI) - ;FOLD USER INI - ;Make your modifications here - - - ;ENDFOLD (USER INI) -;ENDFOLD (INI) - -;IMPORTANT: only in T1 - -;close and stop the communication -retVal=FRISTOP() -retVal=FRICLOSE() - -for i=1 to 16 - $fri_to_int[i]=0 - $fri_to_rea[i]=0.0 -endfor - - -bas(#tool,1) ;no tool -;input correct tool number here and restart - -;stay at the same position -ptp $pos_act_mes -;HALT - -; Only joint impedance control is implemented -$stiffness.strategy = 101 -$stiffness.axisstiffness={ A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} -$stiffness.axismaxdeltatrq={A1 100, A2 100, A3 100, A4 100, A5 100, A6 30, E1 30} -$stiffness.maxforce = {X 300.0, Y 300.0, Z 300.0, A 30.0, B 30.0, C 30.0} -$stiffness.cpmaxdelta = {X 100.0, Y 100.0, Z 100.0, A 100.0, B 100.0, C 100.0} -$stiffness.axismaxdelta = {A1 100.0, A2 100.0, A3 100.0, A4 100.0, A5 100.0, A6 100.0, E1 100.0} -$stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} -$stiffness.axisstiffness = {A1 1000.0, A2 1000.0, A3 1000.0, A4 1000.0, A5 1000.0, A6 1000.0, E1 1000.0} -$stiffness.cpstiffness = {x 200, y 200, z 200, a 20, b 20, c 20} -$stiffness.cpdamping = { x 0.7, y 0.7, z 0.7, a 0.7, b 0.7, c 0.7} -$stiffness.commit=true - -;specify the ip and port -retVal = friSetup("192.168.0.150", 49939, 49939) -;Test open FRI with datarate 3 msec -retVal=friopen(10) -wait for ($FriState==#MON) -$fri_to_int[1]=0 -for i=1 to 3 - $fri_to_int[1]=i - if (i == 2) then - wait for ($FriQuality==#PERFECT) - retVal=FRISTART(1.0) - wait for ($FriState==#CMD) - endif -endfor - -;Wait for a cmd from FRI remote -loop - -endloop - -retVal=FRISTOP() -$fri_to_int[1]=4 -wait sec 0.5 -retVal = FRICLOSE() - -END \ No newline at end of file diff --git a/lwr_hw/krl/ros_position.dat b/lwr_hw/krl/ros_position.dat deleted file mode 100644 index 65027c2..0000000 --- a/lwr_hw/krl/ros_position.dat +++ /dev/null @@ -1,20 +0,0 @@ -&ACCESS RVP -&REL 3 -&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe -&PARAM EDITMASK = * -DEFDAT ros_control -;FOLD EXTERNAL DECLARATIONS;%{PE}%MKUKATPBASIS,%CEXT,%VCOMMON,%P -;FOLD BASISTECH EXT;%{PE}%MKUKATPBASIS,%CEXT,%VEXT,%P -EXT BAS (BAS_COMMAND :IN,REAL :IN ) -DECL INT SUCCESS -;ENDFOLD (BASISTECH EXT) -;FOLD USER EXT;%{E}%MKUKATPUSER,%CEXT,%VEXT,%P -;Make here your modifications - -int i -DECL FRISTATE retVal - -;ENDFOLD (USER EXT) -;ENDFOLD (EXTERNAL DECLERATIONS) -DECL BASIS_SUGG_T LAST_BASIS={POINT1[] "P2 ",POINT2[] "P2 ",CP_PARAMS[] "CPDAT0 ",PTP_PARAMS[] "PDAT2 ",CONT[] " ",CP_VEL[] "2.0 ",PTP_VEL[] "100 "} -ENDDAT \ No newline at end of file diff --git a/lwr_hw/krl/ros_position.src b/lwr_hw/krl/ros_position.src deleted file mode 100644 index eaba0dd..0000000 --- a/lwr_hw/krl/ros_position.src +++ /dev/null @@ -1,49 +0,0 @@ -&ACCESS RVP -&REL 3 -&PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe -&PARAM EDITMASK = * -DEF ros_control( ) -;FOLD INI - ;FOLD BASISTECH INI - - GLOBAL INTERRUPT DECL 3 WHEN $STOPMESS==TRUE DO IR_STOPM ( ) - INTERRUPT ON 3 - BAS (#INITMOV,0 ) - ;ENDFOLD (BASISTECH INI) - ;FOLD USER INI - ;Make your modifications here - - - ;ENDFOLD (USER INI) -;ENDFOLD (INI) - -;close and stop the communication -retVal=FRISTOP() -retVal=FRICLOSE() - -;specify the ip and port -retVal = friSetup("192.168.0.150", 49939, 49939) -;Test open FRI with datarate 3 msec -retVal=friopen(10) -wait for ($FriState==#MON) -$fri_to_int[1]=0 -for i=1 to 3 - $fri_to_int[1]=i - if (i == 2) then - wait for ($FriQuality==#PERFECT) - retVal=FRISTART(1.0) - wait for ($FriState==#CMD) - endif -endfor - -;Wait for a cmd from FRI remote -loop - -endloop - -retVal=FRISTOP() -$fri_to_int[1]=4 -wait sec 0.5 -retVal = FRICLOSE() - -END \ No newline at end of file diff --git a/lwr_hw/package.xml b/lwr_hw/package.xml index 01114d3..c4b04de 100644 --- a/lwr_hw/package.xml +++ b/lwr_hw/package.xml @@ -18,8 +18,12 @@ realtime_tools pluginlib roscpp + tf + urdf + cmake_modules kdl_parser joint_limits_interface + gazebo_ros gazebo gazebo_ros @@ -30,11 +34,15 @@ realtime_tools pluginlib roscpp + tf + urdf + cmake_modules controller_manager kdl_parser joint_limits_interface + gazebo_ros - + diff --git a/lwr_hw/src/fri/friremote.cpp b/lwr_hw/src/fri/friremote.cpp index 97c7620..007b646 100644 --- a/lwr_hw/src/fri/friremote.cpp +++ b/lwr_hw/src/fri/friremote.cpp @@ -273,7 +273,7 @@ int friRemote::doCartesianImpedanceControl(const float newCartPosition[FRI_CART_ } -if (flagDataExchange) + if (flagDataExchange) { return doDataExchange(); } diff --git a/lwr_hw/src/lwr_hw.cpp b/lwr_hw/src/lwr_hw.cpp index 56e1fb9..6962ca2 100644 --- a/lwr_hw/src/lwr_hw.cpp +++ b/lwr_hw/src/lwr_hw.cpp @@ -3,12 +3,24 @@ namespace lwr_hw { - void LWRHW::create() + void LWRHW::create(std::string name, std::string urdf_string) { + // SET NAME AND MODEL + robot_namespace_ = name; + urdf_string_ = urdf_string; + // ALLOCATE MEMORY - n_joints_ = 7; // safe magic number, the kuka lwr 4+ has 7 joints - joint_names_.resize(n_joints_); + // JOINT NAMES ARE TAKEN FROM URDF NAME CONVENTION + joint_names_.push_back( robot_namespace_ + std::string("_0_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_1_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_2_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_3_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_4_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_5_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_6_joint") ); + + // VARIABLES joint_position_.resize(n_joints_); joint_position_prev_.resize(n_joints_); joint_velocity_.resize(n_joints_); @@ -27,22 +39,16 @@ namespace lwr_hw joint_upper_limits_stiffness_.resize(n_joints_); joint_effort_limits_.resize(n_joints_); + // RESET VARIABLES reset(); - // REGISTER INTERFACES - // get the robot description - robot_description_ = "/robot_description"; // default - robot_namespace_ = "lwr"; - // Read urdf from ros parameter server then - // setup actuators and mechanism control node. - // This call will block if ROS is not properly initialized. - const std::string urdf_string = getURDF(robot_description_); - if (!parseTransmissionsFromURDF(urdf_string)) + // GET TRANSMISSIONS THAT BELONG TO THIS LWR 4+ ARM + if (!parseTransmissionsFromURDF(urdf_string_)) { - std::cout << "lwr_hw: " << "Error parsing URDF in lwr_hw plugin, plugin not active.\n" << std::endl; + std::cout << "lwr_hw: " << "Error parsing URDF in lwr_hw.\n" << std::endl; return; } - const urdf::Model *const urdf_model_ptr = urdf_model_.initString(urdf_string) ? &urdf_model_ : NULL; + const urdf::Model *const urdf_model_ptr = urdf_model_.initString(urdf_string_) ? &urdf_model_ : NULL; registerInterfaces(urdf_model_ptr, transmissions_); // INIT KDL STUFF @@ -78,55 +84,42 @@ namespace lwr_hw void LWRHW::registerInterfaces(const urdf::Model *const urdf_model, std::vector transmissions) { + + // Check that this transmission has one joint + if( transmissions.empty() ) + { + std::cout << "lwr_hw: " << "There are no transmission in this robot, all are non-driven joints? " + << std::endl; + return; + } + // Initialize values for(unsigned int j=0; j < n_joints_; j++) { // Check that this transmission has one joint if(transmissions[j].joints_.size() == 0) { - std::cout << "default_robot_hw_sim: " << "Transmission " << transmissions[j].name_ + std::cout << "lwr_hw: " << "Transmission " << transmissions[j].name_ << " has no associated joints." << std::endl; continue; } else if(transmissions[j].joints_.size() > 1) { - std::cout << "default_robot_hw_sim: " << "Transmission " << transmissions[j].name_ - << " has more than one joint. Currently the default robot hardware simulation " - << " interface only supports one." << std::endl; + std::cout << "lwr_hw: " << "Transmission " << transmissions[j].name_ + << " has more than one joint, and they can't be controlled simultaneously" + << std::endl; continue; } std::vector joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_; - if (joint_interfaces.empty() && - !(transmissions[j].actuators_.empty()) && - !(transmissions[j].actuators_[0].hardware_interfaces_.empty())) + if( joint_interfaces.empty() ) { - // TODO: Deprecate HW interface specification in actuators in ROS J - joint_interfaces = transmissions[j].actuators_[0].hardware_interfaces_; - std::cout << "default_robot_hw_sim: " << "The element of tranmission " << - transmissions[j].name_ << " should be nested inside the element, not . " << - "The transmission will be properly loaded, but please update " << - "your robot model to remain compatible with future versions of the plugin." << std::endl; - } - if (joint_interfaces.empty()) - { - std::cout << "default_robot_hw_sim: " << "Joint " << transmissions[j].joints_[0].name_ << + std::cout << "lwr_hw: " << "Joint " << transmissions[j].joints_[0].name_ << " of transmission " << transmissions[j].name_ << " does not specify any hardware interface. " << - "Not adding it to the robot hardware simulation." << std::endl; + "You need to, otherwise the joint can't be controlled." << std::endl; continue; } - /*else if (joint_interfaces.size() > 1) - { - ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "Joint " << transmissions[j].joints_[0].name_ << - " of transmission " << transmissions[j].name_ << " specifies multiple hardware interfaces. " << - "Currently the default robot hardware simulation interface only supports one."); - continue; - } - */ - - // Add data from transmission - joint_names_.at(j) = transmissions.at(j).joints_.at(0).name_; const std::string& hardware_interface = joint_interfaces.front(); @@ -138,8 +131,6 @@ namespace lwr_hw state_interface_.registerHandle(hardware_interface::JointStateHandle( joint_names_[j], &joint_position_[j], &joint_velocity_[j], &joint_effort_[j])); - std::cout << "CLAIM: j=" << j << " " << state_interface_.getClaims().size() << std::endl; - // Decide what kind of command interface this actuator/joint has hardware_interface::JointHandle joint_handle_effort; joint_handle_effort = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), @@ -174,38 +165,9 @@ namespace lwr_hw &joint_lower_limits_stiffness_[j], &joint_upper_limits_stiffness_[j], &joint_effort_limits_[j]); - - /*if (joint_control_methods_[j] != EFFORT) - { - // Initialize the PID controller. If no PID gain values are found, use joint->SetPosition() or - // joint->SetVelocity() to control the joint. - const ros::NodeHandle nh(model_nh, robot_namespace + "/gazebo_ros_control/pid_gains/" + - joint_names_[j]); - if (pid_controllers_[j].init(nh, true)) - { - switch (joint_control_methods_[j]) - { - case POSITION: - joint_control_methods_[j] = POSITION_PID; - break; - case VELOCITY: - joint_control_methods_[j] = VELOCITY_PID; - break; - } - } - else - { - // joint->SetMaxForce() must be called if joint->SetPosition() or joint->SetVelocity() are - // going to be called. joint->SetMaxForce() must *not* be called if joint->SetForce() is - // going to be called. - joint->SetMaxForce(0, joint_effort_limits_[j]); - } - }*/ } // Register interfaces - - std::cout << "CLAIMS: " << state_interface_.getClaims().size() << std::endl; registerInterface(&state_interface_); registerInterface(&effort_interface_); registerInterface(&position_interface_); @@ -284,7 +246,6 @@ namespace lwr_hw vj_sat_interface_.registerHandle(sat_handle_velocity); } - if (!has_limits_stiffness) return; @@ -312,91 +273,181 @@ namespace lwr_hw dj_limits_interface_.enforceLimits(period); } - // Get the URDF XML from the parameter server - std::string LWRHW::getURDF(std::string param_name) const + // Get Transmissions from the URDF + bool LWRHW::parseTransmissionsFromURDF(const std::string& urdf_string) { - std::string urdf_string; + std::vector transmissions; - ROS_INFO_ONCE_NAMED("lwr_hw", "lwr_hw is waiting for model" - " URDF in parameter [%s] on the ROS param server.", robot_description_.c_str()); + // Only *standard* transmission_interface are parsed + transmission_interface::TransmissionParser::parse(urdf_string, transmissions); - ros::param::get(robot_description_, urdf_string); - - ROS_INFO_ONCE_NAMED("lwr_hw", "Recieved urdf from param server, parsing..."); + // Now iterate and save only transmission from this robot + for (int j = 0; j < n_joints_; ++j) + { + // std::cout << "Check joint " << joint_names_[j] << std::endl; + std::vector::iterator it = transmissions.begin(); + for(; it != transmissions.end(); ++it) + { + // std::cout << "With transmission " << it->name_ << std::endl; + if (joint_names_[j].compare(it->joints_[0].name_) == 0) + { + transmissions_.push_back( *it ); + // std::cout << "Found a match for transmission " << it->name_ << std::endl; + } + } + } - return urdf_string; + return true; } - // Get Transmissions from the URDF - bool LWRHW::parseTransmissionsFromURDF(const std::string& urdf_string) + // Init KDL stuff + bool LWRHW::initKDLdescription(const urdf::Model *const urdf_model) { - transmission_interface::TransmissionParser::parse(urdf_string, transmissions_); + // KDL code to compute f_dyn(q) + KDL::Tree kdl_tree; + if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree)) + { + ROS_ERROR("Failed to construct kdl tree"); + return false; + } - std::vector::iterator it = transmissions_.begin(); - for(; it != transmissions_.end(); ) + std::cout << "LWR kinematic successfully parsed with " + << kdl_tree.getNrOfJoints() + << " joints, and " + << kdl_tree.getNrOfJoints() + << " segments." << std::endl; + + // Get the info from parameters + std::string root_name; + ros::param::get(std::string("/") + robot_namespace_ + std::string("/root"), root_name); + if( root_name.empty() ) + root_name = kdl_tree.getRootSegment()->first; // default + + std::string tip_name; + ros::param::get(std::string("/") + robot_namespace_ + std::string("/tip"), tip_name); + if( root_name.empty() ) + tip_name = robot_namespace_ + std::string("_7_link"); ; // default + + std::cout << "Using root: " << root_name << " and tip: " << tip_name << std::endl; + + // this depends on how the world frame is set, in all our setups, world has always positive z pointing up. + gravity_ = KDL::Vector::Zero(); + gravity_(2) = -9.81; + + // Extract the chain from the tree + if(!kdl_tree.getChain(root_name, tip_name, lwr_chain_)) { - if (robot_namespace_.compare(it->robot_namespace_) != 0) + ROS_ERROR("Failed to get KDL chain from tree: "); + return false; + } + + ROS_INFO("Number of segments: %d", lwr_chain_.getNrOfSegments()); + ROS_INFO("Number of joints in chain: %d", lwr_chain_.getNrOfJoints()); + + f_dyn_solver_.reset(new KDL::ChainDynParam(lwr_chain_,gravity_)); + + joint_position_kdl_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + gravity_effort_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + + return true; + } + + bool LWRHW::canSwitch(const std::list &start_list, const std::list &stop_list) const + { + std::vector desired_strategies; + + for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) + { + // If any of the controllers in the start list works on a velocity interface, the switch can't be done. + if( it->hardware_interface.compare( std::string("hardware_interface::VelocityJointInterface") ) == 0 ) { - std::cout << "lwr_hw deleted transmission " << it->name_ << " because it is not in the same robotNamespace as this plugin. This might be normal in a multi-robot configuration though." << std::endl; - it = transmissions_.erase(it); + std::cout << "The given controllers to start work on a velocity joint interface, and this robot does not have such an interface." + << "The switch can't be done" << std::endl; + return false; + } + + if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) + { + // Debug + // std::cout << "One controller wants to work on hardware_interface::PositionJointInterface" << std::endl; + desired_strategies.push_back( JOINT_POSITION ); + } + else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) + { + // Debug + // std::cout << "One controller wants to work on hardware_interface::EffortJointInterface" << std::endl; + desired_strategies.push_back( JOINT_IMPEDANCE ); } else { - ++it; + // Debug + // std::cout << "This controller does not use any command interface, so it is only sensing, no problem" << std::endl; } } + if( desired_strategies.size() > 1 ) + { + std::cout << "OOPS! Currently we are using the JointCommandInterface to switch mode, this is not strictly correct. " + << "This is temporary until a joint_mode_controller is available (so you can have different interfaces available in different modes)" + << "Having said this, we do not support more than one controller that ones to act on any given JointCommandInterface" + << "and we can't switch" + << std::endl; + return false; + } + return true; } - // Init KDL stuff - bool LWRHW::initKDLdescription(const urdf::Model *const urdf_model) + void LWRHW::doSwitch(const std::list &start_list, const std::list &stop_list) { - // KDL code to compute f_dyn(q) - KDL::Tree kdl_tree; - if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree)) + // at this point, we now that there is only one controller that ones to command joints + ControlStrategy desired_strategy = JOINT_POSITION; // default + + // If any of the controllers in the start list works on a velocity interface, the switch can't be done. + for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) + { + if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) { - ROS_ERROR("Failed to construct kdl tree"); - return false; + std::cout << "Request to switch to hardware_interface::PositionJointInterface (JOINT_POSITION)" << std::endl; + desired_strategy = JOINT_POSITION; + break; } - - std::cout << "LWR kinematic successfully parsed with " - << kdl_tree.getNrOfJoints() - << " joints, and " - << kdl_tree.getNrOfJoints() - << " segments." << std::endl;; - - // Get the info from parameters - std::string root_name; - ros::param::get("root", root_name); - if( root_name.empty() ) - root_name = kdl_tree.getRootSegment()->first; // default - - std::string tip_name; - ros::param::get("tip", tip_name); - if( root_name.empty() ) - tip_name = robot_namespace_ + std::string("_7_link"); ; // default - - // this depends on how the world frame is set, in all our setups, world has always positive z pointing up. - gravity_ = KDL::Vector::Zero(); - gravity_(2) = -9.81; - - // Extract the chain from the tree - if(!kdl_tree.getChain(root_name, tip_name, lwr_chain_)) + else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) { - ROS_ERROR("Failed to get KDL chain from tree: "); - return false; + std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_IMPEDANCE)" << std::endl; + desired_strategy = JOINT_IMPEDANCE; + break; } + } - ROS_INFO("Number of segments: %d", lwr_chain_.getNrOfSegments()); - ROS_INFO("Number of joints in chain: %d", lwr_chain_.getNrOfJoints()); + for (int j = 0; j < n_joints_; ++j) + { + ///semantic Zero + joint_position_command_[j] = joint_position_[j]; + joint_effort_command_[j] = 0.0; - f_dyn_solver_.reset(new KDL::ChainDynParam(lwr_chain_,gravity_)); + ///call setCommand once so that the JointLimitsInterface receive the correct value on their getCommand()! + try{ position_interface_.getHandle(joint_names_[j]).setCommand(joint_position_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + try{ effort_interface_.getHandle(joint_names_[j]).setCommand(joint_effort_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} - joint_position_kdl_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); - gravity_effort_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + ///reset joint_limit_interfaces + pj_sat_interface_.reset(); + pj_limits_interface_.reset(); + } - return true; + if(desired_strategy == getControlStrategy()) + { + std::cout << "The ControlStrategy didn't changed, it is already: " << getControlStrategy() << std::endl; + } + else + { + setControlStrategy(desired_strategy); + std::cout << "The ControlStrategy changed to: " << getControlStrategy() << std::endl; + } } + + } diff --git a/lwr_hw/src/lwr_hw.cpp.autosave b/lwr_hw/src/lwr_hw.cpp.autosave new file mode 100644 index 0000000..626fe46 --- /dev/null +++ b/lwr_hw/src/lwr_hw.cpp.autosave @@ -0,0 +1,443 @@ +#include "lwr_hw/lwr_hw.h" + +namespace lwr_hw +{ + + void LWRHW::create(std::string name, std::string urdf_string) + { + // SET NAME AND MODEL + robot_namespace_ = name; + urdf_string_ = urdf_string; + + // ALLOCATE MEMORY + + // JOINT NAMES ARE TAKEN FROM URDF NAME CONVENTION + joint_names_.push_back( robot_namespace_ + std::string("_0_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_1_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_2_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_3_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_4_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_5_joint") ); + joint_names_.push_back( robot_namespace_ + std::string("_6_joint") ); + + // VARIABLES + joint_position_.resize(n_joints_); + joint_position_prev_.resize(n_joints_); + joint_velocity_.resize(n_joints_); + joint_effort_.resize(n_joints_); + joint_stiffness_.resize(n_joints_); + joint_damping_.resize(n_joints_); + joint_position_command_.resize(n_joints_); + joint_velocity_command_.resize(n_joints_); + joint_effort_command_.resize(n_joints_); + joint_stiffness_command_.resize(n_joints_); + joint_damping_command_.resize(n_joints_); + + joint_lower_limits_.resize(n_joints_); + joint_upper_limits_.resize(n_joints_); + joint_lower_limits_stiffness_.resize(n_joints_); + joint_upper_limits_stiffness_.resize(n_joints_); + joint_effort_limits_.resize(n_joints_); + + // RESET VARIABLES + reset(); + + // GET TRANSMISSIONS THAT BELONG TO THIS LWR 4+ ARM + if (!parseTransmissionsFromURDF(urdf_string_)) + { + std::cout << "lwr_hw: " << "Error parsing URDF in lwr_hw.\n" << std::endl; + return; + } + const urdf::Model *const urdf_model_ptr = urdf_model_.initString(urdf_string_) ? &urdf_model_ : NULL; + registerInterfaces(urdf_model_ptr, transmissions_); + + // INIT KDL STUFF + initKDLdescription(urdf_model_ptr); + + std::cout << "Succesfully created an abstract LWR 4+ ARM with interfaces" << std::endl; + } + + // reset values + void LWRHW::reset() + { + for (int j = 0; j < n_joints_; ++j) + { + joint_position_[j] = 0.0; + joint_position_prev_[j] = 0.0; + joint_velocity_[j] = 0.0; + joint_effort_[j] = 0.0; + joint_stiffness_[j] = 0.0; + joint_damping_[j] = 0.0; + + joint_position_command_[j] = 0.0; + joint_velocity_command_[j] = 0.0; + joint_effort_command_[j] = 0.0; + joint_stiffness_command_[j] = 2500.0; + joint_damping_command_[j] = 0.0; + } + + current_strategy_ = JOINT_POSITION; + + return; + } + + void LWRHW::registerInterfaces(const urdf::Model *const urdf_model, + std::vector transmissions) + { + + // Check that this transmission has one joint + if( transmissions.empty() ) + { + std::cout << "lwr_hw: " << "There are no transmission in this robot, all are non-driven joints? " + << std::endl; + return; + } + + // Initialize values + for(unsigned int j=0; j < n_joints_; j++) + { + // Check that this transmission has one joint + if(transmissions[j].joints_.size() == 0) + { + std::cout << "lwr_hw: " << "Transmission " << transmissions[j].name_ + << " has no associated joints." << std::endl; + continue; + } + else if(transmissions[j].joints_.size() > 1) + { + std::cout << "lwr_hw: " << "Transmission " << transmissions[j].name_ + << " has more than one joint, and they can't be controlled simultaneously" + << std::endl; + continue; + } + + std::vector joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_; + + if( joint_interfaces.empty() ) + { + std::cout << "lwr_hw: " << "Joint " << transmissions[j].joints_[0].name_ << + " of transmission " << transmissions[j].name_ << " does not specify any hardware interface. " << + "You need to, otherwise the joint can't be controlled." << std::endl; + continue; + } + + const std::string& hardware_interface = joint_interfaces.front(); + + // Debug + std::cout << "\x1B[37m" << "lwr_hw: " << "Loading joint '" << joint_names_[j] + << "' of type '" << hardware_interface << "'" << "\x1B[0m" << std::endl; + + // Create joint state interface for all joints + state_interface_.registerHandle(hardware_interface::JointStateHandle( + joint_names_[j], &joint_position_[j], &joint_velocity_[j], &joint_effort_[j])); + + // Decide what kind of command interface this actuator/joint has + hardware_interface::JointHandle joint_handle_effort; + joint_handle_effort = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), + &joint_effort_command_[j]); + effort_interface_.registerHandle(joint_handle_effort); + + hardware_interface::JointHandle joint_handle_position; + joint_handle_position = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), + &joint_position_command_[j]); + position_interface_.registerHandle(joint_handle_position); + + // the stiffness is not actually a different joint, so the state handle is only used for handle + hardware_interface::JointHandle joint_handle_stiffness; + joint_handle_stiffness = hardware_interface::JointHandle(hardware_interface::JointStateHandle( + joint_names_[j]+std::string("_stiffness"), + &joint_stiffness_[j], &joint_stiffness_[j], &joint_stiffness_[j]), + &joint_stiffness_command_[j]); + position_interface_.registerHandle(joint_handle_stiffness); + + // velocity command handle, recall it is fake, there is no actual velocity interface + hardware_interface::JointHandle joint_handle_velocity; + joint_handle_velocity = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), + &joint_velocity_command_[j]); + + registerJointLimits(joint_names_[j], + joint_handle_effort, + joint_handle_position, + joint_handle_velocity, + joint_handle_stiffness, + urdf_model, + &joint_lower_limits_[j], &joint_upper_limits_[j], + &joint_lower_limits_stiffness_[j], + &joint_upper_limits_stiffness_[j], + &joint_effort_limits_[j]); + } + + // Register interfaces + registerInterface(&state_interface_); + registerInterface(&effort_interface_); + registerInterface(&position_interface_); + } + + // Register the limits of the joint specified by joint_name and\ joint_handle. The limits are + // retrieved from the urdf_model. + // Return the joint's type, lower position limit, upper position limit, and effort limit. + void LWRHW::registerJointLimits(const std::string& joint_name, + const hardware_interface::JointHandle& joint_handle_effort, + const hardware_interface::JointHandle& joint_handle_position, + const hardware_interface::JointHandle& joint_handle_velocity, + const hardware_interface::JointHandle& joint_handle_stiffness, + const urdf::Model *const urdf_model, + double *const lower_limit, double *const upper_limit, + double *const lower_limit_stiffness, double *const upper_limit_stiffness, + double *const effort_limit) + { + *lower_limit = -std::numeric_limits::max(); + *upper_limit = std::numeric_limits::max(); + *lower_limit_stiffness = -std::numeric_limits::max(); + *upper_limit_stiffness = std::numeric_limits::max(); + *effort_limit = std::numeric_limits::max(); + + joint_limits_interface::JointLimits limits; + joint_limits_interface::JointLimits limits_stiffness; + bool has_limits = false; + bool has_limits_stiffness = false; + joint_limits_interface::SoftJointLimits soft_limits; + bool has_soft_limits = false; + + if (urdf_model != NULL) + { + const boost::shared_ptr urdf_joint = urdf_model->getJoint(joint_name); + const boost::shared_ptr urdf_joint_sitffness = urdf_model->getJoint(joint_name + std::string("_stiffness")); + if (urdf_joint != NULL) + { + // Get limits from the URDF file. + if (joint_limits_interface::getJointLimits(urdf_joint, limits)) + has_limits = true; + if (joint_limits_interface::getJointLimits(urdf_joint_sitffness, limits_stiffness)) + has_limits_stiffness = true; + if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) + has_soft_limits = true; + } + } + + if (!has_limits) + return; + + if (limits.has_position_limits) + { + *lower_limit = limits.min_position; + *upper_limit = limits.max_position; + } + if (limits.has_effort_limits) + *effort_limit = limits.max_effort; + + if (has_soft_limits) + { + const joint_limits_interface::EffortJointSoftLimitsHandle limits_handle_effort(joint_handle_effort, limits, soft_limits); + ej_limits_interface_.registerHandle(limits_handle_effort); + const joint_limits_interface::PositionJointSoftLimitsHandle limits_handle_position(joint_handle_position, limits, soft_limits); + pj_limits_interface_.registerHandle(limits_handle_position); + const joint_limits_interface::VelocityJointSoftLimitsHandle limits_handle_velocity(joint_handle_velocity, limits, soft_limits); + vj_limits_interface_.registerHandle(limits_handle_velocity); + + } + else + { + const joint_limits_interface::EffortJointSaturationHandle sat_handle_effort(joint_handle_effort, limits); + ej_sat_interface_.registerHandle(sat_handle_effort); + const joint_limits_interface::PositionJointSaturationHandle sat_handle_position(joint_handle_position, limits); + pj_sat_interface_.registerHandle(sat_handle_position); + const joint_limits_interface::VelocityJointSaturationHandle sat_handle_velocity(joint_handle_velocity, limits); + vj_sat_interface_.registerHandle(sat_handle_velocity); + } + + if (!has_limits_stiffness) + return; + + if (limits_stiffness.has_position_limits) + { + *lower_limit_stiffness = limits_stiffness.min_position; + *upper_limit_stiffness = limits_stiffness.max_position; + } + + const joint_limits_interface::PositionJointSaturationHandle sat_handle_stiffness(joint_handle_stiffness, limits_stiffness); + sj_sat_interface_.registerHandle(sat_handle_stiffness); + } + + void LWRHW::enforceLimits(ros::Duration period) + { + ej_sat_interface_.enforceLimits(period); + ej_limits_interface_.enforceLimits(period); + vj_sat_interface_.enforceLimits(period); + vj_limits_interface_.enforceLimits(period); + pj_sat_interface_.enforceLimits(period); + pj_limits_interface_.enforceLimits(period); + sj_sat_interface_.enforceLimits(period); + sj_limits_interface_.enforceLimits(period); + dj_sat_interface_.enforceLimits(period); + dj_limits_interface_.enforceLimits(period); + } + + // Get Transmissions from the URDF + bool LWRHW::parseTransmissionsFromURDF(const std::string& urdf_string) + { + std::vector transmissions; + + // Only *standard* transmission_interface are parsed + transmission_interface::TransmissionParser::parse(urdf_string, transmissions); + + // Now iterate and save only transmission from this robot + for (int j = 0; j < n_joints_; ++j) + { + // std::cout << "Check joint " << joint_names_[j] << std::endl; + std::vector::iterator it = transmissions.begin(); + for(; it != transmissions.end(); ++it) + { + // std::cout << "With transmission " << it->name_ << std::endl; + if (joint_names_[j].compare(it->joints_[0].name_) == 0) + { + transmissions_.push_back( *it ); + // std::cout << "Found a match for transmission " << it->name_ << std::endl; + } + } + } + + return true; + } + + // Init KDL stuff + bool LWRHW::initKDLdescription(const urdf::Model *const urdf_model) + { + // KDL code to compute f_dyn(q) + KDL::Tree kdl_tree; + if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree)) + { + ROS_ERROR("Failed to construct kdl tree"); + return false; + } + + std::cout << "LWR kinematic successfully parsed with " + << kdl_tree.getNrOfJoints() + << " joints, and " + << kdl_tree.getNrOfJoints() + << " segments." << std::endl; + + // Get the info from parameters + std::string root_name; + ros::param::get(std::string("/") + robot_namespace_ + std::string("/root"), root_name); + if( root_name.empty() ) + root_name = kdl_tree.getRootSegment()->first; // default + + std::string tip_name; + ros::param::get(std::string("/") + robot_namespace_ + std::string("/tip"), tip_name); + if( root_name.empty() ) + tip_name = robot_namespace_ + std::string("_7_link"); ; // default + + std::cout << "Using root: " << root_name << " and tip: " << tip_name << std::endl; + + // this depends on how the world frame is set, in all our setups, world has always positive z pointing up. + gravity_ = KDL::Vector::Zero(); + gravity_(2) = -9.81; + + // Extract the chain from the tree + if(!kdl_tree.getChain(root_name, tip_name, lwr_chain_)) + { + ROS_ERROR("Failed to get KDL chain from tree: "); + return false; + } + + ROS_INFO("Number of segments: %d", lwr_chain_.getNrOfSegments()); + ROS_INFO("Number of joints in chain: %d", lwr_chain_.getNrOfJoints()); + + f_dyn_solver_.reset(new KDL::ChainDynParam(lwr_chain_,gravity_)); + + joint_position_kdl_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + gravity_effort_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); + + return true; + } + + bool LWRHW::canSwitch(const std::list &start_list, const std::list &stop_list) const + { + std::vector desired_strategies; + + for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) + { + // If any of the controllers in the start list works on a velocity interface, the switch can't be done. + if( it->hardware_interface.compare( std::string("hardware_interface::VelocityJointInterface") ) == 0 ) + { + std::cout << "The given controllers to start work on a velocity joint interface, and this robot does not have such an interface." + << "The switch can't be done" << std::endl; + return false; + } + + if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) + { + // Debug + // std::cout << "One controller wants to work on hardware_interface::PositionJointInterface" << std::endl; + desired_strategies.push_back( JOINT_POSITION ); + } + else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) + { + // Debug + // std::cout << "One controller wants to work on hardware_interface::EffortJointInterface" << std::endl; + desired_strategies.push_back( JOINT_IMPEDANCE ); + } + else + { + // Debug + std::cout << "This controller does not use any command interface, so it is only sensing, no problem" << std::endl; + } + } + + if( desired_strategies.size() > 1 ) + { + std::cout << "OOPS! Currently we are using the JointCommandInterface to switch mode, this is not strictly correct. " + << "This is temporary until a joint_mode_controller is available (so you can have different interfaces available in different modes)" + << "Having said this, we do not support more than one controller that ones to act on any given JointCommandInterface" + << "and we can't switch" + << std::endl; + return false; + } + + return true; + } + + void LWRHW::doSwitch(const std::list &start_list, const std::list &stop_list) + { + // at this point, we now that there is only one controller that ones to command joints + ControlStrategy desired_strategy; + + // If any of the controllers in the start list works on a velocity interface, the switch can't be done. + for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) + { + if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) + { + std::cout << "Request to switch to hardware_interface::PositionJointInterface (JOINT_POSITION)" << std::endl; + desired_strategy = JOINT_POSITION; + break; + } + else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) + { + std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_IMPEDANCE)" << std::endl; + desired_strategy = JOINT_IMPEDANCE; + break; + } + } + + for (int j = 0; j < n_joints_; ++j) + { + ///semantic Zero + joint_position_command_[j] = joint_position_[j]; + joint_effort_command_[j] = 0.0; + + ///call setCommand once so that the JointLimitsInterface receive the correct value on their getCommand()! + try{ position_interface_.getHandle(joint_names_[j]).setCommand(joint_position_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + try{ effort_interface_.getHandle(joint_names_[j]).setCommand(joint_effort_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + + ///reset joint_limit_interfaces + pj_sat_interface_.reset(); + pj_limits_interface_.reset(); + } + } + + + std::cout << "ControlStrategy: " << getControlStrategy() << std::endl; +} diff --git a/lwr_hw/src/lwr_hw_real_node.cpp b/lwr_hw/src/lwr_hw_real_node.cpp index 948c29b..ec826f0 100644 --- a/lwr_hw/src/lwr_hw_real_node.cpp +++ b/lwr_hw/src/lwr_hw_real_node.cpp @@ -20,6 +20,38 @@ void quitRequested(int sig) g_quit = true; } +// Get the URDF XML from the parameter server +std::string getURDF(ros::NodeHandle &model_nh_, std::string param_name) +{ + std::string urdf_string; + std::string robot_description = "/robot_description"; + + // search and wait for robot_description on param server + while (urdf_string.empty()) + { + std::string search_param_name; + if (model_nh_.searchParam(param_name, search_param_name)) + { + ROS_INFO_ONCE_NAMED("LWRHWsim", "LWRHWsim plugin is waiting for model" + " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str()); + + model_nh_.getParam(search_param_name, urdf_string); + } + else + { + ROS_INFO_ONCE_NAMED("LWRHWsim", "LWRHWsim plugin is waiting for model" + " URDF in parameter [%s] on the ROS param server.", robot_description.c_str()); + + model_nh_.getParam(param_name, urdf_string); + } + + usleep(100000); + } + ROS_DEBUG_STREAM_NAMED("LWRHWsim", "Recieved urdf from param server, parsing..."); + + return urdf_string; +} + int main( int argc, char** argv ) { // initialize ROS @@ -35,7 +67,7 @@ int main( int argc, char** argv ) signal(SIGHUP, quitRequested); // create a node - ros::NodeHandle lwr_nh(""); + ros::NodeHandle lwr_nh; // get params or give default values int port; @@ -43,9 +75,12 @@ int main( int argc, char** argv ) lwr_nh.param("port", port, 49939); lwr_nh.param("ip", hintToRemoteHost, std::string("192.168.0.10") ); + std::string urdf_string = getURDF(lwr_nh, "/robot_description"); + // construct and start the real lwr lwr_hw::LWRHWreal lwr_robot; - lwr_robot.create(); + std::cout << "namespace: " << lwr_nh.getNamespace() << std::endl; + lwr_robot.create(std::string("lwr"), urdf_string); lwr_robot.setPort(port); lwr_robot.setIP(hintToRemoteHost); if(!lwr_robot.init()) @@ -98,4 +133,4 @@ int main( int argc, char** argv ) std::cerr<<"Bye!"<GetName(); // default } - // Get the robot simulation interface type - robot_hw_sim_type_str_ = "lwr_hw/LWRHWsim"; - ROS_DEBUG_STREAM_NAMED("loadThread","Using default plugin for LWRHWsim (none specified in URDF/SDF)\""<HasElement("robotParam")) + { + robot_description_ = sdf_->GetElement("robotParam")->Get(); + } + else + { + robot_description_ = "robot_description"; // default + } // Get the Gazebo simulation period ros::Duration gazebo_period(parent_model_->GetWorld()->GetPhysicsEngine()->GetMaxStepSize()); @@ -97,36 +104,32 @@ class LWRHWSimPlugin : public gazebo::ModelPlugin model_nh_ = ros::NodeHandle(robot_namespace_); ROS_INFO_NAMED("lwr_hw", "Starting lwr_hw plugin in namespace: %s", robot_namespace_.c_str()); - // Load the LWRHWsim abstraction to interface the controllers with the gazebo model - try - { - robot_hw_sim_.reset( new lwr_hw::LWRHWsim() ); - robot_hw_sim_->create(); - robot_hw_sim_->setParentModel(parent_model_); - if(!robot_hw_sim_->init()) - { - ROS_FATAL_NAMED("lwr_hw","Could not initialize robot simulation interface"); - return; - } - - std::cout << "CLAIMS IN PLUGIN: " << robot_hw_sim_->state_interface_.getClaims().size() << std::endl; - // Create the controller manager - ROS_INFO_STREAM_NAMED("ros_control_plugin","Loading controller_manager"); - controller_manager_.reset - (new controller_manager::ControllerManager(robot_hw_sim_.get(), model_nh_)); + // Read urdf from ros parameter server then + // setup actuators and mechanism control node. + // This call will block if ROS is not properly initialized. + const std::string urdf_string = getURDF(robot_description_); - // Listen to the update event. This event is broadcast every simulation iteration. - update_connection_ = - gazebo::event::Events::ConnectWorldUpdateBegin - (boost::bind(&LWRHWSimPlugin::Update, this)); - - } - catch(pluginlib::LibraryLoadException &ex) + // Load the LWRHWsim abstraction to interface the controllers with the gazebo model + robot_hw_sim_.reset( new lwr_hw::LWRHWsim() ); + robot_hw_sim_->create(robot_namespace_, urdf_string); + robot_hw_sim_->setParentModel(parent_model_); + if(!robot_hw_sim_->init()) { - ROS_FATAL_STREAM_NAMED("lwr_hw","Failed to create robot simulation interface loader: "< > robot_hw_sim_loader_; - // Node Handles - ros::NodeHandle model_nh_; // namespaces to robot name + ros::NodeHandle model_nh_; // Strings std::string robot_namespace_; + std::string robot_description_; // Robot simulator interface std::string robot_hw_sim_type_str_; @@ -198,6 +230,6 @@ class LWRHWSimPlugin : public gazebo::ModelPlugin }; // Register this plugin with the simulator -GZ_REGISTER_MODEL_PLUGIN(LWRHWSimPlugin); +GZ_REGISTER_MODEL_PLUGIN(LWRHWsimPlugin); } // namespace From 8fe33637cbef8ce1b457e982e7a77c052ac3b27e Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Sun, 5 Jul 2015 15:51:52 +0200 Subject: [PATCH 05/19] [single_lwr_example] - Updates in the package.xml's dependencies - Deleted the state_publisher.launch since gravity compensation is done differently - Changing all controller names to lowercase to differentiate from the types. --- .../launch/single_lwr.launch | 34 +++++++++---------- .../launch/state_publisher.launch | 11 ------ .../single_lwr_launch/package.xml | 4 --- .../single_lwr_robot/config/controllers.yaml | 31 +++++++---------- .../single_lwr_robot/config/hw_interface.yaml | 13 +++++++ .../single_lwr_robot/config/lwr_hw.yaml | 3 -- .../single_lwr_robot/package.xml | 5 +-- 7 files changed, 44 insertions(+), 57 deletions(-) delete mode 100644 single_lwr_example/single_lwr_launch/launch/state_publisher.launch create mode 100644 single_lwr_example/single_lwr_robot/config/hw_interface.yaml delete mode 100644 single_lwr_example/single_lwr_robot/config/lwr_hw.yaml diff --git a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch index a9b1ea9..354017a 100644 --- a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch +++ b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch @@ -10,34 +10,27 @@ - + - + + - - - - - + - - - - - [/lwr/joint_states] - - + + [/lwr/joint_states] + @@ -56,7 +49,8 @@ - + y + @@ -81,7 +75,10 @@ - + + + + @@ -94,11 +91,12 @@ - - + + + diff --git a/single_lwr_example/single_lwr_launch/launch/state_publisher.launch b/single_lwr_example/single_lwr_launch/launch/state_publisher.launch deleted file mode 100644 index 8b93cfd..0000000 --- a/single_lwr_example/single_lwr_launch/launch/state_publisher.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - \ No newline at end of file diff --git a/single_lwr_example/single_lwr_launch/package.xml b/single_lwr_example/single_lwr_launch/package.xml index aedd471..b4014d6 100644 --- a/single_lwr_example/single_lwr_launch/package.xml +++ b/single_lwr_example/single_lwr_launch/package.xml @@ -10,10 +10,6 @@ catkin - - kuka_lwr - - single_lwr_robot single_lwr_moveit diff --git a/single_lwr_example/single_lwr_robot/config/controllers.yaml b/single_lwr_example/single_lwr_robot/config/controllers.yaml index 91f3a34..a6af38c 100644 --- a/single_lwr_example/single_lwr_robot/config/controllers.yaml +++ b/single_lwr_example/single_lwr_robot/config/controllers.yaml @@ -28,13 +28,13 @@ lwr: - lwr_6_joint_stiffness ## OTHER CUSTOM CONTROLLERS LEFT HERE AS EXAMPLES - GravityCompensation: + gravity_compensation_controller: type: lwr_controllers/GravityCompensation root_name: lwr_base_link tip_name: lwr_7_link # Joint Impedance Controllers - JointImpedanceControl: + joint_impedance_controller: type: lwr_controllers/JointImpedanceController root_name: lwr_base_link tip_name: lwr_7_link @@ -42,32 +42,25 @@ lwr: damping_gains: .7 # Inverse Dynamics Controllers - InverseDynamicsControl: + inverse_dynamics_controller: type: lwr_controllers/InverseDynamicsController root_name: lwr_base_link tip_name: lwr_7_link # Computed Torque Controllers - ComputedTorqueControl: + computed_torque_controller: type: lwr_controllers/ComputedTorqueController root_name: lwr_base_link tip_name: lwr_7_link # One Task Inverse Kinematics - OneTaskInverseKinematics: + one_task_inverse_kinematics: type: lwr_controllers/OneTaskInverseKinematics root_name: lwr_base_link tip_name: lwr_7_link - pid_lwr_0_joint: {p: 250, i: 10, d: 30, i_clamp_min: -0.3, i_clamp_max: 0.3} - pid_lwr_1_joint: {p: 220, i: 10, d: 30, i_clamp_min: -0.3, i_clamp_max: 0.3} - pid_lwr_2_joint: {p: 150, i: 6, d: 20, i_clamp_min: -0.3, i_clamp_max: 0.3} - pid_lwr_3_joint: {p: 150, i: 5, d: 12, i_clamp_min: -0.3, i_clamp_max: 0.3} - pid_lwr_4_joint: {p: 90, i: 5, d: 10, i_clamp_min: -0.3, i_clamp_max: 0.3} - pid_lwr_5_joint: {p: 40, i: 5, d: 7, i_clamp_min: -0.3, i_clamp_max: 0.3} - pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # Multi Task Priority Inverse Kinematics - MultiTaskPriorityInverseKinematics: + multi_task_priority_inverse_kinematics: type: lwr_controllers/MultiTaskPriorityInverseKinematics root_name: lwr_base_link tip_name: lwr_7_link @@ -80,7 +73,7 @@ lwr: pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # One Task Inverse Dynamics JL - OneTaskInverseDynamicsJL: + one_task_inverse_dynamics_JL: type: lwr_controllers/OneTaskInverseDynamicsJL root_name: lwr_base_link tip_name: lwr_7_link @@ -93,7 +86,7 @@ lwr: pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # Multi Task Priority Inverse Dynamics - MultiTaskPriorityInverseDynamics: + multi_task_priority_inverse_dynamics: type: lwr_controllers/MultiTaskPriorityInverseDynamics root_name: lwr_base_link tip_name: lwr_7_link @@ -106,7 +99,7 @@ lwr: pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # Minimum Effort Inverse Dynamics - MinimumEffortInverseDynamics: + minimum_effort_inverse_dynamics: type: lwr_controllers/MinimumEffortInverseDynamics root_name: lwr_base_link tip_name: lwr_7_link @@ -119,7 +112,7 @@ lwr: pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # Backstepping Controller - BacksteppingController: + back_stepping_controller: type: lwr_controllers/BacksteppingController root_name: lwr_base_link tip_name: lwr_7_link @@ -132,7 +125,7 @@ lwr: pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # Dynamic Sliding Mode Controller - DynamicSlidingModeController: + dynamics_sliding_mode_controller: type: lwr_controllers/DynamicSlidingModeController root_name: lwr_base_link tip_name: lwr_7_link @@ -145,7 +138,7 @@ lwr: pid_lwr_6_joint: {p: 15, i: 2, d: 5, i_clamp_min: -0.3, i_clamp_max: 0.3} # Dynamic Sliding Mode Controller Task Space - DynamicSlidingModeControllerTaskSpace: + dynamics_sliding_mode_controller_task_space_controller: type: lwr_controllers/DynamicSlidingModeControllerTaskSpace root_name: lwr_base_link tip_name: lwr_7_link diff --git a/single_lwr_example/single_lwr_robot/config/hw_interface.yaml b/single_lwr_example/single_lwr_robot/config/hw_interface.yaml new file mode 100644 index 0000000..21c4cfc --- /dev/null +++ b/single_lwr_example/single_lwr_robot/config/hw_interface.yaml @@ -0,0 +1,13 @@ +lwr: + root: lwr_base_link + tip: lwr_7_link + # joints is not used, since with the robot name and urdf name conventions, the parsing is hardcoded + # but as a general solution, joint names could be loaded as well, like controllers do + joints: + - lwr_0_joint + - lwr_1_joint + - lwr_2_joint + - lwr_3_joint + - lwr_4_joint + - lwr_5_joint + - lwr_6_joint diff --git a/single_lwr_example/single_lwr_robot/config/lwr_hw.yaml b/single_lwr_example/single_lwr_robot/config/lwr_hw.yaml deleted file mode 100644 index 486704c..0000000 --- a/single_lwr_example/single_lwr_robot/config/lwr_hw.yaml +++ /dev/null @@ -1,3 +0,0 @@ -lwr: - root: lwr_base_link - tip: lwr_7_link \ No newline at end of file diff --git a/single_lwr_example/single_lwr_robot/package.xml b/single_lwr_example/single_lwr_robot/package.xml index b7f2d39..77ba803 100644 --- a/single_lwr_example/single_lwr_robot/package.xml +++ b/single_lwr_example/single_lwr_robot/package.xml @@ -11,8 +11,9 @@ catkin - - kuka_lwr + lwr_hw + lwr_description + lwr_controllers From 1b3490bf103053503d33ffb8a0bbf64c1d1c2d4c Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Sun, 5 Jul 2015 15:55:45 +0200 Subject: [PATCH 06/19] [lwr_controllers] Some directions to where lwr_controllers should go until a ImpedanceJointInterface (for full exposal of FRI values) or joint_mode_controller (see https://github.com/pal-robotics-forks/ros_controllers/pull/41), or to allow multiple command interfaces for a resource? Too many options ! --- .../lwr_controllers/gravity_compensation.h | 12 +- .../one_task_inverse_kinematics.h | 18 +- lwr_controllers/src/gravity_compensation.cpp | 42 +-- .../src/one_task_inverse_kinematics.cpp | 310 +++++++++--------- 4 files changed, 190 insertions(+), 192 deletions(-) diff --git a/lwr_controllers/include/lwr_controllers/gravity_compensation.h b/lwr_controllers/include/lwr_controllers/gravity_compensation.h index bc1cd04..cf2eae5 100644 --- a/lwr_controllers/include/lwr_controllers/gravity_compensation.h +++ b/lwr_controllers/include/lwr_controllers/gravity_compensation.h @@ -8,26 +8,26 @@ namespace lwr_controllers { - class GravityCompensation: public controller_interface::KinematicChainControllerBase + class GravityCompensation: public controller_interface::KinematicChainControllerBase { public: GravityCompensation(); ~GravityCompensation(); - bool init(hardware_interface::PositionJointInterface *robot, ros::NodeHandle &n); + bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); void starting(const ros::Time& time); void update(const ros::Time& time, const ros::Duration& period); void stopping(const ros::Time& time); - private: + // private: - std::vector previous_stiffness_; /// stiffness before activating controller + // std::vector previous_stiffness_; /// stiffness before activating controller // hack required as long as there is separate position handle for stiffness - std::vector joint_stiffness_handles_; + // std::vector joint_stiffness_handles_; - const static float DEFAULT_STIFFNESS = 0.01; + // const static float DEFAULT_STIFFNESS = 0.01; }; } diff --git a/lwr_controllers/include/lwr_controllers/one_task_inverse_kinematics.h b/lwr_controllers/include/lwr_controllers/one_task_inverse_kinematics.h index 9a56f7e..17a102c 100644 --- a/lwr_controllers/include/lwr_controllers/one_task_inverse_kinematics.h +++ b/lwr_controllers/include/lwr_controllers/one_task_inverse_kinematics.h @@ -1,14 +1,11 @@ #ifndef LWR_CONTROLLERS__ONE_TASK_INVERSE_KINEMATICS_H #define LWR_CONTROLLERS__ONE_TASK_INVERSE_KINEMATICS_H -#include "PIDKinematicChainControllerBase.h" -#include -#include +#include "KinematicChainControllerBase.h" +#include "lwr_controllers/PoseRPY.h" -#include #include - -#include +#include #include #include @@ -20,13 +17,13 @@ namespace lwr_controllers { - class OneTaskInverseKinematics: public controller_interface::PIDKinematicChainControllerBase + class OneTaskInverseKinematics: public controller_interface::KinematicChainControllerBase { public: OneTaskInverseKinematics(); ~OneTaskInverseKinematics(); - bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); + bool init(hardware_interface::PositionJointInterface *robot, ros::NodeHandle &n); void starting(const ros::Time& time); void update(const ros::Time& time, const ros::Duration& period); void command(const lwr_controllers::PoseRPY::ConstPtr &msg); @@ -40,7 +37,7 @@ namespace lwr_controllers KDL::Twist x_err_; - KDL::JntArray tau_cmd_; + KDL::JntArray q_cmd_; // computed set points KDL::Jacobian J_; //Jacobian @@ -58,12 +55,9 @@ namespace lwr_controllers int cmd_flag_; boost::scoped_ptr jnt_to_jac_solver_; - boost::scoped_ptr id_solver_; boost::scoped_ptr fk_pos_solver_; boost::scoped_ptr ik_vel_solver_; boost::scoped_ptr ik_pos_solver_; - - std::vector PIDs_; }; } diff --git a/lwr_controllers/src/gravity_compensation.cpp b/lwr_controllers/src/gravity_compensation.cpp index b087ac9..13e42f1 100644 --- a/lwr_controllers/src/gravity_compensation.cpp +++ b/lwr_controllers/src/gravity_compensation.cpp @@ -8,29 +8,29 @@ namespace lwr_controllers GravityCompensation::GravityCompensation() {} GravityCompensation::~GravityCompensation() {} - bool GravityCompensation::init(hardware_interface::PositionJointInterface *robot, ros::NodeHandle &n) + bool GravityCompensation::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n) { - KinematicChainControllerBase::init(robot, n); + KinematicChainControllerBase::init(robot, n); // find stiffness (dummy) joints; this is necessary until proper position/stiffness/damping interface exists - for(std::vector::const_iterator it = kdl_chain_.segments.begin(); it != kdl_chain_.segments.end(); ++it) - { - joint_stiffness_handles_.push_back(robot->getHandle(it->getJoint().getName()+"_stiffness")); - } + // for(std::vector::const_iterator it = kdl_chain_.segments.begin(); it != kdl_chain_.segments.end(); ++it) + // { + // joint_stiffness_handles_.push_back(robot->getHandle(it->getJoint().getName()+"_stiffness")); + // } - ROS_DEBUG("found %lu stiffness handles", joint_stiffness_handles_.size()); + // ROS_DEBUG("found %lu stiffness handles", joint_stiffness_handles_.size()); - previous_stiffness_.resize(joint_stiffness_handles_.size()); + // previous_stiffness_.resize(joint_stiffness_handles_.size()); - return true; + return true; } void GravityCompensation::starting(const ros::Time& time) { - for(size_t i=0; i::init(robot, n); - - jnt_to_jac_solver_.reset(new KDL::ChainJntToJacSolver(kdl_chain_)); - id_solver_.reset(new KDL::ChainDynParam(kdl_chain_,gravity_)); - fk_pos_solver_.reset(new KDL::ChainFkSolverPos_recursive(kdl_chain_)); - ik_vel_solver_.reset(new KDL::ChainIkSolverVel_pinv(kdl_chain_)); - ik_pos_solver_.reset(new KDL::ChainIkSolverPos_NR_JL(kdl_chain_,joint_limits_.min,joint_limits_.max,*fk_pos_solver_,*ik_vel_solver_)); - - tau_cmd_.resize(kdl_chain_.getNrOfJoints()); - J_.resize(kdl_chain_.getNrOfJoints()); - - sub_command_ = nh_.subscribe("command", 1, &OneTaskInverseKinematics::command, this); - - return true; - } - - void OneTaskInverseKinematics::starting(const ros::Time& time) - { - // get joint positions - for(int i=0; i < joint_handles_.size(); i++) - { - joint_msr_states_.q(i) = joint_handles_[i].getPosition(); - joint_msr_states_.qdot(i) = joint_handles_[i].getVelocity(); - joint_des_states_.q(i) = joint_msr_states_.q(i); - } - - // computing forward kinematics - fk_pos_solver_->JntToCart(joint_msr_states_.q,x_); - - //Desired posture - x_des_ = x_; - - cmd_flag_ = 0; - } - - void OneTaskInverseKinematics::update(const ros::Time& time, const ros::Duration& period) - { - - // get joint positions - for(int i=0; i < joint_handles_.size(); i++) - { - joint_msr_states_.q(i) = joint_handles_[i].getPosition(); - joint_msr_states_.qdot(i) = joint_handles_[i].getVelocity(); - } - - if (cmd_flag_) - { - // computing Jacobian - jnt_to_jac_solver_->JntToJac(joint_msr_states_.q,J_); - - // computing J_pinv_ - pseudo_inverse(J_.data,J_pinv_); - - // computing forward kinematics - fk_pos_solver_->JntToCart(joint_msr_states_.q,x_); - - // end-effector position/orientation error - x_err_.vel = x_des_.p - x_.p; - - // getting quaternion from rotation matrix - x_.M.GetQuaternion(quat_curr_.v(0),quat_curr_.v(1),quat_curr_.v(2),quat_curr_.a); - x_des_.M.GetQuaternion(quat_des_.v(0),quat_des_.v(1),quat_des_.v(2),quat_des_.a); - - skew_symmetric(quat_des_.v,skew_); - - for (int i = 0; i < skew_.rows(); i++) - { - v_temp_(i) = 0.0; - for (int k = 0; k < skew_.cols(); k++) - v_temp_(i) += skew_(i,k)*(quat_curr_.v(k)); - } - - x_err_.rot = quat_curr_.a*quat_des_.v - quat_des_.a*quat_curr_.v - v_temp_; - - // computing q_dot - for (int i = 0; i < J_pinv_.rows(); i++) - { - joint_des_states_.qdot(i) = 0.0; - for (int k = 0; k < J_pinv_.cols(); k++) - joint_des_states_.qdot(i) += J_pinv_(i,k)*x_err_(k); //removed scaling factor of .7 + OneTaskInverseKinematics::OneTaskInverseKinematics() {} + OneTaskInverseKinematics::~OneTaskInverseKinematics() {} + + bool OneTaskInverseKinematics::init(hardware_interface::PositionJointInterface *robot, ros::NodeHandle &n) + { + if( !(KinematicChainControllerBase::init(robot, n)) ) + { + ROS_ERROR("Couldn't initilize OneTaskInverseKinematics controller."); + return false; + } + + jnt_to_jac_solver_.reset(new KDL::ChainJntToJacSolver(kdl_chain_)); + fk_pos_solver_.reset(new KDL::ChainFkSolverPos_recursive(kdl_chain_)); + ik_vel_solver_.reset(new KDL::ChainIkSolverVel_pinv(kdl_chain_)); + ik_pos_solver_.reset(new KDL::ChainIkSolverPos_NR_JL(kdl_chain_,joint_limits_.min,joint_limits_.max,*fk_pos_solver_,*ik_vel_solver_)); + + q_cmd_.resize(kdl_chain_.getNrOfJoints()); + J_.resize(kdl_chain_.getNrOfJoints()); + + // get joint positions + for(int i=0; i < joint_handles_.size(); i++) + { + joint_msr_states_.q(i) = joint_handles_[i].getPosition(); + joint_msr_states_.qdot(i) = joint_handles_[i].getVelocity(); + joint_des_states_.q(i) = joint_msr_states_.q(i); + } + + // computing forward kinematics + fk_pos_solver_->JntToCart(joint_msr_states_.q, x_); + + //Desired posture is the current one + x_des_ = x_; + + cmd_flag_ = 0; + + sub_command_ = nh_.subscribe("command", 1, &OneTaskInverseKinematics::command, this); + + return true; + } + + void OneTaskInverseKinematics::starting(const ros::Time& time) + { + + } + + void OneTaskInverseKinematics::update(const ros::Time& time, const ros::Duration& period) + { + + // get joint positions + for(int i=0; i < joint_handles_.size(); i++) + { + joint_msr_states_.q(i) = joint_handles_[i].getPosition(); + } + + if (cmd_flag_) + { + // computing Jacobian + jnt_to_jac_solver_->JntToJac(joint_msr_states_.q, J_); + + // computing J_pinv_ + pseudo_inverse(J_.data, J_pinv_); + + // computing forward kinematics + fk_pos_solver_->JntToCart(joint_msr_states_.q, x_); + + // end-effector position error + x_err_.vel = x_des_.p - x_.p; + + // getting quaternion from rotation matrix + x_.M.GetQuaternion(quat_curr_.v(0),quat_curr_.v(1),quat_curr_.v(2),quat_curr_.a); + x_des_.M.GetQuaternion(quat_des_.v(0),quat_des_.v(1),quat_des_.v(2),quat_des_.a); + + skew_symmetric(quat_des_.v, skew_); + + for (int i = 0; i < skew_.rows(); i++) + { + v_temp_(i) = 0.0; + for (int k = 0; k < skew_.cols(); k++) + v_temp_(i) += skew_(i,k)*(quat_curr_.v(k)); + } + + // end-effector orientation error + x_err_.rot = quat_curr_.a*quat_des_.v - quat_des_.a*quat_curr_.v - v_temp_; + + // computing q_dot + for (int i = 0; i < J_pinv_.rows(); i++) + { + joint_des_states_.qdot(i) = 0.0; + for (int k = 0; k < J_pinv_.cols(); k++) + joint_des_states_.qdot(i) += J_pinv_(i,k)*x_err_(k); //removed scaling factor of .7 - } - - // integrating q_dot -> getting q (Euler method) - for (int i = 0; i < joint_handles_.size(); i++) - joint_des_states_.q(i) += period.toSec()*joint_des_states_.qdot(i); - - // joint limits saturation - for (int i =0; i < joint_handles_.size(); i++) - { - if (joint_des_states_.q(i) < joint_limits_.min(i)) - joint_des_states_.q(i) = joint_limits_.min(i); - if (joint_des_states_.q(i) > joint_limits_.max(i)) - joint_des_states_.q(i) = joint_limits_.max(i); - } - - if (Equal(x_,x_des_,0.005)) - { - ROS_INFO("On target"); - cmd_flag_ = 0; - } - } - - // set controls for joints - for (int i = 0; i < joint_handles_.size(); i++) - { - tau_cmd_(i) = PIDs_[i].computeCommand(joint_des_states_.q(i) - joint_msr_states_.q(i),period); - joint_handles_[i].setCommand(tau_cmd_(i)); - } - } - - void OneTaskInverseKinematics::command(const lwr_controllers::PoseRPY::ConstPtr &msg) - { - KDL::Frame frame_des_; - - switch(msg->id) - { - case 0: - frame_des_ = KDL::Frame( - KDL::Rotation::RPY(msg->orientation.roll, - msg->orientation.pitch, - msg->orientation.yaw), - KDL::Vector(msg->position.x, - msg->position.y, - msg->position.z)); - break; - - case 1: // position only - frame_des_ = KDL::Frame( - KDL::Vector(msg->position.x, - msg->position.y, - msg->position.z)); - break; - - case 2: // orientation only - frame_des_ = KDL::Frame( - KDL::Rotation::RPY(msg->orientation.roll, - msg->orientation.pitch, - msg->orientation.yaw)); - break; - - default: - ROS_INFO("Wrong message ID"); - return; - } - - x_des_ = frame_des_; - cmd_flag_ = 1; - } + } + + // integrating q_dot -> getting q (Euler method) + for (int i = 0; i < joint_handles_.size(); i++) + joint_des_states_.q(i) += period.toSec()*joint_des_states_.qdot(i); + + // joint limits saturation + for (int i =0; i < joint_handles_.size(); i++) + { + if (joint_des_states_.q(i) < joint_limits_.min(i)) + joint_des_states_.q(i) = joint_limits_.min(i); + if (joint_des_states_.q(i) > joint_limits_.max(i)) + joint_des_states_.q(i) = joint_limits_.max(i); + } + + if (Equal(x_, x_des_, 0.005)) + { + ROS_INFO("On target"); + cmd_flag_ = 0; + } + } + + // set controls for joints + for (int i = 0; i < joint_handles_.size(); i++) + { + joint_handles_[i].setCommand(q_cmd_(i)); + } + } + + void OneTaskInverseKinematics::command(const lwr_controllers::PoseRPY::ConstPtr &msg) + { + KDL::Frame frame_des_; + + switch(msg->id) + { + case 0: + frame_des_ = KDL::Frame( + KDL::Rotation::RPY(msg->orientation.roll, + msg->orientation.pitch, + msg->orientation.yaw), + KDL::Vector(msg->position.x, + msg->position.y, + msg->position.z)); + break; + + case 1: // position only + frame_des_ = KDL::Frame( + KDL::Vector(msg->position.x, + msg->position.y, + msg->position.z)); + break; + + case 2: // orientation only + frame_des_ = KDL::Frame( + KDL::Rotation::RPY(msg->orientation.roll, + msg->orientation.pitch, + msg->orientation.yaw)); + break; + + default: + ROS_INFO("Wrong message ID"); + return; + } + + x_des_ = frame_des_; + cmd_flag_ = 1; + } } PLUGINLIB_EXPORT_CLASS(lwr_controllers::OneTaskInverseKinematics, controller_interface::ControllerBase) From 76f88421852dedb290a32441486fb71d8088955e Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Mon, 6 Jul 2015 17:46:23 +0200 Subject: [PATCH 07/19] [lwr_hw] Several fixes * unisgned int -> int in n_joints_ loops * Fixes in the KRL script * Changing name of files to reflect the used low-level interface (hence the lwr_hw.launch and kuka_lwr.gazebo.xacro as well) --- lwr_description/model/kuka_lwr.gazebo.xacro | 2 +- lwr_hw/include/lwr_hw/lwr_hw.h | 2 +- .../lwr_hw/{lwr_hw_real.hpp => lwr_hw_fri.hpp} | 0 .../lwr_hw/{lwr_hw_sim.hpp => lwr_hw_gazebo.hpp} | 0 lwr_hw/krl/ros_control.src | 12 ++++++------ lwr_hw/launch/lwr_hw.launch | 2 +- lwr_hw/src/lwr_hw.cpp | 2 +- .../{lwr_hw_real_node.cpp => lwr_hw_fri_node.cpp} | 0 ...wr_hw_sim_plugin.cpp => lwr_hw_gazebo_plugin.cpp} | 0 9 files changed, 10 insertions(+), 10 deletions(-) rename lwr_hw/include/lwr_hw/{lwr_hw_real.hpp => lwr_hw_fri.hpp} (100%) rename lwr_hw/include/lwr_hw/{lwr_hw_sim.hpp => lwr_hw_gazebo.hpp} (100%) rename lwr_hw/src/{lwr_hw_real_node.cpp => lwr_hw_fri_node.cpp} (100%) rename lwr_hw/src/{lwr_hw_sim_plugin.cpp => lwr_hw_gazebo_plugin.cpp} (100%) diff --git a/lwr_description/model/kuka_lwr.gazebo.xacro b/lwr_description/model/kuka_lwr.gazebo.xacro index 0ad8a05..3aaa5a6 100644 --- a/lwr_description/model/kuka_lwr.gazebo.xacro +++ b/lwr_description/model/kuka_lwr.gazebo.xacro @@ -4,7 +4,7 @@ - + ${name} diff --git a/lwr_hw/include/lwr_hw/lwr_hw.h b/lwr_hw/include/lwr_hw/lwr_hw.h index 9164c6e..a82cf0e 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw.h +++ b/lwr_hw/include/lwr_hw/lwr_hw.h @@ -61,7 +61,7 @@ class LWRHW : public hardware_interface::RobotHW virtual void write(ros::Time time, ros::Duration period) = 0; // get/set control method - bool setControlStrategy( ControlStrategy strategy){current_strategy_ = strategy;}; // CHECK CONFLICT + void setControlStrategy( ControlStrategy strategy){current_strategy_ = strategy;}; // CHECK CONFLICT ControlStrategy getControlStrategy(){ return current_strategy_;}; // Hardware interfaces diff --git a/lwr_hw/include/lwr_hw/lwr_hw_real.hpp b/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp similarity index 100% rename from lwr_hw/include/lwr_hw/lwr_hw_real.hpp rename to lwr_hw/include/lwr_hw/lwr_hw_fri.hpp diff --git a/lwr_hw/include/lwr_hw/lwr_hw_sim.hpp b/lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp similarity index 100% rename from lwr_hw/include/lwr_hw/lwr_hw_sim.hpp rename to lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp diff --git a/lwr_hw/krl/ros_control.src b/lwr_hw/krl/ros_control.src index 31a448b..e4d7b05 100644 --- a/lwr_hw/krl/ros_control.src +++ b/lwr_hw/krl/ros_control.src @@ -48,14 +48,14 @@ DEF ros_control( ) ; 1 -> friStart() was called ; 0 -> fiStop() was called ; ---------------------------------------------- - ; $FRI_FROM_INT[1] (not used so far) + ; $FRI_FRM_INT[1] (not used so far) ; This value is used to call the remote that ; either friStart() or friStop() was called ; ; 1 -> friStart() was called ; 0 -> fiStop() was called ; ---------------------------------------------- - ; $FRI_FROM_INT[16] AND $FRI_TO_INT[16] + ; $FRI_FRM_INT[16] AND $FRI_TO_INT[16] ; ; This values are used for the handshake ; ---------------------------------------------- @@ -66,7 +66,7 @@ DEF ros_control( ) retVal = friStop() retVal = friClose() - ;Reset FRI values, although not used + ;Reset FRI values FOR I = 1 TO 16 $FRI_TO_INT[i] = 0 $FRI_TO_REA[i] = 0.0 @@ -79,7 +79,7 @@ DEF ros_control( ) ; Stay at the same position PTP $AXIS_ACT_MES - ;Setting limis for impedance mode to test that the model is Ok + ;Start with position control $stiffness.strategy = 10 $stiffness.commit = true ;ENDFOLD (init) @@ -100,10 +100,10 @@ retVal=friOpen(2) ;FOLD Handshake ;Wait for the ROS node to salute - WAIT FOR ($FRI_FROM_INT[16] == 1) + WAIT FOR ($FRI_FRM_INT[16] == 1) ;Be polite and salute back - $FRI_TO_INT[16] == $FRI_FROM_INT[16] + $FRI_TO_INT[16] = $FRI_FRM_INT[16] $MSG_T.KEY[] = "Done handshake!" $MSG_T.VALID=TRUE WAIT FOR ($MSG_T.VALID == FALSE) diff --git a/lwr_hw/launch/lwr_hw.launch b/lwr_hw/launch/lwr_hw.launch index 564ff46..dd9a898 100644 --- a/lwr_hw/launch/lwr_hw.launch +++ b/lwr_hw/launch/lwr_hw.launch @@ -11,6 +11,6 @@ - + diff --git a/lwr_hw/src/lwr_hw.cpp b/lwr_hw/src/lwr_hw.cpp index 6962ca2..8ef983a 100644 --- a/lwr_hw/src/lwr_hw.cpp +++ b/lwr_hw/src/lwr_hw.cpp @@ -94,7 +94,7 @@ namespace lwr_hw } // Initialize values - for(unsigned int j=0; j < n_joints_; j++) + for(int j=0; j < n_joints_; j++) { // Check that this transmission has one joint if(transmissions[j].joints_.size() == 0) diff --git a/lwr_hw/src/lwr_hw_real_node.cpp b/lwr_hw/src/lwr_hw_fri_node.cpp similarity index 100% rename from lwr_hw/src/lwr_hw_real_node.cpp rename to lwr_hw/src/lwr_hw_fri_node.cpp diff --git a/lwr_hw/src/lwr_hw_sim_plugin.cpp b/lwr_hw/src/lwr_hw_gazebo_plugin.cpp similarity index 100% rename from lwr_hw/src/lwr_hw_sim_plugin.cpp rename to lwr_hw/src/lwr_hw_gazebo_plugin.cpp From 51566200311cdbfd64da4c462992e15b69ae07c7 Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Mon, 6 Jul 2015 17:54:59 +0200 Subject: [PATCH 08/19] Re-fixing names in includes. --- lwr_hw/src/lwr_hw_fri_node.cpp | 3 +-- lwr_hw/src/lwr_hw_gazebo_plugin.cpp | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/lwr_hw/src/lwr_hw_fri_node.cpp b/lwr_hw/src/lwr_hw_fri_node.cpp index ec826f0..2de7870 100644 --- a/lwr_hw/src/lwr_hw_fri_node.cpp +++ b/lwr_hw/src/lwr_hw_fri_node.cpp @@ -4,14 +4,13 @@ #include #include #include -#include // ROS headers #include #include // the lwr hw real interface -#include "lwr_hw/lwr_hw_real.hpp" +#include "lwr_hw/lwr_hw_fri.hpp" bool g_quit = false; diff --git a/lwr_hw/src/lwr_hw_gazebo_plugin.cpp b/lwr_hw/src/lwr_hw_gazebo_plugin.cpp index ae6df08..898440a 100644 --- a/lwr_hw/src/lwr_hw_gazebo_plugin.cpp +++ b/lwr_hw/src/lwr_hw_gazebo_plugin.cpp @@ -13,7 +13,7 @@ #include // LWR sim class -#include "lwr_hw/lwr_hw_sim.hpp" +#include "lwr_hw/lwr_hw_gazebo.hpp" namespace lwr_hw { From 31715a8e7b9ce803732e7c281dfe60501a08f8e8 Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Wed, 8 Jul 2015 11:28:30 +0200 Subject: [PATCH 09/19] [lwr_hw] - Update, switch works fine but still need to work on the calling functions. - Initial work in supporting Standford library (fork https://github.com/iocroblab/fril) --- .gitignore | 4 + lwr_hw/CMakeLists.txt | 60 ++++-- lwr_hw/include/lwr_hw/lwr_hw.h | 7 +- lwr_hw/include/lwr_hw/lwr_hw_fri.hpp | 201 ++++++++++---------- lwr_hw/include/lwr_hw/lwr_hw_fril.hpp | 233 ++++++++++++++++++++++++ lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp | 16 +- lwr_hw/krl/ros_control.src | 191 ++++++++++--------- lwr_hw/launch/lwr_hw.launch | 9 + lwr_hw/src/lwr_hw.cpp | 1 - lwr_hw/src/lwr_hw_fri_node.cpp | 22 +-- lwr_hw/src/lwr_hw_fril_node.cpp | 132 ++++++++++++++ lwr_hw/src/lwr_hw_gazebo_plugin.cpp | 4 +- 12 files changed, 638 insertions(+), 242 deletions(-) create mode 100644 lwr_hw/include/lwr_hw/lwr_hw_fril.hpp create mode 100644 lwr_hw/src/lwr_hw_fril_node.cpp diff --git a/.gitignore b/.gitignore index cd7a158..ba1c5e2 100644 --- a/.gitignore +++ b/.gitignore @@ -26,3 +26,7 @@ ros/kuka_lwr/lwr_moveit/default_warehouse_mongo_db/journal/prealloc.* build BUILD Build + +# Avoid FRILibrary +FRILibrary +fril.zip \ No newline at end of file diff --git a/lwr_hw/CMakeLists.txt b/lwr_hw/CMakeLists.txt index 3a5bcd2..62e5d4b 100644 --- a/lwr_hw/CMakeLists.txt +++ b/lwr_hw/CMakeLists.txt @@ -21,9 +21,6 @@ find_package(catkin REQUIRED COMPONENTS gazebo_ros ) -# Depend on system install of Gazebo -find_package(gazebo REQUIRED) - add_definitions (-fpermissive -std=c++11) catkin_package( @@ -43,7 +40,7 @@ catkin_package( transmission_interface gazebo_ros INCLUDE_DIRS include - LIBRARIES ${PROJECT_NAME} lwr_hw_sim_plugin friremote + LIBRARIES ${PROJECT_NAME} lwr_hw_gazebo_plugin friremote frilremote DEPENDS gazebo ) @@ -54,9 +51,7 @@ catkin_package( include_directories(include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS} - ${GAZEBO_INCLUDE_DIRS} ) -link_directories(${GAZEBO_LIBRARY_DIRS}) ## LWR HW BASE CLASS TO RULE'EM ALL add_library(${PROJECT_NAME} @@ -68,34 +63,65 @@ target_link_libraries(${PROJECT_NAME} ) ## REAL -## FRI library +# KUKA FRI library add_library(friremote src/fri/friremote.cpp src//fri/friudp.cpp ) -## lwr hw real node -add_executable(lwr_hw_node src/lwr_hw_real_node.cpp - include/${PROJECT_NAME}/lwr_hw_real.hpp +# lwr hw fri node +add_executable(lwr_hw_fri_node src/lwr_hw_fri_node.cpp + include/${PROJECT_NAME}/lwr_hw_fri.hpp ) -add_dependencies(lwr_hw_node +add_dependencies(lwr_hw_fri_node friremote ${PROJECT_NAME} ) -target_link_libraries(lwr_hw_node +target_link_libraries(lwr_hw_fri_node friremote ${PROJECT_NAME} ${catkin_LIBRARIES} ) +# Standford FRILibrary support in PROGRESS +message(WARNING "ATTENTION: This project supports the fork of the Standford library found in https://github.com/iocroblab/fril, and install the libraries in your catkin workspace, not in the system") +include(ExternalProject) +ExternalProject_Add(FRILibrary + GIT_REPOSITORY https://github.com/iocroblab/fril.git + GIT_TAG a10695fad32ba8315817c42020e2dbc66f4505dd + BUILD_COMMAND make + BUILD_IN_SOURCE 1 + CONFIGURE_COMMAND cmake -DCMAKE_INSTALL_PREFIX=${CATKIN_DEVEL_PREFIX} + INSTALL_COMMAND make install +) + +# lwr hw fril node +include_directories(${CATKIN_DEVEL_PREFIX}/include/fril) +link_directories(${CATKIN_DEVEL_PREFIX}/lib) +add_executable(lwr_hw_fril_node src/lwr_hw_fril_node.cpp + include/${PROJECT_NAME}/lwr_hw_fril.hpp +) +add_dependencies(lwr_hw_fril_node + FRILibrary + ${PROJECT_NAME} +) +target_link_libraries(lwr_hw_fril_node + fril + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + ## SIMULATION -# lwr hw sim gazebo plugin -add_library(lwr_hw_sim_plugin src/lwr_hw_sim_plugin.cpp - include/${PROJECT_NAME}/lwr_hw_sim.hpp +# lwr hw sim gazebo plugin +find_package(gazebo REQUIRED) +include_directories(${GAZEBO_INCLUDE_DIRS}) +link_directories(${GAZEBO_LIBRARY_DIRS}) +add_library(lwr_hw_gazebo_plugin src/lwr_hw_gazebo_plugin.cpp + include/${PROJECT_NAME}/lwr_hw_gazebo.hpp ) -add_dependencies(lwr_hw_sim_plugin +add_dependencies(lwr_hw_gazebo_plugin ${PROJECT_NAME} ) -target_link_libraries(lwr_hw_sim_plugin +target_link_libraries(lwr_hw_gazebo_plugin ${PROJECT_NAME} ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES} diff --git a/lwr_hw/include/lwr_hw/lwr_hw.h b/lwr_hw/include/lwr_hw/lwr_hw.h index a82cf0e..34e3a53 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw.h +++ b/lwr_hw/include/lwr_hw/lwr_hw.h @@ -49,9 +49,12 @@ class LWRHW : public hardware_interface::RobotHW // control strategies // JOINT_POSITION -> strategy 10 -> triggered with PoitionJointInterface // CARTESIAN_IMPEDANCE -> strategy 20 (not implemented) - // JOINT_IMPEDANCE -> strategy 30 -> triggered with EffortJointInterface + // JOINT_IMPEDANCE -> strategy 30 -> triggered with (ToDo) ImpedanceJointInterface + // JOINT_EFFORT -> strategy 30 with special configuration, triggered with EffortJointInterface + // JOINT_STIFFNESS -> strategy 30 with special configuration, trigered with (ToDo) StiffnessJointInterface // GRAVITY_COMPENSATION -> (not implemented, achieved with low stiffness) - enum ControlStrategy {JOINT_POSITION = 10, CARTESIAN_IMPEDANCE = 20, JOINT_IMPEDANCE = 30, GRAVITY_COMPENSATION = 40}; + // __Note__: StiffnessJointInterface + EffortJointInterface = ImpedanceJointInterface + enum ControlStrategy {JOINT_POSITION = 10, CARTESIAN_IMPEDANCE = 20, JOINT_IMPEDANCE = 30, JOINT_EFFORT = 40, JOINT_STIFFNESS = 50, GRAVITY_COMPENSATION = 50}; virtual bool canSwitch(const std::list &start_list, const std::list &stop_list) const; virtual void doSwitch(const std::list &start_list, const std::list &stop_list); diff --git a/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp b/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp index 7fe5c6c..44afb9a 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp +++ b/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp @@ -9,6 +9,7 @@ #include #include #include +#include #include "fri/friudp.h" #include "fri/friremote.h" @@ -17,16 +18,13 @@ namespace lwr_hw { -class LWRHWreal : public LWRHW +class LWRHWFRI : public LWRHW { public: - LWRHWreal() : LWRHW() {} - ~LWRHWreal() {} - - void stop(){return;}; - void set_mode(){return;}; + LWRHWFRI() : LWRHW() {} + ~LWRHWFRI() { stopKRCComm_ = true; KRCCommThread_.get()->join();} void setPort(int port){port_ = port; port_set_ = true;}; void setIP(std::string hintToRemoteHost){hintToRemoteHost_ = hintToRemoteHost; ip_set_ = true;}; @@ -51,40 +49,19 @@ class LWRHWreal : public LWRHW << FRI_MAJOR_VERSION << "." << FRI_SUB_VERSION << "." <getState() == FRI_STATE_OFF ) { - while( device_->getState() != FRI_STATE_MON ) - { - std::cout << "Please, start the KRL script now." << std::endl; - usleep(1000000); - } + std::cout << "Please, start the KRL script now." << std::endl; } + KRCCommThread_.reset( new std::thread( &LWRHWFRI::KRCCommThreadCallback,this ) ); - std::cout << "Performing handshake with the KRC unit..." << std::endl; + startFRI(); - // salute KRL - device_->setToKRLInt(15,1); - // be polite and wait for KRL to salute back - while( device_->getFrmKRLInt(15) == 1 ) - { - device_->doDataExchange(); - } - - std::cout << "Done handshake." << std::endl; - - // wait for good quality - while ( device_->getQuality() >= FRI_QUALITY_OK) {} - - // wait for FRI to start - while ( device_->getState() != FRI_STATE_CMD) {} + std::cout << "Ready, FRI has been started!" << std::endl; + std::cout << "FRI Status:\n" << device_->getMsrBuf().intf << std::endl; - // debug - // std::cout << "LWR Status:\n" << device_->getMsrBuf().intf << std::endl; - - std::cout << "FRI has been started!" << std::endl; return true; } @@ -106,67 +83,45 @@ class LWRHWreal : public LWRHW { enforceLimits(period); - // ensure the robot is powered and it is in control mode, almost like the isMachineOk() of Standford - if ( device_->isPowerOn() && (device_->getState() == FRI_STATE_CMD) ) - { - switch (getControlStrategy()) - { + float newJntPosition[n_joints_]; + float newJntStiff[n_joints_]; + float newJntDamp[n_joints_]; + float newJntAddTorque[n_joints_]; - case JOINT_POSITION: - - // Ensure the robot is in this mode - if( (device_->getCurrentControlScheme() == FRI_CTRL_POSITION) ) - { - float newJntPosition[n_joints_]; - - for (unsigned int j = 0; j < n_joints_; j++) - { - newJntPosition[j] = joint_position_command_[j]; - } - device_->doPositionControl(newJntPosition, true); - } - break; - - case CARTESIAN_IMPEDANCE: - ROS_WARN("CARTESIAN IMPEDANCE NOT IMPLEMENTED"); - break; - - case JOINT_IMPEDANCE: - - // Ensure the robot is in this mode - if( (device_->getCurrentControlScheme() == FRI_CTRL_JNT_IMP) ) - { - float newJntPosition[n_joints_]; - float newJntStiff[n_joints_]; - float newJntDamp[n_joints_]; - float newJntAddTorque[n_joints_]; - - // WHEN THE URDF MODEL IS PRECISE - // 1. compute the gracity term - // f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); - - // 2. read gravity term from FRI and add it with opposite sign and add the URDF gravity term - // newJntAddTorque = gravity_effort_ - device_->getF_DYN?? - - for(int j=0; j < n_joints_; j++) - { - newJntPosition[j] = joint_position_command_[j]; - newJntAddTorque[j] = joint_effort_command_[j]; - newJntStiff[j] = joint_stiffness_command_[j]; - newJntDamp[j] = joint_damping_command_[j]; - } - device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, true); - } - break; - - case GRAVITY_COMPENSATION: - if( device_->getCurrentControlScheme() == FRI_CTRL_OTHER ) - { - // just read status to keep FRI alive - device_->doDataExchange(); - } - break; - } + switch (getControlStrategy()) + { + case JOINT_POSITION: + for (int j = 0; j < n_joints_; j++) + { + newJntPosition[j] = joint_position_command_[j]; + } + device_->doPositionControl(newJntPosition, false); + break; + + case CARTESIAN_IMPEDANCE: + break; + + case JOINT_IMPEDANCE: + // WHEN THE URDF MODEL IS PRECISE + // 1. compute the gracity term + // f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); + + // 2. read gravity term from FRI and add it with opposite sign and add the URDF gravity term + // newJntAddTorque = gravity_effort_ - device_->getF_DYN?? + + for(int j=0; j < n_joints_; j++) + { + newJntPosition[j] = joint_position_[j]; + newJntAddTorque[j] = joint_effort_command_[j]; + newJntStiff[j] = 0.01;//joint_stiffness_command_[j]; + newJntDamp[j] = 0.01;//joint_damping_command_[j]; + } + // device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, false); + device_->doJntImpedanceControl(NULL, NULL, NULL, newJntAddTorque, false); + break; + + case GRAVITY_COMPENSATION: + break; } return; } @@ -216,21 +171,14 @@ class LWRHWreal : public LWRHW } else { - setControlStrategy(desired_strategy); - - // trigger the KRL with the new stragety value - device_->setToKRLInt(0, desired_strategy); - device_->doDataExchange(); - - // wait until friStop() is called - while ( device_->getFrmKRLInt(0) != 0) {} + stopFRI(); - // wait for good quality comm again - while ( device_->getQuality() >= FRI_QUALITY_OK) {} + // send to KRL the new strategy + device_->setToKRLInt(0, desired_strategy); - // wait for FRI to start again before exiting the switch - while ( device_->getState() != FRI_STATE_CMD) {} + startFRI(); + setControlStrategy(desired_strategy); std::cout << "The ControlStrategy changed to: " << getControlStrategy() << std::endl; } } @@ -250,6 +198,49 @@ class LWRHWreal : public LWRHW FRI_QUALITY lastQuality_; FRI_CTRL lastCtrlScheme_; + boost::shared_ptr KRCCommThread_; + bool stopKRCComm_ = false; + void KRCCommThreadCallback() + { + while(!stopKRCComm_) + { + device_->doDataExchange(); + } + return; + } + + void startFRI() + { + // wait until FRI enters in command mode + // std::cout << "Waiting for good communication quality..." << std::endl; + // while( device_->getQuality() != FRI_QUALITY_OK ){}; + device_->setToKRLInt(1, 1); + + // std::cout << "Waiting for command mode..." << std::endl; + // while ( device_->getFrmKRLInt(1) != 1 ) + // { + // std::cout << "device_->getState(): " << device_->getState() << std::endl; + // device_->setToKRLInt(1, 1); + // usleep(1000000); + // } + return; + } + + void stopFRI() + { + // wait until FRI enters in command mode + device_->setToKRLInt(1, 0); + std::cout << "Waiting for monitor mode..." << std::endl; + while ( device_->getFrmKRLInt(1) != 0 ){} + // { + // std::cout << "device_->getState(): " << device_->getState() << std::endl; + // std::cout << "Waiting for monitor mode..." << std::endl; + // device_->setToKRLInt(1, 0); + // usleep(1000000); + // } + return; + } + }; } diff --git a/lwr_hw/include/lwr_hw/lwr_hw_fril.hpp b/lwr_hw/include/lwr_hw/lwr_hw_fril.hpp new file mode 100644 index 0000000..15a6878 --- /dev/null +++ b/lwr_hw/include/lwr_hw/lwr_hw_fril.hpp @@ -0,0 +1,233 @@ +#ifndef LWR_HW__LWR_HW_REAL_H +#define LWR_HW__LWR_HW_REAL_H + +// lwr hw definition +#include "lwr_hw/lwr_hw.h" + +// FRIL remote hooks +#include + +#define NUMBER_OF_CYCLES_FOR_QUAULITY_CHECK 2000 +#define EOK 0 + +namespace lwr_hw +{ + +class LWRHWFRIL : public LWRHW +{ + +public: + + LWRHWFRIL() : LWRHW() {} + ~LWRHWFRIL() {} + + void stop(){return;}; + void set_mode(){return;}; + + void setInitFile(std::string init_file){init_file_ = init_file; file_set_ = true;}; + + // Init, read, and write, with FRI hooks + bool init() + { + if( !(file_set_) ) + { + std::cout << "Did you forget to set the init file?" << std::endl + << "You must do that before init()" << std::endl + << "Exiting..." << std::endl; + return false; + } + + // construct a low-level lwr + device_.reset( new FastResearchInterface( init_file_.c_str() ) ); + + ResultValue = device_->StartRobot( FRI_CONTROL_POSITION ); + if (ResultValue != EOK) + { + std::cout << "An error occurred during starting up the robot...\n" << std::endl; + return false; + } + + return true; + } + + void read(ros::Time time, ros::Duration period) + { + float msrJntPos[n_joints_]; + float msrJntTrq[n_joints_]; + + device_->GetMeasuredJointPositions( msrJntPos ); + device_->GetMeasuredJointTorques( msrJntTrq ); + + for (int j = 0; j < n_joints_; j++) + { + joint_position_prev_[j] = joint_position_[j]; + joint_position_[j] = (double)msrJntPos[j]; + joint_position_kdl_(j) = joint_position_[j]; + joint_effort_[j] = (double)msrJntTrq[j]; + joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j]-joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); + joint_stiffness_[j] = joint_stiffness_command_[j]; + } + return; + } + + void write(ros::Time time, ros::Duration period) + { + enforceLimits(period); + + // ensure the robot is powered and it is in control mode, almost like the isMachineOk() of Standford + if ( device_->IsMachineOK() ) + { + device_->WaitForKRCTick(); + + switch (getControlStrategy()) + { + + case JOINT_POSITION: + + // Ensure the robot is in this mode + if( (device_->GetCurrentControlScheme() == FRI_CONTROL_POSITION) ) + { + float newJntPosition[n_joints_]; + for (int j = 0; j < n_joints_; j++) + { + newJntPosition[j] = (float)joint_position_command_[j]; + } + device_->SetCommandedJointPositions(newJntPosition); + } + break; + + case CARTESIAN_IMPEDANCE: + break; + + case JOINT_IMPEDANCE: + + // Ensure the robot is in this mode + if( (device_->GetCurrentControlScheme() == FRI_CONTROL_JNT_IMP) ) + { + float newJntPosition[n_joints_]; + float newJntStiff[n_joints_]; + float newJntDamp[n_joints_]; + float newJntAddTorque[n_joints_]; + + // WHEN THE URDF MODEL IS PRECISE + // 1. compute the gracity term + // f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); + + // 2. read gravity term from FRI and add it with opposite sign and add the URDF gravity term + // newJntAddTorque = gravity_effort_ - device_->getF_DYN?? + + for(int j=0; j < n_joints_; j++) + { + newJntPosition[j] = (float)joint_position_command_[j]; + newJntAddTorque[j] = (float)joint_effort_command_[j]; + newJntStiff[j] = (float)joint_stiffness_command_[j]; + newJntDamp[j] = (float)joint_damping_command_[j]; + } + device_->SetCommandedJointStiffness(newJntStiff); + device_->SetCommandedJointPositions(newJntPosition); + device_->SetCommandedJointDamping(newJntDamp); + device_->SetCommandedJointTorques(newJntAddTorque); + } + break; + + case GRAVITY_COMPENSATION: + break; + } + } + return; + } + + void doSwitch(const std::list &start_list, const std::list &stop_list) + { + + ResultValue = device_->StopRobot(); + if (ResultValue != EOK) + { + std::cout << "An error occurred during stopping the robot, couldn't switch mode...\n" << std::endl; + return; + } + + // at this point, we now that there is only one controller that ones to command joints + ControlStrategy desired_strategy = JOINT_POSITION; // default + + // If any of the controllers in the start list works on a velocity interface, the switch can't be done. + for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) + { + if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) + { + std::cout << "Request to switch to hardware_interface::PositionJointInterface (JOINT_POSITION)" << std::endl; + desired_strategy = JOINT_POSITION; + break; + } + else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) + { + std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_IMPEDANCE)" << std::endl; + desired_strategy = JOINT_IMPEDANCE; + break; + } + } + + for (int j = 0; j < n_joints_; ++j) + { + ///semantic Zero + joint_position_command_[j] = joint_position_[j]; + joint_effort_command_[j] = 0.0; + + ///call setCommand once so that the JointLimitsInterface receive the correct value on their getCommand()! + try{ position_interface_.getHandle(joint_names_[j]).setCommand(joint_position_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + try{ effort_interface_.getHandle(joint_names_[j]).setCommand(joint_effort_command_[j]); } + catch(const hardware_interface::HardwareInterfaceException&){} + + ///reset joint_limit_interfaces + pj_sat_interface_.reset(); + pj_limits_interface_.reset(); + } + + if(desired_strategy == getControlStrategy()) + { + std::cout << "The ControlStrategy didn't changed, it is already: " << getControlStrategy() << std::endl; + } + else + { + switch( desired_strategy ) + { + case JOINT_POSITION: + ResultValue = device_->StartRobot( FRI_CONTROL_POSITION ); + if (ResultValue != EOK) + { + std::cout << "An error occurred during starting the robot, couldn't switch to JOINT_POSITION...\n" << std::endl; + return; + } + break; + case JOINT_IMPEDANCE: + ResultValue = device_->StartRobot( FRI_CONTROL_JNT_IMP ); + if (ResultValue != EOK) + { + std::cout << "An error occurred during starting the robot, couldn't switch to JOINT_IMPEDANCE...\n" << std::endl; + return; + } + break; + } + + // if sucess during the switch in FRI, set the ROS strategy + setControlStrategy(desired_strategy); + + std::cout << "The ControlStrategy changed to: " << getControlStrategy() << std::endl; + } + } + +private: + + // Parameters + std::string init_file_; + bool file_set_ = false; + + // low-level interface + boost::shared_ptr device_; + int ResultValue = 0; +}; + +} + +#endif diff --git a/lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp b/lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp index 8d576a5..7d76a26 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp +++ b/lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp @@ -15,12 +15,12 @@ namespace lwr_hw { -class LWRHWsim : public LWRHW +class LWRHWGazebo : public LWRHW { public: - LWRHWsim() : LWRHW() {} - ~LWRHWsim() {} + LWRHWGazebo() : LWRHW() {} + ~LWRHWGazebo() {} void setParentModel(gazebo::physics::ModelPtr parent_model){parent_model_ = parent_model; parent_set_ = true;}; @@ -34,7 +34,7 @@ class LWRHWsim : public LWRHW } gazebo::physics::JointPtr joint; - for(unsigned int j=0; j < n_joints_; j++) + for(int j=0; j < n_joints_; j++) { joint = parent_model_->GetJoint(joint_names_[j]); if (!joint) @@ -51,7 +51,7 @@ class LWRHWsim : public LWRHW void read(ros::Time time, ros::Duration period) { - for(unsigned int j=0; j < n_joints_; ++j) + for(int j=0; j < n_joints_; ++j) { joint_position_prev_[j] = joint_position_[j]; joint_position_[j] += angles::shortest_angular_distance(joint_position_[j], @@ -59,7 +59,7 @@ class LWRHWsim : public LWRHW joint_position_kdl_(j) = joint_position_[j]; // derivate velocity as in the real hardware instead of reading it from simulation joint_velocity_[j] = filters::exponentialSmoothing((joint_position_[j] - joint_position_prev_[j])/period.toSec(), joint_velocity_[j], 0.2); - joint_effort_[j] = sim_joints_[j]->GetForce((unsigned int)(0)); + joint_effort_[j] = sim_joints_[j]->GetForce((int)(0)); joint_stiffness_[j] = joint_stiffness_command_[j]; } } @@ -72,7 +72,7 @@ class LWRHWsim : public LWRHW { case JOINT_POSITION: - for(unsigned int j=0; j < n_joints_; j++) + for(int j=0; j < n_joints_; j++) { // according to the gazebo_ros_control plugin, this must *not* be called if SetForce is going to be called // but should be called when SetPostion is going to be called @@ -94,7 +94,7 @@ class LWRHWsim : public LWRHW // compute the gracity term f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); - for(unsigned int j=0; j < n_joints_; j++) + for(int j=0; j < n_joints_; j++) { // replicate the joint impedance control strategy // tau = k (q_FRI - q_msr) + tau_FRI + D(q_msr) + f_dyn(q_msr) diff --git a/lwr_hw/krl/ros_control.src b/lwr_hw/krl/ros_control.src index e4d7b05..2bf986a 100644 --- a/lwr_hw/krl/ros_control.src +++ b/lwr_hw/krl/ros_control.src @@ -27,7 +27,7 @@ DEF ros_control( ) ;FOLD Variable definitions ; ---------------------------------------------- ; - ; INDEXES: IN KRL GO 1-16 / IN C++ GO 0-15 + ; INDEXES: IN KRL [1-16] / IN C++ [0-15] ; ; ---------------------------------------------- ; $FRI_FRM_INT[1] @@ -38,26 +38,28 @@ DEF ros_control( ) ; 20 -> Cartesian impedance control ; 30 -> joint impedance control ; - ; An friStop() - switch - friStart() sequence - ; is used to manage the switches + ; An stopFRI() - setToKRLInt(0, $) - startFRI() + ; sequence must be performed in the remote. ; ---------------------------------------------- - ; $FRI_TO_INT[1] - ; This value is used to tell the remote that - ; either friStart() or friStop() was called + ; $FRI_FRM_INT[2] + ; This value is used to call friStart() or + ; friStop() from the remote ; - ; 1 -> friStart() was called - ; 0 -> fiStop() was called + ; 1 -> to call friStart() + ; 0 -> to call fiStop() ; ---------------------------------------------- - ; $FRI_FRM_INT[1] (not used so far) - ; This value is used to call the remote that + ; $FRI_TO_INT[2] + ; This value is used to tell the remote that ; either friStart() or friStop() was called - ; - ; 1 -> friStart() was called + ; ; 0 -> fiStop() was called + ; 1 -> friStart() was called + ; 10 -> Init flag, to avoid cyclic start/stop ; ---------------------------------------------- ; $FRI_FRM_INT[16] AND $FRI_TO_INT[16] + ; $FRI_FRM_REA[16] AND $FRI_TO_REA[16] ; - ; This values are used for the handshake + ; These values are used for the handshake ; ---------------------------------------------- ;ENDFOLD (Variable definitions) @@ -72,117 +74,114 @@ DEF ros_control( ) $FRI_TO_REA[i] = 0.0 ENDFOR - - ;Input correct tool number here and restart - BAS (#tool,1 ) + ;Init flag + $FRI_TO_INT[2] = 10 ; Stay at the same position PTP $AXIS_ACT_MES + ;Impedance default parameters + $stiffness.axisstiffness={ A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} + $stiffness.axismaxdeltatrq={A1 100, A2 100, A3 100, A4 100, A5 100, A6 30, E1 30} + $stiffness.maxforce = {X 300.0, Y 300.0, Z 300.0, A 30.0, B 30.0, C 30.0} + $stiffness.cpmaxdelta = {X 100.0, Y 100.0, Z 100.0, A 100.0, B 100.0, C 100.0} + $stiffness.axismaxdelta = {A1 100.0, A2 100.0, A3 100.0, A4 100.0, A5 100.0, A6 100.0, E1 100.0} + $stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} + $stiffness.cpstiffness = {x 200, y 200, z 200, a 20, b 20, c 20} + $stiffness.cpdamping = { x 0.7, y 0.7, z 0.7, a 0.7, b 0.7, c 0.7} + ;Start with position control $stiffness.strategy = 10 $stiffness.commit = true ;ENDFOLD (init) +;Input correct tool number here and restart +BAS (#tool,1 ) + ;Specify ip and port retVal = friSetup("192.168.0.150", 49939, 49939) -;Open FRI with datarate 2 msec (ToDo: pass this value from ROS) +;Open FRI with datarate 2 msec, change at will retVal=friOpen(2) ;FOLD Screen output WAIT FOR ($FriState == #MON) $MSG_T.KEY[] = "FRI successfully opened." - $MSG_T.VALID=TRUE - WAIT FOR ($MSG_T.VALID == FALSE) + $MSG_T.VALID = TRUE WAIT SEC 0.3 ;ENDFOLD (Screen output) -;FOLD Handshake - ;Wait for the ROS node to salute - WAIT FOR ($FRI_FRM_INT[16] == 1) - - ;Be polite and salute back - $FRI_TO_INT[16] = $FRI_FRM_INT[16] - $MSG_T.KEY[] = "Done handshake!" - $MSG_T.VALID=TRUE - WAIT FOR ($MSG_T.VALID == FALSE) - WAIT SEC 0.3 -;ENDFOLD (Handshake) - -;Just send some values to check communication -WAIT FOR ($FriQuality == #PERFECT) -retVal = friStart(1.0) -$FRI_TO_INT[1] = 1 -WAIT FOR ($FriState == #CMD) - ;FOLD Screen output - $MSG_T.KEY[] = "FRI successfully started." - $MSG_T.VALID=TRUE - WAIT FOR ($MSG_T.VALID == FALSE) - WAIT SEC 0.3 - ;ENDFOLD (Screen output) - ;The infinite loop LOOP - ;Wait until a change of strategy is requested - WAIT FOR ($stiffness.strategy <> $FRI_FRM_INT[1]) - - retVal = friStop() - $FRI_TO_INT[1] = 0 - WAIT FOR ($FriState==#MON) - - ;FOLD Screen output - $MSG_T.KEY[] = "FRI successfully stopped." - $MSG_T.VALID=TRUE - WAIT FOR ($MSG_T.VALID == FALSE) - WAIT SEC 0.5 - ;ENDFOLD (Screen output) - - ;FOLD Impedance parameters - $stiffness.axisstiffness={ A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} - $stiffness.axismaxdeltatrq={A1 100, A2 100, A3 100, A4 100, A5 100, A6 30, E1 30} - $stiffness.maxforce = {X 300.0, Y 300.0, Z 300.0, A 30.0, B 30.0, C 30.0} - $stiffness.cpmaxdelta = {X 100.0, Y 100.0, Z 100.0, A 100.0, B 100.0, C 100.0} - $stiffness.axismaxdelta = {A1 100.0, A2 100.0, A3 100.0, A4 100.0, A5 100.0, A6 100.0, E1 100.0} - $stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} - $stiffness.cpstiffness = {x 200, y 200, z 200, a 20, b 20, c 20} - $stiffness.cpdamping = { x 0.7, y 0.7, z 0.7, a 0.7, b 0.7, c 0.7} - ;ENDFOLD (Impedance parameters) - - $stiffness.strategy = $FRI_FRM_INT[1] - $stiffness.commit = true + ;stopFRI() from remote + IF ($FRI_FRM_INT[2] == 0) AND ($FRI_TO_INT[2] == 1) THEN + ;FOLD Screen output + $MSG_T.KEY[] = "Stopping FRI..." + $MSG_T.VALID = TRUE + WAIT SEC 0.5 + ;ENDFOLD (Screen output) + + retVal = friStop() + $FRI_TO_INT[2] = 0 + WAIT FOR ($FriState == #MON) + + ;FOLD Screen output + $MSG_T.KEY[] = "FRI successfully stopped." + $MSG_T.VALID = TRUE + WAIT SEC 0.5 + ;ENDFOLD (Screen output) + ENDIF + + ;startFRI() from remote in desired strategy + IF ($FRI_FRM_INT[2] == 1) AND ($FRI_TO_INT[2] <> 1) THEN + ;Only change strategy after init + IF ($FRI_TO_INT[2] <> 10) THEN + $stiffness.strategy = $FRI_FRM_INT[1] + $stiffness.commit = true + ENDIF - ;FOLD Screen output - IF ($stiffness.strategy == 10) THEN - $MSG_T.KEY[] = "ControlStrategy changes to JOINT_POSITION" - ELSE - IF($stiffness.strategy == 20) THEN - $MSG_T.KEY[] = "ControlStrategy changes to CARTESIAN_IMPEDANCE" + ;FOLD Screen output + $MSG_T.KEY[] = "Starting FRI..." + $MSG_T.VALID = TRUE + WAIT SEC 0.5 + ;ENDFOLD (Screen output) + + ;Please, start the ROS node. + WAIT FOR ($FriQuality == #PERFECT) + + ;Due to init, wait to actually trigger the start + WAIT FOR $FRI_FRM_INT[2] == 1 + retVal = friStart(1.0) + WAIT FOR ($FriState == #CMD) + $FRI_TO_INT[2] = 1 + + ;FOLD Screen output + $MSG_T.KEY[] = "FRI successfully started." + $MSG_T.VALID = TRUE + WAIT SEC 0.5 + ;ENDFOLD (Screen output) + + ;FOLD Screen output + IF ($stiffness.strategy == 10) THEN + $MSG_T.KEY[] = "ControlStrategy changed to JOINT_POSITION" ELSE - IF ($stiffness.strategy == 30) THEN - $MSG_T.KEY[] = "ControlStrategy changes to JOINT_IMPEDANCE" + IF($stiffness.strategy == 20) THEN + $MSG_T.KEY[] = "ControlStrategy changed to CARTESIAN_IMPEDANCE" ELSE - $MSG_T.KEY[] = "ERROR: Unknown ControlStrategy." + IF ($stiffness.strategy == 30) THEN + $MSG_T.KEY[] = "ControlStrategy changed to JOINT_IMPEDANCE" + ELSE + $MSG_T.KEY[] = "ERROR: Unknown ControlStrategy." + ENDIF ENDIF ENDIF - ENDIF - $MSG_T.VALID=TRUE - WAIT FOR ($MSG_T.VALID == FALSE) - ;ENDFOLD (Screen output) - - ;Start FRI again - WAIT FOR ($FriQuality == #PERFECT) - retVal = friStart(1.0) - $FRI_TO_INT[1] = 1 - WAIT FOR ($FriState == #CMD) - - ;FOLD Screen output - $MSG_T.KEY[] = "FRI successfully started again." - $MSG_T.VALID=TRUE - WAIT FOR ($MSG_T.VALID == FALSE) - WAIT SEC 0.5 - ;ENDFOLD (Screen output) + $MSG_T.VALID = TRUE + ;ENDFOLD (Screen output) + ENDIF + + ;FRI / ROS control - communication activated + WAIT SEC 0.05 ENDLOOP diff --git a/lwr_hw/launch/lwr_hw.launch b/lwr_hw/launch/lwr_hw.launch index dd9a898..e874869 100644 --- a/lwr_hw/launch/lwr_hw.launch +++ b/lwr_hw/launch/lwr_hw.launch @@ -5,12 +5,21 @@ + + + + + + + + + diff --git a/lwr_hw/src/lwr_hw.cpp b/lwr_hw/src/lwr_hw.cpp index 8ef983a..22e98fa 100644 --- a/lwr_hw/src/lwr_hw.cpp +++ b/lwr_hw/src/lwr_hw.cpp @@ -2,7 +2,6 @@ namespace lwr_hw { - void LWRHW::create(std::string name, std::string urdf_string) { // SET NAME AND MODEL diff --git a/lwr_hw/src/lwr_hw_fri_node.cpp b/lwr_hw/src/lwr_hw_fri_node.cpp index 2de7870..2969879 100644 --- a/lwr_hw/src/lwr_hw_fri_node.cpp +++ b/lwr_hw/src/lwr_hw_fri_node.cpp @@ -9,7 +9,7 @@ #include #include -// the lwr hw real interface +// the lwr hw fri interface #include "lwr_hw/lwr_hw_fri.hpp" bool g_quit = false; @@ -31,14 +31,14 @@ std::string getURDF(ros::NodeHandle &model_nh_, std::string param_name) std::string search_param_name; if (model_nh_.searchParam(param_name, search_param_name)) { - ROS_INFO_ONCE_NAMED("LWRHWsim", "LWRHWsim plugin is waiting for model" + ROS_INFO_ONCE_NAMED("LWRHWFRI", "LWRHWFRI node is waiting for model" " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str()); model_nh_.getParam(search_param_name, urdf_string); } else { - ROS_INFO_ONCE_NAMED("LWRHWsim", "LWRHWsim plugin is waiting for model" + ROS_INFO_ONCE_NAMED("LWRHWFRI", "LWRHWFRI node is waiting for model" " URDF in parameter [%s] on the ROS param server.", robot_description.c_str()); model_nh_.getParam(param_name, urdf_string); @@ -46,7 +46,7 @@ std::string getURDF(ros::NodeHandle &model_nh_, std::string param_name) usleep(100000); } - ROS_DEBUG_STREAM_NAMED("LWRHWsim", "Recieved urdf from param server, parsing..."); + ROS_DEBUG_STREAM_NAMED("LWRHWFRI", "Recieved urdf from param server, parsing..."); return urdf_string; } @@ -77,7 +77,7 @@ int main( int argc, char** argv ) std::string urdf_string = getURDF(lwr_nh, "/robot_description"); // construct and start the real lwr - lwr_hw::LWRHWreal lwr_robot; + lwr_hw::LWRHWFRI lwr_robot; std::cout << "namespace: " << lwr_nh.getNamespace() << std::endl; lwr_robot.create(std::string("lwr"), urdf_string); lwr_robot.setPort(port); @@ -97,21 +97,21 @@ int main( int argc, char** argv ) controller_manager::ControllerManager manager(&lwr_robot, lwr_nh); // run as fast as possible - while( !g_quit ) + while( !g_quit ) { // get the time / period - if (!clock_gettime(CLOCK_REALTIME, &ts)) + if (!clock_gettime(CLOCK_REALTIME, &ts)) { now.sec = ts.tv_sec; now.nsec = ts.tv_nsec; period = now - last; last = now; } - else + else { ROS_FATAL("Failed to poll realtime clock!"); break; - } + } // read the state from the lwr lwr_robot.read(now, period); @@ -126,8 +126,8 @@ int main( int argc, char** argv ) std::cerr<<"Stopping spinner..."< +#include +#include +#include +#include + +// ROS headers +#include +#include + +// the lwr hw fri interface +#include "lwr_hw/lwr_hw_fril.hpp" + +bool g_quit = false; + +void quitRequested(int sig) +{ + g_quit = true; +} + +// Get the URDF XML from the parameter server +std::string getURDF(ros::NodeHandle &model_nh_, std::string param_name) +{ + std::string urdf_string; + std::string robot_description = "/robot_description"; + + // search and wait for robot_description on param server + while (urdf_string.empty()) + { + std::string search_param_name; + if (model_nh_.searchParam(param_name, search_param_name)) + { + ROS_INFO_ONCE_NAMED("LWRHWFRIL", "LWRHWFRIL node is waiting for model" + " URDF in parameter [%s] on the ROS param server.", search_param_name.c_str()); + + model_nh_.getParam(search_param_name, urdf_string); + } + else + { + ROS_INFO_ONCE_NAMED("LWRHWFRIL", "LWRHWFRIL node is waiting for model" + " URDF in parameter [%s] on the ROS param server.", robot_description.c_str()); + + model_nh_.getParam(param_name, urdf_string); + } + + usleep(100000); + } + ROS_DEBUG_STREAM_NAMED("LWRHWFRIL", "Recieved urdf from param server, parsing..."); + + return urdf_string; +} + +int main( int argc, char** argv ) +{ + // initialize ROS + ros::init(argc, argv, "lwr_hw_interface", ros::init_options::NoSigintHandler); + + // ros spinner + ros::AsyncSpinner spinner(1); + spinner.start(); + + // custom signal handlers + signal(SIGTERM, quitRequested); + signal(SIGINT, quitRequested); + signal(SIGHUP, quitRequested); + + // create a node + ros::NodeHandle lwr_nh; + + // get params or give default values + std::string file; + lwr_nh.param("file", file, std::string("")); + + std::string urdf_string = getURDF(lwr_nh, "/robot_description"); + + // construct and start the real lwr + lwr_hw::LWRHWFRIL lwr_robot; + std::cout << "namespace: " << lwr_nh.getNamespace() << std::endl; + lwr_robot.create(std::string("lwr"), urdf_string); + lwr_robot.setInitFile(file); + if(!lwr_robot.init()) + { + ROS_FATAL_NAMED("lwr_hw","Could not initialize robot real interface"); + return -1; + } + + // timer variables + struct timespec ts = {0, 0}; + ros::Time last(ts.tv_sec, ts.tv_nsec), now(ts.tv_sec, ts.tv_nsec); + ros::Duration period(1.0); + + //the controller manager + controller_manager::ControllerManager manager(&lwr_robot, lwr_nh); + + // run as fast as possible + while( !g_quit ) + { + // get the time / period + if (!clock_gettime(CLOCK_REALTIME, &ts)) + { + now.sec = ts.tv_sec; + now.nsec = ts.tv_nsec; + period = now - last; + last = now; + } + else + { + ROS_FATAL("Failed to poll realtime clock!"); + break; + } + + // read the state from the lwr + lwr_robot.read(now, period); + + // update the controllers + manager.update(now, period); + + // write the command to the lwr + lwr_robot.write(now, period); + } + + std::cerr<<"Stopping spinner..."<create(robot_namespace_, urdf_string); robot_hw_sim_->setParentModel(parent_model_); if(!robot_hw_sim_->init()) @@ -217,7 +217,7 @@ class LWRHWsimPlugin : public gazebo::ModelPlugin // Robot simulator interface std::string robot_hw_sim_type_str_; - boost::shared_ptr robot_hw_sim_; + boost::shared_ptr robot_hw_sim_; // Controller manager boost::shared_ptr controller_manager_; From 470ff4682a10ef07a64e9fb5b591056e6a9eb3d3 Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Wed, 8 Jul 2015 11:29:07 +0200 Subject: [PATCH 10/19] [single_lwr_example] Initial work to support Stanford library (fork https://github.com/iocroblab/fril) --- .../launch/single_lwr.launch | 3 +++ .../config/980241-FRI-Driver.init | 20 +++++++++++++++++++ 2 files changed, 23 insertions(+) create mode 100755 single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init diff --git a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch index 354017a..e7db62a 100644 --- a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch +++ b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch @@ -11,6 +11,8 @@ + + @@ -90,6 +92,7 @@ + diff --git a/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init b/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init new file mode 100755 index 0000000..4b73768 --- /dev/null +++ b/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init @@ -0,0 +1,20 @@ +# Initialization file for the KUKA Fast Research Interface of the Light-Weight Robot IV + +[RobotName] +Name=980241 + +[Priorities] +#Priority range: 1..63 +KRCCommunicationThread=1 +TimerThread=1 +MainThread=1 +OutputConsoleThread=1 + +[ControlValues] +# Cycle time in seconds +CycleTime=0.002 + +[Logging] +NumberOfLoggingFileEntries=60000 +LoggingPath=/home/lwrcontrol/output +LoggingFileName=LWR-Scope.dat \ No newline at end of file From 3c378a42d742db2921af55b954a23ebd5edfa698 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Wed, 8 Jul 2015 11:35:42 +0200 Subject: [PATCH 11/19] Delete lwr_hw.cpp.autosave --- lwr_hw/src/lwr_hw.cpp.autosave | 443 --------------------------------- 1 file changed, 443 deletions(-) delete mode 100644 lwr_hw/src/lwr_hw.cpp.autosave diff --git a/lwr_hw/src/lwr_hw.cpp.autosave b/lwr_hw/src/lwr_hw.cpp.autosave deleted file mode 100644 index 626fe46..0000000 --- a/lwr_hw/src/lwr_hw.cpp.autosave +++ /dev/null @@ -1,443 +0,0 @@ -#include "lwr_hw/lwr_hw.h" - -namespace lwr_hw -{ - - void LWRHW::create(std::string name, std::string urdf_string) - { - // SET NAME AND MODEL - robot_namespace_ = name; - urdf_string_ = urdf_string; - - // ALLOCATE MEMORY - - // JOINT NAMES ARE TAKEN FROM URDF NAME CONVENTION - joint_names_.push_back( robot_namespace_ + std::string("_0_joint") ); - joint_names_.push_back( robot_namespace_ + std::string("_1_joint") ); - joint_names_.push_back( robot_namespace_ + std::string("_2_joint") ); - joint_names_.push_back( robot_namespace_ + std::string("_3_joint") ); - joint_names_.push_back( robot_namespace_ + std::string("_4_joint") ); - joint_names_.push_back( robot_namespace_ + std::string("_5_joint") ); - joint_names_.push_back( robot_namespace_ + std::string("_6_joint") ); - - // VARIABLES - joint_position_.resize(n_joints_); - joint_position_prev_.resize(n_joints_); - joint_velocity_.resize(n_joints_); - joint_effort_.resize(n_joints_); - joint_stiffness_.resize(n_joints_); - joint_damping_.resize(n_joints_); - joint_position_command_.resize(n_joints_); - joint_velocity_command_.resize(n_joints_); - joint_effort_command_.resize(n_joints_); - joint_stiffness_command_.resize(n_joints_); - joint_damping_command_.resize(n_joints_); - - joint_lower_limits_.resize(n_joints_); - joint_upper_limits_.resize(n_joints_); - joint_lower_limits_stiffness_.resize(n_joints_); - joint_upper_limits_stiffness_.resize(n_joints_); - joint_effort_limits_.resize(n_joints_); - - // RESET VARIABLES - reset(); - - // GET TRANSMISSIONS THAT BELONG TO THIS LWR 4+ ARM - if (!parseTransmissionsFromURDF(urdf_string_)) - { - std::cout << "lwr_hw: " << "Error parsing URDF in lwr_hw.\n" << std::endl; - return; - } - const urdf::Model *const urdf_model_ptr = urdf_model_.initString(urdf_string_) ? &urdf_model_ : NULL; - registerInterfaces(urdf_model_ptr, transmissions_); - - // INIT KDL STUFF - initKDLdescription(urdf_model_ptr); - - std::cout << "Succesfully created an abstract LWR 4+ ARM with interfaces" << std::endl; - } - - // reset values - void LWRHW::reset() - { - for (int j = 0; j < n_joints_; ++j) - { - joint_position_[j] = 0.0; - joint_position_prev_[j] = 0.0; - joint_velocity_[j] = 0.0; - joint_effort_[j] = 0.0; - joint_stiffness_[j] = 0.0; - joint_damping_[j] = 0.0; - - joint_position_command_[j] = 0.0; - joint_velocity_command_[j] = 0.0; - joint_effort_command_[j] = 0.0; - joint_stiffness_command_[j] = 2500.0; - joint_damping_command_[j] = 0.0; - } - - current_strategy_ = JOINT_POSITION; - - return; - } - - void LWRHW::registerInterfaces(const urdf::Model *const urdf_model, - std::vector transmissions) - { - - // Check that this transmission has one joint - if( transmissions.empty() ) - { - std::cout << "lwr_hw: " << "There are no transmission in this robot, all are non-driven joints? " - << std::endl; - return; - } - - // Initialize values - for(unsigned int j=0; j < n_joints_; j++) - { - // Check that this transmission has one joint - if(transmissions[j].joints_.size() == 0) - { - std::cout << "lwr_hw: " << "Transmission " << transmissions[j].name_ - << " has no associated joints." << std::endl; - continue; - } - else if(transmissions[j].joints_.size() > 1) - { - std::cout << "lwr_hw: " << "Transmission " << transmissions[j].name_ - << " has more than one joint, and they can't be controlled simultaneously" - << std::endl; - continue; - } - - std::vector joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_; - - if( joint_interfaces.empty() ) - { - std::cout << "lwr_hw: " << "Joint " << transmissions[j].joints_[0].name_ << - " of transmission " << transmissions[j].name_ << " does not specify any hardware interface. " << - "You need to, otherwise the joint can't be controlled." << std::endl; - continue; - } - - const std::string& hardware_interface = joint_interfaces.front(); - - // Debug - std::cout << "\x1B[37m" << "lwr_hw: " << "Loading joint '" << joint_names_[j] - << "' of type '" << hardware_interface << "'" << "\x1B[0m" << std::endl; - - // Create joint state interface for all joints - state_interface_.registerHandle(hardware_interface::JointStateHandle( - joint_names_[j], &joint_position_[j], &joint_velocity_[j], &joint_effort_[j])); - - // Decide what kind of command interface this actuator/joint has - hardware_interface::JointHandle joint_handle_effort; - joint_handle_effort = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), - &joint_effort_command_[j]); - effort_interface_.registerHandle(joint_handle_effort); - - hardware_interface::JointHandle joint_handle_position; - joint_handle_position = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), - &joint_position_command_[j]); - position_interface_.registerHandle(joint_handle_position); - - // the stiffness is not actually a different joint, so the state handle is only used for handle - hardware_interface::JointHandle joint_handle_stiffness; - joint_handle_stiffness = hardware_interface::JointHandle(hardware_interface::JointStateHandle( - joint_names_[j]+std::string("_stiffness"), - &joint_stiffness_[j], &joint_stiffness_[j], &joint_stiffness_[j]), - &joint_stiffness_command_[j]); - position_interface_.registerHandle(joint_handle_stiffness); - - // velocity command handle, recall it is fake, there is no actual velocity interface - hardware_interface::JointHandle joint_handle_velocity; - joint_handle_velocity = hardware_interface::JointHandle(state_interface_.getHandle(joint_names_[j]), - &joint_velocity_command_[j]); - - registerJointLimits(joint_names_[j], - joint_handle_effort, - joint_handle_position, - joint_handle_velocity, - joint_handle_stiffness, - urdf_model, - &joint_lower_limits_[j], &joint_upper_limits_[j], - &joint_lower_limits_stiffness_[j], - &joint_upper_limits_stiffness_[j], - &joint_effort_limits_[j]); - } - - // Register interfaces - registerInterface(&state_interface_); - registerInterface(&effort_interface_); - registerInterface(&position_interface_); - } - - // Register the limits of the joint specified by joint_name and\ joint_handle. The limits are - // retrieved from the urdf_model. - // Return the joint's type, lower position limit, upper position limit, and effort limit. - void LWRHW::registerJointLimits(const std::string& joint_name, - const hardware_interface::JointHandle& joint_handle_effort, - const hardware_interface::JointHandle& joint_handle_position, - const hardware_interface::JointHandle& joint_handle_velocity, - const hardware_interface::JointHandle& joint_handle_stiffness, - const urdf::Model *const urdf_model, - double *const lower_limit, double *const upper_limit, - double *const lower_limit_stiffness, double *const upper_limit_stiffness, - double *const effort_limit) - { - *lower_limit = -std::numeric_limits::max(); - *upper_limit = std::numeric_limits::max(); - *lower_limit_stiffness = -std::numeric_limits::max(); - *upper_limit_stiffness = std::numeric_limits::max(); - *effort_limit = std::numeric_limits::max(); - - joint_limits_interface::JointLimits limits; - joint_limits_interface::JointLimits limits_stiffness; - bool has_limits = false; - bool has_limits_stiffness = false; - joint_limits_interface::SoftJointLimits soft_limits; - bool has_soft_limits = false; - - if (urdf_model != NULL) - { - const boost::shared_ptr urdf_joint = urdf_model->getJoint(joint_name); - const boost::shared_ptr urdf_joint_sitffness = urdf_model->getJoint(joint_name + std::string("_stiffness")); - if (urdf_joint != NULL) - { - // Get limits from the URDF file. - if (joint_limits_interface::getJointLimits(urdf_joint, limits)) - has_limits = true; - if (joint_limits_interface::getJointLimits(urdf_joint_sitffness, limits_stiffness)) - has_limits_stiffness = true; - if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) - has_soft_limits = true; - } - } - - if (!has_limits) - return; - - if (limits.has_position_limits) - { - *lower_limit = limits.min_position; - *upper_limit = limits.max_position; - } - if (limits.has_effort_limits) - *effort_limit = limits.max_effort; - - if (has_soft_limits) - { - const joint_limits_interface::EffortJointSoftLimitsHandle limits_handle_effort(joint_handle_effort, limits, soft_limits); - ej_limits_interface_.registerHandle(limits_handle_effort); - const joint_limits_interface::PositionJointSoftLimitsHandle limits_handle_position(joint_handle_position, limits, soft_limits); - pj_limits_interface_.registerHandle(limits_handle_position); - const joint_limits_interface::VelocityJointSoftLimitsHandle limits_handle_velocity(joint_handle_velocity, limits, soft_limits); - vj_limits_interface_.registerHandle(limits_handle_velocity); - - } - else - { - const joint_limits_interface::EffortJointSaturationHandle sat_handle_effort(joint_handle_effort, limits); - ej_sat_interface_.registerHandle(sat_handle_effort); - const joint_limits_interface::PositionJointSaturationHandle sat_handle_position(joint_handle_position, limits); - pj_sat_interface_.registerHandle(sat_handle_position); - const joint_limits_interface::VelocityJointSaturationHandle sat_handle_velocity(joint_handle_velocity, limits); - vj_sat_interface_.registerHandle(sat_handle_velocity); - } - - if (!has_limits_stiffness) - return; - - if (limits_stiffness.has_position_limits) - { - *lower_limit_stiffness = limits_stiffness.min_position; - *upper_limit_stiffness = limits_stiffness.max_position; - } - - const joint_limits_interface::PositionJointSaturationHandle sat_handle_stiffness(joint_handle_stiffness, limits_stiffness); - sj_sat_interface_.registerHandle(sat_handle_stiffness); - } - - void LWRHW::enforceLimits(ros::Duration period) - { - ej_sat_interface_.enforceLimits(period); - ej_limits_interface_.enforceLimits(period); - vj_sat_interface_.enforceLimits(period); - vj_limits_interface_.enforceLimits(period); - pj_sat_interface_.enforceLimits(period); - pj_limits_interface_.enforceLimits(period); - sj_sat_interface_.enforceLimits(period); - sj_limits_interface_.enforceLimits(period); - dj_sat_interface_.enforceLimits(period); - dj_limits_interface_.enforceLimits(period); - } - - // Get Transmissions from the URDF - bool LWRHW::parseTransmissionsFromURDF(const std::string& urdf_string) - { - std::vector transmissions; - - // Only *standard* transmission_interface are parsed - transmission_interface::TransmissionParser::parse(urdf_string, transmissions); - - // Now iterate and save only transmission from this robot - for (int j = 0; j < n_joints_; ++j) - { - // std::cout << "Check joint " << joint_names_[j] << std::endl; - std::vector::iterator it = transmissions.begin(); - for(; it != transmissions.end(); ++it) - { - // std::cout << "With transmission " << it->name_ << std::endl; - if (joint_names_[j].compare(it->joints_[0].name_) == 0) - { - transmissions_.push_back( *it ); - // std::cout << "Found a match for transmission " << it->name_ << std::endl; - } - } - } - - return true; - } - - // Init KDL stuff - bool LWRHW::initKDLdescription(const urdf::Model *const urdf_model) - { - // KDL code to compute f_dyn(q) - KDL::Tree kdl_tree; - if (!kdl_parser::treeFromUrdfModel(*urdf_model, kdl_tree)) - { - ROS_ERROR("Failed to construct kdl tree"); - return false; - } - - std::cout << "LWR kinematic successfully parsed with " - << kdl_tree.getNrOfJoints() - << " joints, and " - << kdl_tree.getNrOfJoints() - << " segments." << std::endl; - - // Get the info from parameters - std::string root_name; - ros::param::get(std::string("/") + robot_namespace_ + std::string("/root"), root_name); - if( root_name.empty() ) - root_name = kdl_tree.getRootSegment()->first; // default - - std::string tip_name; - ros::param::get(std::string("/") + robot_namespace_ + std::string("/tip"), tip_name); - if( root_name.empty() ) - tip_name = robot_namespace_ + std::string("_7_link"); ; // default - - std::cout << "Using root: " << root_name << " and tip: " << tip_name << std::endl; - - // this depends on how the world frame is set, in all our setups, world has always positive z pointing up. - gravity_ = KDL::Vector::Zero(); - gravity_(2) = -9.81; - - // Extract the chain from the tree - if(!kdl_tree.getChain(root_name, tip_name, lwr_chain_)) - { - ROS_ERROR("Failed to get KDL chain from tree: "); - return false; - } - - ROS_INFO("Number of segments: %d", lwr_chain_.getNrOfSegments()); - ROS_INFO("Number of joints in chain: %d", lwr_chain_.getNrOfJoints()); - - f_dyn_solver_.reset(new KDL::ChainDynParam(lwr_chain_,gravity_)); - - joint_position_kdl_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); - gravity_effort_ = KDL::JntArray(lwr_chain_.getNrOfJoints()); - - return true; - } - - bool LWRHW::canSwitch(const std::list &start_list, const std::list &stop_list) const - { - std::vector desired_strategies; - - for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) - { - // If any of the controllers in the start list works on a velocity interface, the switch can't be done. - if( it->hardware_interface.compare( std::string("hardware_interface::VelocityJointInterface") ) == 0 ) - { - std::cout << "The given controllers to start work on a velocity joint interface, and this robot does not have such an interface." - << "The switch can't be done" << std::endl; - return false; - } - - if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) - { - // Debug - // std::cout << "One controller wants to work on hardware_interface::PositionJointInterface" << std::endl; - desired_strategies.push_back( JOINT_POSITION ); - } - else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) - { - // Debug - // std::cout << "One controller wants to work on hardware_interface::EffortJointInterface" << std::endl; - desired_strategies.push_back( JOINT_IMPEDANCE ); - } - else - { - // Debug - std::cout << "This controller does not use any command interface, so it is only sensing, no problem" << std::endl; - } - } - - if( desired_strategies.size() > 1 ) - { - std::cout << "OOPS! Currently we are using the JointCommandInterface to switch mode, this is not strictly correct. " - << "This is temporary until a joint_mode_controller is available (so you can have different interfaces available in different modes)" - << "Having said this, we do not support more than one controller that ones to act on any given JointCommandInterface" - << "and we can't switch" - << std::endl; - return false; - } - - return true; - } - - void LWRHW::doSwitch(const std::list &start_list, const std::list &stop_list) - { - // at this point, we now that there is only one controller that ones to command joints - ControlStrategy desired_strategy; - - // If any of the controllers in the start list works on a velocity interface, the switch can't be done. - for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) - { - if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 ) - { - std::cout << "Request to switch to hardware_interface::PositionJointInterface (JOINT_POSITION)" << std::endl; - desired_strategy = JOINT_POSITION; - break; - } - else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) - { - std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_IMPEDANCE)" << std::endl; - desired_strategy = JOINT_IMPEDANCE; - break; - } - } - - for (int j = 0; j < n_joints_; ++j) - { - ///semantic Zero - joint_position_command_[j] = joint_position_[j]; - joint_effort_command_[j] = 0.0; - - ///call setCommand once so that the JointLimitsInterface receive the correct value on their getCommand()! - try{ position_interface_.getHandle(joint_names_[j]).setCommand(joint_position_command_[j]); } - catch(const hardware_interface::HardwareInterfaceException&){} - try{ effort_interface_.getHandle(joint_names_[j]).setCommand(joint_effort_command_[j]); } - catch(const hardware_interface::HardwareInterfaceException&){} - - ///reset joint_limit_interfaces - pj_sat_interface_.reset(); - pj_limits_interface_.reset(); - } - } - - - std::cout << "ControlStrategy: " << getControlStrategy() << std::endl; -} From 953cb3d0d64fb0cb22695570b227bd6f9b369bde Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Wed, 8 Jul 2015 22:14:12 +0200 Subject: [PATCH 12/19] [lwr_hw] More updates in the kuka fri interface --- lwr_hw/include/lwr_hw/lwr_hw.h | 6 ++-- lwr_hw/include/lwr_hw/lwr_hw_fri.hpp | 43 ++++++++++++++++++---------- lwr_hw/krl/ros_control.src | 10 ++----- 3 files changed, 35 insertions(+), 24 deletions(-) diff --git a/lwr_hw/include/lwr_hw/lwr_hw.h b/lwr_hw/include/lwr_hw/lwr_hw.h index 34e3a53..2404955 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw.h +++ b/lwr_hw/include/lwr_hw/lwr_hw.h @@ -54,7 +54,7 @@ class LWRHW : public hardware_interface::RobotHW // JOINT_STIFFNESS -> strategy 30 with special configuration, trigered with (ToDo) StiffnessJointInterface // GRAVITY_COMPENSATION -> (not implemented, achieved with low stiffness) // __Note__: StiffnessJointInterface + EffortJointInterface = ImpedanceJointInterface - enum ControlStrategy {JOINT_POSITION = 10, CARTESIAN_IMPEDANCE = 20, JOINT_IMPEDANCE = 30, JOINT_EFFORT = 40, JOINT_STIFFNESS = 50, GRAVITY_COMPENSATION = 50}; + enum ControlStrategy {JOINT_POSITION = 10, CARTESIAN_IMPEDANCE = 20, JOINT_IMPEDANCE = 30, JOINT_EFFORT = 40, JOINT_STIFFNESS = 50, GRAVITY_COMPENSATION = 90}; virtual bool canSwitch(const std::list &start_list, const std::list &stop_list) const; virtual void doSwitch(const std::list &start_list, const std::list &stop_list); @@ -64,13 +64,15 @@ class LWRHW : public hardware_interface::RobotHW virtual void write(ros::Time time, ros::Duration period) = 0; // get/set control method - void setControlStrategy( ControlStrategy strategy){current_strategy_ = strategy;}; // CHECK CONFLICT + void setControlStrategy( ControlStrategy strategy){current_strategy_ = strategy;}; ControlStrategy getControlStrategy(){ return current_strategy_;}; // Hardware interfaces hardware_interface::JointStateInterface state_interface_; hardware_interface::EffortJointInterface effort_interface_; hardware_interface::PositionJointInterface position_interface_; + // hardware_interface::StiffnessJointInterface stiffness_interface_; // ToDo + // hardware_interface::ImpedanceointInterface impedance_interface_; // ToDo ControlStrategy current_strategy_; diff --git a/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp b/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp index 44afb9a..72b156f 100644 --- a/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp +++ b/lwr_hw/include/lwr_hw/lwr_hw_fri.hpp @@ -49,7 +49,6 @@ class LWRHWFRI : public LWRHW << FRI_MAJOR_VERSION << "." << FRI_SUB_VERSION << "." <getState() == FRI_STATE_OFF ) { @@ -102,25 +101,36 @@ class LWRHWFRI : public LWRHW break; case JOINT_IMPEDANCE: - // WHEN THE URDF MODEL IS PRECISE - // 1. compute the gracity term - // f_dyn_solver_->JntToGravity(joint_position_kdl_, gravity_effort_); + for(int j=0; j < n_joints_; j++) + { + newJntPosition[j] = joint_position_command_[j]; + newJntAddTorque[j] = joint_effort_command_[j]; + newJntStiff[j] = joint_stiffness_command_[j]; + newJntDamp[j] = joint_damping_command_[j]; + } + device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, false); + break; - // 2. read gravity term from FRI and add it with opposite sign and add the URDF gravity term - // newJntAddTorque = gravity_effort_ - device_->getF_DYN?? + case JOINT_EFFORT: + for(int j=0; j < n_joints_; j++) + { + newJntAddTorque[j] = joint_effort_command_[j]; + } + // mirror the position + device_->doJntImpedanceControl(device_->getMsrMsrJntPosition(), NULL, NULL, newJntAddTorque, false); + break; + case JOINT_STIFFNESS: for(int j=0; j < n_joints_; j++) { - newJntPosition[j] = joint_position_[j]; - newJntAddTorque[j] = joint_effort_command_[j]; - newJntStiff[j] = 0.01;//joint_stiffness_command_[j]; - newJntDamp[j] = 0.01;//joint_damping_command_[j]; + newJntPosition[j] = joint_position_command_[j]; + newJntStiff[j] = joint_stiffness_command_[j]; } - // device_->doJntImpedanceControl(newJntPosition, newJntStiff, newJntDamp, newJntAddTorque, false); - device_->doJntImpedanceControl(NULL, NULL, NULL, newJntAddTorque, false); + device_->doJntImpedanceControl(newJntPosition, newJntStiff, NULL, NULL, false); break; case GRAVITY_COMPENSATION: + device_->doJntImpedanceControl(device_->getMsrMsrJntPosition(), NULL, NULL, NULL, false); break; } return; @@ -142,8 +152,8 @@ class LWRHWFRI : public LWRHW } else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 ) { - std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_IMPEDANCE)" << std::endl; - desired_strategy = JOINT_IMPEDANCE; + std::cout << "Request to switch to hardware_interface::EffortJointInterface (JOINT_EFFORT)" << std::endl; + desired_strategy = JOINT_EFFORT; break; } } @@ -174,7 +184,10 @@ class LWRHWFRI : public LWRHW stopFRI(); // send to KRL the new strategy - device_->setToKRLInt(0, desired_strategy); + if( desired_strategy == JOINT_POSITION ) + device_->setToKRLInt(0, JOINT_POSITION); + else if( desired_strategy >= JOINT_IMPEDANCE) + device_->setToKRLInt(0, JOINT_IMPEDANCE); startFRI(); diff --git a/lwr_hw/krl/ros_control.src b/lwr_hw/krl/ros_control.src index 2bf986a..11b9e60 100644 --- a/lwr_hw/krl/ros_control.src +++ b/lwr_hw/krl/ros_control.src @@ -81,14 +81,10 @@ DEF ros_control( ) PTP $AXIS_ACT_MES ;Impedance default parameters - $stiffness.axisstiffness={ A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} + ;$stiffness.axisstiffness={A1 1000, A2 1000, A3 1000, A4 1000, A5 1000, A6 1000, E1 1000} + ;$stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} $stiffness.axismaxdeltatrq={A1 100, A2 100, A3 100, A4 100, A5 100, A6 30, E1 30} - $stiffness.maxforce = {X 300.0, Y 300.0, Z 300.0, A 30.0, B 30.0, C 30.0} - $stiffness.cpmaxdelta = {X 100.0, Y 100.0, Z 100.0, A 100.0, B 100.0, C 100.0} $stiffness.axismaxdelta = {A1 100.0, A2 100.0, A3 100.0, A4 100.0, A5 100.0, A6 100.0, E1 100.0} - $stiffness.axisdamping = {A1 0.7, A2 0.7, A3 0.7, A4 0.7, A5 0.7, A6 0.7, E1 0.7} - $stiffness.cpstiffness = {x 200, y 200, z 200, a 20, b 20, c 20} - $stiffness.cpdamping = { x 0.7, y 0.7, z 0.7, a 0.7, b 0.7, c 0.7} ;Start with position control $stiffness.strategy = 10 @@ -101,7 +97,7 @@ BAS (#tool,1 ) ;Specify ip and port retVal = friSetup("192.168.0.150", 49939, 49939) -;Open FRI with datarate 2 msec, change at will +;Open FRI with datarate 2 msec retVal=friOpen(2) ;FOLD Screen output From abe84427a032256d7feddbc177886f09c66a7796 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Fri, 10 Jul 2015 08:53:52 +0200 Subject: [PATCH 13/19] Update single_lwr.launch --- single_lwr_example/single_lwr_launch/launch/single_lwr.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch index e7db62a..28bce8d 100644 --- a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch +++ b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch @@ -51,7 +51,7 @@ - y + From 28cfc9b7a996c16b5fd5c1eb2a04aa1416d64a47 Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Thu, 9 Jul 2015 19:54:52 +0200 Subject: [PATCH 14/19] Update travis to compile with indgo in ubuntu 14.04 BETA --- .travis.yml | 23 ++++++++++------------- README.md | 4 ++-- 2 files changed, 12 insertions(+), 15 deletions(-) diff --git a/.travis.yml b/.travis.yml index 7b36fa8..9b155cd 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,30 +1,27 @@ +# travis beta feature +dist: trusty + language: - cpp compiler: - gcc -env: - global: - - ROS_DISTRO=indigo - before_install: - #- vagrant status - - export CI_SOURCE_PATH=$(pwd) - - export REPOSITORY_NAME=${PWD##*/} - #- codename=`cat /etc/lsb-release | grep -m 1 "DISTRIB_CODENAME=" | cut -d "=" -f2` - - lsb_release -a - - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list' + #- export CI_SOURCE_PATH=$(pwd) + - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-latest.list' - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - - wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add - - - sudo apt-get update + - sudo apt-get update -qq install: - - sudo apt-get install ros-$ROS_DISTRO-desktop-full ros-$ROS_DISTRO-ros-control ros-$ROS_DISTRO-ros-controllers ros-$ROS_DISTRO-gazebo4-ros ros-$ROS_DISTRO-gazebo4-ros-pkgs + - sudo apt-get install ros-indigo-ros-base ros-indigo-cmake-modules ros-indigo-orocos-kdl ros-indigo-kdl-parser ros-indigo-ros-control ros-indigo-ros-controllers ros-indigo-gazebo4-ros ros-indigo-gazebo4-ros-pkgs before_script: - - source /opt/ros/$ROS_DISTRO/setup.bash + - sudo rosdep init + - rosdep update + - source /opt/ros/indigo/setup.bash - mkdir -p ~/catkin_ws/src - export REPOSITORY_NAME=${PWD##*/} - ln -s $(pwd) ~/catkin_ws/src/$REPOSITORY_NAME diff --git a/README.md b/README.md index 19f9dd3..c95ad30 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,8 @@ # KUKA LWR 4+ -[![Build Status](https://api.travis-ci.org/CentroEPiaggio/kuka-lwr.svg)](https://travis-ci.org/CentroEPiaggio/kuka-lwr) (<- waiting for Ubuntu 14.04 support) +[![Build Status](https://api.travis-ci.org/CentroEPiaggio/kuka-lwr.svg)](https://travis-ci.org/CentroEPiaggio/kuka-lwr) -ROS indigo metapackage that contains packages to work with the KUKA LWR 4+. +ROS (tested on indigo) packages to work with the KUKA LWR 4+. ## Overview The main packages are: From ce54935c7aa8ffbf1b0083f82c376c2975ee0351 Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Wed, 15 Jul 2015 15:38:43 +0200 Subject: [PATCH 15/19] Update in the README (include instructions to use FRIL) and comming back to original config file for the Stanford library. --- README.md | 25 ++++++++++++++++--- lwr_hw/launch/lwr_hw.launch | 2 +- .../config/980241-FRI-Driver.init | 8 +++--- 3 files changed, 26 insertions(+), 9 deletions(-) diff --git a/README.md b/README.md index c95ad30..7785215 100644 --- a/README.md +++ b/README.md @@ -18,8 +18,25 @@ For an example using two LWR 4+ arms and two Pisa/IIT SoftHands, see the [Vito r ## Install -ToDo: one should check the commands in the [`.travis.yaml`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/.travis.yml) file when that is working in Ubuntu 14.04. +Check the [`.travis.yaml`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/.travis.yml) file, that'll give you the basic steps to install all necessary packages to compile the package. -The most critical that are not straight forward if you want to use the simulation environment are: -- [Gazebo4](http://gazebosim.org/tutorials?tut=install_ubuntu&ver=4.0&cat=install) or higher -- Slightly modified `transmission_interface` package that allows robot composability in gazebo @ (forked) [ros_control](https://github.com/CentroEPiaggio/ros_control/tree/multi-robot-test) +## Using the Stanford FRI Library + +You need to provide your user name with real time priority and memlock limits higher than the default ones. You can do it permanently like this: + +1. `sudo nano /etc/security/limits.conf` and add these lines: +``` +YOUR_USERNAME hard rtprio 95 +YOUR_USERNAME soft rtprio 95 +YOUR_USERNAME hard memlock unlimited +YOUR_USERNAME soft memlock unlimited +``` +2. `sudo nano /etc/pam.d/common-session` and add +``` +session required pam_limits.so +``` +3. Reboot, open a terminal, and check that `ulimit -r -l` gives you the values set above. + +4. You need to edit manually the [lwr_hw.launch](lwr_hw/launch/lwr_hw.launch) + +5. Load the script that is downloaded with the library and follow the instructions from the [original link](http://cs.stanford.edu/people/tkr/fri/html/) to set up network and other requirements properly. \ No newline at end of file diff --git a/lwr_hw/launch/lwr_hw.launch b/lwr_hw/launch/lwr_hw.launch index e874869..86188ec 100644 --- a/lwr_hw/launch/lwr_hw.launch +++ b/lwr_hw/launch/lwr_hw.launch @@ -14,7 +14,7 @@ - + diff --git a/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init b/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init index 4b73768..8559214 100755 --- a/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init +++ b/single_lwr_example/single_lwr_robot/config/980241-FRI-Driver.init @@ -5,10 +5,10 @@ Name=980241 [Priorities] #Priority range: 1..63 -KRCCommunicationThread=1 -TimerThread=1 -MainThread=1 -OutputConsoleThread=1 +KRCCommunicationThread=60 +TimerThread=55 +MainThread=50 +OutputConsoleThread=5 [ControlValues] # Cycle time in seconds From 4cd99ea6acf231b250d2746f7dd17e5bcdb6da85 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Wed, 15 Jul 2015 15:43:59 +0200 Subject: [PATCH 16/19] Update README.md --- README.md | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 7785215..35d7e46 100644 --- a/README.md +++ b/README.md @@ -24,19 +24,14 @@ Check the [`.travis.yaml`](https://github.com/CentroEPiaggio/kuka-lwr/blob/maste You need to provide your user name with real time priority and memlock limits higher than the default ones. You can do it permanently like this: -1. `sudo nano /etc/security/limits.conf` and add these lines: +1. `sudo nano /etc/security/limits.conf` and add these lines: ``` YOUR_USERNAME hard rtprio 95 YOUR_USERNAME soft rtprio 95 YOUR_USERNAME hard memlock unlimited YOUR_USERNAME soft memlock unlimited ``` -2. `sudo nano /etc/pam.d/common-session` and add -``` -session required pam_limits.so -``` +2. `sudo nano /etc/pam.d/common-session` and add `session required pam_limits.so` 3. Reboot, open a terminal, and check that `ulimit -r -l` gives you the values set above. - 4. You need to edit manually the [lwr_hw.launch](lwr_hw/launch/lwr_hw.launch) - -5. Load the script that is downloaded with the library and follow the instructions from the [original link](http://cs.stanford.edu/people/tkr/fri/html/) to set up network and other requirements properly. \ No newline at end of file +5. Load the script that is downloaded with the library and follow the instructions from the [original link](http://cs.stanford.edu/people/tkr/fri/html/) to set up network and other requirements properly. From 12b9773f98bd2652b36f130d2ff05ca6839bdd67 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Wed, 15 Jul 2015 15:45:31 +0200 Subject: [PATCH 17/19] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 35d7e46..41994dd 100644 --- a/README.md +++ b/README.md @@ -34,4 +34,4 @@ YOUR_USERNAME soft memlock unlimited 2. `sudo nano /etc/pam.d/common-session` and add `session required pam_limits.so` 3. Reboot, open a terminal, and check that `ulimit -r -l` gives you the values set above. 4. You need to edit manually the [lwr_hw.launch](lwr_hw/launch/lwr_hw.launch) -5. Load the script that is downloaded with the library and follow the instructions from the [original link](http://cs.stanford.edu/people/tkr/fri/html/) to set up network and other requirements properly. +5. Load the KRL script that is downloaded with the library to the Robot, and follow the instructions from the [original link](http://cs.stanford.edu/people/tkr/fri/html/) to set up network and other requirements properly. From 67cf4552b163cac6de1fcd15e5e7cddb8037db91 Mon Sep 17 00:00:00 2001 From: "Carlos J. Rosales" Date: Thu, 16 Jul 2015 13:40:48 +0200 Subject: [PATCH 18/19] Update README.md --- README.md | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 41994dd..262b609 100644 --- a/README.md +++ b/README.md @@ -7,7 +7,7 @@ ROS (tested on indigo) packages to work with the KUKA LWR 4+. ## Overview The main packages are: - [__lwr_description__](https://github.com/CentroEPiaggio/kuka-lwr/tree/master/lwr_description): a package that defines the model of the robot (ToDo: name it __lwr_model__) -- [__lwr_hw__](https://github.com/CentroEPiaggio/kuka-lwr/tree/master/lwr_hw): a package that allows communication with an LWR 4+ through FRI or through a gazebo simulation. If you are using the joint impedance control strategy, it adds the gravity term computed from the URDF model. +- [__lwr_hw__](https://github.com/CentroEPiaggio/kuka-lwr/tree/master/lwr_hw): a package that contains the LWR 4+ definition within the ros control framework, and also final interfaces using Kuka FRI, Stanford FRI Library or a Gazebo plugin. Read adding an interface below if you wish to add a different non-existing interface. - [__lwr_controllers__](https://github.com/CentroEPiaggio/kuka-lwr/tree/master/lwr_controllers): a package that implement a set of useful controllers (ToDo: perhaps moving this to a forked version of `ros_controllers` would be ok, but some controllers are specific for the a 7-dof arm). - [__single_lwr_example__](https://github.com/CentroEPiaggio/kuka-lwr/tree/master/single_lwr_example): a cofiguration-based meta-package that shows how to use the `kuka_lwr` packages. - [__single_lwr_robot__](https://github.com/CentroEPiaggio/kuka-lwr/tree/master/single_lwr_example/single_lwr_robot): the package where you define your robot using the LWR 4+ arm. @@ -20,6 +20,19 @@ For an example using two LWR 4+ arms and two Pisa/IIT SoftHands, see the [Vito r Check the [`.travis.yaml`](https://github.com/CentroEPiaggio/kuka-lwr/blob/master/.travis.yml) file, that'll give you the basic steps to install all necessary packages to compile the package. +## Adding more interfaces/platforms + +The package [lwr_hw](lwr_hw) contains the abstraction that allows to make the most of the new ros control framework. The abstraction is enforced with [three pure virtual functions](lwr_hw/include/lwr_hw/lwr_hw.h#L61-L64): +``` c++ + virtual bool init() = 0; + virtual void read(ros::Time time, ros::Duration period) = 0; + virtual void write(ros::Time time, ros::Duration period) = 0; +``` + +Adding an interface boils down to inherit from the [LWRHW class](lwr_hw/include/lwr_hw/lwr_hw.h#L33), implement these three function according to your final platform, and creating either a node or a plugin that uses your new class. This way you can use all your planning and controllers setup in any final real or simulated robot. + +Examples of final interface class implementations are found for the [Kuka FRI](lwr_hw/include/lwr_hw/lwr_hw_fri.hpp), [Stanford FRI library](lwr_hw/include/lwr_hw/lwr_hw_fril.hpp) and a [Gazebo simulation](lwr_hw/include/lwr_hw/lwr_hw_gazebo.hpp). The corresponding nodes and plugin are found [here](lwr_hw/src/lwr_hw_fri_node.cpp), [here](lwr_hw/src/lwr_hw_fril_node.cpp), and [here](lwr_hw/src/lwr_hw_gazebo_plugin.cpp). + ## Using the Stanford FRI Library You need to provide your user name with real time priority and memlock limits higher than the default ones. You can do it permanently like this: From 260651c94c93c26d2749f604ee5454055e2bd084 Mon Sep 17 00:00:00 2001 From: Carlos Rosales Date: Wed, 22 Jul 2015 19:10:49 +0200 Subject: [PATCH 19/19] - Naming issue fixed: - Updated doc to explain how to use the base class. - Updated launch files to consider the new param "name" for nodes - A check in the transmission parsing, return false if no transmission is found - Updated the single_lwr example to reflect the new "name" param for nodes - Added some info prints - Added emergency stop for the kuka fri node --- README.md | 4 +- lwr_hw/CMakeLists.txt | 2 + lwr_hw/launch/lwr_hw.launch | 6 ++- lwr_hw/package.xml | 2 + lwr_hw/src/lwr_hw.cpp | 14 ++++++- lwr_hw/src/lwr_hw_fri_node.cpp | 41 +++++++++++++++++-- lwr_hw/src/lwr_hw_fril_node.cpp | 6 ++- .../launch/single_lwr.launch | 3 ++ .../single_lwr_robot/config/hw_interface.yaml | 1 + 9 files changed, 69 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index 262b609..b644cf3 100644 --- a/README.md +++ b/README.md @@ -22,7 +22,9 @@ Check the [`.travis.yaml`](https://github.com/CentroEPiaggio/kuka-lwr/blob/maste ## Adding more interfaces/platforms -The package [lwr_hw](lwr_hw) contains the abstraction that allows to make the most of the new ros control framework. The abstraction is enforced with [three pure virtual functions](lwr_hw/include/lwr_hw/lwr_hw.h#L61-L64): +The package [lwr_hw](lwr_hw) contains the abstraction that allows to make the most of the new ros control framework. To create an instance of the arm you need to call the function [`void LWRHW::create(std::string name, std::string urdf_string)`](lwr_hw/include/lwr_hw/lwr_hw.h#L40), where `name` MUST match the name you give to the xacro instance in the URDF and the `urdf_string` is any robot description containing one single instance of the lwr called as `name` (note that, several lwr can exist in `urdf_string` if they are called differently). + +The abstraction is enforced with [three pure virtual functions](lwr_hw/include/lwr_hw/lwr_hw.h#L61-L64): ``` c++ virtual bool init() = 0; virtual void read(ros::Time time, ros::Duration period) = 0; diff --git a/lwr_hw/CMakeLists.txt b/lwr_hw/CMakeLists.txt index 62e5d4b..a7d7da3 100644 --- a/lwr_hw/CMakeLists.txt +++ b/lwr_hw/CMakeLists.txt @@ -19,6 +19,7 @@ find_package(catkin REQUIRED COMPONENTS kdl_parser transmission_interface gazebo_ros + std_msgs ) add_definitions (-fpermissive -std=c++11) @@ -39,6 +40,7 @@ catkin_package( kdl_parser transmission_interface gazebo_ros + std_msgs INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} lwr_hw_gazebo_plugin friremote frilremote DEPENDS gazebo diff --git a/lwr_hw/launch/lwr_hw.launch b/lwr_hw/launch/lwr_hw.launch index 86188ec..e5ec99e 100644 --- a/lwr_hw/launch/lwr_hw.launch +++ b/lwr_hw/launch/lwr_hw.launch @@ -1,7 +1,8 @@ - + + @@ -11,10 +12,11 @@ + - + diff --git a/lwr_hw/package.xml b/lwr_hw/package.xml index c4b04de..969586d 100644 --- a/lwr_hw/package.xml +++ b/lwr_hw/package.xml @@ -24,6 +24,7 @@ kdl_parser joint_limits_interface gazebo_ros + std_msgs gazebo gazebo_ros @@ -41,6 +42,7 @@ kdl_parser joint_limits_interface gazebo_ros + std_msgs diff --git a/lwr_hw/src/lwr_hw.cpp b/lwr_hw/src/lwr_hw.cpp index 22e98fa..0e99fab 100644 --- a/lwr_hw/src/lwr_hw.cpp +++ b/lwr_hw/src/lwr_hw.cpp @@ -4,6 +4,8 @@ namespace lwr_hw { void LWRHW::create(std::string name, std::string urdf_string) { + std::cout << "Creating a KUKA LWR 4+ called: " << name << std::endl; + // SET NAME AND MODEL robot_namespace_ = name; urdf_string_ = urdf_string; @@ -41,19 +43,26 @@ namespace lwr_hw // RESET VARIABLES reset(); + std::cout << "Parsing transmissions from the URDF..." << std::endl; + // GET TRANSMISSIONS THAT BELONG TO THIS LWR 4+ ARM if (!parseTransmissionsFromURDF(urdf_string_)) { std::cout << "lwr_hw: " << "Error parsing URDF in lwr_hw.\n" << std::endl; return; } + + std::cout << "Registering interfaces..." << std::endl; + const urdf::Model *const urdf_model_ptr = urdf_model_.initString(urdf_string_) ? &urdf_model_ : NULL; registerInterfaces(urdf_model_ptr, transmissions_); + std::cout << "Initializing KDL variables..." << std::endl; + // INIT KDL STUFF initKDLdescription(urdf_model_ptr); - std::cout << "Succesfully created an abstract LWR 4+ ARM with interfaces" << std::endl; + std::cout << "Succesfully created an abstract LWR 4+ ARM with interfaces to ROS control" << std::endl; } // reset values @@ -296,6 +305,9 @@ namespace lwr_hw } } + if( transmissions_.empty() ) + return false; + return true; } diff --git a/lwr_hw/src/lwr_hw_fri_node.cpp b/lwr_hw/src/lwr_hw_fri_node.cpp index 2969879..23bb46f 100644 --- a/lwr_hw/src/lwr_hw_fri_node.cpp +++ b/lwr_hw/src/lwr_hw_fri_node.cpp @@ -8,6 +8,7 @@ // ROS headers #include #include +#include // the lwr hw fri interface #include "lwr_hw/lwr_hw_fri.hpp" @@ -19,6 +20,13 @@ void quitRequested(int sig) g_quit = true; } +bool isStopPressed = false; +bool wasStopHandled = true; +void eStopCB(const std_msgs::BoolConstPtr& e_stop_msg) +{ + isStopPressed = e_stop_msg->data; +} + // Get the URDF XML from the parameter server std::string getURDF(ros::NodeHandle &model_nh_, std::string param_name) { @@ -46,7 +54,7 @@ std::string getURDF(ros::NodeHandle &model_nh_, std::string param_name) usleep(100000); } - ROS_DEBUG_STREAM_NAMED("LWRHWFRI", "Recieved urdf from param server, parsing..."); + ROS_DEBUG_STREAM_NAMED("LWRHWFRI", "Received URDF from param server, parsing..."); return urdf_string; } @@ -71,15 +79,20 @@ int main( int argc, char** argv ) // get params or give default values int port; std::string hintToRemoteHost; + std::string name; lwr_nh.param("port", port, 49939); lwr_nh.param("ip", hintToRemoteHost, std::string("192.168.0.10") ); + lwr_nh.param("name", name, std::string("lwr")); + // advertise the e-stop topic + ros::Subscriber estop_sub = lwr_nh.subscribe(lwr_nh.resolveName("emergency_stop"), 1, eStopCB); + + // get the general robot description, the lwr class will take care of parsing what's useful to itself std::string urdf_string = getURDF(lwr_nh, "/robot_description"); // construct and start the real lwr lwr_hw::LWRHWFRI lwr_robot; - std::cout << "namespace: " << lwr_nh.getNamespace() << std::endl; - lwr_robot.create(std::string("lwr"), urdf_string); + lwr_robot.create(name, urdf_string); lwr_robot.setPort(port); lwr_robot.setIP(hintToRemoteHost); if(!lwr_robot.init()) @@ -116,8 +129,28 @@ int main( int argc, char** argv ) // read the state from the lwr lwr_robot.read(now, period); + // Compute the controller commands + bool resetControllers; + if(!wasStopHandled && !resetControllers) + { + ROS_WARN("E-STOP HAS BEEN PRESSED: Controllers will be restarted, but the robot won't move until you release the E-Stop"); + ROS_WARN("HOW TO RELEASE E-STOP: rostopic pub -r 10 /NAMESPACE/emergency_stop std_msgs/Bool 'data: false'"); + resetControllers = true; + wasStopHandled = true; + } + + if( isStopPressed ) + { + wasStopHandled = false; + } + else + { + resetControllers = false; + wasStopHandled = true; + } + // update the controllers - manager.update(now, period); + manager.update(now, period, resetControllers); // write the command to the lwr lwr_robot.write(now, period); diff --git a/lwr_hw/src/lwr_hw_fril_node.cpp b/lwr_hw/src/lwr_hw_fril_node.cpp index c5c6138..54bcdea 100644 --- a/lwr_hw/src/lwr_hw_fril_node.cpp +++ b/lwr_hw/src/lwr_hw_fril_node.cpp @@ -70,14 +70,16 @@ int main( int argc, char** argv ) // get params or give default values std::string file; + std::string name; lwr_nh.param("file", file, std::string("")); + lwr_nh.param("name", name, std::string("lwr")); + // get the general robot description, the lwr class will take care of parsing what's useful to itself std::string urdf_string = getURDF(lwr_nh, "/robot_description"); // construct and start the real lwr lwr_hw::LWRHWFRIL lwr_robot; - std::cout << "namespace: " << lwr_nh.getNamespace() << std::endl; - lwr_robot.create(std::string("lwr"), urdf_string); + lwr_robot.create(name, urdf_string); lwr_robot.setInitFile(file); if(!lwr_robot.init()) { diff --git a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch index 28bce8d..b5c3fd6 100644 --- a/single_lwr_example/single_lwr_launch/launch/single_lwr.launch +++ b/single_lwr_example/single_lwr_launch/launch/single_lwr.launch @@ -93,6 +93,9 @@ + + + diff --git a/single_lwr_example/single_lwr_robot/config/hw_interface.yaml b/single_lwr_example/single_lwr_robot/config/hw_interface.yaml index 21c4cfc..7f8a113 100644 --- a/single_lwr_example/single_lwr_robot/config/hw_interface.yaml +++ b/single_lwr_example/single_lwr_robot/config/hw_interface.yaml @@ -1,3 +1,4 @@ +# make the namespace match the name you use to instantiate the arm in the xacro lwr: root: lwr_base_link tip: lwr_7_link