From 9cd7f43d2c0cbc8bd12d6118a46777920c9715d6 Mon Sep 17 00:00:00 2001 From: Walter Fetter Lages Date: Tue, 20 Mar 2018 13:49:54 -0300 Subject: [PATCH] Initial commit twil_control_gazebo twil_controllers: Linearizing controller uses dynamic model computed though KDL, which does not work for mobile robots. twil_description --- .gitignore | 51 +++++++ CMakeLists.txt | 17 +++ Makefile | 1 + stack.xml | 9 ++ twil_control_gazebo/CMakeLists.txt | 33 +++++ twil_control_gazebo/Makefile | 1 + twil_control_gazebo/manifest.xml | 23 +++ twil_control_gazebo/robot_sim_plugins.xml | 12 ++ twil_control_gazebo/src/robot_sim_twil.cpp | 97 ++++++++++++ twil_controllers/CMakeLists.txt | 30 ++++ twil_controllers/Makefile | 1 + twil_controllers/README | 3 + twil_controllers/config/effort_control.yaml | 13 ++ twil_controllers/config/linearizing_control.yaml | 11 ++ twil_controllers/config/velocity_control.yaml | 16 ++ .../twil_controllers/cart_linearizing_controller.h | 54 +++++++ twil_controllers/launch/cart_linearizing.launch | 11 ++ twil_controllers/launch/joint_effort.launch | 9 ++ twil_controllers/launch/joint_velocity.launch | 9 ++ twil_controllers/manifest.xml | 24 +++ .../src/cart_linearizing_controller.cpp | 162 +++++++++++++++++++++ twil_controllers/twil_controllers_plugins.xml | 11 ++ twil_description/CMakeLists.txt | 30 ++++ twil_description/Makefile | 1 + .../doc/dimensions_battery_bosch_12v.pdf | Bin 0 -> 26816 bytes twil_description/doc/dimensions_chassis.pdf | Bin 0 -> 70581 bytes twil_description/doc/dimensions_cpu.pdf | Bin 0 -> 28306 bytes twil_description/launch/twil.launch | 4 + twil_description/launch/twil_sim.launch | 6 + twil_description/launch/twil_wam.launch | 4 + twil_description/launch/twil_wam_sim.launch | 7 + twil_description/manifest.xml | 14 ++ twil_description/meshes/battery_bosch_12v.stl | Bin 0 -> 57284 bytes twil_description/meshes/castor_base.stl | Bin 0 -> 17484 bytes twil_description/meshes/castor_support.stl | Bin 0 -> 20984 bytes twil_description/meshes/castor_wheel.stl | Bin 0 -> 40184 bytes twil_description/meshes/chassis.stl | Bin 0 -> 153284 bytes twil_description/meshes/cpu.stl | Bin 0 -> 46884 bytes twil_description/meshes/fixed_wheel.stl | Bin 0 -> 31184 bytes twil_description/meshes/fixed_wheel_support.stl | Bin 0 -> 76584 bytes twil_description/meshes/left_wheel_support.stl | Bin 0 -> 76584 bytes twil_description/meshes/right_wheel_support.stl | Bin 0 -> 76584 bytes .../xacro/battery_bosch_12v.urdf.xacro | 42 ++++++ twil_description/xacro/castor_base.urdf.xacro | 44 ++++++ twil_description/xacro/castor_support.urdf.xacro | 42 ++++++ twil_description/xacro/castor_wheel.urdf.xacro | 43 ++++++ twil_description/xacro/chassis.urdf.xacro | 43 ++++++ twil_description/xacro/cpu.urdf.xacro | 42 ++++++ twil_description/xacro/eurocard.urdf.xacro | 47 ++++++ twil_description/xacro/fixed_wheel.urdf.xacro | 43 ++++++ .../xacro/fixed_wheel_support.urdf.xacro | 42 ++++++ twil_description/xacro/twil.urdf.xacro | 101 +++++++++++++ twil_description/xacro/twil_wam.urdf.xacro | 31 ++++ 53 files changed, 1184 insertions(+) create mode 100644 .gitignore create mode 100644 CMakeLists.txt create mode 100644 Makefile create mode 100644 stack.xml create mode 100644 twil_control_gazebo/CMakeLists.txt create mode 100644 twil_control_gazebo/Makefile create mode 100644 twil_control_gazebo/manifest.xml create mode 100644 twil_control_gazebo/robot_sim_plugins.xml create mode 100644 twil_control_gazebo/src/robot_sim_twil.cpp create mode 100644 twil_controllers/CMakeLists.txt create mode 100644 twil_controllers/Makefile create mode 100644 twil_controllers/README create mode 100644 twil_controllers/config/effort_control.yaml create mode 100644 twil_controllers/config/linearizing_control.yaml create mode 100644 twil_controllers/config/velocity_control.yaml create mode 100644 twil_controllers/include/twil_controllers/cart_linearizing_controller.h create mode 100644 twil_controllers/launch/cart_linearizing.launch create mode 100644 twil_controllers/launch/joint_effort.launch create mode 100644 twil_controllers/launch/joint_velocity.launch create mode 100644 twil_controllers/manifest.xml create mode 100644 twil_controllers/src/cart_linearizing_controller.cpp create mode 100644 twil_controllers/twil_controllers_plugins.xml create mode 100644 twil_description/CMakeLists.txt create mode 100644 twil_description/Makefile create mode 100644 twil_description/doc/dimensions_battery_bosch_12v.pdf create mode 100644 twil_description/doc/dimensions_chassis.pdf create mode 100644 twil_description/doc/dimensions_cpu.pdf create mode 100644 twil_description/launch/twil.launch create mode 100644 twil_description/launch/twil_sim.launch create mode 100644 twil_description/launch/twil_wam.launch create mode 100644 twil_description/launch/twil_wam_sim.launch create mode 100644 twil_description/manifest.xml create mode 100644 twil_description/meshes/battery_bosch_12v.stl create mode 100644 twil_description/meshes/castor_base.stl create mode 100644 twil_description/meshes/castor_support.stl create mode 100644 twil_description/meshes/castor_wheel.stl create mode 100644 twil_description/meshes/chassis.stl create mode 100644 twil_description/meshes/cpu.stl create mode 100644 twil_description/meshes/fixed_wheel.stl create mode 100644 twil_description/meshes/fixed_wheel_support.stl create mode 100644 twil_description/meshes/left_wheel_support.stl create mode 100644 twil_description/meshes/right_wheel_support.stl create mode 100644 twil_description/xacro/battery_bosch_12v.urdf.xacro create mode 100644 twil_description/xacro/castor_base.urdf.xacro create mode 100644 twil_description/xacro/castor_support.urdf.xacro create mode 100644 twil_description/xacro/castor_wheel.urdf.xacro create mode 100644 twil_description/xacro/chassis.urdf.xacro create mode 100644 twil_description/xacro/cpu.urdf.xacro create mode 100644 twil_description/xacro/eurocard.urdf.xacro create mode 100644 twil_description/xacro/fixed_wheel.urdf.xacro create mode 100644 twil_description/xacro/fixed_wheel_support.urdf.xacro create mode 100644 twil_description/xacro/twil.urdf.xacro create mode 100644 twil_description/xacro/twil_wam.urdf.xacro diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..35d74bb --- /dev/null +++ b/.gitignore @@ -0,0 +1,51 @@ +devel/ +logs/ +build/ +bin/ +lib/ +msg_gen/ +srv_gen/ +msg/*Action.msg +msg/*ActionFeedback.msg +msg/*ActionGoal.msg +msg/*ActionResult.msg +msg/*Feedback.msg +msg/*Goal.msg +msg/*Result.msg +msg/_*.py +build_isolated/ +devel_isolated/ + +# Generated by dynamic reconfigure +*.cfgc +/cfg/cpp/ +/cfg/*.py + +# Ignore generated docs +*.dox +*.wikidoc + +# eclipse stuff +.project +.cproject + +# qcreator stuff +CMakeLists.txt.user + +srv/_*.py +*.pcd +*.pyc +qtcreator-* +*.user + +/planning/cfg +/planning/docs +/planning/src + +*~ + +# Emacs +.#* + +# Catkin custom files +CATKIN_IGNORE diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..28105dd --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of +# directories (or patterns, but directories should suffice) that should +# be excluded from the distro. This is not the place to put things that +# should be ignored everywhere, like "build" directories; that happens in +# rosbuild/rosbuild.cmake. Here should be listed packages that aren't +# ready for inclusion in a distro. +# +# This list is combined with the list in rosbuild/rosbuild.cmake. Note +# that CMake 2.6 may be required to ensure that the two lists are combined +# properly. CMake 2.4 seems to have unpredictable scoping rules for such +# variables. +#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental) + +rosbuild_make_distribution(0.1.0) diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..a818cca --- /dev/null +++ b/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake_stack.mk \ No newline at end of file diff --git a/stack.xml b/stack.xml new file mode 100644 index 0000000..dd41a6b --- /dev/null +++ b/stack.xml @@ -0,0 +1,9 @@ + + TWIL + Maintained by Taiser Barros + GPL + + http://ros.org/wiki/twil + + + diff --git a/twil_control_gazebo/CMakeLists.txt b/twil_control_gazebo/CMakeLists.txt new file mode 100644 index 0000000..0796ff6 --- /dev/null +++ b/twil_control_gazebo/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) + +# Build RobotSim Interface +rosbuild_add_library(twil_control_gazebo src/robot_sim_twil.cpp) diff --git a/twil_control_gazebo/Makefile b/twil_control_gazebo/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/twil_control_gazebo/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/twil_control_gazebo/manifest.xml b/twil_control_gazebo/manifest.xml new file mode 100644 index 0000000..c3790a8 --- /dev/null +++ b/twil_control_gazebo/manifest.xml @@ -0,0 +1,23 @@ + + + + twil_control_gazebo + + + Walter Fetter Lages + GPL + + http://ros.org/wiki/twil_control_gazebo + + + + + + + + + + + + + diff --git a/twil_control_gazebo/robot_sim_plugins.xml b/twil_control_gazebo/robot_sim_plugins.xml new file mode 100644 index 0000000..9d6b5f8 --- /dev/null +++ b/twil_control_gazebo/robot_sim_plugins.xml @@ -0,0 +1,12 @@ + + + + + A ROS/Gazebo interface Twil, exporting a joint_state_interface and a + joint_effort_interface. + + + diff --git a/twil_control_gazebo/src/robot_sim_twil.cpp b/twil_control_gazebo/src/robot_sim_twil.cpp new file mode 100644 index 0000000..e88b33c --- /dev/null +++ b/twil_control_gazebo/src/robot_sim_twil.cpp @@ -0,0 +1,97 @@ +#include + +#include +#include + +#include + +#include + +#include +#include +#include + +namespace twil_control_gazebo +{ + + class RobotSimTwil:public ros_control_gazebo::RobotSim + { + + unsigned int n_dof_; + + hardware_interface::JointStateInterface js_interface_; + hardware_interface::EffortJointInterface ej_interface_; + + std::vector joint_name_; + std::vector joint_position_; + std::vector joint_velocity_; + std::vector joint_effort_; + std::vector joint_effort_command_; + + std::vector sim_joints_; + + public: + + RobotSimTwil(void):n_dof_(2),joint_name_(n_dof_),joint_position_(n_dof_), + joint_velocity_(n_dof_),joint_effort_(n_dof_),joint_effort_command_(n_dof_) + { + + joint_name_[0]="left_wheel_joint"; + joint_name_[1]="right_wheel_joint"; + + for(unsigned int j=0;j < n_dof_;j++) + { + joint_position_[j]=0.0; + joint_velocity_[j]=0.0; + joint_effort_[j]=0.0; + + joint_effort_command_[j] = 0.0; + + js_interface_.registerJoint(joint_name_[j],&joint_position_[j],&joint_velocity_[j],&joint_effort_[j]); + ej_interface_.registerJoint(js_interface_.getJointStateHandle(joint_name_[j]),&joint_effort_command_[j]); + } + + registerInterface(&js_interface_); + registerInterface(&ej_interface_); + } + + + bool initSim(ros::NodeHandle nh,gazebo::physics::ModelPtr model) + { + for(unsigned int j=0;j < n_dof_;j++) + { + ROS_INFO_STREAM("Getting pointer to gazebo joint: " << joint_name_[j]); + gazebo::physics::JointPtr joint=model->GetJoint(joint_name_[j]); + if(joint) sim_joints_.push_back(joint); + else + { + ROS_ERROR_STREAM("This robot has a joint named \"" << joint_name_[j] + <<"\" which is not in the gazebo model."); + return false; + } + } + return true; + } + + void readSim(ros::Time time,ros::Duration period) + { + for(unsigned int j=0; j < n_dof_;j++) + { +// joint_position_[j]+=angles::shortest_angular_distance +// (joint_position_[j],sim_joints_[j]->GetAngle(0).GetAsRadian()); + joint_position_[j]=sim_joints_[j]->GetAngle(0).GetAsRadian(); + joint_velocity_[j]=sim_joints_[j]->GetVelocity(0); +// joint_effort_[j]=sim_joints_[j]->GetForce(0); + joint_effort_[j]=joint_effort_command_[j]; + } + } + + void writeSim(ros::Time time,ros::Duration period) + { + for(unsigned int j=0;j < n_dof_;j++) sim_joints_[j]->SetForce(0,joint_effort_command_[j]); + } + + }; +} + +PLUGINLIB_DECLARE_CLASS(twil_control_gazebo,RobotSimTwil,twil_control_gazebo::RobotSimTwil,ros_control_gazebo::RobotSim) diff --git a/twil_controllers/CMakeLists.txt b/twil_controllers/CMakeLists.txt new file mode 100644 index 0000000..97a29cd --- /dev/null +++ b/twil_controllers/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +rosbuild_add_library(${PROJECT_NAME} src/cart_linearizing_controller.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) diff --git a/twil_controllers/Makefile b/twil_controllers/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/twil_controllers/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/twil_controllers/README b/twil_controllers/README new file mode 100644 index 0000000..326c0d8 --- /dev/null +++ b/twil_controllers/README @@ -0,0 +1,3 @@ +To publish v: + +rostopic pub /twil/cart_linearizing_controller/command std_msgs/Float64MultiArray "data: [0.0, 0.04]" diff --git a/twil_controllers/config/effort_control.yaml b/twil_controllers/config/effort_control.yaml new file mode 100644 index 0000000..bdca9e8 --- /dev/null +++ b/twil_controllers/config/effort_control.yaml @@ -0,0 +1,13 @@ +twil: + + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + + left_wheel_joint_effort_controller: + type: effort_controllers/JointEffortController + joint: left_wheel_joint + + right_wheel_joint_effort_controller: + type: effort_controllers/JointEffortController + joint: right_wheel_joint diff --git a/twil_controllers/config/linearizing_control.yaml b/twil_controllers/config/linearizing_control.yaml new file mode 100644 index 0000000..a393a24 --- /dev/null +++ b/twil_controllers/config/linearizing_control.yaml @@ -0,0 +1,11 @@ +twil: + + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + + cart_linearizing_controller: + type: twil_controllers/CartLinearizingController + joints: + - left_wheel_joint + - right_wheel_joint diff --git a/twil_controllers/config/velocity_control.yaml b/twil_controllers/config/velocity_control.yaml new file mode 100644 index 0000000..54aa494 --- /dev/null +++ b/twil_controllers/config/velocity_control.yaml @@ -0,0 +1,16 @@ +twil: + + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + + left_wheel_joint_velocity_controller: + type: effort_controllers/JointVelocityController + joint: left_wheel_joint + pid: {p: 0.0, i: 0.0, d: 0.0} + + right_wheel_joint_velocity_controller: + type: effort_controllers/JointVelocityController + joint: right_wheel_joint + pid: {p: 0.0, i: 0.0, d: 0.0} + diff --git a/twil_controllers/include/twil_controllers/cart_linearizing_controller.h b/twil_controllers/include/twil_controllers/cart_linearizing_controller.h new file mode 100644 index 0000000..bb27196 --- /dev/null +++ b/twil_controllers/include/twil_controllers/cart_linearizing_controller.h @@ -0,0 +1,54 @@ +#ifndef TWIL_CONTROLLERS_CART_LINEARIZING_CONTROLLER_H +#define TWIL_CONTROLLERS_CART_LINEARIZING_CONTROLLER_H + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + + +namespace twil_controllers +{ + class CartLinearizingController: public controller_interface::Controller + { + public: + CartLinearizingController(void); + ~CartLinearizingController(void); + + bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); + void starting(const ros::Time& time); + void update(const ros::Time& time); + + private: + ros::NodeHandle node_; + ros::Time last_time_; + hardware_interface::EffortJointInterface *robot_; + std::vector joints_; + + void commandCB(const std_msgs::Float64MultiArray::ConstPtr &command); + ros::Subscriber sub_command_; + + KDL::ChainIdSolver_RNE *idsolver; + + KDL::JntArray phi; + KDL::JntArray nu; + KDL::JntArray dnu; + KDL::JntArray torque; + std::vector v; + + KDL::Wrenches fext; + + std::vector wheelRadius; + double wheelBase; + }; +} +#endif diff --git a/twil_controllers/launch/cart_linearizing.launch b/twil_controllers/launch/cart_linearizing.launch new file mode 100644 index 0000000..deccc45 --- /dev/null +++ b/twil_controllers/launch/cart_linearizing.launch @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/twil_controllers/launch/joint_effort.launch b/twil_controllers/launch/joint_effort.launch new file mode 100644 index 0000000..c1ac051 --- /dev/null +++ b/twil_controllers/launch/joint_effort.launch @@ -0,0 +1,9 @@ + + + + + + + + diff --git a/twil_controllers/launch/joint_velocity.launch b/twil_controllers/launch/joint_velocity.launch new file mode 100644 index 0000000..4760f53 --- /dev/null +++ b/twil_controllers/launch/joint_velocity.launch @@ -0,0 +1,9 @@ + + + + + + + + diff --git a/twil_controllers/manifest.xml b/twil_controllers/manifest.xml new file mode 100644 index 0000000..9c40ae9 --- /dev/null +++ b/twil_controllers/manifest.xml @@ -0,0 +1,24 @@ + + + + twil_controllers + + + Walter Fetter Lages + GPL + + http://ros.org/wiki/twil_controllers + + + + + + + + + + + + + + diff --git a/twil_controllers/src/cart_linearizing_controller.cpp b/twil_controllers/src/cart_linearizing_controller.cpp new file mode 100644 index 0000000..3d8a03c --- /dev/null +++ b/twil_controllers/src/cart_linearizing_controller.cpp @@ -0,0 +1,162 @@ +#include +#include + +#include +#include +#include + +namespace twil_controllers +{ + CartLinearizingController::CartLinearizingController(void): + phi(0),nu(0),dnu(0),torque(0),v(0),fext(0),wheelRadius(0) + { + } + + CartLinearizingController::~CartLinearizingController(void) + { + sub_command_.shutdown(); + } + + bool CartLinearizingController::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n) + { + node_=n; + robot_=robot; + + XmlRpc::XmlRpcValue joint_names; + if(!node_.getParam("joints",joint_names)) + { + ROS_ERROR("No 'joints' parameter in controller. (namespace: %s)",node_.getNamespace().c_str()); + return false; + } + + if(joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) + { + ROS_ERROR("The 'joints' parameter is not a struct. (namespace: %s)",node_.getNamespace().c_str()); + return false; + } + + for(int i=0; i < joint_names.size();i++) + { + XmlRpc::XmlRpcValue &name_value=joint_names[i]; + if(name_value.getType() != XmlRpc::XmlRpcValue::TypeString) + { + ROS_ERROR("Array of joint names should contain only strings. (namespace: %s)",node_.getNamespace().c_str()); + return false; + } + + hardware_interface::JointHandle j=robot->getJointHandle((std::string)name_value); + joints_.push_back(j); + v.push_back(0); + } + sub_command_ = node_.subscribe("command",1000,&CartLinearizingController::commandCB, this); + + std::string robot_desc_string; + if(!node_.getParam("/robot_description",robot_desc_string)) + { + ROS_ERROR("Could not find '/robot_description'."); + return false; + } + + KDL::Tree tree; + if (!kdl_parser::treeFromString(robot_desc_string,tree)) + { + ROS_ERROR("Failed to construct KDL tree."); + return false; + } + + KDL::Chain chain; + if (!tree.getChain("left_wheel","right_wheel",chain)) + { + ROS_ERROR("Failed to get chain from KDL tree."); + return false; + } + + // Get gravity from gazebo or set values if not simulating + KDL::Vector g; + node_.param("/gazebo/gravity_x",g[1],0.0); + node_.param("/gazebo/gravity_y",g[1],0.0); + node_.param("/gazebo/gravity_z",g[2],-9.8); + + if((idsolver=new KDL::ChainIdSolver_RNE(chain,g)) == NULL) + { + ROS_ERROR("Failed to create ChainIDSolver_RNE."); + return false; + } + + // get wheelBase from URDF (actually from KDL tree) + KDL::SegmentMap::const_iterator segmentMapIter=tree.getSegment("left_wheel_support"); + KDL::Frame leftSupportFrame=segmentMapIter->second.segment.getFrameToTip(); + + segmentMapIter=tree.getSegment("right_wheel_support"); + KDL::Frame rightSupportFrame=segmentMapIter->second.segment.getFrameToTip(); + + wheelRadius.resize(chain.getNrOfJoints()); + wheelBase=leftSupportFrame(1,3)-rightSupportFrame(1,3); + + // get wheelRadius from URDF (actually from KDL tree) + segmentMapIter=tree.getSegment("chassis"); + KDL::Frame chassisFrame=segmentMapIter->second.segment.getFrameToTip(); + + segmentMapIter=tree.getSegment("left_wheel"); + KDL::Joint leftWheelJoint=segmentMapIter->second.segment.getJoint(); + wheelRadius[0]=chassisFrame(2,3)+leftSupportFrame(2,3)+leftWheelJoint.JointOrigin().z(); + + segmentMapIter=tree.getSegment("right_wheel"); + KDL::Joint rightWheelJoint=segmentMapIter->second.segment.getJoint(); + wheelRadius[1]=chassisFrame(2,3)+rightSupportFrame(2,3)+rightWheelJoint.JointOrigin().z(); + + // set vectors to the right size + phi.resize(chain.getNrOfJoints()); + nu.resize(chain.getNrOfJoints()); + dnu.resize(chain.getNrOfJoints()); + torque.resize(chain.getNrOfJoints()); + + fext.resize(chain.getNrOfSegments()); + + return true; + } + + void CartLinearizingController::starting(const ros::Time& time) + { + last_time_=time; + for(unsigned int i=0; i < joints_.size();i++) v[i]=0.0; + } + + void CartLinearizingController::update(const ros::Time& time) + { + ros::Duration dt=time-last_time_; + last_time_=time; + + for(unsigned int i=0;i < joints_.size();i++) + { + phi(i)=joints_[i].getPosition(); + nu(i)=joints_[i].getVelocity(); + } + + + dnu(0)=v[0]/wheelRadius[0]-v[1]*wheelBase/2.0/wheelRadius[0]; // left wheel + dnu(1)=v[0]/wheelRadius[1]+v[1]*wheelBase/2.0/wheelRadius[1]; // right wheel + + + for(unsigned int i=0;i < fext.size();i++) fext[i].Zero(); + + for(unsigned int i=0;i < joints_.size();i++) + std::cout << "phi=" << phi(i) << " nu=" << nu(i) + << " dnu=" << dnu(i) << std::endl; + + // Compute linearization. + if(idsolver->CartToJnt(phi,nu,dnu,fext,torque) < 0) ROS_ERROR("KDL inverse dynamics solver failed."); + + for(unsigned int i=0;i < joints_.size(); i++) + std::cout << "torque=" << torque(i) << std::endl; + + // Apply torques + for(unsigned int i=0;i < joints_.size();i++) joints_[i].setCommand(torque(i)); + } + + void CartLinearizingController::commandCB(const std_msgs::Float64MultiArray::ConstPtr &command) + { + for(unsigned int i=0;i < command->data.size();i++) v[i]=command->data[i]; + } +} +PLUGINLIB_DECLARE_CLASS(twil_controllers,CartLinearizingController,twil_controllers::CartLinearizingController,controller_interface::ControllerBase) diff --git a/twil_controllers/twil_controllers_plugins.xml b/twil_controllers/twil_controllers_plugins.xml new file mode 100644 index 0000000..2348f16 --- /dev/null +++ b/twil_controllers/twil_controllers_plugins.xml @@ -0,0 +1,11 @@ + + + + + The CartLinearizingController linearizes the Twil dynamic model. The + linearized inputs are linear and angular accelerations. It expects a + EffortJointInterface type of hardware interface. + + + + diff --git a/twil_description/CMakeLists.txt b/twil_description/CMakeLists.txt new file mode 100644 index 0000000..f8f1c9c --- /dev/null +++ b/twil_description/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) diff --git a/twil_description/Makefile b/twil_description/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/twil_description/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/twil_description/doc/dimensions_battery_bosch_12v.pdf b/twil_description/doc/dimensions_battery_bosch_12v.pdf new file mode 100644 index 0000000000000000000000000000000000000000..2184e85f56cba86bf821494bde00bbbd3fb014b6 GIT binary patch literal 26816 zcma&N1yo$kwk?cXkU(&4f;-)~ySux)yAxc4ySsaEg1bAxA!v}`?(oRD=lq0^ ze~;0oen z0{9OH5`w#d%ZknwNhF|jj({@RY2ndNWoSQtTn^TEQx`nPthK-PCq{~Z6C8!J1AO_P^OU z*#2q*F|zzE77!yl=x^Q;0seJv zAQ15HecwC(bv-~J(BIYw1Y%xT z?L8?FoSY3Do&Ssdj7SJ%WFm5+NC>douGY!8VI2hJGvL_P4dw&1Z*FQ7;4}|~J4H*+>17ibc1HgM4y<;io z;%xn{Bu)U(e_<D8J$k7PByLEB&5VLbOw=iN5HgPg~hu^@~`A?g7fd30W5!-i~ zSlF5|NEp92w{Z5L6K7CzF?9X|>mO|2o!Y6`TKwVCyO95h^1q_^GswT9_=D{~qxcUT z{3rX^SXll=I`QyGWgRPgAfk7d-qwCEN1gEqYhv#@*$eoupHdccj%394LA=+CZqJQv z67Y0AwXRdRQKCCM*>1Z@OEzzMzQ@BlYo~j2FMTQdV>M56bA59+m+o)g9o{aBW2bxl zIU~?+ubm%+vx5Sh_BZIm%qF+te3_8(tv01c%;>i#W7_V7hx2mP;iZ0Gg%yK^IFd@!y0RB*IY_|I|39kPS8VW=@N0bAHazLmUX>D&}%qHt*~_GbFs|4 zu0A$)Zbrw;a}O?nhHf$OO13#Poa1@$racQ#KSfh~o-To-4L1DhKow)wj|$x3hx#J3 z({bDWXj|c*_^Lgn7MZNKSnCMYm?~*h{IfFQNTHjQv=G<5;?vP{pgK`n{`V}=uf0d!7=w=x(^18Mx zyBx8)B)_a5BrYk^)SF!ejht)^u$ORW7#`Upao)o8tzG%W11Cr8bN8=o0>x>h;W}FN z8Qe%@oKB(S)n`6E2y_1a5HDBKDRp|&)=k3U6q`(Eujh#4NdKJ^K?sxA1tPR9eZ#RH z1>dA zShnvataX(d5nU`7u`=d_tv-eS%-g#;zhE%Na@WR5BeR7U(Xhs%905c`*@hhEI!LWJ9#>ER9gc z690#gxI|0IbWQ2GajpiIgUc5jV2s4Yx3}JH5s^EwcOks{os9h-gz%3V{jYh$%FOZa zc~hy}R*eosJlUsFB$3(W&I}ETt=@xRVe|#VNT(}}z4v^UG<7|jRWRO(oVutbF!Q=W z@^rF&+v%?A5p#Yzx+DasYU1%jtl*vatAe{f7@O5CQ?ZuPsc#GSTC33yNQ%>d&iY=R z4(E+%4%2LlRjkFkIp{z!&zv1oX&bH>AB_&0iZ{6_q9K+LhHtkf7GM+0r znM8l5G5|@5wb0C%e3x{VhIChkF+djp6vCaoFE(xg z19zUkZzesJ%MRzAexkoQ=yj6_yS=QDFhe0sSm(=fgCA(ZY`NH9gZ0rB7ltu(+;5O`aYp1JhJee4@x9x=aOD zJCpHtLDk#rF8TK)XpIJljMh}QLK*OM)3yrKt-m$-NruwKNQP8{Io803AxqnS+-Mbu zl{s9lgss_j*xt}IYY9d9E{woZG3cq|VWLiVmmnk(rjb5GqJwMOCtG-PoPVWS7oj?V zA^l!EZ@e33?NLa}hlyJlvfx3;fwRqv07bMFT-8;4_67}vPP95^}KP)H@x>H3&Z1Oqfi zOfWRi4)T6A&>Q_wQ4r&rT~+93i4D(9xNuF#Q5b{#+K{#FCE4{;b|zd&d0~_EMfiH9 ziVthJM-_T-5+|kBQLZaWxbc?OMzdnn{ZQNg#tJ_P9Z%?dG*tSN#FgMt`@2v(_+Z}F zKV2Q@K*cId<9vh6$2(f%$>OAwKbx1J!yHPwVQ%g2wn_l4FoJpXZfCv7=R|{92Jhko zZhwdRZe`zDB89qdx&rnKE+eL{Wc?am*m(cfvS#$fj+H}C8avI3Hx96cS`J&vi~^ zN?jIq;J+(zVUkqzyAp@oxqQ{m%_nWTVh6X<=P-m0kXeLa)h6nqPVxZ&1q;$%scU`T z95{HWc7uSSMiuK9O<#WU+Sbbec=^ zHZ#80RwFs#^TqOFSCpQa)|G`Z^3J1@R z`vP+|+vM3+ql8`z>mV96YX|Mol%;Jxq4^2za*M-!-u60e^YhB)=#9oYN>hXZ(B?)Ag`p7H)N5p*UBgSjV`1a<9 z=@K%nsWJ;xDUO^|lt?NIiaAa&N5P}kST>t;`6Jt$FUJ#o&LCHQs`VdwwWGKEDSpu5 zK{eFLSd-qK>G-ETI6t|rW;jZq8?oFN*vs}xP`n9n_4+rqPAO)J-j+sFvoI9(^X*^IC7nb)9 zDW;hvQV_3N(_myR{Ja-BXOyl6>!ge%q>=t0HL$maiP_W2NLPJ6xpe~Ko$_0x#%WSw zDAQ)buitJ!$D;jYLJ7zx6s@Lo&xjoBUG{*oBeg^z)ANyhT6r zeGK{t&B0fo{ZR&oinMh|<<#-ZE7?G6Y_`uYFWocp->V!NhZym5v6s}@!@_fsci7Od z5BUyjBJv&cwG!k+Ms7K^dtst6qEEIj@aavRhXSKK-;z6UUO>jX8PTnkzu5>b5=73I zlxl0#cS}m^Q!869y0y7VgEf4gA?&eiyjG)_v3IcNR>FXlUD!G%@T@~58DXm3BsrfM zwjUg+il|6p&uVC-sy58xKNaM6(efzj_|6v>3&l@nytxT2JFs@7{Oa%MRxyFwE_)1e zH)`xrF3X3k@caat|Dug}K>3^}ts#VIHl`(g--fPjb$g`2eGXS=rDYuhOC&U<{_EJ+ zy!{1G_FKFA5-yWR$y8r^K@2Yf-3Z~?FAa6_Q8^+X#@%4KNxR>S)A$oox<{BpWG=1vB+}F zFT;yZm+&iw9x=#?&U9tfr>lqCW){(VMJGE$Z1&@%v6l!?r)^RSU+%y@=X$PhOYw2V z?*yvDe6I%oE#C7giE)YGjGk$F588HQe`%b?^Cob{9P|7J#aSXy!mtc`oHsr4fO94rkp6%)DL*)O~+U3T&I4yM4pag-$&u#a>8GN zUtqjN@V(JXt% zwphk^SG+?m1I1n6O%&-EX)4Mk3hWyT$1%dOAWsh=Ebx*8`p2DFU;Dry9XP+$U1p5& z{%nhFUzbYF(_Nb+`g5m&A zSXetgd25?l<*@I1iKn(Lm`PP4Z!IX>NVCB{Eh7fW8XSnEPD}|m=FDmdN%omHuRaLy zv_z}d*Jm^3^Rk)=inklNYCSMTT;Mh!i-|=+Uh_DMoozdmIm?hM zYs@vEUXkwQ!p$)HL@n(`*Ki7cvL}oA%YtK*&aX9bqlkfJ-4rKs%vsWJpOIV^_BT;@ z`Kcu^3W@?wK|ZU9_yyp<$s8p$Ge(Pz+k~5Iv82ojdP`|5o=fbdO*LS$tJJ1^P=u1) zp?Jg#e&kkn__W0Gy)lBaC)(K8QI;$y+Y^|UEGAB*t)k{$aDu3hcr!l?UXy)>p77G? za-twCRM@_0>fM|S8m!H+z*c^K#L@?oytj$_Pwe=Amx=y)i_XIIKQ3_2DkBb1#E8#w z=%kEFe(Zhr98kV)gp+SZL6bb%)tb$oL8QVTCY5Ul7271;@%LYAM7!eIGFMyb*vi>{ z&=om1e%qe1C!zv*;~ODxY(f}pDLzVL2bo6?6FK%g9*o^xxIBlTZ$C=q8CAzi-G4_h zK6g_jKvYGV4pI`gHvYOW(0l-WIl8>6PT&B4$>JLB)ChSo!EWpNfN+S%(ciKhOG)sw z#I|1RkhN@Jzdd@0q{;cwm8jFBfS1CjHwq+^#1ZAyx$=n6k5{i(i^$F{!ixTx-bT#OJ7N?`D2>j3{riN;^JN7#NGwME2ze|Ga^pXS@C6wxLYfta^N#s2)hbNX^> z-Tj}4^>4+z|9kD{y=wOFvg52G;Ydo1*uF?}4<-y>%WKptmufX{@al_WW9`a?Ka(T~ zC`=T8!j2CV(nN=Y#Bzs5$F2$g+X_BLol58)+B>XVLHQA#Q{~i+Jcp>>L9D3LMa`hY&Jt- zx7}_XhvQ7k4N$q1axE~ zB|mPGk+@te_g|f3QKJlUZiIszuy>h|cT>3v{k$CV`SL2H1VX3mD{nJGp4;)f&ZKF?04NxVT6-7NPUnVx?YpT*Tj0UvO=RxY_elj z7Rfqi?;l$;VN3V{Uu;E_ol|)wE?`#5ka}c30A3rmOTzR)C8h)4HfeS+RUK%UMc@_$;*U%oCyTL)>uJ={6)Sw4G(bvL@dC^(#25>jSr{+1$we33Xg9=i&{@g9(y5hFU%_Bz9Qml%&6 z#V7!~Ij@);Z^pPloFV18+~zU^BY%$gaxMI#P}t7_?wgF;8YdBl(~td@4!^2E?UK-C zCzTY=d9t)7Wrc)1qDs04`DBCex+QKTo3f3D;5V}GZxD!J%ZXaG|B0CYRs@!FG&XU3 zuX0lUca@WhLD9s_;=L;EK`HS5@X3Vgz36FgZ*5}pr&P=Mufitq-|DOXcXk8+hiY1a z!7+k?`GfiYr=b3SRZ4+O%A+j{gT3-EjMquuv-S1%VRCRZxPdlp zG-`=m6F>-@Rvn)BEEs&ua#8v+5~;PHcwty?11>C`<0nE4beK5HUkdW6zMt}I*@Feb zg5!`OUG+zur*ZW;ks@8h8=xJ%PGPVQB477UJN9qh_PJu(+5lki<^ch<^?Q*x8%u5M z;Ve1lX0N>}G&gQi&0XN~)VV%Ni!CjAbu@7&$UT?g17oU-6L>Dn1Yu`TqI!`(La<&A zr{aqEU+I7H0eiphp0=v=Mp1g39F zh553D2r8uJpPQ5ys`?-+3>U^V&IP;3@DDO#XeJY`%aET>FQIuWKJ+yd4A=3MWA%YW zplayc*4qWoo2;IcfL0zwxlo$#+gyaWLY0rWjzSJZe+N2L5~)Y-i##8+9yP};NAVq8 z576A^xI7bkkP)Op;iufw$tO*LMt>V;pKcopOWXjtR*0C(yCFXhzrxbRF5j% zC15c8K^B*(nyOdO3~JkMa%>DW@!*Wp=EHy6H(!Z zFKHzFK-sU&yvh6;qFX!kNP;gO3JY${FSg;fAbs?OwAK_~61CsaT5+dRZgYD$ymG2L zq1}sEcUznF;^Appl;%JOs4cBJNTaiWTCv(Xkxhji0FkJVY{{Nudh3&M$SxZz88e5N zF4O4jw{pmYiiUbY;~=|S-f*YWB&(&y&;4F3OMKGwPs6tXs&2Wo2lAK?Q8_D6N97%& z7kgS3efq3m9D$Lql8H`%5vo``uGmzH6J5x)TA83#l<2S!c=VN87 zVn?oyJ@zC>>}4EPS~+#tIJ&C1Sx{;!0=UHF?A@qq19^LKeisp6W8V#rT|F}3@^g8R zld0LT@bY6#ZRk}wEJf|l47qqAO>HSzWA=>{MfV$6VK*uebcm4HCo-Sjvb^Tg?VV-H zIwalgJCz(gM6FRUSD*W~1k5Lf`Nj*BNlL5{_%z<788zcUm?aHXzmJ9!}H%Sp{;RS4`Y-~&BV^npT=N5qM^&Gj`c zzjAr-D;f%VXO10CD~o(|d=ZrpPgy1|GsR;v-CeFjH5IuB7ZLwmN$s&D_B$^%0dZGd2Z7IqhMEf-lFm;i$>lek!tluf@mKIQO>4c za8PsTsS2M=M#{quQ6BEw%>}({6}0hkQXeP%+jlF5AS;*-^g_g~To%6fXn|M0-=o6Pyg`DWikqq74rtgJ+IToTn?r zoMO`G2yA}@Iig|VMD)r*7os7r02Li~o%<+CY7R$-$4+uPoFGBfErE<|=fKg*Vsndx zDXfNqB23r?o`dYN)YnMQbxawjEc%TyL~iq&r91stl!-CA8U%Oj#x1*<6XtS=TEu(# zQS3f|O;(nvZ*ODB#zIi?0cbMSRCt_>*mgl)Dc`cO#Kk=A&ge)g@xjH(w)=dzEKQX0 z7!Q*GuHMo`t4xjI%Tjy_o=eHK8Yd^tVU!25(M7S+?46#gf}#S*>Em zUgC_Ncy#x6hi3{-BpfiEtZOS&!9vB@0|xOU?0&y_^sS4m~g)ci9CN(mcH;9TR5m#h^># zK9lUN_;7Xc`tX!nYU~~JyDnKzjw7eh3E0ZOcYQ6^FgzeL9Y%ChmthGxWgR#7_`ZCA zvMyED$GMP6)j`(-=b-Q_=+$z#VcRdBD&Qq^SUHs@$0$*a9u9rYCSAGyo?6HF9&7#z zj%A*9%jW{awzg!#sMW-xX6W{l#%cW^ReT~jaGI`+5+;LmmegTKswiH!dypHBOJU-b zrnEc!YiY5oyeJL+BuOGTc>afzuL16%3j&8k)L$thoXT0HC|x=n7)i{EpG*}*=c6AO5l_t*4(~&eoZA{TS(ZJ7}>_VINP();c#88*ur$a!B%S?NtX&W2NNUMD33h= zOg!;5Rj{;#A0ccEom#5dRsEFHiYHr!dycoREQ?rB!lwO{a1lFOC_KoX2lWwyu0<&T z2$Yw`YiozW6@xN`n=Ph-ELd92 z&Q9MStY)8a?LT22)8`$peWzm=Qx;+#pnc7*^RY5`%`B=v3lE1Xx169rW0_x)C1Ia+ zyW*%!`KnbSz$J=BK6sAf42$ofTsOjSu*b})egqnDu8N(d&(Nf)q78|!dT^F;DaBl2 z!a@u>+P-PwU0A~pbSU82`xu;qM(#V8-(gyyPE^t8pZ?Kfs^9uzOWo#W{IQiC9v0Gb zt--)r|0(nf-=q0c_Xb<%^Y|fI7De&YG57q;!$R}OMmPNgr+1-y^}WKydmc^X?2sR~ z@zoYJ-`#XQW3;i^WrKYSwBKFq?y4^pK!Yzv^nwN|N8kjgJLc@c@eLQZpxW!u%Z&VlTUtyxN%KW%L z{Qc-Me>wGojwgO=netOR3iDWxX)4Wi#ly9vqNzB39>n`aOkO_w5Y#(6EB<}eh_RO1 z2pik-($t;T#6VW=dUmw}JGD2-z zT<1i&>6?MwKq&0Ov*$b)jj5Y84jwk0sB6$ZJ+AxCXuMvgwx{#Y&gua^1J%s7R&VET5o_QK5tz z)v#Mi8`AM-BrE|nFjmTUz?41)DN#tJUS*&%BjYB6*7XYh3^F{``i{tIwyj(^3DbIlKi@|(!ep4V*TkFuKvOzJeLOQgX0ei0_{Plid;%E-$IwVuGuF zD;x@Hgle-jYOE-pjp6?CV6Kpzf3aI14x;40DEtsU5^&h>z{*Wx{ULlyzcjsKVpEbA zq0taYU_SK=j&fd2SN}-(=Rw1j@a>R6cez?_joMRS&)MBbBeVg!}905W@{Vji+busXMW>wYxj4_atn{*+`x&U5}n+^PczS&EPT5f?7}eivyQ@tX~=z zLJA_dLQ-nj@1Cz}wx*i+7CpXs2wkRi1lugKHlL*OwK}|zl}d`ZrI`u1oruSe{@h_) zj8aZ%R9~gD%tV2{{|3-z)$cQ~8U+^hJuqVj4>hn;jRAe6qbJ_v(o0~jtev=j(jHw0 zrVy$f;huv?y4f%k3)l)Z#-J*TgU%uP>bT|HlWF_m;KJOKDUJnYO}5xEY6O)h;DQG5 z=jh?^)jvn?=VfX4+X{yf7}wf->?p8Av&SpVC2%;`7OL!rNiu)t=F`QW+EC&YGeUEZ z4=tnRtfL-{{N-P3??U+r!^+zFm`NAfDQFG?S&C-SygI04>@-M#w* z=}U3>hmVp}-cdo7#JJS(WkNmt8h-YeNgWZK;T<2Iu3zc#(VlgF45qckj`p;)+LukP z21BIVV_~|d?JDTAXEU>b>L*?$a4Wp~Ee!&E>JN#N0-Y@};bB7^HdCHP( zF_^frSDJUq{MF<#xf8opFjN6{OM83TIW60Jn22Cia~>Rv`?p_w4`(|<9PHu zsbi~fD!m-OnkjquX{fN3H=yR|r^^e@+|fPx_p&0a^DtLoF}XOU6(i18nYNtc#o5Ne z#z`CFhy<$r8@MCKeh<~Fe2IIM)p?@Tevgo@yQj{!r_)KZC+i`;%fKZE>-<7XAw>9T zT9%^*LnTh;D%7fEMjKg}2I>(>a&ggl+j0JLe!vV}%pYrmKdw`k(L`ph$WSLcV${V&;f9=goy;+(@?eTZQKYs;69jvsZ% z(&|`5j8~7H*Yt~H50*-=QZ5*gy?=Ga7LLIC3L=E#&v>^`3S>jF=X720-0pL5ha}{N zy}N=$sq(VSxtaNP6MXaBm14UFer_h-)4|yE!Nm#6r5=2_D1q@%YA7Q}icLH$q{p1% z^BS`I{^w45GOgdg0cpd|lc}<=LQUv6+xXSV(DQ|h*Qv_M#`Gj?&tyK-Z7h1o0f<;i z*c{s_Lf-{@ORENgGC)Q%A7R$Oe$@(7ulzXZGv{K$i6HXVh+TjDx&LW_YvG;paHcQr zQzK3Vc$JIEQlFeKH8N~tr55tCrbzLK9dAFcaWrFEaR>B%-^#QUX;s*gR&pVhLKxDQ zN_3rc34uU8X^mADG7>(R9Xkij@Q>l<3r)3fqWt7EUEOA2z?xD^9AwszF7J&|n8|#` zF^IVQaA^Mu&guO{J01I*sokU;;?l8D`!e8Enyl(jvs!vJ$?{BcK$mO>RxpXUA_AGE zKxSR$s;Wx=Dzi0dwHcL9@GYB9x+{tAIkP^{zddWnEA~Yz?j0y=7xS$pUSt!JU3+V*^N`91T&REs>VLT6X87?0#6+i<5FL#tt<4n#4nj*~``Au^s z8}N&G64-yV(DH`%suZdfJi7_TXRx5}pSB35`+=!qSbWTGIf#NXD+ddE1x~8u!=>Zk z0?w0^V|R8XqHVgxi}RgCN6=qBgvw^0d6PZqP4*V#b6t>JzmU9JG9o3X<8- zR|6l#9;ubYdit0TRin^?C(|I$ee6VZqpA}&RAG{1M7l5$A=JpG3`eP=#}Dw$IR&*V zY|`!-!6)VG?hxX6jSz~ycskCUZ!DfSjoxRhPzPT$6MU~9MLYp-ClW}n{UgP0MMC%y z6!3PM~uOH~#jTC2fjWvig};UMsZVx*KX=s#UBWM&(Z2=`t_&r&YHdBqH}V`7Hk zS&%SH=Y>!@!=N^xeb)`gF^3^+-lH7B7ID}o(F?hn+&)M6pyF->kEQp$WZCL&I#x-D z3-_kRtApt1F6qNpJeqJ}^@XO&lZ6Vr;GbESMh;4^?0pFJ)mH{9k|{xN%-=ZPa)e*6 z%!s3T=i?SVv7#pLHTpzF(|aiWdK zLqrs8C_h34OG%rG8;1BU5u3SS5XjT~E;;a1GPc5ee>jn8r^-_czrG$t=|`u@D3*V` z?!R;+x^~3iPI2mT*x2Ff`UT(XGGQq}r!cZoGV~O~Usr?09uCp1);f5($aJ*iPJSpP zvv?WIq(|6dHeot}OpzVdXJ9-I)XmlW;Y^S_mW0<|DhQY3+)@;|7ztBOAaO|mLhU#u zZzOU?-lolt0p4od(gUy4*CFMmN9r6d_T}S7x9=l z%>crh2)xsHdJZj9=N6`-=Fq5ECgfM5DIq{SGcCGGULBvmiO>fmvM-tvC_z;8-~-3R z0#vg~nO;^$mM7yl)IqWwm~1;fOuJAMT*SPH;YU(AOAli=97pvST20SxPlIGqK20j= zaH^e;Ysum2>~92RKOJj}JD=*m)L(e>u(6Kv4Lqii%2pS3Y3$cjmq$-seF+o?eFEb8 ztIXVV+U!y6S}JGLgfT=zMXStEqm%bLP=<>c@$%K|My6^9uve8MsLd)INWju~k+G~D z8T#najza1txUmj~-7mVFtnrIjVKDC9(<*GA-~Fihb&q*O0dIv`lRBO(0V;|Vk~&(d z=yn`k*#Q}6;G$F*dB z2kLB@o|X&I3UCP_2?!u*VmXSrFflkOvnWvkqf4YRzecM7Wegxmen~OCxMDCD@7Z4z zHX=P7F$t6FsX8lGzAT;jB!+5+XNV)-Zu0J>bE7Ye1JDsF;E4wN)@VG}cGE#Y`Ji6c zWw==P#F`s(XawQ+NBu^|qLN|=)eLe-idNW~c+qZ4aKZvsfDAms z$~7!Rq;bM={4A;Ud?P|70PazdxHtwk+LY+V$;3bX`4mEtIuV8!A(oGFJ-XW3v2GLp zRah>12PG*1xh{vZv;iYlTsS!Zidt+1TV%y*|I&uuQ+OMboVZ?2+1)t_-sb_NhlJ`}uAHz`JH|nVzZW{iVk4sWZLBn3xQM>E zqV|2Uo4^0`Af<7}Lhxk=Bx*S; zfd0h$JFjmtwB zE*PfQ&N3HpXtZP3ZU*shT1?bjx^VBw8L**i2{7v}O=g<%^?&H;qbB;%b7vujZ&Cmu zZw;os!Ec#+X6I0P(U51c&!RNy7d69b-rH}_eWGTszsKwS>F!Lb^B8h{LtwGwuW;61BH^Z))W*;tyS0)EzWkX<%$bjQ%!As)b z^=AZWwAr0Ts1T$AO)*P$%CY83EZu%SvAfh9Udg<8S?(8|5=a**hW_li6{?_biY1!* zjW0a3c*p82idM79(R^oUF=aGm5#~;K>IvJ>atVMQu>X^|G~opkq}WH%kjq zE3z?lPo|R@1F-!W?V>>WVn;!8gD26JO5gRW z_eeMjh*>L5^_LppP*bEn7*xp>r||@`=&3d>_kPu7w7^u2&ZC{d5?bbEG7A>j58onI zm7&4)i7ohjRBKo`YoDPQzXN$QI+C~u@<+JmNG|9*B3yPV2D-4_45i!}ku(vhi>>GI zZ*X4kGN@K$rx#2eYiR*7)#UW%(0VQy_+EY$P5HW>jAw}@Z)LemM5yxC;uW9ToEv=r z4@Y)Z&$=K9c%dfo@))fS`?|?59u3Oe{CLf&0Or^@_f@F!7@ZfR8eW*vjVeiuz>I(g zc{_|MKnor#S0w0SHdx|QJ#(0X%jxIewL(BF)070#wn z!y4U+1WcC6rUs&V%C81&S_5UJAe?KM1Mb)ET0^fBt+#vIud>q{JlP>l(#4}j2AyjS ztyH`bw%?X)KCX1jLJlRSm7cGggU~5TH@K6A(>r1sLBgbYSzQK8$lCds;&4p-?3JY0 z*P;?IB0N%_a09WfM!z)5#PYGrbg+OYc)i`-Zj#35_(ntbO zFX9-97bW;`I6VP_jNMG8qN^MJs{JW~%ldDhR96F$DC^AHB`@_r6zEw(F z*qA7Is$tVhfmc`_KVXLK=%l84|EQQW@K7xuvDn0OMw&JCskf~!98*{ZyJlfyn94B8 zn|O#W?fDp1hi^FX5Ma%sRR@hSaw(YLblCn}Yj5FHR1}ENY^LIAz>%$%MnvUqkopDY z5hmm%NRhL3PM@YYZMK8xuxa@a^QJmi=`5UB!9F4yTL7mWWhT-^I*hRgK!6a(kHHi& zLU8CpUa3yLELogrzOE|DqI2~9!fUm;No0>VCAEtunW?S0?A3lCI=}cUhRs!z%$od# z^lGn7gJ(H)rL5lf<6nyl&TbSj@)18b8gegst9}?-daE5Ng613+)nMp?pity zislPkalu^;$z1KZT-xEZ`u&H}0Ps4^s`ByOD24vz{LF*O;<5T&OX6*hRJb|P)J_pp zR~iASFofSit_wI%Y^y4e=<_bYQ!gHNzJ5CL_7A{Ta17Ru!OvAhAOf4Tm|Crhg`-kt+*}x=hq;i(k)mMfF6z!D! ziJn)3nc&yOg60R5+vU4sgFBN$$1+mjR?Wrs{;S;1o8Tw~+NWKd2Zb8Ej`_~crc|q#{>CG;SP8wM>=g(ix5QfYo^8AP+@u8t;0Rs?()v_oQUB7e zra@tuX58-0e25%L9P6pdwf#5B=`js6`UY#>(`9R1>HSmN`-DB@Aiz`#ea-XfT4dzP z3-p88(O3-Dc&Rp56(`S^qsjL6ocR;QE_y9ZP7ni^*>NKLCo?-+UyJAGbTSc=`jE&B zb!~31b%Q|>czXpi?LNYDNquv4jr30~ zv&W96{m6!1$?4>+3y=Jkoy3U?bHR~V z{IH^1Au8s*59@_;5d4y+-H@7MedUQ;Q0~eZhz*4C6uZ#ZZ701lA&8lv2>dbERSOU8 zTaiUpDGd?|=`@FYR*$_xu@Tib*yU{;(9)*vLZEIkELeX9Vz{$dddoMN!lq1fE4B&! z(mek-mU(f7<-wFh{sI48cggSzuP%~M52UT|yn;Xs4LkOD5Z3sFc&HrQ{dk84p58)z2g#cVmF%|MP7v>q1{M8=rv;m5&Vs-K`M8^&!A%1-|1TX!BzNhzWNCI|w3f*%i8k7WtU4k) z6WX|jo~0V?A})1G!XvVpC79EQUlLReeX6)6jdC}Xjx4zMVrEo6BYC3peZYZ9L-2sC z`*iu)n0IR5%%C9PM7=dDI!$jzb;oIR2I+_8fJwL`yF z5e6flddqxMF)F$tCOT7!#e9a1~A7#?*PDm=a6=gH-(U>@VxkaM%D#KCC%c){lH##c}w~A%# z=&iXdCw=Y_1<|(`F6|`{Qv`mr$rugtMbq{k>5|t(RgL>;V#7tYL7hFGv#5MnKe>8R zNoaD1^k3RT@G*7SYB=i1$9!)O-{7C%-m)?86B%wpCi(XSez$oaktgfPjVV5ckN$d| z5gdkl;jo!z8-VMG8@+fV*fBV;qwUsd`0NRW&t0>xM19L5Ba`uq zRJyakJ!koF#0MwcNmru;$I9zCfzs7C8C;~{*G08$X-=?9xr_Ux5070-qu0d9t8dl3 zBCd214dW7)9IiL(_+#92nSb@#(0$5hawX7icB)NL*%%t zBbt0LU5AUP_or((9h>aBf6lV4VtX{OWjF7N`!`nq9z z?Ee3>cjjR+u3-Zw6eX2VD)kziMAN*pFIu!Hp_0-*m}Y54HB&Q_7TY4&pXpHb^2W2^k z#z)Ox$I@i)iB)M!E(B+u*;me~$|U8AWPM<;Ai_kuRN@jgtj7-uxD) z*fZ@p!MnHapVdQHR2N>`R7=Ol;gXiTzf0M7A*t_A-|EKkm07qu>)yYG^B-MLSBd%a%1McUnoEbK+dSy9Zj*xl5R# zv)&!+(+?m~>JzL5a@yKCoIcvu)RwWq4AZq2F@;;bp6JOXy;^@mJ?GZupoqWceB(X) zXnOuf$Kxr9B|T_U^y!nuhA+2jH(d@PB}HV~J=uq))aOKg(0eZ5d!+u(r2@@-PQ%HB zZ`V2NS_?>MC+uUy8Q$yxjOGPp|Wm$+A}4l4bQ5DU(;9is~y5v=?{S zpCh}z?&{Jh3r4Md#?aj}Z*rl<7Bed@-)+kutqYS%c6n70?{_SX-qpiVc{shJl~6x1 ziW_+_XI#_g?cRUPkfB!Sgy)Vvip;P`bUn&+F;Uop0cfaJ|BvcNsMkR_^JWiEYTkE`sy_ z>Z#Q2rL{ooTW*X~7*tS0F0(7{_(s`M<*@1~RG1;g`8pm1b&&@Ln z*JpIiQiaotzt)V)Y7tnX)3QCbXjOV71f)+)p4ypf^q_v6rmzofu`|2@0nt~VPn*_ zDErNOjb_jjX4rhG={C)at!UVIw)Kr$pxpyK1`B6(v`Q8H>`4F35 z9-qqN^gSrc6UTKt{<-hZSM`rgb0%lK8ix;9r=VcGQ}SypDN1_31(R8_OL|*rqCfP^D|vJ>Sk_UsY|2zxeB>{D{?MVHX!x z)YKNNa-c{zE3S`Oa8j;x!G%1vnq8TbD%vUA#ut$p$-2$_wj$x2Q=6i-)=huaGq?Jh>Wke! zwz%CZ*1GdqttxF+`*BKH$0Gix`r_Jmj{J`XZjWa^zM$`BN=AjLYYP;r#Q>Gkc#)Ia zA-?WWCOn4!=kM3MJLJ-4wQPTI=OgZZR!VE>Q+Io_FZVl}->&X(_foiEQ?);PPN(^g zNgvZ=CZx@&e;0T#Ykm#h+;&55L2>v=HR=u>o8q5thV6G1h4U_d8(V5NXRQUvuEA{2 zYu02H`E2fckHc54FepwYH%hA)oq zb-mvqhl^H!5qaErf>vw|{!2;y!Hh`pw=LA=hm)I>SlNe+$1tyUO^mr~u@ie@&gp`D z&A(n7EnJ;eqEXtJ#mU`V(oAj~+vjHJyQXEq!L=3jYZkOy)T@XII&n$K&)X~G4}bk+ zNKL9Zb61nJ$SD1Z)9&PwZpW@Qk7EwI?A!Br%9F>Zzoh$@x;?6QP*@nS)FEa2LdSPY z6)fi`ym>XYZ*}Gv`Cg4(%8qQK^I?7FZ#*)V{BVAFU~5j4Lb5}ps5H6j)`q@WpJJTC zHm`H0*xKvH*`H5Ud=oeB^i?&TtKEL@iPTh1t_Dsa*?-*W7P4(o;F~}#-=f7;-6ao_ zlHstP+$h#dpM*!>xVGlD<{zi^%rgEO>!pXjx5f2x%(wF~n;e&#&Yrt5oRt#uPW6Cx zc(cdsTGg%GP{>W&vPWiTSi(KM z+Fud+d25(b@N(@zy??Ci}1$<`Jwi_GmGDxh@hLG4t3bQ}3IC z@tW4F)zqD5Mp!LoYaX)V>dfgD++D1j`CXp%wYdR~K3e4VRUfX}ayy3dN5itqM?W9x zyS~Wed2x5Jhtg#aT3X+A$4GK>F43?m%m&_UsIuMQ@Sm|O*sOgntzu5~UcZ?i*FUdr zcp76_T$ayG{cu};iLF1?VpbI6s9v?|u2nOuqUTI`$n*;gIp|zdKCNT+TfQh{72NFa z=wxa1FqSXM3Z2Dpfbh>XwDMEaJ8Rn(R+5)wm}(hXebv%QEHqhByZuT!qxu=#?psd0 z`vp~}SsSot{jwd`7H{^o=TMGK?{VPTyPvSnEYb5m#tU_SbCs$e0x8^TnXDPUmv(w$ z{Ivxyr}N(y#wK1ndonbvZuK?)&=(2n&FkveHeDt;@%n7-u&KMO1R44^z3VQ<<)5nC z6=#vK?#T5DLyc~0z%T!b%`$gP1Rn z6-j{5zHmeOVq87(o;Wg@jwMR}kfnd95RL#50T~cSf&fcV@jr3|^`e+NVsdP}0_<^bqWYmI_vZGLRcqTK z)FyALywOuh{c!eE+KW9!sK*XwK^wDoHo>3k=x5J&CQx#oz<=aU`(BP#i7KegJswLS zbPD3`91m^^Tvp|~|HtIWxI6W?ot`=<^duzfyxJ&-Y%5#Sr>i~Lq*pVQWv zPQjhiIHz5yROyvZIuA zvfJ{_irVrwY)a&)UF#5hM4$@{aj(iK1DOO<*xzd{1wmjOBVw$1LXjBhB}l(q!5Dg$ zunGq#hC^peB`N!5m_s-zUs5Uz3~*9m(oQZFCSe5v2%-cl*w0CH=865-^PRYCwis(5 zBU}}L(?#wNH9bIm`fZO%7}Q}C@RUoLq=vq zY(X-PYKsgvN!nzwnB_c{NZQuu(&y&A0z>_*v5`{cC9l6=9kY*b|gANU& z#%3V_45lwwA$Wt++k6vLXI=pc;;~Fnu0%W7F2It_0ota_2OezayW~yi$ zLJRQ^@CTq#D8%27FQSE*pcu%ZZyI<;f-xval0@ulf|8sDhurK|LY4v{8zLCtjId}X z45+e1oDrTv1)3Tna}5;(lQ1w2jm6V&Fbz)}0JEY@5k{-Akj0^`va;?k5WJb7xMFbt z4TA{|4mJwL8wrFy7%=$&F*pnkhXyIoqENn=5rXE6=17GM$QhWqc>+F!$Ypp7g2W~$ z)G!!qzh(Xbg9Y(LMiMKHm;!%H2v`e!B{*R3rxZ} z!#EnAOe5gX-~on>F(XnAl`N5A2{^Imjr6$pI+?G)GsIjuwhuJge&4o8L!q-M!x=$B=TLEJ3kc1fN7|Ej~z z?$;IK@Bgnlv9qID37A0$ion*&G$@G2q7gVO633g2M-yOm7I?esW!$Sum{CG(3rTH=VJ|?ITG>gq)1o??krY!K^1^6NX zTeQ{!w0I$p0rdGHMr>VGB5x) zM}VaqSeGK(l=)U*n~23@!KErN4o@Z^yCQuU*6&XRr@fz5zAOgW&Z8TZP-bgBI zV8J9SY}kUyp#KBHFV?U!UpV?NAAtx1x9lL7qaa^a!FCti$%DMXlFNODZcP~o``7I> kI1(Ow@RdX(H{1N{b``>Zc8v=7&>(wv3KmNmyglWA0AKAN5C8xG literal 0 HcmV?d00001 diff --git a/twil_description/doc/dimensions_chassis.pdf b/twil_description/doc/dimensions_chassis.pdf new file mode 100644 index 0000000000000000000000000000000000000000..114b93c755d0dcc85d2da646998d2177305c4846 GIT binary patch literal 70581 zcmafa19WA})^5kPZF|SIZQC8&R>w)FW4mM9wmY_yj_u^7&prS6?>qO7_tx6kYt^i& zZ_ZhjHLCU^QxFlOW1?q)Biq@XnuCL8A!H=9Gx`e0!^0qBX=`feXz6KcLde7*L&(m^ z%E81SPsqj~O322>%*4VV_eodzq%(5>7$gX_2|1bA2$?vTbouz;Ol?j6Xd(PB2OPA! zqp8^+OUz7g(2Rc{pQ3-=5!(I_jfs(y{Xb|-oSzQPi##8;A3TCVq^Rd z8i3`WG&UAyR?dI$v9Yi*|I4K1xr9pRuq zi(C1#t_hi08IpIrXWAQZE-b~bfn5VJOPHWe{7wlgth zkR)Vc`W%p^w&u=ge;fOIsQ-!K-xG(dsk5Ppp|c_3 zXAOM@Q{Khd`g1CAA_V*^xC(~mrm}y4s5+VcPane{q7&g~@;?PsJnT&wgg+Hn+nN9G zT=JR7|1ltJXX|Wg>+GccSpN3chnphhCzZet@9Y5{=?XHrklbwsB zv8mH%S&4mm_IVKo=ra<2&JKi1e0-lZU}vms>a5N1In^?#n7TWEPLQ8<=lq#bLdJiA z{e%90k^T|_I2NpzLDg{3on`V*6>-PSw`(Pcab!{*|M@LjFg||9bH! zwtsu^UyAVW@?&S=VEf;)lL)U@myX44Lh78V+Ts*w8lmP3AoQ=FJ-{`;5Zs~+1*VIF z6a(H{EY2cza}}#ad8+1~pD%}q+*B|3eQ^#q4@bQJ$o6aRzhu(se0lFH?s|W{(kH<8 zeZHMLjGZFz{cMI^KJD(eK|D&sQt`aKeK+DE8AR=!^8-G<1U(nZwM`RbD9Bpb9tK=WeCK#Utps&;_@PH>ymAg z@r&LQuN%VJ>(3YooDEpd*$%hLkWAqN<>R)Q+zf^jfM zh6mFF^D0MByCM&ON(8m~Q{(l6Qb{c&4s$^Z7@^y!)wF6PHI_H1)=Lf`yQ2`pBjZFy zFXUF*6d>h7O!|X)0%3P0xF{va@k`2bk>Rph3h95VB+C$KIuR^22=(qhzes^+!o?T& zKRCuc;>16~!4`}#+RK)j9 z%J6s)=0E+Ff9}K~5L2(x(zyP zEE#ZhJ3#vvopfPGIt~}@ZNOX?3B(Mrv5n&3-9fSxfVJn+ z0>!-c1QYJe)Ym(>$@6K{Xd+?c2~es7tN7q^0H`leHH{57S*dUFP1QVue2dSsPuiMm zgzAzYWO;vg#ucAzwWG{A+ROU)js&seD%D7kjjt_cBQUA$>J5ys2KWGa8+4oN1nCXj z33DVNbY9Psb=9dp+t}Z_QeM@W%5!z&b@Ig_^C0LNv2e){ww`MX^7g_UxHp1J#vEwC zSPCJ68&74M-m}~<{a>BP@h8Uow=FgvMEQ?tUzw8H@KyB94%t@=JTKuL>zB{U@?8(e zqPw(Kxkpb`#cS@##Pd2P=(7vl^t5+=^=h5i0G@QIOA3~a5H4!mMG13%A%f$HhQ{6A zNgs^m*f~=ar9e#{7hoY|2t9d@zC6>W!?>I(GOA#jhXudTYR@lTi;D-Z=rHO}6`E#a zme}Wmr^$J?GR0gcKAyP43*d9lq=$~z{YX2%!HuKI;@0hFNQsF&J|mwiW9FqRS`@vg z?{7`XLZ3TZrU~j`r0XZTuGk;yv9+mVSWjc-vz1Y;2m)D5Y^&pL~Ym~ zNS00>8@26wo`K4doFtKBG!b@hFe=&y;*C8n!AAaR_mEfJTT!V4vn=tz zyO<09&73@rxqdE-2BWiFLeG69PquTU{UQPG;a~@o76x9aOE>Noxt6jL*@g#{*lpYL3w37wI z(WxMLP$nwot2z22k{9lq+C*CBZ5EyKk;6cm!!B`nzbDH|t4-Z=Z#mA*hSr1X8aG;c zM?N+@kLwICACI-yIRkZs3%7U`2M_&An3;y7m+;GNK>prDm@CNY$L`>_&T1ALh(U*` z1*TWCh9>oUP|K6D{ycg&8nVN0!)B@KQ zP2x;O%*@gUvCB+eFW#)3a*`k#uE@CZD+H)+F2mM-R0;2+m5wWP_t915-cY|wnXpzr zRQ0M9^jxze1bKgiV0*khlYX_bUV!R4hV-G4|GgAEzMg?m#`N(KXt{&ct^n>4IZ+u} zFdiOzHtk-y7h7oVk&yG8td)w;xyOadYP8}Dw$}B!bcy-y60du2fOYg%*GVmzQ5zC| zpXDr)5Vy?afeQ@xruFkycI#Tl*ip7MYmwzm22nft5L=F}R^f@}M{Ta*_pfG~9#q$E zN1kaghsrxlQm#bOD3H$s;Uh1tC$)mx4Ar3?5V?uaO|{!|{CrQxG z&dLZAC4VTl?pSpafLfT`Q7-i#*6=@mSNA5XHTf#-09MP_ucqzQx~xu(D4KfelZpb` z4LpjHuE^9<{zG43BS0m{4NW!AnP^0{j1*gkh?8L+gVT7PX8ssQNQ^Be4}h)Oiff`K zpA#}=R2Py{cL%BcWv0~6|5#7t4u0i!z9pV$3VICdiysiBqUiMZZ{#&%M?)AxmqIz^ zvr0MX*e$Hitaws(z+N=)%4~is1NF5Fio4#7<;U^U$16yzi>Rj6dID2fKU?aE#gkhe zy~pqrwaMmlZ_rOXL0-}=>{9$8R!Y9<`BJ1xpW(nCmUZ75>tfHPDeWABvbu%092rfnWN}UU8I`L z-a(8LT8V_bJl_8(2ILQniw)5|5o?I+!|u|dSg?u%*7h_(6D*`>jCsKN%}~#W>U2Jl zSpUvuj^=&7LdoE4m_&m)?#nzDYG(WvDcB+_v-`OsE1H?!pP2y=gpK(-mS&#SnxMY0O zmYy6ETw9%;wS5bP5lWTw5^&?rPvhWL(p7`%%{sT}U!aAMz4ayevMUUC|l*_ppIy@BCt;eo!1EVl-p>lMW zJ*(2;JQ|JjTV}#VDGYr0EeGn5m@Bs0;uaXF^j#gs(tsV4-aNtO_)a`Sy%A|$umTgg z`;u7cBI<$afUuOg_+W)5qg3&-9M#@D)l|&oJi#*qdpgkJA115 zGKVo;XU{Q*R%~jZ2#{sMgQzg#I4PY&24Bj6QsGVIK7M_BQ-3$Qyt}7>i}0JL7b%9*^m=frV_KM)<&AqO;PJFg94SkyXN{6yRhgWNz6suR##c1aVtL z5(1;b;ii6S(0^CLKZh6*B9zpbQ~AbKxxYZUt2rs8RS?*|Av0tATT0e!sBHYTFpacZ zS+cV5NTWbZPg9(UYts0a%DygIAAa2Tk}rGAIY23(+sG@y;TtD8*-69wBut#}i;ny- z1j)eTq=nZl&RRt(18S|cFi-7`jtkz;gFy#i9v_7x-CeEB_o2V{fLPAgh&`>xv6V@A z_7w-CDe}Eq3!M=ebc`RF4Do^9$-CU3jfl2oTxrLi(VHRik9X9n3W=So=JU!{HFlzW zpT`TwcVcz;=e^8Vu5t;Par;TrP*hsI5DnjhCt!_|MEOrwTijjW`T5CYj%%M_n=-w@eB=(;Krau^4?Jz8}d6C2( zMXZ@!@gw`WIYRy3Zo2tF`OCI>pm>bK-NC(>8Yomi!1zI*dNcc)g;RED?Sqe#5D1 z+t0Q9o2ws2llpgI2qL&cA5NVL>`;937ng;aZPv+NfW%jI&Z@s`e4No#R2(eLWc`-Qwg?oDKTO+7IMWmd=|uD# z*H6&kqf(lg*WS9wU&TI8N?e<;S(^}jH4>e^OR>4AAxOZ%`|t>7p!j7IJuFZs$hG|rU6n*m)GZ{@QeE5GQCj(l6j&Kgu|XPT1t z&Sl#vrOus>Su(wslyl7^YA&dfOg(2s+=$iy;@8K9$<%bQx1~%8t&Lg|%W*IiqV^c8 zyT&c@UScAfmaPLi_iJ6Jn($uxw^1cCB*Er$ySYnqzM1L?CGmi&ePdhYO&>$n)Y3V*4; z+zq{{UGh)kc#(KT8aF z8p#&q?TWg|(MjDh8XQpRxu?icL1ComZ%=TW5z@b(uXvgtKEXMla_E2JzCb0`rhTyf=V!T8H6_5w!uN(a`>HAyCXFd^RcAYWyC0zPg@rXKq zi7IVP$K>MO(pE`RC9+{EDFryI9$ikFb_Js1Sjx)6i>0B4c%l)F)0D^5B5%ht)%WG*erR3Y_(#;it=`xGtqrnf@1B@F*!dc|_QJg0CAm$@)KX6qG8;cY- z)P+JfC)IQxX!$nFZie^%5Qv8__muw8Cn%fmh&W_l1!O%jM}3Oxpv zjIdjK6=Hw}m2Z@O;De%h4i<`?jR=#_#;Q&0y3;4_!bp!c0h@)Cq^gaSKH$YWDrQ9! zxd;dK7y+B8NlPY`KGD(Bg)Mu8(>OU%JU?#A3;8*gnV_4*VGKC>*b=;63a3{>`oRfX z;1p(Ya?IStq&!&-e^7O^mDtv>LDs-m0ZDrYi|?>`s6Y`HwIU5Zh%Vf!-xZWjT{}CH zj}TVx!8;9eOM9Q&C`WJLuNjfc4%@opq(!mAPIBl`z@F^(QY8SKurM?4+4671D`qT5 zE`sz(?F6QfHK*&^J<#7NFVjb<@wh_h-Jo=>62@MqL{cj?#CvCf62lHBINN7GC6 z=mbK;N$`GcmodwkyE&c2irpz&u?e@NA9^HbyEO!X8QI6{1-eHbLpF&%%2s~kYTT(F z%R1Km?b?~_wu{xlTtT=)J)MzNDmA@lD)1u=h}9V!4*+8?JR0op(9;5ih$~_?n>0-) z1bCD+%odf!`F4C!(U`m5DYb(F0~qt`IEwi@Z#&Y z%v;qW=^sgH3J7EY^TLD!O6^OL*eA%5QBIQ72Q*l9v$=3^A`6z@n4rgFD7#rG0P=JR zpb|oLJv+fN%tYJN>QT6Y7$R6(tfA4&v8@SFj*l_7RFjt4AOUBZ4gZq@&;2aDbH8Ug zV*g94_n)?g$UwkQ(Jo?|3AAk~xt8a?MaSEfedQj|ZQU?U^>nZ{yFIIIhQIL7A@7Eq z&zN)5m(_fq$T88;@|y4o z;8Y6Y&8tMw!&UBgYe#xBZBavrTQ^pSJoEp8#0bmG1(*2n<7Wg0`CFvwW3a};-mSk9Vd z!c9SN6t_h~HFSDE%0AT?{*@x<8u|Jw7ARY z$Q*?Hy4l4p>56;4Qnl~O+p>2b+0v`Fp%w99sfI1(L7|5JNi3_%A^japy#qwoe7K3W z^ZS4~4(0wr!J1gV{~UZx4Q$&FqR4WwmgTw~biH0mc6k<<@kpD2!Rr1a^=O+6N(esR z&>wo?j+m5v*8S4hs2Duh>{3<1a*1}Dw!)(}QY~~;?5D=4OW%Rhl?-@y%(i8>>Aa<7 zXC}Yt)O9|q`@CH*(q=cPWu7`t(k|>@jB#)1agVWY`#cS12aGgr;jJ20wg1+Ar}xdu zj3;V))%AuEyFQr^;CxAtwny=(V*=8#Y4%T~ra>$J<-@$jEEAGdo$jy%>24~u>A=O} zx2vh$#c|qV3ZL{|G20dWrd{Ycd=qvpzSI_{Us*lGN4p$06Cz3^HlE5S4 z3&B2PcRA5aB6JOnPfS3ZJq+&wUOXst7w=R^hu-AgGVqKZYo~dfWM@Z^utDa=kF%EM z>9;?4t*fVYjv!~a%fCm)!?wYfk$9QX9(=K-z0kV9x(X2$7_<+SMJ&&)dRtaL-|vg! zm*%~CQ^e%^E^pf|%(rH~i$zPSR^;8X#ynB(kTA|R;{LK;$4}iN;j+$mdOv*ay?k~f ze|+1wE@ukM5I{s1bA+}dg&R)C#P7642%%Hem8_<*L=F#YDGxhl=vEjBb3B{Q?$-Z4b>ooXyi75A$BKHbQEN?h(+1t!oaY+CnRn+I$t@3t| zxcatxzUi#K|Ix=9sz29P5u?Cb)<=$tYT`I*r5i+oFb)F4|6O^nuL1sE)p%F2-lgjPFE{ zaZRlg=pe$)uuY%wyawg?doNkJJ+<~X;)yWNiBU~td$_r*np8A3jjCqJaI&a#ga!lh z9NBZS`$)Um<6WHCu-de&&{)t{1(@Fjq0i+=rlQ=vT8XOszw|JE$@|QxUX zxq0oe=bDOjha5*C%K{b%Yl3{LPxCgJ7O~#m3krfk=aJ;|JzILkktciB&J$>4*&8fm zEwJapE)SDKpn=nO)aP2X=E$m^xx_6bnb6+mj36Y4-{n!K$Izo?=sU>PrInQ49FJhC z#-O$;R*|~8Z^`%6LX{tDq-<7|d%85JdxqlMyqbotRkE~5g7cz_2)RGk7#J-SZRpNd zrk{74@Yd4<6h6}rl}$y2Rnn`U)k$4dJN-0P>njWPQKZi_?0DfNBC6M`><)_X z>Fj=3|0~MWZ1Qvx8$&P@#s24R<|amK`AJ!2CRDimWyADRUfn#i+->5 zsOalGkDQhKsPEa~YBee`odb zWvvA&c`rx9#r=f5xE*TIq^6_G`w3U$P>o|STSUt1i>f!BFBD-)m9lV*Msx97D^@r7e%EudYo`g8P#q}xLsyacW#1SM%` zQd;d&(a6Rle4cJKLD)E87ht36;0>fd$pq=3zDg=c2Wlbz`ktc(`VZ2xxWZi_yhM4r zwx&>;==-z0KhPJ%@cQ)svZ?-OXZ!!V2m85u&HC?qu+GWSu4nDg!7t{hsRH)^&lM-B zgUyac&|in;FK)Fk!S0ej60d5iF7C1PyFLa%UW&cnKr?{C>V;RR&f0l7cu>6448B&q z$oEonfEI6|O~>He$;X;ttc`H}50{*44|9*yg5g)UTKKXp#Ed}o?!?oC``uBTRmV9s zGdli{Q`a+7ye9rda_2Mpg>6`l0=!u{%i@eoD76}R<+ex{4Y05+)OO%XBgNi8Zp|>} ztvFW+?!wI9L#YO2CyWiBBvpGzxgMG=se4H;0^pT5T07H)>zgXLd6(T2{#&m@1erCS zdG2}~FQEX6%P*DPNh$PhR=5;tm$hDPR{{koL-rU*{fM4m zM)Xtv?Ox)udy(eJrxYFoYUyoPx!Ew@#=~lJaYqJu263*k-6b~OZUb>;sD8l(g`lGE zrh;zYFnss^?PaUxYBsxDedk$0b_bjXMS7L5|N4aHHBAKh$oz+V349zG!e27S7&{mCo%h>nX&qup!`OvTit|h^ajo!|EJ3abw)V z*0KrHg<5?LI6=h@0VdjR2-1J%0X^@AYbHMyRYI-?P&z|L3kAeYCs2EifPK=JhITzd z&R1W&CzRbl=Toev462gP_N$ik!zBIh3OB-qUMN=7sF#R6sAKuHe8F5n+gOj6^4{(# zqB#_Id+fG@8Crdy{D9vXw>FQ6RG`6uc*9?G64fC?D#k)Ry4R5rD7U-RsKK1mWH(EK zr>Ri0dOx_^Nce=0?2P@=pI4VQ2jAIln|P-RePd_rx~Xh1%Ar75G}-7D-zHZXK~OCt z>l-&+aFYDJ^iQ>N*Sx13(wIP;=MchRqaWFqb)?9(b zVpzW#H5&|1FoeQ@F@4@DwDb~}0};3DN1>|xo4NY|_bkpUa+Hnd?bhvD*V80h7L+@Y zZ6X%B3a!fd+eW+TAgSL{ziExnR&R2AJgh&ojRMWpeyqOjaEyO1e7$F& zkx%Mku&ioGR?%0=1%185E4=>>`@MtqZ2!u=0#C;)>l_(Wo}9yyg%1O4Z~C}-rl;)j z`Zr7nh#7=YZR4Q~$XHq~L_6aRN_dqYmonoiBY3q~om`z@9m;kz9o>qayXQl`+A2&P zL(uBy?})s3t2@xGtI$@0G4(*3o2`vQFBKwOIZ&@i{y2Gey+yjxVe@g5$@ z1*XTpNS84IZm{jfBivWfFg#l!so4@dfA{{F^-azf}G^>2E9lg%tH~g8#*r zzjgi11?qQOMKzmhlo702O$vKiEz?VG0VE4v^cGex{xy5`V%TpAme1*oC|&@musAk} zTSZvWFg!+sx7UIES>|dDmnn$Qthx{OYf29cv!o$8$#_9fst#iUq*-mZ40H6z*;+Gmn#h zvHZpOOeSX&bC~Nv|0M2WY8{u8g1OxBI1(HxQ{^}QYwtx3@aveUDDK*biofCrNS!(0E_A0O5n3pMr5L^zZM4P@w`LB;W0qTt!AGG3NZLAQ}j@EUT=40mAo0 z{0~4`RIdLE=ySv651_oT?*9uAttVuZGX^i{A3%}#z!+ybw}_vBj)*S*0(3-FJu>tu z^9PXrE#kibY270J1?ZFi51`M>Ux0LP5&r<139@%}B+L#Ng>cmVWPEU+5#FK)jeO6= zUl`6Y_GBYLZO2cFyCuw3qC^D6;FYjIl?j{~KRVeO4M=pE0HNTD{}nut7uFxKwq0Y$ zKtpE@bV-yhoU1UJwzE?O0r5WxniHNmA!5X}^Q83T1;wxCMEf<}^qm_f#_X?-%WgSM zot2j3+@m|h=C9@x?>2w&O+K^pqIP`3ytDWhTilQ=0+}9y19G!$I(~#6LVyDT+g}{{ zF|r7vRS<>)9Y2=4@m6l*IJi0ErUdpuTK>`mNu!1lDEgs*U}ZAB|JDh%f6~6_`;mA! zjo)k=z*#;;%Rvi-kM6K!s}G+&$eHmFE8Ox`+}0{-RqHKy^W~C6?F5hl;JCo&YzM5q z?DaK0RK)%{I2y}I8>-(SiovKTJ-*1Lnd!YIatSWd(af}(m8QAoO-uW>| z3`zRk^Sim{$~NXI9-1P9V89p19q}zjyRB$@5?n7DSb}C?jPJ@8ymOx9Uct^GtPW7- zb^buyYu8wU#cw^iAl3mu<@^SL_n_KfT7Vyf3Ojr~Xzb42U&Akx6^eZp4M3rEgRE;N z*!QbxVPHpzsE1Vdnsr0+yR~Z(EJpZp$=iBP4M^L1;!nZFUomlg*)j82mf@fqEo*Vg zrwd1H?O{TZroj<3%0_IbIkhF`P1u*J^%K^&&>2xJYUO{9*ecj(;G0jIuxk(sCg35$ z((Mfrd8Oo!*fPdcj=+Dj@nQ@56H;wChgNK>0D8dt0j6pF05-Y8i!9xDWMiRr+k=hKKteR+OIRq_V`2 z(q$qPXIt)db%$iYbkqaLTq}7A2Ie%pFlpq6QIg#yWA(M0yL)*TWE+J{jOXy4+Z-qT zA|2ECi79%=Ydp&tnlHKP(`r+f&&yDlcfpN3-&cIj`J3vyiz+)~hgbFuMFX@>)FLNK z^_X?e`>mzu-3QZQ%Az32fGbJYMwB-u*=*MIobafdx>1Z^S)rDO1?nc^MQ-YFEBr@! ziAoa8+s(0WEj&`Ar~rk##iLmJF$J^ni1~nJxxDWE7=X%D{jV&VKL-rW+)g)Hp9Ta-*ryTzoE(aOXz!Sa$G>`x=~gdB6NARw4cn zM~xiFiigS0V*ll@Bh7a~C<*L!>^$)8T3>~*=b|xKZ3q0j1PA$F4o-uxLazrIoAwV& z-Jx5H?)Fx&ZtnB!97LC;b`E(YT;8!Lfk*z>B=5?umU1oT4cZd3dF99KP-CJNl9jV{ zix1o4HN*5Y%vre5TRZNF5POn>08tMxTYzU_6A zPrn22zrag)1f;!;hPiGoehG7oH7mJfHH4v8)|ViHH0B@QVH;oZ!aM! zl2U|#!`dAlIgs1*N_1KxA|E7@0;YD|!`Rkf2wep`+!sk+9uSL+mycn~0apotR_N3$ zWA|!e$MZMj2M}5C7Vl^DMR2NVIiLjThD2N@#`2yv52H%*36pH zPZzKmvMs(lw*PQ^-xYd*@oO1IIr7dH_o?_|Xxp%PfPX&mwu#eB-Ki!)bAF~*om7*Q z`?->T2Bn`MZ5wuBlM=gn@UYQ(VpCnEnmh}=06;VKY$Cmv9}-t=H#b5ohG`R?QC5yv>JexamWPJ9fA_TbF*AzPuhif*V#-_J$bl z6j$yIfJOobHf^9?ZkRh}zqvEvbTtXdLEk807Rw`tX?OE(IkdH|OZ{wG*)v*v?ygVV zTInnE`nKE`?)7u6OQP4IZN-l4hqjF)({x!ZHz#D3f`|z*Fk7opg}2Cb%&2u@18S=S zT_YjDZ^SyvJ02{28JTLn79o&_H68SuTq7%AtSdHRNS6sY#{tgg&p&JlUF9f7k=06M zQA9LR7^6zcMR5S%qL=D@f-HWxtegs(pbK~~Qh+1Uayk9no6bvsgp|7-XMqe^lNQKgthc%tt8vY z$dXM=d!z%aO1eT3%}YQUt8b+iv=Ws=#_3AAr!>yuse7Ci`=YhWRG0uglv zqg=j(mnWsTgXlY|C2_4ly7h8z|0H~Jb=f~hn7t@#YL^Y~Dq8gGyQO{=nLfnc=jX+L z)V%7t)RS7In3;1Nth;}+yz8XZNaC+9rjH*M9|EwMr z@|E4>Yf4#s+UBK&)Soh_xLS1|4`mfzb$08#Y0)pa7wZ8;dbxa^FR-PonXR`GhxF=GGSHtml8B1d5 zF;-Q*I{!?tkfDWUC%+$JcvI9mI=1b$yM)(vqs~>;lA#VwjZ|ZpWE?$6btT^U8zl8{Cq;; zur`KS8Wma~2&T!rC)63?J}r^Kx864S85qT@(KNjw%$S*ls}8KRr0|Or+P<}a3bMCX zG^V$L?g=Bc2IZqhjDH_2S&qtz9tp=h$htsL$WX3;%&BD}2+pC>?rjARPllm5)3Bu0 za^MO_vn4M-oCGVKrf~Rx<{%fei;Qh*NL8NwsA-lRfI{JX&8cK&nzU#A+!W=-CbL-2 zzOB{K?qc@M26)_Y&#+@-B^|lkIE*^*o&HXVqEs4 zpiRdS7t)Z>GqFX0v>Wq?d*W@8B%0~&+xN`KEr!N6;_1$J$79$)(Hwg&>+P;x7vFWi zI#L3XKIolJdAwG5)y1yqCa3iegBLfHD-!O#tNk^;m2ii#A**S~olZf-2T+*7z-9`2 zOvujE9HNetEKsmTblV9U?~rn3VFlRCgGiQ0VqSBK_D34IXze37+7;1q;u9^)A(fvd*2SveaFGvHvT2Uy22zSh3N@QmdjG+dL^gb} z)H}D1w2tJKr+>=hFGv0aLCfmXpik!aRCVz|%j!oKC{zu`_)R}G2a!WCa}qNBXcLMW zs8doWNdm4CZMSnb5(1KbGiLxNne}vz=KfgjH?Uo6kGUL#C$R?5s9beG1ZN=v3?|gZUSp3i{p--~1L(k0!r?&;{5CG+okODR+3gDB zfjIVI8vy=Ekf}YtY0zohiOJfz`>aGqwlF@o%r_UI$|7&>(z21AI2e=bf)V$YT|v25 zo`7*o!K}%(noI#lhF-1i0axW~6Q49whn45rZ1Yf}2aW^|r$Cyr*%$W3ak$m>@r<+V zS!FMaN#bL=kj%)6&~?edp2x}c1mEGK8tXBDZ4=LotzVWuvvuFg*`x26Gw|_6Vh)n^ zTq>6-4DXr55)HgC-{1_=wB2;rZ}k_D%)-|y`kS~pS^gJe-S`tc#{laDhwRJOmdbQ; zui9_~v-M_KZ(J?okpAN;pGDt>jh<1I*!pmA2TT4DM)ILA<2t)PM2`9Eh@^9B*d zFdNnblzjTpx?MTys;NBNRe-$r0y!UiMNOcCC%Q4h76|Gjhai~+C=O6#i_o5!`nihv zd8(dEeTlA-L(8(Mo#z*4v2Ux%{?R!|D!>$!e>`6$M?YnbbYUpUaa$;67Nc2S_Ht#* z&RjP)e_3AkQ~P!*K%*TuxyIb_+d{dm-)K1!$s`aIap#`QfW!hcu^VdCxkzrgF&yk= z+-P0;^m-HJ=3gHl`Hx@Wsg<2NL-{*Uolw5br!StScd3Us2+U$}#mv5a_dXp5Uvf}& zp4Pfo-IYk1N@6ybU#+7wLa8_dICL>0Jw-Xk<%Oc z4E*e&Op|+N?bPX;W%_*0wiA=3Pjbl+CR*Fw0l{Z&LKweI@|&a3F#ffH40^SD zFg)iYo)ynd-#1c-;;|;&syLXv>S*+7sh~UVy}C@_@fsosHu@KLQ!CCms&(5-`hTMeJ}1q$tA?w;U~v zu6g-$Wg@Z7bfKsK?}EDmD^Q$o9+O|Cy4TGfa|@bTD^&1Q;ZB@FatTR5a9NFLcA8Qw zrA*Pz3c*A$w=iWDW5lSIf`<%H=fn4fkC4n^LK~0lXJP=MD^&70IZSVn_uM=mw&v(f zAPMGT9J^yd>~cRmG_U9ZE?`^$wkTPfV;fzLGv|a?>HT)dU6SMN{i`l}&&fUdOB)sJ^ zm~*hF!rv`m!zlOwFZ*|(A)r`%`K-H~SD-j*tR81#v_`)SP-Q9Ju=Ohqk1=s@u=HWm zkkn4ALk8(~I{R9dWV@(4!4M=DvQgxh5g9)-emWH{4evXI9s9^g{I+aAvTD*UL?743 zrX@fFw{Q^$;~Ke_{G*^4z;m>{m;2S;x~4wl9=m^u7uTGK*d~sZ1{qgShZri_2l)R= zd7C_-f{fOf_4cq|waD-{G+inl4avly(+(&i4!^l3HuYB?3OPhMX3{=)xr{HwFW+kV zeyFZ6r}NfYes*k~j&9|hyg2Pdq4k~eh(3Rci780<=e1>_Btt4^_>8xh9`>wfqnIB| z54~|Z0B3o#I)siWE9&fiHi9JRxf%fvpF*x;OCld~3Q$ovOHcxt&3?t{{pLFpQpFdb zsWpNP*X@ohbypcj$6va&9Fy$)&?#mm1h{LAM*DV0F6FO4#v zXP@O4Q?5QcaxJ}E?tlqb=H-t_^T0=rGjZlG9OlpgpYs{&7fuI%F$E}SLGmxFQf#C{ zKr7Cn=rRqM0rEEB4q4}$MSMLTQnFj4~J$#c$m)IT9d1BY9nDNqh?pS|U* zpK>NZpTh9s`28-!eJ%^T9!>V1d73S;k3Hu!S4T-@8H>adMwwfmo6SZJtcs{ZGy6V=bC|IOZb^Fp-mgX5<^Z;!AduQ=lRvx~Z)~u0M*-r! zWM_=WkW9Vt)Obl5v?Y+zMa%=$`|*4lEe?hx#-@4(YZf`DBEQNXy+hWSu(>0r0_l3E zblE94GB`=>m`b_+e7W*)0F-Et###Z)6R>5g*}#-S=QHB{hO6|q zLVpdN+0E}AsATF=qJ?7fP-!<(Hk!{yW?$)B;z*Qjdx=zSX(t8>%5d5(Wikd*zDFu1 zk(1t0Tqsx$@F^moY6kX zEGQp~iSMP72j9mfi&T@20t_@+M|&yxs=ikssPKHVPlm^P&*TLk4lJYrRWj!ms z>5vh(<1 z;d99BQ@=MaR`TUoX!4z+#=d2@#gmk3NP4{SsfE-DqgAiMV;6^R zOlRfx?f!b@PX7i&=biDeDI?zNPi<)G#do3XhCl zg-x_{6fA6SbA=?MGMojYQH3ix^msiPgZ(FRDbbWt3C!kyjTe$>tTRuRzF)MkYBEdy zts?0VSE}ndNNxUZZCWldZN=u@3A2&r!7RN_`?kaMciGt{yI*G~vvIgiOW#G0G>oEL z$fbPM>5;9(;}Bg_JNs?P#U|X!UcTAt!1NSco*pG(K5iK&D#L&gg9y{*j75Ow*PmU9CVE!zmjuOWs@1T4tJ#4AX~7T{2%u-Qj95SUZQcj+E5cqmgx= zqBy6QH`R1t>b+7{49h*=HP2L!wvJEq&Kr~;i0N{>)1+Ah0o8ScWE87vTCqka=wo;n zzP`GfIr78|oo`GFsZ|B@b9Iq0?-h=GUbdc%7(8$9YZ-G(riWkE9GFHUIV?m?d-!;13^soey51raqmHx~v%B8~G8{UnG95-+DdmJPq+LUR6L- z?&-Hg@$sE>bzMxo?ZtIJA(6_-(#&~F3>afHpmOI+iO~S&Hm9OI@K3yG@phCn3#o41UR549Ycb$0;Z6mP2FJ8kmL8W@&&HT*rs85Fp9pNGRyqHQ z!P>qX;&s^;SdCb6cIs*BazBBpa_#*C6@Y3e=?rR{jDLbG8GAxD{=GNslGqE}3nf{( zsc7<9Ik^SxB_7$h4x0CUP*gPj)I0rx?|wEYwTl3k@FNx@CF&Hszfd59VH(Y{kr@Tq z{&BynHA{IJAGj7z{g!ZP5Z;Ow+(8xO2SReyx5Y6)9uiQ(_Jf#r_Y1lyulsWLn<4 z2xZC7rC&1xROTp4Y!h1u`12-~2l6)ol30ej>oDn=CmojTk0%MK+R<&QrdGKbI?}{q z^~-Bm%B&1aDO6TiixEx7HMB-LzBQiei(VDG=Z5PNg7>|)^G)@qF2+N1^zf6?3vxpfbt%`;W$;s{XC4NY8%S)ZZ26M|{ zA5#y_Kc{29@dMgP9(KW0X})_~Yr7s=Z8 zNQjkfN2{y_7$bn3B;W|Vc3~%C3I5fZ>+uK4Yilg>w*67SRQPagTAAOABQGT!TZW^4 zGMpXtw>S+7^_O^v;(uqcm#*@k$Z z)EYB!{%cZ#fp=l;Lxh+*tmb|SolP;r%Cq~X0Ry^^`G+TZEmdJ6W=6Q=K`qre9Z)@J zY`M2+TyYea&FB5NYT&I9Zwx(4=S8n9wW`xfC1+}Orn#+GQK<6wTvF-RpZwgdUN@6) z2h90+HMN^(|DofLn=GT5-i8pf6?Gu73wM^fwmH!uJ0NN}WKtrTCaaM(q9BeWXOogy z&NwaKZ#7K-H%WxVBC^3zpNR0Fe~_#4?>v+F3B2kV+%W>ad_dWz0Lij29m`l8ujQb4 zrgbN{q^WW)iR4o)zf?LX|1j^O?AXZH7_VxO#mxp11ALfFxDH!1aU@1Lazu|jnGBa- z1xgb^M)63HI`&wKsB|5FhuN~I4$yDsM;9yD8XYz^I3Qwqv=^#CaLMBuUFOeYR=?k2 zWwSUB>LDwI${gge7Ym`X)uyo8zw8{Ri(EVu0eiov#je@d_c@8^11K;gGm3el&|p;| zVVJ~%p~)~wZq-+4ex_%wge~)Xz1U+&*12B7U$@3W1#?S3byS*MKY12W(f_vUWTH}O zq@Xt#Zr<`+%3)bp79kn-qR3`TkJSexS2tOqs>J%SHHz!sZnk4@lGOaw2yzZ@Ej%zo_CMYT}%-U1!Lq&69sUKNd@Qr$NKF4#{jQ*PQ`3J z=L|=M15#iGi)`Gx?aNp4*Z*y{Mt#M}i&_66yiUbBCqQ1Jm>X$`enzoRw+uA15r5eh zpvV3(6Y5u*q-nNj1Wfc`$Y-mIYY7hCe9o${$WNI*1HSwNxiv>LUDrreL@xL2u3U%N zI*qpxG)m3foLU#~4Oko<3t*~Qi%O&x2+}({NAPME6?z0tXyN_}<>#s*6~47Bn=G5; z#(81L)E5mzKD$Nz+H>+Q^m~J;q(33hn20vBjy^}2(EQIZb=@~D31kKG=KsQ$m0ok1v(EsY+KCX`45~=Afrr0#%($pZkMG<0%4|fz)TzBs5yS#tz2r zlmaRtWw;tjWvfPHqu3Af)gg5%3+3Ud8j4BxrFANPw)4%mY!meBcP(~+{8#vg`vp9v zKP=@#;xv^!Q);{NAr#t3Wb^BrS)7I6O)fSgKbyEXh;-d=F1)g|$zql~f?Nw$6|B$o z^8K+yM{<7r00j8~@|RPe;eUc0|0Cw~e}o)a89Dyj;ooyL2?sJD!uQdRO^5%dPMY?O$wgy@!37Ch;xd@7;ITXjg}VMr@r^>DCxWbR0+kd7mLRU#t*pzu zMNL9G(y6#q@Ou^fqr*)SYd{;tRZCt1HcCF1qbwfFMG@r(rX;705rxF86q{w)$X>}& z0cjXcZEOF`AL#w#l0vPrt@!ZZhGvhtdOYIJ>GJQ6gnzGuA6NG|BmM2WF64 z$!D9`7RfUnKX3dT&PvUAON-i#CGxLbOiI8e=D{r|K?q&ESsIl)f^@e2M5#B{pIQ1_ z)M3AbJk?qjN5+p&TbtpQ5KwMaPo#HLru_KO3JKA%BzSw4#YaYkUqdYrnXuW3>%TMs zDl0wc^0L>sNaKtj)6;3nk9}}pn{RdVn2MJtXr6GA7S7sJhNcT{!waZ;g8t!94BFL7 zjZ-DK&S1cR7HCG$xd#)3`(PIvwsb7n}3*5PEnH)&{XS8GLllOQJn7 zsbwznmfDNy{OK)4AaksGiilG+uhP&PG8lBKtBHa93%42<&5(Cl0=vge8ULVayMSihoTIJLRhggLex;t$KF zZ1S)ycBw|x{GgFj9xJT6E>}8?iY+Az+jO>?CgC+o)L#a?-z5}h74Y!=-?U=Z_m90o z-#b|&!|MxHJRC~w1UD50-_kyG83JC6U<1f9CgQEH({APp`;9O2aW1jUx2>DmTAA6y zLYQ4P@~sY+(E~O?CLwbfw6Q6wd<=*q(s|S}jnCf-o%tu%80)7Vg&~}$SQ`}__gH6= zK6~A7zy3@iPow0VL}3RV2z$kV))2zFKX;KBMhHgv)zFH>_&I^k7an?;<9V%=?MTfA z*+e>S!||l4hcMKnXJyW)y$C@Xf`)IxqzSu(>5Rb^L4xHA!!;9NDP05~K6}b`NCa z5rEgd@EGU*fPS@3OUaoXG);%$q z@1Dk1d;n3Q=Dhh^^rkcnrfdwREY(VxDfKUF2j2{lig)$NNLk7N{HBqqsHk-}a|zY1 z*|;(wp@v2jf5cVwszc;MH68h@_2iY|4{MyZ6(4nRWD0#wVSsYuBGtJxgEc@C0!~I1GFF-q@GyTlu z1{je-4TbEO(nz>s&|&JdBBUBXl`iFr;+)OvY(U0*te7{6Yqh=kxg-X`)ku8NyxGve zt6W`}l&;gq(a}Ywv3qb)-|0Z(jZtCR+{hjNQTLnMJ<=HWVFIA zqJv^Z7o}PIDyGigqDY)@vY;g2^|=m1Q4G|DmR;ZcEM^C*Jh6uQ26tQ4?)?>sd2UV} zp7Y%}HonCgM0>q)xqePT%|>4Kn8Q>Cmbq~v5tJ12&^RHE;REvzHj6U~wHU0987xbB z8{!lNY4?+|*GVaB4=?oA>@|=GC>Q*k6>`&!mjPXMw2Z9rO{c9?%Mw;rx*9a<=VC0z z7IW`Bzh@JwJ?3+lL_~w;DMte>%Id;-Dh?MB8%Ul%IO6#0cZX9+b2MBIx6;zY7mJ3o z(>`?}TKFbMxynx~n(MKBRV|cnGHbQkkx3ed49LAD*X8aV$+h-ouCGIYHQa(*B2Qcvssz@Kp<+IEK_Uu5DOm zpS*5UT~xJ_wr*25zCEWi3%I{>+DfJ=gD+ttQAKYnv(M$1vrQPp6J!W zH{satTCQ%wNs zPs)Odxfv89qF9>Oc0gM|aWg3wVl+af+N0+0lGlV1|5%*?5CGR$qDB7=o&c^ff zUY)|MyiGksyYkw8@9EU%ubo=v+C!8~K z7!}+}SkmwB@n-ZIF?(AzUO^_F9Dk>moTH@=?Cn(0AL>3Ks|jOEhvUw-HtZB?rnYJN z><`(AE)#Ff_{I)JI8iZrgBTZ|nvt8-S&Ju_`Q-UE+Ds7IyrPMI4f1|-(Ree$?3yAj zu`u!WxE;-!QEcFBrcW71R#Vt8ybXC+9mYvR^KlRgs=#F+hig$9y$Jsln~*xAsG;yk z(7;gvQwXdY@@hZ|NrAJ0h zVu4o7A8OA6jXCttsDJ+1fq@T9v+*amnOVRqC&-t|cU2TMDs0{Q?>Qy!m}&7Ji(E>& zsMWQ_ZzP>lDA%p5@iKVhxAI@Yw5Vx&{<)-UIih7nG`!TQ<&T+hM$v6O*2pT^=xo^O z6qJJ_s!v#mv+~49Oky=V5TYh^CJGAk>}pPl^1N$aLV|I6s-mXRKk=yZTxsFR`4%C| zpCRl5c^~_y_ftwaMDoffKh*qZi=xI z^JQ_Kk+xx&guKv%f7~a$10+fm?jEX>B&un~Db^l3j)kGq6~TbNHA#DPz(q+kyy(Dy zZ0@P#M`Bskd`vYpw;>e?a$fTh5lwPjF6t94_`p$_f+=nIq=txT7>X(Vj{)2~a* zUJS*>4_2ZDpciuHfM^kcBDIf8>G_Gw--m?GP;EhE<_{bCy7$?pHI6i)%b>RIR@>ij zaY&^?q+(8~;9;^|n44ppdm+*`YrRNo)}B25O>t!VO}qzaQOZQl36n;Cv>7A?j3?4X z3Gbw4ETiO6Fze$ZPw@#hR(+>DUC@*J#A9+aruH|TOBrbVI}xn>FA>|a4vWGagqMt% zZ8{_j9j6h;HBDi<&MO6Q5*gAk#f>8<4m_nZZgNY1HvwsEJ`fl%2Q3olvmEC5pM>TK z^f2|Q!@v^zqYQ|-- zo2-X!FM$0gjyZ8VLY&sWU7Kiov+T$+@#L`ifqIJYMbVg<0~xFnU99+#-iVm=O;d1V zpM}J9JP~qJulE(-rt3sQ`0B4No#px1uWWJQyK=WfMBby;+I6udtHkt~gG1KhVm*;9 zmqXnF##>K|P1i2u9;qXjF2uelJBr^OyZjT1J{BFA=Sd+wu$#4PC!`jAGqtr->7{mj(LPmBMmpo6V7AvB>QM z^;48T`m?D&$>9KroK+~|+Os;8J?zTaW{DN&Fa0*5ZnG&yV z(0p$vk*9dTXRi@)5IshiB904{qC{V(?eV=&U3!QjTZjjtXZZsdv`pU|W#=h4=WZ!# zOBb$%31n^Hw((oUZZUSCIlzcmj0nbEbu!ypUu@YB1}8M)N<`i!Iv3`)OSgL^tfXC_ zd=Zj#D06@%X%wF9QVWo$5P|@#3b9cr=g9+vF7nF67U)%b)Cq(SezGN5&@KEeo2WGz zvcNy}ItBr71XdxxjsWHY$&*t9JJGqZ>9%#QJNWY)gR`+)t&jWWbA-1JqoZXB(7H3& z2^R?2uA4qruV|Hy$z17sd@EVzUR}lT z$u|&Qfnqg)pig zNbukO9}+|BJ1c&rBf|b^Y_;2v^T(#^L;O*|SSpR3cQEp>ZjdxAv`inZzY?3!`+s>O zs7g#Ul`P4cfLTq*tsY(@qJJV3KlnyCmO~k#PG1{o;Qm10rXDStHh3FloHfRa?neu+ z!CaRpLcq8pA(VJv9$QIks&QEN9z+?eYyyK<$R=fzyc>IrbSXFql{R&olLO&KAL!cu z21nA)+gl#ENwY(C_c#bsopVi}hl$!zunR}i*>Nl*hP^AJ6MIR>i{dP)%vfOMzYC*D zSyGUjvzdg>swQs;m4$(ZOSfHil?#>8_5=Rcyzz9FU>s!SDD@&LciCocaDXJjD;K5Z z;<{edK!BL9(v{#+!se5jfE!+W2TpGUaXZ^J?9P#dSJSm)a1Ph!^UT+~NVpt@kK&C| zMD|}F?sx4yQ{2_rvr18by**DkzuhM{P{<~3otvlf1baz~QHZn2s=>+fZvJhHRZtl& z2&NQn7B`VY?)I=lDG1-i%ozX^{D_5ZYE~MS9Q^SD9T-#`H+>oa4SoABs87LEuAe8%1;M~-$0o|k?@eDs(*VeB;C4eOGPHl#aKgdIh zZGXof&XvK}{6Of2X^z$#vWL)fO=p9beOm>E+6LDis@`kvm9xawhGfajnf&d&7kAKn zs@I4&Lb4*4Hw@}CliEekc?N$)f77~+tgZr;} zSHw@%Zpc4#HE8RPwy5RVgF!0|Cj8iB)whUWJgOInud5(%gjv*C4}nqKCHwnMI!K!R&?%E$_2779e;@DNXOFZ>KqmUa5dE1EUXUJH;CR z2T=p+(hbT9>a9btqMu9f?b@DMDPG5D2;OvOug%F%?7yJ>u#m8an9nLT^Rku!5Z}Qq z`*aKr_yu`v$u)7vHa6qK|H|!q9_~8&_N269GVb3j^sL(NDhkFLX&u@h3~n}z^tFgQ zf|u|b@L%yDe1|$jELe4$W~CK%e{0Lkx7TN{T!|4IDSz+#idK0G=w$B(`%^4w$_s*% zyLM}fZlm_Bsh`^`;O7VS1L8>YZ}*WY)-Yo%6P00n0Js!PGRh&vxZHKprhZtqg|Ekt zN&*sh_G$^SwV87FWx+v%7r~=h5GX=CCOj`ttAEYh>#C4epy_p_VM4tJw9EjPY5o9Q z;u8rEb1Dxbu>+ z?q@^8geJE$io70d2s|alS+}1b%Fi;76D`*f?APTtTO$NX3?w_4=6GA~Gq^59Da*HXqHqTAYSF-9~@f$E&dUb6X66N5QeiIY@)uV2n#(QN| zwvkJ=tv;%QK4IKQF+3L{{mB=K_rY2Jppkj91drIAR8@oL@ICaTRtk7_+cG@#G&E{) zrf$hk*-fj9?c>RATc^@7bh!F;bVG+}?U#NZp%81JmN;aqLt?${k5I_*x!+#h_TRKX zeB6fkt_7W46&txPhobk0a{RTT#>t54wuK5eA1A%D5P}vxQ&W=^lN2A(6h4iv)=^%VRTEQx zLLE}q)Ia0YMOdiOC&ewH{j|JNX?5A%=@Wl0X74g3u3-NmNdg1Xdm8~L07Y%aX_=Et zK&ZA9H5K(3gjkj{P{FB+S5iLdk6`vKiZoMs(ZUM7-D##n@hQp8 z9&4;){P*KvExURa0tJGLz4;7{0KXSU=8@lY;_Sp48A~OGb!$>Rxw+OwCN_&uf~97Z ziXwB512xe8QL5FOBI=Ppl1 zjbSlZm=CK+kd`T}^7=8KDpiRiYi)YUf?S5N5JxV(oItHods@$O(A$;Bv>>fe-l(#3 z>X^`0n!SrC`-6+(KhM%(K}U2NzxUqX&-Zagd})7t9}8y;k_B`9N|MtRoxN!0^&9%{W=hwB%9%{9dvI0(kLJPÐ}C>ZUo(GwJ-@eIIE-4jzf=*3g=AWf})`p;jVj3EyGxjiB8*AIWRBIx|8d>{W4)>le|IIg!7`rht zxlpy}qZe(7aMWuOeAhp+r|e+BHIaF54|i?8aVS@=GlHQESEf=`_XPVEiZ^6qR9uGJ zkiT-q2bGCDIfbok8e$LopPF0|sW)igTx8dvTWNyvh}+20qY*Fhb-m%so}()S(YFqs zn$WTz$9T>j=muv-|m?R3Mc51=_)5`O_$rfGjVa~<;p|Aj0Q?=WIR*IzQ z(UP|$n97Rul)qQY5ZHm-L@nRjA7aoS)Zbr@`3ARPQwK6T-20>4JpD*&x^u5o;41q%>K>LyamN|GUp#|5-)MovAaNP{Ld# zP$gTXU3MBHX{Q3Ciu7HHy(*b%g+l=CSB1YTtodo$X6%MFr|(4c7Rg|M!8+C8hgc;x zK=Q^Ef)>qJEUhk%3g_2jH=vEW1$1cU&ZR~@+;I-8AN+p6wW6F^a1n6v8_K9 zQ)uo=iQN{ALmWJrJqPgbte=Z;gZ|UL48HvU7Uv0K)71K@@xP0V`Ki|9A_i2qPf<(V zPiw2&=_fT`=(XH+4t0YV&1V#Be+&Pj>jw!w22^(e ztZ1b;Y(r)kpE}$G;v_?Gu+%mq_1%c(LZ6qAXMP0?@Pr?&oE$uioV1^Jh-+?=cSvZ? zNO-7f0;N3?8kn(4P`)#nxQ4((QSU3Wvm!B6~xGWJs2CglB9CFxAmzEJ~BhhxY=8PS*j8x(zmKo8arGIxW> zYN{-I8=R-zQ~J7Y20q=#bPm3*jVj0boAwkYHcrmr#~ESr>quaE7Ku8vyQym4`LQB!I^p~+zbQ{Of|_)bXQtoglzcVmoabDGXA&{S zL(fdW2cJ*0D5&D@>Z;;yOla|COo$uVzvJux-~z$Z(m}yokF)&CMbe`afN(_du$Jid zX1&0^Ba8U3=5cs>U~xrhTzS4xT{-C~qE@c!ISIEgJPMa|Y`_4n!!j{^TMqg7GYf`I z^g8>_+*6JbU2XOJ;@2sZ?1{s6;wE%u7|cE0X6vAEMjyPh(C*fGMY_&*VqQY3OxYVR zfCe$M{zjHP$5rTuyy%+eB&XfsCiD~VS3NG1w+)Wo&js7&c~BdyJJ;`XH#HN>EBU|b z?TG_Xy$e5_dxIm>+{8U7@EL`L`;Q?!#yE^-zdGXt$On?%obo@qe(tnY#(St4;8xL0asrmEt$jRx`pi1`v0Y!>pzjTzIXHGr z*gfdpM53=FW-lTZrSN~!SpL`^)UWi%5zik~0PK)$D9z|KB)V|dZ5;Tv#K>tM5mfTs zH*B(WP*J&g@VjfbDtdlxtwk@dT&uitdNKd|NHw2|k$&R^G6SZhacT@HrAUl>G`~6~ z*DWK6=96i>4P9Svx4L)2*`6mvk~b;TROUsu#u?T zG7CyQ)f;e(iSbDhUjWxMvk9R*0kib5`zr~LV3NGH zA0evUa@qJZn<)XZ>{O2z!>bmuQ*~c_F%>J^SE+0f#lreITe30D2gbNFZs8oHKwaMm zVEs>*mupXttsvR31c>+2zem?Aw$9{aHZ(M_s=g~UckS->?54(AdT06E=Sxn@0SdZp z6ue5hS>a6;hptoCsWID!9JDlOp zF+vuNw0SCtI1*a47*hyXcb+nTlFpGdf3fWj-?92NNpz^{IQc6lyA04%@7^W_#?u$w z>L(z)VNF^0T4a*99Av*B(!_{QxSDScq6d&7lJ*A(A&^u&#EFdKE+EF2f3aI{q>}|xtR;8EU%+wGFQV0po`-qPMzA+EN-SMtJ|*o z=GU0+A1x+pg(egDzQsPi3L(uLi$)&|7R=n{eh4@>q0bLjCGwHZez>G1(>DMiq9KCQ z`j4pB#4i9}+{uGtIS0C3Dj} z&!p8{#l49+0DBxJ{IdZqwtU*Bss=7M$+dD4gU>67*87^$4cs%whGpA=9sgqocg^_u zE{B;VW>)-qS^1W7jPY{MPOFOuPq|JHJ%P`Vt^E|jtdHF*Y0{xbbFxgW75FsD6Wg+#|e$2iR)6y04%V0t#1L|_h13fr9WXh0L%q8W~o~4 ztFgyoUG%T3pQqDxZh)y-OvaWy?`6Q-Udu7!^NH(fqdwQ!UvX0{jfeN3vN1ncE4F|K zC4dj?HDyC5*Bte@aYmaeKN#CwcNKw8id07<@B`->$BT$y=Bb=qx|M$*&>)DZe>oa1 zMpu>3vA+IezVyw~qV32xi{QM;^YhBdfn%TG6Bz7YU4W7^HD;su`%BoPk#r<}xBDZL zn4Zxb6b#h$wDrq{c^c}e!pnMty}XwOM&eJ^R;R}1Y3IA0@|x`(a}#e@>6dEPyGy~l zC`ZirS`G%}S8U{#9EtTcmgnm7u@%-;)ydINbh_Tcn8{z^gF3#pnTLC|Gpe_DgMAg_ zH8jU$Kr(6!K-SDZF`UM#JEPKm-?Xcg}4tW`@ z#MV-CJsWDO9a39UyWHY#qJQcjiIK{aEdh(4pGHK~4sh&mgj-gbL)lXwTjIq0$l?=J z+0dms$!bz?ROYz7%4RWI&uVF@A0<=&+=x4WvzlFfe7HykR-U-5SZjH<75DE8!?aRC z6A$6S?qlz+n8^2T(dnwX+uU~H^{hCHRUYihtkRHy8ukw-a zbHotjnsN;jtP&uq1%c-fZL zYl2qSkm<}BGM>OtNCfGq5X`wn>Vzc?ge8^D29?Dm5Fp!Q;;^$9Z|FS8!40K`mk>oRfj+Y6z`1e7wY*t zk<;@0?E-CmLMP-5(kPMr7&+0s`?tdY*mk7RYJrlr!b{mdClCSC{?b-%pBb)ScU#N# z=MTKDNyUYqAlUb7qzxbo`wo7C2HFuO9l0Ng6BGo#7WP#Tihr%_RUs_`sR91blfbj+ z8AE?E;2DO{LR{|}ZcmF5*--MYKY|7l8^PG>ii$w^c(x0Msus63c+x;@fb1U_nZ&DA zQW6y(CeSYCNpQtbEkJWpq}})I0tO&i;w6aZH9Mju`8`Vy#K;Xlx<(Y?YbO1>BPdjY zd>WWIO$d+bjFUG^d;9esIv6ldQ#)WHfR3Zl2dT`+qxQ^RrjdJTCN!W}{VfOVLlsr? z`t2rBCNtXPhVu|BGYsJJvehuWr)s0r()Dz8(8Yvyqg;FYr`iY(L6L!j{i|4_`3%)jJ2wp%(JhzNMD&%#m`0CsnwIC^O9g{ z03@?mReP{q5#CDAnixO}dLgPNC#HfgVw#i{nhJn`9d1b=&p!m``8{VF0HVtl_-l}iyNR#xMQgkV323F?QgwBNgMNZfie|g$!?>eow{%@H}F3<=0wJg5h zKh&!RT1F@!HlE@Qv!T2Ccu(+dWVmXHGA}D{BMjy{)~4iuAn9UU%D_|1`JM!d>QzkA z@82sF=P?OJJ_ozH}D1%rD7x&M&Eo zd8*|Tr>AjKqvBs6QH=p!DA<|?Ta&yzyw~J{O^&Y;w7TwYv^%1wGsDXK8ldqYT*ruT z^{+?ne<^Z5D$+RqzI^}&UBoW>6d#&G9&{pJnmw@oN^sHDz7A~^edM>IP=d`atN$&{ z!={<~VAhYc#V5$bQpUqjXSUFZ-uyfi$Xbv<6?%o>l#0UmO8k zNXlXq=uNl37EFHKDmf<(z*g4fR6$#PmGpV~(_+5Z$}+Yp23y<4691SbFmC%4XXOpF zjJ0;oHNnnh>3836$(i#J&qUvMiZ8R_FcDieQM!~_lV~?@-aut$VpavFl;tQ!W!~HmxJxFqd;%vO(tGvB3XPR zA!MvDboUr$_*Iq2r`sPwwUioAG}kNg1CHM^?+Rq3=He5tW-GHjuc1MTM)Uc>p2y$) z4u!e|^t=BUW?BrI|NHQ>Tl;APVL<*<=-EHjF45#r0B#zDAySQq)Gfwk>ZX^@Iks!k zDcDnI+yd@>fMo;B7vAGZ&$OZZRI>71f2CBv1BibaBBOV;^Xe=#+Y z^8Zd3YKnQf9{?MPjjY&NI7p&QLHp%m+B5(i(F({;J zWH>ACl0&scmc4aBxqO)Rm$SV?@HL!{vVdxy$Mi_qkP_!mo9}7Os$RO>$PcS9sur$# zjCMfZnn$NNbkdo$KK$h2Pyi$VfjMwrYuuj;!m9V9^0h5de!S_f*BcDjAOJDFqDKDw z!Z;c0VHN2+yd!{aC6NqT9m}(eXXy_`eefl?j2aLl>7^VhJ#ow~1pAu)R3G{vNfXzy z;Yh_zY!m92=VD+C-2g%+XO3~DoZq@c1aSe+oEz6MeB38yl;-#x^lO!cfjaN(9Q|&-g%sEqfdFW@Px_qQV`Blo=2V4V%?-`w$j^|YK4uGxM1*fM1d8Ja|nB4q0oX^m(}f4$;Jy?4Ms^wRD9>8I!PHrb}% zB#ilz*~$*|alIL?|4t?p0}{>IP~eO(1puOCCym?IQ(ukGyH-ihO5QzPjSM0~ZmPd* zp3rrGXAIo7ap_3Jwf&u|5dx*=EN9%#H+vNWkou2{AKM7%HE}No30b#A8}gfu2$k;+ zY`81Tb2g8}OfUYoFqil1+Dy87|6%DKDh#(CTp45AzV&>m)pPAilwG*l$i zxNTQA2Ng_V#>_zmuhEG>&13*OJjLP6O^9cBnGO4VSjKe!0bTT+^0p4Kn(8nfuKI7a zZ#lz~H^A6v^OGL>^!@n$l9L#^xcW!YlC6D1E&{`mE}>spyLLD?cK7UoB76K>jfTyB z(>lF9mqnNSjbljt=g!wVn^aXG?7rGEw%IIC;^y-42Ribzd28f#Njxx!SRog39JMtj z*FcXiP7Th5btKxVG(?#I-WL~}y?_DwofKlUuy#*E z1bH@_(Bq|rG8ZINh0X^syTeFvt2IP<-i;0=D_zunkh^1@uE^G z8)rh+)|&7B&jzqOCugnb#=Gyc(>H?E)53=IRmow>T~`4+8>i^4v?*Kq7H!SZ=aQA* zm6IQ3VCu)@9pcx}8zt01{-(#I`N14vugl8p-ujNWgV(l?y8&LO2eFq|XeZstUEP%{ zKaI#A*?s2hr%t?qO4IWLMq;-*xb+=5C|!wbx|aLBfm^S(PeLfJQbN=Nj_rCcyEmMv z8?BEYUvt5CLJg_jAQ}MoSAv~`WML*~u$f9H2pMoa+OoH=4mDy%_ViDg^u^pveT%Pq zC|?ib3M3neT$t7jMEWu<@yh<;GCix2VGEum zg&4uuaL16I;T_?NHvRQSv1V*81}q2UA2+BXn|>Bl`B_9)x(-{#*Eud3nNSV}#KyxE z@O}}?o|D_eF1l4Y-<&msQW3!a1l_a#|AFo~Sh=|VpC`~7)TC@kxezwq(Cq!B13$wJ ze;z{DJJY^?X2d;vk4v_VM%iH5by6shipHVrDU3Seo~%Sq#SHZ>^(NVQ7X?LZ*V$pL zgIqOAT>nPX@n5y4mo}5&n*2A`dpE&3Owgq%&<1Y@u~qkG+eWPwvV*|0#dGfeGzqmM zeXDex+y$OO0w*bs@utNbF;U4CQFx(*A*GdmkvS%Y!E+QpZg50uUYAh)pamY4Uy~Jd z)~jJh;e|@im>u2Qx!=-Q!vJT?D|4;82BFriHHDOkOAzEe9>7YS&G3x!8)UEfe=+uz zp_xQcvYAOH?(UhmySpb7cX$2b?(XjHE)#cmcXxNs7kAy+_a5v%*dGf`AE*n}O+&-w zo~lzdkI8-0>w!iO6+ec(U%uRSA|i)&3z}YKXh{1ppHuH|9Pbuj0NB$W>hM-jQwfF| z^=fCQjZsu7fM6z9NSnA+U&XSx$9(KsNguVQGa0xq&FB@|^Lk%}RJYXDlh(r4g{K;2 zbM(!8!^m7B<$rq#>o~Nbh9L_lAzkMw_VGO6yUa`d?O_;`?q`Mgk88Rc&07)9ozA!lT%3;Q_Xd+%?wR4?%C zgR#x!F+gvEcsgJ)CM2f~hOjKaE{c8r#meWM6o0+p=*@~h;5~zR!nKIFqfkc?4x<}> zNtpsWw^|;Ffh+GNsU3K+Quvn~O*Jp#8F#kF zuG&PXn)TQjb0%z$wI={^#@X(5O3lSr+kzt%_j4(>M=83d%s~BSWAx6Zi7AQC71Q-0 zSi^OMsi96^trx8HO{O6F0ToZ&ez=>UC7J!a%77_TA6s88xAmz&$;!Sjt_OQ+I>cnc z3h=W9b$CvMMZBPN}!hd zRT0B9RspHWk6H?9P_D$+&NI93@6 zfZE0Cr{8Mbk{6(Tj8g3V-5^bb%^8x|26Qb}OY4!GrhBXP zKLcK-<~3j{!Bu}w_#2csKMe9%^*y6M|KdJIFBxs4=+KAP z!s}W{HaBwa1J*4sMX|36hYwL#tSOVc3v{nmA$J_zj z=DBkT1l{J^K=9I2s}ScE9Jb%OC^x?ps={)&m9;`4$TNkOsVa8m;JTM<5dgHc*y>PR z_c*G*`JCe(>BXMnOwf`475gntC0cour_Hw#A zYRHf}KQ!z2hY}FpA;-$PIU$Pszb3OZY{Zg?b#t^Z|d*v*);=Y3}d*S9*%@5+Nx+ z%k*zOuKJHpO;Al*IA$%Ymfl*m`*p1Rajr!@gyc2hrDplLWK5r55AwcSR^-Nhk92*q z%Nj{mc|E^2WUNNC)BJ&-AI}H;1ipA@94mTUR9n5-S3BQZ1fFr#si(C*$_K3nkSUGQ(KGbGQ?OTai%li3j;lC?x& z1Nm0zKUj`5QHm^4nk?OiCjE5b99+7d4Ytr%`0cP_z4p%pL)6zFu8S%=?xeXy8~4DS zG2J57xfAhy&tz7RIjj`dk0}oC#Ie>r+u^gvg6?Or`i~;IKc;?vtDWjvWVW74O(r zJ{IXy%II{z1-@6_D|RhDv%lzzdKSMPeZF}=^~~SggSI`na@N_m|2*jsU(+~C$uFi@8+g@<><>C7ux5@JAY``YnF6Nwxai--TI20d6FLyAX5ikvT0tEx&%>FY6?yHC zxu2bxE2#~1{Qu?U`CawuZbU0TMR;6^O|M6HYOm4``nua zEUp1T^-6$$jyon`HCP8H2$6*^5pF5QD!Ojg^unq;}RE}(LfxJm33_tSb)k|}6=pR;L^vZK8$go*i_iZ(Qm4t>gir4m-xOWCoO z7nf98F~ce9-pdNfysh^-d1cc94yEFUhhdf5NjA`#=(!>Z-5@W-HA=DC6huL^M4rr6 zz+Kz6=BkO+?fNJ(0+}RUmUiI1Syze}K55$7sl;!k<^?9Kt#M7|Ayl zh{|o0K3SIls!Z0qi3UfioHfUeJ`$54D)_O(lve16x=+lG1;)p0QM? zmjx;VImWzwb*DYbiOR1@A*y+iPhu76~~OS(md%@MI{mP>G?f@4l3iE?b7AsA8$j7e~75jR&?NPNTuN<~In^32L` zCW5%ad}~|Cmk@L$OMw@u{L;^O?~iG8#b+dCMLUi4`%fBH5SThlC35Vgu!V-BfKWo6 zHQ?)2bAi;gk!*a0M)z;9?e@f#p#3;a7$Q>Tqwq?Hm+#V!@p@5l!CloW@Pxwsf7^$x zZ(H#Ysyp3hHE7fzq41mXvMqQv5Y2viW>XmIPTSxSv z$s>r}#xV4cX!L1rYb<6QzPYm)!A<)(Vc)8vRvp*2c&F0WC^jBk0bgo19GawR6;&z{ zUzKpqYG~8knV){<9O>}{)VVq0&0EA0JqLEosdhz-Yazg^eEYTi*uL~A==}9yZ(W}yv!!Rq(WgeKOaIM{&jqf>U4Jfo8^5%nH@ zANRPH&?7m9ZY2)iSq224fe26edy|-s!bQ*A$Y94R|04DyZ|UUlo0aXylLrYvs>uK%TUU z$Sd1-P!mV#(PIf-RnXumN?zl7k4OUEtY!+|b1my_p}BzTmW2r`zX^67yYhB7>R}~0 z1e4v;qVx%W#;jl|Jd4u;X6+A{d$WL8=MQ|G8ywc^7gYG!;2A zbF^{2DNDDLd?M!DblTD0+|-X!oQ*p%=;CQ%P^zFyD!URa^jfoL#d2~K=N#U|G{k$V zddb=f&Vk#v#N`$!e62B_|9zAs{5?k*`IVR$2u4$_--yT4w|}SVdGP^9=I^O*v~Y}* zNxkmP+ZrhIA$TbA#F6PUm?XomK7I_Ay6wq&g08L0(ebYT5IT{|5R3oA+ZQaT83oz^ z6n3|UJ}^)ol3L$SjCiBqa}MQEonk|)MCb>kc;=OBXD95xuZ%bl=EGbHOh0F>Iiv5} zgRcTPeS=SQLF|X*vsMTdN+WCaRszx!HVUnRfa=d3zj8~X1l9fozajR~tZhzN&?+4B zYK#HQKL-V4jv}-k#4{YDVxw1Ua1vIn{Ehir7V%A?g%sMsCJ%%4sINojUt>wqthsYyWsyqsRWk)+q=_W?yWl zbxzX8DRpCGD*DT@kaX)*ksW&_TGyqpYwOgFJ!3bz+pSP#`!t6g`#c)ovkMz?0G_-*-+LtgKi>N-CeGYET^vhFY)q zM}^QgxCos|=Z~*}3^a_2dRKn}`f{7d8H}s&9y;YFdvIo%T_~DOM}L>P%{OW4YH6tD zlAja0KAE?idYFHf*$A=0BqfVeK?NTPHKD52BAZ39X8v+G8)Q%5x*)J9R0080chZqD zU#4&hmkr2{VOJn{@f;EU4E!sR``m%`wGQ?yFBABV<}rD1l z78CjbYNI4YRD@RsMw_5`IO8F zZ4hisNam-3n#E?PW!M!*P;zi68!Hc%d3OLaU#DcWg2B39-N~&NvzMbUMq&ZIZlNHL zz?Lpw!O1UTRKp^^*%inBSfwS-mm?;1A3#708zaJt0g)UDk;Y$%-z??$il?%|>Kd4h ztN6+N%DvfVTj{#eIAfdlm^-j~(EVas5|A5WL^_O)6NhLn==jjgM_iiqv-1}1y? zGDNke7M8N@$3={^F-Q*X-5M62UgYMHuW*8QVQ#i6`D@d#`AUCXgoOVPlg1{o%;y{e z(OPA*{1E3yCAZhdw=o?XG9iMDa~_CI%EXDF5`t5L$F)OPe?prZo8|-ZNeS=2DaF23 z#lA^s5@A%yAcgwI!Sa=AnFRkY-~K;0r}O@1NSv7J-LVO@|LiyzVLJKe9}SQ6-+$0G z(UAeFB_u`h>A^X{DM6Fp<3iu6WIm%F4ewJw#UX)02nHqw#)9<%5FSPn{nG(ERcrwg z{}yO5A*o@AVG@F!vK#b&U(#>@l-Lhy4W+j*G632v-}tYqrz~h+WBs-+d8HxScGgE> z8%5^6F@K|L5`*|V-SZZxXnlyQabJlEB#76%0DA|mfPC-N4|4j~lQ+Ufng^OFnoH$C zZTQz^@KhjH4>VnR&^L~`#;FFT#%ftmTgDwNkiQMHj446PVUQapSK9-9on1=)s-|V~ z+qam8b22u1u)^hIu^M!6u_cI_G0qI%U%bE3$^#xWHt4L*Vh2XrTjE|S??ep5MZy8H zVF)S_rM6!`BKu2;N=S`%t`8GNiE8pea!!{r5@X|_WM7>KtJ4t@*-#JqGa2*KXa6hlc10SKCAD9>R8xLdh@UioQXpT6~jsXeJo93GVvHDqze;iuuOu z-5_;lYrcHpV5Iw5@XSTZmXUyk$&E*kSo(8eSwSh9V#=m9P&#I99gJoH7ICMlUgcs^A5?%RV^r;vruK{2$hyjpHVt` zlxO7-m6i^lQQBjp$;x#|r8PVXNMP=^PS9(}|P#~hWq^v`dbFF^ZFpSK_! zE!HGhZo3v90htHrDIb zs!fe{4^SHwo4Io$($w2b)*Fn49E>6nB`SnF)zMg=4uk0Hk?NtH>@JpgqXK! zf*y&?yV8<3C*%@0NDr9H#Dwc_)LL>;EvST?cqsM6Z>s_1m0>*%O=Pbn5xz%~wugsf_DnSSG=O^_XkZ4#nZ|q=n5EDgWehEcP(U1BqY%MZW>B1u*eEzgk(k$L89sLM&^^#6EA+%uZ zftw)8#OJXcQ%#cKV22IX&j3jEZ4H+Y>DSJHvQg?u=%2lywT-Zop;KldR%bQxbO&gM zCf)yXmpjmB_l5fmr4_zTdb9?r(^?N zM0M!yl`jH9p)1_5N}Dm>qayUy&p?ZFzT^)dqVG6A2fIBo>teUPFI{*X=8RS=CKZ6S z_SaS^5ZgCa1;2JO=WzFMZ8HoRqgA2n{|!Oygi<3@jt+sY zlxFkEaH3j{=j-~v!?a+eG^GB8*gB91C$0OmZ$b-++iUHz^WAfI35mIz=QZEm(ew5G z^c;J1_lZ>-YHl%Dd5^W=!D^&9WX~Afw>)G!Rz2AB*CMbZr;AKooUAew zTJH{GjM20`I%=M|-98Nv51t#Ra|59OW|MvtpI#l?_d2@9o54qOsumC`X0EgJ5dsYYpFL&_QFbLrGIEZQYMLD zU4;gR0N~N(B@7@T-|&_(;)XpO)UX(O@4{spF2SN~2q-TMealDl#O^hVutUhI#}V&g z;Wg+_D*KvxBloP_JlPQ|e8$6$^|Sd{>EsVKAjUZ?Pi1OvkM-5a5}NvT&hQ^eZLafD zK`k@5Ps4EYWYXpnf57vgOO)1?F#d*eBg1gl{h1s9OFt}GhY#X~GK2m006*}vX0h~s z6}Rz06lg~cA+z8qv*6k!`e5_4&3!xVKBaMVNz#r-n~TFKZn>+>W3|=SFk(H4uZCpH z&ztHM)i$gc{(9E4F?qS=$(J%=1X?1jNL(pk5fuOeH1z zbqS+*7E|t&Z^+>DhBBdkINSb*$rD%8K&m+KoUoN~RXqFn5Y`TNif7Rm@@pr4K<9^P zY`NQaYZLN{c|?|I4=Ax}7adGHd#mDpWRBnn+>w4aM2*Qn@hdms+UL!75pE@lkS)A? z2*iq;@7c9~E>qY24J=%nSsZoKomHLWE>Dz;Tk}K33o*D$;)2fiKQmR=yoKWb)RATV z-*jX-8Q3`fdq>twO`_R|8a``z!)=Ays8Af>%A-unb=N0P0wv%5 z@nW1+gCpq8ioX^seX#QRVfmps4G~>B!MUdIi3gLJQDb<0cXVs<(LuBIopTLebZ)6< zdq)?T>gO1-eNQh#bh6V6H6L^7#|Sa*pIF-o@?e2tN*4 z6xsg$+dW&D+jV3DZq|s+xvUNcgVU}D-73}H5A!CMtTPZ{l0=1B=h@DCA48ElL;~M0 zkrh5r02lRVw4eXg{#9A)wwxe0I?VIAe{JpQ(eJ-~oNmYjvhjW~;=38AZwXe4-Y%6y zTz}-~XuG^`9)2f@ahDfNQQ(;qV*9&%Z2z@Jik&5caIF{SoioqGMd6y7z2?4N{H>*( z4Z|_p@es@5%_XBI`j8G$_}k2WCteo2QH7IbOJd6Xg%!OSkH$)}LS~j$TIQQkS_b6; ztW?(xj4u3cK+z8K0qxz!ZPd=8%*QE2E|#JaV(j0f0b&SZd$5+ub~RSo)0Sic+xA{U zqQ-PWupVUxU(amBQe6jwR2za425Ib~0%NyJT|lVcaoNH{%_oDUE{_@KTN0u zk2RbB!NnMflEFZ?r9YX7RqDOKnh-{F@FZk&4-cJqqZGcgt9rYc*2LDgBl!;>jOkB1f%ppbVK~9v(cyU= zQ_ALY<@T1A`=hXa&d$HdduI?dgG%<#$QmK{K44db`QoJ8`6lv(q7&kVrUi&sO&e?;8!G{dW{{=EtNJ27_Go7oKcMgx=~hl>$!}hmZ(4w zx*}_j6Q@pY=K)4lc3(GE(xckQn}`{o(psy5Yg)$fJXc)M`{9x}v{Ohraw37M&aJi@QGl z&?YZXNKldUV)MvW;Q7Qe>!S$yPHigh{X;{1z9q)F$iNmauGJ(LhU0_TIc3Vw!w*h> zea@;yJy+QE3e1p3e85meTzp@7hYZ~7Lg~>2e-W?8n{D9&2 z-puy_i$YxzLXiL1bnHEKvPN)yURc%L`|+MFzr#02G&KrGT-6}yvYe8wLhFWkA6nCT z{Akow?J7F4A~P{YqVKv!4;G@e`~g{aqvdoyF-&pGC{1LlTC_eW)h9&67Tkz6Q^SVX zeI}TG1@MLKJv#oCO{}jnBA^JFIzuK2IUOm|NOg0K#n+ga@Sele;x(G(?HqJvemnms z`JX%Ub}GdaEtB$Qq~~r%=0G(p%^eBxn1yMO3bDmgnOLx@?kNh}xC>IHyq_BH&gunk zDWyy0`jrlj3&I$4;|G>1(-M&yX=26tmhg%{<k`^9rHmccB4FRlPz6p*yakIGAcBy=sz-D$#rhbEyvorG+yOb zuELqoNzpg>%lP_PGgAw%*AACCbb73;+{In#;`=fW8z})?3XE8tsj*MlGT?A;yr01v zbUbLnVw{<7LDG`Ugkh>#6g+jj`)94%btZvGmserdU4~kp;mc^TFg3ljUSXZAhn|(| zjo~s&bv#z}3ddcXJCI$`sR<3h2`U@iXjiDNcJFm_U0%j3b#1%>3p^p{9e)O}V#eBQ zW+@R%Vx^O9n=o;sbL<@7>xRJuBtj#lG42xNODzL=TSfj(f>yGU2f;L?oK_V2p@a3@ z+oOVRhdmF2wi{Z0C79b*JKxQNnWNHN#zAn=8-uSSMvbIlZBJ(KHH=n0H(j@1^mC>h z*qkX+V%4@dw>QnZZ*VOzD@ndYP>Z0^Bi`_01{K)af*KW1`$9OCR`vBL^L%Y^b@b>D zxPE(8>yB_TZ5hOjhsv36jK5TyJ+Kffat>f3X%?4kCN2SdkbjjT)sT3T&{Ve zZ0%uFbfbL3?GKT5r0yy&Msm<(#>lGF9mIc!y#e-RTL=}u}{ofvMg zC%l@USRF&|{i$e9U%eKEqkF;gwh#B_FPq{OW3uKa7)y%MIu+;_Xr!##LbF ziT|CXO(5&lWmP(_-FpoanJ!x7xl-Atk7_h`pJ`*rCZniTq6^eja5Ga4qskc$_|?Em ztD~f-SZ_n*BM4%xuaaa*zOw>gE zu1B7pF`CPb+_AR$xO1K$-F9}B&wWQw`Dy}aHI<$gZtA=v(BC-nZLf+;MyCWA+_dF7 zf1kiqbeL&aTY9D?0Q^s0@ zXcK%m`&9o{YPzqaog2m7an2LoBlez@Bn3)s%fV}0s^yKaSctSfNTtAJV@d8w#=x!`(A|gTRX;XS&&*<_Ln4qubfx3(Ug$J$5+n~v zwKcI=e}hqWvk%A5m}XCXY-9Pk>@}ZY#CeLiti3n*{p~IKYdTa1jYiW*p{e!px z%nf!E@iN7bABHEVXNu_#41d6bZKBg=lda>g9a?v8HeMQ*U?zk8mm_1S^wZH({R`Y& z+bpa!0*~xDl!DyIp-31}VJuTylGFcOO3_#lI>&nNWuAxuCK>*D-CvdBoA`}?To2k^ zllj&A5^Pj~Y3JG`)OW3qev!?=TVUOo8LN}iXeZ;@JoBWd@r7U-1JE-!RG>#R3yuF6 z@D#Q+F;+13s-Pba;GDO`n;-3+N9jWmxCQ8LB zDL3sFGfngTQw|T8CQLSxQT~}vc?l|~dUeR}7Okbeh@T}5;Fmg!49R$9d?`$pH+_yf z`A^pR7&P2>HuQUUQG_&_wOz*kl$@c05h=lgqYb`{8Q`GBynS>SyNsHr@# z15aGSr1)GN9879@0DBl0Z=uCcj(oI5~ZQ0%_H9f4H041|z?}u!;xMuwN3yauwTvDoOm3S~HXSjnQNoL)5uH<49R9S^U z_SA@IrjDg`4?|m1xDyUTB5trffWz5>_W@Jqmu#_x(Y_=ICGgf;4eTzNC3D{EYEtSg zhu93shK7Hw&=aiJ@omhi8jQ6jx9Rh8RW{;2Cw(nM)Q8hq4qi+twjS@cTun>mn>}Y+N0aRdyy36JztKr`6zAD7ob0U!j**Y~CZopRs$>nbE zWvL`@I&R^0Bj}knd(P9D=#Ai$?c%F0YE9b1_lvP0PDzIhF^neIOsvGJUiZUyG2dO! zKp6E7tp#g=T|8=%iqLIF#~WEGRIRD-E#!vQS62oEuCBpD>st2k3gkDA^Ocx5$;Org zvT)d~Pj}k7NtXfa<-Hhm*16HEYvXXf2*F;_n7)AGw*&fCvC1X@V|u%u<0FGPqfW=j zNO}FcMkUDh1=aADH zcc%7AmLC~Gm5I2RYmaB#RK~~)3C@yel)n8I&(ca;dD?l+wi3_Z9Wa*~Ig4M$-;Jje z+nkb`fPu2Zhn|rL`1zk5o*+G=L1#WUfNaVKDf`Opyf?;-fE;Utk6d;)WdChvX(8OxrA|51KA)QI|3G;e5gFm!CyyJICKARSN;|UqrrU@cSbl`*L>u~qt$9^?*d#|UF|k!1AU;tv zxX;96qbTpp6yCv-)jyG%Z>}B~kdO{AIRnc7c%=*XGIo2EEug|QW>OE#6#&S{4)Eh$ z;f6v_{rTlwo)>dc+TJb<043(IrGVy565QAOiaw>DX51>h>iO24=w8XX2=jq<^L2S8 zW4yfM&DH7Fz$x@%ZY}Ve0btzVqLtV_*228FRsW2cpZ?jcTpr(`jzpRjtV60D%w?oM zL$_y@<^rXbZwf^)qtd_9AmtV#xg(%-)OPOP0nsC(wik!_E8G8xEgQ~Ck8YpZHvm<_ z>mu}J7~!@l^5u<8bii^I;kJrk{{rLoUq)+X6T!X~|KJM!K1_wRRHLxx=WI?ZmznKW z<4VBODdF5U~GD*HplZ4l#!hQNVkipM^l9sS6J@7wt(+d>SY0a!%atl&B$?N5NB- zX~=vymhk|_;Rmmfbvei5dy)+PNlMG>@-dUc#cX7U2Znr&Zu+?+8Ko*0c*SL9}@ z@k3a$8>ISTeS1BkX6iVo1>AR#@7BQ-pZqg3ydAp2eCpO!+b;Ig_wK-4v>7$mj;n2W z77pZXRs{l(drIyu+vd=RM-=O)sOdG%>Zupv4EX~+5Z-vx0PvfiX4@m4A*`7LiBLm&miBE4I%Ei zknfzcR|^Vn0aUrzy-zce&7rYH|-srH9Cj@Vg@$xh#KIZcD;%`hhsd#Qa2bU)UWXyK#_9<{Q zdOK$Qv=Pa$uz^a*(kX$lNNgt7Y504UF7?tv2p4?D6U{2mA%dNT>OI#*BLU90UEF@_ zX4or1oR7_@bHwDqTUt!dMp5&8fmgDLIo$Xzk@nyWYFizN{JAm47S6by6;O&pX9>8e;XSZf4|*^U1t( z1%z1d*xb#;G7sy^v##N}z;2^B>af}TVS+W@|Qc}skj=qOw zXM#>f&s0p4j9tnD<3_Rpzk-EvKxELMqzlvu7u|q=Yg^8(s0_`>f!^6#yN!RcrJrC5 z?Tx8rb8gchCZ(=lciUqCvx?no&SL<*%1e80d<3=1i)U`!CLDcT^RCk2a+YcYj@FcL zGH&E#WjtpuhzI`?i|rknQG~K_{c&@PA;ch7Tlf>Np;`;G3^}}Bqr_KQOOtLQA3mCQCz+U{CA@ zAi^ZoIJDsJ*B#e=@Q`!ui(~I9Xr!?Ep)eu3n!W-uF->)ELBwce@c52HEhMo?4KDP;?vUwO6=&R_^ew~Zohc$=~GktH3=k-PQCG*SyK8f3~2e@xvmlZ$~Wb_ zRz+rhXK1?I=hCW<)hT&yeZ(ra{6os2L)n+&8f@wgX-c`YKe}^_&s{5<+LYNMlS6l| zQ4?$sYEtgu%Oh%Rqb~10nwF*NMwAR_q^OX!w7dv?-zU^v0N#w@3`$tKOet3%nCJk9 z;^O}2rOPNO$2*$HcWHNa&;m1nI9g*=1ut}TR(VAgu%dk(z5|C|CPPP0R@ZDv3EQN@nEu~X=0{;Et^OA1s*0HPn!GI8GYXZ_8F@Q>UG2@(*r!P9FTdQ=L{M9YLXy|;=}ynX%2Qgi zEJM0>j@xGt)my|(C9axp%?qM@>a8Crv3lRoQkzp<1Dbb(< zoh&&wuxziGW-#=Oqa9Y(8a9HA>ge;tA&HoYM@T7upp%dlikCzqLwut0xo%Js@7G36 z-o0*+n4)fw>PK&o0-?YN82d$|WP9{cV0Fp7f)=6qgvOx=7$53kXdh)AkOQ-V5;2R| zvw}A1vj%r@%$z1Zy!XTws<_Fws|5p@UK@>i%RQu%Z~(`P(>S(bBty(cM6 zA&7+>-fxcvgaMZnJPJgq!I>j1f_8Zf-1rg)3m!#SOc{S6rV!VRgVZm|olscmC$
2IXFyZQsZ;I{N@aXu7 zyqUX#r-=9q(H{?JTs+7A5R5;(AgTICx^Lz{2|7JTMxedI271LicIQCxABDsboJ63Q z?g+F&kTM+#iSk|P?ZL8lD&SOEX<{Qba3GW(KD*ZcLiU1wcNujEx2xT>Z{1HKPS9#9K20}kUT~BY!YQaDKL1VzIDdW4NQJgRrp(Zo){Guj5lD%1 z9PF6cBO86l)V@FC+LR0{oC`cT|9&XB;4o@R}D{m}e<}*x`8&p7Tp~h!~)~}i))d;>NQ;+X5`3)o}^zK_=!c02D@Ax~& z*hX{PSZAag)&;HtxaM@mB~%V3hlJud0vIhT5Cfs|{j-f}=l`JA&W~OVSv7|=wTcy_ z3^*M#TR11ve5vm_{Hv3??`TmPI;6byviL^fODgrR6hqbOg{f0$r%a_aCFs?nw08{*Nq3O!Sd@C4L)%}CmOGk-K9*) zxZ@>enlJGy%rH!)K&Mw5u6{8`B4ajP-$5MI$e8fICmIy@V7ZNteouZ3bc`~cpfd*| zDXJjKwmV&Lu!_wSSp}#MKxpXoyP7n~7g z>iv6WFa~Dem3B7k5An>{)8m7)W42{`cEPTG$}*hTvN2x>TkGV7?$}2(Z8+f$xohf+ z-wv`!bvzK6IM1gH?qfOjt9<#A-KQ7mZDc~%Mi&%FufGc#UAsslqH?JtP0fLPRc#tn zX*-wAq&2DAaMSCU{Zb1B199x16d`&J%01IqG%EWoAnDQI<&pPw>(AIA7vA({XtzH@ zrUta;mA^F!g}Jif_DV6f^(dLh(uu|3-ME^a$TugT>n7&a6LzPNU$ca`H`#UeF>?zB#`n;qha?}GSym%FO=6 z8p;V>(~jiMu5+2AB?EPQ)TLy7`LS~YSH%d7c5q30#|CdJ9S6oN2X&l=(}aJb(LB)# zmCji0iuNXjx%N;I;cC*k1WQ>Fl)xR*l~K2qQ=zForDE*^d!?3MhVc~IKMvM#Pe`3K z=0gpms0uvzV~>Bts{vdN(cN(uDcY4<4rL{tOl7KIWvWp}O-@1B-0|`?{|aQhd?f9f zHE6Kr&+V8gyL|BaMw7-C^s`Zx@qtO^f$IeGKWru$3Dz|Bsa!(!XShnE558@5sW_nq zm|@#W!Pt=cV+kh7b*pRzUo|+>Hz!?ih{4ODUc$)J3>Lumx#VopC`|?Us<2S=P?Z`( z)h%mjw2EVBR?9pB()!a zcbUk7@bSe*pX8n!kG-;>2iuOiiZMg91D2`HLU=aJ;mlaqoUR*>6Tdo&DLW(Cc=F7& zvTSS{u+zfK5ht99w{~eu+U@8rxX;ci%*~?=)|ZeRDW4DD?kE&*(RCgrEmgT-UC`X=tNuD2hvo~oFdzyBScP{gXzTT;fKZ<`YLxB`@0 zL^LHC7WnG%*W8i!f;=yUc>hn59k&0H?8rG7n>d);04OAkO>CUZo!lwu6-@x<|I&Nh zDFlse4NWNNm7MMDtW2!`E&pcVg{pWk`^c>X;1$AL9#UF*B9S}E7M8{@Sxsc1~ov{N}g zAt2I3s~Nr{tD= zf!A4Hj63#b>!5k-?0$r$^kK&LE zm+8uM6;zjShn)iTew@Z^poEsAYPO;U@gjwpm4A4ydb<+I+V7KA)8uV{LW};%z(9>} z==-;nM&)wLh1AN(4cevx;~ya+E4SDeLvZ;nkF5-}FXP?1O{bOhuFTJ;brGhO%iV3x zkrS4m#I2pt7Vp;Sd}w`y8UJWV_g!4M88>L@lUV9!?t#04H(dtNbV_Ii!QT|r>z+lH zRL)izwTzRX_jBP9(Nd2u%uTNwdOEF>pjV?-4*`gH*DH49hq$K<@XuG5gG4YKRI}a> znXBxUEbg&BQ9Q;tpY5n+!^>F^fE9Bks+s8oP-^P$dWIJJAmjA}*+)mZ7PhlW^%~q_480SZFpdwhSMueu^-IQ_)9Ro9{cD>y7tL zJuz#0=2ge=75y%(+zx|%`x!Hb0g?1pAvo-YbI1kuHf1z3=L8a6Hioi;6&yyU>LQX| zXvhN$ZC?#CeMubbu!^-7A}>lSkf-A+&J=Iahw^d<;Mj8YzEPsNMB52xD85-kS7mv& zWp|2ex5zQ}nj6lmi!1fI(r4Q>pF*leZ75x5IH`_thcN61{a*VuN04DyQ~WlE%qnP{ z^Wcc$Cf(s1g&bX8jEtOy3$DX2zg|T-c%VXZ#8MgMK z)+=a89fB2pEE;4|6^eW4y3{#wOj6_Vq~L6Y(xyTJx#zTE@rr$QecD5k$^}I)r5q-? z9DQjf`OQWG%(qiyi$^jh*(~yFWx0153HTjv1}eHL#*azHtqO*JWSj)ic7p3)HS}ql zXghPXrt`2ymgB$U78|y8?yCso`vSL>lh=IhkFA@H zbaC}OE11i5btzYM)E6tI8%MFzroo}W7R_C+XnRNcz>ZLMTacj3;MK@h^$2%^p8Xw* zYiveF6pNSExuSY9u3_fQanfn^XctxFT}Kab_!~k#I`FrsHs7bOC>t=~$ve6`yXw=P zODjJi8Mndoha?llm^U&x7$?x<>#O(?%lqXH6}|8F%q0qG+>Ug2n{_z8cXhkwZARto zEyd0P&?;WwH#U7`Id#&IBhvE<9Y)yst`Y|f{ci52^hU33ZH2IrKd-Am5^>v0y}GgM zG|j7e{T*S2NQgQ5xjAxNIr^s>+=QU*=z-@|4U6G@a-tsb z@-Mv@0P(gX5z%oZCOCYYhSDYyD#qM|Y1mOr{`-EeZzJUmSVcqdJzKH}=^Ge7Zp&XN zb)FVX?9`g3q(XkkxPFx{?rwqi^)OX2HWT^WUWnpdWnCbT7G(T6P(gytx7yJu<@T8> zzLzG3Mo~YGVWYeu1BzW$Kq~r6l#GNGilxX>p#19epzGsyvVuIkwvRT#MlS|J0;UYg zb#Ce@XjxWecFG|}uU9=^@vX?`UuDzxi7Z-0$n#UN&IW}U5TShlj^T=bjv}QWZc*N9 z(~9f1ZhF`8vUKChU&^^<5rKZt>YFjU%Zo5g?MRC+7pxH=XLideqQpS5?sNF2fu1PC z?zz}iy7ejM$`A6K?6eLwbgVmzjdU9^`Z7N3a3@s_>qL=@8~IK^8uh5~jkjLvVqkNm zrdeD8YQfsPwYT7-s@lBcw;L}xagbqaETG!#xqAXe^MUN>|EfKp#DSVn7jiYHE zY{Of9-}mfxG71(6R-y>u+<{bCzYJ0)uh9aCa&9$KkX|dU?>kbR{Eon?!m#0W{L;F% zV9>A;Y!}&mj$w8X+Qk_Ik~4_XR1m;q6Gx8g2nQzgjqtD;3(N$YpX&<1$;63(YSI-n zzS?GFVIsWHwpPUK;Hq}QyW$o>qhOMmG=A1u#vYMxG+@6>O|{FAv~fU9<=~91r}6e$ zN5J`U)mpb}43D^(2ie`?-ei1)PI!ev;KE09w^F}a9CPbo3Udn>N4?>aRys9e ztIsIWQ&R|G_@$$7c!+{)zj(>@cR0FXk*hu%>x2G1LsZ>4Zde9iie27iEwdtGr>87& ziWV0PcSE$%5aTM-<4!rBYtTe&blN3okxYwVMe}@M45chLSm=RN?RBkbeVW*hwDF zd>ul)_C6XNYP(?PzaBZ>&=xZpI&jOW+BFI7)desNa@u~htvr%nSra@zlC?!TU&?Ty zN%z{2_3rANua$l@>*cbMNYctuC?EYS-*l7bJvD6pGlL#08p%tNS3?=^CTg&xTTWeM zB0da&*tb%R!tpa_ZO+%EXD$}t2WEj9N#=kx{G;Lm0y#()nZ%m!y2uH5ClQ7)XO&z= z{<(Y4(iJyy@$qLJSu-y8s9!Jk?5X=GI()v-$&*c7<PT53<}AUDO!fEpwFQ>P$-1yG44Y~-h#fAmT^6$@4!ZX1g&bv({ytUAWx zDdelDG9rq^V{x$oH2k2sJ)|V2vqEQ6Q`r{(G<2KUswq}H6I#xK^-i%;qXqP;3;228nC;dG1~ zD%=QXBFKWZ=`cU(Nt05l=7wmmsgPmKdtlZhHA)sFnp(mHr}L*9%B*_~~NKbZ$Vi?dWoLl8f}T$LhNnUmP3 zCQl|O?UcN;#rF5>B35!a+143mZRaU4$U1Y?CM-&MLi+89`TYyf(-6o3xf9-=_&Qim zW#Cgx4~gLMM=a$-#oAPvoF_7R@G8>I=m|7(j_sEDVKwTMHALi@5bP;WXh=Kp@=^EF zK{5WSWQB?3t17ssEVTgdLJt1QAL$2Y(~a1=cxsvA#rF~>O0qMsJs@+LYafFgQ@2ML zv|WB(MQi9}?;MiUnCrt0`QTgzgp|?-(SLMQn^PvU7q_Hd_f42v(D4y`Y2lq{<8HA2 z?$&}!FvA;2ts;AIy@F5sHk1_eoz7MB>RcaLPWiCXsJZ|RO;PA|iIgL;336^)QO-nO zVeM0!zTBa9YVD>wenJs{F4WqXp6*wrxkzHkUrVxh0r0nP@oE`@i!T}LgXkZ5863Zo z&m&1A&wI}<-WLKRP7|^lqeQQrF3bW)B_L*p?mi%A{EaqdMvnAH%o|X`r>_c_Bu5Bj zii-8rCGq8ikum`7iU-AC69o0u{4sM-Or|FATePQyFU6i8Q7-o7@I_U()J8 z|Ks(?o9Vl$rOm+eO=qozsS1m`Z=2F40@t*!$`rj*$L{nyj|t~7*uJ;s**w{1(G}Mf z4yr21tyORi2~B)G&mVDsf_q=L5dN5?FofWPeRt6jYqW*^wBP-qy@{X;Gs+@d1d>#; zPYAJBBR;B3NV7=}&H0z>?Xdiv&mNWa2-SDH;rL~|4eMi{pO(Vu6*6RjS+4YZjGyOH zZK$dboC6Nh9^<r+vpTe0k|6mysfn_jwKy7O8Dp02p1wsI^=f6x zv|4%4-nn)m^_w}#VaB_mwW#OKMFZ*-dW0efz!Bv36F-w4(y*+TXv0T->K*nf2^%iY z<+(Hf$i~}w?>-A!8oLrjq_NcFpso6Rn_%)=+SGWm@L0U}t(r?2C7S{KoK)sk7t&gT zCZ4wR;0P0EQqkUrUh#cxq9os9#Z=p{4<9}(LmtC`WDsU#e^Bw)zGjVDyXNb$X?65L z?svVBWz|}#c$dnld8vG7SkoT3;#cCs&LR*AKl(|c#21(_=utsI^@$>~H*DotLA(nF z`A*kT70Fgf6_@Xxb8E@{z{2_P;MJ#8_}M{YA>?!{biflPx+(Zi)IC(98q(hw#mQgx zi>krLjG2|UG?D8}6ux4QPLJ^2g-$O#nro=b zCYE-MGV7+Nyw%(0qzJxcZ^j#l)mgmH6FBo-^D`Me?BF3Fmqh` z)?3_}BeVF>+ENpI_)$0cdfdOi_T}{=Zu9pm_sZndB+p)4Ud*9nlaM7ir{|*Eg>5oz z;%m9R&qswsGkd4--MA}nmnGRE}on6c_FVT3y71H2|7TX(N-a#A#;zWD%hGbL%#7`taVgtuoSQmpoHE>pZ zDcGz)L%X_>hIRRdP6Io}m8Xw}{w6=5e{;t@UG{>=amfvliv)(ntM$rjtE2GbYo<(_ zxA~j41haCvjDHbk()OD zf&qaP11jiILZznvF@kbH zHN)IQoRbB}!8(B1xy?_G4`1{K=Qfo0b*nL|WxvSBNhj#rtlxXXzi&mZOZWi~)Bd(< z-NPrcGEw?U>xidGYWD7{8OPv^VTP}5R0YbW^^CN-yX{#nO5CF1QuiEeedmj#D^L1_ z&hWB#JgA^0o6`m;w0wJ#Q>)%N&7ru7V57fuw3Gj<$YGS9N<-9@9?S^=Z(0|WafnOYQk0i1m z;$uOmlJ!KWl1!(r4&|av&l&n2Dckhy!W)7(cC!#tvwM|}>eaB^VEdwnHZ|RMNP@}( zpVa2__feuc2Uw0k-9CMDY5NSlLi{Y#%7~@sgr1?FwM9gE&}i($ZAD(aRxaC?m?y>T zs{Y_6{X%12LCfHUPGGku!_Z9AX?OHC zO|q2?cXftG{6(D{x-4zAv_$WIqBY>Wd`+vWJH&5-Yf92&#!>CVH2c~(vtN&Qdjal9 znii|F)Z~XmPt~sr$l|9>965^0?(*+*-juSWrTgh$m2_OKJo1z;Cf4JK{O%DY|9;^cA>#KHYrXaj;l;@4R{SWC>39Z-8 zP6jVOQ_!n*=j;uZR#>nwO?A6+cQvk?XYOjNu1I+ym{bac^!6EjlR?{yQLYO8Xd93x zSsIo?lguIHz#NC4!YZegL{)V9>a-7rdI9lqr#VHZ4}0X>x)-Rm=&hg01P4`)%#3NJ z)GCMqsO-X@WN-k542g2`zbG#wCcO1O;x;LBn8S6#)A0vmpK~7GBeuY=13E7D9hRaQ zxO5>htL6A#*+-7B7A|%Yytbg%gTFMH_6j26h3UMt_VVSBRG5KB4UR(TozF+g)Za;1 z3H3?Dq36r&4sF~*>)2(f-=^;A**2&ejHS6MnYHcbxwtpW_=G+BQBKLf@9mRX6bg{i z_B3MUi+q=)a-H!xsFqJud49q`P+-0I0c~!uFl24XWn!MsBEo8 z?9bmmRD}???1U;H_p2s5;_xf6J9(5r2(igM2CYS+b`+ln{3S$ zh;gK!z`?#6`WlKCtrv)!GBFW_n}U^U8X|feEm&Z_FHGo|W>##q3Q0?nlYSAknN z6Qn!5FG*N^qGv|&F^@yYR|>6@!7-R7S_MN$#D6FXCWdX`<6t}fUR#L|=IN33*QljN zJWeo2|I|i_vE@@hqNE?8;-w!MJ2?!NchE(_2PGJI+Nt_ktmvx<9k0B$t7P}Ai}976jv&LlRT(devDn6Ipp_pEti1U z{t^9Chd$dl!QFOs!I1=#LKf4P*$m*(A){#lMSI(_ZUn?JsWABo9|+@V2KhEF=H*4D zb~DPftp0d#^!22+Hkmdd688QL8oTLP8vlp~>08mFWBAXL?{nW3z^H1zYL|k9FOd#@ zo`i|RwlXTjz&xcsyyl$DpHnUsnWJ=i(?l*V(SWIHeoDOIu|BSR#lEgf1K3b#xM%nJ z{=uo&jxR8cnj?^bcAcE7G~F)h;%K<01%?^PdCi)5z1?b6pBL-QUdl_etJ0~IY}{m9@r zlpd4gOSX=&kYv4EmB&iK^Cq;^`PtKHg;kHvroYTCqx70Y4WUFou2#SI~pp4 zZeEKmTe`{3cKYNxJ6<(wvZ-z@JASNv{vOQOIHiW0!p$Ym=@Q?Pb_o?pxmF@%NLf2r zT+T~LeZxnUYbR?rOg@kopaROmcaJHNF>b`j*=MDOLY%xD;zQ*k32>S_Yulnsr zfk3xbt|_d#585Y(=jW72+6!OXn*#;=Q?O**!EF;{xj$BxPEaF=ms(HRJj#>5-r8O2 z@Z_EyafNY6Wf{|hIcfXtLA~$ukWs}EkTddJl?$<>Y_S?1S%&M6u6i9{+<`QZaaFig zP!Gjywm+g=KehxcG_R~5H3QLo>_kNOVNmi2I&j>+@UT+HyxDlUo;mA#@cx>YtW@Xd zR;HFDzFaI&3|9qL8;P11X#P%??FnbPfHDDwVR^N@-{I@iCrY8;@MJ>1>D^*Z9q%Xd z>qwd`_2)Rxq-GhAoz`QF24@t;I*YtiY{@dl*eh89( zoa#1Fo0HQgW4x=&?3bdho6U}`$)fl=GP@e49+0kW+l5Nr)QPOxAie#OU%9NQYlz@W&LoE^hVlKD7pUBIjv zZZ`GW+Tt93%6NI&N&#m#%m1T+JdpW%- zew~($dDGDqrFe)e0U)D|Wn@xm^D~gs>ruQ2lG4*6ys?v_TvgIbc^9uRF7SiaLh>s4q_Z5Wrrux!l0EAz&jo`jj4~rcaX8Z{gL2_~sOu_@j^G zCR3-aNE708fj^#X(Ym@lH=wI6pcLI+XNGAzvd^t#R!~y^;0QUA+9{z@NDlMj7CsX% zE`U=>VO%Nne{-tP*gq+lXt8{?$dG7l&p*?e`Cj<`77%q~QJc_fQYNnu1|wfKv2_)%xVIZR2)M5YfC$@N3K{cxVsW|zQ)jnh;!AuK?YeQ* z?Rz6Q^vA{lLI4Y$DBHJ>@R8BI2@|{hcV1`WBIXGO=5?sB<(1^l_=32S^|9LHa?aoM zo_1`vozL7PreL+;4ySuI=dHBw46P>Y)OaGzQCbyyW!uhm@Hu6BTFkA8c>5#06R;=0}t_fmUOwNahRau+$B z3ptfBn|w@g{(Ax?KLn1o+(Kb<7_KhkYJL3M@$$(eBe`c)ycW&bG(32s@9{)oTD^J# zJ#MGezK!6xVqBPBzxlvp819UInppPcnP(o>=lx*^4rQ|b3Re%>HAdqa(ji%mXvIm5 zaS39Uj;FRlE@Ds0f*@^iKg=d>nU$W)XVT%xEh+EHsMyeF)$wt z*xV`29>Len%k$)J>^(#WcGF6b#b&7U9L~mD6(kO5FIFO3`A zYFm6nSRRbkA0|TzlY>D*enJ|G21LWn@czQ=B zM@Ce5usbfJAL3%-@trtX@Nq48tWWv!?as5$GXRq|OB#Xmh+)269D;Rga&|WUGzkW_ zaarB=d}$uys4IIV+^7R1^Bk5eFskKdE{Mp*7Cdb=1Y( z+v${6C=;k&4(tsaECrUMFyYKUYp!_KmGr19AQayhmt&QboL!yZ z9u8&jo(ys>4-nL*!Vu46dt&=KMRedQZOt?Yq#wwlmN21YE(7;odI|ZbuFm7v3@LI!Fo#9cpASq={1MJ`w)w@Z@uX>qG@i;x^ijA{5OHV#OzvZ7Ko+ ztJs|bw4N4r-OUWon=~uVJ=?RS+Gq;iS7qBL2%9LMt~eLq0F4Vm)eTlttvs3MpVu^} zX1}LL4Lb<)&R~I|*Y!Pyp95Z`wrBgOk7AN+pS$_y)+7CJXWtBYULK1(#MN8Y3ACwR z^k^qoa>At*=;(!{NPHLXOi}`M&grexbH!f0Xm%V=)h?Ul-SigUg%)X@<(A>gFc@5~G4>T_ zy-&-_qq@S&!prMM=kpul%ghs*)mS+;`~^0S9(G^K0sZ7rRt=s^vhLMv2`R6fv?fPO zf<#{x^$M=K&_>tCVx-b%2SxHhcths)uu&+oOa1gsQ!lEencco;@z4zGmpe&ZMyHLg zZQ@wW5;<#Vn0Sx2RFC+q+JVO-%7&BpS}59i-CkOuoDGjRp(2r7*T40`+YvR)!Tk`Ij49(Kfc44(P2zn!^-0SH@mJt6J{9ye zb_^d*Vq~Z#5Q8hsvY8fDyPN3oaveWky6b|5t-;BiWwN=)WdX`BNX<50BaAa1e{cIX z1{Xb+C<@s>hB%2I_atk+AE(?BJEc59bmzsMQgLe)Ik{Q~yn4assXNG$=eR7(aF@bt zwVF9+$GdDY|FMZ}L1n&ik$u7|+{KwJt^3jfem+0|ws_ure(40o@v!c`$1~quQdDc; zy{Nhf?3t^%LcEeWmYg?>aJT`xRn#CUAl0n2A}IeuYBl=pbbmVt=DfNhLSoe0uLyJY zWBa9c){7*BrpJ3QqK}ap_*;>PH}<+K3JQmALcB_d6-Pmnzh~kVOLHZJd@6iArBRYBu$J z?J#NOagQ92!){vGL{m9|f=69GX33j4MHRx1|Ei@Sh31r|XmWVG|H@IL2&quZ`u#IE zK6)kRLeae(+*Q3Bf}y9^qf6#iS+^d<%hcWO@IDlkX;}ElAmNOx4?CzsGw`W_Jthl5 z_pocdkG=UkoYOLB`}M{2Zg>Jbo<^p2?}hgUXBu9~e#Jr46$9i4&0ycZNJ3Sr>z;Zh zqeWN|x5SL-a%ajUmrFDz>ZpkMK^g>q-P9l?jQ(rSck=VoV#8YoyONW)F8Xk5PR` zUN}xcjk363i}7KX@03VW=Nn-7Tg)|9BnvipyxDwQ8!Q*{*OHbqzSjC13L?WMIcK;t zeJI6hfqx^u<}=#mnc{bo;(vUP%=x3XN!0H0a;A>)7{!@^p#SwQTx*tBPnEqM1ta1zd4YA*r=aVX(-$uaYNNO_ zHh4_#jM6U&_%iG-H*UVu?L=MM59Y`18%lgbwdoFY$9HTT9=bW~8;)}w zuRlF@YADIcAyQ3m*dItVX?ESVR9_=#Q5iq^h{&np&y@lD3HJQu%;3kDNyEoq-2oOP zr{Ca90!zfhIlCBljf+~j9ot38a~~#z_BXu325m_(1@qIWyZf+eqkQ5mBhJ{q<-z17LoC( zF|q-&GrWT0n2n6ryY_WvfM2jG`^P5vT*Sgm4{QGgr;H)rcZTe(;tAJ|NcSC>?-&}T zP9!!*3ztzkXQ$((8@DpIi`nT5k(u0XT&YjD)m`q`=1h*P{hn6HvV^gLbeBc0FZN*F z29^yDhAE+b#~Ap9$9O$VF^5McB7SRXN$STr=tw@8>3HVkn@IZM_bU9gvrF^rjJZflhQlI{(uBsDcfx|9a?!}(U2T!&U5|5 zV$vd}9n-io#i9y|rNL~3%MVP9>|FSFkp}5=0z#h!8dTy2mp89V@Q3D*BV0Y%3SMtr z5{fjZ;kYa@tSss)Mb4EU+t*i}+0PmAcHq6IS(|p{tp>j9rv<@!8hoyLt(%2>an99f zD{`)+>NnE88hOgpK>fIUanvcGKFXylVf1+R-tGSW?G5Ixga3GoK*v>=yX0;*4uT(V zsGZlN5;(VcS5jlupjQ@%d4-56Wd(Y-ch6t$Rw#ve(5jHou$@q~zhZi^yTE*uh?EGt znYMUbMp!MBWDr%D7`slA(`q+osv-ty(K)f1_N z_W9fA;IBowdSfQp6C+n6HZ69Z+uFUmbLH+HdEes5WXl-t4O(vuQ|k{N-Fcc&I#)b% z6yit&@97*#sF%LhlTx25OT(B)P!9sJ^*69~bv1NYFQnO}g^}ZbNYU6A%~q*VR;(@> z%S{*~-m|Q;HHL`9zdDNykx5bdFe0s)XLfBvl{F?6UwOz)tUgltWy0(_@OtOEW%=UP zYw5b>`piRS@s=wV>&%-}c1ht5g4EDb_JbdDxbpM{-_?4t+j%`=A^JY^QJc5q$;U^i zuV3K#z+$_66$sPb@Mew~kNa(ez30BWUOv7E?NO2;l*w0e3lSZoSu74W zgF_zWqt6`w-YY1IpVMGzPJ2d))T{X#f)5@a{g{xhS7Fy^f-GizxV^ozH!I^gOGnrf zmW#9oc}=K#61y{U*TUPU*E3%b@$%Jo#ZNVYT(OOdNt4-UM1x`DhYK9qf#*7?i0erV~^JfdciZOUj)AJUF=~}&B9*?rSEI2enqSx_G%{~^lG23 zhCC$z#0W447sn=fR*k;8JM|N2EJ{t-ufX;7sG=#i-e9dnXamSBR_a78zd~An#tc7b zn>?VLlHCiSq-kL2ofZypAw5xB7nhUf)|}+KjR<;4)8J0-YgxR05byE)JBk`aNANYd zCcyArM$!3!$`kh9=bIiG^E95AEcHKF#%%26x23vFXQ<1gm&Uy6gm@wvOhCwK@fmu1 zbdoB$)PsP;qLd_!4tRG^!D2)0dJFm%^itETap+a)cuK~KgM3@ zx+MWozUyMMJyW_&IZ|GseW&@tUnN___L;@8!x9OCV2&R4(Kgyw2D8*^$+2AL+*WZ_ z@;kwBx<@2eT$({h{_f&$TBF{LkQ902o#S*IkF>k_79@V7CqWQ#JF{^Y3U~zTR>z); zbQ?(p7L*ZoJTUWp{iIwBe;0fHEP*dCAQpQ4#?sK9!m$fT!qyj~`QEL*w~y%AnQVGD zd=~Mr8Yy>CQ`{yK0it2Gk*Fk{26N6q_|-}F$M>y`Oht!!Lt|a0Z}@TZnes%-qWyhZ zMa!5ml+72w_VkROR~NwEAUx)v@%7gfs?oj#EIqTpcYPdk``FSEspSq#1d&<+xa(=~ z0AqWmt+y|=)I;HJHq`c><|Kz1Gof%x8_SD`DoY!;Q+_mM4#npacq-^NVT1{nTyMZk z4j0l(Mc%nNig7QTPjBReo2=bH5G%hEX1McoElDt7{fJZxg*IMKjL~)=($Ladzd3id zczr?-u>XwwMmG#>Q0H$JiuJUZ2S%q-V}xfyr@W5KB8$41q*mvUJgvS>(=iq{~e;4^N$hTSQ(U?;Z019I1q>jLL1izAML9@vEH4 zarMy%2VWGWuuyqlBqBr!zt3Y$nGmw@s*F7M_beu zRX7V^motUk#i~^y8$=-8{A=z7vH9WIw@olIHcGl{+mosC>P6$z+lJH&+v?`@0f&_e z2RRqc)tO}FYSh>PhtT)lcTNTz3uZH-5tkzo&7|tpnL=-|BGDPKdRyJr32Ua!moW07 zyZnUCb_CJ#`{g~!=STRCKi2;#e1`L{@EHLI!-rrUCPp?!ppdw*A{d%}h}Ka63hCRv z0h^haLICVc96(|4FG6}2M)rr`9TNut2qO97@7iQZ0xP{Eq`XI{$dZr$OsgN=v$f@3Rs(1f&q*`MF`kR1;EAuRC2Wi|0I22 z-`>m?Vq*_f`$H;L7HGWDpAkyTjDM*_P~QRkAlX0j@}MMF2WSK0*2Xpfribt-sIJ6? zm2AYsg{Advfqw=^0fkkeih%O=fc01V&_JZ0RTLc!AP?L@t3D7saLW7_zd%(@7ENY$ zc5NosU%%LY{o({La{yRbK>%jXpBXG{n(QD(04qBPz`?`Gn+PuO_P@ba25>^#f2hI%wHPZWGn9-8zy>uOh?4^VVrB!dv9bc#8JV@& zpj8+dwb_|8**I9W+1WIiAHG3bWn=_!vT$f~uxYYzZ~$0XIJG$$H91(ApsaFevaoS# zGqHnyG6iix8ya=>kk)2q1Zh4nqWzo7nf_2Y6!JkM+W)cz^B)B~Jiz}wS_}jN{T?o+ z6+391!-(mB!Q-E}{~qQBHW-rxE$NN=fE244v5!wIsWh^E52+1*L~Bv}(`UJ|=V!cI zUsKtxoesN1a?8DTP@T{UMp2e@3Q`YCIp$8j#b|}-?a{isOZ#UhEnG-JMfn z21RqdzpOeQJ0B~dj*s$DZrkvy@i$hvxY;}(Cgok&{88SlRu?3t6pynkP3>g|Y4 zJEnGCN&MxienD4o@FJq_+R{HPjVwR&seAgTrK_QItIFOliot^nJjw=(N6U>m@=iQw z#Oaaq$}<^Y=3>(QtXB#dLi_+H8mCRXJ`z~*LLW>eK|BqCry4?VNNo%4F(oqUPmlh*q)yFX2OB3D7&oL-l zHgj8DiABjHz-i&#N?}7@(g!?)q)NO?>kn^kPB%S5`-cIFndL7J5VCQEj!&#mPq24@ z0GJ=%>8t>h(*G;{vyaO-{epLu&^;fA)rGEBP;a7_z!~pK7#;Qe)eDB zPr;b~uE$@3{p9Hnk^g}w#@}@N6YC*n6x#X!#uF10BY=gK9l#8oF+gl=|C6Vm_-E2hY>oY{u4{T`SIUsJ_z$r z^Ff$@toi5I2-U(bpJf6{ni)C#ayIQ>^Mstf$=@6vD)1lT{}E8j!p6Y{jmZ5q&!|aD z{i-GnhUgpVL-hX|J$d+DZ1oK-pi{pAG@RF(m-O&cD=EOth?i8ARhm)SRtRir_QuT~ ztmr1AWawsL$Z15%&xgq4!sTLRYXwCExL8?QJ8-%1lIlN10dqmq57|Icz)up01uyB( z@L+(Nv>ZUl#vTj+F)%YQ(Hk;?SOBcd3@jX+Y#i)#0O-`h31nmgGBVRMv2Zanaz z0sb51UoHQ{5V8k9#7O@$2Gj2tzft}h#-GOiUr_$e$sdmKllI?mezss^uViCm$){*z zX=bEqV{hRAwHS2Kp(w}5zzCp%rkR=98L5AX^?QXsuy}wEYW_{_KW+M;v46|||6vYk z>HoJutgQZrO{Ar{gl!BRt)Sz(xGJk)qE=&&t7QL=VzuW1{Ee1hLVx z8E}HxnG6g#*_l{=iu3onf7cDPOxzkeWLq18|HL&iGBf~#KnCYoJ?$n#%%ik!u_r8|Fxcs4F9DhTSt4#pPj?V5D5Mipzi?nT&BNk$;gn)_+fbs z;nRnP@tYayL!g}lXlrE51N^J#H|e37kcTPqPecCdHb2cNU9-$s7d z#(zxzS6%;6MZXjLS6#nr<3FbVtFHg3qTdPrtFGU*@gLLwRo8!1(eDKRFLfdQwWWk! z0mVz|4BasP!#U4y+hYMoh^dV|)xVZpzpc5n{0a*W)#|Axj`dc15RC4GU z&YyV@dwuAcx;+Xa^wdDn%niED28s)7@-Pas2ne$aiZC%U2?#KOgg8V+IfX>oSUI3y zMA(Ie`FNOFIoX+61Q>=z&Ge*ZYx?|h6?R0G0w%M_5cWmoV@3YT;_StLQyYKfrQ)7;* zff{dBef7>sDkmgD%SgupN4m2+ISU8FLdZa9t!D0jdpH2Vqj?n7AWsD3QfWOEXIhg(;V`2JhTL3G=zw0pp{%V7nnT7e^ z^;j60|I!}|2P50R>jBsp*#BL|3Sjz6e{9Tv&!qmj{wFqeM!;XB*N8xs>V^S|eciHVJwQnYNZ2_!*@r9Z7 zZ`!i`H8y58j=#jq%+B(cIG8#98XGeQ$6v;X;ZI5a|G9Ut(>1j)w1b2BEN;cmx+Y`> z&?{J5I}m>QOQ=9EZe?Um_&I!k-U_L63o^3`vNEv$Ni8!!0}DGlqagdI%YrNnBCMBR{d89xDO zXl3kRLde1L2}uqBy&@qqJ1?)jgPozSB^->&hMtZNqJfUi`v?%&&-X9IK1d;|nC#dw z17JDHzWlMi(aV8nz2SWl++UvIU(yC#j4;7$n3J{Bdb$YDfk0pILm+G+f+$1@$KmRO zu*5)Zqmbt=*?@o{fQU2TkKtfG;r&lj{{;G<4E}T4kT!JCHPCg?CH$=L&s54fI#_&8 zB=&@Vkn#ChPS@B_`cD|j_J;rc-9Lo(gr7tIsi5R)V@NOf*@1<%@&C*upTqdy1_Z6G z91N`-?A1TvN2oyfSsb6wjGuV_^YV{A2pRujn~?DzCJ7n;A3j*sPSVlmS#CfVM(fuK<-{kA}x^?+L!cps;bIj zG;`Q#Hdg8stGuYFh&--smd*wKccV8wpHol9`uSPWOECT9q4vY*Y~SqutILN6hqq(W z&H0&MmOrTTbEiL|M>fzzh8GuMbn-Cx8Ql2nB}Kg;&yU&e(J^P^#)UF-KS7Gq6l1I{H70; z$R2=lQQF0XSJ5pP7*=zW)-tvAEp`$hWM$1>64l4KubUyVSnD@_@m(qz#GQm zN!&lFpeo+|y|NPA80`2!4p7%z-mr%>mZ(bFQ^3sbQ4X|#4gmSF+=CLX#h4S11h-pn z3or835t_;^dyy1dFZ!_p-ZF55P(RMWWhtP$T(O)PWO)$+Crif_68@o7L?(`;%xyRo zi^orizvc@+`AZ`_Qe9)au)!o}LIcVj-7D*tWhvT1qH-t}7by}(gj2^VKNXS{D768T zz%P?x!=7Ufsktj^N6Z>`2(HQ=Z5PJ~7|H{!FZY~s7Uy{;n#{PVSB2lXXeyZx~JlsMJZsGD+6%&3uYO{N>zkCt>4)Jc@7nD8r3XW= z`+}zc^qwzgA4NJhLmZT~D2-mFeprBN-dtQ?)>C#(!&G z83o5EN6q^C%Pr3x$xpYhTDR?vYsvbwXHZS=DY1s{5|GE}qfs#m$2ujI4q%otLGw^U)5YHgQIW|!77I~q=5DTpi%FBAmq`%I;t z5HD8o92>xP>1s>9Y+PD5S+#sjM!LGqAunj-r)iK@?!&sfA6zUtdJ$c2D&B*(nwa>R%-;7$3&k6DHHgzj10m1b-p*E$INe=kc;y_+%-tOV=z8DfLmB zc@Zr`1X|4gC^bx`ZKav3FsFBPp`Ifs=W9oQaJur);F4^Q4#Np!q&x#AC%QQA;*_U=2&i7nV(C9UB_<$MDUB~V!SMq2dco# zbEK;H@j3o1)J94xdigpGrL4&~IL7UCGOE2nq1{ zcQFPLo$`BDBFxP>?#d3anNV!EQcDT1N#0Bpg61ue*YAU?J!LaLjNvlvJu9i*c0XVX z@04-hVHkkU`nR|K20H)PM*L^&Ffsq@x|gmZ89T@DW&IGf(?>J*gBSS3cOR9ySa-I= z2X66D+zGiT?i|F-Z04DFxRxj|B682Kh1S4=f-dDnuLa&MQ6xG`nVa!}bTJjy`bx$k53c2O9X+ z1q^SbL(GG>Yq@pHsJ>ln7R80$je8O!+P3qex^D5hd5Tl0#fze@Z>v`p=#B=G%9=$jecLx6OmYkI6D_uidXP)IKW+H)t0N_J9@>hMq99gt!#vbri3wjM@putr z0NTl^iaD z^Kn81CqUN*2Q>p{%lo#qFnRy>65+p+m)Pq%c2D!|j5i1vPU9Hx$TD3A^YlA%dtU^p zbL9*BYWHx-h8NVi>x%1-r=0FyP5$pTjkE7wGCVKpUcwPHeG6lAvna}03$}44Ph4); zZfX2h%-JUX&ff;#%AA2U$}4>YO*fl;1mkKdza?eCTfEPL)vL=iW6+RG=q0MpY{B1~ zt0o|dCb2amwrWZH!+2tmp$y9Z^Elln^#Or_lQ(W{58D^18lp&m_Iaz1az)I?H zf(Gd$G*M-tDM?dZ;GL4?Je4xtN45s@rpfnV=Yk(OSVWxBs8H(sYPc3Y2cKa`>fRX?}kkl z?b)=acg2*>mmZsg7g_rgM!Tl=xbByRoAaNp2QL>9ibdUhTK;mTa~K9g*{aJiSg&9| zpYddvWX`mGfPuiC*IEA#41aE${xcYu{udZLKEbe02=%#2w0tW<1spRL9zfNNYmdFL z`CkIfY69lNy%2svLOp4pb*?-quOv(!KI*9iIO?8ZkDZ5ihgFl6Yc*BB;Jo0HAl;E% z9#WL+KEP7{*rRfqFQ1x>I#FIPvf*`Vx;*kv9!L=52AiD`GO9O(Zc`GJUqxKVg`M;L zULM7n05{FrWjjtg81F&*E<~>ED&fQ>*kpr@x!&tpg88!mWvYCNJ_;av7n-(kbBd-O z%%0|6Zeb^L`pj`XPNn0tM85gd&a=2o<$@@xXtbJd8rq6`_HDKaU z%m#;MH2*YrH=~DbSmW{AWu7Xrbf4gvf$oi^SxZG)DujORtKEKY47>h}+j|+x`jqH+ zzX(B<6ea~0oDuV2P~QS($!jmK#b}l85{pP5l<6yudD#l&TIz(F4FNEYaEx3!%P%e5&>7PO zBo6i47FOmzw3g6k_$c*e=W96IM9ZsR4q;T43{LQb4_4^ak5A{#q7UvR7UF(S*}w97 z;dxJbkiCx@>#y70E3udHW$9x*2^_4ND#w#bB{q^1vZC~n5MXwjE|fPFK6XM;VhM!B zcE)k-1fS{;du+whm~CDzU1}t=YQ(5tuf@^DXWs!Gol?Vk0Wz0M_ke#|k5FlK>wlwB ze2TZhCD|sxZR1@Jvm!z@o2+aUpLIf(6XYnt2~`3h5nmwVyYi`xvoKD5m$q_O{utM8 zr3Y=UTynA$=^5X|b>T?68UnkkUSXCdC_73D%5w7VUzN94TCZw`dubDLI0PSXiLfUK z^E_W+)gCv7X&&mga)QY>grdW##Bt)MqjvaAJqDj?Y4Rz*8jbd96BYVV$0G^BG7+Cr z=c9*DhWdl!*`znf7og3w)!e^>#h>Gr{|pNjz`w2$7RutWxQtNk57ft?$~oZTzp>!? zdKQoTKfDu}ZjV%pI3_S^#!n-DzL_E6I`A%-m45Es zv^vP?moJ0X%sB7R+ra|Sl{Qr6kg2o_$L zvja@+pv_E-%W+UOXm#R;1*xsPl%IMoFPT@wybpPGF08m7;8L@y4OH7Z;EFC3iM@ql zH>(bUagJ11rX8hz701ObK)uFcLaJ}Rz;kPn*n z^6vHK_SR9$Lgq?$EPSnqkNhzy(GdV-TCvAkZ%CxwmG~Yri6?~Sq@AP_dmK-)c-B%! zaahA~cT&m8$x%_dNw>TYeep9_W6O0o>)hq{dv`EFIB^O~*z2*U`W2a86>Z>Fehc}9 z?F!(Q8Z#ATvs0}dcH2ziRf{pHfFQ_OpfR@sQt|>5T_PK>>#ovAtvfGbGJcksAJ7c& zGp>8Y&NIzJ-$b9XV+*${2lTuD4%W?^cL&u%BVkDS35q2mFfJMDyjf3KxeAG6V9k}M z*1xvIuAsD^Q8&Qat;3&FG;78^M~|Y(69?@@qEhZJ7Z8T+>z#&DglGJ2mGcuX#Y) z(Q59vhk20jJA7a1S7u?)K84I!S$185`Z9-BOLZRbWLB=oNW6go&mfWhRo!C?NF2Vf z5k+{#Jk`Y^yT<;V*`wdGOTD(J`c5%34H|UJ!abIOJ=QUI9TeD6Zin8 zAaoP}gHmKpSY_}FsxsUL`e7-Um(TB0%qJ1i6NZFzoHuwOh}uoKk6eorlgb_#b?(x# zVBJ9axncrL?&&oYvQ@EHw&bGkJ9X;)#)l@DY+-NiBI}*9C@#uwZzwuIx$G-Ye+QTU z`!Vl7&)C>l|JN$wpdubi{PoK};8F=xQ}RCd{^6KE2Xa5AftvzuB2Kbx7kx5+xL&oH z1;To6jW3`GkGV9*r5|F;J#DBd*Qm>CRmc<-A)tD7lr_!nV>H+oShNdwRyOxq!4NP10;u1JXO}Q&;Om zw@7j{qH4!tIXg?=jN^GFYoDte3_LSc)*M;K1U7%Q$lXF;4ceX*TlGpr;35IbR)Ovo z{bZhWTou`B_H0)QFd>9oD907)V3mp$x`auZXJ}doK!JBvF^8 za{mT;BQs%m+JxHY8V~4u>0r0wIso;h9#`0WL?$XJdpykPvkB^R3%WHc4>gz@i?%ON zzH5J&Rwr^k@TQg2A~-S9`tC!O@uF2=C?-`ra6reo9J4RL9|&1FpB`FyQqe;-&cwf+ zyHP#{lyOCI*Nta93|q3EW!gR|ESnViZG%uTRP)fjKp{FgX9!0~J#44VLa%Kn#}$R( z{F=+dn?v1B$xZyMIH4raP~JVb1jiTDhRUGZNjgE~9&oC^j!_N%+VzBJIMVsNRoBbQ z&6APqw0Y4%9**8egHs%r)C5;=f`k(>tp-aR$GgNB-*3xf5n+J@!4+gnU`*|w<5@h| zO+xUE;;~f}LYaU;O=g-#LI3WGifK(>){tNb;WCU2=1V`MoA>WJeT^x$S`HDjLnRr2 zi-NzSYT%i!;<@0W{KTP6JZ{%(4=1KKqoVnKwnnj#qB)+v{<&zF-P)9mC#v&eq>pIk zDK9VtLrWIEH;@V6Sk|p)!iL%K+706vm>%Cn?aybZ?0x{;?Pc44r;Q3amcHuoH*tka6P~;oA6c=vd9R z1$VF0WOx7Y;E2j$8$nmp_$CZivyPZGam{U_Oy~7S7(c79!-;a&^V?*{j z;w9vMfobcGVB*(pH*6)$7mDm4wr|;9g@F(_Fk)p5F<`os&GoE7sY)f3m&alYPlZEe z#Mohr>pzGWLF=j;pufz=T#6voTUnI_ff)wP{l=9PEaNiwThtW1fsuCMm%o95b2$qJ z*zqvq$Ngd`o;zjpA(+P0QlJ&V0R4Pv_D{|F2% zGCW!B6ff%z%VTxrBhS zm<)ta2gsd@)LMSU{$(61Z`ulSeJnPycn-L8le2jn!b-t+=_y!6f|;2MMGIi@tRk(z zIZP2b6|VIJ2G>RTX)P&_c#ud@`ZX&ZINA%7coLMlxpth?8&6Q#xco=QNq}F7X)p zw6E|2P^Xj;?Ai%<9BksyMQKJW^NEETjS=M=%8KjxP6;n!X2vybxi={-$+b&r!W?|x z69rE_+VneoU^|F5k%?cZmDOc-a5-y;f>Y@X`SK_0;8%FBLvytGu5UEF4PB&3g<28rFCWvsN?z5*zHT@18>*!&i6)oQi!DtS6ukAyW}l&X^y-{Q3m zR6F!7^Sy2ICwrrogU%+}Qw1PL#@3O4&lb*$ke^h2A@merx7!Ht(DK&y*1Gt!7t4O0 zb^1GW{0m_wYiD3+_sIxR{5K;+Nv~jNZ2C#uxKi+c^7Mw3p9GPOjfJ7*A6kpye@LJ| zr1yW`(Eaawelws?$O8ES`Tm_#|4*#aC;!gI{7-(9k?@o5X8KAU7k99jUByS?wPm$?7%N;{mR)s{!YSHs-| zb3*rBPjjc8s@AD4?Oa7FaZ#m)@8yCi&_9Qk>wj-WlGJG z*(RCR%RJ`WBsPfrlST=tDD=0SY7?-($WeRC%~qh7I{Q=?Vp2xYZxp=8@dDU(6*dvm zp`TWpr5JfY;Yh0M_if$<^Omb;O-viDIT^v~uj8$io>2xT>L;zg`LDM;%P%k^jPW|1 z*X~xwP7f{|+`!dsk?6lB!S5!S3@9XehjEq~B93=xL4*ZwB#KVQoFgKOCw(`ZZdw9eO3)HK}=MY?@-ws;60 zf@2*<{o+SDxWNpfNW4F{QZ}&hCB|)-=fcHSw~Y&8H<`n&xA}O(h9HPJSq>C`c{e&> z@EMbCgCp~<#Kq6}`?heDA#9a5&{=)#26EnjgJJEAC0?CdIq$txFVtQxBCOo-RekjX zjug2~tdd*A!IVd7j-W$4FWOgmaxKIx>eYn2x1@6B1w%w`^16V||z%$48yAsASC1tus({geYasMI&{mS&~I+Y|8S`3;-TGsnIYENHWG z-ADrAZ68wSC$7JmWN|qJy-SHm{}Ed?9qJN<{AUaZpmLZ7?X^yDhncB zDWhC?-omD{3Yi_E=w{GbNs+Ncqb|chrn_A-Q6LAtPSf$C77YLf(efgc{UknDVa5c> z5i~TjuvR%w70m*zDLVEqhaM$CeRKj;B3bOVJ3Ju3WQ7xI^NFvl`nsk6c4jqS-$rh%@kWXhw3d(mw*zKgiT1 zaY_=R72&CZ6HrFjMl7Qwm5qz{rC{eE96PAy`OKz*%&}5ssTVWnSj`F>MNjN7qX@XX zc7B{Jox5Zmway-Tth)Y6IA+qA)iA82Ta=En=5ikQ-woRuncmgNU^>l3uuXI`1>+e3 zT-$ZM$KmI$uf@gIEd)GFkH0+_nqX`|sR>lgV&alV zmU$+4o4`J@6-jDrKXGUrx$*vl3>d_EM=-Ww9M~num!m#(!3weqGW4 zF*|xrP@e6LUzXmT?uk$K!l&q=lf325W6#+5$V)KE*fVH@KYRpa%=#LOUsEgmxG(rMeKT&EdqBWbaHPQi9 z%-8{^V*?(N){UfW*5b@2k0~BY+fpew3r36-xBfwFB)$$VE4`zU3&2(8fBzlKK#CtS zhv*V1tl~gSzHSnu-dU0k$^!E=voQI6&TSoC+TNdTlLq!nquZ%5!>@27c8UTSotVZ6czePv>^^IA0ZB(J{V}HFv4XF33u217?ZdOIwM#EQ??}Vm zT2+x4xb2Kmk-of$2rK9$vNd41-sM8lE~_Fr&wMK+Mj+iV+(Ch020U2G(;ZvcM?7nl z4vQF|+J=jDNEnj<3x?flyvWDF)=?#`yMToUsn{{hh_)N_i(cSMJI8>Tg z4^=`B)nDIRxyAcBhcuXV4tIAKiAxi$CJ+n)#uMu!VwSP@W>Bx?S;hqf=~)Dgn)}Qu zSsa>lMI5RI5ns;zcD|k~ z4#=p=HS5#XoTQ!8Xo)`=_})B!&KiA`DBOX+Dx2RniB%*%gBXh1l>bU$5sOI_3ad?$ zu-#%Y7E}#7e=5rlE)y@p(%`SKx@Ci(rv!zl$zDnk;%I`$^4b(e6sDhEI*uHsQH3Wn zo_^AqqU}cQUD?LgHRnl9zDP6Q;ZW$DT;bA#l*I7jZSmdGLh%sIYto(1qpHjE?JZ>~>MTD9OpjcLR>Fz})7IoS z5vICiMi7lEY;r1`-^h2uZn0J}kT4xf(;SO$l(Y`xP>c}}0XhY_*s}}oCP%C#u=Qs9 z(yKEv7E8-5GJd(1-`ys89^R`rAGjy&Gwm?|+PXf=gk%k}@70g1v`=%ffts-Au|bI% zX6Na0fJQ}LOsK_v^BmTNIn=&8aYgP#slgp~PQ@8^+q8_xxI*Bf@UvRa5}l*z<8~gJ z!!f9FVErJHx5>=(*CSl3R#H)HJGhn>`_2~e%3uY@rSobI3i`miue^KkNdYEHrM4Tu zbrUX-Me1W7UyR_V?ShlPU}{iZ;MLoFk#7&vy>_EmF=v%%s4>HF@-971Nu}itQC^%V zs|cO7VaN_1wAA-^=eu~h!f=P=TYq26Gyd+Bo(ZVhm2w|Si=O7&c2V?x725XL4)0A0 zJT>R@7r9(dTUuXz86kLwI@fF?Lrf>ce=8zOm) zVJo2~NQS_Z8HcPu#E*@A?dX!l1^HT-O$nvm{qbtNw(kwFQ-%^jQK>;K!z5ialq@w6 zUdA?(#!@GeTo6jJs3*hyrL$aALq-Q?oiMW~sfD0Lp-Tnc&^3f;f-vAcU$*+ zbUtWo0k*25FJ>_)usS=jL5X31+BDlF8P+d_yAWD^=?OQVkw+4`T@J-un1>XCD#gV3 zVu^iZ;dBY&eXHo6{*nmY{$G32f*cq!{zF?5aUrEdaEk1=JK!a#MwCzs`um>d-_M+hPqXh8vvD1ccQcykjk)gp6J+FQk@dbg(^%6N?e8m}?5*o-j6sDDI=GxSEk?~PMl**}*1sk4|bHF zG?Pvl)3BR>Qe#9;%Uqm1sbtKWY+Qx>++Ng^Yy-I1AFsv zdSSeYm24Fz>mDBA;T#hmo;D}C-vXS*42lzhLZ0VC}dM9)UC@P)a2`SruX&8;SyZD3bA z%y@H?akk}f2iFcMp@_)rx>VyMAIdC9f!}~b2C=w%djFeTn9vs32<@RVdgga%s@`JN zpLX4Kmbt%n+52EYSQjL>$l_O~iPVFCag~Z7sZArD1q?l4n-#DIj6XVBwKHV4sRxu* z0;9$CDe=qNiV3%Y5CuDnGRoTywzl%_0&pz|Nd;oAK7Y5YKQ~h+$~$_|;+`HQ=K5Hq zm&>4XX_ExYcCAeXL%>f!F%*X-zpHzllWu~x7AtO())zap1xN+bZo(o#w1tipYX2mc zKIwuK9mCUpk`~qI>CTC6;G_b0)kEzfOS%UKthk>9r>WwdSE%QknGDO}r;5$ROa1=L zl+-;G!4#~4)>AQn{s0MqV>t#n^z3$F!waMIxeYkpjxHR5+^)2ms{^ZCyXs0Sih0*I z@oy;S5b|<+_`(%^d)aw0bEjE51<`7>7E{)&(xIHcq>O*s*nojpYpShgs&zT)e*Lih z+F`vM{*nmS>G1qoBS`I3t{!no?`f|*RCD~R)PK|Sg}Sm-?&nf%v$^NH&ih*sk0fWN zv!q1ygw)!B<3N-(`QpX!NJ2R>%a<#?uLl{7suhx+nY zO#H$hywL`Sa~{8NcTNS!uHP=8Z5Cc`cHQtgP9p>D2@^smuqtpE% z0~ZN29}J@JY`g9f?smG+tyh3AF~oX28R}sj?V%j&kd9`=0vz(ksm^B{kPDHfaG;}E zK(tyy=&6liG{*B;Ie%jHUHOTPvVWb}9#It&cY}-OCzVGgG3X<>RUEE(P9^NOVQk(I zdR1tqyl5C1ojxm!aG{AXV*3{8qDrNrd?c90#ev0!(BtsS!t-Mk>4fK`6fg%n>)rVf zY449y(UcTQT!;Q6%{q2eWplzfE&&m*1I&4nZU`44+s2BsNG-E69=wnWJ4s0OTb$&c z2>%o&OaPmihLS@9Qe|jWZh+3HhWaTB zxRH=8>;4cw_l+%R;HQlFLE@TNku9yDksY-<&> z`Bi5{dvofC1?i=cj8z7N>8?ZgnP7WJZ5yYll)4UAoS81PBYJ*o-mW3OJ@4T3d)T~F z%?y0#^dM)-RUCHsAuRXl4uX5;M*dA;E(&w#^2~bQTGD5jg&oliR_vfHGlT=j zY?!lwF$Qj2Jg#!-lgx5@l*45cON;S-PUgNw%c#IQONeJ&;smyX93uI;Au`;&k$$51 z0Q6c%d7TrYoo5k@CdyqWQ!o#Z)|S%8a(3aL+1y6Y5{kvqEqo`{ye{|73tUxqed*iL zx-vD&{HrAmBgb`#o?f>g-1kQe1_6Ap4ri@eC)d^wYDxE?9Cgbp))jtJFNiz{qaur| zDO@3rkNJIbskht{)z&`c64-8Bw-u4Ncr5|kNK`OH7zUw0%3#WIX&8F?W52^hAuB)s zWmFdB(s3@7pL0&N@B^~Oq7!cLD*3YCe;a3=nop&6+9B%|tw+*m0K78PW;CM^~l4o#G*K54FN*6~2#nq<%-P zZm5@DgRt3k1FN#GYE>r3}!QIk8XE3~zf?^$8; zrCU901Wdj+xtXzkh8wOBF-3+bJ&_QB^fwCGwrvqES;KQPkll0@F^93Oo^`&$6Wc-i z`Edt8t8F46BYyQ>_pKG>WSZOK1Qgr{AEZZhrMiB5p$u(cD)qVuRqRO`f~@-V396z9 zme~7vE%rrL^?dYj;O9w0@3i?%K<>%+fSD75SdRkKvUIn(pIViB!;8LDj!{Xa!=7waz;h` zq!~rUQ7vdR(aW%vXi)rN^i8+8obZTpHkO}p2Fz>OgecJGyA_63VBj~DD_f0RC2NqX zQnsD|#y#;6q_*XqFaRm{La=fC3SMcv;r7?Z4#z6THSF4h%s>Lo6+_Qv92Jmdgo8@W zg{%SU1?LL=$HSIOvat>*>Iti(hIgl_RwK(z*qTmIxh3?{giM5!B=H^A$fX9J?hf{0~{}YGX+3?OGzmVeKH( zK2{W&=Q$l5AqqO+WfS7Bj4KfOfsO6CYxjoR?Tm3dg}Tp?)%t_y5OoA2Ry1CEht{kt zs#)|G$Iln{(y$o39m=@S3GH_Ri(=fd>LfCC8s(+CJyJtb+}f+-(ld(5eE!LMZqF}h z?=wOrs%LFkA;`P7*n!G5aGjQeMSE&espFxOLO#3Dso!+{LI>9)20XoTgmn55g&0hU zkSKHfrxM{4>cb`S*9TrZU8JB~;QVTDNgzyJx>>?O*u&6@cx-rM?hHo4YTFxcqnr$e zp#9NgwpVort?m`imN=R$NLTLHH5G~5GQO=SF2!$=4C6_l$CnI?DFH2af^GSlG(RSTMFO9}#T0jsQ$@E|`1v2KN{f&+B{c5#B?cIv4@+ z%~O~KQDg0oIHQlJVdn)p1S+O3mpn)N6i_Loi3}qwv**hG9JHil_}9)Xl|j?bf9&;QJLs!8rwM>db@1cq?GE zTfO%5xxZ&IF|0`*8QAsV6GuU-+1+@;8z*VVd+R+%E)dX zYFI?&;g|h|qE%+4l&MIntgJbIjJ&AVQI${sb`03UbXccGx1>_c@ z1w18{fH+J(6-#{piA=aOEF;WzsfLYso+G2leSougn2 zFfjNTHYSP-`roQ04Y`A``MO=;@+BI;C1Q|^dfm;a^t*cldAsICI2gx*JXoPD>gAFK zy{Pxt=%i-!d-ile6D5|ZHBur}Fjce-qsO}yB{gH=VPYmZ@aTpUwqyKWt1srq2?jRG zsWR4=0j6Hp-|6RGtp-|2kCsQV!$<6Re{a|xik+ZYxIa&v9+2zFc2rkbii|(+yJx94 zoV5V#kI{vY4d0WRyw$rty0~&gT(@Ko1Vm4!6zyV;zu6%Lpuwjn6%Ip88Q4W?_Gk*q zzvbvJg)(_^Ft9M}xQj?T7#a?0B$!sJju8h+ELySF+8=gkvF4f?EMBtJqh;<3rx|D$ zXmzVl=R-1ds_^gipt!zWve<%e4wRo7sJP^H%11l0mEGn=rxlI!vy#`~yJP;?08t#Y z)ol{JW=QYpDPlC}VbLoYC=3o4t@>)6Q7L~Nz}BtJkq?w7pe3&bQ3_pwFa>g{d0|r+ z2w9d_0bO)C(SFi(Do6IXbPlQhfX~052EDtyjDAu)h&zmA}~la<79!2uMry%IpPyLW96lT`jET`O~4MP8juk2$#%!4JBN+pRZed!lu1 z!SaWrNvUmlM{JjC>h3kwhr<}kUf$3XZs3@sFfHfB+?0gw>{%A*;dcV?y4wZ;=1m?D(uN(#=*iRFT@Fh z<)yZ2@^Vb>+?KI_HCzH~mFwEmasZMs<~oIm+gPizYCB`H+{}uT0zD;|UZ|M#_)}JX z`G6}N3HCp6Px$29NhWJ8qkkNXpNuf#woN}b4M-4qlC9e{nw|wd^EX~(ejt>cT>8DM zyLc(0D6-vlHFS)d(-)*oT5#tSKh6R1dIxC5$RVx`)$LBZjJT8}#W@H~x^zGOeo$3T<+Yj8mC<$B-f93u4Yc7T|O^* zgKt%XlnFtdo4OnSLltCk@M~lpQwRFkaKkc(BG74Y1_}zr5UN!6TDJ6|Pk2vOw`%89 zGj=ptz@P}tRm6f7+P*9Q)_(h!_WNNe{?4e`X|d5=cV6wHHRbo~70BeFN`Klh|KZz% zZBjmM;+OB<*RSsl^C&iF5ry{@GM?^N7#N+;%kz^L+?}`=W+s~L$4Bcn3t;Kj(C}YT zkf$nTRV!hWMt8vjR53YZ7}Unv2|?5|Njd^_#UZn}DQ{uEP&;7eF1)FtLKqDgBCt~AW9)0_zvdWvmX_{ ziv*A0Qi?24>i?vaQDp6j)#Zh^;gNNf8g%Kv8L>y;9!SZE@$5L31 zPK-~5q;@NAzie}DnpuB;k$-!5@Zr1=SVYT{yw;GJgf6>Dy&DfQ(yjBV)2-9_71!eD zlSxTK1+%wQQn7^B^aExm9p1K4FYkBtvVEjiEDDepZNBgT%GPpYen)ty!yXB!%@K_R zy68|B6H^ap6QszT2=?6%vjdRn6s!4k%x%$JpYdJhl#Z{_%UR#Z@+S9W5aW+hPK!AQ z1EFzXrfrf@=c;#?da-rhPOHsS7I^1Xwd5;f6Z4OGD7a0E%v$GaJooN98h^KA%)&a6 zTpwtteIAY7P0ZZQQzML9r`6^>KM97f6nnIj5l#MRc)g>Q=HU?(O&%byR%yUZtA&o;ZcT~v|8Qulyt9bj^8dda$558R`4 z+l*mFNqr8z3dUpacqta5X&L!2PlaFjMgj-b;Ws4JpfbK5nCD=yYb~k?>u}XB&{^Fo zC|Og0mWRez%a?VWq`aacYL zSYe*Gk5IN2YE6$_-httwJ;$a>(cSEgmiXRSE!Ib-L4mF_{}AY?^qe4jqJrR9%lE{$IuC-n?-)4g`5yhI3+!vy z^BY3xQXYSMy|kRw7R&)R7eemxrvg~$4s0N*XmO|r^n6KNh&9dt`hFV!( zNrsAfxguUse|_Pwf!a(Vx|93)B%Ru7p!MX(hx@zzC)w0?n7PZf>Ef!nZoOFfGOo7g zk=PY|ujet?!?qzTdYAWAQzXf8xY=MhH1iAfRa)f)N+Gz z2zgz37KwGTW{F-r7l^*WrQ<0-5^v;8b8(@h`Hm}+PGTm$D;);iq*c**#o$F9?H0ck z#iL{EVj&4klwGGF+n%9cWFgSumPACp0Hmhbd6s(2o&`O?J(|f+9dF(5l9)0{$HX8< zT=I^%s|=O2_Hp^w`vA*Ao_Go9nT#pv7zQB9h5uWx49+tKt!c0kL5tTa?Ml3wLcBA0s9_7JpbGIGIqE z6n`cr1JS6#CYGTDrNJ54Ehu(~Fb%J5U~?S5wYC!HRI7MRoN@ z^+8ri@Bgp8GmnP4`yY6lM3#g$+oY0h%xX4ULY9#1Sz?UAFpOnnD>1$+x|UZh6KKK_)=E8>6n_1v znv!!_BT`ta#qw@tZg`%WMw|-EscpNaq@&+Af-4?YEu3t0ihq+~diP2*UsnAN^A9ue zOi2$Pb|RVgaz@-uvDzBD?P^Crh{ERC{mf2Vu5R==Uza#9P3s#RR9bwv_1-AoO@3K| zK7{7};m(8CEc0Pco*Y1YeUZ&SNI|Qe3A659)P~=PDpB7X_mg0udvi2)R84Z4L)NN^ zb#a7v%`Y3)7Z#vC{XE0CxXPyz+VqZMb>#W&95S|fSMTMac&p(o^*E6jr=KI_7`<~H zu*0_b#@-xX1ex=kR8$KEo3tEcta%DG3f^sVR!P7!Ii=meH0+s$-Er77_2M?xL1ahA zHZB9r3Ta!|!)>PnG2g@^RC$zQuURy;ii;$P__E)Id6vnFHJI5qa1M{Vq`rT({Zr9n zuZ0Rel~DGH0W|VznZ+on)vD) zPc2rb;~gy-Et|dKtgS?bvcC8HrByhxePj1X;z+o{Do$^t?;Nuc;irL!>(t_^0yn+E@GLo zj|i(AdT;Em%ThjVFNM<(x~odsK(yN>piXuD6V4Nepl zWR%JpRpsiB9a2{GL!)-~9hI#gZDdOWCGB^XB@fyms_QB>GH=vR1gT1~556CYm2?gq zP^IL=b?lzf5#SWd|5^4KBBZaXVq%X)9g5Z07cpWwDJ&gDsO2S<9Z|Gc}7IZN*O8cO%L)>GMcLk`md(yp5tE-6s6*<_R7Y>ZMo?07+cZ2RYd z0;t|yr98Gk?Qsrdi*H}zeB(3mq<|j3g7hBcuu5c`^5&o zzVIhDZ0Z;aBXJ|ia8l_o7dc9ywkE#`CvZfHm6{8~F z@J~&nq%WH z(veIu5KVhO*T&z>)B3pWroUU>ypjC8f~Zhad77U*F|u@llPg=;g$q)vF~YKJbQ) zYlV8Efk&&@ro`%$eE)hs$GQLT`J)s+AxATmcu>u@`+;EI@bfDDLFHU7{4RR4mYWfM z-vC;}j9=lI{8!N3wRVI{_(QY2_bcS`uM{e7x44FN#+vEiWH)M%4q10T4)yn}K3UCO z%{2?JN-4Gfc-~S_;HraP>BMnb5#Rp72K>(P`>eUU#&%v~nJQBpN$&ZwsWAU*Y2aHH zjcPYu1@DWp%6tdD&WQUm9U4)(lQNg{!B2L(hRddDf|R6=57#G|+UQ!#;0WqLvVm+N zc2D>maGvJK&3mo#20lc!A3|H^^?n)-CnW0U>hrU|uq0oM*j-5)+w9CyT^+@7$v@s%5=WDj)l&`hndiyPt> zD}CFTRoxB7+$BnEMg5rv zGqf(nZoKov#E}^`^qB?{%_&LBIoSy(#&YrAYq@Tc&Q|y#J*5TyB&z1=sq@n#QbEXF z_5$;lZemAo`qYo!@)<3jzE#3Cy8xDxNJx{fZ%heS90UdG74J*vYMRw}-dYwC{kZ1J zSvkcC5b~OP1%rr>9L55_E(j;dHs4Y6Av#uZu;b` z#jUy$xwz5llnFVLag!HcP7TS9yWKKT$Y!3?4vxRzxdRz8wbQYm0vh5ve9N>?HblA$`G}3&e#SQvNKQU9f(S-dk-666N`C>pzk1JuN=oI>9l^Gr)P{?7mOj1ttq3_3U$Z_YY~dHT0V= zTzh!_eBzE;m-6(qFLp`AI~RnGDEO5z(ZXwKpBqn3yc#`v{zmN)xdFo1+uItitGv>M z6SDW(9(#MTOk3WltjJ#BW5((J$|vzNodUGhn=y3_ZpIXG3p8n8*qzBnvX@ZX_}j~K zA$3OZune;?g!ntPs;ZJVHEw}F`TshuZiEm^c2asP)eJuU`kh8^o8IT2+&}Wtw>#vP z8QC52-tFbX?J`q*E6{@$#M(b?`9boq>%H{!kG4CDc_PaHdMI>P^Q4|lhJwa`Jr{c{ zM}+C@R`&FrKkAc#RmziqQdk$4LWqYw`Wy$=4*Jsi6TwX;o3GFD*tOZ8yX9^iS}Eu@z4z6tJr7yMYTkNtY+jMswTJ=^e?`LtcJa=nAS#l5QdpM~k$ zZSRoAPu0|^ei)4l(>TYXJ$T@wolP3Iyc9NU@|^C^^A*iZj~ld(o{zlTfnMm+ot1dW z^hNB7yWmy@mRlLP*MbFCs-xPX#L(9p9`7413TAyJk-p>810BH=fxDQyvvgDP?j){?X!FSI;%jy!fnu>#%%0|mY_lOC+*!z)kv-Qf*N7@{1 z_x(5R=w`GHj}6VnY#(~@fPO@(-iMc?dXY5s#;m$a2m&{aMHNGABMQV}HckdFvdn+f zjxs;Xe6P-FK7cmA>)dEhW2m~y^k>2Dltm$~%Jav42E}=GVR7oont3fTmL*AN12x|s z-#hs@d~Q_C`6&7%%7n!{Xo0L-bfhPyl~?(PSeS5Hl6$1Q=1_=D{ug!g$#LqDs^RjO&t+Io4;+tdkJy1+(>v?BK`}}mE zbN128o{{p+Y8HtT&fdjMZ=X6k{utjiS!YTU^>~*oTbf>c3gU2|Vn=CtxyjM5z5YoM zuY{b6L@@vH&ER2y2j(wBrh;lZO9~G0c_-gN7Y_QCmbR7e&w1X{nabxbR4#ZgQHoXf z!qBr51>rb>4MsZtjmMuQ?sE3od8b8}W|B0KEi`q^uMtl=wm92pRxz>|b)9Mg@=j~~ z_zk633pV2;zueDF7-$mKk$P2$<{TEbys`h~g{)e(PNp)p>zz*?v|btAYN9CdeDhZg zsPBo2_D$BzbLKS7x`K`K4l3o|uW!H_+Dk^h_tbQcG*Ko7XU2KQ?-vE1b=u$^8B5_N zZ=IUf`)aRgAG&orEtclxZ0AYFO-nMTXpcm=i>?;tcJW=(eZY2 zuQyCz^zbj|l;32Sde^!rG(0f;yT1YI)v3vx{xn@@Y0S2o#oQU2i|)=@Idl7ZUiL~@ zw(MDmoVix@j3>JNh^c?xkr~`mMN(*fMO0iQR;8gS4dZrGPm&a+q<4__FB@H(GXn?p znd~AS#qL53x_c*7i`Dmkr`;O9+pXEIZkuVx8|gLt=%`Wb(3QM1!WQ$}EtRJ)HbaMm_xDq^hWXqWcPEtn-H%kksu(<34F z=Ep+J_aMmym7mX;nc6B3bPA$_>U@mVTMNBCFLUlGkh7VSl(Pt#`)=1Jt4Z>q+3&3? zv@?(nIABs>;S={N*=bfKnxmDP*5>n_tE(qdoW@xSo3gbvEE*1)HY*!GYEXLSozD}z z&jTMd>{D(2qJ+s~18;oa%0N@pus`uHpT+RVN83=9l{#WOK-;@xTB#$66UQ}?FI z&Zy{VbL3`L8G9x_Kj8Hu26|$~8ti31`HlJG)Si6#M<{Y31pi)=(@Q)$Kw2~a_b+=rNl`8i2wTI^nXtFDeicJS`YJU&h?RrSQ?Gwu=q(h=q z=_{^e=nQ+VgW1eurDl~g-R3pJ%_=bspRVLm{ZclRY~^Pv-k>e7y75}dg|phdsiiDt zhkk7Cc*f*B_$6JpSG=Vo^odG{Mv;W>skn+gn+OMC184pAa%|wJlmNE?rU6TJ=`#ax|3TpXS1z{gUS`$pt&Sl zh{T?U1qaaIL}eU%nXJO2vQn}RsIeM1`=`!asF>3cyMl9288i=(NYveQ1g~gmbBxt7 zs4pTSqWPiKwk?}L**rWdcXHJ5tv0Wpe2vfb7ps>h_$zr-Y-J+Guzv;ld8S{8$lHDd zz+N=Tlwp2%d}|F@Op(qW1Q>__j1;1zt_%C(&@PmkdpNn|h4W#A!biFhcs^ax;h z0!bP0M@ED;-jVowLLwb$s0Sc1sRTQSHpSHuPiAB=T2c=Qg+kN;%p{4R=wwT#(-`%r zL`Opq3bTY|r01qH7F|isREjIac-bmx1aKgG1#kAq4|)~BedD{JAMf8iP-%0_@A0NvJ?4}vj3m%mVsKvsGJI=T_QsxQRI6k!TSqs?LH zrGHr903ApgAkYG+M>ujRgaU}9OCc;H5dvk3MgpnONDu}Hrhh^fpO6!k6G%6T5Su~m;RFmR4V>BwL@~EV4B2A{)g)2_G2e8xN~=-M?ZXSFZ4X=b-?Vv@;qj?>_$H+`<#_w4nJBALmfLU_ z!eUSH^M{2BRG|l9VVU1Nqo3b@eDao3_72-2-@8ftdEpmX)sz~-{lwERoKCb&4>Hu* zY;gUcSG+6<#Bx1LJtozm`OsiIwfLf>G9>==!BRW#>yycYDo%;Gh!=@ltu*4r#8@0b zHa4+w6;FE;ouL>}el`wPW`F?aN3r^B7pAZqB;-Kl&c7SP!?ht%B*gRJ*5bem39md3|RBQjmmZ_K#%^z?N(2o|0^ zJF4R`CV&5g*_(&xqR_p^rc2uK8z z93#29QRzK|-Yqrpt6>Hkbp=$rrsJ=HHzQoG>@o^h zpF|}SMfL26L@G>djp#K8+m%h1gd8JL%^`XaRf;}kO~N&2d=-IC!_ZwDK+FPUZAN&d zxFxHWiZcYx{o+9Y`_-E0Ms%{HtSfoVd0)V&r6G2`kR_n;(onP{P}vpl0URy{8Ip(| zFvMCr)|~cTV}~vXfkgu2H_+peFksXGh`awVZ0(B%gkbby2*WV=dOt21#?Wcm$OWydMpOz}`H#)8LIz!g) zbdrW5K+-4_2u&YRvGCvMvDK%<=Ng*ZQlo`Ij+3n2mRg(nDwf!7O=|<1 z)UuY#XcFL@Hs;s+$XH8rDccJFd36w#Rq%Ai6C8jkf)#M=+(}M&w4_`ZM6#9>Hj>tY zYB?(r?MQ0gu0%a=ZGD2b0|9F-tRT-S>xuJpbOwIRj0br-lAYXeo^rx?`e}6>5T-{% zgh7lXR0la>#xZt~v6c=<&^IV)2K62%Ebmy5TexKrhXh1UVUmo0O2{#B5Zn-s%JDFVe2 z;t9+PU{X-XFUfS_fLCw;L7Qabr3^r%<>62m0t^F8g6l)!I3yGYgMonn6eFLlZ z-J(Dk;MYUNmdsk4VOf?egzn}wZfDf#|F1ftT131}kB#u_YbgG7UoCdw5a1{q!iwBAdH>gbvL^g;lC!%jnbA3{ z2@v8ENWu+hxv=$KvL@hc=+khjJRZPJkO+7x&^aK^);6+`)kkZr2O_ETcjQV%0(H4k zor+}Y`q-5RWD>pi;>dU>TRCA*ur<*J?@p!)%UhFxnsK8L-7E;s?iN%J5_ze;kV)(1 zEXA%D&rt90n#cm$5$Iir;`%oU^k%3>bXgy}s-L{37v9<3iE_q_N~K!iU0o?|AW_Xz ziaG|`Ck%n+P0#*&t=0==X!SP@{%3svsFYuoyKYDV9sm`KSYNR~Bn|-GTe}m8u50@* zz`O_PxLc7)ZgxahS$a*cCi~acxMT+~6a()8$gdZ{KRilr4*&DdY6JYAi(VD@Um>f$ z_=C`Y?)n2KttR=;U8}zMgV2BO`U5AeCi%}@tG@Vy(0}gw11GH}`8Rj5t}Z2kT^%`L z4`8AAn+={d%VI@$svX5u^w*SY&78~Z*QCo#Oboac2$;$N(^2|LMpPMC9l{X6o&X#Q zETI_-s>4v|;pJ3-yx*@;%vKgDbb-JU?cZgsOqkXRTQ^}6gDmYF{B!EMW=CWBIw=rx z<=!;>5E#Ki>rX`3HoO>4vj$pI|D0m|F|y;`9HfD T3)ogzdm9!E24J?A@5A~(;3s_d literal 0 HcmV?d00001 diff --git a/twil_description/launch/twil.launch b/twil_description/launch/twil.launch new file mode 100644 index 0000000..384f343 --- /dev/null +++ b/twil_description/launch/twil.launch @@ -0,0 +1,4 @@ + + + + diff --git a/twil_description/launch/twil_sim.launch b/twil_description/launch/twil_sim.launch new file mode 100644 index 0000000..9b13c48 --- /dev/null +++ b/twil_description/launch/twil_sim.launch @@ -0,0 +1,6 @@ + + + + + + diff --git a/twil_description/launch/twil_wam.launch b/twil_description/launch/twil_wam.launch new file mode 100644 index 0000000..1abdf97 --- /dev/null +++ b/twil_description/launch/twil_wam.launch @@ -0,0 +1,4 @@ + + + + diff --git a/twil_description/launch/twil_wam_sim.launch b/twil_description/launch/twil_wam_sim.launch new file mode 100644 index 0000000..eccc16a --- /dev/null +++ b/twil_description/launch/twil_wam_sim.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/twil_description/manifest.xml b/twil_description/manifest.xml new file mode 100644 index 0000000..d5b36a3 --- /dev/null +++ b/twil_description/manifest.xml @@ -0,0 +1,14 @@ + + + + twil_description + + + Walter Fetter Lages + GPL + + http://ros.org/wiki/twil_description + + + + diff --git a/twil_description/meshes/battery_bosch_12v.stl b/twil_description/meshes/battery_bosch_12v.stl new file mode 100644 index 0000000000000000000000000000000000000000..a8fa985f58af96719d9100ae30b611e2c9a75499 GIT binary patch literal 57284 zcmb`Q3HVmi7Vx(#B~-U7l2S;S(jc?WIh2`Xh-7x9L4&B!oRn)y<|z>kWN0$;Kj##; z+z7duDnpqv%S^(z*E)Nj_jms9+vk4I^YuK}JNcWDj2Z%lOl zRrkjYTh)x4jqe-GKjq$dYS(S_dDqh?#uJ|#QYF6^iHXnsm`k3iu{yqMaa|?4U$Z=( zd+P5M2-@I#7j8c%9=3LE1%fHLrSaYITV40~i&XKwB;?t2>7;ZqAJqx3CBF}EFlz&Z zm+-xk+P%7*@)rcPq(tUla()GZ5-FcMcfVA%{d>6H(RUWwFoC*XbhcEs( z4(c5H|BxyY*YsNxe|h|V6>Kn7)RN!-x<`=^dw1Tt;|6T_cTtP|u~@q7ol?42p1nr< z-T#&<5>m4d-2QHbUdwk;i#@HFDoRL58@p!pstPtpP^-Ex854Er(4mD`v#APvtMW<3q39I}FR4!0Hw8lfC81j0#*}Sms~0V|ArfaJC&Y#))J`h@Wv{hF-c$Xv zPgRLp2Bh)B>Xc|TO=r{UJ5>co){C!lPg_qasF9K)ILk;7F(hxa!DmZXnFIPv_prg zY0idy-;gTT+DYs0Qk#_t)U!{a(i^rx0{O_jXfaj3Px#!D@HQl6@^4J)w0w`sQ{qZN zf6sKY|0)rP4ZJsS&+@xIdm`(DVuNMnJ(0A0|9g?3#M4p={`XSpdd^FHKc@{zt^6*! zS&HOI2ru!pw;{jhHnfE}LUUf-e^@$TKC)Km2`>>X|6Wgc8=_nCS0sEsq(1!bqAmaO z(#<7&uP10jsp!?8mjw@Q`iqW5n?Lhj(56Q{&FzK>YK@%yQSj_ryZ!~icaf0iCQA;> zOII@@d5NkMUQ2%W<>s}sd{DyoN@^d7Dn(0_NGXiHXKTKtBAt zsKxp(=7SOv+rRu|aPT$5D%c=FtxG#S6x6TZuL40y%?0-bCr<0CT71)nQ$^yE11+i!T86*HNE4p8c`L z?eivIU_IPP4_=yHeEJ|IC^_Qw598h5J|-3|zR8$Zmi13xxHvAeLE?^DAH+S6@2a#h zt6uG$UiH=MWdybE{AzU^UU{;n(3tsk{+aG_%vvQVA#wGI@5k3(bC$Dl?zj`vWbeOg z3`c@m>l(ZhUp=drvvGEvD4lrTZc0!>;^v2!$Ah2g>ukKXrfvGjX8V^B)Y{?x<#G4x z`Z^o$T)cDo_>_Z{poGN5hrAuner|xXG40MqY0V|alo8ajbsmc+lA1MUBV*FH9z8<| zN=QsP{MC4P^P$eh>Dw(%&hOW^jG$KC_Akfxd^6P9nEC1b$)vX~RDu!`13JANH>o$w z*_d?u#3X)tNEtz`2akO*{?A?`oQ?O7ZPNPFGxt;aRDQa*K;KBG3W*8aof{^2eg56w~q35iF(PvS$4@itBxwPiTD>&P;K zS}VRw;-Sk%xSanqZ9&ju#V92xAyLf7t#{N5o_K3?89}XnyDrq6XZbj-*_-jQ+cO)K zkYKqP)9b>WqyE#gmiYOo8S&3`&(TuswBliHeNt8|Lt{4mV6*7_I^8r?l#rNn%G`LX z?+3a1IQ)*!!d@?*TSiceC2h>)P1;4RzTU5lNNdm3o+`OzYK__Vha;i`?r5q6B_!^9 zbVmH=va?-%96af`Xv(<_$_Q$;erdY;lB`FyY|uTLI=7Y*l#poJZmRmLtUf-O-ZT1J z%lFh@k)YPVqwZCYn%Sto&7kPV%cm$o35hL}De=uS4s-cv_SmISP<2rmL9LIMO^Mq* zdYG$^K9`M*n%-Gg2}(%VQB+5RELFo=jf!fw`yrO`gAx)ocATPPNtW|>zZ)G5*nC=t z>IAjK_KdZ=x>VhH#^`A5*4JxvO)Yue{@Xn?w?(2|-{H}nD-R0A1|=jUg`IxiwOCeV z1hu5pA9<;{OVz#021J{j`IHirkdT@^dYk%=s5QA+)VSplk)%rcheXIyCelB4S-p{J zNvrJqD;V+VrZM>p2^)wU-gpl2-ZltM!}>*V>h!ghVkPuC&mWbmp)6)ah16P>UsP%tc2|43Azoq>PX;qv?B}YHc#LHd@L?gR*>( z5T9Q)WsTCtxY3}Dpq6;;@1FnI<-?5zN>D;Ve7+D_A8feA9r64lMwb!Pk`Yz%l=buH zcRMb*`u<@`P(nh+kBfKx%Gq$^c^N@1i3~36{gt!vU=}kdK?wWEzx2;Z;T_< z?@~fSp2Y`eHa6L5WP0V@+h{+pPIxVe`o)W8rQ7q=A?e1=Zd8I2zE@@wcQEm6G~7*qF7dLHc>`UOQL@9?O8sSZQCX7K5T2P4@yX|Zj8D6pTp9H zN1miM7A<-|zU-tHvGrSle?Dr9vB9jvS8LtK@5W4-G|CchXnjypi4Zy`Vi|Er_-D}) z`s8DeR@-^15+Nw5L}WHTn0-Nd`P+|{5uO&UGd_Jc-h0{!&c?Rq_f6aEvRDa9DiN8D zSME709lZaqWrU|i>)Adl|vP(9*qofj%*|=eBlk~}3j#3*W{Ih6%H2L-Tftu$#8yk;pl#X~W zo83`TiO6iM*~+Bt?$2g-B>b~z-B@QyoX)?<*|@&`(xm67eKb{+R3b7PpU$0_Z2m+x zS0mw{MQhzDi{s{Z4RSUnZF*VqK-DE`gOW-_W~1f)jgr<)vw0K=|14UkPkb)6YckG8 z%l+?&yB?9viYTc>cpG;Fl?YFZRN-7bV4eJ>q?-@w=XVE%+pZnpjtoMn$ z_o1W`k=d{wF7h6Zgnt&T@48Kg-?d&e8t1$yC6$QGh8;g5JASB7B;lV$YqPhe7RL`u zyrH83C6$QGh8=N)&=H4(fA;zCW0#H}lB!VruDsVvDiN6t$+;ar$_P)3mXyMMe{Sdc zxhq{ID5*qbHe3ys5uO$;sm+ypHE=duD~Ti@lvE-z8?Ggm5uO$;X_X7F+0@x^tz8L9 zDiN6tJAO!yDkD5CTGG4POs?r{xL&ISC6$QGhVu+%gr`MIyhPhYzg1;%iSs^6P*RD= zY&Z{BMtEAZ#M||*x6avcUQ`K6DiN6t=c&sGPm5OOwSROr?D!$0ffAHdBD@V9amol! ziY{XDM3jkBD3Kl%QC{# zq9svg$zQqXRlN@-m59uSi;&9*Pm7jB%ig;hBT={=Ka`-P5|P;u&zAig6WzFAc|5)5 zsj}l9Jl$tm-0g{;`h3$-_s3V>(Ndqiw*3E?h!PUl^?fNGwQ|5;5Y&>EzkcS06$qw^ z_FBCDZro+Fqbd-TkZ5_vL-C%IxBd%)T7Nz^Hy-mX|?l3w5X zq&|GBl>Ak0SCo*D`mfwdNKi}iRJkQmLZa)3)ARZ-uR;GVYOz%sbHZUeq`R&@IQq3t z+mNdRTq!zu;M?&DgEoqL-_YO2Ve!?MM)N+~Efj()rd-*c_|83X+jsVG#2Z)6N^Y6d zFBO72Jlu&p^qg1YgJ%qN#Ht?eCm)^tby9n~L!%vAt%^UKcXoVd{eHokHE+kaojy>X zB~|0wUf_sUz3V5N9JVO$L z8r?P~j{e(R37&f-ea`)_##7pUQ6;H0=Cn;(habH0T9w$~Nn)NuUeffQ_#M;9*?6?` z!%6&nm-wA02SzWv@=^TgMV(dBv*#yT&+=ZLHqG;q_?-Jww=653pfzUYC8Lw}oApn` z1|=j|>c+Uzjl~8DYVn+{F+W__G;HzY?Mg7`-yCvZ{B+-LnkSx`Hs;k|CWZ}On>przX35lm~c_#j<{U~Q+!n7vApEvHVHb_uQ+FR+& z_6Mgd?a==DN7M!-BsLBf#&eg9b~Y~WcS6;zquQtq64a7*>`#0f^YS*6;_<6zstrm= zNNfMs=EI#0*FV$-32O1gw=phNp|mUZD6!Fb)@toVJTGjcj4bD&v|UO_NGZJj{ztA4 zy3$n}B&bz9hwN%lZBRl&YV*bsKR6q%m8cC8)RGqJ?`-5PQEgB{LR#g#>ub5vb*)`J z90_VkPxE&{@*br&C?O%etLc7?oDJ7&)dmS_@t%e;+mD?QK78TJfz$^jB*eq5zi$s` z!}-JxQs*S7MgM5b_3PUtEg$RLQV9A!`b3_mH^zBUO%)|1#Jld)uDMH<*?pJflaXCC z=On1bvBa2T>eh*#N~h@}&+jcQlacsD%bmbGew1hwc_tZzU2vv9jlo1|ic5)v^T=z%PUE*s zWvnGZE&3IkkITn~cXi!QZBRm@|NLj-Bp%^x{MNlHIB?nyYJ&u|=vR!{yoU+eo!v=o zP(tG2)(hhwJCAZU#V zafJByLmyR1ghVf4qotuUgQw5!7)gClLPGMi=aMx_8*}dLPGP_0jnxJTYSBv=^J0TZ zVYjjE)dnRbq;9%x^|Q0_)|pR-{V%JjHb_v5Uc#8`HvS`g{E-G~gAx+b#^&F$sjH92 z_c774eP0ZvtVmFcUc#8&+O~)~9rju%Wkm@I=_}LUYvgQP*L|C)=bXN3g9NqcSB$AY zw?lM$yUuEZ5)#Ge^_WfvrIRMrRianJkK#k`Yp&Mm8Ai{@&L?IO^4H6DOwS083nb^1 zkf0|r=D!DYOkaHMu~>3Wf?8txrj0tgoHrTJEdBL>y6PDyAtCmB{Af(awR@%)%$uy< zhXl25p74G=d&ODKhMOB`+%EG0f8tN(3I2p(F$#Za+-~W2JM5Z{59WrHkSN;dpKh5x zxV6zfSRjxRMw!Mee78=z(YN<%&MD!0nI{{C|8ZAx+};fn8KX#0s~Eky(Lf_hN=R@d zGUn^3buwwqt!jfY4*d$_Yh$YRnwaeW+CS7MQbMBWeWtB^B^m!+3oR=W)M6Rh+1>KD zlXDI_Ih{7TSRW)f3p3`>cWR{vpWQX>SJkdigVbVMFs9+dmnKWQ4Nfl`(5^7MqYa+- zGv<;1?vQLYw_iHLriv00^ufl=y|PnP(-tGr$&=d_2x{@%qA_c~pBC)X<$`o^ zspTU$$)5)zDRjEO!vE$X}Cr{r#1gCwZMbA2AiZ5z|+<^7^} z?;EXNlmxYyCu7Dv+bdeue?%fakrEQcd^EefZ?sk8$CBR~w<{3TDwfsP(JWne^-;LL z70nTjc{1kP?{NHD%OW_C7yL^6Jmpcc;&8spY1bzM}(rB=UvrLi+l z>G4!xzFwlUZLVd=c&PIfIpMjD0lUDRTpj9I;6 zaMCmA9f|j$ghVkP1OCx0Ie-17(fY>i3Iw%^W#wWY%{kXXB}Vb9r_7TvE#^Lv?9sQD z=A04|63LWSo$HyWlBcg}r8y@-E#}FX=T6!<-M!|K+7c-t!BuW!j$6MbdHU_Mw6&9< z7VAG>N!6Tl-B_YbztYS+8S`7OKav}NSfVo)N=Qf~yUXIgyD0pMg`1`OJzraMPJ&v@ zlRY&zf4_9*IgK>ul#t*FL3>VO{9fr(e`_0w7bQV0?hfQJwdS1bA`&6{RTbvRt_Uw^ zm=1aRLd`iPBsjk^rtdy`q}vaBTxVV+sKq=PlU&z5z2o+mLh-wlkl^`CW175qO8VK8 zCc4LZ1`^a_DcCj3q*MCd*G*IDADq{SmcQF2ZWS}1+I^h;JKk2ce9M74a#BK~cJyLgd+leA zSaxEM^zB{WOy0FNco$JlZCrpp+ z<%mz8{YSK5tIp|XecOh-uf*F&)iou{_5)X>jT9~=2d{GVO=$KwW#4nExHiFn|Fm+12gYafrFm~yGJ zvH0#kgYO=GI5@V!$mq%z55(Qq)sO9deQ@T8`{Q*zx76oFQ)k3eqkkxE%z%M4!_H@< z@#yhcj}my?UIfS|<;g8h<{ZKN;M+>eu+n&9hXEnt7(atK|-};#KzUqok1eGiGe`Wbn6xR>xoU85vPR;>sSg z<0EVIcd43l%68$Y)2~U^>@cW6P>bbeZwB45Z}8C{nd1(a;Z5ep`#(HXwLaW*e!Rt# z!(CZjSgUJ?hj#s2^6n?r1|%e!T>V^Jw@XIb?+hH#G)_)mAMdwvWK@u>SR9Yu=TfzC zQiB)cX?qWIHolqnOw|`p{1o3>e^gYEfOzx9CGq$zeLh-$@j?9lPS+-v-!iyBP^)V2 zviRcV7dabO_PZhO{rRhLlUk!9YCZVvf8+DFyiikBB(`aGX8c}@x8sf4jfyBC@!4H( z#E-nz&z0_q-8v*A7xYTP)q@KJwO;MIGXDC=o-S2YTR#`K{rHyn(p^SH)S7OaHK0}gcw{DRQzZBoGxOe>d@uMP2Nc{Wk)$#1p ze6L;o;I+wrZ+Ivku+NYJL9J20ei+}>qoYezr+Yq+ulo6mXO|v3Dx%h5KYb8iuysdG zRgw6(+lO(ZMXy&q(REZr2?=?Y`zF%ojX8DkjftF`Sa;BnGQw-gn+}OuyHq(F9lQ-M z;d|w|_k`BYhRer+k`KO%T9UtAj@Zc&u5<$_T}q^MCw|aawWQP={JCwh1_P-0ntE>+I&hT?ar zB_8#rnP2OBH%w4MLcDf|Z@zM=vb*|$-PPArk)W20M6WLW&ZWwYIDw2f)RM8}jE{fF zQnf*X?;;`N)hAPaa;dU2$k48yXQ{%ws3l`?z2O_Xmgq+3z>m&eLPAE->+bO_aYF>P zWNiPr!6vTlzGNerA1XvLj9!XF*N)qTKXpDhc<|vYlJW75#3-L^pY?5tOZMrxlgkGQ zN=RG~O^xT97A{qGZ#%RngmiD41hww^_Z0PTS&y>&=b_y{pCS9_l#p2P;=S;R&W5g} zlAu;GzOp+eq1`{%9TQ4Oh`okW<^G@eU6=D%%8CTF7~AQZWg6QxOW9YW7d`07kK(`A zY_0JpeZDbv%`)|CmXwf?=NBe-bkXag`pr^V5%xCxSVS$3cDf>*`W0bHNHCt)lLM(g zIY5G19Ow1qKm)732M<->N;HL*WoB3!Fi%F_T<2`{^S4&Y86HaIXMvflLM5H zD9$&PJMNT_pdZs6_sH+Klb{x7$abY@ zK(om2xKl!ceoS}VBfsNLf?Aw;>)v+sH@CM<2?@?|?T$&hW#sqINl>e}25|awEu;2} zTIud9C0sS&n~a%R6-FdIF_zvE5` ziQ?+VFMF;H(;CO6S2eWzA6R>#7T0R*zQORNVXM2(OFyr+ibJCK1)3V!`c*3HSKuIXcpQa)~E#}FXlN+`Q*LUidK6L8bkP;Hbe4Nw<{3TDwb8_BVMn1 ze49Ixf9*NAurk5Xhk3Fq^xdmse^!kW62&pfo>hzeSv3;WVxEi{{?0FP(rAG0(NjW# z-;*+CXz*p#%^Qu-a{wf$#rij<(Y;5eKXq@YrxUn_$nS=6Y`13(2DVR6*t1>QXs5Oz zB_#MoFuP0kaierzul>@IyUZ;R)Z*A~_wF98lWu6D0UWFnbwPF8ADLyuMkw?fV@g@jjH0;5T{fDZR|^YR*YeizRK$fwO|}pnEQf#QSguOGXC2YsIfl z8FTxnap9(~^wc`1goKR2rCHIEEG~(}GmxMbzf&dNXKk3&I4%=Bf{SMMGCFOvGPto*{&MAy)P_IU_S>>pccVRdm68s)vmh)%t7$1t?B|$Bgw8TE&2mOxSIlSQMVG(;2S5nhYX2&&utPzKY z$y(o_r^W>b?0ihPpv$m`E3{k@ZZZF<_?uNfS7pTTG2iSv_UJRhQ@$TsSas&gc6KNB zTSv^Pb8S3ia<_2d^r3~-bFR?ebmkJ+*k)d>WXGikga`K?TG$2PPQ$u=-#|Xv>=h&% zkE|WeJ8)>kJ&(fJ9=sFJFTOg?Y9m8m>geo*6?WWU)zTK?t|2t{W5fwd;>t9Z=d;tBc`0*Fm3we zk&565QdVZ;_B3o9el$Cr##^*!oT)tW+gw*+U3r=^$*`E)H zPHL6J*WEuiWcy*eVyiT!=^GbE32?^GdF-!Jsoys+5^jh_Bl#rkw(>f1rokvpV z^ojI?S)FIzPU}3hb*`zR=j3;aq#c($oa^W66Dc7<4{pB|HFfi-?`|{08`~Tj$vELh zmd{r`kdI46-)`$%JcD{sjsX19RFRmm=H%$a;ctfZ_njM3LPC0Tsm{B#X&1HIXnH84 z8VPDKwKiJ%wrMnfx2?+ZLE_`3_vz|K7Bif6#GYaMdA;KC4-YS#3geDqapZjJtB1nJ z-|il7JAa^-l^;_{6m7Jcvtx9`d8fuVxYG3mwdgC2`EsL<(Jgc0p!#@Df_XBg&kg5C z4L&#~tnPQI#c@9OqS~V$|@-3pc&+)A*9s!y{=KJ5N1BqY18_a~<9oSLcb; zIX$w}ruQFW&&MdnT>8;&(O!?m8p%*Xg0}4m)62Gw+HEp2k+w^MTE!YXwb7(-VV$N) z^%^8m%m-Tu-$kwBzO##W6Nz^vu6=D*->j@~`cL9ue~!@B;BoDv88e%u6Ya>!v4~?7 zOTm~q`)(3FT%%s<`-d-460~hsYuo-D9((c|iL^w%i&`uNYopc0q5WUd*tT{`NEGvN znQbLCE3^`7vBl((ej<^+MD%ArI#|n!Cl6%?P&(20kDlL!Jvw&Lvf}8>ahIiFjQA1j zPqeHkAwk=AmTLW>^^2*rD-zUVDcGI3I!!~{wzOSQLZXhxuM}$=R zAPH)*6tt{jUsjZmDCT2Bt%O=^F?Q$2&TDsCdO#xcTA9Cke)*9qk)T$g6r>L(z7JADqL>f229U@a z010XpT8wcs`b1{*uiBZr9|vVd@6XfnoUPqkxpl|%qNm!X-(4`b5K}W+W+@mWe%<
KV;@<| z@TYubjl-W8)|er+aiYcyoHcO1%u=u?Yph?l{#|1RN=VSQ#=EKY?;10ZpcYHPp7^zX z-Ny`+kSOM3L#>2bY%%s*=ZEx5#!mRS#q5SdBcAf*8R2D}vvbH<^eV(AVVxO5P(nhU z{kdn26H^-}CgS0^mcjK4mYXp$64((TmMDV~611&Rcxp!kEnO1SV!0V3-p$9Gp&M7JMa}MUoo&>ah-THT(e^5d~QtM|+_M2zcuUr2fh;JuB zE#}Goy`mQvCjT0IeQ?$VeG4^6g6n?9)Oe+L^7*V=I}ARkSm)G|QYf7yw^6wCD4lt6 zjw~(Tuhub78il9UTWiiKAtAk>v}P$@+Inl9d6A$N^JGl#qvj-!{uqQ)C-qg&;7gGN z*GP@|_l_qgU)?!3xcb!0mw19&Trbs_I<+x%Br!GT`r;q`e3^ODm^!t-He{cR*ZR1xjvu}hNpL;co_ihKI(e;qgYd@j*@)u_ zYH@AZ7#krcHbT~%b1g$gQNMn{JZXfS$c$TZP6-JaA4}`);z4EQKq6!k)MB2Dx%l4Q zledna8=9m0X_Vnhkp$P??d{A5zKSZMWHQr5Zyc)gpI*{WqYPh)d@uJY zj2V5vDezB zHIVfTAHDh#r55vK|0YuXalz@2RE72X^j90cd`NIl$KFMb4(Tx9#jfEkJ%$wsYVlTq z#-gE(MYXkajZEfkzMnHs8jFUq)*v~jgoMoDe0$SaG?cXlsdEz4VxEi{yj7cU&>1tr zE1C|_d95!+65Ri?d#RV*5F8#J6mIikHWT&)wYV3ik!55f%Sa+iuIb6_-urguNh8Zh zRt_ZRl#q~_zV|U2S%$K5AazcHTFjF%w{^Tcyms-JaL+FW=<0_rMG~?G;O}|b`?Wp4 z3x2QDIP7%5@B%?C?i=bC{=y~8-qafkTzli~0j`&2#I$#I*KYz+LPFkDx;Nq0`T|)g zB0;U<3Zz>p3S>Qz5)!mZ&_a^*KgJ}7^33;A0`1N?BTl$o2$f%aecuon4cYl5<-s!-L z9MRd1%w6pWExq<1S3MXnJ>azX$1mpvpKoiwlznDzeU{XgY#e!Z-EhbUujp4D`5kJ0 zXItJ>tIt+S8)LO&q2#U%za7o*MZdc7>v6Y3H+6(-SGtDW>G&D(i4Py8k~Z&7)3s?y zA-}(@HUeuS5gYv4H1omlNEcV`C?UZTv7S21x!%ViK`nkqT8YG$6>~o0mKAyV$alT{ zm&fyYR46@)5)v1`{9Zin=N7K4t~_h!q}G+)wLVBti{B^DXA|0MDIsyy!K?C;R?m=} z^81vXq;yG8i{B^DZDA_;2oOZmDkny<-FLgMpPb6lKLP)tt`s$ zU*MP7BiG3MSInyuhdnXK*%-cl$u#*&tk~eY6}`3QVINKlKt zIq&D8@8|w|^U`a*|ByG8zFhBCowY|%LPG3a^w6JG;#Z83-egmyHb_uQ@>Ke}0B*Hb zZBSC3Xuk4SXJg&(FEy7tguZnByM*>y{I-6+%BeOeAtAL{$cMBNwLyYf^ubvKaMAbQ z>?o9nVQni@wX=g0L&jen*iK5>jq`nw;)zxEZ~!q>`W(eOI<> z@QB-qql5(G72REuxwEcplb{xTS3W;aC2psLL^1YpvsAS~f?CqMytm6{!glXjZBSC3 zXt2)^S5~sx#oY}5E}^{^yKAq!GLZTRp zYTs}(dJ@!<6nfv4?UKnpy`MXKNp<3il|Q+7*X{h|b7xP;d%YHYSH8QXHYgz>byJF| z-AO?84D;`to_hd#pCh)*qRhP4%IO4Mv!sLsyjFp0Lay{7E-?E=KxS-MXX9opo1+5)wrlvNGs*Wk^tq z(Q&N1IrGJp17RxYS#nIUvB_#Z5I;qY4Y?PjdBS9^;h5U?{5}Y;q9ZY#Iy-Aa%!`1hwex@^i0xmXng|MCq@Fy0yN1r`r2kp}iK%EkAjtrwu6~;m;># z`QV9064YWz=V$KpoF!-U9HacHz|4j{^&%_uTIZCI;3#SgPaBe;mfttbY`Fc8!j7Uy zNH7|(zP-ZvT_LFDch52#_7tm}Xw*}zl#uYdP8s3$qx7UKB_tRJ8RO0&>zQp5)bi&c zGaL3)nC$lHsW3`Nh`myr$a9t?sO9&NG8>h4mqbEBO4>)Vc?}j$U<*Mlzgv^pa4SW+ z8YL~muR8gi4bk#vJTpS}wdL%RoLl0`gv45Y9>rMO7`sxG*p;HPD4Yas+i#L*d-OUw z^Ig`#KiDEwNse3t%tEcWsP^(y0?gWI+qd5Cv{J=b^Z8`&wOd>_ZZEA!Nu7RxO^Nv@}g zDIwwa!ZI5?xlDpuEa`kbQF|2EMI}b@YoUzJ?XIQmO|t$fYp;}$kT|I18Dw9=_9|^x zB&a3hyzl?{sYz{Dl#uY}le3)5U4R?hxo{HH;)-`3k!g?O%w6IuKksLr@-wNLb4o}s zI@ejMoO{){odmU*r~GWK?&?!Q!k^#Ga?Uf`B&fww$nX5wVK{(P#uSKd^bJ3AYC z7l0BH{v>dgDxMK0K`qVzbaamV?HWo*_`4vP4R<euh*Y&`Nqr*!SJJCzaC^3R!#Bf8g1Yj4|C2}=C4*x3H% zCxe5p8Rl%v+GJI-q+QQ4f?EDLv+=KF&tzr&5lT?vpT)+;?H2|0ZXD@sEZt-Cc$XEU z%Lr=u=gh_qOD_)JA9Se_l=x?{Veg3t@)two*_h)y%ny$`w0{{vE&rU^=-Y3*Xzx`= zDnW^VmiKP{%zMED(K*h>gyZ&$9-G;&jG&f(&TNeN@|>vY;<*oY`=t8;K1{{Il4Qx{<%rAkTI^F{{Bcf?EDL zv*B8a5|sF7d9SpwiOoN8HkxNGv5cUWf6i>YnzeQ%DDlr?L;A|@?Y?w2uFQH=89^=o zoY`=_RtZY{v)GV6zv#vqu0EV+C?lxlpPh}&`zS$)e-<0!yTrT7v;7KG=Hbc+YWe5P zhV!D@N+|Kq@?P(cGaJ%6vVUVDsWtHc@-As5(o^O6y$4u zNKi}4u>NViD-e{BkaCmws@w(%YDrtzXTQwHlv=LkBT7g}{Y!jRZi581q)k`0K?w6?|yiV_m^uEm^_pccKWU2lKZ{*AbLmuV!!R>In}F?=9*+_OmkKNF5h z-@LX-D%MyZb{-YTEo{*uZCBOqIxGFU)30iS5)yW95Xdd;%tqR)Z@O3e#bpGwim7_$ zi!n)``Il&_?D|C@-yD#4+4Yh@ZpF(pYu1=aUoA))eAQ10N=VqXnm}%^XQ|rs`CpUs zhn`hNP>UsE%+c31N$n>+mBR& zIcJ{iYD?hP-hC?>qXZ=+*h1At=xvaomR+C8OWhb-AEB=gN=VpMoV;%AUtRd%KVhAr zeKl2-kYJm(t*_U{(GQQFRz^_EuEU`QZQG4}+hsqn>y&xhC2hY=wXALA>w^*!cEuAl zXzM(Bz|}bkY86vu`(WhzAmb9d%ANN+rq&qSKce=oe^5fgu7#sV**+M38YB5jh z8KNHbF4L$_2p`Fajmu7Iq3xBawI?$tjfxf?`9>fujFL)3*4iCmJ!Fyav}iF;#<&`c zgpktpQIVv5HW?OY#}(zV{FjGz|tl(%+Gm9+NW_15W% zskGy^i+qfm#V!e+Nl#meL?%SJspVWGvGJ;y-=Swx{MouMU9P~X({JC$tq}BV#XrKfo zBxGbL)u4pHt$Wg^)LSFOf$X+M~Rd zyo*{a5%qAX^>9j1LPDZ}Qm>UL!+N+ff?6y$X@CCTn8>c42mXAk-9revJ<&66-~Q3S zo`(%eXN0}Jv|ma{*mH})sFeehF6mb%s3pC?p9(D!Ocm|fvlKy>&5o*IgAx*Ur!m-b z^45PrP|NPn1^$d@F;!y2mx(>Sp|cbzE6ImHO<5!;A;Hvcn4p$DO&OFIDc zQbNL>Nzd!QR2$OTNl=TevUr<=qYTF=yT=-o_SJZsgAx*U-!LfcrSdih<7h_VcE2qs z-L!Cb6#aRhTtdR`u?D4+fV|CNciaPi^4;!12mXY*q_$*(w>j8G*$3rKeg`u@->#>M z*{;}@?A~PHPZ8){fc%R<_DpKvPqEoEuv%+!>Y8m3^T9Tj@4o7HSSTUE z5-Hy1AVDp*vHbRc-n3xO?S5olKJ-fY4F%m9rG$jt^9=khX?_brZIGZAeOG?dLT__W zLc*RS%uBj>n}Y`F64as}%kKhcSy57* z@TZOKcX5ihIdcChwAZ3PF5c##goHf-Q_M$xn}Y$O(C`*W$RF*Pwa^N=Qg;7V?qb z<{&{W`rzVi4*FO6-QqaN+Z>dT5D#APSNUxY64c^YQoPMUKWNW31pcH8eOK`|2PGuz zZhufZrN`SGB&bE-RlLnX2?={@LA_{xE?mB4p|?3mP>a5+c$x_*?q8`z-&MTLK?#Xs?8Dm}B&bE- zRd$;r_k-05e|9*(-S59ml@sz_uSIWHyv;!g35gR+F&uAm(5o@Zq$eug=AeW`F&5=* z4ieO&Cn~$mk$bi3gg=Xyf5*$;=EwLa4tt(9_W<-h_AGC) z*XFl5C?P>_SG>(Zf?8s`)N6U0gAx*AuM{ouHU|l6+0(7)wY<$Ca}K{h!1di?q|e(N zl#nRe;B5{P)MB(;yv;!g3Faw3JE)Ni32GIiaNg#igak)BjmYxv4l@2=f8;!&c$~8ZJ~IZgR@5NF45Z+Z*x#Wg8Mu9_hj@o2MKD? z+m+qs$USFuqO@03?KVeF$a}pO%dL2ugAx+l5z4>DuHUC7K`oYa@iqr%^cd~qi)*s^_o?+Z2PGu@3Tw8G`}?&z^H-LZUN2k7BG{yv;!g3ED2+<{&{W=Bap_gAx+OeDF3032GI~ zinlp9`(gaRJQZ(qP(q>@W$-o!32HG<#oHW|kl_AK{^feTn?ZtFtpDO|4z4d6()oI#_9(7QNQ~mwLK&SGZ*x#WLgJv3XW(rP64a7$-uM6FZ4OFE6n92>n}YoD;LW0qG@iqquYB5j6+Z>dT;Lf=E-TVvuB&fwwDBk8^ zR4iKlOp&~)Gc;wQ9PZ%+Z-gQ#hFa;HU}jncp5^# z7MkDYAVDqGP4PAdB_xXH8F-t61hrV3+0Kvus*3%NUa;o3nStyHUNGbP;Iv;J3jP>5 z&#rua8~fig;+uMN!?X4p7*RsPKF6NUh%G)iCOUXzqv-G*ehl^;^hoe_!?}Tdj{Wnl z2mcUnb<@Ma^26kNGV(9pV~c3v-X}+V7j2XiS8UcWS~U0Ah>~hVP_(iA75hbhzo=b- zuyn4))Mlyr{KJvaaqTt^tv3#aH<%Sn*><*#r+@9+H5!DfGd}8E_+4QYA~-g z`Td9AyH-hCFviw*((&%@oBKNVl4^AmPgvcfN?MH8UMeN#YtTzbNIjkXWS^?6&TZ`} z;cL)KsuQIew6&*%uR%|+{#okA*xF0C*#FO|t_Jg3lNz+MqAICPmbyJHGB`V%SiN+s z6GwL)RF&1atvyXu^%|7-daYurrk-`K5@V~ilIp}!PYtY+eq)U7O-i^PmG>ffuh%M; zuC!a5^PPO#^|@uskQU=ps5!U9XiI3j$|co_QcG+ztaqe!{!eYYIU(=$TGEbv3XPdQ z^jsz0eeZK=y9F)p8H&U{H99LXsY~Wd{JTWU6YRnEd#?}gr^I_lwo~up32Mo+Z#{OW zVN^pU9ywioNiHEFe#N(GJJ!zFLWv=toFu*^_aCC={a}$ey7|2Dq)$)YV(>--#lz+A zB4PVr?vL%Mu;zOz@$@z$3Iw&}+4s%NU)^@-xoP7Ez6j5*J27v4tDd)5HBYljuH~m(@MQoY}me@N*wS0agc;OdoB7gV;D0~Qk}3-Mx4bZb~Mmb$!I`Ap1oGFbgTB*BFnjLC6rVr z?8p#j(UP~c^R_d<`g!c@# z6l4^2rF%(}HcH$TA5iE~HXnH}k{0SyShPXwl0xrsiZ&!VmVCH6&#hM{{HU$5j}qQ9 z`1Hzqy_TfV*NrjE2PGtm`H;DXq^f#97cD>P7YUgW3E}&>FB1}Fy;cd|&pkmcdG@_o z-mX!AdIq)zYeV98ZA;~Z_db-6DCR?K*xaX*b4p0C3`JifrquP1yxgl1d0)v0@2UAN z`h&q>cH0lM&*xyub1iYL%x-e3tiDz9m*8@;05> Qz^InzP+Fp=St7>#AHS$EdH?_b literal 0 HcmV?d00001 diff --git a/twil_description/meshes/castor_base.stl b/twil_description/meshes/castor_base.stl new file mode 100644 index 0000000000000000000000000000000000000000..d7cc923055212587bcbb32c4ece5c1cf7b6a04d1 GIT binary patch literal 17484 zcmb`NZK!5d6~|988abt6V!mK_=Z@t|sE~s-_nCPFbpn%WJ_H&D2@^(&A>s=;#8HQ! zQj$y|h0?i_2_Xp;I`^4-Evyeg5KeR*6jGG5!Z4etAg%phd#!zb`<(MkedvPI?pf=% z|9h>y_B!Y8=Qhp%_vgyD*?eu&v}uk1(BAVIH)@5uGVtWgMBNHFX5s$wOIBPvmAkI&1h5;m+75^)O3szwQV z@f7q|)twI#XI^Fc>FS!~JvWyYZGmZ3*t*U4^VS4h?ZfaFUqY&D2SrnlvMq^cY5Y_omtLPF<5c`N;DG;(?cUFxch z9qiRrsS;J9G)f$WpruzOMh{mtM#xK*U&T>0XbBAw>e?cz-fr0?K`%WSMCe(P(v-rE z$Yak{Kaqua4vHA=NBY#}l7&RXSF$S^JGCU}rKh$u%JV#kh87ZxFFD&!)*wMIy-P?# z?-DgZ3yFTNat9TwT&4G&8P0hb>vO#m$uB>jNW|NcGC?}})lh?k_b%(Am4+l@RppIL z8bK)Xxf&$Q%i}BkYOpG^M8!~}>I`dI)y8zbBPTI-LT?!*SMtp|Y2IQPBT5`rQ`C?p z2<1oP-48stP!R%bRblB9X;qdH`Q@6LLztJ-CA-y$viB&gDza;z#|{=9?O?HR-WZd} zl<&bz8lvazxxDq$PMs(#0byB>TxEYJN*qu8;>6j*WG8lvGT*8K5yeZd1l(_ z`^zWA<%$tlmizOQJsLC_NW5p?WRt+C^U>-W8H^J0lywPeHCpXd%Ijm~Wq$NZq|Gqp{~@RaqkK zAT1<3hg%O%&`UE_*)1AgOSYJvr6+5d z&kWz$(y3h{5wtjMPZ|H*#^#;o&l)7?mB!Vxw$dn;5yCaT`0AIZxBPv!?Gq<73vurL z_2^&hxpeT!^Ebt~JA+Q_KXd0tHt}?790Yr1(@=v%=;?gKSb9x!+fS~We*e%D+Z7Eh zF&4qTGM}JVjI+k$=Wd&R^5zfPyC^L&mPWnjLF~G`Sqv}DMXwlVjbC5z^7d=b{G4gf z5@Ttw#+oLGU6;3;!b@|}E5=#l?6iBzuyRF9jHSWKZ<=`oy<(g-zIy7Nt6R3-WE!-@ zSQb4an|q?Wvikk#?tWf=o<3~dc`?-;HT zMCv7b!%K6~E5=#FJDh3I5@Tt2=kq-eBGuJ$cxf(r#W-ttZ&&R$w8U5%-sk--d>%os z7-x-mMoEK~7~6i}c_qL2$!{4totkUpskSw1gnv37)3NNzD`F}{o2c|(JLUPH7tdy= zAc7VW5mTihnTntnW2!aW%OZ4*CCy9inxKV**TST%%CUM?^zs~bM4OTB%~ErD-fUHV zHantd&_aT%HRqy1f?j@tM>J?5F^EG#NvHeWKyk2Q*kj}@Z~e4WT1asJv#;Fy1ijcR zYl0RMtWYCtevMMJcDJPWT}6)fUHiP;unY*lPZ|*8_tcsrSc%!YTbB!J5Slz1AK# z^co+2RS|i5r8n3?ds~WC(JN-+{Z*-}Qm-U*pRAcwV|C=5i(ct-BTBWm{o0M2ZOt1u z+Zqpdka-Uc5wXHSm88hKouZe2A3Ynt*_OI2B$(+c@|JVa%fBU`jo)lbLlzQaRU$3@ z?reAZmJ^*7{eR_$@!6_c``3xcA_<-}`R4uBNIR(cRB^GJG1ljLe;6lZ=@Zh9y6SFg zLxTi6YG{~_y^%>-|0!Dk4#D;&&16|9eK#THp1N2_`1c9*ez->?USN&`aLq*`YkW7*#v#CjP?0= zhYL%}o7P?kjibX2HKGrOmuSrtgeN%VOVP=qy3%gOSf7j5=Xory5A;TVUBH#&pY;PUthR;@eez0o~nN+!gymyQ+_TfH3FO8*< z&)^?-+-w@Jr3}zQf+x6XL>yeWd$~{0OJix|&X95>jaC_;g+%D(p6G<-j0C-6wVC*9 z&Q+`brG-S~Ex%Jc(ew#=Mb*v5>xl--snlh z6E3gHYj?R%&?{=XL_U>f{%@R`^&A`YZ8 z*eB?vaaUKbyT(%~XS9$Ay)skKTZ zK`%eePOvl3Lc;rsy$z%;n!Atn5)$3pb4Xdw}K zD|Jc367U2C+E`1G&dYZ`m++>2-XVsFt zykqE`ABLb8dQ2kpV_^zyOJc_PxDuSr8YNDGPYeExjX zNT>EN1igH$bDoGp>B%pRIZuS1%F;NPp6j%b&>N@r z=Et`l|41g%Ie(~6(96fOj&O}tT1Y@|U(r}d8Wlk=tTqvde3cdw$lJ<%f?mjaBCzLc zw2;95ABLb8swWYs-8EWBppKo;Gb+_?MbHbUAQ3o&)zg^-PH-afPrgk>XIMce;&{pY z+tk{vwm`%=w{F1r<`UJs=q2^4T551!tT3-C3FTGMLZZ%)&%3kl4WPHp-r8YJk2_<9<&kibmybG1S*%+w>0lj!Gq3tM8QEe?fZRYD80OQNSi z0^=o|&6;RwL6_JHdS(8qNU)F1C+G$3o(3%>pqDya{>k6$`+6sO=X83acSGL~ecnYr z6-f&T_D7fSzfd4SFLrGs+O&hFf&LNa+@9xHZC+I&XhFw`9aK!cIH-|9%^~%SO9Mtf3-;G>i!(i!L&1eb=+T&;C67ec#5Q19Q%r zv%cT;eV(<}v)*U__Isx3|M%C^U)ST!(=;F7|Bin>JoC5TetGqaAHMg7$G&j*+(*A7 z?HB&ljmwJ{z9sF>2xC6p{o;S_e&B&uUWgH>i$JCQ$#?$u?xP?1mb6C(J!Hs!>r4OR zphzQwp1;5Q7rQ_B?aO;Y{o8+iZujXQ{f8S%M#Q=9Sb@G7tc=S@+Ztp%`roZlo!4eu6>C67bxg98(N{$VQQ!FXzuu@IJ!Di*uV|1# z)Zab(*|CDds+>i!U61Wt(L;tbJe9^=kwMgBH(z~6UAmkl^pNq)+x~oG!jVB#&6O1m zddOJhsx~tp$snpG(TWB=WUw}4uA)m0o(56#gOJKk^w>esmboH|>|h?$HA@CPWJEO& z>$8LmqBIZH{Ywpc$cQW))@KPBL`Bx`>3l9V=plo>FlLt?GNS&6^(QA8M6stwjhH@{ zeh$XG>KSFGM+W0+RX#=A8uXB%O#1|<#@v+VBN;?#wc$HW(OOzg(e5Eb`|!jlaQ-ne zh*B2TR~2LSV4;kCpC4;Ea&S&tr4|>R0J%h2b`N(|~ z>TtfNQG;tIqfT?Ow;4p$*<4}NiAqnMm9%+N8#U-5BXW3MdF=Hl+I%E~s9^USV1nmH z>G$32xVR1UZvWakk&L)yY@AxgB8pkBEwshy&d^US8PZ#yS7Z>yGv9*8@3XojdPz5y z%jyi>chZj2rRQ$i$0wtY>+wWgVbDXy_CClUN_n&PxN~~QSnOkNy!ps| z#BA@o=pjRT>s>+yQS9k)ACVtDadN$p>HbNWkwymh5gIzF z$qo%YcTYQ?8!yj??pNuF+H{n(BihP@<4P3QCv|&O^pK$yeoeXRDDLln-?`(~UE;L! zqK%W9DCVte%$g;9vhZ25ohy3C*xm;jL@Dd8Q(sjWV+G0Bt~u)*=dO1NwMPwl$fzg7 zN_NR0N`LR3UTWAwhV)#`Z3a==pS!X%=E&8)JQqLvp(p;h`Z(=cRocl2w0_Nddd?Vn z`kWYz&=}oAMs@!4Fo>%2abnC(WZp;I{H(8i#GdrDOjNA4YuAGEkK9N1kP&&)ygF$V zZDbHtPoEWrva8QaT9xXddxC7&T=rsBm#XP;k4+cH8DzYz@ z6{I>>RnNo~20dqtyuB_p$f!x3ai#4ZYdi2h=s9ELv|DPBp;hV0DU`DAo*p&mA*1w? zz0Dv>Y)!c3szM_tnLIU15>?&4!k~wY>fPsI5LKOjV$8^HKiksKb4e>?rpKMrLx%RJ zd&zR=WDvznr$%3uy4~Fn8hOW6-0JCzr3O7@L>5%@)2g}#8AR~}k2|M_j9TqUqiD;y z>rUj^95r~(rJ-k^c3axp8tEZJSDsQCLn!N*n6Lx#?cSGdg}O7&l7&_hOa ziDu%;KFA=J$<^Fu5EZrQPt=h?&kAE@=VX+fsHlxj@Wry` z^sF#W8gpA)J_mcOVkb&jAEsz$&_hO@^OaSxYB42tuE%x-={aL)Vx0C-DW3OaNY5zs z*szbzpl5}#qCrO4iHa;}cCGB3o)yMPqi2_lvJ(~69QV-~^pFuf)~D+{_{4Y6gNJF z<#(w~!;CL|WV&ILVi9G#X}tb5_wS$k(??T-9@~l=pA+-j*QT+>Aj)>r_{x3XzmNY? zgC5(8t8X&m{|`-Li$Rp_rV)GC$I4QJ9@~nmZ!%(ErLn~z%68L;TI?gkSLzaaY)d14 zQk>tVw|$rq^|)h{Vi9G#_VKPK_v%Jz&|_P1qsQ_)`lbZebt!lX#;Pw=%M88kMVC>RqE0izwT*k5==&H0ZIdxK;nssG2VrMA>c{ z)rrZV$F?-8k4s~VL6q&LQ70-j=&>!0I*+BX#URRd)2PXi8uZwfMoo;;Fhjj-lwuKO zyJn)s?zYeMOIL z#f^;QH=|8MQ$dWHyQ!{NMA>c{npNsXY0zUkcV6G{HjOPtbV+^>Oh(ht%vCo^!zg)d zixGXC-$6HxEe27xn?~&6sBV-7J+>7$&SQSJ-88lsMA>c{k=diVQ5y8vR@|5v`lhkw zl^Hd6`#0-E*{*%W(_j574SH-#Bj#g%Ygzl)U=U?{(1^aDW_oO6ANK|gF*K?Bcc!(f zMA;s4rDxPkk8Q=Ryd9cGDZvVcPDBHDyOQYsWX_!%S zS5qc6h_c-@aC@EUu`P}0p8SSawyKc7<|yFtzQ@0O^8@dBAk|}4{Wkfj?|Jg(jR$_P zR#lAnV?NSDM(E`ob*VuHQHMWy|}Q0L=6zxFk| z_r308H{}V2?$K!nW4F$rhm5E{ZpgKhSsG*z#a<|U{xNn58Kt+A|U=kq_ViXJjJA4d%`h>BCt`)$;qhYZg7Z3a>7 z%8~K$hd*`mhhP5SPJLD9BkiB~>No9v{5S7Qdt}fh7UJ)3`tKKv?jfUQ@XD$fizsG&)S!oqnpZ0tWDv#L zj2cnFgKJxTm2o4|J@>-Mpofg={Pk7!SVS@FqXs=>)CpeEAcH8@X4KH^5K?uHxzcZ} zi@7^DUe3fmk;$k?IfF+H#v&>@^xz3TGUy?rPVLIh$smfA9X047qo%})1{p-L{?qi- zZ+z#~gTMOzz0`b@dHh3996s>r&-B}iZT)>RZka)kZPjL+?V+*CAj)>rc-tR+<<|GT z`W;?XJ`LnCN*bKU)3n7P%68Lu{L$V1r{4KcYS3d_8l2$Mw8bFGcGGzIdwyyg_VhHF5gONxQY@luH;oVe=?X)@!XcTYEr zQY@luH;wx*zHR@C7d)IA^w^dLXXP|)F^IC=G_LLM-g?QaejzpJu`LZwzG>QG5M{e* zC`Y;}>34c;mqvfu38!DHjE)L++I=5awU3z|+m)++`^bHmp;h%*vGb0y-Rp6zdd&3L zmPXVDH<_r18Iw_pMU?HP5nXbuzMAQ=Esf}&eml>;N=Ee69itSBDBDdVy8T$^W2VQp zG~yKCrf)`^kEe}NETU{TjX1SOpL2R_OCwHm|J0Y~JQ<|<6^fA>)(m>ch)Dg3n%H@bK@?9~!97Jo$!U{?ad)4))d^nd434A-M)WSaiwsoPio^5*v*uf6HlZ^YXhdLJe$7;jnVotb3VZu|Jh zr*7YRE*Mgy$F^3*_j0DmjQc~wD8(YmcGJ-JUHT?K8uZwf2H!85rY#0hwwuP6-u&ME zzsK&SL62=|@I9$%+F}r8yJ`GWXxxAMwmucj^w{=3PH%;op zyB?=^)hbunTSh6CvTKy>rco744SH-#LzO+frDsO$v4J~wX(ZlD7!}4ZW^9Gu7{_O zQPNOlJ&AhF`@D*7$SGR&&!>Uyrs3%$4SH-#qdGL%(_&uv-_a6fyXR_{S6-D-(x{VG z8g&LUS4JroQMQ{#O@=rs1ubtr^mMTQRnfLt6^SwA4J)18Z}E)bD#6vhf&g~ zxpJzxX32sR}3 zK2b#3ZW`zF%IDlD#pPVdS#qV@QuUSIZ@pBkK9Os7L}fG6*;jcZtG-Hg@53l*%WfK+SM=DHhB6YpP#R$9MDc{HA`~(&|_P1<4J_RGDBz3D8(YmcGIYtn7vDnZSNzVT~+ffhV+cG z-83p!dCuvvEe&Nv6JyBLfO4rBP=vcW#to5oNn+)GX=q%1;BMq)~IFG|W(68Kqc6 z*=`y&6FIN)S!lD6!of$1~TV_R{R5#0=$1{gW79E&L1O~cd2 z^UAjjqZGILsx-{-yfT9*+fBpMCp7#V%pDpfjq2mlFvIi8_bZ}o_gwYc5c{HQ};%>9Os7sHbI*_ba0mORF-<_K>SSeSAKQ fQe5S2{eESXVi9G#X`Ih1PamVCq55lLw0-;!H?$~! literal 0 HcmV?d00001 diff --git a/twil_description/meshes/castor_wheel.stl b/twil_description/meshes/castor_wheel.stl new file mode 100644 index 0000000000000000000000000000000000000000..718450c9dca0929770a5f40380d1d502624754ff GIT binary patch literal 40184 zcmb`Qd%RXvwfCnYnV8}&B6}5NgNlWj@k?E`Ab{(-}s2yt$Xiy zVxZktJEi^i9#h!&C{G?Ty{J?kAyJ%oi_>p?@|E>OsuNUI?RF4z|M*&uJbt&y(FG$U zmYr~+dlcJjJ~br~Ta3J@t4>f=wcA0=o^h*t{A1lI1tTP0TRP4?4qmgZd5Exk)m0~` zs@m-!HhOSx_c-EX=NF8SxNYZ)yLG28yKSU-h@xWWIa*s(}XB3Q(n11c2!eh5B%|pZ%BZqX=3971g`!i1bZ*FNJOcm3#2^JpTds@m-!KG{CRJ&yU;tqVp-jC$|T73%Y) z&wbN8nh2_@b~}i-{rq_MIDh7U^e{r=T`v!Jj~N@yFpnmJs;b=%Vvmc?a*ufjYI*yB)-co6dEQuN;3&KO-bQfBrV^ zvD*{xYp2viP*t_tK^*_LlicIX$9~e!2#GuY^UdyY|FM^uhX|WXdg}yLRl6O;?sxvH zdn~^4O&vx^Shn-$!?K-uh>%B}psH#sKN?|~(>*M6b{HXHIng~Vb5=x^YcqnXs;!J_ zgymZIu*}(EgoNcp_pr?Q1_V`ATe;Q<%bY$ZTITF9Lc(&QdsyaN5ro|<<=Tv(s%k6O z8ey5!JuGu}7$IRf(LF44Rz#I+GlHtBtz2t_Wls07%-LatgylrfgO)ifqRO=yK~>dO zt~J6kr`@rXEOT}kAz?Yu^SNctim-d7T$>S8Rc+;3BP?_F$ip&chY=E%6I)fTtqAi_ zuFVLlsAzDRaINL)(Fd-?qRvMpAiz46Wzly=Nk}IRc+;3 zBP?^ehh@%wMo3srbPvm%mZL;exi%xHs@lr6Mp))_56iVH7$IRf(LF44E^j8Ns@lr6 zMp)*QM`@XJDkCH;C%T7aPFpjGsB&#aP*t^+YmKnX=^mDAdl(^MIng~VbG8PFR41sa z+RC*?SmtyO%bY!okg%NS9+o*PLV2)GP*t^+YmKnX=^mCj3r0v-PW0zPJIf&CQ75RX z+P)W!U8?${zDp%xInh00m#SI8fR6q%{h#-=?a65`yXM+HyYdxkYc2AXXWIVx?c49z zcKHC27$ITTSKsL#FCFrV&7$$+V>dBEf-`tCK~;JAFWh6^WfQ}rte(Mi#p0h%Q4jW< za$n0Jmuc&!2Lc&I+6Hzsw2MMZP z79s&1GZS>mGIZ?^0lKk6wPJ$}t#Ly3Ta6acwuX%1~gar3+nMX;2s)Igx zk>5s48J+{0x=NrI|frhVS$u`{o`FZU=JA;CRd=8;HH^@-6dwS#PbblJ+9 z2O}h^eOtA=3zz6Y5>zpxX5Xr0ghaJ(t9EzvAVC%LZsw8Rb>%fJUE%0gF3L_9Mto)^YZ=K1}gx= zVk9y`qS{kcJ1>4K5>%~vCRQ1v{xPC9Q!_$>`>XsqNKkeE^FQ_eczma4YaWb{sPH${8V1?WwAr7d=Q&#pluWrS-Y? zgqn9X;#xK%x2loY(g?R1Tvy(*mHzrGcY+ZT)w9wXd-L%lBP6P<)`|)wJxEYxdj|Kg{YTA%5fW7vZAB%O9wex; zy^lX>wvWm^N}J)@de&^V?5kFNEv+VPcJ@QLTNdcP3;oFxp8_#cUVXJwPx*qFQTJ?|uZcVdkWYIWhA{oX@L#-cp6Od2VNf zM782*MGe_p%IZ2)7j5Y-Do;>l`$YfTDy+5VoDmY$%BdB#aC(rS%J#eNVSDF0{K^Nv z6(c076`*E2tLev2++7k>*}mO9tOn5M`f}jP86i=vWHl!SVOV&Opo$qa_h5uXwbs_0 z*mh#jg9KH~yE$RIqPBX_c35p&Gk9BP&9=7lw(ZDj9*mH%@#aKUr}q3of+}01I$`VG zng=5!Y*eZ;p>g~M1XZ@yb`M*(*ZPAI5;iK`Lni|Hy&^#sGipvSLc&I+dt?B^`+oZm{vN=#tBxxeA;F4XN+SL|^T2U+f-1G;5objs9=_N; zc59toFhYVAJv&P^V(rWW$JPm|)Rsro6EFYz8B^6KTV6J|V1xuKdMSx8kKQ^#mD=)% zdg2qm*}7jI-#>PC!3YUf^ipafs8U-VQBQpT8Q*h{1y7t>FhYVAy_A{=s??T;PUuov zeag^|u4BTvM;45buoY*^=Js}+-HEWVJGM?xrM5hR82cfkk=p0}mcL{O!+ zJmR$PjGrCk9w(05u3&@&&)ZUJBB)YZ9&y@t+o318$1(3()x!u0p3tS#L{O!+JmR!( zn|;o6kFBO0-opq9R@+i)BB)YZ9&y@tz^n0o;*b^FwHP5`+0OesDtAo;Rcgy4h$|y`Pf3J4>I7A4%Oi+6_P&zt)p&bXm=O||SKK4&?IPA% z{-_gFsV$En7Jp(h_vjyTM28U)tdXZALLPO3Dz)Vi75a7WT&nr1oLQXGVT1&0pY~7``PdiS-n+U4ZmPZihe)sGiyI1MNS?6>ZA;A-DTQf8eRH-eGI6wd1hkxT9 z@A&ns4kILZf}K(mL6zF_i1YKue!YF6>p0}s`*#>2!4vG1MA*0*TPLVeTOM(Ke(bVo z?lI)TT|11B;CXaPO$1eH%OlRux4ZRd_t^h)uk|P!Sm>pM68*)s<%#1rM5ic zH2ed94vz=F-=4|{37$u%)I?CFwmkIim%StW_cQ!njeF#4J&cgB8i)5sycH(mFZP_* z398hVM-Z3)FfEZuk=Z94KMBb_hb%U z^OVmSkDj`=Z`e<^^6x%p_LY6Phcne1bgL(gaaGTYw@+c;Tzt$<{`r2xpNtAiX*L~^ zjF8}64~L2+KKGpc#}NVINqv)B`=Nd&h!3YViKJsss5m>$G`Id)9#;>%deaf5?rG;6I5}w%L!eXu29bj_lBBP^|`V|PB21(yS`?ED$Zj$!3YWN z`kD!s|M-^=>~SBy4r& z9`Qzsh-!tL5mc!yk05N_9@p{6*ZLVDVQWVBh*L`u)k;4js8U-VLD>GoJ#5Faf)Nsy z&)p+VEt?3c)RspOwvTcT+ec|vG#DXa>j(FUQ%e!m&MPCRQd=HD*nZGGY(Ln;2nk!& zxQE^Y@*QNS+CgRnRcgy42;0}XhwX%W7$ITvm3zcHMNI@%YRe-C+n>9K?dS_eNZ9=7 z9`R056G4^Q@(9A}4DMldhJq0iHfy^_yi+8is!U`ARcgy42&KdbN^N-rVf8EfH<~F~#j9Y1gsnw!qS!=G zrM5ic4ASawsz#MohbtJ#2%G|Xf-1G;5royL-NWkC1tTOZU%5xT2Oy%VY-a>jYRe-CtGBy{)!Ta* zAz@k6J>oq85%Q=LRH-eGAne@0J?z||hY=FC8gLK2S?4DWB6QM_5mc!yk09*)!wEYv zX){8?)+_E2Z|OA=RH-eGAnY8+J?!MCpAiza+jft5ORtHbN^N-rVdqiqVJBGqjF7P1 zy?ex4dQAjXYRe-CJ6CfLJBjNsLc(ee?h$Y4H4#*)Esr4Ve9%4YM6tsN3EL04N4%xi zL{O!+Jc6)uPWP~L&JH6aZ2##V@y?xy>SQz{s8U-VLD+e%=Bs2Uyd6eJ*sj>;u6XCJ ziJ(etc?4nS&hB9+)g4Ai*zOMR+%*wYsV$FqOV7^FJ%8Bwd4~}awwv@Er8ms|#C=6| z;+_#ysV$En>^*>f-79+!pu-3W+vB!0x5wM+BFsZ?4rByXYRe-Cd!NBQ?0tp~BP6ss zmq)ywwQ*9s9v@fMA5g!E287 zyZh*=C$8T?`iQ3oY2J1JN`v2u5fW#w*~Lf6*|QhcJV;Q*(UWDulbdepo(`SC%DqLapljpJw<&sV*Fm&xXMR+ zx%cS#-cw(=e|$G{BF9+n!3YUvyJmu_#<80?mbj{E9#@Qz;CdzdRwW6lctK~67$L#^ZvL%E zP{liv6a4Pnw>4h}BP6&Z%RNX?#VnB%jF8}tteK#Sxhp3)i?X7_`7tLLA;DTrGeH%{ zLQXJ3g0-4vf+~)fly)4kZAaX*^A7ItG()E+wx&`wyN@R+b~?TA!y?MH54^p@2nnmn zY89>;xsCRUNOgiLwQaRj5wGrix_f--|9q#P5fWA@b`PCI*c(Ddy!EqV#?}d{)RspO zhp+Q@?#c!4yhLYngAo!snbURXY|s8rIzgm5L6zF_2;!tWqLO;UhrZs!2nn5-%0m_W zltkEdEUFV!@r*TkPCaNnSujFEy(kasBlA#S|8E3UYU?_JP|u05o-7z4p}v-f^^xr+ znh2`YmPZikIeA!57L1Tk&&k93$UH=-&+7zLYRe-C^_)DcCksYMsORKiePkX@1XXIw zBM9}JJgg@RMo6fyz z$;0}{Jemlq)RspO>T7vu#%6?sdQKkJNA@f=5mc!yk08|7^01!lFhW8-ClBi*^AJ%z z=NUnj+VTiOeJu~o*o=@+&&k93$UK?|s??T85bA5QC^cgz$;0}{`aFL8Ju+W~E25pE?u*)X2bSC3$BDt+c4-#!@ja(hijYvx z>2vF&ng@RuRa&Wu$Z7!Y!AMRtT?YwXt=5n7$kx>Eq4lmJ+LLkYY89o=wbqV1HE`vO zkl@qROi-oOpggqm&Ix{Z_F&_6l#Gzz7|T6KP^F!WzLj>Y8BsDqg3n4uBob8du4hEa z2njy(8R2`JfgYraed9zq(1YgTBTn@lJqx1kj(1zndRx2j+=CGkdiF%y9S>sAg9KID z?~2H3GCmR+A)z@$gxzt=YW6eeL4qnik4^}34~{+~TGj7e-aHZ+Az>a)tB-OI5>%;< zBEPIsB#-ER@T3dOn zS7}6u&>i1^80-&5NT{zx>yGDFPJ$|X(tL)?sm5oIAu#wnd zgal^{AG;znb~A!1wdE1>m5oIAu(50PlJyZ1HpYBrh}owiQk|emZFvM?BT=V)rH#Z6 zBP48$VJ;C-jopl(N^N<>>|-O**X=eEJB*O9(c?3NaBgbB|bs_f4NxeDB507Tq{xd~x;6A=+EEx*z#zca;Zi zysq`OK3Ch`leszmUeUD09~`Iw45};xc>AzD`nuKr(YbH3Y#_os#?}d{)RspOn?I3s zugdO;M-_~a=)Uf9_xMCd^^%H6b%H9jboE$451O2G(;{Z_uuJ&cgW*k`nt?Rgk8tNIzg4%@(AMMb?y zL6zF_2x9)F^F0qfu-jP$BP3=IndKf&obYz@5MkHRRVS!YTOL7t_J{xB9$mK`Uob+V z(_ZKvzn!?Hc{CAJsV$En-gfm?n%mRP#i0cwBz`)w^W5TU}?O}w(_2-RnkJVRy);yXBs??T85PM%3>yqm>S=7S_iC3Q9 z(LF9WaFls85mc!yk03UicY$BW?{?p{hY=Fr+Plj=cH8bK+eeA8{^+U`RH-eGATE48 z{(k@;JbF$yBP1U9x9~XW7yDSvQiMGpqw54!YRe;tMXTdF4w*5!pAiy&nlj3-W9?Df z_oXDluA{e3P^Gp!f;grt-i|(^SkTW1iTA%0eLm;XIp)zsP^Gp!g4m?%SnrR0Cp_KH z2#K%%D#q?@Ti#+GO$1eH%Oi-}rXAoOUwdt2hY=Fn?(l*?g9~OnW*$uhRcgy42>p!| z%_UmDGeTm*w#~9^7QeoDL%-HaYE2o@;lxrOP}-=sB+wRH-eGAig+EfA24) zs~(=)VT8oHpZlh-8NRSgb?PR9Dz)Vi#J zs??T85G!w8;vWCK^pp-GB>s5FW$y99e%qOc2=zyuph|6d1o7~6|GSoH!JbEV7$I@| z$UEF)@t&KShY0JBMRkHIwdE1SRbzH4bgy22dU}Tu5{tKa(mnpR*E9AEijYU0ph|6d z1Tpi!d)(uka<>j6BsRKoA{H9!&&QYRe;tR~|XsJubd+vkoI9?pf(|xYmQm ztEMkP*HI^^Qd=HDd~4K+?s4u#_x3YF;yV-H;ny+qZwH%46G4^Q@(5zTL(XxJYyNUh zKO-d0y4Gu!ttr!2TOMp8s8U-VL40mRoDVL&{pJ;nkhtT~F29b}{bQD;)I?CFwmgD3 zyKs;4@!wuEl@Ss@d?2o4Z1?@PW)NY|$Cx@nmD=(M;w|_2y((|m^RymDNZfgK^vA0^ z9MGLoMWi}GmD=(MV#uGo&&%15uk2xj#K@!Ljo*p8e8W6M*ti;7C#X_e9zm@6!x8H9 z^1_!lEf^u8-K(At?OyF~R0Wah1XbMcrlg&)JnB1P65JJQPSB6nkjvRG#2#Sr>6aJ`ZdB?+qT-1H0XvBjl(*b_w$Mo4hIk`W~ds#G=5 zbqt=}mDQD}VoFpXZrOCr6s~>eof~&#{^Psa*o~jKaz;pSRqOh4z=H%;yz4o^2nnug z<2wy_kf4fvlM}Bz{VkuvFF5eJ<(wtH{!r8`XU(5yGei8ul`}$u&wn#P)ucaM=iaY9 z_r==XT{iSk&-70%xxSBi_n!~H?4RHL{%_Pq2_qz!QS)y_f~uAKPV;ZI{Y@8#M>%kJ zPrvslA3x*Yds;Vllhc=d&OcxL@00AQji0zzjF8|y(e>qk2MMY;LMw~vl#CG)+$S~@ zRB;^V-|B#;mMqtkGi?5~-K;r$>fNLL${%~?i?u6fgaoSzxd#cVc-QmmV1xv#3C#pm z?3QlAqMOyPjdni6N8&$UTu{4mMo6%(m3xq&YQl{t`kf3Vc{m=29-SUx- z_T>a4B)H;iCaBu{%rCpg{j2n^0plmGgAo#3aW)fFaR$!`Mo4hQ*-TKyc|IqYU%9*A zAlDieSI!6t?%OjD`#+wn&)ZbpefBOs``qx*{My}Rgar5Pxd#cVUVJ_NW$|H$UsLm- zihK2Df)Ntjh3DUj1XbUD^$wpI4nMiK_N^Ep!CiRnL4qpg;GAHD1b5*Xkw{R*Oq~;4 zCver@yk=m81lRMq2MMZ1AMsUxYKQDUygMftA;I;0GeOnXOJ=*rUyuDr&4UpV`AR=r z;)x<~mD=Ey`?q3*1ka{2q9j3;))Ml_)+O%22nn9CWmjI3ph{~Zd1UJ= z_n?aBgUtjZB-H2fh;vT+Ugbcalb}lDO@vm1*}Y1Pkl;ydcI6pC6~|ld!3YVSC^r*S zaa3kRsr`qpP5NE>kl=Y_GeH$ceokoBrz_NY zkTpxKANBd*e$cR(85kkKs%q{*f-3Dr<&o`ceY9)0t%&yFtlVjBr_Z%-&pj9+!P;Uo zL6z31^2k=N{;e1x!5V4qL4qpY^_*aYgjUP?R#6cSCi;T}RqUJGgL5tGaEKRXw zRk6_Ls*Wm^tBzVr95hZ^YRh-8%A~8aO=k?75Rh;c|LRC&(hbpE#6IOjrpR2-} z6O54HsdYwpwRYflQN_ES5s48JJbiB_sAAvbg!WPTR@#&C^i_K}eLh%wH7uT5Mo92{ zIQJkymFm9o$ZE*`L@`2w=iIpm398t$Il%}Cp4T@MRI&eaLVGn`q4s?|uhl+LpJ%&N zzj8)M@I*QHAVC#-HYXS%!ISZ3f-3fZPB2^YWVAVRGD3o9x48!isCFUH?0-9n+j5tVxK%IhoxQ)yT^LuK_Wso)8;dBH44c_ugamhF zK}_7|lCC;I6<5wF{e9GxdIO?7bDuLhjF8akT>H=18&pK96I5|MpVB@Depzool&g=N z+hK$R>!pK4suNUkCzH~=C;b0Gm$td_f(|1jSYZuf;yy#W>I7BXk=frK=)cR~PWb2% zC)wKx>-T*mSXFN(sNz~XrG=A6_&oCSeLvD+gaqsG%>-540i^WHm-cp#vus2%LW1Wa z%>-4<^C|s)`myfuw%)beMU&|6fg*TK6>i}Rm|G|Twn6I5~aVc%-bJKW>c zqxScI!J|B(H4X{ZmYWHxm{IM0>Q%q;=lnhWpDq|7!Afy6K^60SN-I|MxW~{-&Mz1t z!Afy6K^1eC{pIhQC;OXc3)^!GMo6$y9EA19!a6|}bFhu}>J98)+8fx6kWijipT};y ziJ*!r1N)m{`@N(bm3j~TSiuMho;n4gv0EpoVr?L$@zW=Cl%5`bn0pkT8eT9$g6CAt1XbMW+j}x6p5h)GO~0*&5fVJ73PNj!Izbg{9QF?6 zZ~R|WrSsPgu{W33*F{KZ_o{mp?=y(7an)NVsN#M%rLOD!|G8YgyZ50LjF8}YLJ)Qx z3+n_`+_$IHbJJ&an1*&rZq+s<`4z>3;yvieNJU literal 0 HcmV?d00001 diff --git a/twil_description/meshes/chassis.stl b/twil_description/meshes/chassis.stl new file mode 100644 index 0000000000000000000000000000000000000000..57c9257cde5ca392205079e83748351ce5c9e928 GIT binary patch literal 153284 zcmb@v3)F2#RV92-BD8c%cuIJ*8LX;4KCZGu+2(;QL5+Z~O z3516xHrg#=Ade*A0~A7#hMauo2)`(UmuUj1yg@MCHXs-R2sHd_uC-?ES$o&MH~$#_ z8RWZ*v*xT>t6saRcI~qli~oN=-?&XpuPhd2_3gVnb#uJxBuRq_rLF?&C4&l z>{{4Qx%StqT^VMS)xG}Hdhd>ZcJUIZkN@ojjeV=j|C@i`GJg4a_uJh0gU@ykG(K|Y zCszB|vmVhhJXcq~=NY?SKL5XOpz+-|uXjz)?T7u-Lr#3_vo3SHYB)nZ$~fx1ha!h9 z!>DBi&li5?c=sTV*L>qMUJCgB@*g>OhCz=qVDtN$tExedqULj@kzf4Dzu!Iem6v)> zG^SQVJ<7QMWgp$W{|kfdj1s)EQih`NJ##x{(4!34{611w4SEy>4VL;;gC1qTX5Cbc zf*RDc6s0v=8D^B#@BHLtOKagLqFsSO+x}gi_{&G_$M-EmJ<3Si`^rHXj!NwgLp_@A zUG93>^2gutt`0*z%J}xa|F%5r-~6t(<2G07Q3mWu>3Ug>8ALtxw=P-IZZ+)xE$?>I zFL-;sYWwZo%bp)LG}sm@qo6)s@Vuj!^j!Ri2QQy;(|>mM`>*?+<&CF2Vd#T~#;2^* zql`yA@Ozifv8GdwJ)#{*04jcU<+on}7eV7kgUQ|MQ>h-Tg(s>$YA++gzz<%&>V$Cs)dVP1O9=Sv|`5 zoqODI?}qbU*3nRgqIAB}#_^XAK4il&5%$mjOq7C_NXx*Sime3mHnp#L-UEhQmEe^X zQ1smP1E*|W|JyNgYD)7OV}{M=IvSc*&iWjMn3%&>Lp{nk;`n1~iOe$;rDZr}uymD? zbJQV@q?MJXr6_#Qx^Zv`N?D!vxJzn;zjccjZhq$f`2kN?>n4*AqSpt@L>YVk{TZ8| z`mLCw&NCFHHQO?-+CF=8{Qfr_jycZJKlYr>AK&4+YhZ(6vz*Q>Lp{p)`zM^gIr8XZ z*3;RNGFntIy_4q|CnBw6>_`qzm}=PAThlt``j^$bt9Bc?dX#bYD}H}-t9v}8z1A8v z`UlHIQAmmPG}WL-8Q-|-ziwW7={sjM$WWBF9@i+LR92aHFRMFVS5OCDRvDjvKh2fJ zF=1pGI(wd>D6N~8q4klu@_N>iZW-!P#*?0WL2Z?lQBWVsP?W{C0kXCdL*r9c>QTlI zzxslf5rh##QCjK=_J3-wymXb3dY!hbX(>u;v(?DaV2KE`W$ePvmgsiNP>(XQjU9xc zsGHZWl#wleMuRO;QCcEx9C-!s$n%QhHol+i8W`2q2I5i1%U}Pbo54^NQnJ3;i9!~sd;!uw=a-8pIC__=&dRh%!y;zEQCG&K3uf`dcBYfgIXxBSO zDLdySom}PY&ONy^;r6Fral2h=N9ysntkg4RaL=h_C@S|(s>Xy-5C=5qQAW(Wltv)ac1fZb|MdfO#Wq`ze2KOi< zcM}GNp+iH{QdF*~T83+=M;W^7RLe--T?VEQ=*e zb+tWVp#E*;-C^XuhEud1%7D!gyww;ph|1lT&h2So_woG$qeR}y>Kl)`@8;Wgxr2Ma=4kL6 zpT3XThjke0QHE;Q$W5oL#tcRd?c?rx&p`t;XQ)Thox}l#ecCvHvb&3um;xJrV`j-{ zm4R}5!pr_`n=9AQXcdLJVM?urdX({nzqo(R;XFf8|Me?BQR}HP3L?M5FCJZM3MiJS zwwTH=BUUV|17$$3X(dT(8H&<2)@o>eHHTUvEkiwH26I~(g>kUlHQE;(|D;+XEkixZ zxb+`Bsg_%1m|^#dBrTxWS2VXRLp{p)v%fp%X4JW&u)bn^t%iD(@!@lSX{PNeLs5Ar zzSG(-f5g*jndnMy|J$E7EnP1w^(aHN+c?GyMhk70bjwhWrrV99pawM#pxDAShpmQs zl!0<<#$8JvpLXr6C~aebjlXS=QU+?1Ihm{p`H$7&;YHV2KDYeW@I+v>>*mrqG-1o>QM%4Ysaky zWL9GaQTU$rRD&K(H|-N^eIzY3Mhr)##yrD4nl9|gxLe~ejmjV@d|y{c0P@q z=_(2-acIv5Jvjq(l%|x)`#-IQGIDM=Xe6y=C<+?=9;K+90oGjg z8JdeJ7adX$m# zm7%OMYjp@EXp$?-(&?x4BXet};aBwX4-IYK(9_l#WVM4YoK< z7dC75zzm|GL3_%eN7GHaGXv1H6qVo4Gu)#L*cRXJ>{YEYh|02>VGyP1!tT!iG%ZEV z?i6h$@-^CVmK$y4cHNZj7U^c4ufbM3Yj(tt6OC&*tG3R05ZcvI|y`^sY4+{ak5UV~srZG~~*}ikB`u z%7AV6yj-u%6*QDVl$?4B4T~C|vPB$3$+>5biQfk{{zh5RqYODsHN;U^x@0J7k}F6! zL-yF$vRm)1#9C#iCCXgAVHkS(xFf!UQ^liP$u2otBKjR$qT9$2KV>U(^@bt4^@E1d z%2xKH*RoIT8k3gj3~11!47rat(olw?1gDbxK@k6{?154J<34M z=H1r=Fcc;CQb)N`kM>~Ij#6S-sb|b!Z+2|4zxH3Wc18#`QF4}I6o=fSTf?>y)k{>) zPmCD28W1Jt85*|dD*u$NrmGA&KQYo!hN9+kg?R#_g`MYF)^h)Aq@mYvIaAcXo}+-b zn7vSA%*ZF7MjFb1O_b)gEi3gXL++l9G?bwzErnJiXZn6El5=EhIa4&!u;_U*b1kPo z*GP%;IoBxm*Z#wpI4~3?rvgVBny#EloocucG&EghU|03k&;R^A>&Vb$C@NFx%m5T6 zd%et6hoNaHL(W-_B3DL>@-oC(&JiO^*FAF1?q=pn8FFH8q@lS|6u#&6F$>oJiTa>N z8FG#=G)nMVhN84pM&e{>fyxqpy6?34SHHxYrYc7l6E^v2|*wZO-p;KYF7qGEGySghHB3< z6qPNe&6R7YM;YBXoROomuVui{xIk;CSiQ}${`ai~Wby0VN2;&0h1Ls9Z<&PYQ&%7D$4rKet~AO&c@iPF_;Wth>fYn74ntB!`Ir6^tFwi-EC_q1|t z;I{5-IHLrwuDl$TYc;o#L$>KwLp{pKwV|`;8Hz$m2d@uhsft2O`Q+rNM(WlZP;OG>E;UC$3g7{8G`>~v+&``+qE)s zt=`d4hN9+kr5)L;w*@*~+uwYkBIMyHTAP0NNF2+se@0&stUmtzFkk zx(3u$UuBpPYc;NMlmTsiKhIDUG;$Al)OOXQ4A|BScI!;WVu*Rkm_Zb-AAJqEC%Be7 zioTyLJ*|dPe4m;gWyn3xQ5?8hvOeU#>RRsIju`5JM*cpB=ZY!SEFt)2_goor4>~kT z@LGnVu$t^^s7D!cXMCig9=S*FYv+S&C_~N%jLJ%Lr6_#QdTPr`J<5=~nH>$Lr6{@2 zIWVk*%T_(w##DPgSIR)^q4qpOQF_m!WvE9Pu=`ieF@vbwLFkNd>d|yz=hL#IR)RYU zdIy6V=(SDcRLE19;e)T0dO**V*TtcnyR zcdCb6d7Z0A?rl%kYMHfmt)`6mey(vSO4p)otVtZ?Ir5%9y`*rwm2uy~!GRL4C;69BVCw9J@M^t4A4HB2~kTI`{Fk6a~8< zxq6hL@wFPtP*mET5l%hIupCYAzIq(WP?XNK+g#;U-y_dCgWK7rJ9VxeW#p`;QylmcUdUY@`n zjST8hhPLUp29=?xyi&KhDroIm?pkhIPpyV}l%XXu&rnp_oz|`%Wn{lO2t!fXANQu? zm3owce#0@pjYAoV(vvDJLp{oX&H3Dc8AKr^+EWHSny&7)Iim!xY;}!1&XtW6L+OHH z|HV!bJ<8B>i`3(9%TQF>Lm#yChxx8)xJMaU|E-3mr6}0!U6o-v?bxo2`ChAODQdn) z<;>FiTFyn?&N=E3d1ftU8H_yVzRt)QfZH_=Gs;#yIcIQ`_RW@|o-t!mR<5B8*hJ}7 zqSa83GUi8Wo#|)!cuD(}Q#wd}C_`(rn=4OCQCgcVL+c>tiM0k< z(k(+vR2eyw9a>2VUY)(VM^T8Wuc01gwHc>iOwi@agGsvE2fK8OH09uB6lrewmMH!01_dL}z)u2Zi^7Q(s zm1tUu!nKPjwHoRfGwlB0vOkkyT3{2U=ZhALD=$5Fd;i-$V+l1qks$VtoIBWAEY5uV zY1_>QZ;fB3Txi=Bdq-NOG5+e3Ki@pyj9+nvmXFvw5|c3=_@`&C?)&90B3DIE7>d0k zrwxtqvu}L%>YESV?+jfvioGK%$bsSK74%+#*gG;O8sfld#zp4WcLBxT$(ZoHF|w?j zp?AZ@-jVy<#>o2cTbNe}fnlp(h7U*(RMX($6DCp|L^)40(z zE=Ub!h`p8_Z_`kQdS)1=@nzGvFg27R_FDGHO+y*#nPHfQeYSsl^%-7P$`IS{6*a$3 zSsAzj&@;m@jSqkKyPMCYhBCzFsmW|t%Fq#DhG7~xCVCvo5PL1-iZNb){Yjfku0PKi z;^D~Ytv$#2%#||KBW&L(9L|?K+cbVBHIyOtI z*ZQ==Vj+x$pmr1`_ReDQxsQEq_ul)?hsHuZVz1ltC1l*@-4A-Lpmr1`wrM>7>6a`o z`rI>ILp@@z^*qZwLs4Rz#{TlLX~7r#vM{a8Dg*HtU+pk zai7m#dc+KB#5n8J`>)>i>f@t6{VmBv8<{5gvL~PUePuD+v^^kp+yM}ti z=F>cTF$UYRfN7BN`JZ^q zk?I*U@?8*v#;!45rwrIcB^!GjgT^i*SI-Q?G&1rDL)a|c)KEs2sC#A@rXgzs)`v5M z%~q1D?QA7W#F6z357z^Z$`<3_*OurE^$447H#M@gPZ+{xA50BpWG`~h48tOqb<{!` zVsk86qIX#wHu@~zbJz-z=V$;A#}Y@$lU6$|Lp{PCJ?FJFjgwMC8Deu3b!|Jymy8#F z^%eVPP$Nc;yBxmHPjJ zt9ZAMrzPofM&|4~TbeL(e&r~!t*mkm=M43T&6#CtkYQKOBLu~nrK55-2-`GrF6tWU z5u5Yf)R<%BOx96in?}y5T|+%$bKai0Qbx|g-7~|mI?uI%YbZl(u0K*k8M%UR&kVyf zbl*oAVsjmZl#G$xuI@5d%E;B$ff%M?AFKymLm6Uom6{sL$W^0zW*DZC zYiHL`hS*%ur-m|eh3%dhhH2y;fNLm2Z0<~?hB9)ez&$ez(|Droemv!!N4bVF#MUSM zcUp!#Ke#i)Fpa00##yPM46(Ttr{e~}u>5F0b(4F-f5+mS0W z)HA~vG%(XI$`G4zT-#_kBhz)y3}Yy(2}9T{-MvA>O4k{>S3JWo4cT=r$`G5a1RBQp z!b6|A`qYINE$@Ej_wScy;&$-d-K(E}_G^F=d#5tIywxN2TAvIY7^ZQhpmr1`wrQMl z$g!)J-tyQj>Qp^quk{JXd4{6IHjTGi)L(h%GhIVHVq5v>bE$KT7F8LhamYm%ZEgsS zA}I4z6rVEAXJ5&<%b72}m!R~$GRm-&uC;Rd(L=nfiab->F!br%fw9l(Tp5ZI+cd0| zY^{}`&Wn1)UgP=U7hQA9eYIUV1MNysJBku}(C`sXJz}pjrF;T3bA`5hrJ(f9K*|`( z%C8@iR>Q~=!TVppwNfusXj&P?naWs%_tAOLPrE zHH>V>sWHb;l-QP1_CeQBkJ#+zSs!zZ?6r;(+cY@(NIwUPBZD(!#8?O8bJlag$kPHo zTIzXfu}$MkHp2bSXuAvbh`r7`{5d9)@$aoZ1hu0mu}$NeTOPZ*PxL|0m7OW@TnTEO zCkIkvj-e>AP2=kp_5aTCN2s?}O?Q+v_8Lk8tfR5oI-DpxlTO+cd0|paz|x94pO?W)T_ z{Szg2Xe_Cr9J(QLADD{ZlJfrF@5oNVPyAqVw2m3k7Fm2PwI(H5A zi0$o)BhkRHI=@0t-mZv3TS(h9vhBKtdc^kr!5q#r(2j``JIV@u&^6Q}w)bIfkOdHjVLkWi8G%1jYW58f0+1 zA|uZMo_$-XIafL&?lHHu}vd;R2{FFD?xEyk{V=iydnd= zmZz@8HVvymtkt~E)g!i!K2}y_V7$UCjP;STFwcqDrjcW!k5}puoAbnsV~&xtK1Ydd z8spU+M;}3PzMC3zjGVnXN^H~6(MLUEbKagBbBvr{J4)=(z)T%r6z#zIhB z4>~GWdazA{qYti8>Jgjk+SDKegmIzv5TbDtqKtX*{(XeAug#Ey2gq=tIL=6=bb(Pf~ubG#Be+Eue2WQ2m^zRyrr zU51P+%7{9z%k2j1ov8*rGmI#!!hQ%; zGIr#--HFDaBaF2&#Ex9mwyPeoU61j3`VE7g8Ag=VEF;;jVf}n4tA;@jG&+o-tiUQj zCBw^ywtVlA53#5RxYYd!4_3H`F;93qkEDO6)>BTLs&Vw(m>AE^(ILr`n;)n5)B z7#y#x2A$EOD#J8n^eKWePerkRWE{dUP(`tSI4WCyYG;o^-Vq1wMLr0$p1G&l;YIQTmP?XrFkt4PDLG_63 z^f{QOqpWLmTP7>pTCl`@XlFks4%t;}(m@|mY z|BsmF7>c4D8o9IW*K_sIM!J7czHd3St2u_EXorUObM??>97F$@V<1;V(GHEnY##dl zoL{MjHZ)LfLq8|u8@DKj6NR)CMLRS&ieey95ACRfW+VdCKfWVXM<28?j$LGj2JzNC zR_aj(dI3tIVH7ZoU0Wj9XnjD9+H@5uEA=P?C4wG2)li0_v~N}cGs>!0x=5Gx-)J~P zJz5Ig$R`X%X%45kVuZ@jacrKUsM*N3%sW~J%MCUe*1V5$mSLk+iZMdFl*6 zbK7btLs6{FsfK!#(bnL2WUzj>%vO!^S!TL!$M@q|22f*0mQ}Ln7>c4DDdm;Z=RWG8 zja+3MsWHb;6z$N+8Gz5*)k7N^S%#@W2InQ#517Q)I*zb*qE3aWXQb4 zHIOT!Xop75$m+ZVD0qm12FlG^Xle+<=Ott)igswoETgE0HZ&|owBytehR;i&9%(5m z?D&2>%RpLVMz-VBm}4l4cBGV7PLvg|gRVgo;>d9@pE_so8bnLv*hO||5N}=3=OsibgMGeX6flhKtr{Mr%XZ9`-!Kdu z^Ae(zfpTM8sCjY?O-oVi!BY*^0dvKeSpQRodbE7Hk$W7R~ z4P&($Y$chljG~b~{FX3pQjQKb;Ek&_5ryA-} zMq7h;=8n4`cy{T?qu;U8|l9Py652ynW;ert{+4pEk)4|4V@O9+x3`{HJch_psbY9qP#75N{dCdL})+;tt35RBaUpLsWHb;6zz!P z*0u-m$+&lC_gK8Oy9RA&ob&ke(5_O0474kvkd~rohX#6+<;>?L>Y)vdv!45`&6nT$ zgu`LSNkA}ARzx8!MZrGx;-A^qXe>W<;Vmy$k1{f)oknAccBKqO(GHD_-20$Y*KZj}as6XdT`{j1?ZFm2GTC^+H1#On1!4Uf}GCFP1(v znpPrg|GqNJC@XF4spqIHk(S{a%21T{%~qpVy2zE*Y|BuOmO?jjk3$)X(j2xL>QRP{ zWAh9}%|>qTypL-XS_8`sHW{^*6a-=a+p?_SK}_s-no^UiMnf5luhD=EHGIrqodea? z@LZ`!8J3!ld{rZ}hIdX5kt<3|p~m4F>B-(X^di>HRHO9_j8>ajLgdO&lwRR#uFSyv zYPhB5X0hweS&m?v&-{f1X8&EBPb^;cfK`_sR7rhi{GifOFUvjhY7-Hv;a z+gI(pX!mXRe~H_bVMc)l(sfVjk-cXcEyFbw1si9|pl2F;^BP1w>UMu~Ls42Hg8~^WMP*=pWxuf0 z)<@MKLs42!t%la~_7fM@mhqBDp1VBi^xF;^C3v`=52c8f!TKMSdX*_F^(X_YuznoM zP}EZnUoOA&ic^PNrAk?;M;YC=Ypj;hq8_+>{hyrD(Lh$KN7r)9q zzkBi}%eU`-zuRXoFI`^zw&PEnMy{S`{l;%C-+#{8yFh75HCF{?r5*M~9`rSY{I z>QP3we;Bo_l%XiC|El4PhkgC2%YC2Tw}~iPV4KXUowuY72JKXA&b^$ZNOg`3{` z=ng|`EnB;{tN9viJ>J?6(h^(7kgLDG=z`^GAG)d2N?OmrXiG#RHyc-dk1%H$Zs)aj zh`a==Ue(<5hsXaIW`J(z^{T^Ak23P=(=tpa?gH5LuB%~lhL&L&E33T9Oc>o7bPZ)F zDrbX(Mg(petw&qNP|^vuEFo88hF$wuYnVl~8qP4jc!qRyens{mgB_5{P*l#fS`7o^ zisSQ7_vC!X?Ma=dN?jFA7&&w5XlPoB(j3+xJXh*bM$YGEG+3gFnvWbBKlGp%d0L15 z{-5vu>bEX-TXQ?j6=Zc4>S;5n zL1(B(8P*myWP9X>#;2@Q!`kkiwDzhO*!b&pUOi(5+rm5pxgttSx-trKW&dx(u@4OP zVCy#&M2{XRdD7B}=znecI9mqd-H; zT^Yz#f6icI)E+f#jM}pmw(DtaW`_Kqwmy_$?hUWn^9)64Zd=C4Q`1GMGl%mGMWJ*V zpEFAE+B!!Ztmn2i2bGANb*l`NVZR17Ek)hD(p83CeXLbR{SSFUooiZ((weP|0*1}J zHZm8j?bT*#o5>u`8Lek%yEYrF>{dftU)#b*Ez#1)$Jc|kjgA>C^}qr?W@x{&ne%2c zr*=l`8RBS5B+|FPo-6Dd$NJn>UUnZi*5|3`s}~^oi8w63?oo!V!YrlU`drge6!w#w z^?3=Eva)s5hAS*vbJTQgg|y+CiaEl+Wu+cv*qT9N0u=Z$Ls7Ou-psC@t4A4@S}ns! z-2Ymx+O!6gt@P2ZhSDu$w4Q;XWf)j8Qr*`znJc$##k%2&wPmPB8Ch=aYP+DUl%XiC zr&dEf%D`O??!3%16s5K449gKdZLVxpyy041OC+%I7j4%|)XPU1lYU-$3`J$j&(-9h zQda6whW22`R}Ez-D*H-XA4ZKn$h|(>liLitb>8QPc9j`xd#y5T=Wf&Nq;?sKYFj9> z6BKCp6>^C^fV^_Log=v0j;)Nm0#p?HM2_&|g2 z{;e|rFHvQf6Z6N8#waa8-JF)F>E?{HqoHG8i+bROy#V>=r|log$m{Nm2GdfM?c8r> z_w=hr8QnTBDBV#_VbCpVsG8AQZ{x-Z<=-?8RvQm#S?9Sg_ z|Nfw@2XTkj^R9O)m7N(1DbC@#4BqXnjKY@4o`ZCWn$Hzb96!w76}!DBZ0X}uXO^C; z5o4FyfsMaY22r_=_LLl3$WRY7$hdj;wiT7D@IeC-rW1F=c^6q3c1QWd$$e*#{Qfx^ ziqgB*NS>d{*kEi&{d1?FyXG{S?=#e$0%gGFnE<9AacEkKLd{yaxwbP(@M?Y3Tru4& z>4A|#EkjYzuokly`_~3sxN@l$P0k)&w?61U(q`P#absU{n-r^e&*-A1lM^0v|gel&4$ZQ3m^CWdtEK z{Co*KJS{S2C)odqTrnrg_}XPZ`C6Q3>1x!xD{4Mhym}!mUQ1x3X8UEO9%XQBpXN## zio*A}GE5nq!@SVQ75HRvC)otfn%8Fv=C@i9oe_33mwyO)iW4cYM{S|X*z*RtY8W%P zPN*8-6y!=7isJ0GVSuz%k21P-?i$KyQ85djYM?D)PR%&5LJHJShL)N56qYU-+7h{9 zZ8V(GdWLl8>x26VNQ?Unu(@N=XjtCLRz1q#uE>;OEbIua;o<5&P;pi3F$Rw^c#S$R zLs7iKO&RJ*#tD)uA6KF>;x9&@p+uFDIozolRu}lR3`J>Q32gi=TlFX-%W%+0TG?t1 zYTa;8uI8#T)T0dU8XlO@qGC^O%Fz5OgL{AnW++Naq%AAd2kvtqE$;P3x%ShW#ax@yoDO;Z87&A17t%fobWwxJ_nQBCU&3hF=dEwz`49iT#$kr{+Uh|ZWI$uE2TsdS6yj^HI3N{h z*ocGYKV02L96bL~bJ)~i%6Mz9rK=1BEO`x1u>aFC6m|1TR~aZP=CIY!v=pT^8`%k- z?;6zlKpd=twxkD@h=b*>43y!dbdA_D6s2u?P#}Zlt_-`DSp7$*!l&x6( z8I!4odX!N*6_Ajo&OQe-oXSef;<91-l$g$QvIcmFY`=yxS zbQtPUMqXSwo-5;vXJF*KWEigujZdA)cv_0eIm)0>oL~%X897g=?0%hV`%y;D zI0lW7Fb!oWN^_WC|EJEDJVIsUJZMIPR|7>&BCom16{M%7cNaCc(_FDk#*F@bHBAdP zQFd3(pC+I7^HD#jJy?4|6jJ1^?H~4CWvF%=ho+?{ySwO5$k$vIYN$sU^Kk&h`Y^lR zS5vm9UNzJ+V$9#c!uo^lwW4xAU}z;(Lp{(?HtQy0j=y!+plT3>lz6Xr%Af}tWLS&w z-%hBdo3zj%Ls5DUx@r{k^NeGIv@$1d>*~HT%qUy+D8p>r!FKim85K3Zc2QKJFPY(2fU2)zEuIb_Lk5 z<)__Yw4Q+hy@8zq_K(kZk#5ZuQOW3Ns7KQ^8tn>IsATjtfMTvHqkA3nING#^ zt6DNT8m(tw%+K_dp{RDna{D*_?Dnds-3}*l7kUSjHcmJ3j%l29I`PY2+?@EQXF5aA zV$cSPCoY2Vj}P9zdGs5f?F{YPw1HwjuZ(3fik>5(4V1Cvw_Yq)%gj~L5t%j^9Kl1w zB41_XMdzQif#NJP7+1ab%Dv~@`?KgEmlT)7V=K4P~gO#|Vwz zH;q@OhB9aa#U0Pk=rI(fb}&Bj#&<9O`ogDrS!r6d!O%U~#e$3<{OU2UBMNCLigsvR z`@vhU&U*Z5uAv^<(9oUY#e$5xng&rwOHs5#_G|oy5WzYtSyHpVe8CU(@9~{v`O&QNW>7lDH z-Eg>pk*n*kK4W#O#lkhzLmL|HuHhU*QM5y2=Zs%jZ7=zA|J_0L z(1r&0vZf66^cY|-7Q3eL=G0IIZJ@Yg5gN)+Pmd8A4=|0tN)2Vu28#O+p+Uw)kNC#^ z9%{Y)vd zcE5y-!@l~K{X`)xMbQq8d+$4c^|_CIZ5JBqp$!e)pII#C7>c4D8W(-;8LJDPeu>ro zVxb<|&_JmVzrCXj_4F8EFBZ=?jq_4N8MJ}oj$Y(S8S3dVLgRT4KWFuZ=X}iLPzG(F zxKk7w%1}>_5gIQtjZ0HQ8MJ|F=M2hFPmd8AGB3f5to~{hZJ;Qsi~n1+CXuiDN0uvt!LON;`gC(!g~%|{nQ_w z%R5SBh{k}K9y26_Ml;m*C|6$#+F}PG!18DuBxZU z2n}81Xj-&^vQm)U4=ddb>w_LdNE-|*Y2Q1E$d#d<9wTyfvT3kgDT6jp)?(zTEoG>u z#|RBw4=RH;P}cJOS+ZbQkJ_>i(t`+T17*FdKJ94lq7#OCdW_JpkzvcRL>aV!vQeTw zkGEJTLp?o4XxIq1<(Q}p+JVw14wYdeXMGm2#|XBK)LV}2%AgIDjoR`&uQFQCaJHJ? zhlcI}(1ZG*4U}Dd{Hfny*i~)I>mWT~&<4t`aJ~l=ZC4rU=`ljXuFhLt&y_(ND7#YE z=j#`X9z#)TN3Lv^u{}TMC7Kp(Fl<)izaRkHXEI%eqG*SP&B(T#!>NZh(zW@V|9U}a z%rO*2J2Y%`+vZ%fsE0PvwHc>B-5(lc*j)5VqL7xNXorT)kheLfF6yC;bZzGB&(wzo z88)YWEm25IQM5zj#4~U;PxChW<1lx8Ewz9@4)YD^xhV6@Pa$mG4gEmmM<0-!`rVRD; z7@;9M!bKUh12ydR`ul4)c!v~bmUdsZ{<@U?-;JCXbUW(9-Y2}oo2|gGk9Y=#-7)oF zfeJk`?i}wXuM9=e4h?%F^os9sR}XEZYv%*}ccVgMj-e>pp>dOFTQDMjT_RcW0L}(QIZ-djgV+LC25Qi{~ zFfbHFJ5sVYnQif(p^JKGBMv*M;J+0XF$u%_2h@?4qG*SP)!^2m-#|k>w2`izpV%AP z6&WZiqL7xNXlERz!M3X&+Khu|hwV+{$*{J&pD4yb6trQdMwHbGMXMg#&_KBjCw{Z6 zCJaT<4vnlqXQ+pE)WI;WOvfv$k7cCg^}i$or+4Cejy{OPK4@1HMz+volfm(d3`Nln zjq&KiToHv_Wq(YKIfkNWhenPJzMrTb+R(@mBQ?lCyCMo{DT;Pzth(p$fpSCNjQSssS7a!Pc4&;pEB14uB3&Jc-fmZduh>lEaEpVd)g!IpjJRDW{JeO4 zZ*MYN-caXP>KPb%UVO1218rB+QWWjbus5=;e$?JghGwW9+K8h)modjs6z$N+_mX*? ztA{o;^c+ZiFWK@ii-Rbnr6}5shL2b3p)GNo5Ou@1rJ2SRL?Nxza}@2+$jG-SEA`Mu zx>;^{E_{xmDB7WsHRu}Zp&fbm`cDlq&_9TZv=kL~e4i~58YNrF&Y01jbtl8xF58te z6h%8yI^~dKw=d24m3n9+4n4EKSO{Z56w*=@?a;`#BKmlx9@@~*lk48D@aDx0+7(eq zOHs5N4R5>Zp)GM-6LpihLfgH9D2c;Sshz)un2~!QR1a;Wn@Im?aY=lEgght7BHDTDu=P89A8F?M_bdi>#XorT4)LXj_x`ujaBV8NkQL|Ye z!oZcY#-S+Mp`qiIdT2w#u0;Mj!Vw1{L4{eFVN1{3=`glbY(n>u? z(GHD_e1&$U9@@~z63Ovuj-e>pp^-J{8tS1Pvz`9!?Ozdvv=l`ZlC1NY& z)R@rt`q%E)%S481vqqG*T4c=Tbe zh(fyAH&bJdp(xs+kt2g&qtrti8aZO51{o+TqL7xNXlEQTCi?tJJ+v7I_Bf)fbpMJd zqy;^qXs5<#ypsKr%0Rhc=Or~}7>c4D8sqVbyEsHey2Ep2)A5Q7w31<$E9}tV=wpaN zRCoqPw&RS0431aa@lq7+NJ&N?dyo6@UQ61DBl}}&2*bxK#-S+Mp^;+=>fFaG)(270 z$T5cX5o5^)`&UFEEk)4|jU3^;?W%`1D5)D0OZE25AV^oXJz8spIis4)ZOhQ1jZ za|}h%4h@bzR#v%cG2E*AD|7oM;4c@&=|L%RGv*?{`*`wk3vMvVIG znxk<=^UoN?-$Um2)bQtO8wNF$!DrVTSS(l2DM(9D{tHAI$K;u~&>I=93$nO7r+4-KU zfBUCpdHKcfUElZ3pRkbvyDHZ;cJx7G?2$oKcm~G*dhPk1Qe{*PWl#?&+M&H(UAH{^ zlfN{{6;WUu|GzI-{+Cn#DEDgS7>c4D8n0h2R}VPp-mak@+R(6ftXnB?KWL7jDB7X% zs&jvBb;eJ=(y!<0p$(1g&V|d*fA_w*t2W0_6z$Ns#bxKOK6$&3_%jXap$(0f{@{hn z6E0ii{=*zYQM5zj{q{W0?d;enTB3SrL*oTcdEWB-c3zSia|}h%4voh?>&~l7@AfFy zP!DZryzpl)SpM>zH>oklP!#RZ_}zazW%>DY&T|d*(1u2~(A1b?v?y=+JE8IEe>`RL znbaUEJb{A7SAOm}5(gP~x>Y$`8H%DEDgEDb@4US(%St`8p>gAn{-)Fi8F#wX;&P&p zmZE5f#@Fo3-S2((yFO=74{d0C{JLjJyP9Jtigsvx-A11G-7(s(dT2xAf)_qZ`Ue>n z$KgaFEk)4|jdRZZwe4Gu^FCPALmL|BJpMfC=VX}1KBAD8qG*T4N0-a(Au*QNnTbei z%=n%AK3m2sVc4$0z)%$J(6AA1lVf604{gNJj=REG5QVf9MLRTPY%l7e4UKG}d1b(e z5TCN@#i4qkLA<52>a|3mv}P;5fYGWC{f;?oG@Q|T28L=^4KrE|UU4Gbf!$^J2%rpJ zOPXA%hBFk!E5nqb`PK4i;~Vl-R_alPw&?+n$d#cet=X2r(HZ&WC<>cbhG`t?QAXBm zj-rD~St&zNyuwX2TF+2xlhQ4rQ?{%%ZQ)|))xgk|!CC`K+0+QOGSs6C##9-RDVr-Q zLs2ZZDI-y9cvzc(ic*+mc!bK}h;d+sqS#6rhLu;@>NSJy7$~;NhJhm6sz(`G3Rz6{ z)tI3uw&STr>lw9+M$^EIkLWw1?8bERo1ifwwrsPB*Z@VSpz@#z}a zA3gU_f940a=gGs7D$06s7-4+LWQW;WJMMO2&6Pa|=}-D2SLg-IZCiut88be1>YdtLSuD{9 znHJbYX^FHN>QRP04eGz@IjuouC`!w%YIv^n>TFLR`md}qa$dD7!;E$;QHDK5>Azt* z%@y*_v=pUfIMrZTDTBWUQ8g?EeA?1gl-6uO{jV`}TtZHG1<2eUWQ0?OJtgSBPhE2r z5<^*eT8gq~BK>!38%9AK>aiy^{g-Zmn&isR_|*Dv4P{*RnM-D70GgJfv@JyH@i(r{ zfAY;=-XJITe4PL4K5VqN{#8vq%CIN+T1E03YfSb8pTCo!(Qt-(l#wH9Cs)c)ls&cQ?;)rfmOei5Mo-&`_q6Pp zIDc;fP|6N${PlNd;tJVi;Q7I-k+hb9bcveesxorb;Az3;+5p!m=GMU_D8<(qMDdwO z+QLpU$kgs%52VX|C*+X&IW6%)94G*)2mo%E(f*1Z}HqxybH ztq(nk%T=c(sIQymLqG`CKW3zj)KvU|NdO5@|JbWy;@M zLb`c<^xRfPL4Bx48T=)sX|9x^D149834I1V%HZ!J9hjjgE%h3Q8Byn~k1^x7|M@rC zTzTZ07Hp#UOG?vR0mb^jjEuIX@8L;_%CLctfZLx5-x1i|7^k1}|I?!XL1jdGX@s1NlhgJ@F~;Ca}-2K$7fcv7}u6vUw(o?>O> zOlcZ9J<2eYpJ=TbmOegpt;Pr|N?T80<8Rxp?7PZ9ZQ|r<)ks>)P?WamRzvshwT;2% zjI%NdTOvKm(3-6bGa^@HC<->euMF2vk1}+0tqj*thN5yTY3En2p&n%%_o!Wn`lj10Lp{pK{?TEK?+;o1dk!_Fs!`b5sjhXCV{k`9(^8biS2fJ2 z8gdl%bhVyZhI*8NT;b`Ork~rFb)=@JqO{aojghA^^6JBsDyd#^ z+@q+x+D#et%~@}H`ort2hBodM!L9;`W6PN^Jm}|`A=Ae7amwJ`P6?X1;?@SrI zM!}Qy?m65@et*Vc6HP4_&89e7uHEOP)L58B{bEO_-)B-sBcTi!oMTD;!^n|C0l8tPF7?Z0xxa_BxGx49*DH?4EkixZ;11g~SISTnzHhFBC6vlmJ<8y| zUtfc1DN3)w(>ScBdjH^_F4E-=>r_KMT-N}F+%lzk4P|hJG}X|w6ov1b`e@3E9%XPJ zwy!~kqO>ivaqzwY(&AkJ*u3jdHEOODrEJ_0`0RbZd9Nu$J<8C!X>+9vMe$BU)ks>| za_1i&-f4iXrQT|&M;X?4e1E@c)X0^gD9vH3(Rzk-c?Y6u)Hsx(sQJhW%{k4LG8EO8$e zdXN@oWH?zvdy=aH2G{3Ak--xlO|D!+8H&Pei6w&E@Kd(;IP{5rVgqUMBuCnQT4buh z(;{Prwiu?5f6G=Giqagm4D~1@XMJsbxP~$mHHo~0QrYUdhG*3f6K4IB`fv^Pj2SpB zR?7++_Fvg512$1wPlm0Zw$7Ddtss{&@UD@a|dV};DsYs*m2n89`1 zJR?`$J|^0T>Zc~Bai~WbJR3P>*v!&TuEJy2cE7s-JK274Ak(RAk&{N&U_snf&cv&gRRz-gH9PBQ`sL^Yg zmNIPJ<|nYHacEkKx_R|6X5ftYR72B(O_a8U8o9?Y-YLM74@fshpN@ulV3T1heSZpK znk!`}O6#f3m3oxHrwXPT%1{)(Z}yN&D3vYtqw#w(jFz>@d$(1iGSq{Z$k6!OIK~XN zL}=qTd8$Uz%9eNX;mJD!j?(yAjl3VhwESK=*kCY+Eo0=VjJ!9&lq#uh?TVVum3ows zcb8@~SU!r<5~*1-15dL0uc3KbdH=(0)ovN;QHG)XK6kB;61;kKW_~MbzRpLU%E)^m zOsQt9UY*^esQFfcICxEk9_{>oxT-aA@T#VavnMyvqU$r!S2uDvRyff_iNdsCJfimbh8EzqM_=_ zu)O;{w%QUinA%D_T}5S^=J$zb=}LZUy4ms%!cdf!NEI-nj#r*m_FA`ZUarOrw&PYq z(}GRZa3Oe7_pFx;sQ0=OnnJ z6K5vm9l1sC@X!W|Gv{E)`-F?mSZM>rd1)}-Zf|QoGv3x*bOk{hD9-wWq3^ucd&0DV z;@#e0Smeum7u`bF{j`DN9zZbc{c20Rk?oWx9rD`Io{T?ZgqFd5lwjCf-WYak3l`D@!8MJ|F+paRy(_@5&_77#y28w+p81_cbRlWlhZ`-WD z6hRv(tfTn^@M571_4F814Q0>e`jJ6Tt6k9V@-&7}32W7=S} zJ4JI0MbVC2*_&cl`EJ>TdT2vKccvB#GVI;5M-YXy6h%8UK5B0OfA1If@1eD;hc-00 z!!~88r^f)>-tA)=JNE8yXefg=P~7(m4P~gO#|Vv&na0ciPiQEEHc;HZ3Jo$&e%?t} z^iWfVy@7becNS|}w87B*vc+PKp(xssD|`3yitk=l4{d1ZE}p-8xyw)#?a;8dPOtc$ zYW2{D26rQ;4E6LFU@sOIo5stY^D+P3L1oYeihE?Cp$zr(7@={8H~#GEO;5X>sVx@D zpbZpyGk@J-u~3G3dW_Jpw}7wSoEplY4OBa4P=lf#Mt`81`2772o4d z4@!|XP~2gS(p83fdW_I`kZC;hk52N^RR(RKaD^LwTSOV^=`lj%IMaA!YAAy?Q0*K} z8S3dVLPO?>3uVv-igU(boV@SyqFs@3>Bk>(qovkK5lvWgNn=$TyFE}K zXai-Vgs*F}bcLaw9wRhtgxhjVR0eIJY_!{a=@qAD9Ay06r(StP4>e`jNWIM!99`)1nQA z&73yxKj-YcmpaE#6z$NkIoy`BKK0OshRpys7r*WJJf}a$P!#RZu({|qXRk#)w4q^h zRP2%MOd0CwF~Ig&_%>(ZMH#e#viY^|!-a;;!Ye~PJw|BQxW3KRL{SE9plqG6dHe47 z?}dgiur_dYMX4POTjOkVRa7)B+F;n)$A1q5wy%nuVXLCo5{0xBMLRTXt+vh8T~QBh zq-!g^&1oOHX)iQ{fwkJ?*GQBR8n))#=1RCQEqG{yVQbvYzEAJlgoZG%=5%#16h%8U zY<<4{(hY}i?Q&k!LmTPZT783GXbKHsV14fDNJ~+)L&J6rwza5&}IO)ea7Z; z+kr$Yp$BzK8w}eilwUSdhI)F8$d&DKZm`P<4Q0>jn4 z_kONxXj-(v(35rcR=k0+APVY=YJWY+7`xDT&PBJqLOsf`l;o5i85a3M8H%D^BljI) zFw{dEaaf7eU!dy0FE!E{PO)0S*Ix%(Eco_QXtbVz(Vn0sL*JJQ4Mouo?cV!R#|%AN z-+x~!7>c4D8hraHqEHWQl$D;XZ{P1s6w*=@?BN%IQe$(^8y{|OcN{#*$dpciUe&<6 ze(@gOnwFwyM;yJkpGxGOZkBG|!J1!!IDve61k_F z<+cuu-uqI)P!#RZ=)Es>%*dKe4ZZ;kbxX0Z?k z-;n2#D~fh#^X*_Xotplykf41Lawqurp6pYQM5xNM+U!-qaNDO$Ppto$Us>U zg|rk!JLBlQFLlg7O2hfx924>G%>9~{qG+eaXuLvN@DPPKP;U6WrKrs;t2$nhp(xs+ zF&?k@+f778x_a()j)8Fn?=@9MXmIpFKPM_Y10&mUvdQ3hg>=DC6zxb!Mjs!q7za_v zRra*h5C(gcYbc6#XynLH$19dDQP9ZIhxO5UUnehN5VP21g&OZ(a>*4G!rJ@-AS!?nC<=wZx zk|!{c7Efua9l5%}(BHNHOrj744{b2?_a|BnqQIb@+7SmvhHu*J6>$&+4{b2?w;}u* z)nzCOHs69$8JmaOT1`F5NWEO+WUkN>7s^l+?T8~w*GC5R(3Wz`wU08gtlZOMfW25` zeYl1)XamLHdWl^17>ZIm7+@WVG*hmUR88Xw{o%Py^@N$>3S{$dcu1i>x6hg7OpbT?W8l z`1_ri7D{2vuDQy(7~Z#?>1w$-d!CVTGz>n&kG!`N|FZYDSD(??@m@=NW%iET$HYQXhXwRWP8iopOzYP3`NlnjdvdR%H`SizF%mlhc+}8SAJ*j zv=bkj8f4t*R^>HBd0L7}J2bAn<45-J7Gh{Htuf>5@A;n1)fZ7?j-e>pp>dDJV*A&2 zmlqQ1p^Z5H?s2!=y!VqVt2u_EXotr7ZjajD?OAtr4fW85#?@awWb^JH`1vfWIfkNW zhsGz*Id6N|4X1d!QV(rt{6YD?4O+g}&4LW8kHd*VT8g3_8lN?d_t|^BQC8}q%{Xp2 z?H5vm3}_IAw4g^6?a;``SI|%oZD^p}KKH^i+p?N46h%8UvId=@9@@}A{eSzjXQjp* zLs7It;{&(*$R6JQjyTjq+v~tu`>FSSVrtAW(DExP?a;^`1&uD(ayPjdt7>hL3Pi zM_P)a9U3yW7xmDF21oEAY}Wsjq3YUKn8V5_%$0hS zq1ukE4AlUe*FeNt=GEfS*M%7#;t!$N{D6|+{ai$E-ua=L-*XBw+%Fs4F&rlTG z@ibScHH`Z3Acq*8VM7mBoGC*+%Fq&NbES+1Wjz>I&Z!3SPLDFWrCY2+typW?!eNsQ zyXMLntTlL)O^qo-J<8~6m{`G1bDe)Eisja5ID>7Mx#BEL*)QzG-4NAuO$PaVH77le~OyWqI{XVtKKiKlY z)_Q6+)T0cx>1pK3Xi(XvgYm$>Ie+!chrVkMYF~WNjeF-Wp0Ghb_^i#_@BX?o8ao)v z$DhA?%cuTv7Yw4{p$+zFKYiogDJPx2nQ9OP5B1cJKKL*H<0-3?&wQWHuZV(&HWZkKbo?+Vv-H5r=wcL*tLn`PaP{Jo2p6AmdKATI?eVX(@_! zX#D00moHa;^K{ox4{c~%{lf3;{oPSdOpQ5)qG*T4r~bpc_8$H>F>hB7ZD{<=O}E(G z=LW_x$50gQ(0Jx!zP&m6FCOo4sE0N*UjC?CZvM?n&&)W;u(Gpp|QH@S=%2z>I`pJ>Y)vdOKsl%yYDz7HRc$K zq8%ECedN6D^{+X}M|t(ohQ^6sJ7n{?yZwA>%rO*2J2WnT?8)2bz4MMMv|aVkhQ{|k z@s^wK`(LM}#vDUYv_s?Q>u<5W_=?kALp`*i@vFD}p3Qe(_}J7S1O0<2q@^g@q4B0q z{o@|S6U3n&+R%9P_B(rDKY)wC9 z4aD{ig|rk!J2Z}7{L<=8 zhkXd`s;GxHG}>`j7z?71mZE5fhK%h+J+z_05j+^Ex%iZAFAmk4GT2_>>9v^3DAZ7O z_NcB#WianRDMPg*^_~W=IAeCp&~%ldSBZIsqIhMfkteNeHNV>OHNI9uJ<8BFJrsf1)K)T^Tr2hI2qu4b8ivwA7~>tSM#Kde=(fj2R6w z6vdNnO|A;cNkn{e6EyXC_lGWH7tF6+Fom4RFt+*hvuJBf4?BpstnXDPNY?h z%Fue=e&WK~GVB>u|6Sh7C_#x`6u(KBYSO=k%H4|=VpHS{}sF4=#7cN$0Q85ooLsAXl(#4P{#4%c0S zwCt&r<&j4pvxfa6=f80IriZ*?uWFQ_AXmj0C+`TuZ7@Fkf{%|p_qhFi2J@?Nob>^3l|vj|4gRW1q&vjd#-WibLtB1j6!bx5D9WDZ zKuLQkv<&qqLwj0fm{IVQh@>^txjmJFn(dTs>lqmK6wLB3|K#qS(#<&5D4*1GJ9E`3 zUG*p#Ui_B6Tw8aGgyQq5IC z>8eK=+NLYRjFzD&*leMd;Tq~u#?5Q(iqhU(H9S}LWU>G9SCom@xtE(g0ldVs$kVcF zJp%*vbkkcO-C=0I(-t$|2V0N#yMwf=mNDeYp3e4P1e?audIm;YB137_E2l@8S8BKO z+CD^XwTDlgm#`mTR+FefFR<}9#&#R^Cybm$4H`*n87*qAKD4HkkyoD?4c4uq>=|y% zYC8<|C?l_;2Vp1*Y&(@?m%di%3TOZ2EIb*9~yp}OSNo`gMV`zSJ zhUDpLi41sXs7D!w!d$D9D`hAuXRjT`$WznJIpaYXiqe+f#-SRp@vE2UclIp0zuBef zg9VYR$DWG!H+TT0Da~sr!=ChC{`_%g4{=!f__V!NQKK>pxHD{}xNECBPb*iAZu8mq zCJtw)M;WkfjXUHDDh0V3Gl;Utu@Y_>uAv@H*KC{w92k~9J|1~ZOHntkbd|wp+^3Oi zT8hH=tpCVQ{EhWF^9v1@w6a@wL-VNoqhtkcg75qkm z|F!_qGP|O7|LW`ejynC)mQhe2{M`pIv^M!G6-}<3p&n&e+x1`Zs0>5n(`xWHAjW!u zjlXRx88iAds5ya6l$Kl7D9DwK8GE)4_c8&4S2!D2_H1?EDJ%6T!_wUhSJA3s8g@0n ziBC@pdc0<6ZU;PaWh3>5D7)g|)SR;?r3+dCLp{o{E9!>V$5umgf|zWLTT9{K{ahKA z?xue=7)4l7n%g#4BTr@6)n~&T&NCFHWmp*nWo7@b)|A#D*!?^h7#bg+!`1dPW=tY4 zV}_Owf4OHGN9!5lXiEgyvH$FYT*WU%AT3*~ZHASpvv(VfWDFi<*t*Sr@uaur%)EPA zio!21{L~|!c4be)bLHy+TUj7iZu9q~rVRBc!&XJeRlDXah+G+p;%|CQH57&48TreT zFZ8_6Gt{GuOler3TaNH4^|#HSt|bo>oI^kiP;Jc^_JjGxASu?cSD@G3niPOGR!C$5l%CztE1b<-B{-~6Gn1YQhwna4HL`~W< z?P)t|1VWn;H8s!=TEGBCL5dV+?oHK}vhzJ z$@JZQ_gZ_Mz0bMlo_p@S&w~|`dvfLE_WCGMk1}#KIBJB19Usb2l(sOz{wo-)k20XQ zdUpwHT(60uW|>2w;HaI9IIPIL?K(oEIsRW`OgxpL`2}`~p(uWmYdt;+8R}7n-Cgug zz^#lF@~gXgS6AvQnA&P{bab7d$>@1;iu z%)^cet4~}zWpxiDZsycC8YQcX`nYGpKtDOV)zDaGR}^eUstjsWk23OjY+Gg2+UM?3 zR37sSjP@Rc@9E||xUj$Lt+M%iGiEq4kRL~7&BI%z3`M2g*2*>1Ghv`^*}_r9Gl#mz zGDbzEy{rM$jDhpjszznBC}%8aBq}{)++$rEjIk88x>_1+wEKL8r&}=cZD(o&8+F4G z+&uMy{s5z*c&q@$qpLEkFYsgE+n2{PJj&qFRT)7D4Sym99zI_(WhdBw)$b6jDuLbu7S<#ovKlS7o!BLS9o|e0ee#QDpLmaD1%ooRRf%YRw+YK zys~H*APwqK#^Ts@4P~^bxU!gQ;F!R*3_Mc?$AUE`ehRBgh8|J8{%kay(R#+dne_){ z2JWyR7I!~jW4Gn9mmj#N(J)qN7>eRD;GyRs2$tTcCV=NheNWMI7E-bBMF z80|X3v(jGxYJIe;M;Tf5FE$#MP#Kh=DDJS$8R}7nj?lJN%1{({*yb9oXB_!?Y%YxU zmN8bBcL(Mgt!HGkJv(L+=UUw1L9AQ>xSi+0wg|uI4o64GrFpLfkwLdfZ%>v>LO_bCuyJ&8gK;k1`D9_o-^F zO7QARhND4HV{f(^lkrm-xqe*8Lm4e<;ixsSI2-VIRz{w8S2V~_lvcgXLp{pK^}~XO zG8Cn~*=q1^IO?vWg!iCpeQM%4+=Ffy1+|)tAFOvBrLApSHStu2>a8;r#e4Tn ztBhI(^(aFtQZ)(~hQigTw;eXK<#P^mjsNP8`cnw-@acrK{i%gHgU>Te8N921Y=)xN zTcvqerTy74#I=g}(>qnevc`|ss(Sdm4^SE@u<_rvR?4u^<4++~jij{a=&GXFFV@Ik#X9v_I zQkC(Uy7rnf?3lNGExx^636{CWYEkig;=EPJ7SDLVgFfI{4XwqK19OIYlwq^0@3tMA zp(x~pCkHB{L@s`IuB}23vL&saX09G(VDvN^Ns3XzY!!t_&p)n|VP|ct+fsjMEJf*< z9<#vMwH1p$BOEmuD{3nof3~*Ps^-ypMux4TR{BFnM%xFIQBp$0&x8KFG1R9F*09Y3 z{mk>A_PMQ`{aNRE9<680qpirOQU*S=jaasN#S{3xDz?=!p1Sw-wc|^$%3xPQ@azS{ zu7ozX?0Mx*w8Zsxn^qaC3>sJU%x96#Us#2!M;WvJK&xCs8H%ziy_%C@(XS z(hfH?ep-g2vLa)xf?y20V%hxTHLvyhWJSGhd^*0Vm20R+8CgTWhV$?xM4|`rz6xR~ z%C6fs_=dc>hI*8dHC)h8hNA3x5XZ-;QCrn|;!Tuj$-*eHRO0v;V~vdLr?FL$_=KS- z9ia*KU%p@BZ&aWqcBSWUTEMm|GJgYOUMoEgv^RBBwi@c0GT2Y+4DJ8*R;foBc6IOX zg3R+!hN5iGp;n}A6-GFBylgMa-_(k@$J2w#upKXdi*DYkJc@k$D5@Pj)~*t5i?bT; zH6vE8OWe-0gxij-j6BO!6vtSeOBNXF$#bH&aHbKBvXMAt*tyT+<~eHAs0{UJT+J!L z{;Ldm&hS`y_Ho;GSh2!c&`^&u5Q%&Jt%fobmFuonqu{93>gJlkQChcFLp{nc6xJ)P zhW)XwGC0c!>Uc(?#?5utf`*R77BwCPZ611jC`0>couMe(zxMYz=f{V7l%f69YUtfQ zy^p73tYxTY%4qIjC9Pf?)P5$)?tks#JB#OeOvVpZ`i`3AQ9{J;8|bL63~gVAahH5SLp{n^-!)K%qVRXTJ<{Y+FvF=w8D{&tAeCWg{LB~?Wsy+zR)dV{ z(YUA~_h%xw|2H%$Ls8IZYE_g$k1}Ah(t%xL5QT~`Qp;%XzWB~&o*9mBmvdyGRXmzo z4V&A09eqS4!$)PyP>;qn8{;@zIC6XzosM=#C1Y7bj|qvpb{=eFDa!2yjXV#gXJoWj zdYXqa6xCi8={Jq*9Z=eM=8AVrpCh3Sl(FUMHfz-;TUGQtK^qL7S3<)w-{!Zn7hM(828wInU@U#N zEIhhL+P<~LZ;JiU$)|lpJ<8DiQvd#1|2A6GN*Rix9j&r&)t!B}EIdSEj^f-kXQ*e1 z5i{Ibrg2Yv*Kel`+CX7U^9`=9Q-*q$7@_fJrg3{}D1$ao+*OS{mKcgsI~ev&%9}6U z{7$<|-E|s^HW<3s+jV68*t0+PF`^JlQM5zj&?7&zy&}F5x>FBrXtev(WW2&Oh(aty z(GCs!F6?c7dv>QD+R)&B>71dSB?j1C_jc3xjoY_gD`n6Ql)f9T49q^*BZK-9BiO%b z8ds!-GH3(Ey|c)Jj8A{?!>?LG%^CLn=iB_o^iE^Z2BY1FTVp7ScC^aA$9+R4IpdZ`uid`y(eu1k8jCggWSsKs zXJ17W)D=ZLTJ`wDH*7!kjUE5wVfE04M!Snc#;MPKc84g$QWWjb_?gqL-#&HZJN{Y4 z>Y)t{-8JgEHHM;ShsJ@Yes_E0z7JUMcb$4@LjzSGKYK?R>RDod-F3fj8rPztS4n)7UlaxON?MYU>X;thB9aa#a)r8 zt}2~U!3Q8(1TdCf#PmLXedKHON`Lin#M1rhB9aa)vgnjp`Im1 zXvkW$QwD9IxGoLG`KNtk^QK4ldFJ#WL)t)L9fbXW$XprfSz?67kDA5>si6$oK(%XX zWvFL~5gNAA=eiv${klG<4HVb#!FcI2JG+<{G5gSi3~2-P%wyJuT7@?upI2wyKP*w%mld<@a7A#E_M z()Fz*Td@j5Jxh#e)%nKYxKajfplrm*J6Ot4&k`dv^mJGy$?bI8%I4D~EALc?Z;fpdv6Xai-lM1AkF>y)9MB}Qo23^#C2R0i!p>06Y_ zu$i;Ix4Fa!w$0Q7=XPb#2Fhmb{?iw}HfyDf)-yg^&A*3+?g7w){-6z%oqhUOzx5^A zgLYOMcpjt&4BBAW84i0jyZC$8DMLL=jA)geod=%Jl|dUQJ5%?#ml_&N3`MCO3|nOk z*XO!KW6=h~RyF;XuljZ01M-#3B12KML&H{N1J`isp$!dN&-H)!`LoV}?Q6J2hN5VP zhRtq6u0@M_Xd|wzIQ#o{Uz9sYWY}8t9-(uHsf&7OL&H|iJw7on@*u<3 z)E^}Zu@pr+G|qY3yN1ujwLwu2ZN#-J3*Q5rGt{%hh*sHk)R5OvMH#e#vMZ$il7Ibn zzA+|@ZV5GK*wx*T*Mmi4(FVh=4g1rcJS}&Gg@LQPs;(&7k-1%^4tZT$)I%E@c8%NP z)AwN8*c}DK@?i0DB95Gquh(aty z(GCsURqJyfuBeALG_V>N_xhBfo+Sp@9d-x%+)pgZpbeDm6xPq%Y8mQTVuXh6i}oLn z{luaS+CbTkXZ^gbu2Y73mKdQSJHka7w1LvSUi*&q0|)y5wr>Z<_tD$4G4)et?A{UH zsL5xp!jAs9&%V?9oAvvI)iW~eX(5jkts-O3Y)vd_TD5J7*|9gmZD&fpBt5ojg70j)uW7zlusLyfpMh_ zMbU0*wY5At_0UEhS&^J2vQ{&OqG*Q(XCG*&hqjEX)c6;x>@zw0*i%9EbLT8TFVCC1 z9U9-YW8A)B-djafct(ajcjBK97kXr1PE>}XXh)=v+g!D^Im^(UdT1lAJ(uI3$`=}I z3`NlnjiZ*sCv(114{gM?r?+e^%BQ2r*mL=d?jZ`X6h%8UP$$bCW4BWeZRRmPja_Hh*xezDc@PC{*r^e< z+M=}Tp$!dGgzvPN#tK7Gv_oTU_8}_zV4PRF4wc0*lH_HsoIBGo>JhXFM;fdC~R$F6O06~Qv8aWbuE+HyBBg1Asc@v2Y)JhqOq8*WJrXK7( z=o;#wjXZ3gmp74wfitJ8BbK6QhX!XKYf(`TZD`n;Xfuv0GH?tMg;c4D8k~KQhk9spT#YLyTetVPy32LD zzY`O&^c|eAp6M5h79zFG89ESBH7AvYwLE`P!Db7Ve3-U z=JntjLs7It!&b=kdQd&IpAb51y_bWu)H1^`J5o zMZ2jLjzO&3(JH?lq>VhXZh0M*wVE*$MLRUI2c4lF+A*%icXNE70i$HVTtZaDQdHRS z_Z*4PC^<@aJ%};pZMQ2+jH}FpjNE5%6k;igc4*j@@L>B4uAv^<$iuFqy@rvKFgl_T zOHs5#Bd@&tdQd&I5!bHt>-%562jEwb7*|9gmZD&f-wc!*8yi>HHK-nCWTb`bL1ie4 zc2lb@#+7<#Baf^|UaMuTW(-Bq4h_ye&`=NU=!2MJ!sZNzxdgMCorUwhQ}dPx&WZW= z>1t{8jEp?*ZbD;?p(xssN3H-obM??h++0hf#u`IWv_m6TGQNMM9@@~z6;5i9fm#uT zSc;;ZdBhsduLspbn|auIka;8{*X>x{dEKE$6z!%~I0k)v1r$6)K?8N;Cs5V3=!~H# z+MzLBEg=>>L_x#kvDR+;+%<@bSc(ce{?65s#VL$6W#oA`HORo6s0>BXj!3dvD(az) zJaYYz8p7ZTz%y4A?a;`zkIz@?p$&~(;f#HbYqdW28T_3w#8MRP(8v{;k6rc9W*)X8 zPYp6qE20n!ts;tcXiQg2KusB_8)l5?|22l9Xom)8AL~7?UR{Hzh&#?Jey!H*U&(xh zU4v|i?+th)zk+P`uVlWe4Abk!JgimD$Z_Q;v{zBIYpt67E4GTL><{edjI~;1SRYgr z?a<)tgIcMFHZ-hfv41u8Id-Eqn6HRJEJe`{jl6>N`AR*snFnVgU$BQ>3OoL8b0S6} zGzw!)88-7_za%w;VT3W3qG(4XTm|Qqa8VC!?bL{!BA>6+ zLmL`)zQX<$HIjk(iYUZV6z$O9?1Qw`Lz{Vw#|IfW28m)GL_wRglAqO3t1UFtLmL{X z$atJ*t!4~G(T+T_2c4lF+R!lhInrBhJm;fhO<-8 z-XSAzio&~Hs<+OdhBBHr!-};EIt3bn@^{pz(J%n^mXVPf%5b~3%Ckl;#%NGlE7gcP zDT5lyXx`K-T3w6f=ZS0~ZD{9cN9-v>YDLDbGTQ!74Qt79GN_>p*sPV0tJ)ue!dR*r z4Fh@9{-6hy7KYo@XsfFz$?16*nTJ=DqkXK^(}%7ae&^Q5{EYLu_uSO~&rkhN^g8;jj0dyQK|w*FE>L8-|O{{Y!s_UOlwI`1c>Vxxf0t7oQD#WL$Sb_me~+ zmZE5fM)$He50{>Il8;99&_>)lPr0f8=NI3R8fy$i(GHDwSk_-Vbd_tUhc-0sI9U1* zJ@QYfvBppo?a+9?)ye7wjiMgf(D=l|`}^DO{rl7)!)kRWQHZ4|+M)3!tJA$NeY0z* zhc+}0zVJHqY-$LjBMPw;MLRSevO0b9*2gfn7WL4E#yfAj1|w!K?5-0=M-*ZyigswA zPByOm{SWofM%)Yj^BRn+FNOvg7*|9gmZE5f#(h?&`_DURusk~T&_>+*zj7VMRcfp; z6h%8U?zTD|v7-ta>Y)vdzkB?8jH}cj!}8ce6k;igc4*irIgH~F8tS19jZePfMvSY} zAOquyD8y0}?a;7MGT69s4fW8524@V|_7>F&Ls7ItV{P^!3UN7Oga$H>pEA&cSezMP zlN}nwWA0UtGI-2aMxn;ixB^PYbX71`8PvmZ1%~#lGYpNNmZ2y;HUk^~Ed%=iaWyCH z*_NRmWy~^9S{am~C~aY@p&n)EJhskI)N1C^{~&6UqcxjZ;b|0X%++Y)vdzu7r)^Ok?REH%hLt%yP_MbQoo)XByb*1JVLw4u>oe&Xio zYu=g~WMEtog;Mv7+42&zH5KB?CL*vKa z@kIZq9f#0R4{d00#(>>*YYauv4h_ye&`=L;#N~_;8bHQR8R$VQJ?6;{4dQKB4eC*b z9?gy~_FwyFpQ@6h8nHM^VC$H6M*gP^>QM&!zqZQahlVl~rN?Hg!9GAN%}INz?9xI5;zL{&NM;Yt2Qih_~n^mK> zNY}}I z1r1bWbJ8WLK?c?gL?M=ZFl|PhL!F*VfgU@b;ME>?a+|> zYDGP?q4D8zqCdkHbrVKM6k;igc4**vRNOnTtULA4W*+15K?Z6?6!Rbo+OR_d_dak( z0~+d~4Gq+7JkHk`ilQAFYqJkgQJ-;ML0kCaJI{6Y!5HJ*MRsTqZ^LR(k23UVuJ{6m z{a+o4V6*=xV|pa{XUY<#4DHzw4h@Z^C_OfvQG!mU&Yb3BHwElhtDy|Gw$X5g zdf4Zy8r~}Q0a4?u*36H!S#7KA&vmZVDmdKY$4(JEGp^*ez#sJr#*S4EW z2(*ZRjIE@BrbR%MA?F-L=0bWB!%O;-bHvHh z_w66B;-FoG7`(F1GAmENZr+?SV)CKaE(2lZWhZ`RSsC&2!*A(>u=0{SUmAh<_3Q7c z5muhL#`gU($H7;hQzNXr%64BKfp~EC)iuJ(rwpzbf!OW-evPp5iv4aKfw*<<&uWB~ z4}0pN0zx&AhFpPo@UFwEG6GGCaFwlu&U0lESPA{}Kkr|CaPLP7h_}CXP<8)>kNc>E zrpI=9;E-za4v!TOXyn%-;Lf8;5oAH!$1Z=gz<~x15Tn=OIQoiL2#4;=uVn3ya(2%we4@-z*IXHul{lzo&Vfc& z7NH(H^NkXRMPMbgc0qX^Xk?Wl${ZFUSyn+_&*Gsd0P}h9rQCWm`^U|;1Rp7Aez)F02 zyu1g|$jTzbci@D33LL5dC#N#a$-wT)bA?7679me-9(P}X!y>Q}S~WlAta}Rx;*D07 ztR%C(JSsFPLe(rsWf52j&6;u!G_pz&We$swEUSnfkt=c{E0=}7swSBn=24+Z5jrc& zePt0?!BOsAA=n=lp$OIa<)}blB@V5xyrYyKO%t+`%#@)zm8T3eDMGaoI*-aCu!>Pt zhi$R6fKVs?X2A`0_pv7Ju9<6GUqGOdU-5x}JC7+y15p-BRzj4<)|zIE1}6k&Vfc&DWc3_ z5t3yU(PQL_ZdZQPeIUxcOBQ9NU8FioChPe+(4+|M$8slH1XggA_n;80!y*)+_DVS_ z5Lk(WEaV7fRL_gZN;1!vsIukfOVFeURa5Ak!y>SXQB|uxG`oOs@mA0M=~y3?`gq!l z^Sz9xu{kV4dw$8CClxsGrAV-ntjEjsK$9ZG_lNV(C~#;UTA>iK+U@@8O|AokB3%0Q z-3uJ)I%Fk2a+v4J)u7K6KsBdh=(ik!Mt&_qp04}$S%s)90;?ERf8*tg3J9`D?6Q(f z*7K;)qzLs`IVy|5N@&)UbD)t`iYRkfgk)Jo^oU$(cd}ZSg}!=82y&Q5g+^8up;MyV z?G}L*9OZp3D|$&BbfP?!5om}Cgw|Ky=N5sL(CV1-S)xeRJZ>MK9~+_2Ix+HGp^;yU zfO~8NR;)=UQI1eloKY4*rgMbT`28IHx_k1lCKs(g`EmrB5@N5TKU#>&A|%U7X!Y^E zTOLzDppjLIIBw^Utpp*otb|tQmpRZ7iA9t-EJ88}bxD~64Ut$xnZqI^gK$|GM_;9g zk@fJtVs`t~gPzW7uGQ*w4%WfzA3Dd%uYaIP5iY_?=$ykMu!<2@ldoO9fKX>hBP$oX zyC3)qFXL%!4vWw(Sa#wD1rB_P11rgTynOngNfF|kviqb0hpNWBqfE=M(CpxR9cW}_ z5%Tnf4K^=uSOiu=tFI1y|C9oPc%xM%E6J=cj|xqSP&La@Sp-%>v!{)J+Km=9xv}GYb6f4eKZ0M>j0tkm3NdyU`4LV zyH*+1Yo@Z2%xkHtZ27fRG$}&W6gscDMPMbgi?BL;)qgG^)Vs&+{I5PLp*g#>gWYql z1q2%TwFtQLs8R%35cjWN|89W;4ICgwufwgj&snSNvJUE$M}>y$f{>?~kN&C=20FaMW0)i*x#FNLVkh{GaSUmlf3U?sGo5_gV3!#ap+bgt|=Zus!VKBG3moWsU$ z5x;zBgKER=|Dup9i@*vF)h6e#R^m|A#zu&PI$MO+SFWH%U`5`_QK<%SScK~I$mZ`Z ztivL(636JiQdIXob(LT3KI{KYA6fgR92FY*wFt@IdTh;Zo?S&HO+?i4HlJKlxpz7h z5YAUcB<_7ubr$q^nFEbDEJE@RUz%Frn78cHzJEZ_yNXu3xx5bcx%`5FZ{-N8NuA0F ztnf?Tl#v|43T5@_oiD1Ud}+H@rgMbNl|}q|;RV&>M@}o`$|A55-{=aWk(E}fIwO}W zXuHHB)S=}ru?VchA-T+f1}ma+(ds>Sg_TsE2*pbz7NIM(to5(` z9!QJ83J&eAGJ<_)5s`1_u@P8_Bd%|k9HE@RA({7Cs^7{{p^;yU&~zqr&S4Q)#i%M* z*#g4F>ou}+>u`P_-B~i8#^$gHmp6ZojE%qwj&hfXotj%jJ_OfVc`9FP(OAF8<3n(*m8bHx7LE0bJU#^1T6rp8YtdN0$m2tBt(B+pwHA%_ zi#$FA*IIchUu)4=zsTc5aIKZ6^0gL?^@}_{1XpKyDxd9WtY75uA!H?lJn40#{JcVA z{YvK9Xd(13JWqxd*IMn`cr_SE=IY!+)EdxSKZIZ%V3 zY9K_c`J3RNON6F(TO747BB6JMU`MqOJ}P#Rtm3Y%J;_@C>Uz`~IN0YxbNY;p;PerK zGqHv6QE?8+DxSMFx2*MVbX1(wLUa8X8^QHM2x`7)=xN*^x7wOL%3RO=<8)$@;0v)a>n=Lyr?xvljfCT}wT@r&gEv$lx%Y;qT(Drz|R4XYbc^ zVts!;c2uVG>$~k1!uvJ5$lou&xv0#pt?z_e9N9X|DN*0owh%rlbK>|r(>E8DIpOMi z&K5@&RXkDs?5~5`H(2ZcfY5c29c2)$ zJqW6ZV0ZaRzswQu2mG#OZ^vjo8vj13p)~fML#vH@rOtYWkVfn9_cd0I>+^RkpcaXv zg}^F4?)k8;qpH~zp+T_nG6%8OR(5?Ehxg0f9d~s1UA2c^=dADUK>2ml2x}z{Wu5!M zHUf=BM7cjMgtrohUNN?2Ui(G1YvMIwpV^-NMqmCt1to;#2q=q?ta?~J%MlRx zmBu0@D#ppI;&m1 z_Hh1J_RkPliDS>pHm~ma>9&#MsChGoTV6QZBhXmC`8v+te&O(;_a5X=9NrHltB-E7 zVYSVi)%}`yKU0Y6OZR+!_^Cxx`|^v%A|#)1^M=*=>xOqzbvhGwIb*oq`aAf3wFs=_ ziA)EMO;(&ZT=Ab5cmx{jSMqKPH>&2{G%2q9)cubfe(uZvFGFA@M7x6f{Jb}OdC@lh zq*g}to-|plvfkwCwFjT}cV1*9MD^qK4jz7f;%Xj&#v&wN{_Mup%wL4}^>sQAUjLcl zIq&*mmR+obAk%^4#iOqs3@-Sr=TK+p-FULPy1z~Jz=J>XQ4wuGOuO^d!8NDN&DH@z z=so^!YBlqP@SeL)XW0{*4iC6(uMB~e5M-f_s!LS7OHWo8{pcfgR74vP|Mjn1bl*KV zBU=Xup)yv&$W?tbVuP({=CaMCIPO)A`Qq`MtNDc85ox zu?WdmTs7BJ@X1T(_I|tDs~G|-^{#z?VyEM}q(_&av3@1*a>k*)$HF>XC-&$>i@-`8 zWIZ5U1$$HwjrA+}l?nTqns0ySt6jRpBCryI+60by@1NQG#VxaYuUX1O17^ z%6U&}r}L9v?b|#4zKuLW>yXAGBriW~t~o`I|IysuoO564T3^;mkE>3+gRay0-PT9- zy3-%`2s9QU`PKE0Fek&_Z#lVl`jW*N0xNOQJz?d)o%X+bcmDWAfA*oVekI@k=#l1x zb7x|YGtnZj5`wM_98*vDX8+jjKi|53$V%OwUQ233C4}OYmEN;y5t3KCU{8+@h%at( zR`qH3%jr9pWrZe1eCW3y_MUQ%OZVTZdgg~) zS3=yp@1$yRcVjPir%$XF-@dxPezc>yYW4v&!t$Nno$Jv#2bwg((NS3hRzm;Rq4P#W zg+^8uvBxHdRQsI#T=MK-8p+mwoaHmB$H{uW4m7f|2y!?!0xO|kS+MDdsL;sDBAR-< zyz7kae)CQrZhh*Nef1A>f@H3in&IxgX2WXYhgHFey*+z-?e>-G)@L{C4gSZT-5XAx zRlWU>Gb_pGZnUSDg*fJ~_pAoT%!-J2zxMmVx@Z1;Agg_D+_u_%!B6H$KJ)wUsJ^kq ziaA1D@qZ>)U!DJq%kGmi&geaV{x_<1emZ%e*vY$O>LK(W{%v3HDIos#;dQ%bzp%V7 zD_cR(LVW-JPkO$9*x)p&MpU@SD?QqaSeCUEtR0n-%n}~2x4T#ECkg5r>{GA)c zsKnt`K49e_WJPwxO}}+IvuA&{xBQ4B26rB?$Y&RgMM$Pjbv^pj!y>Q}2j@yaY<|kr z>bPHR+giE&(j`LB`5`Lx{B|e)lSiPj2+8zY&C!R$BCrw%ogX;%-|U-J|J0?v6X_pW z*}l>`-utC{T_;X^@?E{pUG&c3(-+JNxt(>KXPKM zdF+w_T|(8w!I`LaGzit>>`99UJKX2)D~%>ayzt5vu}icEpZ?>EgLiKBa0?+cR@zZS z8`iOK((=IrOW)=1InktuhbPU7yH+cI-{d2@oBYH3hVu21b3amjb@@Yn*OE6qu3TO6 zrR6SHifX~6tE;1yZsrka!~sHblilf#4KTV*G{{vg|JqV z$$F=AgsaDsKR#-B--NRUR$~$N>eK1m`pm5E4|Y0w`2F+lX(6nY?S-)Nt#-O@@ZA3I zY|S592m8*hDXjbxU*2SR;kP#OJBrm>gd$|mhaI)vcXl1#{?mQ@2>`-c*)?@K>cpoG z`K#fH7wzTG60&F!S_k*hozC9Z%AXH=X7{r@ZaUcd zEvNZ;S6!kRS5`cCBEDvySBqzMZ|Gh#_{Zyy?^%sSNalHzPUnGVZ|a_R+EarW-}qRD zz)GGtV>+FE?wZm4*3}yikNN!vJOYjNE1Bm}Laxqz_w3<%`)!;du(Ek``{Sfp-H9*n zH$33DwLF4KS-+B-XC^+ea7OpyQ;r&b;M@26dRPQjLNxV=*YiHtbIx<^RIW1W7|!6( ziN_o=W$@L9zUKQ1O^V=p6*}?B=Z_uy>8)?~^A!mB#md&H)6pq<`Oe$*FaOD|t$L)0 zW+J=oiJSa0``10TpoNfMth92vr|zq6+E*!pyO+A=J!<~o-yi6&obt(O_)>YkU7td%Rtd(6;-R)hv zo%~otdmV8{b=grMtd-;@SFsa&bmA3D4)>FVthjfU+}zQ}nW3whLAkQiB=e`uLdeyp zo?N@P?bv+F9$I{asi~OGYuU%1`s?5ACje@05$$z6_TE|DI~RVgcf-fO&_Y-%$#hIuxw|Xsa#v*U8twGTn!?K0 ze(bjHf!D0+r#>`VIS56_^=wVyE+&CuVgg{OLWtsryaKYL1l<)W6f&V$M$8lMbFdeEhgQ{Y=eNEGwR;7GECa>ctZd#o9dZ2a<(GCBePMw|P$}zIa`SBMim>wT z>2c*2ft3(sT6eUaj%Iev4(osM{jJZa>C+s1`b?kZ&?iGd+%S0Is1q^-R`P@#5SQ(^ z)$oC%clQW1dZy6I`fQFq4H^*6dgxFY0xNMK2ZW1gc;4$bbgf1lSV`6=hUTyGf3FG% zw`zyjAwys#PslCAz-p{t!{(4=s ziSSl&9R{I#tM10vF2>5sE+hUO|G~d{id?yM$XClsp4tfYt*U4>;=oF>tH1N~XjAi^ zs+c0M(&NY>Di={tRkRxGSF-Ef{`q_Fw0S^ikE@C)0xLa^+(LA%#`-mUao5JEGDM91 zcEcSJIu+RGSXsZ4W8UKF6SLd1zO0oVZzEy_JpzqINRE}QPdMKt83HSDActIqzu`SB zbcwO@9Ww~s9(R;Qps|Q3SL(N%BSCnpxQ-gpyqY0jtlV(iVIKD!8N#3XvU0U?ejoJ} zbn6p`&s7_NCPmm&bTk4hgZBHQjfj!>lhdt95$+-c+{#rOfksvZL}BF?5oI{~BUkP< zCK8J%b6A9AkBD_DAmaY;D`%(1HPz=;d*%3&l|``A@?2R2R))jZJf9i(q_=W~tW5LC zVjj94mQ34m(Qcx=shHv3@11EBW-Y zf2OlFGl<<<$x{*G&s{VY0Uw_Y&u0d)TPvb%5OL*0tFZ{ls)s(w99AB)n<220C***L z74!%+)~{sMpU(-`U6LWN5(jeN2!ETIL0y6s9ix*^a*jY_5mD}s3*oKeIt(J68O*1m z{inNQ7W}8a>s+;F1`sZ9-bzs+2SmK8k*oR>|E?*37`C)Ugr=a^Og320r7C zl{j=tw7R`DGl0NK9LRwqP8szCK<{G3I+|UZ&I}+Fm8@7tgGgrv_8^dadYK~mF?;j$uh>;u?(FZZQ9@-PEoIMz`P@h-rb>K@@7QyZ+*1SH| zu!4gfm2>D@FXPJHKK~W9DSUsTtW-gL7i0A6zqd4^U1ig6J;e$Rq4iypAoB0Cv>M44 z5qd2B)>B!b0YQYS|M)m8qPz}#5uvQ2?DLk_!y)R73T+W1IV{3;OyE#2ul|uQ^4DU0IN<6HaF(D-ZS{(8w={DA#>8 zCc;~BiZ&eS%s?b?2*LV-|9Hjm6F|v|l~WJ@yie*h#8T^E-XQS$w0R&d!Ko08&f13%JlhavMlEtB( zZa6FgP4w##V{;@3AA4~ft>=)5#75=v=D+DU#N%?+dJY)`Rx!H<5${;YmDj}V*0QU) zKj#BSdOt{Zu@VPzK&1DB)Eq1ExqfqVNw^y1_k$p?5(jeNaP`(5q`4ogyWRU0hxnRZ z8>7k)Sh0=)#vZGZZdtf)tWh!yk*RgJU6%Bp|sOjMU-2&}|`tXyR? zgZ~bFRy)Ogt2~JOo9nG6MW`P6x5}potU&AA-}9)HD`{kkC;{Q7(J~ztxlwBRRY;&~Ugl6@K49RxUs8v#1;RNL&{DxBTmI$s=>+HCR!>(H!^^ z0xRVF8~CjTS--j<*=5~-6TIrdzh-7&wODC?=;R|;Z3G(YH_G*IbBu}bR^m`EG#u&7 zAWgLLvBzCo|Mq}?R;~3s0|@1cPDBn7rOz|S%KDW|)&nA5IoY+|ueH+3+lX{#;CB8d+JC`R3i|ofqq%cMgm{{8&y`5B1T80s>zoSSRv=XwPiKP>6-F- zxLmnAy4^j8Ta*6p21qR%F3N>nl4p0xO{<=f7TOHOM9lzE0xcUo$h<)k;?H z>g1D*wf+wXG~!6=U)LN|5#g=a9}P!3GY|&u0b@&I};15(jb%QBMHsMC+GzsK;7SWe7z@Cn5(#TzNe+ z$jbVaOjia(Ix~R4ih8im>k4`ftgK(jsz19npBd!KT8X2L2(dLYgFT}p3$31RI4lB9 z^y}`)n{#(u2p_wRFnHH}v+8dBMk~)D*=59^V<6hkGY~sgF}ntl&J5%Vgg9Ky{dpWX z;+2zncwg2^9Bo88Gf;D^gm%4KUvcu80R&d!Kn_u*GlS`N@0SQUck`J6grbra>u3<^ z%)lN5Ar9rOb(XZAX8?f}^=J_3%)nU!LL9Dl%_$nYWN3X^D?M%z`OKhSagA2~w_cI+ zU#XNvtJSZDN>)_*{Zh%QNB%3WR+AzWRhdJ(QyL*8>(^+bJOZJp^b52lzWkSaiG-CC z``8>>EeK)_aAiw1Qf>x>9E)HE$!(h$BJQH6Ih)?08^VcRoC@MM;IdG&igRHDy$+mav?D{JXzN{7XV4v3& z`OF|+)=C_0L|9ETGuSgqve4@3hQlJzM8B0mo2bS>cqM4k26?{5b}q zJu`s7DrVOp(wTu=fe?qQlRu9GM>;crz)Bp*0g=uOrc1nEak$>CuQ>V400JvSGqLqN z0|>0dfvk13uTgFt{rSJV&|jk*M}P6b7jt!X&n;e3xUY4-+;idQw5;IJ<2i@eMk=ZY6k*PxdaU)f^J=RV=PvfL>hHcqvVcHC4L}fW&S4Q)2`z5rFh`)V`GK#z z4#(kMoA`>4-PT63)>q{4nixr4P1UKKU3|r;yj6^I{>g8X*p9E|mT?&okJX zOIGjdtSlqY5S2muUI^a9-{yIS)QbJlaHKPXG||e(E}8WO@9~-KdS(EDRhp~%s^$?` zS-+CWdf2c z+*)~$70Sx`m8=}HKkDpe2&||_gNPOM2&}AM$##F_GlP6tD{-_DVKvRnz!~MN{COp` zdYU~L>~;QHP4w##V{_okTG;c*E3Cxl zYF?j-`D+s(uo4Gy;7Df%(fjtO99LgK#uJ88N%m4x_>d_$5nL!%sSF*aYbtblE1`t?@16jGsXNKP_xPfbJ zf0gHM^s+mp!u3O%2WMa1vVud8=Nw`mg&4_U5tXdSl_JbJRD(rVUQ=5gw#8B} ztNt_BxW0fugI^Ftn{!wMRzizgIm{7gY<}P?ufuV;@9e(b$L`R5Y9m?eD{^>EjHE`W zPUY<4D@Nt5VpM%)A?I-Y>NP1s9MoJW{cC0hTXV_kU7dVo1R6LD+V?{69{x5nLu$qT zXgJcDL7HggW0%bOg7 zAkvuu1XkieZXxQKL7iy*!bi8~GXn_4ZhN;u#Ff_*fHc;xWM!KDQD-+pU`0I|L^?A_ zWBp3D`y-zjKwu>f)_nYX9f_8T~@54L8LPSdk};;lsC@Zd}aWF74>Kk>CC`c0zw?>%GR0K zni)V~B@SfeDxVn+oNy1<+WskL-RotCaIZ(+SGayiv)ldsmK7X&Jm(PmD8xt(i*T=u z-A9C#BFs5dgO_IgptgGWmVuX5fA`+n0s;*+070}lheco|w78YS9D&B>2fp$;9EW>9 z!(Bdhhwf7w$y#5L!)szBH9~bNXBS^FDsL5|>MIL5hwDDCNfF|p=0fRTGc(wlOIGjd z(!^&I};15(jb%QO^wOMC%tmx;>v6Kqz+GyA2|p8Kkj( zB`eeHk2<^c%m4x_>d_$5nL!%sSF+t7`OE+UD{&x)T!p{Q%)lAtto(T;4)rv95L7cW zq=>OO@MW!v>uAjk;)qstR4#AzDVjge00OI+U4uwx266>Le6IfWnV8QEAg~e#a>!FU zGf;D^#Nm3kKHKw|0R&d!Kn@(~%s}sA#X2~5^O*sJqLLNsXb|blz#ar44&{w=H=h|m zU`0I|L^?BYmVgk4y0Ud9wq^zpScwB!xyomT`!9T)Yi)nUhEI6eA^K;&@kHVJAy{$I(~3(QlvHI8S}8ugKvwDMEEBXBS^FDsL5|>MIL5hwDDCNfF|p z=0fRTGc(wlOIGjd(!^&I};15(jb%QO^wOMC%tmx;>v6 zKqz+GyA2|p8Kkj(B`eeHk2<^c%m4x_>d_$5nL!%sSF+t7`OE+UD{&x)T!p{Q%)lAt zto(T;4)rv95L7cWq=>OO@MW!v>uAjk;)qstR4#8-D_5=O89-navuhCP%s{R{h|kr( zJ`?kq0R&d!Kn{6IX9jAHl{j4Q)@OS@Gl0NK9LRwqof+s|tXK!$ALBjZc@BJ)DBZWd1gE%Y_6|pi_KnnpOSBc0J zkU61Hs74_|Q4xsb-S>V74Kj+TwBXcLXtfm=rFAS0bbt3bzaO7{^G^P17K?S(Z|~3j z-gD00XS&Hr>Hqi72`}{LH7PX%l`egJm-d|te?QqAu(Pw_jcR; zcK6!x*xkqZwocgp)~^SNpDcLR>2~&;$Lj>WSf@zbvh`QT^i~t^Ij6Vhyhprz>l^kT zKkM!lcj)(59ez=#t!N=}=hqf{{Z2plfc#d?upT7n#TJQgMGJ`s_kWky{4F=`+o?GT zda>Q2#`MA+daB_)bC2q&e^s`g9A}F}f)*05x!_YyUp0I0&Rdb77uzjr?7HYYf7TCQ zaK)ISLvLku=pBCK@&5ao2j1A}4_ZhlIz(F>Y=EE_TO_^}EhLmx(y;jI)SLvp*lt0i z`OgDC)#_OXzv90pO~dm}F}%Z<5AxrizG>e!5Q!ENrsuSxJ`fEFdcCZ_k!vja@R?Dg zVQyRh`g7Hj>*cu#<*cQJgk_b}>U)2yW+sAO@4Ws(f2)g5esXOjXdz*_=NifxC+vUz zRt*VyS-iQ1#akvuZ$%3U%RSdnmPHK`^kUBjBGE#^;@CBmy>)_K?EgrxpDp^lw(8Yt zpC?*KSid{1UJV)z33{#hkGVc3?)c5+oqEilbx}{zzVgs3*J{L6*?Mh^`5!bAEhID+ zinjjf)d_lWl!(NNZQtc@wfc(_t;RwJq6T|S&(m|2S=AnFXd$6q6s??z8YJk|zw96BaI&DP@ z3H7x!lrvF-1iejb?Rl_R3B(pBevc6{|_3ws+q^>9!5p|V;-`JuAv=0szos1p_?Jy{fm^DcPS%NO-8 z7}u<(-=*b*{Vx-=kT~@VZ*h%dKGJ8COhNIZGS*{<=(?>6tWE(vSc@98keIyv94FQd zE{{Y*f?hUCOsXCl>7oWLBz8LCZ=HDJFIHxvDY4s-pqExK($L5nG#Xk+Z1v)2oVfN! zE22gsK`&-n)S!jLpDnzmr?>jfX_v*fN+jsTe2f|z`SmQl-G~1BaxWjZ@28dbUe*%> zk!T^Y)eRRq@sV#l8Ht7jy=)9|LgPTxpoPS5Z#v6~)o-00YwoL8)kDvsmsZC5UE@I1 zpoPSx7a!xqPmlQXNHiqq#Y~GDw2=7KZ3|rEspF208i@qGn2%AzYUa<<+kI!}4|w@Y z|Fdw)^4`mOVkBrGanA!wo!Ec&_EU9&UN(j}p>ZG*w2=7m6X!ee`@8?J0fJtd`PG9O z2ciZoBo@8>GAADY`gI#1=%p2mG&BxG4O&P%b)b0hK+wy^ z5GOPaL=9Rfgf?mwDs6h*ff4r;b z8aEtqQb&UXy_kBcdz{#9<-0dP(96b< zp0qV`L=9R zV(iqfJMmX%U9tg!Ud*(pK?{j9=gf1BWiMLM(I7!D=3~_0deFuzZyy^6!>T_LTBE6N z)dD1*OIP~uU;fSedrmaNl|Bi2+1TQQ-Z~PrkeGMTN++J)@rk|STalobjZ;o&bc!0Z zkmzr{!inp*o7GjuH{)t$F#@U4mZh|CBy+=~CBt+r`ID(L$p1W}Bl# z#CdC$zqw1$i~XO{>YwJ;?af{^O$&+An{AE~5vH+qm!KE>Kc#=V>v*rn6Aw&H(?X*3 zf19I3#QAGpKBr62ixHF3bsvA9YrO2?7Y%43QR1rA>{BP`6(jM$CHuI>-Un_opoK)4 zOWHg~iLkbs(vrkGp+lU~I zUtYFkKnsa7`?PtEsuA?!e3jBC&;I1NG#>iI(g7_b%Ba`H5OVEq!(v)`F;;dCdT}M2 z(oZ(o(KV)S=nZHgQP#VycB~^JbqRXK74qe;+|M=M@$uOMT1b@rXPfu6g-Bh3Ufi*! zw9UUR&TVzzZ>MP?QTCs0-q#i)E$R^T;*Qnk+JFD3YdpEnKTOj?!e-PdTd8SwwpE4* z8?RP%33`=sFB6B{bh>NIS~50G3yHG-Z1cXh5UEShi#yhou77%|Yix6R+tNa!>{#2p zuPsFC67=F8H>J%#dxkX9vA>=*K?{kp6K-{ul?kmGx&*!A-ud9`KIR$^{OpPeT1b?W zsWzW@iLmkN^Id{oJj+Vy@85frYut6>lM}R%C?`{GKJls%^x|1oN^hUD&@~os^6EY< zB+AKDn@_w%X#VID^x|1oN{^nqt809D>HIz|B+6Mp9Q7109yfUp{FYVJp zqMTW``7B(-`D>QHsY}p{r`#!R@s(XCq_M*@r}t?gQBJwrd=_3K=*4sKlm=&h$u({{ z^29zZB+BV|tM6ZRf?n~w{TFM0^UE%GazmeCYV%jJ8bL39F-z&2bB=b68&Cc21T7@uzP3itizhFmy>rsunHCZ@@A{5D z@3yV;8vAdcUM%0$T79GA=u^H9wECteKmExBEhIQTX7`y0dX=vnt(_-!G-x5gaXxC0 zpqHIk_)11!Yn&L>gBB8;uc8JCdg-)TtEKP-%Uf5fvgq7|IVey4t}~nXR~Ej1m&`($^Si=qxa5&_aTf))}SAL|6Y zl;6_OSAs~;LW1LbouC&pEfTbl;Cxjl=*4`DL^(rlbso+0MD}bXXdzKX>T)icnLO^2 zpcnf;YN)-{?)qNC6EBTM`rTTljRY+ucqUgT=v7XmH70g6Xd%I~#i&7oUgcE19i7k{ zmfMOJ5O*JRPnR^kO~+qTyPEJ9^8TDYfqU>k?W>@XWzAnqfwfpqC<3 z8d_6Cf))}yI|=njB(a67i*&-y}_pqI+h$k9G$+2*eC`eh6Iw2)xDrBoy6rLr_~wD0koNBrF9;nR=q(?Wvr zmQszNm&($}(SGpiqg-RjX-oRFkYK!}R3qr6vNSaIr*!kOU-lG<4?VH8PYVgISLy`4 zRF+0wEm@RLOG8ml3kj}QJTGP>=%unWlmRJOUO1tsr-cO9D|LciDoaBdU{Uh$#sk$u zQBMmAu2<>=y;PQlG9V?3a@SDQ(?WtPoJ=S`x&*ycmWDDQCCdxfP}I{xg8Py>K`)i1 zp$tgL^1?L~^|X+%C?D6@u6V8!^io+GnXtTY4MjaIBrM8ZL-Cwaji8sx(#VA6g=;8J zXdz)y?iz|`&!ia%dZ{dpOjursXp|?kkgzCs4aKu(l52DcdZ{dpOjusHhVq0K5*FpI zp?LQB!!^1Dy;PP)CM+*pLwQ0A35#;qP&|7kxki_um&($}ghjb)C{Ji1VNvcHif5lc z24(&T1ie(2MkXvTTtj(63ki#I-^nPReg5!zbP0N?ER9T9UTC~(lqa;1uqby8#k0>J zKEibgdZ{dpOjusHhN7Mp5*FpYdsRI9{NWm1f?g_1BNLVvmb>rslqa;1uqby8#k0>JGZOStSsIzpDoGm36Iw`Eluv2gRXqFr;p?j|K`)i1 zkqNDqTC7P z2`wZn%3VY8?DNNr1ie(2MkchbQazL>w2-hUcMZjJUWv^_&`V`$WTLj4AYoDN8j9yQ zwwIB5%%U*-O=9JRX^a_Rty|_O?O2BMhg;-jvDA~7>3P}S%G#<%&`V`$WP)=oEhMbn zT*F#7x7DDum8%b*MK6{0dnUL7poN6>ziU{OSXAJ&`V`$WI}nNNK`J;LPAk44U1>fs1fv1 zSsIxrdo|6q!+n%nNGQssVexDlh49@SpG7Z~rICrUgKRW5(n3N}E)9!k(kb6HRF+02${eLV&hY%oEhH4>(y&OivAqz=lR(f* zWocxBb1f|-6y?&ec(ysJM$k)TX=FlCt~}S8fff>qa%osR_u`s?1ie(2MkW;H($Lz6 z77~hbX;?g)Mvb7C%F@UL*Ko9uP?Srfs1fv1SsIxrdo|yA(LzE|E)9!R)2I>jQdt_AP+q7WS~bx^LQyUai)YiQ z5%f}78ktaDNW-FjxUY2!2}QXyEK*IQM$k)TX=I|D0r*)NEhH4>(y(|ojT%8Om8Fph z?YLAAt(s^dp(vMz#k1wPh~ZfV33{n4jZBm?8DD47LPAk44U1>fs1fv1SsIxrXG?wt zOA84_xil=EO~d{)_MeY(cAt#LkKHchBc`6Kezx0)yg%$Vt4s)Tf)+*w`$-bdYmlIq z-K6Cjb}LuZXzT_W&m6nW#^)owm9mI$>l%{LTj?g9Q9YPl%z{8967*u70@2ugGOgak zZZ`52h05NOt7iG{b}vq>N3uI>Mi!2b9LJ&t33{vu0vF*LtBGOi9F+3+`UkCFrHHH1Z9xFP!^#zK^>9w37$4 zkgzqXqGU4P{aGXErLr_KvG}NSdg}R~{d(zu781PeF{K(oFO{W{@0y&y-_5>vR!`DG zf_FFCzr3#y^io+G`L4<3m%Y*V9_``<16oM%wny8a8)5x1r%TXFWohW9(v-e&&AVOW z&=X!dpoIkQ9jz1eQdt`L*3%nz%;#5EefyYcT1fET(Ue4NwP2rBU4mXJOGEd-ru1Cv z_kJ{+y!wH0T1Z%?^%PfmB~yshCFrHHG%|6^Yz^Dke_s2mZo9<$_L=3EPJZiq_j>ulJ04%l8C5-@ zKTb4%*!n*AI(4f@_o5!@>_60?g~WPqHPlEX=(XNkHA4-(zuLs=GsfQJ+s3z|g#`P_ ziID~gda+KCP#fv3j2vS=s)hBt)${osr1u9cB$#PYg9N?UB2L)>TA`|wAOOoWs5|D z78068^`t!4W+wL_33{>JqK5iG&oXk7D<}1Xez&%qj07ztxF)I-^kR!df))~76V(ZN zvE3rUF@tM()mSxGHbjCJ5?q}Jq9H*q#eg)do*fNZNN{x?HAv8lJsSyHNN{x?h(v;3 z?EjQ(#_8Yx*rlJh8OK+Bwu1DtFdGN8n)K61m96GIolK@=vszzDHV;nGLc&H=r}LR* zji8sx(#V9(&aPqe`7|vgY`k)fd}diA=%unWGGVI>*RXZTfEE%qKDtIezp4@RQdt_A zu=SPJiOJSi16oMfsEyN)8bL3WrIF7|Y}Mx)woV+-Lc&HkoPN{@dZ{dpd|qO!SFIBp zTfGiwAz>q`pML1<%vZ?MWxX2+dZ{dpOxU{JHEb0=poN5u^R1#XpTiYG>-Ip)v8&UyJ}o3{4EFrc_fJ1BnUSEE%F@V$o#I$L`ngY^77{iy_*kMZ zzkcpBBS9~frI86cjhc{#onQ57Az?FIPqCZ7BG(9dsVt35*r{4y8g{DIr-g*g)UJ`g zB8#y8&^cTn=%unWGGV8Ku3@KxeOgG^TEaE**Ci3#7%PjU{CUR3u|i6Dq2WzWf0qn1ihFmk)VYHR|a*0UX1BTDE>>tt>r3H zZKU7z4w0aR1lNysf?k%Jo`Y)jNYFxp>&H4lFZN9&7#SRc>rp}r368F=(F~)V1idt} zsdZJ)_*S%#SZ~}NX^@~7dp5omEhM;;iEl-MUhMyrCZAi{pV;)1*M4u8-k1@ikxcz- zwbl8|+EVth(ryJl>Xk4h<78x7PeYBO3$l-w*QEH#2&%;uD= zja)-5KnsZy3x4KQC+NlK@hFi-qc)?3g!RAjLlI;7VQn-haTN%9m2$}_Ya`cC3(!Ks z`rkEFH*Zz1d6%G9DVO=f+DI$pMr}q53G082aDFE1k?3pcESYp8B1{U1%^yUhRq literal 0 HcmV?d00001 diff --git a/twil_description/meshes/fixed_wheel_support.stl b/twil_description/meshes/fixed_wheel_support.stl new file mode 100644 index 0000000000000000000000000000000000000000..e9500ca6bdcf300362004bec4f782ad0de4209e1 GIT binary patch literal 76584 zcmb@vWtbGl_x{~Dfv~uf;JVndi|%wc?gaNB2^!ojz|P|CZo%E1-RW-JJ-9^)?hqu% z|D5XS;jUix`}|%!dnH_b&AC5)%Ij2B&$Oca|NHkY0pHK7J9nKoH={ave_zj!x6c;# zU;E(N(>>Mj=r0p&`2yi{2*vC8A(i3s;rJ7u2Z%t*90Ghegh;JJcrC~W-^)om`V*hW zPWXMei9pUpKG=`fm0R?uvTw%+r^!y4Lx2xV;b+3j440RabAKJUeTY)9wf4V)VDC=( zxC!A;A}qfT;ob4)PhpIFFzIC?VEF>!FRMWZhl={By631diR%2X74v;fC+`>6Tt0jq zv@)GYVVv>j3`L2JKowu}oopidZ6D#I?9v$~T9EkeZZhGc^o!rf2NQ?yj9l&}P{r5m z!zLOY{z3T2+vJ&v79OwVkJt!Q@iqGh z5US$?El5n<^CbLpKFG%x2~_d*=X}InJVRq2oO84wapc?19`<3EE)zGXKHLPV`1*5w zly3G+_&7p!jus^TTDMmCuv@My(z#e9d*hs$O@K ziP6;_eV8~yKHLPV_?ms#M7?)?gpcnR%`nk|#Pb#Dgb#ZZWnwgqiEaW_e9b;=qT<1! z!bjHQM-8+fvDH6I@Hnq1u@R`^YxZFiJpWOZd%4~n%d84Xw>sCXa%ldXb)O>{w0wzh zd@#j-Ufr3a&<9`h=Ug|A4?9H;;aD6W4()s{?rjMd^pE3%y*tn481X}RE0e>-CyF@s( zMk?p?z-&O7v3nF+@V-u|$LO_zIg0OvDrbxd%pdGSL;>8No%xPO2EJw$`*uDLl&&Dq zf&}|;=-3HVaSEA`@*&~|T%X~3kV}CHskMt#p+zF7HkpuW&?fxedCYK9#j_8tMdW-q zxpn3!zAvu_kd_Iw;MxG!BC!*wiak|4!f{GC9~ie|YGog2K>}A6u@k7mJV}HX>%eI- zTnF4&VyO?XAmLm~{X?`8ycenhZ2|kBO*rkx-|sjjPG8~cm@N^@9aq9m+m&XV80`uP zT&qiEB}P%F22mBr2hKRQ4<{dFK?3(2Tt0w674|flz%>W1ad@`l)W+1SiF-9M+M1aZ}k7E!bT5|4% z_YL@q(c1A|sB%7!(W3%B*n)&pA2IreO!(`DRn8b=&p54T479k!>fdgo1@2327b88) z6YUn*gqH{tEfV2GQ6lHyLnc5K@GXc1d8%@%yzLicwa~)X9Q9u%l@mYOIrkGv3pE81IFig;fxtIw-DCam3Aa=8gq$)(FBOMhPa&q50lJQIEPVXFls z5vX$JF1rR(59>fOBXE?LF1THH;O{_ z@nr&3fl<_HC4%5~g%-Yc?u+r9Xo+7YAWp=YNFp?};C%!B#Mn-4*YP0}PO3;1NUb1p z=e2VlH9xD47QC-hZuT6-#I4;~a>pQGjq8-UO+cONXu^L+Un$01PVk4yZ7`&5Prz84byHLl0rt&NR9l|K&h6Yg^y_QCf; z!oSA#eEA&5AyDOy&isV?9ESs*v#SYxzspeU9T0sPadze!_h!!vxm{ z68_yUe=CWNK$SmQ{@fD99OazKun%rmNceZZKDT!19LFJ0<&WY0g!>$a3GN>fVV}zQ zd#(E%CqRJ8zZUTm?sFU_xS#v?;l#CnAI?AexX*DM0#*JsgP(Ap<1oSF6%zhkb^j>p zKF4tgRQcBoe!_h!!vv4JNN}X@jPo(iaU23w{_ z8-Z&a+n0Y8FA+>T^OfU6KF4wUaQr!+i+hWildl{f&OGSk$?@T&%HD%>2&WVsI<{1O z-V4Y3I@kUP#}n9x^K#72KCndn>m5-Ca-Fl%A<%+^KW6X**5}?Y5)?CVs#qnrUE#t` zl{m*?6~{RK$jQSol|1?YAC_Ymk4FP`ATWP$Td?C@BrvYU_|w0J``l{@vg-paNXU^T z_z>qf?4A2Is{Cs>(VK03z=ypTE-XmMktO(W_ACW~D(ow=56n5{NnTB$540fRUsHdf zT}gz!pDa|)s2#JlqXq99@E4=CO9ZXYMM;y&`8;N?MGM~7sgD@FHZVu=y-?+hN`d)< zitF<^jx*o!$iUaEV&Bf^f%*_}99ocI9}XQmfhzxgfIRxJ4==9Ia6QPSz&-+VR3IN{ zkqCRYMXqy^563%?8BVHrJjb<&oDV0r&K$)lan5o0TAB@n54}A{vJZ){pUe~MHf+-_0$MxX7gv+9 z6R5(LFA?G#hjYlYFs2Y!ND?8=ahTxNj)eczA!chA=Qshv-g^@&j<5K0X~q$CjuyOc zz+a5kE)h=y&T-fWw;zo3Fi$bh zahx)d2q*3mIR_u&94A143iBjR0W7M=z&Vac72S(f&g|^Ok9N-8=QsfZ<6S6)nCCc5 z@V)T9TvqJQE-UvrjzgeIE?s|H^m0^&79@CH`Rs#pZBsIVDrY9LQw4ka;v9!l#TFzm z;t1^N2hMRE0#(i^8Yo@S(w%c0C+89YkyFfboB#o;z*ysaN~ImUC+ zsf;-J2@nt`;!GqF;#7tSXYOMk;@a^i#&-8PPJjSaARmHopW}#BktL81zJ};rQQYS^ z0RmJ`ec0{D!vtIKzE1tyv5)`kE^v<07KF9eI;q*s4=k9YHhd>oy^XE1}rORVU;2g)XNQ5)4I5jAp;{*s$1;#5u zzz8RgqDV+<=kW`NSQR6eL}}fVn$5mH8ohG=A&f%ifcl}I?J$}Zh)eb#9MskNsr)syoPxL3&(Nm%8{z3sFi6Fd9b#BHh% zv>-t>D`>lw{5kP~c7WOyw-O{!MXg7q%5I5emZa8~Q4Kz)mWZmkd%KGJ-c5VTkO_~U zcuE9Xkf2^5XuC%pjV`QDpc;%%{R0V9QBM=83iMi?dTkl*wW#WU=NEC`3!9G{u@h)P zf<_EM+oMlNbThpvwe~JFmLP#D8kIz<0wbJGBU~9C;ZU_Kl_Boiddm?bb^Eo5V`M*lf_F*OeHy8eKoyPPB31U-K5pRP_RRU z-YDCWG9C7h=XoMex)bE~DLzUyB-08i6)Y`-ZKarmZycZHqDdbLOk&kUux@BqRJeXsgM4-wk z^^dI$B4}1~>RdyWQ-e*q8i6{uiE@6T?|&yWycZHq>zQyWntX6eTuyaPEm21TRZa`7 z-zh4jV07SbW}O5{dU)=K>x6bd^2q#dQx^B?}dcZ)6}3ni`aCYf(l#!UqilPk8dB8iWsGgYc*>$e?BbiB5=csZb znFrtQ3dBA(0nrlIdEj11PbI?YiOA#<+{+{=lOSKo{d z#MCyyQ8*JdiNJdyL8FqmlRd)KqDY_TsIoM|A%Q9yD@Cg8ad#`NCNj`?b&AGaR5`1O z;c2bF`oku8#li%wSa{qG+zSaB^F^ux^M^H=QbnsGi9i+2E8{YHtcZb@HT-RbOw|Ag;Tl+-K0|(az_ric0vDI z&HXJpBv7?#-J~ea$I@!N#z7zTF5EA}mZpE6G<+e|McVHVJ7E<4Fj`!X8p!KG`tv$D z#~eDUVk@Hmk7b2~$JX~CPo=fZeQK>8BQC!eZl>`RJ0)Blt{XZ95b*3r>vZmaNRmNf3 zc(D$gdgeJQ_WD2z5>AVe<|vUWBv9q}=5a+zm4X%|9DgxeqLXv~OeS*6quT$iKAiGl z!YMat6pgh$Smo5FJ)fUFoyS@g9A>?^J4K3ps1!I=K5pR{snM_85HXX8t3;p$2`Ujm z+hvtHbuw!P5$(p`mIzc~jH)QtQzf%@6ETzsv>-vHD}30cn_=HM(;(vf^fXeuiz3qBc|=@z@6(V#74Ez!N?#(T5%G`+v>-vf zHk^BxJ&KC0bffgj3`nRLkb<`5M&VBddTS%bF=>_(F`zs~40KqEDe zyTL7jB?48>EMcFROdx_s(I6twf`l{9+fhbInsJsAad&zei9nSz+u7$Ig^A$t>J1TS zLBg4@I1W;jw={F|xI20LZ4(JpIkUEXn(>Z^%|z590xd{5^DalrigLvtGn~FVMIun; z?7Y}#6TkUmhJ^Q~m}o)5i688BE!Q{aqfHk1d>K`^kD@4C7YphC+C-oQ2^v?#e9oiN zXX3{!hk1kx?C+q;Nv*xN#P{bKoInIxkZ}CjYXcgqbcz}Dnv^QC@QCc;9QsE%vF312 z9qcm}y1!0yt-g&2w2(g@Q9WFucqc`)f@_icIjU%s5UJwvLndx4=*^Lgo{+{8v>@S}A@FH0t;~s7PecM2fhrn_V0}Jj zes66G5v7Sh6^)O96J?p8SX8AkQKwkcLJJbk83Lb-E6ShKDyuXb==)p*s%Q)r`wxM! zUFDqf*p4ci8N^8g&lxh2DsCDccXf(hEwmuvoFVX21d5U|P8xF@5i?u_s%ZA%DBNSu zYSWZ7CikexM4*c1#Axn=JX^}d+eWKQZdZe7=0pn;&KUwfaY0Xu5J7X4KGQ{@iss#D zPL(~MCu_XQr1@N*N(8DX8W5@CI6)?kS9oI%C*lOf3}`{ZIYZ#5QxxSk5nSh+T?DEq z;t;8_Bbl{CaLx@PP(@LVNEJs&GSRk8W**yh<%7>e3lh#50zb*4C>@C49>ozE5~!kB zOQgz<;YJcct5khG5vZaFP^5}uLz$q+(xTW$A3$*;T99zg5csJlic5&#mYC8-po*eQ zkt#cSJxK(`?fTOS6-`u8>?=~mQL#)^xLMrdk(zfL(1L_>ZO>}|Uj(b1JK1XkB=BC& zHLp2j0`j4u1qmmAd_tor6ovEbtY4uO3lgYuO5I)+og;$VRSH@ap~|TbK2eehsB;Z1 zNH}eQPqUtwmy1A^GfVJ}H~kLs=lMfN zl{0_v3Ajwq`oo!{bhIGh%w2r?F3p1yfhuQ44ea|kbFGdlXRhTlbD4noTt^EM&OFag zDo8PdM4-xvKI|PYh)Z--IdKV}nac#kJ~~>EaAG2Us)L@0r)Y`RANmp6heHBYPNZh< z^<^T$AmSVmsB&UBJ~Nkz6ckx<+x?pM6VZZ%6F>43FpBbuqE}jZ>1$jBs+_3S-sOx# zK4{-ZpGO3$oOqYd%w^&tMd3Wc<+?XTLkkj4tj$jgiIta5YiIp9?Y$y_DrW^?uRku6 z4<=3#fhuQh!0Q^Ba8@ijt#QzTgtIQ;C#w{N*EihHr@9DK;d)0=crNFD?j-^(NceY< z{HHQJ&$5pcv?@XZRSs>hqwGC;`;@HNsg%C{W>z(g{=i7{?bqUZe&T1wvzCz_{(Nfb zSCkJV+Em*nEa~?hFlv`SC$2|lJZ0?dxmjFKdCm2K1X_?N@#2gi^56Pj1ga)$XhGt|^8--zp+CNzPrW-xt_Z!%Mb}K;wRoG%=0xd|ad6w0~J{IKu=t>n5sKR=Ze0Z^} zuzXr|nj~^Qv+*0-hu1kp{^u9F{j@m0#7H@~mqNqu4KtTt4pKP4D5>(B!Wu1AA)o3yH+%Gcx<1H3;Mb zElAv0zCpCzJRw_TA6~3;Od-;8KG1@M)oEuLPHkkBjkXW3Q@Ti?D%Mmf<=;h$GKpVp zgOR^{YH^)-<{snHwwB_0*WopCJ`}Vd@pSQd(dX0tw)KAysKPwSIY$c;m6wMJA2WaR z=R8m!NT3Q!LH5xy+gy>uhaWc>ckiYb*FS_GH?Txx0xd`kHgXEO%@sb!vH$GWjs&W( z+$6$_v)bT-Ydu`gX|o=aW;lsZa12Kx*M!-EZnMPyypPvuB}kwOX9?K{T9Ejvy;u0C z(b)Y|7!s)Z=0-z7q)Y)%Kv?VzE!&Tk7OMX`95(X3{Z?E@59fVR`_C?2v> zv3t(J+J8%P)V~vli~87*;I^wi(1LSRjM5GGKmt{@3(pch-j2TO@_`m4ur}pnb<-{QTmae~NRRuT}3Ce|UFxcsEit+hZDC zjB4RM=z7_ZDC2ae5@nd~-kJBvFjeRS?<*4*>MjyKe!lT33@u39(3T2+#oiwvA8XpJ z3FTBR=x%IB0#%q=IaL=rmEiB=c&cqXX?#~bl{iuCedoL}+51Xd-%sXxF5HV2Bs%2m z7tVLunb2JyNT7=I#DrbCP*z^FAQ3T5JWb_Uvci=r1qoDLr?O%nc3FWB1uaPQX#P+TUbRtxGgA(I%W9|CgR;mvI8whtW6Wgvx103yEqoD zupyjf5H~U6v zB}g2qe^t;=+VOtk`LWR=9}g-okO)+DqLGN}oJS)14U1c8g^wHC`-GtdiK_R<38L-V z?Q-cVNTBK%jd1KE<_L!tBtAW!Du~}3`u6|=b&dq8MtfgHv5(U!+&iggL88O(6rz=k zJ>&L)1gfy7N$pBO3ljUhtA&q7arso{=ZZN*E17;JA`A&sVSiMVOp|NrA3l9D)l4h3 z{k|O0nTxbgbNn{iSoQ5mah>$wPsWsMW^}z0Rn$Lj^2#eC5g&=rh(HSxo74)vHEToE zA%%Jqk)DV|ieeRZ5vXb~R9O z3|4s+*SCN!uD2u`Yt-A(Nn9r^(BCEkb&dq8cumE33ar(rQtZ(OElA}0;gBGzt{v|3 zfdr~{%-0)_cl%nM^CqiSzb}98L|JVZ6$6Ra{S4J<@pH@lRj=d=1rad-0mn@xiG= z3lgc~-}AALADb;CqVL{vdcHqWTPG$j(6FYk1|Lt)=$m}5h}yF>*Pyy0kKQ>>aVvYD zi5gmvc>kcjPYW)jp1aY9h}~<_>-Qd3w7O>MD-oz_HX)B7vJPM$>7)B<&now~Doi=7 zVy$5-L0VCK{Ss)4;tjE;e78hJ3lhFKA-0`G zu2H`74~f<(EYhOhV1!fN_H(}}p1BEOZ8>iku|NE0ncU^}K~QiDoalb2_= z=0(kr2vlLeQIvrvEv--2g4^#m?`lHKm=NlNHF%ip!&PZ2lVcLBdf)^d(})+|%1QRoL$q>@8!|{(6`?u+K~bX`3iz z-WLQ~kZAm_u<^F*WOZU{t`GL{_3yg`ftD`wzcJF?nWvVVI{6De?v7do z6op%2;ZI3KOT?Cu=2^IJY3T_mgX`l(&34<|EfH1N#_ZBr<+Dgsbu_T?_(MIF8wb@y|$6=V(D<^j{OgD-6r5{@l2U-$&nf zqhb)K!qJZ2Cv(y=CyWo~u|z-7sF{&sXD;*^`|Oz*?A&WNT6y|>wLzudZpCGiB}WBIe$^AF82@p&BcMj z@=xcQ9yR*}qsq%f>eaHDJ*PK!7O6^IwG9!}63sFz%5f{v(SpRhB9TVs3{N}_7i)eZ z&fYpP2vlLIi~eDL-(lodE?u-BF`&&)M#p5=J;Rg^7jSN~+^@w`FBbODmUGrN1r`)b|v>>sp=0o4XL)q2nMQ15hT<2Z7?b_-l zQ1xG~tVWq>)zqOwHxWT2gSo5IE>VMMLBd#g$(P|PkJ{shtNxsCjvvNjiH-!SIDfqU zuv-b2Rmq==iL%;1CerxtL=QE;SM}t0x4`IIyNB9z?y>M9Ifn~kM%_~6gL9sA;~?&} zI$Ds3Gj^d-XI6c6--kotVk|MUolPLh3JFxPZ_YXUwu#Ec3J3x%NGv}v&luakq}uw< zW%9wPT0bg@NEH&O!ZvODIHt!DEfFn9EW9+s=)3D1HC>61&F16A1a zMSNurnf^)SgWGQE3**FCQoYU~V@jW8YRQ!~M33V5+U`+Y=dT~v7e2U0ITj>t)B0&` z#Rck>#(Ai$DE2XDE&WHdT_jM&`CFPGQsv$(A{ldau8Z3!W)S&sEJ#c(HO)v`Vw!qr zN+N%qr=9;alaVF*h>mJK6P~Q)ifHK?2viijs(k7esV-5vXb~c7a$spPtSUK(U^Utm#9pYiFx$Fwug9 zyqYLZ#3&-pxd>GC>#|g=?z>G0CLa$cceEz`T2ssQFxo^561aL%lm|pC{sMujO~EU~ zs%XHv9OPp~fv#4UN4boJ%PkWvNZ^{vCdv@8$VH$k+ah{Ogw|~d`{p7am*2OsruLd- zUMs!ZL<Z7OCi5Nq~4Hto`xF;8j6{PocQS!limhotpvo!5lq6Ga|3)CE~yMGJ&cNXGR#jR*SQAB>8w(f0kM8*Irhx=g$qaAb~5r*a=iM zo7&yrHD{$w^T@~X6LXBg!4X!eC;$4;f&{Ku73HL#2zL>vx?Hq@!E5Icr#F+2Yc(@y z4K@w7QswBUq6Ge92lh885`)m;xFY7)`fMWE`$wXY1` zFFWzuL-Ii*oK7R0MI)Ss79?;rDMnG9Mp3J`i$K-h*H3-CO3iui9r>U!QKvD{q!CU- z3lg}-rC*^XVm1*pib@2kig&*15~56r%xK4<7j9>0(T1S(>^*~(rFZx z2vjv``=5{ZEMIQ@m+CxCkzl=DqY%Am{c##vkiZ>JN)-_;h@eqaB2e{scM5}dRkPK< zLq2GP(`ba#-^H(`p#=%tlcji|+)6y-S))rrX9B2ZQMLpg&_8V(M($Vc$WIqJ{B5&Fd^|9a4Z1fC91|L_yHTm-5% zw`gJTNyDhNYskm@ni;a$!35@ORmGIe{hr~)4 z2~^DpnkCkQo{{y*#{lv%p#1ePUO}P-35@OR_4$lio5V^O2~@@XcY#xEc0F6hasFQBv6&>>|(L6k#ir%K3rBo^~Q+x2U?K8*v`(!?+1#A zvO)q?@mnnsyC02T6eb^Z3Sj=VaHv>Ep#=$y?dTiQMC_>XIFwESbRG`Z6u$u=x9L#V>?CZO2oFhUXc$ZP&FiZPq70zc+gz(!7KU(@27}9 zh!!L;wzKQw)BDk)K9E3Ffr*X84s_9fHj)pn^Ruf{@;Q!<79=pXv-?NsR4+xZMFLf8 z3wy*q^^35BejgX|r4ac*3lbRHiL)XzS%KZ6K9E3F?gcr;K6U&QSIEb3%18DrlZ)S_ ze4qshjP1l3q?xW<7e0fO2vpr{9VB*c z2~@3L{-4<2{dW$}=Of5Rk3R3hI3H+10%JRRhXN7Gq`_gF4TJrJV%KQFz&I59j3gg>p7q^+hkT#~35@M*;(V@d zF$h$h8vTdZTe?4u<15Zby($~RI3H+10%JQxsYyiK15aWQsCt|Hh1gpfl7eGu-Vy%u zo9=SZNcK-I)zZz*T)$9^AM8Ws}!iD*FrV>^4U4LdVbqzVaC z6-b{&>@7v+yhT2E{&<=xtJq0J3lbRH*~G?(vmzfzpsM-KP_aiElIFt)Q#m*!u6DCSxuQ1!NU zN3oNdeZpeDkM46Ti17+7NMLMdkL_=IZI3~qD(^?H*sX7TYCQR%b7wPI?zkdVXh8xa zH9N}qvrKETXNd%=Fz%u^hP>Kkmig3KueUOdi6?wGKH@nQ{UT{(a_h%?HS|mmJD6xe z0>?2$IZZ@cA_}+&RN-lsqST0A#u^hZtG=W5EE6qA;5bJ8oQP3GY;h5&!qY5zI{H!* z>$rYa8&GnSi54Vq539BUu&z#539}E*>{*| zK?27yMTt*DNg^t`2vp%tx}r?qR>=xlm&`i4_ZJf_NZ>eT6Df%>Tm-6cCtXoKo&VO_ zr)k!NMqU#wNZ>g3KL{8(aqpep4D{r>S@zbC)_=P~Otj#AapY5!W<;n&WZW$isFL^e z-<)b<4)6@L#unXVpalsW#}wtYpBUjHP=)74^eY}Ie(@}M7GZTBqj=DQ1de?48$y1f zyNf^-o;1;HP%lFJb!tDWVV%<|T9CkTjP@CbxIjd47lA7I1nckSkF@LCT3C%w>Ka;* zkjKQ>2vp$-COy5ADv!S9P6=yI$S4ghNZ?wOMmQqY5OK>zph`NyRH`Pbp|@KY-?|aB zTtf>IxE7^U5z&)~tu8`RNhhP;GHvu%|4lddF4(2vX($r77NuveiFirGJ{N&1`7Cv5 zp00Z6s9>Y^5=%o161Wznw~P@HJTln$*+rlV&+F-Jv;{lr`~PX6&6*#rp#=$Ci_))V z6S0?wnJxlVcwSF?mh&3uHCFwlJv^~aLkkkP7Ns3}B0`8b?jlfyC;T+-ZVc5YR?e&M zD>_v}3lg{%rKgHFgzB@2xZxsDB|kZExL+dua*2BS#)r)`v><_NQHlVFI8Ve_7lA5# zW=2s;4qTz_eAZq6YG(osElA*6R8a~Ov73mrE&^5flnt$M1|L@6&l#$Rx5=iW1qob> zD#}bhQP@SGN`88$;npPPi?T!XzjC)W(1HZ6MHQv7pZMKHpbFzI`pq+cL{{4sks*Px z7DY0>(pfW-SJdmw9%)+1BaF=5Myd-Vw@A->;IkBpQYn91E9txG+N#G}&3skH7`e9e zP`9>R=ILsVHWCi&qpk~I?vb91P+B&uW>uLJUyrV|-b4!$JFAZ{PPX@|SI+P*XM?|L zT0K90(h9d*BN3>QQ&ne79xL)r34Q6`!%egxapb^oqxLJWdT-5I^09`9TtwV+5valv zQIxWj^TL$#Wv-lKo`$X)YgDz`tLML6LOzmp?O>HY7^2Ncbksx(68NkUoxT?CW)&VD ztS;*rB@w8~eSNHPvOo*<%sF07EGMGzh+uUo5okf;@$<39jvt$-t=2K|Dn&;ti(`T9Durety!a{_PG{oqrmb9pCsQ0##+Fj4|rfudYtNyOeyC8(+gJ`23T(_Sa3K zKKS`Pey+ziccf9Zx2ks9x=OT?&puvUZD2iI`Inh<`dU%vjs=Mt?Z+7L7gkeS7hFa@ z3KLO&?O*1IX)=K-IaU3er?X}SRkZRX7-iy3$(8F52>T8KW6_yC~^KTMcql(wFvh`^ol@$_+S`IX(M+K{+GxOTHAQ5wk zc->njP=)12Z+4)ZFQ=SecI6!N)a_IYqx`j;>XIK$l8?Rjf;{1mBdmcpHv7tWa^6$w;bG8!5Wa^zOC-ab!0j1md8Nknud0xd`sUR1|8_ae6%_p8f9 zOnJXT8!@7XwXVpYDq4`hr(4C^Su6div-SPTG#V19deESvc#3uWzrT}@%VAUC*`}T9Ck}LKWrjKTGKwm8@2xOY_JVwjAmSDgZ;3z)64m1uG%_xzskU11 zl88YsI_bqvg_vWn?9|YL1U`{QHTa~HKKVca^UciN5`n6kC-NIDk2X_tcjUd-{I@#m z#SVpNPf~8x_`c3FX(#U%Fe+sJN$nl^%Jn>42_nX~T&Mb)?bqP8&UabHYmqF z!iZSYYMmP8B2Xo#YUkkEbjJBfJN4ZHjqAX9itTdsBE}CJ`>99%edfW`(r(ndmim7! zR%`KZMM?QUqHdEy#*Zs|s0+t(eRLusNz2t*JQsl~%#)&Iy?9mIa_vXGU~-T4O=Lym z7j3k9@%-*kKa)1KtyUH(1Ju%^QK1Y%;VLU zZ_W@gam1eRk#8dOe@C?Qp#=#ZwVfwVX>1=h!Po6+gnsb*?z4 zJ}zu|Vh-KZLcg3dOp0DxS08AkEi+pEDR`$8$tuboB1RFhj|hAY83|=%ZzFlav1;*) zQRG9-v&c*z*+b8HDZNCX3R6hu&a=E`=BfR3?>C1G$pZIXlBuJS(j2EQ4dN55#k0NU zlPUf5mRV&2RdUYx+#qx51L6!aU-jn3tCVBas`_Qmf;AnC!jH$OXZ2H_iwCM0f2S;> zh9u;tEOiPIj>&P5~r_7 zpz6{2F-GsGChGcnOwe~m&HDTLi1QD$%osb`D6qbU`lS5^SE~5wg#81G@OR>L^nrwS zY=kjsm#&t$x`ll38B30VyT#cA5~wO~*Dz+f}niW5kIG`at5xJ)Moijq|I&ygo)g=sR&{oJO-sxbuOkIh|S=^PlHc zm)!f62(FK2Pm_t~8L;hQtK6m5HhvvHT3!Di$3AU{__@v$@vH$_kf?oEHIC#gsW$lF zoO!if_qAw=NT8}qsS?KGx#iTsp|AX@+L5-UC@Zv_FA`!DJW)$EE57yMo$Q=j>g5}@wX27#&>`HC84%XL)yW@Livyl8MfYGsjiazfF?c%-SM@jus>?rwlgA zo^Ga=IPsQ<5;;m+KO8KoXRFfRhih_N(f>AZgb^I>RVO{(K*am2-&^mDg#ZhsUf@_@NX$BanuN6@DOo=99a={d4u3}e> zYaf2rv7WKTd~6eDBpz2*eLa-hRn^|t%sDf>+UhPXbsPtAMEw-q!5IE*tokqxuW{W&t_d6Z?HjWIZ8jLZ_Pu0}{Pk7B)Ez@Ch#K95fy)i%P*w?TR9(d8&Xxucf z+G#F--(YmNq*jrBh0VsL>PbFY4;*Q9o~fy$CvNiKh(XU~5OK9{VY3|(XhFhTInt<; zK1^NSh}VOqPJc4HY0b@Zzc-QyRN=TndwoQ-C*nL2XhEX$r~XD*;ezU#nPrNwaPFeL3?iBy(6oj`paqF~B}N!eMn|Z> z%;wo3{m7Kop4v&YrTc431gda`Qc9n%tW9CiO2268do~BS5uVWy}l`(GFkQhDdrhnpr%Bi3TISB z*+xX_+r>Oxi9iby=hlujW=v|L`VMnHZ~bjXE9~o*#+J=8fhz1>6pQ}+-U!KD%$Rp- zh}6$7<}YF_3$3MA-u>2tqc-)yLGO){MEpVoT9C+}ppa4TRx@>R@Bb)O+p4@abl+Cb zxfDYs0#!KX({F`UeQmsq-s(9^1X_^jm!YsxZevF^cqY#uN5&;K?=RS-7C$gpB2a}h zgQ6TH;*p;~3liPy6*DRv>Z|@y;5GU1; zZM0qORkw8JIjZ@_n&yX2m9-jw^wp6-l{`n?DK^$jnWLY%P}#UrqmY{R@IREQYpcFD->hq3ma5oCB2a}92Yrua_4npp zB1#g079^&%@)$)o6jxU!eL_C6)GKP1ypr2oW)6@DRN?GHJ4G2PSiK@1nRzSU(QtI$ zd}ySRaG$DvcWIpmM^yUVK_ZS3v9{734J}Bl>lwi1}jQ+B7%r8h(HSx@?87(@$}Z7AHUJN=18F9SowzV2(uBSCsPD%u- zaD1d++#{kn5haK~3lcw{8f#ozMW-3{R!~{xxZT-GJm!TbeeJ^%fhrtP=?!^ATpdk2 zKt!Mg2~V1FM*nV2)Iq;5Cm)GN+%--=E~-D=RYJc|zn0Oi_*ivbmRlaHP%~rX#c^uE zs9!z1|7>QgOE*rv*ya)uOZG*Zv-^+KQY~()V@!oB3z?|<&jK^wn@H`#^-elkkXX^` zJ7aX@7&Wbz*B{d;RZA&VX?B;82vlKe>6xNd`P9|Pvg_-2R+jRCMDUVwM$UU9)t*y$ zeO`uAwVhIRh*E_q!H67bMM=0U!c-S_(Y8hR(9wd#SMSRklWL4qzuwMq`=^%q)FqUv zt&}PxP$j48uV2HoSIH9T@uC{&XhGufxst}w+>z?4Av|6sx~}N|UN5P?{_sje0#&$Q zM(e1qdGvqoCD#8fm_$bl61ZPRPoxw(q~+}Q+^AKvlaBK%t}Jj)RFs=U8)0Y*I6P^g>#~!v?pR55tWHR3lj4S7BqrBc2xKL!>giX1$SvHQ*_tj z_3t1NsKPl>QA!hWiip?!I_PLY;@UDYtt0|fIEyMu z?zPE%e~ig%9h+EA$GLC8$ht zJ?U>sRf2|JX>0bSu$nfkBN3>=8IIo0MZ`KHnh=2&B+gzcW4xIcre;g_h9J7jt8YVev><^cLcf5yBiM{O8fw*Y z5vV#A+{)03PP@uHl468e@Ki?~ElA+b3%z+U%_?(X$`NKZ7lA5V^-&Dh zue@0@SwAaJp<0^0qqDK$uiR>qDTkyJMLcPw(T7%$cWDKA%e8{URU@WWQO4F@Yi2OQ ztRX?!qU`pRGi{>+R{5UEb+jNMM>2beNJm6D7lA6w6YW!noHO73 z)xlER-B!_p1nyEOO3q^E%nL-E=_nJZ!t-Hzrf6bjYZmQ(%xWp`exMKeyfzQ*mvkpW zX&*;L3lbR5(bMYHDqHE+WVeo8NM#^_Dm)pd-47y45@B9VWuOHKj7w>*C87cm?a#^t zs^k;*S((~fV-nsl2bJ4wJl{UX7#UezEtX-G2cH(erwA0K3hl{cqCJ_mu00vthrw8z zzGE_=nf1ehC1$%e7o;d03G_|hB_m=Q5%FCFsxVLV8;zOUTh-&;Ff&!#Y@h`RIUj?F zI2rebX;99QK$TopooMYmh}O<)Y3+<_WQ^x9Pqe51eMf6-&h%!y0>?D8AR$M6?TDB~ z#FP9ofhx=sebXZTKx^^7T4sfgkE9wz0-tT6Z`Tl!kcfsq$^@#g{^@Bd+E2Vs`-w+d zPBU;15uaPaXqmntt@g1R#GkB9czx4A3ljLu6wL-i^dzF<8<{{AM$5EQM8sesZv1=G zKnoK1tdXJwT^M2wKA2nm`rr2wfhsIFio%IVNW|{f?+vsdfzKLIBtt~qL%CIrd?0}; zENMD%r~TdZw7)x`y}ZARYaIFcs|X@e5z)A5e;-GPqsc1n0SCfh|n|y2~B4q`ckW_H;NACb#wcdPIy_kdZqP2<$C z6vsSx!iOh+ic*jEkayD_@)Fk`GVUAW3YmUWcIO}FS4oQKBW|XV*3L+vZ~CS;5jVdo zqVI7LsFL!eEL*wW45`sg&qDb?3lefZekCF$5tGAZLQ+X(wVGCUUkwXuX(#jHHZYBc`M3w zA{rC%A)id33hSSCQfVEPoqpBf?fX|6u8Qz^23%j!(>qm`X*bI@*H>LUBdxrUz-K8G z}Ca6lKu9=tKX$C=#fW z_eGP_u0dY^t^rz*z#RldSwv@d8R+aT4V~TLc^y7Sglk;d19(wGKl{rHHEW}cI$Dsx zCz2H9TOw{PTA?Oz5vam7F8wk$5$}k2-7uq$79`|niq?J9^%hY}wJwoqBmz}fPqaG- z1X_^5XPBt96VZTt^d%oipbFa?J)c-8h3N~qYFu!gDB>w1?s3qr^O5!1^^4QZgDu)g zyB|ngSXRs^en3}CZs6yyx*c7wy&z(_i$E3bgwV5`4@>Dfo$x+dky1LZMFOARQ?QAcnoo(E~#??LMiSm&kQfqzi4|Dmb?{%~wA@2d? zC89DB+g${zFi-Rrj2xMDeM3g;@PY(7T9Cje9TnvlBFYi*$wie3ASK4JeanCbkU2D}%lTJ=}NTNldRj{Ery#5%vG0`H3{{P|;U52tW(+Q&xV z9V1LAXh8yhdEEX*AbS6YCf@%6zoC!6jf`&+k$*!7ec*kYF8;y8IrrXuL8;=mlCTf{ z)giPX5z|Lp|L+tbfvV#@W_b7)V$0WlNQmZ4QhC9VgbIAhm`mnu)x$BFy4<(nycjc@2p zh)naF5C_p)j`>=8%dsHPf&{-)k%_>&8XX^ABv9q0cVsic@5tu1!GCtD(1HZEP+RUN zyhxxb_Oim9V+v!GRUlPpL83Ojt(o&7y{%c46%wezdJ_3?e0Z^*v0d?-&DjUP3tb`< zv>-8=-j~XR^uAP1l@|$A@w?Ckfp1I~`DjOPZecJkYD6{4zvJNKx**7?2 zQyt$#gYTHZ_sr5a+=^weMpUb2{N1;fj_-WIx4Gb3W9cMrQ(CJ{l^=~;A+>e97y6Ki z&|}H1YWpr5zo)6EqXh|kLye*|qEz*)Qq8zTsX_u(m|A*TJzh!6DpS~4x~`a1R$M;( z?o1vz@$E{A(yn*~OAjjLNirw5jus@)H+>giZyu}7meQW_rOHbLs^oXqY)t!&)$pIA zzJp1s>u5m&OPYR(t#=%2O;pNU!>)fX)gYEMzKP2Ir4VlO{Ci7iK?2`jY(HUotYTd8 zb)PLqXpm2gm+Dd?11E zc~X>x4^o(+Z$=rtZpZ|xu-xePMKe@3GoQ75Yt#R%qXh|k`xLd^(4OXj^UFg2J25~a zP$k!gw|O1w`d}qzdLxa+^BuQvj!Tl=d?T)Nmbb4DW-F@lHGMZ@=Md}M@EPi^GPhNp zoezAsWTxeA0#$s?J~*DEZ?Yb2Eqv5U^U6dE z5?s=sOSfjq)>iFm-NWZBdTpWw2{|s|8sxI#8bktBShMuK?MLB)NPel1ROd)w97JuG zh{F31geG$lsH#Kp6}KKczFK|rYpb+xTByFip@kMCFgjC|*a%epOz|%Ju;bl1;p@!Q zEsKR#EZ@^Y3lbP{(v##w4EsGOmzzKpU$YN8-d(dOi--g6y&r6$1qqBLXyK9Ngz-FE zZ{O-2LnQ)L92u|=JIYx2A%Tb-9^Htr+$tv)k%@wylp5Fhke`NFXu*gBV+q=miG@H_ zdWuUpRd!rbhgL=Tk006coYpvKK|+p8nBY{o2~_bl`>-RKCHK?nOuQUc+d>Nx7zfc4 zTSQO|E_V~C;%oL{M`ZC2loUSFdWu8F9pnJ0R_NAPaTOv@!(K-9DBmHZ4 zYUovW#m|-KSSHJ@;u>U?Oe87XPNb?r?!Qg6VAL;1udxxR;%iRTa$!v@Awyz4|wC!)TL-xygeTBrt{-Bem}RJt#+# zS2BSrzGffxiiO5q&WD%AT@5Wr$mYRx1hy8P9brGoIYxcp>nWB_W+fP?k#K~DH+eGbR)9j*d zpDPx<1v8JTwxaf66Smqu@! z=qK1a->W&P_?lHRk?vxMzRGC0ZEK!VI$Dspv3!G=qw<7sS!E!C>tnNvKowteYHgzR zH=DR6dN)k&p`!%}tJBUhoWjT|8_9>CP}~Hn_?ms##K9ZfOXzzCts``_AW?aFn1}#o z{>DBI5wUtl@D?|Ls!Bw#51Sa*@~QcE?-W~aQYoVaiKmOt3m<8Ju%PR3qeit?qgUN@RKowteK5U{+y8*&Sa8!Q{ zEl3PData@9uJF6!YZI}j^32fEE&^3Uh~RwKM2jqgtxCgYhaNo}Vxk3!yLZzIA3ua2 zCm-Jv!8LfgG*up#_QH#ea$VI8^-{`8Z0%f^-p~-?<1>6(WN3 zVH0;(C$jn{%NaU9V^a$)Nc76xTKGtQ`Xc%Ghlrt69}8Rrs`#4oVH2r_2brAnQp1K= zXhGuejS`}N4ES(~e8fhe>JSl}51Z&tqt5JK)@=5q?Ps9{iL96AhI6}`u>1n~V1iTS zCQ!xKoDZAWJ~5Zh#IVd2EwmspC374x5`_lyetT>Ls`#3H*hHiB?S+q8y?!^*f<(Tz z-wGem!;g>;CVp-+DyN%36<@Otn@DpdLim{dJjg%`5;%g>vp7U7-aB_&a~FZC3pD1l z4<7SrR;JnD$)D4=m84Qe3lccy)0j9d#3~av)XJM7M8h8S=|f!K%J~O9|GnR5U~i@# zMTAB~2oY#OLVh28wGt_;azuC={~-~m!cmES^Nfg+L<}YZElBM1u8!suHj2BGa^Cmi zIx~!jJhQS(BOI!5bXAmbL=++-KM`m_qQmeM!pGP%Jnp_MSJNm!#LLMgBmz}9OHi*Z zThrju{f7v&Ao1z()H0lp-y5=z!z~ACrHEMgCRid+g|i)vK7L|85okf8>iu!y?4#}4 z?c}3>xsMvBD$9y^5`ik5wW)N8C`d#RBG7`wq54+CgKdsT@*74`!9<|GmQh^R~iT98mk!Tn9sL0zTbZ%EiTA%bGfhz3H^zD8k$`aAx$CEy^Akm}wM^PU^qYiU@49=xj zAfk8g#U>J{!cmF7g-t|xB6<;l79=93ofbZptT;(Na#nhvRU)Er$k!GUsKU{ep5G;+ z2oXhzKnoHba`qEGb|&O`aOdG_S_l!j9~6-YRN*W^r}{(`B_aZwHk=zZrr z`8dDtgu(TZxlD11Ko!n*^xV?^6GmMk{wrNvng@|6ST{79>wMQs&c~=%`^>6Dd?=P# zB2b01Ha(F-L_Q+&hh~=Mb0nfN?u_O>IJC)W^3h{=dW-YXYyC+R?}aLiK4?#$2yRz( zi9ibyde95uWBS&kEwq94-r#|KnoH$&eJay=FMg8`fhRP z+a4A5DVZaqyQLZ)-m{#~7_&NqxIPlG#~4o6@48C6TC}D5U{p`*ztCM}_+Hi9o-{6WDiOsc zT5a1&V}kcpnez1cgJj&=`^eILp>M=~EM=Mn)bED?Gxd}U`rqz^i3q6P1J zU0W)A6nlSwd=wz!T*lqSvbYFT-5{a|mAXw(8R;#D9WFMS$_yT2 zE<|uXY+`S+qncSgOEHZ~04+!y>r_J2dH2q{$p;h07YJ0HCW2e2O}vOZ-RN1R;MOON zBJ`J`yQ0|AEo!$Rsls+eaogq3>G$D?n6~})W+oJ{Ac6iAYPzMB?49B zysx6TwVzJGJt|_>TcfZxErja@El7+ef?J|ZbnAB6{HgEYV%0qzB?47)uWb;N$tv-w zpl4u@nmSsL;Qr4(xc`gRZuwigM4$>s4BFXV*;x>&f{tovL4sPP@bUi|I~VAxsv``a zx=c-5X+%(3s?w@JsUqZs))InXF%%>fK~Z@WK|rjC#R@8vL;@;?B!CbQV+7QMDx%zk zhvaYtDHNndssuz*UV+5&lqiA~^`Cu`wZ3yHu4b`Vd)=Au&e{9yJu`dmx%*DJ(sq!V z?a_bz^oC^3_7Fj>DiMFueF}(dd4vI)yDw?XC?Qc(Tj*>Iy3e9>mWaEbT)(s?hM?9# z5jGbB;`T8;qd$4OcxmxP&7+i%c);)OY+N$mcByxWxTf$}((^F{wML1segwqYMt@)3 zV)V$QG>rfyBl<@xZ zowPfBe?zJf-`~DAl@b!Xv!1uOeZn#$5?1wHMuJ+rPpaG%Kh>%3{M7VWm93+Ef{xFv z@p-?1I3Z%T2ueus88&^tcF954j~T;nOl8EOCt`fm_aN(uWgh?|5mq`F`&F3Rkl#N+@w{d)?Z4vR|IT zh)MDcrqv)Jao3zT935Hy+IJAtvbMcbKrEDJFdH|^Gf+Ze;Lqne8;8GMEE`7jEBxM7 zu>`fOZ8iepy;-Nz%tnqzfD#g2zRY$u&hKtEjObUGePt{`Eo+;NfXG*_U^bL(L@6Or z85!toEMLD!HfD%;z9KF%AcmmUb`fSHAg)(-k)78wvP&aC35g3H@9Au;7@^-s_Rd96 zD_(@z2nfxR^c@BLBMX#YQ9`0eo8HbwQt^wjVUgc@J~oD+mbJ}BK#W#?B_L~@Mt~9$ zWxpBaZ2attxw4@#O5b>BUfJ{*f?DMw%*JJocuo0L!u{LJx@gQOA@Sj?TxVn7l0w-y zAtJZ5Z6rB{pw>1KW+NcB%{uMhSJE#@vm~7o63138bT&5KH%B)1h_JDWC8%X>vk?$e zwf2k{q7k5k#4Y`oIUCJt=jq*ZMC4aYP97dZP%A@(*$9YKt-XnPo0AV}1Slb49>XfB z<}u`{Mc7q+5JOOlKIYushXnnK=hd|t+rgsR(iIz0&m8_^#r{|3b=*|B&~N(e=!$B! zziIuF-y$X3y*@0lNLO`R%fT+zCf2k|ZT#fRPICW*(vVg`Ri2}7T5V(XZnIZijQV86 zuJUo0KkX!&$1n0*O&RCfEpICEX*203x?*FSUxUB*Hz9OTF0jqsj5Ia!N=n+%el-)wJX0;cowYU9#CYGC3ne zP>Z9kn&pHx(W5&PqwDtPcjElvNOOj228#Gn#9k4Ukl?86te4`d)nAFYwNaCF64c^K z)5)qLzNsfDA;D4CI-eBr&-*wrx?oL*(5j^tJ%-LHnjG;D$wrw7N=St7V3m6O9}x#8 zv9lq9Xn+B5iUc6r)IRhUz&>^?198UHkJ_^S!9Wh^kZTM0_Elb#;Cy z){>x?(C-_l$EQSOG-?v%dr^y-f#1BmV^juF;mm?a3Vet@wo^}NYG1oUSIXNPQ*m5EE3dW z#wlMS;;@K0A}Aq2kLr2L)ni*93vwc%yp~$@F>WSCkBE3s1SKTsSAwXvv!H+SLgmz> znx}NMnEJ?z@AzdKf8Eid<$s5-_aka2>2+)CGcRR(6CO)Uo~9^G35m;h^>uXPi>v}^ z`Jwr01PK+U_6)(bU1cY** zH03@^EkmY+#MQZl&c=}Ww%dM3L~mtFlVb>KwG?4C0^(I=d#@{#>7@~%gv9u3|LSa9 z(qf}*JSXC|9~PwC6GKqz2@!TbE_H-udqr#WlIt`Al#m$GJ>qOMTVqwuBoR+2TRIg( zP;01&_OcNWmQz<2>`Kzjbvr+JcFB=opb_aQ;QqP_nWSG(+WQYUr(X9=g=A|HhapV{LCabR%OGQmLE)5=*H)l?cVh{Zhg8I zIU;AS`F8Zfql5&<(CKGchHNbo)H*U^y0g({n|+R>zpMs=5)$m6^CeN$G8V{}_}BL+ zuCO_J>cA0y=9m{MZ1zoDQs>(Cy0x8Wa98BkiL@FdBnFMlbM&k`PkjeLEo<951%!Nw zi&63=QA$W`s(#qn*z)3+vSCqeTIu4Y7S%{lYoiGBB>`booB<^}5-mniLSn|8uFghH zt?kT>=>IQQ9|PGe>8SBnx@+~c#N>= zsN5$+P|Mn8BOu1q$EZJR1Slb~c6VE6%gSD)w_=pF}`AQWLykEtzIH*eFTJ6 zadPrDN34oN35gE!80IC+W4PQWIzGsKLIkzwV;W+V%Y8!LhXnnKKGjdCOfe5P?vb4G zA5Xv5)e~NO^tgXzyY>|pul8;@?7!J%nrpw+>Vz9t8>zsHw*KuiPV#J{L;lLf`L10v z_UPF}Rs-Sf&U9LfFFWZc|LO+Uj^A77_wM_kYmY9lRl6YNVpm(rKUS7X2?<`UesBBM z4z3?J`;{pqsMWkrj@tQz#*E&YovY-1fM8uLE0aeU8F)g9fQ|E<$w{Sz1n;KK zBh${&c6a+#pSdIC?UaILc3J$9QTPBtO^AQYK8Me+nv^mxK{)v zB$(CcWNz&ojaXrIALNPDVpgjsWL5XsEy8LVl#pO-*Hhl=@m>*is!))i7PE8DJ0-$u z09!>+LV_7!P{sL7#AwwtNKlKr47a0C-y>qB2uesW5AwVU_1O9`SXCSn)Z%VQ-(wMB zRkgXQf>1(&nVNnpUOl$z;HRokkf0WKeLjX@$PA;BnNzsC~sjo7S}MS@z)a1@{phZhMS@z~ z$#~vS5uW^2rU*(%FpJW6`{b|eGnPeKizKMU9hovq`K$Uk7}~3mU>4;08|%0vkX=3VmC_5RAL&LpU1*{kL4!QR+NKlJDMyHsI_*_Js2ueuMuLMt|SmviQs#bTtWv|QVGxpTF(-thdx9{`W>vraV zy?!>)AmKLv`OQF`hiuQs=&w%ae(=3`ngDH|P1u!~brROL*Mn0d?EM?^cG}>T*y#>- qwRW0Bpx;1H!m}FqPGN!)5>Mj=r0p&`2yi{2*vC8A(i3s;rJ7u2Z%t*90Ghegh;JJcrC~W-^)om`V*hW zPWXMei9pUpKG=`fm0R?uvTw%+r^!y4Lx2xV;b+3j440RabAKJUeTY)9wf4V)VDC=( zxC!A;A}qfT;ob4)PhpIFFzIC?VEF>!FRMWZhl={By631diR%2X74v;fC+`>6Tt0jq zv@)GYVVv>j3`L2JKowu}oopidZ6D#I?9v$~T9EkeZZhGc^o!rf2NQ?yj9l&}P{r5m z!zLOY{z3T2+vJ&v79OwVkJt!Q@iqGh z5US$?El5n<^CbLpKFG%x2~_d*=X}InJVRq2oO84wapc?19`<3EE)zGXKHLPV`1*5w zly3G+_&7p!jus^TTDMmCuv@My(z#e9d*hs$O@K ziP6;_eV8~yKHLPV_?ms#M7?)?gpcnR%`nk|#Pb#Dgb#ZZWnwgqiEaW_e9b;=qT<1! z!bjHQM-8+fvDH6I@Hnq1u@R`^YxZFiJpWOZd%4~n%d84Xw>sCXa%ldXb)O>{w0wzh zd@#j-Ufr3a&<9`h=Ug|A4?9H;;aD6W4()s{?rjMd^pE3%y*tn481X}RE0e>-CyF@s( zMk?p?z-&O7v3nF+@V-u|$LO_zIg0OvDrbxd%pdGSL;>8No%xPO2EJw$`*uDLl&&Dq zf&}|;=-3HVaSEA`@*&~|T%X~3kV}CHskMt#p+zF7HkpuW&?fxedCYK9#j_8tMdW-q zxpn3!zAvu_kd_Iw;MxG!BC!*wiak|4!f{GC9~ie|YGog2K>}A6u@k7mJV}HX>%eI- zTnF4&VyO?XAmLm~{X?`8ycenhZ2|kBO*rkx-|sjjPG8~cm@N^@9aq9m+m&XV80`uP zT&qiEB}P%F22mBr2hKRQ4<{dFK?3(2Tt0w674|flz%>W1ad@`l)W+1SiF-9M+M1aZ}k7E!bT5|4% z_YL@q(c1A|sB%7!(W3%B*n)&pA2IreO!(`DRn8b=&p54T479k!>fdgo1@2327b88) z6YUn*gqH{tEfV2GQ6lHyLnc5K@GXc1d8%@%yzLicwa~)X9Q9u%l@mYOIrkGv3pE81IFig;fxtIw-DCam3Aa=8gq$)(FBOMhPa&q50lJQIEPVXFls z5vX$JF1rR(59>fOBXE?LF1THH;O{_ z@nr&3fl<_HC4%5~g%-Yc?u+r9Xo+7YAWp=YNFp?};C%!B#Mn-4*YP0}PO3;1NUb1p z=e2VlH9xD47QC-hZuT6-#I4;~a>pQGjq8-UO+cONXu^L+Un$01PVk4yZ7`&5Prz84byHLl0rt&NR9l|K&h6Yg^y_QCf; z!oSA#eEA&5AyDOy&isV?9ESs*v#SYxzspeU9T0sPadze!_h!!vxm{ z68_yUe=CWNK$SmQ{@fD99OazKun%rmNceZZKDT!19LFJ0<&WY0g!>$a3GN>fVV}zQ zd#(E%CqRJ8zZUTm?sFU_xS#v?;l#CnAI?AexX*DM0#*JsgP(Ap<1oSF6%zhkb^j>p zKF4tgRQcBoe!_h!!vv4JNN}X@jPo(iaU23w{_ z8-Z&a+n0Y8FA+>T^OfU6KF4wUaQr!+i+hWildl{f&OGSk$?@T&%HD%>2&WVsI<{1O z-V4Y3I@kUP#}n9x^K#72KCndn>m5-Ca-Fl%A<%+^KW6X**5}?Y5)?CVs#qnrUE#t` zl{m*?6~{RK$jQSol|1?YAC_Ymk4FP`ATWP$Td?C@BrvYU_|w0J``l{@vg-paNXU^T z_z>qf?4A2Is{Cs>(VK03z=ypTE-XmMktO(W_ACW~D(ow=56n5{NnTB$540fRUsHdf zT}gz!pDa|)s2#JlqXq99@E4=CO9ZXYMM;y&`8;N?MGM~7sgD@FHZVu=y-?+hN`d)< zitF<^jx*o!$iUaEV&Bf^f%*_}99ocI9}XQmfhzxgfIRxJ4==9Ia6QPSz&-+VR3IN{ zkqCRYMXqy^563%?8BVHrJjb<&oDV0r&K$)lan5o0TAB@n54}A{vJZ){pUe~MHf+-_0$MxX7gv+9 z6R5(LFA?G#hjYlYFs2Y!ND?8=ahTxNj)eczA!chA=Qshv-g^@&j<5K0X~q$CjuyOc zz+a5kE)h=y&T-fWw;zo3Fi$bh zahx)d2q*3mIR_u&94A143iBjR0W7M=z&Vac72S(f&g|^Ok9N-8=QsfZ<6S6)nCCc5 z@V)T9TvqJQE-UvrjzgeIE?s|H^m0^&79@CH`Rs#pZBsIVDrY9LQw4ka;v9!l#TFzm z;t1^N2hMRE0#(i^8Yo@S(w%c0C+89YkyFfboB#o;z*ysaN~ImUC+ zsf;-J2@nt`;!GqF;#7tSXYOMk;@a^i#&-8PPJjSaARmHopW}#BktL81zJ};rQQYS^ z0RmJ`ec0{D!vtIKzE1tyv5)`kE^v<07KF9eI;q*s4=k9YHhd>oy^XE1}rORVU;2g)XNQ5)4I5jAp;{*s$1;#5u zzz8RgqDV+<=kW`NSQR6eL}}fVn$5mH8ohG=A&f%ifcl}I?J$}Zh)eb#9MskNsr)syoPxL3&(Nm%8{z3sFi6Fd9b#BHh% zv>-t>D`>lw{5kP~c7WOyw-O{!MXg7q%5I5emZa8~Q4Kz)mWZmkd%KGJ-c5VTkO_~U zcuE9Xkf2^5XuC%pjV`QDpc;%%{R0V9QBM=83iMi?dTkl*wW#WU=NEC`3!9G{u@h)P zf<_EM+oMlNbThpvwe~JFmLP#D8kIz<0wbJGBU~9C;ZU_Kl_Boiddm?bb^Eo5V`M*lf_F*OeHy8eKoyPPB31U-K5pRP_RRU z-YDCWG9C7h=XoMex)bE~DLzUyB-08i6)Y`-ZKarmZycZHqDdbLOk&kUux@BqRJeXsgM4-wk z^^dI$B4}1~>RdyWQ-e*q8i6{uiE@6T?|&yWycZHq>zQyWntX6eTuyaPEm21TRZa`7 z-zh4jV07SbW}O5{dU)=K>x6bd^2q#dQx^B?}dcZ)6}3ni`aCYf(l#!UqilPk8dB8iWsGgYc*>$e?BbiB5=csZb znFrtQ3dBA(0nrlIdEj11PbI?YiOA#<+{+{=lOSKo{d z#MCyyQ8*JdiNJdyL8FqmlRd)KqDY_TsIoM|A%Q9yD@Cg8ad#`NCNj`?b&AGaR5`1O z;c2bF`oku8#li%wSa{qG+zSaB^F^ux^M^H=QbnsGi9i+2E8{YHtcZb@HT-RbOw|Ag;Tl+-K0|(az_ric0vDI z&HXJpBv7?#-J~ea$I@!N#z7zTF5EA}mZpE6G<+e|McVHVJ7E<4Fj`!X8p!KG`tv$D z#~eDUVk@Hmk7b2~$JX~CPo=fZeQK>8BQC!eZl>`RJ0)Blt{XZ95b*3r>vZmaNRmNf3 zc(D$gdgeJQ_WD2z5>AVe<|vUWBv9q}=5a+zm4X%|9DgxeqLXv~OeS*6quT$iKAiGl z!YMat6pgh$Smo5FJ)fUFoyS@g9A>?^J4K3ps1!I=K5pR{snM_85HXX8t3;p$2`Ujm z+hvtHbuw!P5$(p`mIzc~jH)QtQzf%@6ETzsv>-vHD}30cn_=HM(;(vf^fXeuiz3qBc|=@z@6(V#74Ez!N?#(T5%G`+v>-vf zHk^BxJ&KC0bffgj3`nRLkb<`5M&VBddTS%bF=>_(F`zs~40KqEDe zyTL7jB?48>EMcFROdx_s(I6twf`l{9+fhbInsJsAad&zei9nSz+u7$Ig^A$t>J1TS zLBg4@I1W;jw={F|xI20LZ4(JpIkUEXn(>Z^%|z590xd{5^DalrigLvtGn~FVMIun; z?7Y}#6TkUmhJ^Q~m}o)5i688BE!Q{aqfHk1d>K`^kD@4C7YphC+C-oQ2^v?#e9oiN zXX3{!hk1kx?C+q;Nv*xN#P{bKoInIxkZ}CjYXcgqbcz}Dnv^QC@QCc;9QsE%vF312 z9qcm}y1!0yt-g&2w2(g@Q9WFucqc`)f@_icIjU%s5UJwvLndx4=*^Lgo{+{8v>@S}A@FH0t;~s7PecM2fhrn_V0}Jj zes66G5v7Sh6^)O96J?p8SX8AkQKwkcLJJbk83Lb-E6ShKDyuXb==)p*s%Q)r`wxM! zUFDqf*p4ci8N^8g&lxh2DsCDccXf(hEwmuvoFVX21d5U|P8xF@5i?u_s%ZA%DBNSu zYSWZ7CikexM4*c1#Axn=JX^}d+eWKQZdZe7=0pn;&KUwfaY0Xu5J7X4KGQ{@iss#D zPL(~MCu_XQr1@N*N(8DX8W5@CI6)?kS9oI%C*lOf3}`{ZIYZ#5QxxSk5nSh+T?DEq z;t;8_Bbl{CaLx@PP(@LVNEJs&GSRk8W**yh<%7>e3lh#50zb*4C>@C49>ozE5~!kB zOQgz<;YJcct5khG5vZaFP^5}uLz$q+(xTW$A3$*;T99zg5csJlic5&#mYC8-po*eQ zkt#cSJxK(`?fTOS6-`u8>?=~mQL#)^xLMrdk(zfL(1L_>ZO>}|Uj(b1JK1XkB=BC& zHLp2j0`j4u1qmmAd_tor6ovEbtY4uO3lgYuO5I)+og;$VRSH@ap~|TbK2eehsB;Z1 zNH}eQPqUtwmy1A^GfVJ}H~kLs=lMfN zl{0_v3Ajwq`oo!{bhIGh%w2r?F3p1yfhuQ44ea|kbFGdlXRhTlbD4noTt^EM&OFag zDo8PdM4-xvKI|PYh)Z--IdKV}nac#kJ~~>EaAG2Us)L@0r)Y`RANmp6heHBYPNZh< z^<^T$AmSVmsB&UBJ~Nkz6ckx<+x?pM6VZZ%6F>43FpBbuqE}jZ>1$jBs+_3S-sOx# zK4{-ZpGO3$oOqYd%w^&tMd3Wc<+?XTLkkj4tj$jgiIta5YiIp9?Y$y_DrW^?uRku6 z4<=3#fhuQh!0Q^Ba8@ijt#QzTgtIQ;C#w{N*EihHr@9DK;d)0=crNFD?j-^(NceY< z{HHQJ&$5pcv?@XZRSs>hqwGC;`;@HNsg%C{W>z(g{=i7{?bqUZe&T1wvzCz_{(Nfb zSCkJV+Em*nEa~?hFlv`SC$2|lJZ0?dxmjFKdCm2K1X_?N@#2gi^56Pj1ga)$XhGt|^8--zp+CNzPrW-xt_Z!%Mb}K;wRoG%=0xd|ad6w0~J{IKu=t>n5sKR=Ze0Z^} zuzXr|nj~^Qv+*0-hu1kp{^u9F{j@m0#7H@~mqNqu4KtTt4pKP4D5>(B!Wu1AA)o3yH+%Gcx<1H3;Mb zElAv0zCpCzJRw_TA6~3;Od-;8KG1@M)oEuLPHkkBjkXW3Q@Ti?D%Mmf<=;h$GKpVp zgOR^{YH^)-<{snHwwB_0*WopCJ`}Vd@pSQd(dX0tw)KAysKPwSIY$c;m6wMJA2WaR z=R8m!NT3Q!LH5xy+gy>uhaWc>ckiYb*FS_GH?Txx0xd`kHgXEO%@sb!vH$GWjs&W( z+$6$_v)bT-Ydu`gX|o=aW;lsZa12Kx*M!-EZnMPyypPvuB}kwOX9?K{T9Ejvy;u0C z(b)Y|7!s)Z=0-z7q)Y)%Kv?VzE!&Tk7OMX`95(X3{Z?E@59fVR`_C?2v> zv3t(J+J8%P)V~vli~87*;I^wi(1LSRjM5GGKmt{@3(pch-j2TO@_`m4ur}pnb<-{QTmae~NRRuT}3Ce|UFxcsEit+hZDC zjB4RM=z7_ZDC2ae5@nd~-kJBvFjeRS?<*4*>MjyKe!lT33@u39(3T2+#oiwvA8XpJ z3FTBR=x%IB0#%q=IaL=rmEiB=c&cqXX?#~bl{iuCedoL}+51Xd-%sXxF5HV2Bs%2m z7tVLunb2JyNT7=I#DrbCP*z^FAQ3T5JWb_Uvci=r1qoDLr?O%nc3FWB1uaPQX#P+TUbRtxGgA(I%W9|CgR;mvI8whtW6Wgvx103yEqoD zupyjf5H~U6v zB}g2qe^t;=+VOtk`LWR=9}g-okO)+DqLGN}oJS)14U1c8g^wHC`-GtdiK_R<38L-V z?Q-cVNTBK%jd1KE<_L!tBtAW!Du~}3`u6|=b&dq8MtfgHv5(U!+&iggL88O(6rz=k zJ>&L)1gfy7N$pBO3ljUhtA&q7arso{=ZZN*E17;JA`A&sVSiMVOp|NrA3l9D)l4h3 z{k|O0nTxbgbNn{iSoQ5mah>$wPsWsMW^}z0Rn$Lj^2#eC5g&=rh(HSxo74)vHEToE zA%%Jqk)DV|ieeRZ5vXb~R9O z3|4s+*SCN!uD2u`Yt-A(Nn9r^(BCEkb&dq8cumE33ar(rQtZ(OElA}0;gBGzt{v|3 zfdr~{%-0)_cl%nM^CqiSzb}98L|JVZ6$6Ra{S4J<@pH@lRj=d=1rad-0mn@xiG= z3lgc~-}AALADb;CqVL{vdcHqWTPG$j(6FYk1|Lt)=$m}5h}yF>*Pyy0kKQ>>aVvYD zi5gmvc>kcjPYW)jp1aY9h}~<_>-Qd3w7O>MD-oz_HX)B7vJPM$>7)B<&now~Doi=7 zVy$5-L0VCK{Ss)4;tjE;e78hJ3lhFKA-0`G zu2H`74~f<(EYhOhV1!fN_H(}}p1BEOZ8>iku|NE0ncU^}K~QiDoalb2_= z=0(kr2vlLeQIvrvEv--2g4^#m?`lHKm=NlNHF%ip!&PZ2lVcLBdf)^d(})+|%1QRoL$q>@8!|{(6`?u+K~bX`3iz z-WLQ~kZAm_u<^F*WOZU{t`GL{_3yg`ftD`wzcJF?nWvVVI{6De?v7do z6op%2;ZI3KOT?Cu=2^IJY3T_mgX`l(&34<|EfH1N#_ZBr<+Dgsbu_T?_(MIF8wb@y|$6=V(D<^j{OgD-6r5{@l2U-$&nf zqhb)K!qJZ2Cv(y=CyWo~u|z-7sF{&sXD;*^`|Oz*?A&WNT6y|>wLzudZpCGiB}WBIe$^AF82@p&BcMj z@=xcQ9yR*}qsq%f>eaHDJ*PK!7O6^IwG9!}63sFz%5f{v(SpRhB9TVs3{N}_7i)eZ z&fYpP2vlLIi~eDL-(lodE?u-BF`&&)M#p5=J;Rg^7jSN~+^@w`FBbODmUGrN1r`)b|v>>sp=0o4XL)q2nMQ15hT<2Z7?b_-l zQ1xG~tVWq>)zqOwHxWT2gSo5IE>VMMLBd#g$(P|PkJ{shtNxsCjvvNjiH-!SIDfqU zuv-b2Rmq==iL%;1CerxtL=QE;SM}t0x4`IIyNB9z?y>M9Ifn~kM%_~6gL9sA;~?&} zI$Ds3Gj^d-XI6c6--kotVk|MUolPLh3JFxPZ_YXUwu#Ec3J3x%NGv}v&luakq}uw< zW%9wPT0bg@NEH&O!ZvODIHt!DEfFn9EW9+s=)3D1HC>61&F16A1a zMSNurnf^)SgWGQE3**FCQoYU~V@jW8YRQ!~M33V5+U`+Y=dT~v7e2U0ITj>t)B0&` z#Rck>#(Ai$DE2XDE&WHdT_jM&`CFPGQsv$(A{ldau8Z3!W)S&sEJ#c(HO)v`Vw!qr zN+N%qr=9;alaVF*h>mJK6P~Q)ifHK?2viijs(k7esV-5vXb~c7a$spPtSUK(U^Utm#9pYiFx$Fwug9 zyqYLZ#3&-pxd>GC>#|g=?z>G0CLa$cceEz`T2ssQFxo^561aL%lm|pC{sMujO~EU~ zs%XHv9OPp~fv#4UN4boJ%PkWvNZ^{vCdv@8$VH$k+ah{Ogw|~d`{p7am*2OsruLd- zUMs!ZL<Z7OCi5Nq~4Hto`xF;8j6{PocQS!limhotpvo!5lq6Ga|3)CE~yMGJ&cNXGR#jR*SQAB>8w(f0kM8*Irhx=g$qaAb~5r*a=iM zo7&yrHD{$w^T@~X6LXBg!4X!eC;$4;f&{Ku73HL#2zL>vx?Hq@!E5Icr#F+2Yc(@y z4K@w7QswBUq6Ge92lh885`)m;xFY7)`fMWE`$wXY1` zFFWzuL-Ii*oK7R0MI)Ss79?;rDMnG9Mp3J`i$K-h*H3-CO3iui9r>U!QKvD{q!CU- z3lg}-rC*^XVm1*pib@2kig&*15~56r%xK4<7j9>0(T1S(>^*~(rFZx z2vjv``=5{ZEMIQ@m+CxCkzl=DqY%Am{c##vkiZ>JN)-_;h@eqaB2e{scM5}dRkPK< zLq2GP(`ba#-^H(`p#=%tlcji|+)6y-S))rrX9B2ZQMLpg&_8V(M($Vc$WIqJ{B5&Fd^|9a4Z1fC91|L_yHTm-5% zw`gJTNyDhNYskm@ni;a$!35@ORmGIe{hr~)4 z2~^DpnkCkQo{{y*#{lv%p#1ePUO}P-35@OR_4$lio5V^O2~@@XcY#xEc0F6hasFQBv6&>>|(L6k#ir%K3rBo^~Q+x2U?K8*v`(!?+1#A zvO)q?@mnnsyC02T6eb^Z3Sj=VaHv>Ep#=$y?dTiQMC_>XIFwESbRG`Z6u$u=x9L#V>?CZO2oFhUXc$ZP&FiZPq70zc+gz(!7KU(@27}9 zh!!L;wzKQw)BDk)K9E3Ffr*X84s_9fHj)pn^Ruf{@;Q!<79=pXv-?NsR4+xZMFLf8 z3wy*q^^35BejgX|r4ac*3lbRHiL)XzS%KZ6K9E3F?gcr;K6U&QSIEb3%18DrlZ)S_ ze4qshjP1l3q?xW<7e0fO2vpr{9VB*c z2~@3L{-4<2{dW$}=Of5Rk3R3hI3H+10%JRRhXN7Gq`_gF4TJrJV%KQFz&I59j3gg>p7q^+hkT#~35@M*;(V@d zF$h$h8vTdZTe?4u<15Zby($~RI3H+10%JQxsYyiK15aWQsCt|Hh1gpfl7eGu-Vy%u zo9=SZNcK-I)zZz*T)$9^AM8Ws}!iD*FrV>^4U4LdVbqzVaC z6-b{&>@7v+yhT2E{&<=xtJq0J3lbRH*~G?(vmzfzpsM-KP_aiElIFt)Q#m*!u6DCSxuQ1!NU zN3oNdeZpeDkM46Ti17+7NMLMdkL_=IZI3~qD(^?H*sX7TYCQR%b7wPI?zkdVXh8xa zH9N}qvrKETXNd%=Fz%u^hP>Kkmig3KueUOdi6?wGKH@nQ{UT{(a_h%?HS|mmJD6xe z0>?2$IZZ@cA_}+&RN-lsqST0A#u^hZtG=W5EE6qA;5bJ8oQP3GY;h5&!qY5zI{H!* z>$rYa8&GnSi54Vq539BUu&z#539}E*>{*| zK?27yMTt*DNg^t`2vp%tx}r?qR>=xlm&`i4_ZJf_NZ>eT6Df%>Tm-6cCtXoKo&VO_ zr)k!NMqU#wNZ>g3KL{8(aqpep4D{r>S@zbC)_=P~Otj#AapY5!W<;n&WZW$isFL^e z-<)b<4)6@L#unXVpalsW#}wtYpBUjHP=)74^eY}Ie(@}M7GZTBqj=DQ1de?48$y1f zyNf^-o;1;HP%lFJb!tDWVV%<|T9CkTjP@CbxIjd47lA7I1nckSkF@LCT3C%w>Ka;* zkjKQ>2vp$-COy5ADv!S9P6=yI$S4ghNZ?wOMmQqY5OK>zph`NyRH`Pbp|@KY-?|aB zTtf>IxE7^U5z&)~tu8`RNhhP;GHvu%|4lddF4(2vX($r77NuveiFirGJ{N&1`7Cv5 zp00Z6s9>Y^5=%o161Wznw~P@HJTln$*+rlV&+F-Jv;{lr`~PX6&6*#rp#=$Ci_))V z6S0?wnJxlVcwSF?mh&3uHCFwlJv^~aLkkkP7Ns3}B0`8b?jlfyC;T+-ZVc5YR?e&M zD>_v}3lg{%rKgHFgzB@2xZxsDB|kZExL+dua*2BS#)r)`v><_NQHlVFI8Ve_7lA5# zW=2s;4qTz_eAZq6YG(osElA*6R8a~Ov73mrE&^5flnt$M1|L@6&l#$Rx5=iW1qob> zD#}bhQP@SGN`88$;npPPi?T!XzjC)W(1HZ6MHQv7pZMKHpbFzI`pq+cL{{4sks*Px z7DY0>(pfW-SJdmw9%)+1BaF=5Myd-Vw@A->;IkBpQYn91E9txG+N#G}&3skH7`e9e zP`9>R=ILsVHWCi&qpk~I?vb91P+B&uW>uLJUyrV|-b4!$JFAZ{PPX@|SI+P*XM?|L zT0K90(h9d*BN3>QQ&ne79xL)r34Q6`!%egxapb^oqxLJWdT-5I^09`9TtwV+5valv zQIxWj^TL$#Wv-lKo`$X)YgDz`tLML6LOzmp?O>HY7^2Ncbksx(68NkUoxT?CW)&VD ztS;*rB@w8~eSNHPvOo*<%sF07EGMGzh+uUo5okf;@$<39jvt$-t=2K|Dn&;ti(`T9Durety!a{_PG{oqrmb9pCsQ0##+Fj4|rfudYtNyOeyC8(+gJ`23T(_Sa3K zKKS`Pey+ziccf9Zx2ks9x=OT?&puvUZD2iI`Inh<`dU%vjs=Mt?Z+7L7gkeS7hFa@ z3KLO&?O*1IX)=K-IaU3er?X}SRkZRX7-iy3$(8F52>T8KW6_yC~^KTMcql(wFvh`^ol@$_+S`IX(M+K{+GxOTHAQ5wk zc->njP=)12Z+4)ZFQ=SecI6!N)a_IYqx`j;>XIK$l8?Rjf;{1mBdmcpHv7tWa^6$w;bG8!5Wa^zOC-ab!0j1md8Nknud0xd`sUR1|8_ae6%_p8f9 zOnJXT8!@7XwXVpYDq4`hr(4C^Su6div-SPTG#V19deESvc#3uWzrT}@%VAUC*`}T9Ck}LKWrjKTGKwm8@2xOY_JVwjAmSDgZ;3z)64m1uG%_xzskU11 zl88YsI_bqvg_vWn?9|YL1U`{QHTa~HKKVca^UciN5`n6kC-NIDk2X_tcjUd-{I@#m z#SVpNPf~8x_`c3FX(#U%Fe+sJN$nl^%Jn>42_nX~T&Mb)?bqP8&UabHYmqF z!iZSYYMmP8B2Xo#YUkkEbjJBfJN4ZHjqAX9itTdsBE}CJ`>99%edfW`(r(ndmim7! zR%`KZMM?QUqHdEy#*Zs|s0+t(eRLusNz2t*JQsl~%#)&Iy?9mIa_vXGU~-T4O=Lym z7j3k9@%-*kKa)1KtyUH(1Ju%^QK1Y%;VLU zZ_W@gam1eRk#8dOe@C?Qp#=#ZwVfwVX>1=h!Po6+gnsb*?z4 zJ}zu|Vh-KZLcg3dOp0DxS08AkEi+pEDR`$8$tuboB1RFhj|hAY83|=%ZzFlav1;*) zQRG9-v&c*z*+b8HDZNCX3R6hu&a=E`=BfR3?>C1G$pZIXlBuJS(j2EQ4dN55#k0NU zlPUf5mRV&2RdUYx+#qx51L6!aU-jn3tCVBas`_Qmf;AnC!jH$OXZ2H_iwCM0f2S;> zh9u;tEOiPIj>&P5~r_7 zpz6{2F-GsGChGcnOwe~m&HDTLi1QD$%osb`D6qbU`lS5^SE~5wg#81G@OR>L^nrwS zY=kjsm#&t$x`ll38B30VyT#cA5~wO~*Dz+f}niW5kIG`at5xJ)Moijq|I&ygo)g=sR&{oJO-sxbuOkIh|S=^PlHc zm)!f62(FK2Pm_t~8L;hQtK6m5HhvvHT3!Di$3AU{__@v$@vH$_kf?oEHIC#gsW$lF zoO!if_qAw=NT8}qsS?KGx#iTsp|AX@+L5-UC@Zv_FA`!DJW)$EE57yMo$Q=j>g5}@wX27#&>`HC84%XL)yW@Livyl8MfYGsjiazfF?c%-SM@jus>?rwlgA zo^Ga=IPsQ<5;;m+KO8KoXRFfRhih_N(f>AZgb^I>RVO{(K*am2-&^mDg#ZhsUf@_@NX$BanuN6@DOo=99a={d4u3}e> zYaf2rv7WKTd~6eDBpz2*eLa-hRn^|t%sDf>+UhPXbsPtAMEw-q!5IE*tokqxuW{W&t_d6Z?HjWIZ8jLZ_Pu0}{Pk7B)Ez@Ch#K95fy)i%P*w?TR9(d8&Xxucf z+G#F--(YmNq*jrBh0VsL>PbFY4;*Q9o~fy$CvNiKh(XU~5OK9{VY3|(XhFhTInt<; zK1^NSh}VOqPJc4HY0b@Zzc-QyRN=TndwoQ-C*nL2XhEX$r~XD*;ezU#nPrNwaPFeL3?iBy(6oj`paqF~B}N!eMn|Z> z%;wo3{m7Kop4v&YrTc431gda`Qc9n%tW9CiO2268do~BS5uVWy}l`(GFkQhDdrhnpr%Bi3TISB z*+xX_+r>Oxi9iby=hlujW=v|L`VMnHZ~bjXE9~o*#+J=8fhz1>6pQ}+-U!KD%$Rp- zh}6$7<}YF_3$3MA-u>2tqc-)yLGO){MEpVoT9C+}ppa4TRx@>R@Bb)O+p4@abl+Cb zxfDYs0#!KX({F`UeQmsq-s(9^1X_^jm!YsxZevF^cqY#uN5&;K?=RS-7C$gpB2a}h zgQ6TH;*p;~3liPy6*DRv>Z|@y;5GU1; zZM0qORkw8JIjZ@_n&yX2m9-jw^wp6-l{`n?DK^$jnWLY%P}#UrqmY{R@IREQYpcFD->hq3ma5oCB2a}92Yrua_4npp zB1#g079^&%@)$)o6jxU!eL_C6)GKP1ypr2oW)6@DRN?GHJ4G2PSiK@1nRzSU(QtI$ zd}ySRaG$DvcWIpmM^yUVK_ZS3v9{734J}Bl>lwi1}jQ+B7%r8h(HSx@?87(@$}Z7AHUJN=18F9SowzV2(uBSCsPD%u- zaD1d++#{kn5haK~3lcw{8f#ozMW-3{R!~{xxZT-GJm!TbeeJ^%fhrtP=?!^ATpdk2 zKt!Mg2~V1FM*nV2)Iq;5Cm)GN+%--=E~-D=RYJc|zn0Oi_*ivbmRlaHP%~rX#c^uE zs9!z1|7>QgOE*rv*ya)uOZG*Zv-^+KQY~()V@!oB3z?|<&jK^wn@H`#^-elkkXX^` zJ7aX@7&Wbz*B{d;RZA&VX?B;82vlKe>6xNd`P9|Pvg_-2R+jRCMDUVwM$UU9)t*y$ zeO`uAwVhIRh*E_q!H67bMM=0U!c-S_(Y8hR(9wd#SMSRklWL4qzuwMq`=^%q)FqUv zt&}PxP$j48uV2HoSIH9T@uC{&XhGufxst}w+>z?4Av|6sx~}N|UN5P?{_sje0#&$Q zM(e1qdGvqoCD#8fm_$bl61ZPRPoxw(q~+}Q+^AKvlaBK%t}Jj)RFs=U8)0Y*I6P^g>#~!v?pR55tWHR3lj4S7BqrBc2xKL!>giX1$SvHQ*_tj z_3t1NsKPl>QA!hWiip?!I_PLY;@UDYtt0|fIEyMu z?zPE%e~ig%9h+EA$GLC8$ht zJ?U>sRf2|JX>0bSu$nfkBN3>=8IIo0MZ`KHnh=2&B+gzcW4xIcre;g_h9J7jt8YVev><^cLcf5yBiM{O8fw*Y z5vV#A+{)03PP@uHl468e@Ki?~ElA+b3%z+U%_?(X$`NKZ7lA5V^-&Dh zue@0@SwAaJp<0^0qqDK$uiR>qDTkyJMLcPw(T7%$cWDKA%e8{URU@WWQO4F@Yi2OQ ztRX?!qU`pRGi{>+R{5UEb+jNMM>2beNJm6D7lA6w6YW!noHO73 z)xlER-B!_p1nyEOO3q^E%nL-E=_nJZ!t-Hzrf6bjYZmQ(%xWp`exMKeyfzQ*mvkpW zX&*;L3lbR5(bMYHDqHE+WVeo8NM#^_Dm)pd-47y45@B9VWuOHKj7w>*C87cm?a#^t zs^k;*S((~fV-nsl2bJ4wJl{UX7#UezEtX-G2cH(erwA0K3hl{cqCJ_mu00vthrw8z zzGE_=nf1ehC1$%e7o;d03G_|hB_m=Q5%FCFsxVLV8;zOUTh-&;Ff&!#Y@h`RIUj?F zI2rebX;99QK$TopooMYmh}O<)Y3+<_WQ^x9Pqe51eMf6-&h%!y0>?D8AR$M6?TDB~ z#FP9ofhx=sebXZTKx^^7T4sfgkE9wz0-tT6Z`Tl!kcfsq$^@#g{^@Bd+E2Vs`-w+d zPBU;15uaPaXqmntt@g1R#GkB9czx4A3ljLu6wL-i^dzF<8<{{AM$5EQM8sesZv1=G zKnoK1tdXJwT^M2wKA2nm`rr2wfhsIFio%IVNW|{f?+vsdfzKLIBtt~qL%CIrd?0}; zENMD%r~TdZw7)x`y}ZARYaIFcs|X@e5z)A5e;-GPqsc1n0SCfh|n|y2~B4q`ckW_H;NACb#wcdPIy_kdZqP2<$C z6vsSx!iOh+ic*jEkayD_@)Fk`GVUAW3YmUWcIO}FS4oQKBW|XV*3L+vZ~CS;5jVdo zqVI7LsFL!eEL*wW45`sg&qDb?3lefZekCF$5tGAZLQ+X(wVGCUUkwXuX(#jHHZYBc`M3w zA{rC%A)id33hSSCQfVEPoqpBf?fX|6u8Qz^23%j!(>qm`X*bI@*H>LUBdxrUz-K8G z}Ca6lKu9=tKX$C=#fW z_eGP_u0dY^t^rz*z#RldSwv@d8R+aT4V~TLc^y7Sglk;d19(wGKl{rHHEW}cI$Dsx zCz2H9TOw{PTA?Oz5vam7F8wk$5$}k2-7uq$79`|niq?J9^%hY}wJwoqBmz}fPqaG- z1X_^5XPBt96VZTt^d%oipbFa?J)c-8h3N~qYFu!gDB>w1?s3qr^O5!1^^4QZgDu)g zyB|ngSXRs^en3}CZs6yyx*c7wy&z(_i$E3bgwV5`4@>Dfo$x+dky1LZMFOARQ?QAcnoo(E~#??LMiSm&kQfqzi4|Dmb?{%~wA@2d? zC89DB+g${zFi-Rrj2xMDeM3g;@PY(7T9Cje9TnvlBFYi*$wie3ASK4JeanCbkU2D}%lTJ=}NTNldRj{Ery#5%vG0`H3{{P|;U52tW(+Q&xV z9V1LAXh8yhdEEX*AbS6YCf@%6zoC!6jf`&+k$*!7ec*kYF8;y8IrrXuL8;=mlCTf{ z)giPX5z|Lp|L+tbfvV#@W_b7)V$0WlNQmZ4QhC9VgbIAhm`mnu)x$BFy4<(nycjc@2p zh)naF5C_p)j`>=8%dsHPf&{-)k%_>&8XX^ABv9q0cVsic@5tu1!GCtD(1HZEP+RUN zyhxxb_Oim9V+v!GRUlPpL83Ojt(o&7y{%c46%wezdJ_3?e0Z^*v0d?-&DjUP3tb`< zv>-8=-j~XR^uAP1l@|$A@w?Ckfp1I~`DjOPZecJkYD6{4zvJNKx**7?2 zQyt$#gYTHZ_sr5a+=^weMpUb2{N1;fj_-WIx4Gb3W9cMrQ(CJ{l^=~;A+>e97y6Ki z&|}H1YWpr5zo)6EqXh|kLye*|qEz*)Qq8zTsX_u(m|A*TJzh!6DpS~4x~`a1R$M;( z?o1vz@$E{A(yn*~OAjjLNirw5jus@)H+>giZyu}7meQW_rOHbLs^oXqY)t!&)$pIA zzJp1s>u5m&OPYR(t#=%2O;pNU!>)fX)gYEMzKP2Ir4VlO{Ci7iK?2`jY(HUotYTd8 zb)PLqXpm2gm+Dd?11E zc~X>x4^o(+Z$=rtZpZ|xu-xePMKe@3GoQ75Yt#R%qXh|k`xLd^(4OXj^UFg2J25~a zP$k!gw|O1w`d}qzdLxa+^BuQvj!Tl=d?T)Nmbb4DW-F@lHGMZ@=Md}M@EPi^GPhNp zoezAsWTxeA0#$s?J~*DEZ?Yb2Eqv5U^U6dE z5?s=sOSfjq)>iFm-NWZBdTpWw2{|s|8sxI#8bktBShMuK?MLB)NPel1ROd)w97JuG zh{F31geG$lsH#Kp6}KKczFK|rYpb+xTByFip@kMCFgjC|*a%epOz|%Ju;bl1;p@!Q zEsKR#EZ@^Y3lbP{(v##w4EsGOmzzKpU$YN8-d(dOi--g6y&r6$1qqBLXyK9Ngz-FE zZ{O-2LnQ)L92u|=JIYx2A%Tb-9^Htr+$tv)k%@wylp5Fhke`NFXu*gBV+q=miG@H_ zdWuUpRd!rbhgL=Tk006coYpvKK|+p8nBY{o2~_bl`>-RKCHK?nOuQUc+d>Nx7zfc4 zTSQO|E_V~C;%oL{M`ZC2loUSFdWu8F9pnJ0R_NAPaTOv@!(K-9DBmHZ4 zYUovW#m|-KSSHJ@;u>U?Oe87XPNb?r?!Qg6VAL;1udxxR;%iRTa$!v@Awyz4|wC!)TL-xygeTBrt{-Bem}RJt#+# zS2BSrzGffxiiO5q&WD%AT@5Wr$mYRx1hy8P9brGoIYxcp>nWB_W+fP?k#K~DH+eGbR)9j*d zpDPx<1v8JTwxaf66Smqu@! z=qK1a->W&P_?lHRk?vxMzRGC0ZEK!VI$Dspv3!G=qw<7sS!E!C>tnNvKowteYHgzR zH=DR6dN)k&p`!%}tJBUhoWjT|8_9>CP}~Hn_?ms##K9ZfOXzzCts``_AW?aFn1}#o z{>DBI5wUtl@D?|Ls!Bw#51Sa*@~QcE?-W~aQYoVaiKmOt3m<8Ju%PR3qeit?qgUN@RKowteK5U{+y8*&Sa8!Q{ zEl3PData@9uJF6!YZI}j^32fEE&^3Uh~RwKM2jqgtxCgYhaNo}Vxk3!yLZzIA3ua2 zCm-Jv!8LfgG*up#_QH#ea$VI8^-{`8Z0%f^-p~-?<1>6(WN3 zVH0;(C$jn{%NaU9V^a$)Nc76xTKGtQ`Xc%Ghlrt69}8Rrs`#4oVH2r_2brAnQp1K= zXhGuejS`}N4ES(~e8fhe>JSl}51Z&tqt5JK)@=5q?Ps9{iL96AhI6}`u>1n~V1iTS zCQ!xKoDZAWJ~5Zh#IVd2EwmspC374x5`_lyetT>Ls`#3H*hHiB?S+q8y?!^*f<(Tz z-wGem!;g>;CVp-+DyN%36<@Otn@DpdLim{dJjg%`5;%g>vp7U7-aB_&a~FZC3pD1l z4<7SrR;JnD$)D4=m84Qe3lccy)0j9d#3~av)XJM7M8h8S=|f!K%J~O9|GnR5U~i@# zMTAB~2oY#OLVh28wGt_;azuC={~-~m!cmES^Nfg+L<}YZElBM1u8!suHj2BGa^Cmi zIx~!jJhQS(BOI!5bXAmbL=++-KM`m_qQmeM!pGP%Jnp_MSJNm!#LLMgBmz}9OHi*Z zThrju{f7v&Ao1z()H0lp-y5=z!z~ACrHEMgCRid+g|i)vK7L|85okf8>iu!y?4#}4 z?c}3>xsMvBD$9y^5`ik5wW)N8C`d#RBG7`wq54+CgKdsT@*74`!9<|GmQh^R~iT98mk!Tn9sL0zTbZ%EiTA%bGfhz3H^zD8k$`aAx$CEy^Akm}wM^PU^qYiU@49=xj zAfk8g#U>J{!cmF7g-t|xB6<;l79=93ofbZptT;(Na#nhvRU)Er$k!GUsKU{ep5G;+ z2oXhzKnoHba`qEGb|&O`aOdG_S_l!j9~6-YRN*W^r}{(`B_aZwHk=zZrr z`8dDtgu(TZxlD11Ko!n*^xV?^6GmMk{wrNvng@|6ST{79>wMQs&c~=%`^>6Dd?=P# zB2b01Ha(F-L_Q+&hh~=Mb0nfN?u_O>IJC)W^3h{=dW-YXYyC+R?}aLiK4?#$2yRz( zi9ibyde95uWBS&kEwq94-r#|KnoH$&eJay=FMg8`fhRP z+a4A5DVZaqyQLZ)-m{#~7_&NqxIPlG#~4o6@48C6TC}D5U{p`*ztCM}_+Hi9o-{6WDiOsc zT5a1&V}kcpnez1cgJj&=`^eILp>M=~EM=Mn)bED?Gxd}U`rqz^i3q6P1J zU0W)A6nlSwd=wz!T*lqSvbYFT-5{a|mAXw(8R;#D9WFMS$_yT2 zE<|uXY+`S+qncSgOEHZ~04+!y>r_J2dH2q{$p;h07YJ0HCW2e2O}vOZ-RN1R;MOON zBJ`J`yQ0|AEo!$Rsls+eaogq3>G$D?n6~})W+oJ{Ac6iAYPzMB?49B zysx6TwVzJGJt|_>TcfZxErja@El7+ef?J|ZbnAB6{HgEYV%0qzB?47)uWb;N$tv-w zpl4u@nmSsL;Qr4(xc`gRZuwigM4$>s4BFXV*;x>&f{tovL4sPP@bUi|I~VAxsv``a zx=c-5X+%(3s?w@JsUqZs))InXF%%>fK~Z@WK|rjC#R@8vL;@;?B!CbQV+7QMDx%zk zhvaYtDHNndssuz*UV+5&lqiA~^`Cu`wZ3yHu4b`Vd)=Au&e{9yJu`dmx%*DJ(sq!V z?a_bz^oC^3_7Fj>DiMFueF}(dd4vI)yDw?XC?Qc(Tj*>Iy3e9>mWaEbT)(s?hM?9# z5jGbB;`T8;qd$4OcxmxP&7+i%c);)OY+N$mcByxWxTf$}((^F{wML1segwqYMt@)3 zV)V$QG>rfyBl<@xZ zowPfBe?zJf-`~DAl@b!Xv!1uOeZn#$5?1wHMuJ+rPpaG%Kh>%3{M7VWm93+Ef{xFv z@p-?1I3Z%T2ueus88&^tcF954j~T;nOl8EOCt`fm_aN(uWgh?|5mq`F`&F3Rkl#N+@w{d)?Z4vR|IT zh)MDcrqv)Jao3zT935Hy+IJAtvbMcbKrEDJFdH|^Gf+Ze;Lqne8;8GMEE`7jEBxM7 zu>`fOZ8iepy;-Nz%tnqzfD#g2zRY$u&hKtEjObUGePt{`Eo+;NfXG*_U^bL(L@6Or z85!toEMLD!HfD%;z9KF%AcmmUb`fSHAg)(-k)78wvP&aC35g3H@9Au;7@^-s_Rd96 zD_(@z2nfxR^c@BLBMX#YQ9`0eo8HbwQt^wjVUgc@J~oD+mbJ}BK#W#?B_L~@Mt~9$ zWxpBaZ2attxw4@#O5b>BUfJ{*f?DMw%*JJocuo0L!u{LJx@gQOA@Sj?TxVn7l0w-y zAtJZ5Z6rB{pw>1KW+NcB%{uMhSJE#@vm~7o63138bT&5KH%B)1h_JDWC8%X>vk?$e zwf2k{q7k5k#4Y`oIUCJt=jq*ZMC4aYP97dZP%A@(*$9YKt-XnPo0AV}1Slb49>XfB z<}u`{Mc7q+5JOOlKIYushXnnK=hd|t+rgsR(iIz0&m8_^#r{|3b=*|B&~N(e=!$B! zziIuF-y$X3y*@0lNLO`R%fT+zCf2k|ZT#fRPICW*(vVg`Ri2}7T5V(XZnIZijQV86 zuJUo0KkX!&$1n0*O&RCfEpICEX*203x?*FSUxUB*Hz9OTF0jqsj5Ia!N=n+%el-)wJX0;cowYU9#CYGC3ne zP>Z9kn&pHx(W5&PqwDtPcjElvNOOj228#Gn#9k4Ukl?86te4`d)nAFYwNaCF64c^K z)5)qLzNsfDA;D4CI-eBr&-*wrx?oL*(5j^tJ%-LHnjG;D$wrw7N=St7V3m6O9}x#8 zv9lq9Xn+B5iUc6r)IRhUz&>^?198UHkJ_^S!9Wh^kZTM0_Elb#;Cy z){>x?(C-_l$EQSOG-?v%dr^y-f#1BmV^juF;mm?a3Vet@wo^}NYG1oUSIXNPQ*m5EE3dW z#wlMS;;@K0A}Aq2kLr2L)ni*93vwc%yp~$@F>WSCkBE3s1SKTsSAwXvv!H+SLgmz> znx}NMnEJ?z@AzdKf8Eid<$s5-_aka2>2+)CGcRR(6CO)Uo~9^G35m;h^>uXPi>v}^ z`Jwr01PK+U_6)(bU1cY** zH03@^EkmY+#MQZl&c=}Ww%dM3L~mtFlVb>KwG?4C0^(I=d#@{#>7@~%gv9u3|LSa9 z(qf}*JSXC|9~PwC6GKqz2@!TbE_H-udqr#WlIt`Al#m$GJ>qOMTVqwuBoR+2TRIg( zP;01&_OcNWmQz<2>`Kzjbvr+JcFB=opb_aQ;QqP_nWSG(+WQYUr(X9=g=A|HhapV{LCabR%OGQmLE)5=*H)l?cVh{Zhg8I zIU;AS`F8Zfql5&<(CKGchHNbo)H*U^y0g({n|+R>zpMs=5)$m6^CeN$G8V{}_}BL+ zuCO_J>cA0y=9m{MZ1zoDQs>(Cy0x8Wa98BkiL@FdBnFMlbM&k`PkjeLEo<951%!Nw zi&63=QA$W`s(#qn*z)3+vSCqeTIu4Y7S%{lYoiGBB>`booB<^}5-mniLSn|8uFghH zt?kT>=>IQQ9|PGe>8SBnx@+~c#N>= zsN5$+P|Mn8BOu1q$EZJR1Slb~c6VE6%gSD)w_=pF}`AQWLykEtzIH*eFTJ6 zadPrDN34oN35gE!80IC+W4PQWIzGsKLIkzwV;W+V%Y8!LhXnnKKGjdCOfe5P?vb4G zA5Xv5)e~NO^tgXzyY>|pul8;@?7!J%nrpw+>Vz9t8>zsHw*KuiPV#J{L;lLf`L10v z_UPF}Rs-Sf&U9LfFFWZc|LO+Uj^A77_wM_kYmY9lRl6YNVpm(rKUS7X2?<`UesBBM z4z3?J`;{pqsMWkrj@tQz#*E&YovY-1fM8uLE0aeU8F)g9fQ|E<$w{Sz1n;KK zBh${&c6a+#pSdIC?UaILc3J$9QTPBtO^AQYK8Me+nv^mxK{)v zB$(CcWNz&ojaXrIALNPDVpgjsWL5XsEy8LVl#pO-*Hhl=@m>*is!))i7PE8DJ0-$u z09!>+LV_7!P{sL7#AwwtNKlKr47a0C-y>qB2uesW5AwVU_1O9`SXCSn)Z%VQ-(wMB zRkgXQf>1(&nVNnpUOl$z;HRokkf0WKeLjX@$PA;BnNzsC~sjo7S}MS@z)a1@{phZhMS@z~ z$#~vS5uW^2rU*(%FpJW6`{b|eGnPeKizKMU9hovq`K$Uk7}~3mU>4;08|%0vkX=3VmC_5RAL&LpU1*{kL4!QR+NKlJDMyHsI_*_Js2ueuMuLMt|SmviQs#bTtWv|QVGxpTF(-thdx9{`W>vraV zy?!>)AmKLv`OQF`hiuQs=&w%ae(=3`ngDH|P1u!~brROL*Mn0d?EM?^cG}>T*y#>- qwRW0Bpx;1H!m}FqPGN!)5V`ceAD<&o#nF}sBpB)%$hMfzBK z<2CtUBH^7;E8PUD_?ms#MBWbBrH|HsRkF~6#G>`mOQV)=z&;_2;pE8PUD_?ms# z#M|aib#5cI4}NE%1&K0QI!hl%_r@h3Oys;BFPED@6<@Otn~1Yyru32WZ66CQNc4_+ z9M1Jo^l5zZ!Nj%OqgJ>HRPiUnhOott3DQH-Rd?W*@&Ee+5{||3;n2?CSsjc^yp9j{?p&h}Csjd0 zINm=;1XJa8{9sDZ$MK@O!?<+k{k~n6?thVtL$HrYsm{ppgRik>|I0OBp#_Oa{i7v) zrMNv({pUj=K!q(-^)V?rLf)%f)Csdh$=y+$_H5c|6UP{paB|2h93PQZ3A7-AW98=w zRDC{Gy?qhkoOaF!&R3XP)dyOTz?tat1gbDkpC-69IHkbXPFo1JE5hv7h!!NAdK%bv zm))*DNubKPlhfKcWvUO^5(D+m_YJnId%n;3kc88&NQJGE@6Z3F4=>gf&LvI?xt?sj zlPa_zfwRQt2~-91;q(tDRRS$Y;4I;*D6GyZdm1vO2PSq3e4U);Qs8)cRVuiHLLhe z&fkNj%W*?+R^#*{!9E=N^8~6mA519ukUnsIhU-Bt1tyf%E(x?K1l1-JN)5{R$MMc% zhLb9ueQ+(J=EKRYGe_}#c|Cx%LU_@_Jw&b87%>^g^gp(@xGun(%Oge(g2 z*_Mdqjw@koJ!;O;f&{MBKTn`4m=BzB)O?Ty3EXpV`GB5-D(q=0fol$2i7KL!4D4Fxm5}*qDmc+u`Rb{H$FU(@0g|B&Tzd|a`IbYj3|11G2wXE9Y zy{XHbuWWCj1@Fsc#Xjt^V#3;$c}0B}fhx6howmqxI$Dt6dF4MJpCeG^%tUsolIOh1 zJ4K?!s`eIIkl>N;zp`Rt|L)8y+ytteu`*b?a&+VRK#M{+@vc*YpC&*R97Ua0A_;1V zezfp4r=9B@<2l(9KTSZKh;x@h=xD+F2K~vgo!YMBLnWM4ktN#x2?RT5DPvKVN= z`#R-juZozsxhwO^7(}4fSml(uO+cL+Xu?+Np-FesB&75O$1t^m)C1( zLBeUr3PGSspvvh5HWBE9Ug}W>T99!1qn-0WAI#|{Q04UIVCfp1BraXFD1^6|{Vu@AL&c^z2$`0U+5_c@M3pehhw2MG5$ z4ikJYBm!$V->1)U90FB=xFkThPi2_kdm#~6s*nimYXwTzeU9T0s0u`{0m6Nb z!vxm{5`o>XKr3;d<2VGW0@3n+Es&ahTwK9@vMI*MWVw!06*X$8iW$1=b7!!hMdz1dmrp z1a{Q}qp15F$01M^STh6&_c;y|JnkaF(YZ6u$2`Yz2vh~)c{ww1Uy{2-UcPWFylQZ+ zc`k8iXEpKP6Der<6oG3T=}VsDaH`M;Upw=a}O0ICku~PMKf|)zt+0KnoIqHFa=~Vn&vgJjY=lJP)GE z8MR}!cC;W7^yhBv%KU*U=T10B*)@n3B%Jz)*=rRdP|~b&#+cyz!8zxsOwKqwN3nMv z8Tgu2d?)ActmA(+ffgj#heO-?PZ6jJ><7qELM3p0hU-Bt1@;k~qk^eIi$d7DEoz<1 zc+~OEV}_F|o_%mFqNd8ptuse)N}O{XzUIFxggnP_EVwqnwTME$EnpwC38(##MIr3HtWUH=EO%T9W9w0Kjus?vt^RoeRl$7VjHBj*EJ)y?oH~4>wJU_Z_a;>wUvX-c8As+EEqLFczZk7uA)HzxmGk$Q zJqj&&U#HZS8AnMK-wRdF7-P>kaK<9fahy8GNDuQA^Bl)16NPZ%E}3)iAy0mS1gJ1i zLby+5WUA<1tm0_EImh8^JLjJzFy0NcU7K*9yyR6*jI1Yg-wRD}f z$nz~)koZ&tz?@2;%9#`GRKcFUJjdZwu>}bp`J6lj_w~sBk8Vd5*(`Gxu@Y z<+bBaj_u$>p5p`wPzCcL3HLdUOchyJCCi7eA=VbceU1|(K;_hjJ?=uC%TpO9*n;feri+~+tBfhwn6VYFoLXP^ZMryVN!8DyJ9Ng!>%lQ-sqW?VP*MaU23w z&S+;7RJsNy$vKsAa;^~0xZ>2Ha*h)uKouOXBoP?lyv{ie6FdtC$1A?Jp9u)G-3g0^ z7!@OyhUwiC`%o5okf8e#fPfZg=1q`FJ$5 zve9ek(y&-lvMB_rV#l8>Q}ttVeqQu&bRlE@@TF1l(}!EAY8g3E-uLXA4>Fa?@IMl2vkKhS{ugg?L~E76%B1z zM}I)6sD|Kg%$Eeym)19hjgs8@@CwUx#4| zfhxM*&8Z3!W>cy`CQy|j_3y0m{q@6X^M4Y-dm%xojbhr)`HV(&{4Ito4J$?Yzo)Cc+B&Zii+U`+D zq6=9QsRrXx|3Cs&)YD|Dg1y$FUK_=|7FGRk|0M5w{^w)n=LxhRK_iBw?a`-bbTg|d zwe~JFmLP#D8kJ*m+(6}pU9>Im!6w%L`=v^9i zk49=FP(>rSOqD&hk6$#z+T&ds)t_bqv>*|?^a<%>Kpmb93Q)gjlyzxThkX-xo(SFx zRWz5#zw=xo#C-C>^Wc}{11+B*d^S;3P3EJ1_ryA? z93SOQ?FpvVCME`md_>^AkZ?*NR}zbSL{jONrJ3_U_VEgVDyP&xv^I&LS)a;F1&F@?9@p_+NI0!$;>l?8!7XtG)j7390|`_)Ewp~KC?aT9vwSp`Q2#Jc z<+S!&U892i!zS|1vWe))*$liF5>8LklI|uS&}$U}RZegI@$pU~U}P{*<%|qx67C9) zB{l)0kAe3>!Wos?#9<#jXoO2eV@c1NZ4?4k&dB%eH#>;nQFPkirBO7B8mMwc(HWh0 z1jk*Q;E|dM8mSGu7ZT10e&84W4HnI6ewqivXjW4QR5`Q6U$f+|whl}%X;$Mo%0QJf zZj4i z{$~^8j?R+A{<25Rjdi-q>pIhp1^v}Z!Vv%x&VAW}#I$d+N&1&+?qAU%fvVN(Cx>x9 zmQ~|54*IBf{$3PYn*MRZ^cAfx(|&LGakI$#G4gu!Kwb~hKd+N>%%P(ywlezvSXM|l z{!TC8SSXQalHNb$hS*dbR)ArHd9MoVp3tIYBnzw7wrE zMVU@+U*7PUP8+**-u=5&v>@S>NZJb=Gq3~4hm#VnTPNo)m+bsMwksrJ_+U3qKbLjO z{Tx+JZO)s|v8eseCeVTe<|#-wL zxNrKDUMpjF^x>$uM3GifCD8IILa9ON0}1DvRn!(_p13WjKB%mug?kQ_kG$s5F3>jv z>kpf;bB-1yoI5G?Ayeg~oy){21@2K;hDxfuX!#VO^eE{A3FkU6K8ACB@c5|s5Yz{y zg-2@Vn&%IP{@-(>A!z~;mHG0bp5wnQ6LIhfnpt6#*T~?`5B{60a z(Qd*mg+LX?s6t#znZ(#d#84v8f&`VW^kJ87`n_j$lZbOOQY-N;sxY1xq8|}I5pjVC zv>-wCFMZgfPrik{^`%5)Xc3|isKRxL5bKGUKtxU=(1HYw7&7*;XPjSWR@NpFajZuP zg+LXq;e_~QdSz`D5s^fo1qm8gyl_*bJ}a1zC=tX;sFt8L4ta1 zH1{rh6g~HKVQVfCaVu6-2vpJ9K>Dy(EGLOrLd1m%6_wp6B&eTDA3V+rap_d3b@5cF zas2m68r}<4fxR=i$`IlT5$B00_D3aU9}bDY{1_mv28fowSK<>TnO=@$Q04fx*Ep90 zsaj72T99!3+2hp_$~pJi;uR|@dzPqjO5NUjJwwDiA~F+!79^Z_NaK=K! z8Y21=ffgj3afKr%Ar8@)$o-r~IE6r!GrHPmEKg}nK77=Jc!kKqDS{CARAZ9pqXR1P=%Gr6b z&nA8i#0>H8PW7V&2`7HA*R@>VoR2n{)$?Uk;XaBGTo;SzzuH8g1qm8g@U5v)2YRR#_A?ST!kCWZ@Cn$2km)aB|JzoI2QN zEOdX1=2|O~2(*wt9#MT)fI^(c(Hs6}1?dDsD?EaX)1eYZDRusa>H33Fi!fPvwM&ohpe%5rEa)MWBjWrA$?@ zwOiCmEN<+?9Gvk6`#fuv>@S}A@FH0t;~toKtwzjfhrn_V0}JzL2v(5 zBFYefDjFYyC(0^8v8YL7qD8T&g%%{7GXy>v7vhiUl}(xrti3J*RWt_6{fFS#ZgS3f zY)2K%4DzIb=M0rd89OzPyB0;S7Fv*S&Jg%10wFTQO0AD4Vy25g70o^zh5PJTZMsOU zbB~%r1gdCG4Cg+`v!zPBX|!7Bb~T7*PP8E5oFVWN7xc6U5j00xvs?tKXxiiIuOA4P(`tpOqCtO zjUs|psn!M}P(=}-Oclq5DnXH@L9vfDfZ{~7AmN-L@Ka9|mk_}%F@=jj6-AjcRd)1x zf(VM+ttS;K`cXx(uS^w3#VS$ZMhSyQYTj``3lh$?J*)kH5v+3VWUmd7zka#|Ik%Bc@tZK(v*xsDbjoVLKH zSxUQ72vj-k&0Y^e+tpF!v|T=ZQwiuF23nAC`VF7_2{DO!6qnV0TBRa^DyKKwyK0Mw zkfSIOsB-!_pH!;E9U6UjKJP}WZL}caj4^ylO3@M#kwo-z5vX!TK6?+KE)hI){zL?- zoH3D4byXrQjqRNCKD5t(79^bUm`{|2ctT@4_o!Yj0#(i|Vefvx{9&NVnLqdhTqS7z z;mlD6T99z&EpaltMp64eOl$b#wP~}7) z_Kp|CB?hXTxP;HlRRUrk11(56F%du2Aw(OBmT3K99j1LaBv9oHn#7l}^Y2{_DbrGm?qFQ^GGZy)veIIK+5vX$F zT|P5ci3=2k^9Yyo?o=HuNI0=JKP@CzUKXvLtz)$JiUg{h6@b0|xI{jfI7tMmoV5Y3 zYgEEnu^6<*K?@Sjx`dys5`xz^+|Q@E2vp&EM+lzFxu1K9KnoIq9i+gi49~OdBRQ># zkU*6~+v_NMkKR5dYj!e)r@udoncBE-rvCa%dA%UvQ}b!d2p|7_TA7!W4oFNlntOWwEU%}&;`#tWpaqGN&reGt-%S_cMFLe5J1&#NpxW+pXS5)Z zHNzfBrhac-%ZVsI~+l48qen+XQhl*F!%D_p6?UKDPrl?$X8GLDE8B0mydgQ()qYGH2E{i#Gcyxd;?xI^%9|G$fQ;4*Z4}lgWtWGdv@kM*D^iiX+`>8M_ zQ1#XIhLT8;9G-wM*c)259W5hO|8_WJ=6&`_Noj!_9O5~w;qYohe=$L2XIA<%+EnzT(M@%mIC zA5K|$kwDes=;e|))^4uq!;2OqGEZC~i7!S@u?feAKmt`&zTF{-baxiGe4qu1uxA$} zk*Y@^RY4y}psMgdOA=`-FLk8~ElBie`CbxDle!}SBv3VRsZSD%lC5_6KnoIISNKxn zRwA~#=O`pl)pYJA=_7LIdbO+sT9BABA*J*&9K1I-lP)p9>^Vg)^#>DrI&?V)~Pb(nr~ZZXb9rRNtkcQTWWoH(SmbSjM8;{2qaKdyU=Xu zd?*B}O4j&E`gncoq00wakib}5^??McX7pYteGJ?D-1ZU7Ia-jwC{y~N|HYhfre=!e z&f2)K*3lhC@wU+ZovQrmS!ixl|uuZG^KnoHfOa7ET4p!&y58D6i`al9z*z#54 zMe&_so#`u>-J*7xW7edP=If`6kDF66Mab(aH~9Sg!rZ^NbDgi#?v;3OXHIlCQZ?J{ zH@leCqI=Nw@*z>?sZJ%MnC{-0_sB3+=mYPo66fnKmOg&G{xK9SNL<&KNq@!O?I#~= z+pUe{R4wdoZbJf9m|8Ve=R1|;-{bhIMV>Ifsh(1vDE7X6&Ya?XDX;G(aX%N179=|4 z=oig*+7aJfA4s5z^TdQ*x>#0dL1Nf+`81Vp>B<1aMHiZyWiHZI-khia8T0#)~@EvzOV+!ln;rmiT#M4a1+wxb1!b*W?dRuYk5C&!`{ zHl~nu-lIwXZBsKvgmZd(mh+j37u^qMRb=aElYGm+kIv4ki3Q6y%Q`RiUDoYrLE_{4 z*dD&qzwg}Z4a^+Jw)~?SHlpBv6HIT8LIvQirmSe05rvKnoHD>K2zJz4HaP-GX_u z$@}g87@}dQaz1}s_N2Az$D)VE-?6Q^2xI8Qr2~=T!6e8o4TGsoIA9XF`Dt(_X zdw8b8EzIn{jxkq%eL`L*KJbG%^{PL-Udbxv?>Bhmm4S#4MCe4I1&PgC1<%@bMa>}v zdlQk4hy+3ygb4njsiMT~RDiVPfBz`TOTKd?ZeXOgMq^4EeiBTaY zuj2aVH{|t}B;(9_+dIkY`1$+Wgj44N2~_c#itiL$t5K!Me(psJ5;?y+D2b};M!0++ zfvW8bHcR54?9+(IG^LjDj&dHBag~44{Jk=V(?VyOFEd|}*Av%_GG8^h;29oP#oRQX zS9j@&h()DK_2EYg5-G37(YR(SwHQwX)rS$6h|(?sRsUr8!;>#>L-XriyykR#aH`OP zM9R2#J?!KAW{ZgEyQiF$_xDuB@hJ;+tSPL)M>8^brkpKo_AJ9SsIAOxb&gfS$ku0) zjus@|-LLP_LkgN_ulFHh*V=T}-3Jwot{M9(1ge@%%q@v51K3Bp=)V4^mHQhNrXJF; z*07ZzErhRMJpbZ2LyW24EY;A0gfCW6&xynZ%&4vGBkus8|LDt3#uqix>qwwVP1Uxp zQJ(S-h8cHPr1fEIz*cf;<G z`B5_!0#(>=gcx|j^7rXlAoO1Iu2$9PN8$4_tTM-r=xk1HSI1ML%NTQAL?5%yj8>ld z$JUu4iTY8hdJ@rjba?1}BG7_Fym99w-S-2RZYLtH7XS0-hb{tDd&aNw^!RtZd26DV zh<-$b)`}y2paqEv`>%V7Em&*bk3X7-zC>)Fcd9t23j5u{Jz-kyFNd20`^++twu#dI zdy+s45{=&$(%y8PLhp9s`d}Yl{~PMRRZnB ziRI>oY!k>wFYk`q0h>6?9Hm(os zcZm<=)7rF1WyXp>-NY6uL|Y<`-y65>5fNxXB63(M?eDk+&5|c(l8-?|>=!9YaIZzn z;~a)2239lMH=gbC(T#|{ElX_YRG|+fk{V^T7AZTJbEeKFA03HU_D|IkTpviF3j2x> z+!70YOe9+(wv5zI!#&GtpYmBfdby$uF5UfO_Q?9c_Jc%{qBA`kP95+aZ##ri#Wi@i z#GDues&JgQTS=3g6+$^5Xh9;?vtypGW*qgE2;=dp8u=KOEmi0X7lA4qgYC9E^ufO3 z>;o-G{QKocPy9yLeWQo)?m5>-oz+=nSs{TcY&}BsA!24oQ#mrA1&L~ATCIwB=linI zWb(oF@w{fc;_jA+Dr{qR={BC&Y#WaZ*s2$eOzgW{qrTa`MO`KKwP%BS6Fo9j*gufi zoaTP?oJu9l<+JKjs(6H}@-%G>0#!JU*@XG`C|T!dL1N6G6Qe5(&t(4CxJkfA-?yV< z5U9e@j=n&1!qO*B2;s5BINqq4mV8G}^J2YWp4`8Gqn%H5!T0k1SWo1yRpj6E&YJ9z zrK|Vt-Yt?!*FXyrtA>YaNqgS#?F?H?1kIfK)eZ3?sdNj^sc}p_ZvMgmG4j4m zpaqF+Pcmt5c0KnUO|vzSs#Im?%TytOs?n|UYESExHkTw^Lj>pidFi^`KaAHG21?7{ zoojluY!kIAFA|tn%4YJM`nj`ARjR6Oh@h6JhpjBft;9eJ67vg3XqnPK_BC9h2Z&gE z>ck*Wg{3b0hyHDcQN_4)(SpQ)Ha}<`lU(x+7ahn)4@yZtC zb1a|B+v02K^~C03ZNEn?D{8y?)&5VoT^VRWVtLI6o&yK7nbC{SP^!4jyL8)G%uS%` z-<(;ru<6yzp+h$lK_i2{v(rvlgJ?m*Ty)Ws{tJ)UQ6w z5-zJ!KNgc^wQp>M_V4i?WqqxprJ*qE#aF222WIh}V64Odg*AkbUZXTSP zAW-LN7CedMI>&pV3R{momej8^b{mf+XhA|`ou>`FH_FWF{ew!ETjGl!M$3MV1gfx& z**z-t74b9I2aj-ERyo6*+h~RPOUjjUq)thtZjaPFUKM;aUFL&FYR7_v^}do; z?5EY{yo^&R=R77BZ9hnsE)uB1nw3$XK49pm;QZm#ITA0Hx7M=PTWy}m(U*L1ozF_y zRrYhd7pk!S?XqgrSw{K>_U*&FPkNSq*Tj7P`npH$=iGJ&U#rNmsDTzF_7^_q>71ai zIXC1QrHYB~s+NgCpo+&B9x?3kiitZj8p^hd79^hR{L}MG+OcN2wCBkO*LlA=>1584 zKoyU!+(PX+iir)FVdG31*6OqGp(v>>6b zCQ1-7nuxP50#*IGER(DIZWBYu$Ac*yjmf{%^yhpK?MDj|xOx%dJ`qbkL7-}L$V#~? z8n8Y)`B<61tI_3QPHoW&%a0Z$a7|?sVMHu;5va<#c!gZI#qXPwd|Z0h#+cS?vVOJ9 zEMjjIx<>Tr6b#%r}$%SMrpxAkZ1)qd$^ zgN>Bg`)O!F0$1Kb{7OW9BEE7FsG6O+jK-_`1v?Irk6%+p`45ihYz%6iR!0jGxHmw% zoB?8>i$K-G(^)j$jarh8=cvAOl3G>P)HJ&EY_FpQ33YYXgNT|$w004wI)3#FjrYrr z|N4M@&l+NVMat;{YR zElA*=9KBVAh~b|gP?hlEuO8m(yLC&D4?114{{8sTPv7 zP1^qJ;XTV2TmPXtPhB{~YS*Z!)wKS29W6-Ujwhvxh!#Z9D5?;sdbBIK#=ELn>)$3H zG{X65gtOkpt)-&{3EY#Vc$bLwM7(klsET@=N8{6hFQ#z}_qhISe~n*yS*f2r)6jwh zo(>4{jEL$)q<0ahD)hdb#wQI2Mp)z{4p9FH5I0=}s(x-9DdwyI_CXQBlOb-(>hfT-*uP=&D_eHVbDJ{l7(8WWYM4+)It zglIvLW$sp0OFW^t9q)w^;O(&!<$ADo&0drbj>318d?5D#(1HZUcJ@m6%#DL`C5!~B zW+t62*Mpu>^~uKo@-d+NwQanDL<@nJ{nLV@efTkigi^ zUPmQ5c}wOT2~?GRHAU_%)+xa|cXY0%x5zSUEAKO)1qqDp?A?!=2X+?YeFh{@wJ_c& zxdYk0I>&Hax>>J|;xiTlEl6N&Cq!2wBI|l(K9E4wkYqjO4&>lL^T-FU=o`G7D*GT> zkigi^u8)uJ#>o0W0#*4ZHIh5fMgHDIKDf@$tVzM=I0jmfz}U|2A7xU$ki8ZORIMxI zk^9uoLk|ReoX?wF<^wHAU~DJPiu5G;cggxd0#&&d=8*f;ag$#rA0sFq*)mVreuwgb z79=pXlV^~6+Hzg^3{oLbb)$7sxpNz*^j-47yEthsUEa#A1T9ElY-hKt@6NB6yEsUo zYQu_u<^JwJb9p`=Nj`e?dAp7Cffgh%wxe$-5FsWH-p2Vr0#%1z-je&f8=8M4AGL^B zUNvdxb0W}!1jcqYQKE3X7zC=$q_`n>jTR1!MX}E)^0E7A-_YCS11(5kY-bbaa(0VB zpz7q9-{s!Yz3CiZaX#u**|?4Kffgh%wiBWz5wZ6_jzOU6O|s{5Z)r$!j;VP^_>U7a z<&H2~kigi^?zMHp4B5|-Kvn*#3FY2Wj$DrdKDIP0DEAZ5f&|8P_FNl!dZ<`8ot=+O$7;qPP<3E!ExD6=A@vUO!Q)l3VLfH4(1HZUcJ}Ggf-4W?T#E#%-qh|W zcT%%WToUlneO?7QUZDjEjP2~P{dKQxF$h%U`QVki^^H$XARlz@tS8A8Tc!#vNMNL9 zM;U*FwU&F9NT3SiF8X4~%bj}I$Ie#0RjK`W!iVD{o>S2qNh6XO-`}laWqi=Vj}|0w z924Rc5p9Xc?;=ozr&&VOh#O{%jg!UNUVFA5ElA)vM*WG8ac_eV;6XG-x)rlzUB2a}p=|aTG+uA7n-5R}iw(Wkj zAc5nU5OIkpMMOmxfhycd7h*`ocLBPm~d++pRpvTwrvNyjs{@q#Bj~2Wyj(kEiBSIr0!!DITmAa?@ z`eYM*fM=jFuE=H+ElA)vCd8`%G15h#3eSz`Egs2#@-2Nj%;-E;c+i3bj(qeEp#ag{ zMW6~#nrJqtH_ZRbw0=gzI;S+WAc5l;?K2Q@o`@1I0#)h>)?dvZ`maT{FdCmQbhIF$ zj)|WmP=zO$^z=^3+}4)cC5_!hN9$-o0@tE6!V$5Sh?_0~RmusbsG6XL)oxK-<9gB+ zI$DsxwJ4>Eh@M1jbrFh6IT`hawXt6QJ44^IaHo!^p-A9bl%BmN;sp_VT?DGsv(#m| zyIRFZhiJ8zS~^;gz_loSWsHcBQ6buoE&^3}UQb`6Ezr^0_jd#T>;=&}T9ClCD7`hC zh&@EiauKM)^LpB|oZrBzvHDN{gX8OUv><_NQQDy=q9_r^Tm-7{grCOUO~tKAmGfA8 zi%iqef&{Kb>8aw4#jQC+Tz3(uQlA_+)GvW`sboEC(}QL@T9ClCC`AB7oFihKi$E1V zGb2Q)fh+wxo_4ps*bz@h3lg{%6`~LkyNF2RB2a}-+0Yti@FDZv+@V%@o2(jIkifO5 z5VHbAAs2xv_3534TNCNe%MP*r%+=aN3lg{%6{2x~_{~M23ga$%=UE^ktL=)&kib}r zBAH%kjhV?RT6N}(@>|Jl>G8aW`QJ(j}XDNiJl&`Ik`0Wh;>PK7sd8>@oa&GBi zZf&{T)73vli$A=NxjuY_M|msybtH8xgllTFd?#;YSM+hxd=rYQOZFch{~XA8U!oNyJ?jfhsH! zA<9zD3sKIOyK;_s8oGX*R@G{6p8I+!`AE{WgHh%{QUA;YNBn3(0-rUa)7L`Xj6x$q z%;i0!6arPbu8q@918DcIY0xd{9dNxkm{(Td()p{mgChuruI961D zn(&|>El6+*|9jG@{;dv1oxdCC9bfwt0##+Fj@9bbuWrt`vy6O{n^40j@a&_$?w8H7 zKKS`Pey+ziZ~l9|9m{Z(!hAI>Q6n#jCHck9SagQ+K<)ZE~;j>F0h<@ z6e6Phx%nIV>3yGfm+4g>bT{tTN$E!m5`8B2*JifJZ~A8J zq*P7rxkO(wv4^o{^_L2PDl8G|=U*i>Mwh5(WbM;HDJvurv>d3-hzc>sWa71R0V3uR z@v654zU)9bUqLy)vqI`;V!au)}k7E(Ztd4hU z7+*c;prZweDm%+)^Gb%A9#@n84b+jOXPlXEc*B_;=O(Kht;Nk*> zK-G?6CAI2vN}CCC^11UqBCZkf;KBkOEl9-aQB>s0JT*vZn0MufLwPOCeBI^LRe3<&kD)u8zF-n(t<3 ztJuM!{>Le{>U>}4nY0sk@@o|`{b2TvcV>uMHuWR~P#$Mw;Ph(s;d_~W<;RAHWk$a3L|f6LYHtpdqB`d1MZ zwV(7c=7n>=dAdz6tDVU{+N>u2@^CwLo~9IH)y=F{h2pwZ@k3`FEl50CS5n(lKf=ry zi`(v-d+Dv*nJQW{vh`L7RAGq-QKC;JEB^W3z*l(Is?TfU@r|AW^Y(vW> z#47G0P=)12E0*(D{Ff-_dy}d;$2`UVzNQx5f1H`T?^W{A@6sy&tf4(D&)6#(T9Dw8 z$a#)bi0Sbf`kR&+XdS+>S0PX}cV9#8=Bn{#mEUYT$Yqiu$Ij6 z>W`=Pvsz|R2~?>$=W~NhW%kQ6$h_5?YcErbGpibxJPX%$&Z_Sr|jG1on zeveAk=)rvA4trh==F!>?aklJ^?{sMuV~5B zS0qsN@Z4CfcT^K|Lp>(wH=}y}y?x~Q2U=#18>8jlP{VxOexoZ@{B**;0fqTDaR&N8 zLO(iEo4nI7OJ3PRKKP6!`@miDYyt^X74&&Q$rV0a}o#eMi#{=O|@1 zc<-EfwO#+EY>7yqs!QpT+LC$Y%)!N922!;>O-or;XgOE7s8-;3Ez@7|jR)^!=iJgR z#qfc|z$}I7$$@6(#>afx$NghZyD>2cRL#s=L@QgaquDnD6I|y-Lh{HuN6WylP%Rhz zZhq3~e_W~J(yeShk*yumi$r9qaIN^;VdmA!Pszu0BJNK+TjCbAL?lp^zH&vaMxT-9 zcb7S`{O5jYt7iG5dVy6b42-WZa%xklptkKmP4i-$*F?-3U(NbDQ7%18i}VIskhqj0 zL@Rr$nOXAq8zM?(FJpXnpoo>VN`D`&$#F&h>%fs(NVwOW{AeQ)@2-4n+|4JfM$M+1 zXh9y0kQK9K;dzV{`{?#M5!+gIK)A zsS`J~(YX6Vt;L>i4D8!DGMsEMR`Y+XZVq_NYtCvJ59uQhjMVRr{ocU7hJA4V^Uhl1 zrg_Xx^Z54$W4a|a3im6dH!fXI@zHwVD6R7>-5fJ%vj;~EdM<;AD}4*;?TA1N65h%Y zTAg&E=88tV9xQ$8quxz#uAlv_kwTyf#}(S^BceSK=ZHWH5}iNx*Fp;wFxTGjlaJ8a zf9YAv4$@C{`&J=Pg{43zKS^HcugY}r_gvXTsgIMH`)KV_k2PDw+ULR9hvsu4mJuLq7W5{C__XhBG7`wqjux8%N^RA$xHHH-_%YSje36<^Nq=0Qz1}= zGpZ1gM5MY^%-59&v>(`B^1Ug}sYn(I4MwMKcxC z=ARs*^z#e(3Tw-Y*D@>bdgH-SoBH6OcUmbTej)-bNaTxGP^)*dnYpC*zm%%TDz7xd zx7Bwx`A~&G6^{AzuCS`Fv=`A^eP@V33lja(7t+dY>S%_{;`!t7_=Nhsg`3S1`v)ro zs&Hly;s6m30|Z)-=w7dwR^eb@^Y{F($cHC;PCet^RQ|nh1{z493g;5)wM1kO5NJUn zUH39t+cjQuOJ|;=ns2J9zwcDpU*q?_1`?=J=cwDo#_1`t_tTeN?54z5Y5LaFjy=d@ z)-8U+6(R2+Vlfdv5rL5f5_uL@)-Km5Xr?*zH>K+8>TmVe>l^5$EA~+cRAIzHzhhbR zt-gndQbeEyiRrC8T9J(<%vFgWlaI{xis+>-=hBz^2Pg!paQ2~{qVyGvUc(;hc`D!5 zadiIq;3zHrUd{aG;(8B`sPx`JB90QVuF`ECEl8~I8=<9pTg)7Jihs9VZF>%*PIwxl zS6yKsfhrt>g{V$MQX)(u(1L_I*Zy@Zow57-udJ@w;~6;CK1|z3`{v+Sv-B~)2ggS` zaVH{Co3E@#+2R>!L8ASrVOrjjqs)Pmwo^XVcQ0e;mt$Gqr+%y>fhrsy={-e6)FC1@ z5okdIqYoj9Z>Vo9sOIx8{_ToFpbE!FIv-qL-!O=X{l^s@El8-5%&%A48jUm6^EVYI z6arN^KGGZah-gkkNg~jK#E&P(X;)X%X-2)3R94wLLL!U z#ys~4BG7__C-r!(f43&)px;)IkAx%dXr~?(u^#L!X`HWLOKVqRoH;-9O^;QunKtUe zc(Xv%FP>e0G}G3n9dBM}bCHOpd!zL^{YUvzE@^9EOob~8m8kpoLOt*62>eJd9GcjZ$@xQiUnOh#YAl;x8YjYm2)0Bcpp5XhGtOcjdLoHAb0VZsWN9W6Qke zQcBfUN)-~QQd9NkFQNXINfKCbq8b=zLE_QbQreMR5$5V4JYFTZCaiz1m9k#Ff2kvZ zD%>xlbyU~f*57v%TK^PCWS|8J+%KaiQi>h)=jiuLt5vg;f%7Y_EO1T~;sz0Uh^R*d zT98oJA8mX`{3Gl1Hmk(xtPrTeIZ=rAM2sh*G7)G&VnKldTG9_4&E0?Vswhc;o&HtH zyZhtx@1PKxpPW1X_?db1_VNJwMdUn&ct*h<=&G zJhZ2eQ8Cdh9Z!BRRa0iR)ONJbX|4`AL&VW-A$sDY#f>k%E^43!2`mwM1LpP+J?cnt zqn3+6)zOevTKB(mnN1$@PHIS+)%xM&BlQ9&I~r&~0(V~M%ZsU3>jP7a)U&z>RN<^iEIHD8Es@XEFmVNT`v_ZX(hWQO-r63iCw!)J4zg zZ~yFIXzgxkXh8yZDTK&T?5uvCh|?Wa0#$fEOwSZe%4E!@-H+KV)!h&Dp`O>~ru~xc zM2PmWG_)Xr@f-wN_Kbz0Cjnzg)R5y#IU+uxC1@I{XA*#@xOh($1Y3tgP!F?Ev zwdpq|1DYA%EnKR%Yja+S!jVAV^jk6_rV|m@MW71vMDJ+K)ZVBb=enM;+Rr9hkWlk6 zh=>!huj?k|90^pZWz~t+&Vy*}ypGn+xJJf!4)a8N`rmdm#^p$-$H{+GM+*{a)Yp!P z*+e|frxK{bJkc*L;tn*H?5(9&==e~nK_u|m7W#D!5%Gy=_`OP?3hSSqrlS4Cd$gZ; zxaD*c_Ym>9C5)Eo7t&fEqe0v${)w+{m}o%)pP8cBfQX(%RD7)xsKRKOc8Z7?OvLqn zZkT960-rS!BI)@d#^3|F%rF0Wrx2*Za-%4mi1>{FK`A!;IkigZX5Oc`KRw7bVPzgl^Cx7$}(A69Cr`5Yz$I2wvOSJBwHQzkm z3{8I2gC~4=@+U+++C$z&d&o;&d&szNj4Nb%r|gd3^)C_?wnpAat*o7qK;QIBZz67d zQP|q;B2cB|Ni1KrK`&aPo0XaJffgjxeEdR03L>V2tAwIb%4!X*?!Fi>$}e22J6yM6 zo`h(cbFzMBO9`uhmCHa261bYA(z6!Tlo~_=&%A}W zMnq#G-se>bRAK$oPAaXVve8=|-n@IMOF^jyY^8|L|&J*?lWtxyP5VY$(p5T4&K zqlg$+eT9w|B=8voA?6Zsi-=j|0|``NNz0Z zpaltBu?lgQR$du$9`*O4l@}7IQdeHb&xiVpCQV?S+1pYC5~a^E!Nv2-mo@2k^Xxb>^p)W|l@7474DD zPb3NPH4!%#uQcPi2vp%3m)^`x#9Ja>HOye31qt<;qV*pPt3}i@f0u~V3V|xDC)ynZ z0xd}3GfdRliD*DR`jQVMP=)P{o=+^8T=x~dqMdi0DB>w1?s3qr^WhEtYZqqd2U@gK zc0Z6fzr2`MV!vUQ+Q`pebvv@b|D1>wE&^4!6GG2&J}7M&bi(^^WeVlI772WMPl)$) zCR~At+;k?4_d*q(71L_FZV|mL?QE~0oo(E~#??LMiSiLI!r%J9@A`_--x_E^Lfr$% zLqugFwz&vYVV>wK7}+yf#>NcBp@s1bv><^`ItuX<5#@;Z=ps;sr9f+(H%ZK2X=h^k z7wXOgK5dG74m7L1NMar%qA=}cpalthj#P+=!@d4ysoEO5j_p+lRN>x<5J!k;LquC5 z(1HX$c}lZd#=rdKQdBY)C%C5&sKRnn3A7-A&#KZ&m`XPjm2Q$n@eCwTg(V&QzJbNx zH^A>0;9H^bUFGt;yxcZC zbHAbHvh@5t;lLZrEdEXd-V0T&`V0Bhg>tuI|MvxAi@zO$_r(@7r|AcRtR!_s(-l6@Qh4eehd{ z(1JuvAF%`PDMA8O$9l~4@f%{x*M34i_$~jtS|s9ki&#jY3QJo4^4{NURij9H9?n7w z5}&UR{t7UAuS(yeF5W1SeDmzEh?}NfA*H+?eEhUsA6}<^k)RupWK-K5V z3UiJrj8Rs>RG|fl+Vr(%&WG}~W?5E9pbG0r<|F6>>lxb>f7zUU@VC%a0xd{Pq3@+K zp?oh@rV0sE@wd<=fnQ9QL_7L&D_i)>t;y&M-F(eo=;m*_^R@D=cuAlI3I6Ug6a1}j zH6KWzioX-dgz~L;_Tj};A&q%beV_%2Z_1yQKE`B#FZarPAc3kFW#x5RBDOfJP5!1k z=YzijucituNbon-nV44QrK_xvKvjDBRy-5Rx8h|!(1HYi)13+X%kMR^95gYq%B)tOerfaAO3bGkDT~* zB_Z0Cs9+dLOZyVd&1Ikk3G_|B1=y3@XtSk^Z$jzv3V|y1+clfgd}TEJ`-ta2qUr`( zkie3rH?j4OWvq=#v10hOZ4Kr9?S1rLJJc3{bKtG)1wt*%O{tSKox#b zi+0uWPxKVLRl?Wu*)XN;; zxhjDw{H_#5uWw&y+qb)Ccpas9qgudzbA5kgwpR!HTs`>{jsX_w3^CZNg`^oj< zuSaXWuB!y9u-xeVqUkH^na)_Ab?JUI(1HYheTv#{@t*qrbIT+DJw8AoP^H#~w|O1o z+F-FfotfI=`HovS$0bQ_yq4EF%G=imvKBG8nH)b%(-x7D;+I3x8t3J`2EQ+gGb*{FE{(pf&|XmpC?eo*PKE- zzDiT1zw~jd;3z*@kih6n2qr#^%9ztlpo*{A2gh^tOV$IerH@*vU;5F41ef%GrCT#a zYom6x?$L7>zw)C62{kU^8sxI#8bktBShMuI?T6u#NOrNHQs+ou97JuGh(i1JM<#I* zsH#Kp6}KKczFKqROQVc$dZe+hp@kMCFgg?Ba|Eh>qG^6EKaSgIcB@z{CCsS1+*I$0LVAQWhuK_~12~_blr)q^<8(cm+Q2Lm-vXvh# zNMN)qM{2A3SFyLzNUad4s!dTi`>><%Kj=4ieQU+rHuA-04_c7G7+#LlmiM=$%M!g* z2~_bl`>m4CJ zN1%$Y*@wN3TJ|tp`bc=Opn(=7a1}=HXCR^kjl1z&1gcWdN{@Z;N>7fWR$$yU(1HZ6 z$b?vZ<4dcwFJ)xeeGL@?RqbhI$v${xDa5?+_5L(1w{E3T)IbXoxFVx779zL?-2|%C z70ar{nf>K+EiXdju7MUL_Q6+bg;;l@oSEzJL(f0+hbaWAaJ58d+dHZncQc5bzux{j zMx@WZmLq+P;f0_+XmCEL59(;)YlpxHhfXtySQyo9TU{4{s;_BBhf9}tbf`X(4>UIH zirAJfx{Hn$Brw*ZIwvChLH`w5Tm-84ntgC|CPeu({VcIE*78bOC+QcOW|MXMOjz_4 z=ydYB$)8d3`o;V6KE9@NwS?cxwmY}w6P;C#1&LqJbxIHvfd0Kwk* zUd>6x*Q`>Bv=@q6tIdYRx8^QwpaqHRD>lkGDtA#XtMo*0ef;bqP{r4rTAOJ7)n?fe zH%{qcpalu5(~c-kVMLWp;J=MW~DbX8p=O4id3u zdq`0?fvQSGun(IUPo?@-@8rd9B>dh$3ldM3oRdD%{K{XQ9!JEWHt}=12~_d*bMj#m ziK45?*8au9uMD&xk*|Cz50_QKS^O<*CI*uaH-Rd?=6u*hopuAHkC3STI$DqzZ03+Y z+Fa&u#n&cccjZ};Wn2WRh7iH|u!$C#2OE`!&xt&8rl=n+NZh%TPWt#R{22N8mI$uF zOD+Oce9if=i9_KHBvCg{G7Bw8ge>_}*2lr>XUWGAA{M3{7Ws{fKvh8^I3G4~XH5d5 zf07)L3oCQ#(;~n-oZiuZ79^%-iX}&);vu}>9w3C9KowuJ51VL|uD$e8tJiOSv>=i9&DYXL z^oYacgNYy8j9%_0P{r5m!zNN+9wvRvd6v{f3lcbj)3Z24EZH-!cykwls`E7FvkxBg zX;!9sc>KqV;-zRdKnoH$=F^xsy{HiuySR}jeNi2I)W`R+J*yTR@csL4uZg{xdK3{l z5k-kW3li%0=&O}XZj>X!+xT~dKoyQk^v*LPN)a)b2(%!v*SjX1Q`ji>4$67o3+wez zB682pri^f?!qHWT@kA6PA|DZGL88Nm(6JC|6U@^E(X=Se$8QbU$Dx*k{H2Ll^g2W#P=&J{jXnWl0TF0HqUycz(d?t`x^3j6 zf4L8SPF3cWaTEeoIBQes5>bGN!bG42iG%g8M6V!}lkAXhEV!^AEBml(c^=$xsG7eh5xMRcRtQw#EJ3IGL=+(+HxXz-;+yIzW&h}X`yBZ= zxA(Zl^^qy8ghHSSXFGasY2R_JE)oBhDWS}RNEE1BJe=!%=L^oq=$Cu-szkgmmPsK{ zg|jw2kwQdXBJvf_q|E0?L}l0!&V6ublT+lQ$F6h+=cCt#6MnoGsxbPXJ$)j$UDYK5 zEl3zipGzMzwjLoLMp&q!5iutGgNX#HaLlKZA0j+NOd|pe6Zz{}_)7bgVlE^nb zDjHKWMTB=tIU>4eIiERpO?r8Kc-U@p1YMVF-Ok6?^lVg~oK~-vdm>-=sAx^e6cOE- zh$=UZm}AzYm)B1hA2%cDx&je=P5r#F@WGaBJ@~`;GZ~i%Q#vryFXa1&Jv{Fnv!F>3dxAKN(zf`|a?K3V|v$ zRZWv-v>tyb;Op0;riB(HIDhPe^GEOZp`250#CyuQLVyZOgq{mu)mg?2>5?AtqXqAK zOwMY=&K1GrI^>T_>UkmAXxE8MPdKXzQ5SZ#1+ZaqrHY=+%^uX1jUK z$;7wAD@S&B5vY1V1h)m7Xw|!>l`Seu`~J|3ljgYv2%g0syf2(sY`0wiV;C+sgKqQlqy1AXf5F)ScHO55fqh25d_4F zSgfEzNhF|RNCF4}5hKJ(s3OQsct}pJAO%5Mq)I>}njay8T3ZxRZPr>ubz|3m@aAilXza!)A;Ea84Edbt z{=R}_n;#*9S|=32&4xvAyW3ut{&V-860RS#?FfS$K?wElyS~hb?{8a^K?w=oSo~)=nHzPKqvU!Y8(DAu7 zKJOP0Cq&E?K?w;y!>0FZ7aw%}m^So=46ZngL|h;B9%P(YCL$z3>|%^j_8KQ@5(sMX z{_B0UII&IyB_tSQbegW7WB8!qkJ5E|T?Mb5ePTQg6O@o(#^H$A#<}mN*$H{PDqaak zXh5uer`i#ekl?7)ZbGrdM({rsOIke|YnzhvYWXFd=J~nv%3aNBZt?=xw$H7tC;Jr{ zjF_OvU|Mw&5_ise&C${2uY3nVEo<911w^qTgW0%Ak%1Bt{eL#w**N^=BH1vaPvQ59 z6A5Zr+iV2HJ2Ot(Y|qNEYy%P!9X`)?HqPy0HjL;~m_0v{pq91GMnL4tM`pva4N6E< zM*BM(%hxTGjcFpDE3cQ*j2%81|BEoQ=1?FD_)=4)N2ghbaCJ)Mozq8DVtGBUe^qZ0^fS=(#`#7Onnh%w5qC?Qe$ zn-R{&Pd}S28|I@8hvuYDO(3XMCcWEk5qvZRxrFYOOO$mwjXXH8?dlwhV#t9L* zB`wp^5(sK-6=604V(X04nfET}vs9xbLJ5gutBReCjrY!yjol)w=ZOThtZg;|VzPQ{ z#30Q@N=V$?cbT)%xMq%QGpBNpQKv1i*2(u9o8S3%)yiL)Anpu>Pu!v!mRErpj z)FSMv-b)~;#Taw;=tF{W#q(-gj9zA|+R_#4GtM0TW7~ayom0NCve<9*%*eL;)&8pa zi~beq+3xcpDRXsIw>BN<*4mWnRv8VRc*#lb8&?w2DyYhH^ozuBZQuHE#;1wL)-Z(5v8a#uC^sY&TeBa5AldfVsuB_kKP_U1`?=V;VI zM=yN9=112%f9`DLUtOC{2?<`UelHlDn{GY7uE!f8f?6wQ&2=`;O?_TA?$2tLX2jmC zh3S-#2>0CXo)PwcdXYr9=k+o!a{Xv{ytIrG62;qRx~rOU+#=j#A9fYY{oRBPFtSUw%7|A9|W2R3lKt=OXrqpo9dyuCrc>s@i=a;+FaiBP6KBnWmFf zMSK+}C?P?wYo1StW}fq5N@V`(HlbNdEk+ETQ#3J}c}O-&MNmQ_dNkw-7x9ujK!RF~;Cf3)M74-HA}Arj8LVGSR=0`S zJs*%0%_KoBu0(n%L&U#DWXflhkl+Z_bC%;;#I}jpDG!jK7FSfAS|{Q&5zY7Kht^sW zj1v0$21QjBr$ls?2l!poVrJlZEnlpv*eoItI|}+nicH3`?=&5XJVgf;}rXtKnK)kFTzp6~8yRtt@NQ}MaZ_dWWS8R}t zXGPrl!-CSg69{TOF2e4|C5|v3&0UihtyT6%35h{nqRvL+)mG(974f*TrBew6wFZl5 zEgJ!0Idx^h&Zu@?nUs)t^PwfqM!{#kY>bcR)J+S+1huSf{RjxP~o)S4>7 z`VkPV)Z^(TeU{1t5lToLefEB5qeX?;h=?dE*`AU}Q0tfo8&?5gJ)W+em&>UkAmD{-7|TW|Mx{txc1@BHU~*iLL#r(9~^PsIvedIC>b`Tm(v>5diDQlgT%P2 z`#8GguC)m^cvaL|kTl#8>$lod7G-B9IA4_xX;gMFx!C#Vm#yCN>9<}T=Q<*1w#9bz zBa0Fe^r6$ws>{MjQ0vIBsm?}=t@b;P{(VDGLW2Esu_U5e#+8aC{&ii8+S(XBb>N6U zebn=9ZS;*_Tz4O9H~GIQh2jUx62j}bOXl>3ATYFXQC z1jMNL8ue$zUrI=<+11k7I5YF0Y*^jrRFkEy?n8oFYekriFCDQ!K6-&zm$+z zzPXRHv9`y4*|1eDU*pPFH4@ZXA;N3~M21$JnI+p_w-tvH5+|oja5fgzJ0Kf3h%jFz z64bJ`*$9YX@{ti^mHkmdqQ|u}osH8^*2u;P5o60Irj1D;sMTGB&5wYvDo#$`rZlVK zP(q@OB8Ei?ix|PmKQ_pHLIkxKW9rr@m-~dG4++K<{i>f_S!ywH%)>cl7fijz)e~NM zu)n0k6xV*e*$G`$@Gn@Sn*a7`CwZp+A%A6qeAliXee~NzRy^)z zdAoWztwoof^wWNIy=y1!sr7sIe!#Uy7TBzvpMH_6E#)68&7gz?uU3C=`<6DYA2<1x z=_IJtq*so!(e*NW>$m5iryS9E$}Q=XkT`qK$8UYieb<34H9oy??SOvn^I!D0Q9@r) zLLzMA&ZYxh-KSG^t1=SQ>VAF)cb__M`A9aFC0Dxo)r5z0GAJRzyQ%ZYRFSaV-9GIk znd5LhXBMS5sYF0r|oJ)+#`Y#63l9JGPi0N zMy#;95AsB6F{{-RvZ`V15}}$#DBmT)wOvnntA?>hM6Eo)@1hp7bDi8F!fF6pL{LJ4 z8DLPw`9#D>d4L49xXW-m`q*v}D@9O3f_aeVm8&9Q{TL_@kf0WKOL~t*gjLmMtGY%B z31({gTk)z$SatAYd4L49xa$ilMb?i}5tNW%rlu2`RFSZ%L046ANKlKrS3S`$!us)h z5tNW%Zl_byRQEX}8w=zC64c@@Tr1ARsBe|KRU#-M5zZ6$$E!H1Cx!@Wv6`TFuteBs zuNFZGiEvKcS2O9Lh?(*L32Lz_qGxeLST#yj+X_lZFo#$4iPwE%s^XBK7Gq3M_p#_x zB!UtWj4L`rNHgiUh(q!K*E_B_Tv3(1im=hXK?Efv7=!hkWjy)}mIp{siH)MDP{d0&b! z?`{`C2??$%S~)e7?5eElOoCd>A3d+Th#ew!i=c!=c#X1|WMg-dVmt|IF>?+o+s8!I z7eNULuI>8eM>EMH^$vM}1hu#W&}#md7O^T3bIr@xHIQJAq8fl^lHHFk@&E~HaVO(> zgGG3XS3N{fLV{V8-tAMovfo%1%4Z~~#T}V4OU0}BIvCokkzf|(d6k+;HlvQqXZ$W| zai6F+KjZOAzcPh(kR+IQDN@Jdl~tYjUDV)92V$g0)zGW;%{CP3TY5MCW&S7O#lSld1iPK~fW#PfEKHh3j=x`SP< oohA|J*AbNPtOkBln4p9NPhrs0hNFkN4EdA6`57dr#Xfo7*FUFr&Hw-a literal 0 HcmV?d00001 diff --git a/twil_description/xacro/battery_bosch_12v.urdf.xacro b/twil_description/xacro/battery_bosch_12v.urdf.xacro new file mode 100644 index 0000000..289089b --- /dev/null +++ b/twil_description/xacro/battery_bosch_12v.urdf.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/FlatBlack + + + + + diff --git a/twil_description/xacro/castor_base.urdf.xacro b/twil_description/xacro/castor_base.urdf.xacro new file mode 100644 index 0000000..9271976 --- /dev/null +++ b/twil_description/xacro/castor_base.urdf.xacro @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/White + + + + + + diff --git a/twil_description/xacro/castor_support.urdf.xacro b/twil_description/xacro/castor_support.urdf.xacro new file mode 100644 index 0000000..b5c86d0 --- /dev/null +++ b/twil_description/xacro/castor_support.urdf.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + + + + + diff --git a/twil_description/xacro/castor_wheel.urdf.xacro b/twil_description/xacro/castor_wheel.urdf.xacro new file mode 100644 index 0000000..21172a2 --- /dev/null +++ b/twil_description/xacro/castor_wheel.urdf.xacro @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + + + + + diff --git a/twil_description/xacro/chassis.urdf.xacro b/twil_description/xacro/chassis.urdf.xacro new file mode 100644 index 0000000..dc9e36c --- /dev/null +++ b/twil_description/xacro/chassis.urdf.xacro @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Gold + + + + + diff --git a/twil_description/xacro/cpu.urdf.xacro b/twil_description/xacro/cpu.urdf.xacro new file mode 100644 index 0000000..dcc4a58 --- /dev/null +++ b/twil_description/xacro/cpu.urdf.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + + + + + diff --git a/twil_description/xacro/eurocard.urdf.xacro b/twil_description/xacro/eurocard.urdf.xacro new file mode 100644 index 0000000..b28b461 --- /dev/null +++ b/twil_description/xacro/eurocard.urdf.xacro @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Green + + + + + diff --git a/twil_description/xacro/fixed_wheel.urdf.xacro b/twil_description/xacro/fixed_wheel.urdf.xacro new file mode 100644 index 0000000..dfc8761 --- /dev/null +++ b/twil_description/xacro/fixed_wheel.urdf.xacro @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/FlatBlack + + + + + diff --git a/twil_description/xacro/fixed_wheel_support.urdf.xacro b/twil_description/xacro/fixed_wheel_support.urdf.xacro new file mode 100644 index 0000000..1346e56 --- /dev/null +++ b/twil_description/xacro/fixed_wheel_support.urdf.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + /> + + + + + + + + + + + + + + + + + + Gazebo/White + + + + + diff --git a/twil_description/xacro/twil.urdf.xacro b/twil_description/xacro/twil.urdf.xacro new file mode 100644 index 0000000..efca20e --- /dev/null +++ b/twil_description/xacro/twil.urdf.xacro @@ -0,0 +1,101 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + twil + twil_control_gazebo/RobotSimTwil + 0.001 + + + + diff --git a/twil_description/xacro/twil_wam.urdf.xacro b/twil_description/xacro/twil_wam.urdf.xacro new file mode 100644 index 0000000..1c1e31c --- /dev/null +++ b/twil_description/xacro/twil_wam.urdf.xacro @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -- 2.12.0