From e53da7b299d59a47873bb68b525e2a11f261c089 Mon Sep 17 00:00:00 2001 From: chapulina Date: Fri, 21 Jun 2019 17:47:25 -0700 Subject: [PATCH 1/4] Start of lidar PC --- ros1_ign_gazebo_demos/launch/gpu_lidar.launch | 2 +- .../launch/rgbd_camera.launch | 2 +- ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz | 47 ++- ros1_ign_point_cloud/examples/gpu_lidar.sdf | 303 ++++++++++++++++++ ...s1_ign_point_cloud.sdf => rgbd_camera.sdf} | 2 +- ros1_ign_point_cloud/src/point_cloud.cc | 158 ++++++++- ros1_ign_point_cloud/src/point_cloud.hh | 4 +- 7 files changed, 501 insertions(+), 17 deletions(-) create mode 100644 ros1_ign_point_cloud/examples/gpu_lidar.sdf rename ros1_ign_point_cloud/examples/{ros1_ign_point_cloud.sdf => rgbd_camera.sdf} (99%) diff --git a/ros1_ign_gazebo_demos/launch/gpu_lidar.launch b/ros1_ign_gazebo_demos/launch/gpu_lidar.launch index 0827bfa8..05bb6391 100644 --- a/ros1_ign_gazebo_demos/launch/gpu_lidar.launch +++ b/ros1_ign_gazebo_demos/launch/gpu_lidar.launch @@ -2,7 +2,7 @@ - + - + Value: Orbit (rviz) - Yaw: 3.6185994148254395 + Yaw: 3.633599042892456 Saved: ~ Window Geometry: Displays: @@ -146,5 +177,5 @@ Window Geometry: Views: collapsed: false Width: 701 - X: 492 - Y: 396 + X: 352 + Y: 269 diff --git a/ros1_ign_point_cloud/examples/gpu_lidar.sdf b/ros1_ign_point_cloud/examples/gpu_lidar.sdf new file mode 100644 index 00000000..1a8f514f --- /dev/null +++ b/ros1_ign_point_cloud/examples/gpu_lidar.sdf @@ -0,0 +1,303 @@ + + + + + + 0.001 + 1.0 + + + + + ogre2 + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + /world/ros1_ign/control + /world/ros1_ign/stats + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + /world/ros1_ign/stats + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 20 20 0.1 + + + + + + + 20 20 0.1 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 -1 0.5 0 0 0.7 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 3 0 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 0.2 + + + + + + + + 0.2 + + + + 1 1 0 1 + 1 1 0 1 + 1 1 0 1 + + + + + + + 5 0 0.5 0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + 0.1 + + 0.000166667 + 0.000166667 + 0.000166667 + + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + lidar + 10 + + + + 640 + 1 + -1.396263 + 1.396263 + + + 1 + 0.01 + 0 + 0 + + + + 0.08 + 10.0 + 0.01 + + + 1 + true + + custom_params + pc2 + custom_params/link + + + + + + + 0 1 3 0.0 0.0 1.57 + + https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Construction Cone + + + + + diff --git a/ros1_ign_point_cloud/examples/ros1_ign_point_cloud.sdf b/ros1_ign_point_cloud/examples/rgbd_camera.sdf similarity index 99% rename from ros1_ign_point_cloud/examples/ros1_ign_point_cloud.sdf rename to ros1_ign_point_cloud/examples/rgbd_camera.sdf index ad7dde98..5577f421 100644 --- a/ros1_ign_point_cloud/examples/ros1_ign_point_cloud.sdf +++ b/ros1_ign_point_cloud/examples/rgbd_camera.sdf @@ -16,7 +16,7 @@ 3. Load the example world, unpaused: - ign gazebo -r examples/ros1_ign_point_cloud.sdf + ign gazebo -r examples/rgbd_camera.sdf 4. Launch RViz to visualize the point cloud: diff --git a/ros1_ign_point_cloud/src/point_cloud.cc b/ros1_ign_point_cloud/src/point_cloud.cc index 35ab1b05..8a78936a 100644 --- a/ros1_ign_point_cloud/src/point_cloud.cc +++ b/ros1_ign_point_cloud/src/point_cloud.cc @@ -15,15 +15,17 @@ #include "point_cloud.hh" #include #include +#include +#include #include #include #include #include #include +#include #include #include #include -#include #include #include @@ -39,6 +41,18 @@ IGNITION_ADD_PLUGIN( using namespace ros1_ign_point_cloud; +/// \brief Types of sensors supported by this plugin +enum class SensorType { + /// \brief A camera which combines an RGB and a depth camera + RGBD_CAMERA, + + /// \brief Depth camera + DEPTH_CAMERA, + + /// \brief GPU lidar rays + GPU_LIDAR +}; + ////////////////////////////////////////////////// class ros1_ign_point_cloud::PointCloudPrivate { @@ -54,6 +68,18 @@ class ros1_ign_point_cloud::PointCloudPrivate unsigned int _channels, const std::string &_format); + /// \brief Callback when the GPU rays generate a new frame. + /// This is called in the rendering thread. + /// \param[in] _frame Scan data + /// \param[in] _width Image width in pixels + /// \param[in] _height Image height in pixels + /// \param[in] _channels Number of channels in image. + /// \param[in] _format Image format as string. + public: void OnNewGpuRaysFrame(const float *_frame, + unsigned int _width, unsigned int _height, + unsigned int _depth, + const std::string &_format); + /// \brief Get depth camera from rendering. /// \param[in] _ecm Immutable reference to ECM. public: void LoadDepthCamera(const ignition::gazebo::EntityComponentManager &_ecm); @@ -62,6 +88,10 @@ class ros1_ign_point_cloud::PointCloudPrivate /// \param[in] _ecm Immutable reference to ECM. public: void LoadRgbCamera(const ignition::gazebo::EntityComponentManager &_ecm); + /// \brief Get GPU rays from rendering. + /// \param[in] _ecm Immutable reference to ECM. + public: void LoadGpuRays(const ignition::gazebo::EntityComponentManager &_ecm); + /// \brief Rendering scene which manages the cameras. public: ignition::rendering::ScenePtr scene_; @@ -74,6 +104,9 @@ class ros1_ign_point_cloud::PointCloudPrivate /// \brief Rendering RGB camera public: std::shared_ptr rgb_camera_; + /// \brief Rendering GPU lidar + public: std::shared_ptr gpu_rays_; + /// \brief Keep latest image from RGB camera. public: ignition::rendering::Image rgb_image_; @@ -83,6 +116,9 @@ class ros1_ign_point_cloud::PointCloudPrivate /// \brief Connection to depth frame event. public: ignition::common::ConnectionPtr depth_connection_; + /// \brief Connection to GPU rays frame event. + public: ignition::common::ConnectionPtr gpu_rays_connection_; + /// \brief Node to publish ROS messages. public: std::unique_ptr rosnode_; @@ -100,6 +136,9 @@ class ros1_ign_point_cloud::PointCloudPrivate /// \brief Render scene name public: std::string scene_name_; + + /// \brief Type of sensor which this plugin is attached to. + public: SensorType type_; }; ////////////////////////////////////////////////// @@ -115,6 +154,25 @@ void PointCloud::Configure(const ignition::gazebo::Entity &_entity, { this->dataPtr->entity_ = _entity; + if (_ecm.Component(_entity) != nullptr) + { + this->dataPtr->type_ = SensorType::RGBD_CAMERA; + } + else if (_ecm.Component(_entity) != nullptr) + { + this->dataPtr->type_ = SensorType::DEPTH_CAMERA; + } + else if (_ecm.Component(_entity) != nullptr) + { + this->dataPtr->type_ = SensorType::GPU_LIDAR; + } + else + { + ROS_ERROR_NAMED("ros1_ign_point_cloud", + "Point cloud plugin must be attached to an RGBD camera, depth camera or GPU lidar."); + return; + } + // Initialize ROS if (!ros::isInitialized()) { @@ -161,15 +219,23 @@ void PointCloud::PostUpdate(const ignition::gazebo::UpdateInfo &_info, return; } - // Get rendering cameras - if (!this->dataPtr->depth_camera_) + // Get rendering objects + if (!this->dataPtr->depth_camera_ && + (this->dataPtr->type_ == SensorType::RGBD_CAMERA || + this->dataPtr->type_ == SensorType::DEPTH_CAMERA)) { this->dataPtr->LoadDepthCamera(_ecm); } - if (!this->dataPtr->rgb_camera_) + if (!this->dataPtr->rgb_camera_ && + this->dataPtr->type_ == SensorType::RGBD_CAMERA) { this->dataPtr->LoadRgbCamera(_ecm); } + if (!this->dataPtr->gpu_rays_ && + this->dataPtr->type_ == SensorType::GPU_LIDAR) + { + this->dataPtr->LoadGpuRays(_ecm); + } } ////////////////////////////////////////////////// @@ -230,6 +296,37 @@ void PointCloudPrivate::LoadRgbCamera( this->rgb_image_ = this->rgb_camera_->CreateImage(); } +////////////////////////////////////////////////// +void PointCloudPrivate::LoadGpuRays( + const ignition::gazebo::EntityComponentManager &_ecm) +{ + // Sensor name scoped from the model + auto sensor_name = + ignition::gazebo::scopedName(this->entity_, _ecm, "::", false); + sensor_name = sensor_name.substr(sensor_name.find("::") + 2); + + // Get sensor + auto sensor = this->scene_->SensorByName(sensor_name); + if (!sensor) + { + return; + } + + this->gpu_rays_ = + std::dynamic_pointer_cast(sensor); + if (!this->gpu_rays_) + { + ROS_ERROR_NAMED("ros1_ign_point_cloud", + "Rendering sensor named [%s] is not a depth camera", sensor_name.c_str()); + return; + } + + this->gpu_rays_connection_ = this->gpu_rays_->ConnectNewGpuRaysFrame( + std::bind(&PointCloudPrivate::OnNewGpuRaysFrame, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, + std::placeholders::_4, std::placeholders::_5)); +} + ////////////////////////////////////////////////// void PointCloudPrivate::OnNewDepthFrame(const float *_scan, unsigned int _width, unsigned int _height, @@ -357,3 +454,56 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, this->pc_pub_.publish(msg); } +////////////////////////////////////////////////// +void PointCloudPrivate::OnNewGpuRaysFrame(const float *_frame, + unsigned int _width, unsigned int _height, + unsigned int _depth, + const std::string &_format) +{ + if (this->pc_pub_.getNumSubscribers() <= 0 || _height == 0 || _width == 0) + return; + + if (_format != "PF_FLOAT32_RGB") + { + ROS_WARN_NAMED("ros1_ign_point_cloud", + "Expected depth image to have [FLOAT32] format, but it has [%s]", _format.c_str()); + } + + // Fill message + // Logic borrowed from + // https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_depth_camera.cpp + auto sec_nsec = ignition::math::durationToSecNsec(this->current_time_); + + sensor_msgs::PointCloud2 msg; + msg.header.frame_id = this->frame_id_; + msg.header.stamp.sec = sec_nsec.first; + msg.header.stamp.nsec = sec_nsec.second; + msg.width = _width; + msg.height = _height; + msg.row_step = msg.point_step * _width; + msg.is_dense = true; + + sensor_msgs::PointCloud2Modifier modifier(msg); + modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); + modifier.resize(_width*_height); + + sensor_msgs::PointCloud2Iterator iter_x(msg, "x"); + sensor_msgs::PointCloud2Iterator iter_y(msg, "y"); + sensor_msgs::PointCloud2Iterator iter_z(msg, "z"); + sensor_msgs::PointCloud2Iterator iter_rgb(msg, "rgb"); + + for (unsigned int i = 0; i < _width; ++i) + { + for (unsigned int j = 0; j < _height; ++j, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb) + { + unsigned int index = (j * _width) + i; + *iter_x = _frame[4 * index]; + *iter_y = _frame[4 * index + 1]; + *iter_z = _frame[4 * index + 2]; + *iter_rgb = _frame[4 * index + 3]; + } + } + + this->pc_pub_.publish(msg); +} + diff --git a/ros1_ign_point_cloud/src/point_cloud.hh b/ros1_ign_point_cloud/src/point_cloud.hh index c29073ef..4d1c711b 100644 --- a/ros1_ign_point_cloud/src/point_cloud.hh +++ b/ros1_ign_point_cloud/src/point_cloud.hh @@ -23,9 +23,9 @@ namespace ros1_ign_point_cloud // Forward declarations. class PointCloudPrivate; - /// \brief System which publishes ROS PointCloud2 messages for RGBD sensors. + /// \brief System which publishes ROS PointCloud2 messages for RGBD or GPU lidar sensors. /// - /// This plugin should be attached to an RGBD sensor (i.e. ) + /// This plugin should be attached to an RGBD or GPU lidar sensor (i.e. ) /// /// Important: load `ignition::gazebo::systems::Sensors` as well, which will create the sensor. /// From 2ecd6a2677656e8724da62483307005230f307d7 Mon Sep 17 00:00:00 2001 From: chapulina Date: Mon, 24 Jun 2019 13:14:11 -0700 Subject: [PATCH 2/4] PC2 for gpu_lidar, 1 vertical sample --- ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz | 18 +- ros1_ign_point_cloud/src/point_cloud.cc | 197 ++++++++++------------ 2 files changed, 99 insertions(+), 116 deletions(-) diff --git a/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz b/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz index 8141374b..73425318 100644 --- a/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz +++ b/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz @@ -93,7 +93,7 @@ Visualization Manager: Channel Name: intensity Class: rviz/PointCloud2 Color: 255; 255; 255 - Color Transformer: "" + Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false @@ -102,11 +102,11 @@ Visualization Manager: Min Color: 0; 0; 0 Min Intensity: 0 Name: PointCloud2 - Position Transformer: "" + Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 - Size (m): 0.009999999776482582 + Size (m): 0.029999999329447746 Style: Flat Squares Topic: /custom_params/pc2 Unreliable: false @@ -141,25 +141,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 12.205142974853516 + Distance: 4.168473243713379 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 1.7377599477767944 - Y: -0.8083325624465942 - Z: 0.38970595598220825 + X: 1.9921716451644897 + Y: -0.8546587228775024 + Z: 0.7135224342346191 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5552024245262146 + Pitch: 0.5852028727531433 Target Frame: Value: Orbit (rviz) - Yaw: 3.633599042892456 + Yaw: 3.5535941123962402 Saved: ~ Window Geometry: Displays: diff --git a/ros1_ign_point_cloud/src/point_cloud.cc b/ros1_ign_point_cloud/src/point_cloud.cc index 8a78936a..15a5669d 100644 --- a/ros1_ign_point_cloud/src/point_cloud.cc +++ b/ros1_ign_point_cloud/src/point_cloud.cc @@ -45,7 +45,7 @@ using namespace ros1_ign_point_cloud; enum class SensorType { /// \brief A camera which combines an RGB and a depth camera RGBD_CAMERA, - + /// \brief Depth camera DEPTH_CAMERA, @@ -68,18 +68,6 @@ class ros1_ign_point_cloud::PointCloudPrivate unsigned int _channels, const std::string &_format); - /// \brief Callback when the GPU rays generate a new frame. - /// This is called in the rendering thread. - /// \param[in] _frame Scan data - /// \param[in] _width Image width in pixels - /// \param[in] _height Image height in pixels - /// \param[in] _channels Number of channels in image. - /// \param[in] _format Image format as string. - public: void OnNewGpuRaysFrame(const float *_frame, - unsigned int _width, unsigned int _height, - unsigned int _depth, - const std::string &_format); - /// \brief Get depth camera from rendering. /// \param[in] _ecm Immutable reference to ECM. public: void LoadDepthCamera(const ignition::gazebo::EntityComponentManager &_ecm); @@ -322,7 +310,7 @@ void PointCloudPrivate::LoadGpuRays( } this->gpu_rays_connection_ = this->gpu_rays_->ConnectNewGpuRaysFrame( - std::bind(&PointCloudPrivate::OnNewGpuRaysFrame, this, + std::bind(&PointCloudPrivate::OnNewDepthFrame, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5)); } @@ -336,17 +324,28 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, if (this->pc_pub_.getNumSubscribers() <= 0 || _height == 0 || _width == 0) return; - // Just sanity checks, but don't prevent publishing - if (_channels != 1) + // Just sanity check, but don't prevent publishing + if (this->type_ == SensorType::RGBD_CAMERA && _channels != 1) { ROS_WARN_NAMED("ros1_ign_point_cloud", "Expected depth image to have 1 channel, but it has [%i]", _channels); } - if (_format != "FLOAT32") + if (this->type_ == SensorType::GPU_LIDAR && _channels != 3) + { + ROS_WARN_NAMED("ros1_ign_point_cloud", + "Expected GPU rays to have 3 channels, but it has [%i]", _channels); + } + if ((this->type_ == SensorType::RGBD_CAMERA || + this->type_ == SensorType::DEPTH_CAMERA) && _format != "FLOAT32") { ROS_WARN_NAMED("ros1_ign_point_cloud", "Expected depth image to have [FLOAT32] format, but it has [%s]", _format.c_str()); } + if (this->type_ == SensorType::GPU_LIDAR && _format != "PF_FLOAT32_RGB") + { + ROS_WARN_NAMED("ros1_ign_point_cloud", + "Expected GPU rays to have [PF_FLOAT32_RGB] format, but it has [%s]", _format.c_str()); + } // Fill message // Logic borrowed from @@ -380,59 +379,94 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, _width, 3 * _width, this->rgb_image_.Data()); } - double hfov = this->depth_camera_->HFOV().Radian(); - double fl = _width / (2.0 * tan(hfov / 2.0)); - int index{0}; - uint8_t * image_src = (uint8_t *)(&(this->rgb_image_msg_.data[0])); + // For depth calculation from image + double fl{0.0}; + if (nullptr != this->depth_camera_) + { + auto hfov = this->depth_camera_->HFOV().Radian(); + fl = _width / (2.0 * tan(hfov / 2.0)); + } - // Convert depth to point cloud + // For depth calculation from laser scan + double angle_step{0.0}; + double vertical_angle_step{0.0}; + double inclination{0.0}; + double azimuth{0.0}; + if (nullptr != this->gpu_rays_) + { + angle_step = (this->gpu_rays_->AngleMax() - this->gpu_rays_->AngleMin()).Radian() / + (this->gpu_rays_->RangeCount()-1); + vertical_angle_step = (this->gpu_rays_->VerticalAngleMax() - + this->gpu_rays_->VerticalAngleMin()).Radian() / (this->gpu_rays_->VerticalRangeCount()-1); + + // Angles of ray currently processing, azimuth is horizontal, inclination is vertical + inclination = this->gpu_rays_->VerticalAngleMin().Radian(); + azimuth = this->gpu_rays_->AngleMin().Radian(); + } + + // For color calculation + uint8_t * image_src; + if (nullptr != this->rgb_camera_) + { + image_src = (uint8_t *)(&(this->rgb_image_msg_.data[0])); + } + + // Iterate over scan and populate point cloud for (uint32_t j = 0; j < _height; ++j) { - double p_angle; - if (_height>1) - p_angle = atan2( (double)j - 0.5*(double)(_height-1), fl); - else - p_angle = 0.0; + double p_angle{0.0}; + if (fl > 0 && _height > 1) + p_angle = atan2((double)j - 0.5 * (double)(_height-1), fl); - for (uint32_t i=0; i<_width; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b) + for (uint32_t i = 0; i < _width; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b) { - double y_angle; - if (_width>1) - y_angle = atan2( (double)i - 0.5*(double)(_width-1), fl); - else - y_angle = 0.0; + // Index of current point + auto index = j * _width * _channels + i * _channels; - double depth = _scan[index++]; + double y_angle{0.0}; + if (fl > 0 && _width > 1) + y_angle = atan2((double)i - 0.5 * (double)(_width-1), fl); - // in optical frame - // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in - // to urdf, where the *_optical_frame should have above relative - // rotation from the physical camera *_frame - *iter_x = depth * tan(y_angle); - *iter_y = depth * tan(p_angle); - if (depth > this->depth_camera_->FarClipPlane()) - { - *iter_z = ignition::math::INF_D; - msg.is_dense = false; - } - if (depth < this->depth_camera_->NearClipPlane()) + double depth = _scan[index]; + + if (nullptr != this->depth_camera_) { - *iter_z = -ignition::math::INF_D; - msg.is_dense = false; + // in optical frame + // hardcoded rotation rpy(-M_PI/2, 0, -M_PI/2) is built-in + // to urdf, where the *_optical_frame should have above relative + // rotation from the physical camera *_frame + *iter_x = depth * tan(y_angle); + *iter_y = depth * tan(p_angle); + *iter_z = depth; + + // Clamp according to REP 117 + if (depth > this->depth_camera_->FarClipPlane()) + { + *iter_z = ignition::math::INF_D; + msg.is_dense = false; + } + if (depth < this->depth_camera_->NearClipPlane()) + { + *iter_z = -ignition::math::INF_D; + msg.is_dense = false; + } } - else + else if (nullptr != this->gpu_rays_) { - *iter_z = depth; + // Convert spherical coordinates to Cartesian for pointcloud + // See https://en.wikipedia.org/wiki/Spherical_coordinate_system + *iter_x = depth * cos(inclination) * cos(azimuth); + *iter_y = depth * cos(inclination) * sin(azimuth); + *iter_z = depth * sin(inclination); } // Put image color data for each point - // \TODO(anyone) RGB image seems offset from depth image by 3~4 pixels in both directions if (this->rgb_image_msg_.data.size() == _height * _width * 3) { // color - *iter_r = image_src[i*3+j*_width*3+0]; - *iter_g = image_src[i*3+j*_width*3+1]; - *iter_b = image_src[i*3+j*_width*3+2]; + *iter_r = image_src[index+0]; + *iter_g = image_src[index+1]; + *iter_b = image_src[index+2]; } else if (this->rgb_image_msg_.data.size() == _height*_width) { @@ -448,60 +482,9 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, *iter_g = 0; *iter_b = 0; } + azimuth += angle_step; } - } - - this->pc_pub_.publish(msg); -} - -////////////////////////////////////////////////// -void PointCloudPrivate::OnNewGpuRaysFrame(const float *_frame, - unsigned int _width, unsigned int _height, - unsigned int _depth, - const std::string &_format) -{ - if (this->pc_pub_.getNumSubscribers() <= 0 || _height == 0 || _width == 0) - return; - - if (_format != "PF_FLOAT32_RGB") - { - ROS_WARN_NAMED("ros1_ign_point_cloud", - "Expected depth image to have [FLOAT32] format, but it has [%s]", _format.c_str()); - } - - // Fill message - // Logic borrowed from - // https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_depth_camera.cpp - auto sec_nsec = ignition::math::durationToSecNsec(this->current_time_); - - sensor_msgs::PointCloud2 msg; - msg.header.frame_id = this->frame_id_; - msg.header.stamp.sec = sec_nsec.first; - msg.header.stamp.nsec = sec_nsec.second; - msg.width = _width; - msg.height = _height; - msg.row_step = msg.point_step * _width; - msg.is_dense = true; - - sensor_msgs::PointCloud2Modifier modifier(msg); - modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); - modifier.resize(_width*_height); - - sensor_msgs::PointCloud2Iterator iter_x(msg, "x"); - sensor_msgs::PointCloud2Iterator iter_y(msg, "y"); - sensor_msgs::PointCloud2Iterator iter_z(msg, "z"); - sensor_msgs::PointCloud2Iterator iter_rgb(msg, "rgb"); - - for (unsigned int i = 0; i < _width; ++i) - { - for (unsigned int j = 0; j < _height; ++j, ++iter_x, ++iter_y, ++iter_z, ++iter_rgb) - { - unsigned int index = (j * _width) + i; - *iter_x = _frame[4 * index]; - *iter_y = _frame[4 * index + 1]; - *iter_z = _frame[4 * index + 2]; - *iter_rgb = _frame[4 * index + 3]; - } + inclination += vertical_angle_step; } this->pc_pub_.publish(msg); From e318ee4c1b685f90ec3a736433f019c81423be13 Mon Sep 17 00:00:00 2001 From: chapulina Date: Mon, 24 Jun 2019 14:58:08 -0700 Subject: [PATCH 3/4] final tweaks --- ros1_ign_gazebo_demos/README.md | 4 +- .../images/depth_camera_demo.png | Bin 52319 -> 105009 bytes .../images/gpu_lidar_demo.png | Bin 151250 -> 71314 bytes .../launch/depth_camera.launch | 8 +- ros1_ign_gazebo_demos/rviz/depth_camera.rviz | 147 ++++++++ ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz | 12 +- .../examples/depth_camera.sdf | 316 ++++++++++++++++++ ros1_ign_point_cloud/examples/gpu_lidar.sdf | 14 +- ros1_ign_point_cloud/src/point_cloud.cc | 19 +- 9 files changed, 496 insertions(+), 24 deletions(-) create mode 100644 ros1_ign_gazebo_demos/rviz/depth_camera.rviz create mode 100644 ros1_ign_point_cloud/examples/depth_camera.sdf diff --git a/ros1_ign_gazebo_demos/README.md b/ros1_ign_gazebo_demos/README.md index 2bab3a58..1fcfeda3 100644 --- a/ros1_ign_gazebo_demos/README.md +++ b/ros1_ign_gazebo_demos/README.md @@ -32,7 +32,7 @@ Publishes RGB camera image and info. ## Depth camera -Publishes depth camera image. +Publishes depth camera images and point clouds. roslaunch ros1_ign_gazebo_demos depth_camera.launch @@ -40,7 +40,7 @@ Publishes depth camera image. ## GPU lidar -Publishes 2D laser scans. +Publishes 2D laser scans and point clouds. roslaunch ros1_ign_gazebo_demos gpu_lidar.launch diff --git a/ros1_ign_gazebo_demos/images/depth_camera_demo.png b/ros1_ign_gazebo_demos/images/depth_camera_demo.png index bf6c726b2d4f395bc3c29ee740c255fde924b86f..9b4d27d3183a3141400c7f2cba7f4dd37c85c157 100644 GIT binary patch literal 105009 zcmX`Sb9@}{_dYza)iib+8;#kZvF$Xr?KW!Aq;X?gjk#fC+qRvJ^K9Rr@9&v^_O&y! zd*5@;b#$FG;YtdUXvl=f005v#ONpxh0Bj)uK%XH(L(UKtg-1X>U|d9{)esR8mp2tR zAYTbwCA3^s9n4)lzB-!$7WNKyW=t+7&SqxzE|w0i=P(^Y06-2%i+@)0Og~xm@Wkm| z0xmqvmk((`*eZu0yb|OO8liBG_^r zPz%9AR-VL)qf{29t60MTqS&&=4K*~N0OEcq*cbqytr4Xa?-xI$44;{BX6tJ+aImuC z1t!@;t$$-#N1&LSq7s_hV$&4K{P}5I0j5Q-S)^_+m z)jjXoQdH{BE97Jmn4l;3o4aT%W^lDmA6|Ka{1e%}?E_M(7Q74uSpW7pL1z-hR$N{K zgLxVW6h~n}J6*EH(M}#6L}E@D^NZ49!LC`dH>ET8m2L~38cL`mefyj5Sb`RkcE!CQDwAvam_o1zX<9HKKP$iWklo{2cj$gcN4->9L?N)KkK3 zCgwYYXZGFY26nsS6Adl1-2Uym2ear0PXp6a4M(&-o*0&m>xUPpUV5eGy|LJ?0~cOj zs1%EcEP~e|;fbX6bf$g|ji*{ipEmc_Gw-dx)b{&7&YPz zXgIxb8~bf)Tc@U`r&LtCySu5RZyui2)z$lJYHMqwwZ}#JYJa+T`9+*y%sU~!&6iXB z6Nl1A{IatzD61v3&bGFwlDvJt@3=ig@lApO*6u(o(ZK!tgM)$YZWZNxAe%%3hgXOq zGmjYfliD%I(I*=8DRbY%I2RdNrY=h7oq8qs&7hHn5z3A^z9 z)@1C)@LJR7+eiKM_L9HI+u@ecwa!4&y;KR$ydsa~n^fWMm~n_Y^`o!#<3MB!ewT;w za9ys$t4FMsE3MwfvWcYLv{b+ulyd0mLhxl@aGrM{P8rr?of^O zCqlP4E$oe1c<JOwJ{6Sg#>}8gGtZ<<=FAflgAlO9O~J30d7b0 zqH%1Ecb*-&#SzFNu$d`vYl>dL*sdn|#%!Fj4C4n?9ugR%P9Nxc^$)>6(yf2F zLXo5LIEbjfkTNBIHic%PlXtyh?Q8WjC>((9kKzNNZX}>>lmQn`xhz^=yTh$biV{D& z`UuLYQyR=l!?SPxPzK}GR6EDpGylgDeSa{SLJ6c@1w4!Gij1sd9?{~sIC*PF6KAkw63t~v-fxK zvR}8)hOLrj8PLFkecFWJU03c=Qc7D^E4`ba{j)k%qWMcFb7}k5VmS?om|=mZY9ILU*U{_weIDN^8>?H04k?1i`11CMHx&B=Jw z&RicJ9Agxtb(yU z2`Y|ZTRYXnhL1YKlb)HDv81QkpZevLPt=FHZL9ik`W&lll%W zTrM^oMMKc-MCLn#tsf`h3enks(Kv%61O2R7oyk+NoaM_XQj3P0>$T2!d(Wm0tH9_+ zb&1T!%gnxkOT|0cHV2ai%B!wM=Tr3g5WHxl`x-Z9S?bSXdgDj}q!dA;wRXGaqJZ zT1qK>+ZWJ4X~OYisF$Wc*ahfR`@-|h3+5AJ?fQip3=mjK8@w$J;^YzyK3OV6y!S1(L?JDrOLx;ENTi_D4cT}>r z$xthIv#q7R&ZhIPVtfZc=eau^Y@V`3R8&Lfw+}vn!5&B4pVTorpW6e;Q?}TjQkq9~ zYw3%%0z4@xkhgDkAGm&?=50EC(b-D`eMQoMCQruE2oV_5gblt>cp=Jkf5GyQ_y*I> z)JCNj=)6d5Mgcqyux|dw9#Mt|E^w1QsfK3HQ>@tF6WA+P)5`R|CY^{H8rM+%rA`5> zdw(nXUSa|ZWrV{^^9`&6QyQI^^7{;htc2f6+S-$r zeTfX3oFkm>C%;1p(l%9ZnX7JF@W@hsE48X3E1vLvU+#D=`j806Q`x^`^=#vx{G{Uq%!>*P&0h?yo;!ryFS{b<3Na?HicudxSrad_h^`ddgu z0#N!^%MUUr63k}JPM__R)IxP88f^^v=Qw6$P_ysOXX%Thto$sy9=P2228|n*N=v&x zmh)vWyDH#D=XIS#L5)uv4d9)mqM+@lsH)bX$#@mV$D*J;5cc_Z3FZ*!iqI|9nA@a? z(n=QG=aj$$=KO7LCP_cFTMc*^OYAWMSuBnpLF)99U8UG<<+0HT)I;hK4dshER!2h4 zN~xs2G!3uq^Is47PQI&UVB+-D4ml#(B5*xBkX^*lMr^Kzy2fnxY{}&hU@z7Op^GrB zf}C73CFO`ewKu9WgdlIOs@wu=CTU!!WeL3pq$covMEtG^(L5sRg17vSzeTLF%d_8g zcR&0PN1>}d#{S3)6fllc2NiH-;LjddF-hL3CE)OP8MBKABN2xq;Q@eLH7>K^Pj;BV zs`7~f6=h4W`7fuAn@8ha9YCFpOUZXr;mmUx1rBHB66NRUcQFe&vanD}Lp3tb!5pGe z1M}{uJ&-|TYn?p{5e z5oF++>;OBZ=^4U|dQC@7+`qWCBR#xPa`xjq#yd{4N_$fsQ1T63Potz^IJ$XyGh0uS zd$XP$r7V!(vy8Kr_gSJMCfMe~D})1Xy2eQ}jtcweb;->}W;v+Qj^0xgM?aHvusq$g z3VN5Vg(;K$i%hT3);!%5=C@mRucTOj!^6;Ro9kG*EtYfD}fl?I)jrnWw6+ zw*Gf=&v8WeNNM^e0gpG6T{1;gepcDw9b(Can5+5vn$;%7cvboUmUYx8D4>kb-~?OT zMv6(x&F*tDm#dtPV}}td;szXCwm%Pj;5_!lj@q9KL<;II%D7;BQW56Sl3!wJiCkVf zDw_-}ju!6hzl|%tP{7m?zRa45T&thYRWA;uuQeN@Nd2a`cB3E z3@-kXSD6x(n3#B5Gf*?dYQmxB*H{vS1}N1$pMnGE5HY4DWxfw5wc6FvbkmkZv8l)Q z7F!NFR3Rg3$Z8D*9>zpSfZIXChRRyXW*-2xh(AYAfNihBm#b5mq1hN=ZZ>!kCpF%m zUrFE%Z;fhr9M-OU;Wu@1RMdjEG(|p9W3+6gAilw{RF>u&_m`3S_#2}Ff!)QtPMtHY zt<>#r2R{6sWzD<7`2Vua9FAZ%jh7`Hm@oJ+xEBaK`nSv8{)X9YZ367{Dpk`+xmr3J zSlA>?(jQDj5U;&nbmk!`#aI81^67AiaQrDZPoDoj@C<2qFx86qmNh^zOSpwbMiiz$n`f0E|9;s14BJK{#vc;Vlr-SDCLn zNG*|;9+f6AaXV7e*9{m97nQuIrBFBhKVqygG?UHs$))oh~=)(XrI01%pv4Z0*gT zaM}f{kCHA}gCxdfe5pWZV*EC1M0$mP#ZtZ>p&bPj zgGJC=C~5fl$wsr6sTuNqYJ3-5=kY2&T8=Z7VXDNsB?936E(FaV1xcos~~PI9k^Dq>ftwG1#W!7 zu>ANKVevR|IxVq4_01$NiaK?^oZnWW4c|Mep29kpXsGjsgoP>%ZvZdS?|AARZZNPW&xTeSwB7`33`WsTzPnaxugIJgkI#ewG&d(r z9?)4+rpiq4d-Zp}TXG=D%6>}P_r3{D9SDVTQRg9FLjHchFv_QMXd(g&O7VsheV(|N zVk0Snmx;lH&5g^yXLbTMcwTVx)U|dL6gmG=Mr6O=!`r2&8zk9^ z1IU$6`tpRkON-AWWm?J@g}0NF|VJ3i3g6%gF|sT-7^XupIrtTx|0 zEq%)K0Uf29OTO%i_bT~ZNTg4(EU`7_ToWWzyL4j1Okc+48MdWH>%*0d*VLfCx6ydq0rB+rY zKj-479tm_6D1~BL@3ka!st|=L$A5$iz8?xp5B5T)pIwk5Tr>Ggm4PEu)=>34EnFZFSCq>QjFQip#4ouPC9VbQxLmQNIj4qw` za_VLY?;MF&{&37I6i*z8Q6d;%Y)9{U$4%8aS<^UYuuD-RdX-bZZWSt&;XNB@I%V?L z$3uyf43u5*Ca?#D!D4k9ChVKBQ`r6apodcD=c0TuC_Xe)Q{*~rU~{ui!o+qpGMi1Z zT z(aBI+ohx|`BSq_bX-w=Qr*CyoDG{JTLDuG4*xuvzM<)yQ`vD@B;|c`eqJ&Rfs^j`q zIkq#}@1+m#Nslic%M?BV;-mYsI_w9~&~p-HWo+h$0N~Vvibjn^8abzIWd_x?N;(|d z=fl5Zg(VOUPj4PtSd@-}s<%Lzs*qEQr9be@Qmzduy}?8w+)Af_lC(*TQ{{IQe` zncLCGvNR%9!p`0v9EWu)-R{*j%Jj4QL zFsQUjU^ZV!6G^w5 zA*OMmPK`YDJQ@~G&01tp1{{fnHK?wQKf;8M%RHs`je506sBaU%C}Ym4)A<<_&>{n_ ztZ92_XTOeylJ)PHzYMo^l{l$4kDS8-8-sjA7tmENWE9Av%1+X$IVP$oOt4PGntFOu za(%*YE7~lPjKgRgTtPf{&rO=`tq5fNZeu4AZ@$%c#hOXq!EHl7sD!>i2X@P^`*v_; zQBoNgkX$ADpqZR^m}QgtwhH^Zc~$`pscIm{mtG{U z#8fez44efR>1~?3L?GK!F_UFu)d%{~VroP-w14caV1Q?%^cyZfyPmaeenJ@^{SO0( z^)P*bC2|FvJyZlAg9mETlXZXn!l#jrE2UlHJJC_s!C!3x8F>7drA54+zP zk|;+|@-)0Xmmy<*98wqqP(2;76+CR`=gLXgVK%z0X(Zlv%75dpvzvxeKQ;+u9aP%A z24Ige=Kdx_laUD24ls1tNqi;Z&N)x zhKS%C@4wkSUTWfyt0V}ffBT-ckJcsA!W*POiKaNr17k8W@I>t8(=qOjoSut!i>&JL z@_3vjlIs=`dGLOA1I(#XmkFb2GX6@v1}AzyS>HkORc?GR-Eu?QhZ}Djb%~e9kz?%7 z^}L}6poEMY3xB!51>I))XMfP#}d0C4y7&G&gdK!eSu@1}X&kQffgX5BypJl~$rdmLVJ@PFRgg#Jr8X3o^qM@JdR zgRQ@5W5SSkGU7(|8c!bH3XGSO9$h~WbA_#LW+$k~)IrI?lHX(qCPJ~!TGxk$XuEj} zjypw^dJEX=7RdWx$4vDVt^rB}CZ&Y9xVR&<3=v7yL*_QWFYCPCqgebP;AfQnK4jNn zpUjI$(o@1}BC_d?aZIWn0F)e!yt)J!B#sd2tiuf8pQHWC@9KF9W}_l6Ya_=55O*Aw z9dn1a_Xr6j7KLzZ)LbO?Nx?MvU(z?}GrqWFZ7`@mPb9YjOwb zk5A~B`61B|y$_@@A{&R#C$1d#x4ir$YQ$B>GEbR|Lfp(+L!&|AUFwjQfyUZZlzeQl z>Lsby_2xrfp#rIJldN?xERfwK>r&frR!;z1JYeuTMYB>)2gAOl!q*QqP#M?u5uvnm zg}b38dEV$}F)1H$0nCqCgggKHt?LI(1O9fyB3kK|>EOuOr^6Uj4~7)v_0ea=TOEpF4Pgn?XG> zMg4wB1O(y&OC-##Any@Eir{ymJTi2e95$k?Vy7+M37F(F<{oP5i=}wp5OrRIU^%!# z-$4^s)GRVEl;M{N`N*<2a6(5N{Z#3}(k_*%=UiGQ-+_T9R@CEaoV3M+MOVwp`@nMS zXkUNiV|D9LLRrErEHTa#5JHE7qig$;);~){u!m-o$9NVh z5tTjtj%y9&a0|u#VK&&ZOR_fg=NFBQG8i$T;8$eAv0!P~OuYLq1_T0& zX_lv1|F>?bo{>eieU8~OZKQuDnvKTN%J`HNF0I+_uSN6rD^f@Svf1x0BLoef-HjfD+x_@xZjRn#0Ie8!X99W`4;TSs`0J;I z(t-zzP1V)^C;YbStz$AQ8Mf?y>XT1=VZhR>m>CvN-ls%eA%kFr-3uFQ@LBm@K* zh*UL<-0@M{578v5F{Fa10KG}=-W$F-CzH?1-p^L&_Ghnoj`J5}V0Fs44{h-IY&0#) zAH1)99q_y{D7z$l1VQ|NvTuw3H5Y^@uDs*weRLOriU>0ls1mJ;zu0Ey!@5((;U_zq ziR<2#kuz{{+`H}z@*Iq-!mEEs!J1mIl#epq6r`%w2k!y4oN0!nx< z$wE?*Xgu|$bR)vhejLETS3&AJ_n!2>16A9Z?atK+tlzst|@N!{Sxkr z|HUGIpWww3IL)1G`~;t~%|qsMiGCG!C8!DfGH>_?taXU;rZ4!Gi3Cv}dC{L{FpRDV zI1{9)@1n0F^F>9bPkp-Ze7VDLIfmjtx^TivlIF4`oRPY`RaxdZ)~Y_$E6?B)fq1-f z9e)0iI2!s=cl-aF1;}kx{Q(xmbr%+#u57;=7xo|>9z#FVZn5<;|6)E)y2>#%O|2); z&PgMAkf0}YTO;-at~9JY>cz`k?|AFP(NwHmJk3GUupLNct6qN;u6b&b1?~?mP!Lc_*8(msaD<jtND zwGLTOL3sYvw0!MB!@JOdQ#DtMjjM~zx>aj02rt_i;A0#-A|ih8nE{p#9paVRgX7+L zeIGQy7j&OiR@tnu+-w8Rl%+OIiktLW7+@>YsDcW7e*T`HfNCeT7K9<3I#*JLTe8Nv z-yYC*ZLrKq!54!m$`g%(f6s5Ej#&DKxL&-b}L$p$|5&zyyJc^(a^Yijb+wa|lcMm$eQ_)v zqvs*c|8t81lt{jbqjmdIubbOXF}ta5aYhp;Lb~6SSyFF}dv0`Q>b`Cl=7_;Ntk!LI zqx7%2@2~RqE0!C!UM0e@2wd(=`v(93`_!}sT0%DciV@}Rc_jm7r{39V`wTbPxty1(x0l4l#&vBqwS?clF>wf*UFPk9h5LT<$VKOkjnBYB z(`C$NPiTW3NAC46gDN6H>zO&bWib!Z!LpMStj1%<9CF88TB$g4Y07kU<27p9Jh`Hxn|5DhYRK9xr zFhpyVcxWu>NsTHa3gT%=z=@&5szXRq^?e%*4a^ z!z{EwAYHOTba?b0&smF=rY>Vrk7P7-=hb;f7U%We-@mXR1Mmb4*s6%n_2A-6&}U!p zsZOCtR!*+TZf<0Ey{cIAEMJy-;iN%6z!p9bf;0j1o8sTUe^0>5CNrN;x6b1vEAH~x z4{UtS`x14(+qe#8bpI!Zh|8Y7s`%pRSyPYAttV9e;Q?+J2M6SHYkM3jzMuE|H+~u@ z7JNxd1w9@K&4S!UiL5wAOn0?XBzz|1nLCw@hvqHK5 z+B~j#)xK(;hzOgcg@c)E&b*c(;yZ`?e-&ni2ebh~Je)eFTIRlI=C-E{FR;*IQvU%V zbqEIsr@-#Ol`noUf1ao=#v8PD>dw)Z#QgLc6eC2>Ot;BXnV+BEmJ1C;L`Gs`W7j1h zaS}CqdDRd%8O>;&=B<+*EY-_`wkV}ro@?j~{p&p!CMXP9UiVUp_UB}Or6o7|^=Acz z8f5#qHm`!bZ(##Bd%~FY@AP%7k0vOBSn#<{rpIx0D(1R^;GKy*Qcpvae#FJavD##~ z&2q$dgNd1r=Bb=|&al6ChC@4W9y=r3(L|iucSw7mw-Gg$lu z0Na%&tiMP7i>fJ=AsGXsK3gS4$;=O>l3@GbUtd4=Sw5H;8$+m;I#W1KqVRAe>UgW| zme~XqOYhCw<4Vw8snxup(}NjKVj?z;p5D2ov2phgl+b{?%dp!!3^J~pYMM+Ld3gdM z--BOWFz3zZ{*k@TP|-)?c3sD}l?Juuk8blJXT%en_Vb(HQ4q{**Rsa1)5$M_r{sOE zA;}nz!h5f8`@GS2Ls5$!<;4y~zY7)CCJNokbmO8h*{yee6byHyeR2|Y+~;0rCgC)O z-S}TAk#mjNj}m+(Qd}-7@|BpSP~xFZOnL9<6B8=<`?M!t20BO~IWq|vV9=~US7`8B zEJ*ghpQM36k~9W<%e_A5?tZw!`%&;EWk1t{FQc@SRLIwK`HlolQOI(m^Y_7l51Hpd zM2RY8$!imbsWlrMSDW8+ls;+H$&@@kRu|(;P>0r5$7@F zH0}Q%kd6|P@X4?<-{U2wzE6vdTcG1)6R7s^G(Nw`7uqCw6pfrWL6o1Zu$eEbYB7GM ziZ2>(vg+xRUu|`pzBBaNof$6F}Seg$n+Kh#Cl=EqNUDPUe0{Z z9jsTD>ZdEmMn_xSmpIWddc`FJYVU^?@%$%CbjQyGpW5&GbR$YF!$L8LtgCQywOT2smICw@(}RG^^(g>cRBYcQ6G{i*ixnSdJ1v7PiTa5 zkjSdv>i%-^QZtsp4+S{!5L@I*{d1%gGofof;8pOtA0BYlbX>`Q-cpumam;B7U9i-t zAcIJ?)G^VxtUPkCsdOYsSV zxalbM5aI4@rWA{Ke9_U!LRCx<%Njwq(QbU;K%7?Dv^m9;c$_1VM9|xFBk=WqStlO0 z(0Q~|Yjn~HpN@*s9z@RygUX<(ys52fn3U|&X~;qjp%rqUZF z6H{Xy?|w_{b^D)(uiF(*YpW@&r@LP9#>-`L|J62{-rxhQm9=^g2Zr&x!=fxmb}kL+ ztmo2R39!s;@I>!>fehXTEyy^rudKe27Tn}hWR(xtKu9ru^Qhs|mg_U0?d@%Yr{!TC zPSzc<0C`DtGAHj9I+AHxDnNcULQY*G7f`;~QGDhMU5k`*$R z^BMaV)(!k##(d6j;GAZPu@uMsa^)2wCsN`U>8>v}KT5`s+WTk9mCZs(o5EfnKm;kp z%c`mxhOctrSH02b+D9)OV1k#oM$vraDMrsVw9lpCZ?ljI4a1AuS)Gs2I4+;Q^P4KS z{81Ke35>(+B}oVK>wS=efj6DYPTca86PLk%^1l9up^eV5xh%V#3l#CszbKX8Qz^gq zG{A(--2dmtGWTtuy9#SK`gGP%XfC>0ge!rQCb9hlg$#B@789Aa+sv}ZdOI_nlICCM zRl3HSkq%*~$J4K`_xX=HyhaiN$7xiRX)@RTD5~Fi z!=&e9H&NG?)r`})#6>&!S`!!EgZ!zbRIvO1n;s=}ve0eo#+z|;Pr@CW&n@WLK+AC% z;9VWwUw*npuo*%P+7sku0=?#g0OP6NM#@>=3u5idGyW|94tK-q;e8a=$vA<7C7M0q zPwhcmC$)};=>!4GdzBvWgo2v|A>+|?0C0chAF!VSmt{9njew6;Zk6ZY&6I_rmjM5EK1Xq>I{wGz!Y zBz1t#hPe$i?=Itt!nD78$!H3^I4Xw`W%^fT71(a$IlO@DQ@FkGnEh?DkpK~)y9W|Y zq57d@r^5^sY7abT4gagPWJNuf?E7mL(gPdY&Ca=)3svhczjx1kP@GGvWyo(Aj3iAS$|{YQIHm{7~@ z($DC##(?{KDGp%R@NUb-X5j~3$IC(JCsM%ZM#97=l{xL9_t?;o+tU4u8ob1p@4v=)7j_|T|8zl>mP7{(KFS@cM$1=-(Fvq z8H8GMKDOKc<7;yE>Q6tQ<>;{IV?Tj0`8+uB7*iBwTh&RPqv?}n&~QzpR*u%6`evYl zATw)_WO0H*EOhjK!}8WU9Wo@%x~Qt1ke1~t7W^uXi_GG86QIN?zA3_E*gKQe{G~c2rgB8=9hnwzG;diH*(|DQ3 zs=ORka53$5rWPfVC8QmL zYKaoO8A5=no&Wq9_}t%7Svm#*uiaMyp~9){AxxpE*rg{@^QTXWQ#7FvqR0Q=UTe^!OpK9iYu2#cYn&(yv{R)x_FdgVc0qHf42BK_wXA3 z9WnaVkH|8U0+(>{K`}*B1D{nwLrn=s0&R5UP>xUG7XJOSM8v-h#ak^)5CZG#Vh3$b z5TV63ea>sapFe-vEb8H2U#wk*0vha?D2L>2uFP>f$!h-UMcX?!_9L?NC!|!5e za)U)iJH&OHa?apIMxD`b*I>#$>XexR+*sM^hpf4Z3JSQqZw{(W(8Frm%F9D6_*)C= zq|GLp3rOrIU3hn3gsz8{seOIt8_xw_UMDd2Z^{~1piovRVQKMd-ep>hbIZE7Sckd7 zM>Ba}RD#iIRw2EHv6Ip=U77w^Ja@0_dNSdcm$A>uz4IxSR6FwK@Xm7)Rj*C8=d@*a z&8DNt9k@RTrV;*P2mV;g^A7RrI4mnbs7#%fM^Q*@%ffv%pe-;ICWpd15Q9K=Vll~3 zixyFI-5*9w!?>yd&VLEM1PM<1h5QdXfVdji_W@*X+@YGvWZvJvq}^XLO(bwaD(D`C z$!9$xQM5vAQI(*f0ly^pYI`suk#F%brJ%@xHYL<}z)NxkB`*IPJSRwF|I%-x8Kdp? zP)@{5GR3=w7+upAWRvWBB}%Z`k-lF~G-Xtv@_QacpPU-S7IU&Fqt4=zE(Y zCx?LTN{fJyui!C)BK{UP*^8T*)TLIJx`mfQ8i&`-J}_wtb=Gg6^Mv+G_*r#t+oy8~ z;Z?N%47Qh^&lSPVG}i$iWK?xr>~IQ>;^+!{Jr0sFU>CM~+TlR~Qd@s{IfT}3Vj9iY zKQen785jQQczh``(At$rabLe(y%7B0)VdpKW9xD!#ge-l8M(>N05}XQq5!CuM-08% zqsGuD68HXMHoSUus^ubxEcPIZPjCi3q4S9CRzBYrF;q353 z87>`KnFZC2GcD;2cz91cG+Yw}CVj^6zw8Obz-zlX-wkMeJ3jK*MRfRaDsd;lJsmlUW4W; z?J4gpf4Vo-O;4x7TV?6q5TEbDKqk7Kb~4VR+Qi&7-X|w5x24kwuygUrm2$ww%QhVx z_Ue+AGtx7H5A)*RbyIaG)T`oedIGFJJ^g3DdHqaJb)H2N?|vM8?pNgQ(9upXRM{;k zEN*I|t<~cAFwJ_OvW_7j&lA1Icer=;{aGc3nTwY~uav_$K9bAn+A?${u=_&O5b$zUSYKmU* zx3o-ntsWnvn|Kv$W|@EB)6G6ia*Px=k!ZgOr>+b?w*+?b3VIN!?!6cbgIzv#7&?i2 zOFGS{4SOn|$C;YLzM;E-g$*Gr;Yx0Yy^j7N2iArxJxLmvY@C^q`^P7W@AAY`+eeXo zndQIw&LdpB`o>xi9U|mDNlKwaPO1RO{YJz_M+jzLbcgxnD8kfcX8G1iXP?U4AbLV z&i@hVZy+wi{2U5(b-I4eDDY9QKMUx&CYN?x=*iY*D?O#w{PuX+V=SH5&IjoyV!ON6 z$D)DPEel;1l2s-Fxp8dcsmL!RS+VcA8XQ!l6Zgps9rW8Nj>W4Zw-LWRdZjVvgT&fv ze^m1wN3Z(#X8;#f;PtZj;=}s|>-x+T?+nfg+h5*|mg-h#N9rBJQMhzpN$FCzLk{sU zTJNU99sFzk=ceD}uoy&ZqdN|^F1Hng7I6NL8FLX?W}ce(gj>@E!F*NAWImX7 za-46%-bPGBQw);Qjlrz>;&TP%5) z6I{~Yr~m0JpY!i6)W4cE7?TwqRn3SVCh=RTU}&Xoqy7EGSIFyUocHS2-wiVoqGqM1 zFHrDN1Tk3qvYT&;9%padX2HwRD=>=%y5QY#XpoCcOjRanz_vt6hl9{#pQi39b5`dh zQJ;r&G~4Wml#b+dLEUbB-BsMN6JN%3ks>$YPb4Iy^S0|Tx;4B}&cn9-tj0xKojRM^ z#XZ3{U)iNnw3q9wx0Cs*EONwJi*fYTw^fgIGgH%p+sDi8{{8)Z?vVwxwDeCVc{+>a zw`XkOn(s_h=@}S$W$TfNf{6C?KL`=~CkJB`e z@>P8qBW3MdSaLi55{=)5KRm?ezNm}U>@Rj7||cP})q`|>-_6h}pkFjTeB z)6huz9GuL7_J>(IoF|(i!%zvhEXMo{s=y1?C(VjN_5LrR_NzYVqylO_>`ZiY8NP=J z#Rm&0EQHBvY0Io!{8aLW+J4M2hDnJj@s9_v_NG)O}S&=NWI*`rK8bu|AHHFcPX7PsTM{Y;-P8VNpUDI5<|gNA<1mcw%ujceY^Ke^Y6 zOOHZ-5@n@fLQE1uKGRUMc2+cBVv z?(22`)|+JqT$sSp($0-*2(kZICb8P$*7|hD%hGnS<#P@q(h;+xyL)>D2UX}c&Xzq- zh>d~e)aMe>v>5rB@P(k1qd2U0Whn#f1s(BoT!f-M8LYiK`mYpY} zKJ(&;A)PiZ>N`k>{htZ~kE%0fyHHGQ_bW3Ft*ofy4>!IAQ56(4uJWaAA6$GDlZ-Rtj4lcJ^ST(n$D74Q zhjqGD9C`iI!H%&wzo$F6DsBo23To=YH7f2|>QU3@=j-ux&+VU6Qz{+n!k!l!k<2Z{ zV^pb(W(@NgXwItc*a4-bzoH~2kmQOSOPkd26( zR#Al_=i`&{>H8TTO-D~(D#SE%82ck8a$1NG6+U@-afahEUQyunz$9k*#2xsf!>Bmw zms_1cgVZMq)_a_Zsey3$C9fEdW?uxo<+GNlJ&@!JY2`MoR@;~|T&wl#ig_xYhK;K& z$tpB#j+4LIST%Vi@nnplFEJqlKlPne?I6>11RUm;lN;)q`nSD!hL(cgK0`uPXk)QP z3Z#Dlc-nCZ+^iR1jJG$89Qs_>noUa<7_d1*nBS=B!yTT=&xb|r%>T7JG5G>!PIpWo zJrPfYdde&ncwxC?9)yfN6oV=s; zd0RdO>#y|`Z`Xe^=wSEjDqW2CIUS)_R_~i`q2j{UYVa*K)3wre8XO!nuk`|-tu8(J zw7Q=jt$}>XWbHpsGDS*_2cNCBzFqWSEV)D0wX(7T$=a97E2LJ_{fCHyIEQv~H6ChXL0%!NTDWIOdYJc`Z8u@^^`MlnUlz(B}q>+jQftDobN|k}D_%}eL-x7x6;z-cst=eecU?l^!jwRH!RxL-a?=p_Wt-~bZfG&JUNB_flU zbmxY0>ls!X9UPpTltE&bmq-wLefnK}O+wNyGwmcZ3FY?^m);>pdp@ z7T1*~Cq=>AnIBjm>zZ}v%C&2Kz-PQJd!J^h<;?`>Dn1L{U-Uo%#vK1A(}7=U4lUBM zGjgxql40ls=uuEm05obKs}byvxg1H^_miRjZx(=^gFTv5usaYluwuEPZU?vbe`6Vl zP->D!voGptTy`xdHFRBF>5#$jtbjW@2zfw95gd1vyh5#*>Up>$-KCtNbbZfndoZEv z0IK)K15D&F?LP@WSf1b&nkd!t}WJCjQTb zo5$|E9XGR?-`Qy(@N#SyY0_Tj=+zP49yH(JIep9uO~L~ol~t{IA6GyqvOijk*ZboR zyRI2PHWSi9g)VpFuo;Gz{FpJ9$KjL&|B_IKFH8IVR-4y#-DwQOAacS;y>DkV`Q1;N zEGKgjNIl7gg#-Tnz(T>(Sa*Y@hWa(8gXz33+2LGP^xM)_$pY6&X^=LMLizyOnWDm( ziNQqNz7?vF`p ze%=_w6CLI?T`ex}G>T^0xjCoUJ%7yj3gzJlhZxD39SvvMIs5pQHCn8HDp7R(-TwbE z_0~~sbx*i3b-|%Xae{kshf<(86e|wJEx3jRtKd@Hp|}+&?$8z|NO5=9;DI2yhxd2C z_1*mkizMruv-iwwndh0AWBuOUPQyEa?St0g*|lYyv2L5)l7~5J5esemfH2pm7H5&67^k%gAetx3BUaJbF4lSrWRdH;}mGf3=dwpgWM5sI}e*99#|? zx5y5&cr5$lSu}SKV3#Yw)P9$y4$Z{^wtVI``-0GmeIIz+qjBT?`5tQM*)dZM$wLle zIPgK#_RCxIdK+EcWYt0^J{MhYQjD*`--4~2+(lpgUpDml4^IZq?f{i6fygx*`F83T zjt?g&kB-G$9;Sqw1;+DT>#bupf$8xZmVkJAUMRK4k1w&p- z|M^_O%{3kARJTjCI} zP)ptCDh>9oB%i<*(bJ|zxq_6;w@ZmF=c4HXNs|2~dx>CQ#A0@6Owju#%Qx%xKezGe z-t)~vh)bvLc8&H8oZ1$ht>I21+;nnF$lv0Fue=bqUe5?4UJH{gZQOgZ)UL%x3hj5t>ehj{YfupG5e~8O?v#eY+ z1;5XF(HI*g^nb?pAui&n`OtBC#2MC)_zwX47XN+OGb1|Bib=~KjD>;suI7_knoW)s zPtvBqXRSKY6862=HP~Y z@MYNW`0J=uG;c!j^~C{Zbx^HC*|lXu$` zjEVdB`MYQtsr$gdtJPSItl=%sMrMG1Dw7UBWoC%S!+2*q=#?XDs_#zH^Z*;wWVPB< z@USI_tN;raw_d;O^^PqzA+>nwM$#joQ3|i zWU<+deL%CPTeq;n%*AG()z9|||FvmtP<~-S%~i@UDnBFBiY(99QT^l=xm3S84ybGB zv!pB?rZ+lw;+T3wKwjlcPQhbahjNF15nkx< z_3T`V9C?x z{reEcZHnLFIo@@9Kq|-f_|Xlz(rd{@RSQb~+n+bCYGzS)+Nj|yitmXi@dvz(S^Vb9 zuvSn=SdP{MXsb>I(TaY#(QnRaqVJ5B#eYA3nlY-gP>M}~ppzF&Jx3Y)=u_y2btLxo zE&5X|Vh5_X280=_yT}fJ92AVVSZ~)KVT6b?#`S@_3k891F0IXOBj_GrU<7qkvBO

h5lDG`uiAE-fx5aWPj8`L-X&v<8Y; zM4^I0BJ+~s($ZoQt-cff7V2?)=?*5uz-C|jp#;b^9A-+H zgg}TlU+mvD7jko=2&&LQo~z>)Oq#4T-$T&EJ}8LvzO={*NV zgApP*p*=Ce`A$?jxHQM;F%77sq=bMj4YGdw-mmb`^36~s-3cH842*=tMBxmaA&XW0 zN_My_dk-LyDlGUfEO-^z&dv^DES_sL{b_%?vii^BvRCDJ{CJ!1wagE(7w_o9oK=!s z9AW?et@!x`vBj*46r{p@OTtEw^~n<;MvGqa_h zTTYF|=EKWdtXwba{I?d65~us8GG}*ai5831jg`3=QtTDc^Z?SW|0D^V46Is?{$es^ zdYh@J3<5xf?}En^hhf8;hoVO9rfZGpmS1l5#tS~@;?SF~S$>o4jK3Q4@-$6#76kXE zj#fGxFWcW(DS^1j&}V0tacamz!6GH(qGsX3mb*xP%3M83hW|)Dy5%SqIB~p2PmlZp z3;?w`aIeS|_c`CkZ#xLj!8^7S z6i@T?JL@Z~074^}s9UoVQapC@*s@@#nQKJadzt8g6y&Pgurq~Mj}a1fbSFwR#XnS; zn}~b=H1{`dn*(~)R`@Xsj_sSN_5f^|o|WZ4s=zccHASdyX}OW0W2~pEI}M;Ug_%Bz z@TXH1CX#mJMf>~vf4)5P2b@M3_YQ19*xl6@ul3OWWZ4{mV@O^ue~}F*24I7OZgMBA zC6|Q6gpb-fORi(_XJ==?UdEj}EOz`AsD9HoY6*;R^RReK#A}cLq*JpFynxEmF+qra za$X9Qmblt?vo&g7@I#K<`U0_yZ@j0|uc8|bIc@L4(LRvv${yst=yKCup_aA|;fVH> zvZIU8Q(S6p@5>NMQBMN=;nOjM|1Uu59dha0mBuc|glgyHd^PsNZGcUk%+~IO6m_j6 z^P($hJLEif7O#K0Y<<+3YA`G>t!QrZYL^0(+X|RQ7Xw2{WG}WT^6u7aD$_R$a`n<;j6(^M&=WP$c=6)1hXB33O2V(K9S& z=H7N>rYQRQ5IPEz!qZK(BqeCoVI}*Y!To-l?m?uTAeTPsm6%(A`lRQOi`W0OYjd~c z%f>lJQ#=j^9|VwhT575%V$ta1$BVz1T)OPUpj19v4L`p-z>V++jy8ge-fPvv5~r;( z9l^NKl%f}t22N!^f5LY1lga^jILr$_0I%QP+yW_2*^;x`*`$Re>^+<$o+GGXfqPV9} zwRw2OnPBASj2n_9>E?J(ZOO0k1YXg0hh(cD80pFKyBKXZ@k3|i8wlLlR_Z%8uQ`JB zo7S;QyQ(0!vx9q6ibg?x?RMub9l?l&#)AvsjImZ;T%zGH)8qljQ?l&N6P-y(?R(@X zCG`Mbyw3SpO%h#oGZuY;n5pz$c^KZs9=3YvvLFXxgwUA9a3`pkjrAl1}B;Hs0I{oXthI`AVf zNu{L|EMVe0L3BS2ES1xX8;c?E#4?=VQ);88SH#44Bfz4%Ip~+Clr+Q+#~~M?=jWdQ zu8^=bQ&d#c&=`%_LEc?lQ%gj}uQdRg4Gj_T+!wN04giod{CndN*a+Ga_2R6V0goYC znf_U;y`sy4J>i?r-kkL^!w`B<`wW+=1wjAuh%=)lP&O_um18>;BJM>s0Uax(;~(8tRe)s~ z0L)NG1lKJ9Lj3rSu8W6ej_%_rF(gKlE6kz zMy8usJ9of=6Fgyd?48WQ!a^M0c#anvn+JAV{{4VOO>tQI_izUDdmpff(GoH6`}uiU zhcGZpl-&48I+=T-dY@rnNQ9W3J+0+G&xFlYAKv!LR?Fj|b-7cLUAZ^{RX%bvonYtb zvMLi|3a_%J5HR86TNea2nmtv+9#pQ4xue%GG6GU)OD9Bt_%C2%IRNnB&zPK~BJMWr zez&8eqXJHg16Az!++>TLz)X->i{ORnJXJIZ&x@iIHHMyRd#Pmi>1nW0hhcjl6E`{eDn-O&CC7|Z?w|9r>e@;RzLHfYRUFX_p$x-{oSZxG6UZ<5nU#6B9W2GtF-?+tZJ$?+TB9V($ zK~vmL|3xZM%Fus=!N$JCS>H5mRM$I-xb)kKGewJ@?$o1;kT6QaW<##n=xL%}YP?N!}HYO6>DwraZ2@m7|<-&TfKx~jF35?oF4w#FarH^BpeK$^V} zIPhcU_{2mG-3ITiAtMeBj_V7A|LtIXl(=U@w+C0__U9gA&hoOd(juXwao%CImNPTk z&C-hYN+4aKprAl6dPw;CC->{uJHo;;1KmR0xnkmdCu!n)0KnK)z^$1wUwX55 zhSY<{g)Mv!{`b zD=BMDX}GtStD>hvT&35rP3_wO$NW{LBr!L*uPh~37T?z2cc$>@3e{^dg)0wjliGTE zO^Z-@v7=U`mnneqxQ!r;6jn%D&PyYeI(e(k(N7rnRCa@1^SVF;RCXoLpHv?AS4Zfpl^}Z1IgUZ%fA7QNcf_}PI~Fu1c57hxY}=AQD-~#OMap~ zEzH>!;D-vfGdszNEeDV)t`t7%RxfgzkN%Qry&OgNLOosEsq`Ffm*_n|GQY6h%{ zXmcBXZJy3KMFN*RZnlJ)ulXV+8-Qce$MB83IMrkc1Qp0<`RnKQ$3er@3kp{AuF#nCHp} ztWA>Ky+h8Xqt6S_i%i}XSa1iVPnKjJI&AddCpg*M8izs%ug?{5mA2b-kM*{AVbSSq zR4~L}+u><0LsXZnxC%WOeVJOlR7L^a8bzni2h!%ynW$u5EGHFIa!CrHv-Gg=DQ`B~ zc+uM2mVeT`&|lo72E1wUR`u=s48-!E?Az+YY_vM4d8I zd+=g(E5R#7Nbpdr`A}6b)F5Q(w)2q==ib%6nqbEF*-Ll^a$ws3PcwDanBIg0P|C{Z zu%@uyz14DKpZsY`Xh;+|S=46*_X`4sh>UY9vb=qST)a8$bMo`L!a&-`2RW!k`GOC= z$|cP&jlH{R^B-$sDS@bUe_!ts|zfUHt3I-6Fm7EH)vH|j9vKq z-ZiG^xkZhY(0+Nw3w&Ug2Ha$*kXc9xQ7~ANOc)~oJ;T`jLn`Os^iSM(iTaZhD zpQJT-<93T0v5rPIA9|Toh8f%z-x62hW*e zvHkGcLG)sZU*w6a(CGB;t>xf2(~NOVS&;zp?1its=o`9n_;lP;j`@YZc=(}2vh5CA zs0Ch{)`Hz1G`HV)eSd$CVDLX=b)!gIlyDbDIxc)j6gbJIg*Z&XuBh*gLj6OTGu~!^3Aa zy5hgzxHK9rRp^UbouvRMirW^K7-HV-p@HOyQL;=^&npC$+kbAr3n}{U*c1jqcZ-3K zQ7Vdq-`BA0t5W5cpTvZOa6!>m28RX)Y1-3HZ+qt1)AVd?Rv>cWZ)G_6u~oo!j)x;3 zQB)%t!VLh3c6gcW@geb^a=UZ&#S6_?4 z%w5Etn%su6lQMl)Que4wR8lg6488x(&oJidjCERAPSaVB!C6{xT@jzrdkeRPwOlqRKD$&hRe$G`YC& z!p)xIC7w%q*1SfCXF(4H&55K=iyT*#6Eu@5O?? z2$21%?*U!>`wf#xHN9x+LfZ#c=FtOzdQfQNbKBxGaWmCgJqT30Hm-;tD-^qy-ytK@ z`D5uf6^WI~9_n@>r3r1mwMkRbq<9O{)V(O7XsbVoL9_1z#f(4bi$ZL%`9sM6+i^NRyqsDJA2 zqvgR!X>gOr$J6XlAGai9U(q_M-vvv*X^yg*6G3}yqxc7 zQQot9U10T#DbT;ej)6qhM;opC>H9V$*%|5c={6(}LPDylsvb*yB4s2n(!S5z#_D+f z`FlbF(Sfw!g>9{VJlxN<-?(et6LP zrv7}->*fT-hTAq`I2~i_E0m8W^1`)l^D*z)09I zrae{lCeYonu%Lp(CQ3>1YG?AS!{d)%QzxRiu9thN?3%;98uu9t+ODsDHU4mG;}ar~ zw(YZY8q{sva1PJSK1u4TV4q3%*~MmR^pJ_0&-X9?<#G;P(h(3&zqs{p^BxXsS2-ws zIB3*uJW^qM)swY9B)(SiXQbT2aI8h?ipwdYsHQU4;Ad2$G-9_fE6Fp; zn`88n2GlRFwp8a^O7jv6UWCRWP4thTc{x|-0PhXCd-18rT&_bEBS5IjB|Rtq6Eeo}LrRT`+UeG3ZyEJH@g+eCOw>w$MDoP$sDv&U> zw*FjjRld9AX5yGV^BqzkeE(xDvD2a|%(vB$nwx@KeYbpU8Hg}ya`HcpE^RL@F1I3m z?^sxDSHF{Mpn8BU>dTdK51?m`{jrp)6HOjM-rolVLa)Uue z2Ojf?A3Hu)=ew2VL}|UFG)bnRF#SMyb~*Cb_8i6dT_UP_~|Ky}4? z1~a#bl`pl*R#K|(3FwYm#t)jIw6fMpM%o84K8vYw8A%Qf3wgSg`zr zaE5UJn(t&uT$|2KD#t1t}6@)39>K42^T>IbEv(cN^S-JPax7R&H69>{cQykrd z%WsLq><9aIMm<0M+?A^IJ76=pv3-3vo!<)$4c#i{<;_68k1r)6RLRTGZ9`Vk#Q8zOti)%g0w3;j>z$-n|!orQ&q;Nh@3c?f8;G3kE>_dLXiWna)|PwD zCLn;jAR?Vg+BL@?Du%DFh|~=Bm@*aJyjhVx@tDTJzzE1*9!|c8zyUxHGX}S$`GEWX ziv{@aOBzSo|B)ORog4tWbKe3QzTM*^K*OuY1Gtv^wn_}5{_mf+^Y4Ji-nS5g`~Kgz z`y2oF&;NTf%^INU9MEDs5xz*d=I0oAv_(=gf=Z;TPF zyeq~SkKO)`y8r&ZUo?!sK29ASv>2<|`0bxL`Db7pZ)<4o&4<2pV)uY{2{PQ1ODnK{ zma+H0s~-M$l^)>9o_>*cKRjL7YIr8#gwMIHd`}y#1OURpixY}+%X)3I7-z*wP4GCd z#hN!!TqL!$CZdNS=Kj$UkN&#}%UF`kE7|BkMMd|L;5-{9Q_}aUzWswfhU&&$UZyQ& z+vfKo|N00J?ptMzCrs23HDMDlos&$$9t=5~lS+qXeg1H)yXVAj3lLqv;k`P{Vp)5y z2BA63{ru2TW$kIg$5JUsF)K;iFC`-48@V~mRqUngSQ_`kbidbar$Bo~l{{g8VtRjY z{An>q9b`UUE0ie=G<-S=V_9gFlVc(5|1)Y%lvAJl^3NY2rU_&5Kk?97wzHSKDg@85 z4C_33H^J%}t}?;luK`tc-RqalH)&yng5*LeUW}SMt>nRIT!b|d21fjUgVO#1QB!p}fnD8+ zZ%|CUkDqYYxX^rxb=4*zJkp0eDPGNQvDAJ-ccSobUFT0Lfu4nco|j#J4mCHicAQ-yC&5#0Yr& zpN1gKEJNamzSgqdb8!C)%jbMVPJ&4XKAVfM~`^kOL`k#WLGMSDX_+i|8n!H;gl&i>H< zof|qX{fjEG22Xq~?BpNJH97;RHJ>_s3UhVkIWg8vQDy|$fx-0ki|&9p{`{xzN7`(P zwtvkR;|lZT;snYRjjKnS4g@)%ruwO1a-A80a=X{gW^292gVIAZps2O=?(~zxyp|Q$ z#>Z05jfTBY{7*b7>8eb%*qQhTtANp||EE_XN{=GI)98$ zqg~WrA#_3otV{Rv#Zbeey|^E0*cWw1#AV?1^M$WmA9>pb*`D2SYbat=2bgG5WO+du z*@)*g-%U1bNPzVP>uaPZK!>IyZ?n#eG44as;S2fZ)DY zU^hgCEQmq8v6`6WWJaJuRqt9>C@cmL*4*ZV#%P=!Ny0sq9$+JNZ@Z=?$xKrvEOD7P zakW#76?(5_(CPYb1|$3IKUQ7nPpG~q1{PMDl7GIKZzGD!OG?Dti*j1hX-g`^V-r&# zH=#@nGvE2A6kNrp9nE5Rq^j-y1&W+=O$odwcx~HS#dn-o#d`qi>!uTZ$>KAdv6u}FIb#b<~C-t&h_U)9grjPWXq+Tq<((wY-X22@Z*r)~P+|KsAj@~bf zFVyYmLIl!N%+kuqp2q%3zh0xg(hkeY{QZK?O>+|XtpBCBk-)Yfag~g3MSEt*%O(%F z12yItFYg#0<{Z#9QqaT(?;1o;p1t2)?m+HS5+i$l^NrItZWXe{9dO~=fy#u_R49i- zYx$9i3iY@i=RvP+sDI+95jNf2lcC>DPWb(PCbwQaV}}Px<31J_qaKnsRnMgKIlwNNbbp_1z^zx{}W8Uy-`B2m`l_ zMa8r>?5nl>Pp-MP{FD%7;f3oB_>*5rKhZl=2ilX4bgH72YKa91g+Io1S4hdaM8Ua} zCR{QXFanIZm;{uVeiZ`y*T4AhgNcbrozv3XBHNk8ij8u^+P&0+hb{3i4=$c|cM^0| zVZD&S!l!%Q3wr@KI7lgRR7ri4gqZxLz}V4!S6g^NC~$R>UeKUbmZawpPz8R=9%{eGU0CMBe(aeL69+~~+n+Q(F?Y3=yx$y#?kG))kJ zLbPfU!%Pz5@uB4&5Lcvja~x$Oa}TmI+G08?OuIp zg1Cw&dS*RsYF3MvM@(G>Ekl%=>HG=WFoX5%Z@&|J zJP$2Cw#0E~B_X3s-UobbW8?m0jvQtlcDbClSn%hZP;*_>d@$*1?zciQAu4Oh99sj< zo~>tJ)gNj2B=Ox&h=lJlc z2<@#rn7F1kiF4cVm+;>{6H^tdx@a_T^xb(*IoD)!TM@k^fQaVwxMNDmvd_`E;m(se(5(qlTDn?d*z1YJ@W@h#UM^Hb-tn zvG{9i*Vh{y6>3IkLprYpc?_i^p%3_|RW?u)bDCe zqLN{!$+(k#i%mA?TnLV(rP~uGCS3S>NQg3|aM8VkC2PR=_%u+7QE`xO#*xsm{Un($ zC}bdGxN!}=cx`pJwRGou9_e6I*MQCN=e*(a&_39zO2(pJbmQ;XiKIz&Z64&^vx;-r zx&0ElfqAbb$yy!~9nw&9NcYrE!WaZ%8E-6a4rY6q>Hxxw<-4^= zMjBa>k{}v*1}T^2Sf0=Alzn=S7!O}~NKu%G)G%Jx51=nlyuvV%1 zwbKQ4v<#IAB#{Bhee0u**AZsPVgM=b2>h~lo$Ci1FG&cOCp0VVkFzb9_q}G!|7G1q zf%vHhq}9r4R!6Hde(h-X)G0h88RdPWrDbYorefN9|eTru{6~n-)XV&B{H;ArsV=Ry#q`Ptoi-Osz`f=!tnOLQ> zq?F)4tSxM#BX2WaBlAR83d_jQA8`iO((6SXCUP5;Q7GI-y;KbjkHx&keH~lI3}ojCaCb|WH33aqTSbsn-+`M5_n(P^;|%uUIwPdL9EmEmTtWBkgw@PYwt3}me1Bi z6Mb8OvjPb|e&~cG*R6YDsl(j2LX$V6O)h=yZQ?~mb%bd+@!GW9@YVV6sNs9hqbuc=exNZdw&aYr~rM%A3C< z0T0KdXhZ3PZMLjLNLbUX{?0@Fi8UD`2P5~FkDoG5T`D95Vs-FsAbX#GdZa9+x_g%X z>8XTmKZ5ok-f|{@%u~P-eK$qtTOnNeHY#+daFN^hW*E8XzrwJT;r7n>pj+FY=Qh~- zmYwAI^GvmWE2>Sj#{mHF$DVB&>~G9X-c>Dnj2KX>!MXAAxhd85n>}W~O{F_`zujw_ zVEcFgZ(P43k5*v>Rh>zk4jfjr`;1-I`iffXV-9CEZxbltJyVKzyZBPg)r?vU9;U9p z*&q4hrr%#*VKi)bb+Jd92b@$R0B4j&AU-KE1jPN*ov5#u$Tz~>nmXVi5QN#$`{kF? z%&^|H+%Njds1K#JFhX{Pp}!L2#Qgcc3MGfK+rvhFMd-63$EllmCemgzrTbpwe|HPMdIO0Q@J{^tLxMCtcpN1ge zRAR`nDao5PC+l{F@T`WNo50s)mI@M{s9=+<%H8_1u4nd?ED&OlTM{pmNe>Zg8;Ryq zBlqxp=>mkEJ0oKMD$5UY_)JMcx7DNL&v=wLSF+1-gQ~XyPl5dvQQjPn`b7cJ@VFFYjdf$o1JA zmFTqqZZvltCtbJKYZv$K7di_gj&lX&xoAYxh<;e6miMSOZn}FyqAZ{V5O&fb2Dc1- zP-h)J*?Rc)?Cfk&!t)$OqTP9GR|+OUgav6qHnP{5q&OQXFYLgI`J?NA`VMs%c{^}- z?{)+LZ!O@G%Flc17LFsM4uO1&Kat6qY+y2x51!qj=@ipOWE^V4MjbpNedPqsBse{$ zn%)rQW+PpI&pcRkk>zUax?$wzrAoHJ0A%pTI7k>;Fh^QrB?H6Z~si(Pqq56K0S7`uCu?}*t0)2fx z^~HE$&cP242MGMZ>L3WEYPQ1l5@uV}9tm(0TgowzS4G1ZD8 z7Zg>AOJ-?Ty5zU8U%{b zX9|(0f3PF!(pbonXt@#3prRx=t{|zGSSGwNIxAJUV-NxSok({r?pc7a)8G3!SRm@h zFA7yHLOYw~<3}@?Uw&qOP9N5ZNgqPraN~rrnp(xG)?HWO9OqZX&StR*T&o}*ZR&H- zn%(m&Rg)8+=QOXkaFzwWI(9$i)PKKtT{bqi008TUHpC@#+dZr$JcM**`_=%&4GPT( zb*Pye`NeD6xHMh}9%j+0?K97Hqu65J)`m=4+$Ehwa7cb_KmvW#&Vp4||41q>(^tDw zI4Gr{H9PwHpU-Hr+CMND>52cglukQXfqqpsyUb6!>9@5!J!s@xP{u#98{Nc&_n(sd zwJ$b7T)(S+=Kh$M~S~+dB-^G`5uc$00W~zdR@tICnaTs^P!FF_U{LF z8R2b>H!ccEmnSsdqmSWLV#Au(`%DujeJ{R;?0r9O z^w@z;R!3P;ixRLac!&p2or?`ET0hRW?1MzR*-x+(;>7i>yNdu}pg@$^bS6MT*f}~T zRtw(acfI$PNCq<5|32qdl1mlvSqvwW=Yb+WSZr9S)kcv}hW;C0km+No<+19$;K*Wf z5s_k8QmvVn##QEe|7}6He)a8h?ud@Wp+XA*&+S>mf7J}_I&M-SAW3-CzMARB?UXA`RfzXSBH301F41tSTxgg##87N2jeV zN0^y}DGYe@kCh%j%~AFNU_Mt#&Xce4sP${q*SZyo4S|%;H1Y|qqbHxuTI4>Ch=vqjSzPAMP(;Oi>L*JWz+$l;#&Ed+FhEdM z(;srr?!knpaj$R_7q=EX5E4LhI7K$HG%_;9XeT!NXr*fN=I_SV)U^FMN|=lEjT`M* z5G-=hA>Eopxa&+Gt_Xf0h%qoe06@zdAa~!a(RH|WS0nRFP)4Z2VTG*TLSadRo0{)Q z?|y%lh6FvAv}jS&BlWs1tvmYqmL6uGc+*!I{mgp5N`c zfBT(JjS@a_OZi%zdOeb@ zI-TddZ>+>pK89+6jyg8fIDVKuQ~SRjD%oT-d0dN5dtfjA;+5bN)dK0+3Xm zXOr+&2FM@OItzP*$12nIl~}NhdTk>6(KFJZ7|qP8+QfPHa9f9-Zv}=gR3@wlFfcy9 z@kO~eDwz_oJnjdAj8;RLK-!!EA81b)Y6j-#0R|Mt!o|i=9r{?u9;#Z&zY{7$uNE#t z(Nh%y3&rsOUL7Ts#%&(Nv)|~S-k*U52hzzI)!3+gZjO68J}L*$(4I&gxl>f(dOh{g zGBA;&fTw~rjHu~Cu;7ZdexGUHXrRMB|Nj0Vm`XI;f&HsZ(nBCG0jL%6sQ=HqS~sct2BdR~PF^wukeL z^1gqh)|G7TkCl}6SHBm4LZllXm~P|mRb~Pex9j9~u<&^s2CVe0;n&f#th+j$LnWKU;t3x*-#5yFMvMohm<&7F1GJ8mY=pHg9TEzew%oj%0xTyF zk23R&iOER}P3DouU^lJKx=|*<2EIsI^=)g-Y5P#WkZFBqovcI&EpOqCC z#{d*Zyu`+9kh4(7MyRMLa4|gj9MkiMPDY2ER*&o;Q#@d~o8%*pG?EVrU2-E{_j9xzV$u2rB5Tzc&r<*`L@nT>v<9FZwVAuRP z5*C@&LpBA(S<3wAXC0!KS?9%B`>MvHeAii9)=Xcj{pzuLlVvoinLM6Ml=-Z_m*S%{ zmLZ@vrR*Q@-#KB`&JQ9_Fy7EacKqCHXntE!4EmQjW-vW=DOMClTgKop_PqW|>W6b= zazmaMmwn~q)+c$jZz@v;b4q1jDJ&~vNq4@Xe-3gv39ey&3F6YhsJnfk`42(?9EJmu z*XTyS#-ehjT|%HH8M~&?IX7JBA8ZjWl^Q3Dak885C^H<8Nsf7JY>v^_qh&}mwe!>B zxwF9m9{LavR~TooI~GX#^EUm}X@f98Z^EPBOz#dtOguoIz5YdWyU<&Se*MYBp=)sP)p@5i3&AdAhIaz5cHH`vN} zRZg5gv=;zQ&@RmJxOAFx91x98O`Ps6h>6AY5J3N8M93r4Zgc!ZP2NJ(;4yZu9gRy4 zF*SG7c&($LQ=+6vTsB1;VeI$iB!PJ#&+PfOhw-4SA-$iLmXr|oYA)Viy|pCRzt^x+JN%;w->H-K(UbY`uMQw%Pqjg!BCKq z(kfyQS3HL~JTahBc%2p>p)swWv0Wk!+HB~() z8*pDf;>fpWCyA(k3E`#yWmzd;P!o>#0w|%vueF$4SCIT!9!r|N<9W_D7#c#m8uGPH zLcOsrWxTDnknfKY=9|utP8UPh`^GbT3gnucpPx&;VviRn4GC8)0zU@cMG!I(Wcwnx zE$R4U3bD-MX>&v(f-*WE+v`*nM*9>S&}82Lme0bEibJ~Bm`z@Y%!~}mKa_S1OTJs# zFZ}i{cgxH_U8;O~SX}xL7*T&ePnyca1V3#OABI$qtc9$TbI(JJx1C?TMX7B=7#>Vu zH*vL?b%ia@y4j%xM!acCwA}~HfkeU!U46bCEHV)FcVW@A=1sD;?CkuU&wke&vt1*a zOKrZInwq&rFDrl}KTz)D)y-dbb!utT2YUE`PH1MYA7Zao1pA#P^t_>n3X^zF38Kcs zuO!Ay%WxPPBKARUl9TDVacz(Xz!8eCAact-3 z&!08A?83srC`Y|E+J76aJI$7lUV_*_48W2=-V$293-8Q$TvAf{Qc}iqgG`aUT$m-47glrnXUAP6Lp8iBHa*^gC+!@CVgC1{11a@)0$`HRxX_!e^V&@Ekj3@I zXE^i^6)d(Id3Z#11dC5z?|2ije-l}>%8h?z?^y>>>1Nd_?8KZbp{K&Dh8D*Eeiepo{cDBi@3bd`ZP5oZy6e4n{`VD z?+0d>ID1kS*Ti@VFHh{)m|nQ7l8RC1ub*(Rgt82lCQF#i`VL+ZH9og8nL62UVR%m0 z#%LKXsk_EQiDh153>tSTUIXAE3vG!buiWd+x?Vy^O2mEG6okU?A5Uv^9r^r{hmBl;pS*kBAGeG|#8qCh2cl-OEzM==$jHb5;XSrZxLQA43RezmN0$#sTNB>IkC1)eKC_&L zdju@kerrt_Cq9rF@$V*l>>4drQmb3Xf0r_Nt6TSbXMca~qCGiR90Z~OfSK)g*9}`# z!PX(pd|_|z&V+E9clCJuumn;s8}*;ifIvwzuw+Xel)R6GYb2t#qe_nC(+o(8d9}fh zVrpb(Kh?&G;j1(Nm636*Fa_;KX%$-m)vz9vkp~gT%85}by;`xuS`D7?`E6(Pt|oR% z0mbx;P)Z2JWz!$|{Bun>D2IArlb>0ylzEyN9bpZ~^CeD=B6T?Y*l=0y4?qg*lv>C0BenF)+3eAEAu@L(^FRwbgVD z7jW*B*2PFSHLrNif^CDpZ^<{8_w1J~HT3}z+}DsWD*q3evq95ug4UjCfA z>1S6ecPrIzEpD5;f51Ifdq3X@v(od@J-;*qhK(RZh!H{uB9)SKfS&8nW@Jt29}*l# ziGOK}h?2m@62IIVv-8jL`q>%r!^l_9c^8T^%Z-^kohG+#wTmPYFM%vFzltbK7BdL& zeJF{DX;cOM142Zq914yn@+b#VtAm#NqJhkfUc(TFLrv~~wy&C?Lh0--H6t-A0ukOA z*mMvS`0e3U4dd&c8rr;mXmutaed+Xl!en}-L^7pol}3Dke2=Sg;@hf>UHR^&V-e9( zWx>;8`wCyHJ`Qt0?Lsoh-xJ%@zV2f4F+EJ@2nRZsf?#n^uLgtw6)zNda9+VnncPGf zSMS;|-0W;P1LZL1-m26MS{y8{ZNo!>R%#C2OVab;n{zPDN(LqNg8Ev{-fQ%0XD}{q z_sleiAyTa${9rMqE25wHoq@HQc-&HO&@Y$N*Z{)^diru#%})ODp02e`x$LA~dq9v> zVD9#)|6C94n@|+h=DE=v2-xvrVpL?0@p}zXqf7WGv8z-EodLaueM$oJL+Fw-WPWP= z_dmz+i@BH~QpiM{c_v#)&`@B`n=is8Yf22O=7iF^29IQwPxFI{29lSno2#G;RYt|J z=?_<1MEB@gHk9)6D+AY3#Mg#%%F?a(N&-KhBE!Q?zF&7NpC5Cm#_T+Qh!X?S-y&E{ z9C*~pZ@;6H1g(Z&5leimRPa<1d!weP%fv)-PDn_04LDdF@tRz%w{K8ye62y3)aa|T z5fc4<9!WgOOieFAkwfwjfB@X`W=D-1uV)00oa#jnVbgF!ZP)9+N(? ze~OtDFbWAj}>H#J41YEPnOTojts4JlB3-xjt&S@|==K^h(1IJ1dz2 zZkqXA4)(tEEi~f`n;rG->u;yKnsY((+ABi|F2K-13VL1)x$Nc}h@)VGXZmi!O~-ty zfKb~u$RxrJhMm76Iu*dqpRlb;5NOjt?<)??o1pWG7NNqH+V;?t#-xSmjEFPJK+YWBf@%Dq9hnfQ&!U# zdoxF4K(w`RnwUn&sLv_bQ-rpR7A5M3Y;br`#L?qHPFgi~_+hNzS-5)y)bB$Lk65BD z={g_^@6jKLH*@eKmE$QnP9Dd<-Uu{Ecv}qbJIjAXITvWiH=)$<*?#8ebe6Gcf{*c5 z4zb_qIpPI#38dWNCjv%+XbV68t3T^pjmUohh z=W6nuX-IqI)dxF`G*FH2P`7Cp_)a1~Uf?s!~D5e4s6as5P1g z@G<|pHY9J+$O6u!vVnH~uGho+`)!}r#sqzlh&Tghh9K3|d71J>4Q_PBC8y~&yVp8kpR6iZbK^8>Uw`XiH_X+5b$rpfwMCKN|Pi_^MwZT zAm6`{nCFL&xIHOEw}HApKo??`nfKAd8lNObNFHU2W%1Xq4KV!Gj&~k|CD-$HatTA2 z#4q-N8q>uSxjVnco10nX(b*YO^62MH+h( zp4LRo_V_73Uk(RfiT@xh8C04wVCnY4_-@!rknURS#5N){^LbPT4W~J)MUuP>4rdvl zmi0aZxqmkKVR~2&*liaIu4X}!hL6; zw=**bjD7WLj02woR7L#J z+w80yvpu(wZ6F)}ZjNT%*8FV~vNu{?4n$rq{!Fu?iYZ>D+5y|4V{bI=S=R6BxaV|n z^*+JS>py20w$${ItD4F;k`xL}9;)~*;{CC79M{rqOsbqM8nMjlKjvi%Gud3E9BiDy z_3C=7N>rvlUM0yGg@oyXc}uXPZGg3L>DE;CAjUBk6L-4Y?!Rj2SOBVZgBT1eezT85 zt-u?YG@AVR4!nj-}sY{teUm=uL+QoSLhp~9Wva)^tdyNP-1>86Q7SB-?x3lpgIrL#b zLv#Ja2bCfO@FHGZxRKN4d-COW>7iwut)c!xLA7)9bEkT5^zFHHO5Og#!Z%QjrpWC- zxvPSZJ+tSsaqpgNz!uWQ26bxaeMI|}1ZWETnZ0of7eIXIeEw-nDE*}Q)3_tIslBYk z&qHK`Zr3By$Nutek!bG)I3=9=%AY0SUMU>`K(E(RMg7FpdM}rCSr;7N(`0c;+iyJQdF`X2`7X~ZMVp=;dCzT?y5wdDtK!NS&m?IQ=I@uAm8AI;mCxX} z;HBU?Vzbxz(>_AK5kVC7GIyCzqI%L(M`%~nSVxF)Rxu|h<*V7j& z07=&jW1ux?YJCadUaU8h2dc5V?+HTc0?tDls}J8mR7T}+j~(nHv0qgTg?ut%smQ_* zlLef%9=#=`U|mV`3Aj;Wkg@DnOU-6hTbv5wcz-pdt2Kj3A^rbFJ-1uk6`=gI2<`I@l|+A>OsApC?r2m#&hE>3s`Smot15K5N+tw+4W+ zyL;(#OS~zA=`#ZWne@!V9y1_EQFrTsH<0 zCrxz!j0$$|ef8zs!U7Xlb{Rx@UO#DtGn;eq(R%V%+3V-i6_3T_E+1egQbhOl4@U*r@om^e-2d#4JkY2nEgaPOoz zA4=u1Z)(gy7(hXPbUp!ooQbmkd@`Qj%<&mpQQY6+&?|j(>;Au0ux_p1(c84vV(mQX zD+U(|JK4|1JQ;gO0|U~L$M-F)?HKmdfmKBg)^l|~?u?1d5-^Wg#Y>3YpA5&W8iWX7&?^cund0E_%l_h=&`!YB7$-K-KnlkO-Y-YcRDbSNw^lHql>Nwud0 z;}0P^pL}s7xYIQ@3F;0HzwS7g%C&3Hxs@E0xciIne8T=?5q6}s(f+y$Fw)3ds@?c8-q1IAw+@besJUk9Q9~7kuR{b@^xW|qr{jduxz_jd zrMSOfXl(Zk#XvAU8B>#Ro6uu}1<_T_*R2i!nfl&q7>(!cao0p zg*M8HBYk%n&xh$X!||pCB7aNKRhbpA!W5^*womP?%BMBni0- zEJ8Zz60+Cl$GKFd4iO9IDsyDm6ZZR){rqd~xlG)^$TTs-H8Ee9zI9Jn^BDDTUpNjz z#4a|9@CQY!NtIyu+;9CJuM$pHKw6{&(KI~aIq>fzw+&>FllYsqXcD7R+ex%g$nOxm zEr-|K?j5136Q}(aryWW;Lyg}*9-#16xaFx%c= z3DFc3TsSG{0|s{s%r0R#-T!GjpdY-befYJXJRVdBh-d=*}CFD*be0hpp?*Pbf6!kFj-E4d>5zDX5aUp~X(UP_l)( zA~w2a8`rN|i2;VD_m%@Dc(VuDCa4r^_od<(^x>kZp>@>j%@l`8)v>+^UPNMytOZ%T zLB^_zGPU6BBTX8McWxG+$nSet@NU6hetViOrLpCH-E`U+NZ9Wnuy&;V*29);Xytpp zSW}H5yPLKue4el^rGX&oWe|7D|8ar6{O+vTQ`J0#lQ3O8n}V7~nZjbqLgs80)3v^0 z$?(u3C>PmKvRyx6pzhBQp_ei-jmo2PH9FHbH$KQRSm}q#78mHV1yDfTh! zM~KAK51bKH-1OB)Ux&{-<6(I@VH=TKhSSYXJJM*=*YV8XbC(X7PgB6OSMNcCCoAw2w`w3P7+H8&vq z`D6pcC~y95d(;zKeOHEia)J(4xt-gtUBq`5EDyFv!P2M4uT4xdEy|QG=!6f!^8Ctx zh2tZ+i%Je-_(Pi|b${PPk|f_C{`Z3j+1km6BHgZJ+;_ib$;9IdX_y;SN)SXJGYcG&Jc(0C7$Hieo;jBSe3i6cpDub2qZC@!$*=_`% zUJ!!eQSpTUnp}?^sq5}r!k$y?;IT-YORqsMAs&THp5SIqVC_|5s0|vzI^~tu_W%L| zmJFu2Vf&Ksyw{G4X$w@WOCkQOxfuw)0*(FdEEdFAEFLO`jZ?VgVX6H~?@ocqO5-{8 zyv6xO?C3+9Oayp}F6&A+@Qi_Uv5zmb1Nkyt{9Rzf)5kJ@DNaeOU3&LxXtWiB^Quzn zZG09LK1UEAqfphhKWfgb+^0{;S$>iI*jXfxt|3jiE0oaRm4B?bALA*lHB&bp-*n0! zKBMdMsSzb+LqFQh9C>s(t3Rc&nGdj}B+&ll`gQqd0c=o+U=R%#lsOpsOBfs>uPOIfNP8B!l1=b+*3HYE z0`B25cGNkR+`m+zv!g3YoRq~yhhaB1&3s7_^Nt^X>hQ%?v~C__FcW;U8gIr*pEM_Y zK7255yaPPs=w^@6(8wx+WIn@)DY6?Y#jgTOGUZCanNV$*Qv?Oee0dMnGemd@jNg0u z?~zbM2)AyK&U8?|4h!QmicnL)7?J{LVtfUE^;v{i>Qp;)pOtzeK5PEUj!-Od4N zs{FMz^0rh~9$@MrD8HxrB{5kM2>M)FjC)`*t7?0941C3H`|e?+eHIDJ*bxZQCR5HR zRJQz6Z@jezrN73*1|7p=$~Yn&W?n7mM1=reRzA|oS;^#|Kgr}T zw_&k!rDX$j;a(d;su2ks#CAOZ2J<>YGrtZ64JPepY#-OI&P9Gv=mKlI_eu>pjI zhaZdSa%7r#r6K-uO&ME_DP)S9Z-DRD*B2Pl?raJ4W&pT|Xq$JGq-*Uymp$ODMVU^h zh_MG{e{Ini^!dL$mQ)m++0&BycyjXc`zKsYX+|?-wQje8t=H$ zO>J$z4@tm-Jqs6ypcBp;)Z4}4R2zK{4H{%}v#^<-qQNapU5>ca6{~Svs^8kS|7Css zZJF*5uVuL-4J>;J*AUQ5cD2647j`nKe}?sMXwoG4{oT+xJHj+IZ2%*2PzvtVfI zX~K6K-gK7qbSrY92VpF^;3X&0gtSPJI2oK+f0540d=wv`@=*3WkMQyFPqNsu)YMcU zBm<;x6{dl6k*%pDGF4O;en`E3L914>Mb3|8Gi7s{Q??8z!QxAce(wr*-sSS&2&b=o zwxy@HDlS4VuXdgw$zU+Q~m#U{G zi+R)ul1EDXjjC4om=BI*lcbHrmGZ}y(EKYUr2_IaB8d#A3hIEMWChT~gJzgp3)eE% z4DapJub+4RO=M-IXJwt%*H6lHq^ApWxlAncTTOao9|+Oo63_VLYoA}IKnF}7Tzd-j z7_$?iF`@gF7$!oY2gp{1w>#>XQ(AE~DZ-;+c4|1=S+01KL%Ek`FnW-q&j6lGbp*8D8Uz=8saQw zvhcwp0L~Fc5oQSw4Z@DZs-=Bv)1O`SqJUL71{+$K+)w^q&Upq@Y5TDss-C%QDgn7$ zT31Kw1X9Mmxi1o9Nk>kV7BSAbgm&f)2v-pPCGz!0AO11qpxw+Hk;vB515FFL$rhPN zx(|zzV(PW zAX3uN!?$VaR}4&MR9YWx97REq~^OiuBgtkMsD z7t8$OzVRl!H6*N9DRQ83MhJMBCT21No+MenjV}@NqnvlolOnNPB21td14~n%v5H2S zNI1TKTUlJr7w4Zj3rr;`zTf5J%nI)%RmV;R{*~Bm2Wf^Zk(`PlhONlz{zgP*R8;$R z#YIm%PpvdZa|D0F_2B}DJpN}^;i5eHia;SD2s6ziVr?OU7W{K-Z%f_H@)CWSI<4%l zvJy66p;U2!7R18jajT~jm3OeN_T11TqNt`l_oe#)P;k7?ViXN~cL63Tlv42LGfQl3 zPBFCCIy?IB!Fjd6X1}QHL&F2=Xex~@EMeqJS5Fb3 zh5G9~QrOCt>c`eY$eg5c$=~?kD^fgr00%34 zd%H|y;5mY9pwbEncG6M#r-OJZ*(H=!PoLDyFN00xV&v-o8a~ul37QW2Gu{Dv!j5{; z>MOJ%cSCQ=uKgj>g2^QZyJ|rLh235(&3wmt0Wo;q(sI~&)X)$vMl#eaK%ZZmOIBY) zjlODZG!tWvjC2UmX)1ab#rG~g)6C*vOk=24P$%2;mBZUG-ufdGY$h582Gar$C|H~$ zwN+U`U_mlm%6Er+@YLNUO{sbH)K!2BtCmY57n&WPAsQ7Y#fv7dws)oRYf4vE8w?vx z*`)S4Q6a~`&jM1K=UiI}l*|UWB}GAo$FU&JNt*O>2KiEkNbtX-{aNk2ZG ziT8COLUBXrxKedg4i1CngMP>`9@qVPioS-G>pu<|GVWKjxA5}a^t)g8e?FC4LmkF= zx#Z#xky>{64wKgR5KoxYx@gDn7%i4g5T!pK%@CQawmhs}AKq$vhH9?*KnuR(18T%i zZh`9Y=2bg-;Q#>{f{IjMN_w0zPf(hzx2NS$Um7>x+bHEoY2k}3rE)#XQjk@8#k|Yb z%?G-2Tv{XClFMZ6CY}}xMG%}S?#D9B{7|DbBCSdDbX+t6Y&%JL9Ev3^*xZR}`0^r0 zc2U>Q!>!uKtZwrJ%%WvSq45_pWg^!HcHFIHIzn_DaCKGrv@WovGienpJSm2Q&rW3#S=Fm;$K`ZhVWYA z;@Z=~woHlBy>Nub^dB9w%hyZ)UP%Q`OL3dkl5=d9hPY&wa5XwLUNLwCy_POr?<3_X zZprQ_b!ZZ@t%~p27BW;2_~!N&K3H7X#fZ<2T^m6KK_x3_y_!51t#=ec6R~)L2M07n zcOD+Ou6||x_W?@f&8A17mTs9_tn=x(oKBO1hV>;{A;CRO$zq^_XIs1uHj)=E(3}M3 zyMr7o&lLZ#$zqVYd~2Q}u2l2t`r;xlA0N{34_0~eb|W$|6 zc|MKdXx;}?2Q@GE6ho^L)} zK-v?4zO~k*D729+BqOD%yg%!_HzeoR5iyOI(9}W0zTg&p99Fh(KW&n%4*|;sudp=LU>Gfr8A5XgcZf(y(cobGyNwKc*a}cocut&Z2N%~A(kv#0+%*HN z_aP{72J?uFsNLG8m@{PgIO5JQUw9-HB9%kOan0W3x?rY7;nl_z#i(1>?Ypc6;|>@{ zfmYJ$Y2Vg<4jMV52K_c0b{rn$ijSQsjC@72xMNoRmGG_M;rnG(&-e7?QW~zL-*?gE z!o*OlT@R*Eo?D>=4Tf0*s(P**+CEtv?w9=p*BJxyHojS7(^FH%pikUKr!*M9EU2e< zLeUnWOtC8Pow=m0B(Cs+-WWqTEphfB2TH|BTGeWA@GyZY3~*3&NN~bjxwgM{C@vjY z>VEHx_Kf;x;2RmN`y+^PzY;kDME2p;G9z#>`xBk0yen^vjE1>snI6XD{8bi8dmT5S-^MRGv z6c-ZXMQ6%z)^ya?bgI-;-zF{bCbnF+`2HUZk##RS6mp5X_s_I)SC78>a4=AtjsjU2 zVZe^lQFXi~Tl9Qn<@#sNTCc7%(+@Np0arqp`-A03m7l1SkQIN)u{t>~mR443p4l(g z!9!V&|HNA?=gQM00=T$nP&jmovWwb6c_%-{z5oea&IEGX1tGD;&g`w!3z8&>^hVCH z;M88txczyWG&!B2@tq1*m?+|l>3uv`)xR5!badvvB$Zm%*fKRlqX2CQNBX3&i^|JU zp@0I6ByFX5j)nDgbSR)Y#AZxQ_eM;20Z&ob!v167Fj^s5(JkS8may#Ty*0hVW3S{r z$57F3eKV-e<0u}chrDc}pvXb-Be_HqeY@-W(I_ zD+2H^p-Xq;){7K9O?B>XfC&Mmji&rT+gwZPNl|#{Bcu zvL?oIqdrn10}n`vhargd>WM1eAVcq1G|A>YukkNiGhUrJ5Jg(4Pkw?=>Vo__jSPkQ zjFc$B(hhvT&xA{zjGW1=)VigdTkYTBE->$2?GK zhGZ$@8yoQx>FfYG>O54n2ZcFo_K17!*Ci+Q zBXgz2teM8Cfn}vRW)(RvuM^64>&vO?zP5sBGM0YZr*^L>(>|J-IDJTym{0Bw8b{f6 zJj}_{(~~6H2d!uBz+fUJB6CurCMEc~r%1SeAPCY9e3@6u>=^x4;rmN<*jxj5Pv2=z z2o`8Z^ifQjD}EsApd+7e#5OllBEAExs`De@f8+K2+|6=VOJIBCoiL=kQFP~4+hDAH z8F6ewc+z2Zt3WH}g)M6@+}j?pn8Jb+=ltY5Y^5b-4xCNdu6VW;MtuCqZ!@hUH-y{= zW^0*Nzemhloz=8{Fj_8|BP4c3_1soolje(KivNqOa~n+dZPJizV!;jC6?_!goBX+= zESTGnL-ETEVO-Xk<{tf*YQDMmxJ1&T%ycMN_Lr)Hh+ZU>9zKe=ZN$gDBsrFpN5x%e zH-qm(N^1CEAjx{?iEN`OdcQ?eR8}&qq|xDM;cdM9f3Qg~KNMl}*mx zB9^~5mRh`BNQgo~L8joi-)ziAvQHUxPDW`U8@)*3gWMSjkWcUm8|9S+$9KtE4NE{j ztkKrLOW+Dtw!sib4l9wpNvQeyJnl0bCXXqOfyNjlNn34Fb!*ZY!M*Y5`V(O zeBq}N)b6;JBla6EW~y}BLdPyI`_tl%EnlJLE$0g7b+1W@ln>LG!@+;P=bRnbU>v7r z9+ufRqbL}`>X?~?wiFG+!kKu!+fg8kOEzq!cAhTx%h{Rz&dWHul+N&Ll8v3WoCi(| z3RBP$!UorF!9{Sijc8I<2K=)aswFZ<#C%tKbX7$>sTZ%JB5KKDd@s#eQqK55RjRL3 zXr>d4owq?Pfx>gYnqS*ShRu<<$^&J%-O$$pibBD6qT_|D+UBuAAp$xZ0tB6hW2c{> z+c*jmR9ZrglI|1$yjmZ!1PJ(bkPye23NG@OtU*=T6IB-dS{KV}on zBYMLqH!i*})bAhVQplltRlX*Uc33=fj9Q}A;x2nB zq4@S3YBveOiC>Y~9a!Ra^%pLgMaR&-7RbF5aynuYF@%coBVz|BIl6LOs_*kdWd~PS zi!!S%-#mO*TQ61oMi=8VkYL8Q0%#GzBg(ZqqcA###?*PMdj;%bV*!DN*!`(lc^^7gQi*iR1WMc!?%5~^l62KE{>E)O zdj|BW9z@b=lwXZJcr3JaQ9|3W#N!*N>GJL$HbV=|80~UCwT-V0pwBQCUgPFnOO)<@ z{QPKGLV9C)b5tf`ac4SC$Wvc_%ckj9Ho{fb6*8o5lSbMWI<9`H@^`oWjth*sPH-1r zTO%{RB<;DI#W+bmi5Ub=g#e&-C6-Pt>loQ(u;X&A*bkhqFuNomSwY7Iqp|5R%&nXPe+QlN3bRz22MCHJ- z1+5m~)T(Q#4}Vh*dP6^&oh7L+4ziF_|mxx*TlgdxOstB&On=H@|mPJWO!JKs2L$`jG}F!^5{5n!U9| z` z=40ssVmivPtCoIHj&z8`Bw^(MQU!3nrbvI zOAm528k=f=C3PN6gj?O&pg>RnFwc6#zF zbkqJjs~@qAs4qW-Y%FTedzVI1%xU_`|0{!1-O)kehSJUKaCsPOH)IB!DdtG1tZ~_t z7wOH23%+eEkmHo#aTpe)l@l$M)^*h{Qb--_6ke(Huw8s$3>-b;*O{OXf{J}S#=r6UgdPm^A|<;q zUN|B{-}FUNHkfJicDG%A_Q1{n7yra`W@$1njifrhJ-h#Dqa}p2UEi9c`koK>FG^lI z#~try3WeKJ`>gIs&`5_b;$9B?uwX%s+*NbIC}pU+O{fsA(vu$Ru6#Z5g8?qgJ~f}E z0R3kP4Mqk7OYyYf+xtW_jMH?fwoP-qvK@Wv;VWel-F+9xGhW1rFb4cX{?ZJQa}}!Q z6}9`%=`ha8s@#`)+|N8udk*(00-^eM(TRJJje}5RIRpQUz-xjkyo zi9r2eK0Fb|M!N@+KI z1dORIzv7;d|7UDGj?mLh*9ba)jG4Qlf)@q7o%ppbqF+#(=DF}PK}%qE0&|p$;e%_5*DA8U@K%Yr=7+=3+z)-Q~`g23Pj;j8^3hKk{b~Bs}2J0*1|b^ zLNDCT7hQ@9E1Gk5f9uM-;1aXFoe&76VIqg?Z##Q@qYCE?n?Cz^>Dj>7JgPl4bWkT) zkb$W=6MZ6(m8&&!l=RRWt4x3jRccq^0bj#AoV7%tB0xCWAO9Q{i$;)U8l=+M2lEwy zkrXZaF7u@WqjGf61s^38yt2lNfWVoB>|f8po;&Yz_5BKLW=niTri3`_e81)DNPOfM zr8$t|#lINHa1FZ7y&L8K{EVW~TLiO^&B2$fm3TO7+6_ceB0w}TeP6&tuX)G{A|l+X zp?$m2zeG-L(#71UPxVFiX#O0T8qE!}T*#|C`W9GK%-9YGRr5R!^5Dlr*^Hub#oTof zRjB;L`EYv@D~~A$Uyd9HLqjhus^Dg-Q^2lZ2hXW>9SSDDx@r9oQjH*9Cnt>_tdU4l znXhtO&WSxI$nlz-ko%=an4fFqR6r%;0mE;>d!o(EXj9nHn4$Y$J@x59m7x3S+1u;) z&=Okz)1J(G3$>6nOW0cU2gyDBiuacI#!z9$6KJ+Y&wr^yH02bX4LQKuxhkGzP`;{!;u@`utDV>LdcFPAodB z591H}x^N{($-m3|HOxppJ?+j3lS#M_WjF1mhNzYEDG$(~xf4}_A%1|0nuDqX& zEK&-&=_i%vy~u_|A*QwpRX)ua2(1C`1XnOPTxv>7M?P)@mU6K#SxbobPhh+PFD#RT za@VC(&7q5F@s%q|VN| zUlob#)fon(PMzMxE!-4a97I!aC@Z34?=)VY(^{XD@;X)-osoZ{!040dkkS!Gn`UYw z;=K_4y*h2`@M?;7_M}_Ql;#fVZ_VxslUEAwwwLU=14*PXjj}j=B2LXpW3FXA2cv&$ z2_aw}L`Njb>N^c{Jw2R34|Dwv4>NBPB{Sa5-3>gn>1%6?`ZhN~N)ZwnMni!$kY>#) zAL6tUOe}(g*UW`T`I~SDwt^djMdgU{4l2f%KBLCii)(<}SrGZ)} z&RRx|7n717qe6BbayR=|m#2+Aktj&|M_)ccZbPBoxV1ZZw8cwT{E;|(<pgNMk!@i#4W%+m!GT#@3vyhU)25 zntK~)K$MA^^*r#ix*G?{pdlV_UGoNG>(x0bWN6AKwoPeL3Wet!v2q*5WH0Ji$fL$KLpN*-Jk~n2s%l6^^jp5KwL}eZU z!=Rt`UDHzf8K+;gD49HU?OpKDJ5WQh*pI944S~1>FQ}1bii-ayZLO5EFDVPK=~vT( zix)qhl>+s+6K#vCCu5>FP&iyi6lrP}v9{tvgvVtBtS!v! zoMyI)LBcg@O<+cU#{WN3YBJwgbEML5 zV+;BGo$-2L+>dPRQF`doyGF6~XUEl3a+z7fPXG0_i**uUCOgXJPeRE{!ij@Eo z16vn8S(u{4-VCEMQa$|vyxmrcn*%!M6`N@Nf{?rLtGMo*@qI*LhMDU-Sa#+RwOeek z>%((s(m}L)QDcOh0b<%EpT=sOo2eTXxreK^Emap0<(Rb3nO!VWz!gXYu*c^h7RI%<;#>pHqLqE}r_hVvatU ziJKHKghEX|)zz1~N%FS5lL!_axz(G?0Wx~)*Bhx>nZot$enMEPFc<^~1MSAVD^*4Ifj~t&ibKK!Pm$J;)$)>$gZjlC{M_`fryn; z0-^1CV|DS}E+gLK!E8h)m0C@o--AVky(NiP>pj|m@qavPzCtk<=#IF9Kx3<>h6ZgXtL(?57 zdkJcOjzRrZ{%X3e>R*d>Quh!|CF_mcaK3)CwUM3AQGcLRAy=(HKd7mDjKa;^jLyT; z0#&%NGrmr_j|4|Fm0yQ_(9^UZYwXsD1UmjAvN1?=j9F)Wps1_y`FL$}VU4Jw6dxM0 z{(=4}&(yP2`+z1{;;XnBn5 zu-Nsj88=R_NcX}m>+sM_N^{V!4t%TX3Q*C| z(K$vVS)%L=6z(r`N;=kSvh_cy{G(}DT3ji^!bm3qhWcBU!`Ef==MHn@u%grzQDF5c z%fi05VSIz%_NArlzRAJ2zP+s%@9_A7Utt}5X?`}49!2u!h%Wl;+S9~9@UyP;gpEpn zF69Q6%S6RJ`a{I%PQD-FhTt}7dx@p-xeo;?)qF~!*=lyeH9-v9WY92X`$xE8$`a&j zf|oDO;proTM!ZQSv^iCEGco7+0#f(0+7N~3MNf$oUh*la46zIfJ07s^zy40fATUt? zE_zO5yxn@s=^u1h^@DN3o<%0v@(b$h0e*#%SPGGq6$00}u`CwSr@v+wZSYXJv;_p& zI?KKf+RsofIYPBOHD-TU^M*=oo*K+=f@n3zWn!D|x$gTe=K~GSZ`HC~Cq|x_7Ok>` zMGyoK6sX#wB%ydNma8PpZ`QUZVo$?@W9sphOR4NuH&=X1>|DJn-$t9~M&b;Jf_5>N zjIrQ`8MXourr{1W><6z-qb*F5B4|$=eyXG(;I=8b*|SiV`FK>m!SxHmCV68Dn!*i3 zK`z77qx1!N?cR1@V}f1wqszlXx)gW5_?tSN%He#0hJqOswZA5atGEjhrJSgH;;^`d zg6f*&aj%<^!vm%Vva)$SRLeda`o*foQ#(`n36Jz9ES!Ou=mbH}{q)q~$H(#zgf?GF znMOT0DCLAGG77YTt7b6};3!7Yy|9JSh55wEogaCEP%7yqx$zlcc<$^tJ72)`LMuag zz9@N71K}V!jv*M!W^#UG=r1@3d=${~m7YzXy>@PKhMKC#dZE~bbESTj1)$0h!2c|lWp*_BoGV}Y8>;Bnt0_}Uhem7pUxED6KE zeP@_F{xr}~AeqM!ool7oibg~h_9=q!!!hI4vv1#8(l1>tsI4Y3tA}NNFLvw{oKncN zQEKfi@z=``3?55D$eulTd> zRe!mnX+Bki4US~FW5+XBwLn^{nRudDtgF`Ng$b{Dyz7t9Fqo9*2Anu1DzOc40=;Uj z>e)!dffnPTIk*?-Xb9r21g-st17i^XoJk5QjJQEs22s;Q8fYvk1-_d2%>xoNtYQH& zc1HF?610%;!#ht>=||JRw`^!Njbqgg(H?AS^R2lU%F&sW zNANyZ`U(2uJ3q*`{w4)z6RjW2Zj16>rkT?3<4eV>W|gn8FL)vh@K#nTXQ(OtMhs;f z;g9-ehom-C_)Q9truz5W@&L`vUOtm-LeBe*c=4YjSAGK}Aa4a1u4l`Uj}!v{v8dw0 zF`?vxku-9HfIoi|u;2m{Wor=RAHFmBLtHE1AV?R~3Buv^l)*7%;xnNo<-bfz|H~?> zgwc?b+|y|zv2>@L@gPL)Zb={?yCGZZ2Fn@-^iKL4-$&7e3?m|>K<*xJ02KQy@TM1dQNu8?$9&03Ae=oSZT3My==f8LrbaMkLV)J2O zcd3vi`y^dIT3+Mefb^9Hv z$l>zh_>XYnGZ7PN|Cmg@{2^!s6tjA-`aV^UJ8cw<^#5qr33j01#s9&fbSnn?(W(9T zfoT#SXFj(O23WL&&i}YS`}tBYcq6x^{?;bo@DlnAQ)!`0%ZJlO90cZp4K<21rjGz4 zn@pLrR3T`x9dhk$AuknyWzQmhj#`mYz$;pdveUmui$~i`$(1-&Q=PU*j+1h@g#pngZh|5TsJF1@G4v$&+htw< z{a7}@DuE~t4+5PL71<64BEYivVq0Ngq+ZoBK?wJ>zNx3@ahpwkrUWPoN9Jm{u!R(| z#_Xcn9tgM~1%V)7`CCR|A!yUpC$)^lux*gIbAZn9pqw>7T+-rJ?ve!HuFk!X z02RhlVu{&Ys!yIo$yW;)`1C056Nty}%K2AF0jP9 zruaUXT|WVzVq}P{Y`eBnsxs$5%W*rCT2dmJVohxWHy|(X=0Icokn6`{aT{cYLr9gB zN*15bVj9wwz%!f%Vz>jcJ-|Rz2ab{SJETd{$Md*cq!NAVaD?Fi)QA0m2&_CJHOZV0 zQjj*$zk>K(Fc0nGZKOGheCZ3GOqZ?MJmQu8m?seN)`nWn;d+hDviu#08wB=({`ri8 zPulTCu1JZqvlk~3J46MdDIX^(#IIS#<}5u%n7tBZ#j=SM)F*y-FxF&7|KAE+Vc_~V zL5J#Bu^U}8VANw0cqXfzZOQF^`<^NMha}hPY1Z(QAI$*T?-u(1R=iHs>W);9gP0r` z58d4qAJG8k6xu&-S?06X+8>VBKB<#XQ#BLjhl0Q_$K zz+hQPy0bq4zj{OB53Zc%Wi+9M_6$_mrVx>rpK9Q#Wt*m+Tr3xAaR6f&+yobDL?@;i zR*1S|g$$pEBF|8yVY8AX$P25Nqd&ZYzHYEijTB@KQz=^9kzhF-_TR=`rIy1k>!SH> zLXoIvDjW#U46odf4T4t%!ONEbQD(8$IC?w=+GMprlw>Gqm}C%ykv%sV3M7w=8s-VD zVgrF7nSJq4fv*jrg3WS(7DVqO|B=2}cHJ;&FW&YI?}HNq!g)N$dza5y;{Va~6<|@X z&D)CsOUa5z2uMo_ND0#2f`o#k5+ZU4=>`!532EsRSQ-hXLpnu3x}>|izv2C^zt?s2 zu&%q$?}?dv?wRMF^k+=;oDXh(q-lvE`oQ^sQ$C#Z(FMVymKb`BsaHYL0tzjpJ|L{L z$(RM?P_p2|pu zNSsJ>L6&FYL^m3EsV-yG8oE7&o}}vTNHb`*v09+J3&RZ8%y#V09;pX!y?#ZWGKr)5!XtPHTl3B3xUyAf zd>*~(2&4F(I!&qh(M=aCKq^uu{XVv!&I<5;yQ&g$!%=q{mdl+{Onl@!RjMAV-#2gr zMR9Z|wm&4Rok*{i9jOY-mp?=r$|{YN28#xlvLCO9%zVp&PIL&m^}EPaTGg(>n}`;A z>L7VBWEj1S*Q3w3k*BtVGRC|25s%E;^ddeyyc0|z7|g5p>!hDfE^TlB5bNWw+S;SS z#v1)Xrhv&b+FI6t>|38S!d0HINVkW{5axG5dtYc{hiCF2WG6HvJ$G`g7oooS?Z!Ld zb`nz_bcE8Eh$qGuv;vJHwc^ZC-JZRdAzBMe3}JuNU&mtkbXZ5VvbpfkqQo7Ref+bj z-4vhvWc>Jjj@;%!Ad&3QM1Km)pANs_n7O3&EKO-nm(M>BZb3ELW(Z5ji2liE3)xo12@V zScoUqqbF$s3K5$pX%XQ6nJ0z!S<^`($r4spR($$Q(;BVA+uN*g`? zlO@>9*lV>-CPl&LXGg8lOe)nxdGi$y7n&n&sR5Vm4~?WjQ>`pARScOSDX!zc)+6sF z=+u$f;NPFs=YV2cA^rTb*Vi_e=}V5?=*hDH87OX-7akpT6wCQ&vA#Zk_bxiQ=msr^ zff#QmpW*Pg@ja{XmX?-4c7B5Zes?b7{B6VG!^qa>ZzuSBJN&5MEUhiY33_@+p#MAh z_i-nH3qktC%_+dq(N$5c`kFVrtf{Ff^nNa|{a}o9aei{*qE@ZkKi#J>N4n4GgcC2doCfm{a_J9lxm`5BOH48u>ez^djk=arf5?;(DL~=ff0M`X%&{_| zYgsMs=1p-Qe-n<5&k=Ar==ing(QNW>k=4A{jqmPa2Y0l1)oi!un3!Zhk+xFWJ5)M^ zV!x*CT4L{!-vnON&L8p5E>j@EMj#RKOh<>DFC+ZRmoEVU0Y1v|d&K@3a`V`n$EC*8 zG+o%o;XQb_anc_iQ%HuZpl+c1k9R8Zs}3o-_)TWYRXd}*qEFjPjfDQuxqN&QY>KvF zF_4i`jRU=Le83`Q9-O#IsLnQ7YRrUFs1Sk<|~-Y;4(7oc(X{^1<($;`k>H?c9qmZ zVGtPEarp(tA33#7Tl*`SjTr@T9{8az?b3ckp=PZ4Sy)*fC?`BJI^jw3=xw-pH|lQ3 zD}wi*vVyj^>OX5gLZzo%O$zFcsv9-(n$?S2e%#Gfw(ZeOji2xpw`=8+`X(nWALRM( zU~}%4GI7K=vE?b%&T&iLIL|&%?V!04?UwA}koJDfPQqV|!SCZfL1<_beGC0(3@`ek zno~zlkCAK}(d-!&&x_7HvVIj2XSE&YfNu^OX5aoZd{|su(a?eBN@3Qk^%pXgU0!0S ztI||ixzmu#h1YDec=|g2mGQy-=|#0`)P;TMu7W-p#t=@w0Aq=rSa~mMhX<2_VRAXC z#zKS<d=V;J=9&B)E=UyaP!x@Z5mXQn!ooy8-Z>?i96Q} z(_dETX5T{VvPavL<>%+;~4=`ISNaR7AC-^MOlX0}WNYDN|_ioH`!O|Eh%3 zn7)2>V(sweW)!GNn#p$!p?YiM8`H#KAZIwC0aco5Oe?oUku(ycvJWc1B=+(ROuV@N zXE$NaLBLs^=7gGyT;< zZnPsTr3!t-pcp(YE$wIKf~Uvs*w@)sa`JokPxm885B_MCut?{qpnZXVQG7avdh)h=6Z%&>!H&0Ru zIuesa>)QP~PNozoe%YJ&z}FESS=hyojE+i%ONpxAWUe8M*47;# z|95<3q)J4bT)bpZm{+mfvdN$LrMC9Me$_zm?_c_WnS>`LB)^lVs6QAuC0 za4Q-IQeOJwIX~_Aoiy!~bbDI%+uVIhLVu~G3R$zJ;7HW9u$wb3a}!fPOHP65r~>$qQ^9hn!@0w1&RmDsP5CSc~@ zzZ7cZkjFkN_-vK)O{-P%6`5cPdF+g9ccnRr!XG@1bL#aad8VMRSK_cU+HvqRRO zS$BR=^+BwDcKcC_!`i6*u}O64k223{`&Cap*Zd)!zXJo($h*B9L`A&b)NsuPGrWE8 zMi$B}{YxYRR17D|O@?J@fA_amd(&wAbw`?nY_6X+Dw+5i^WmekmLhdjQ#h>(HBp*j zp;*m@SW4TheHHcEa64)0-(|aw^K={$CPHb|l!jj_1o}tEJ;|=Wclh8WTX|l#Het_d zPHuHy#}aj4PUc7!G7G0h{@~@kdOm4sX&uqyIbRZklLP!IxcmbxZ>K8E7k?O3Wwy;a z!`rWWHPQ%BeDSP4Qge5oaD3sBTUU1((j%m!qbK}+#_9NH2Oh#pZD-lCP3O#d_%CCi zkjTz;1vCB|=>HaQFFP}mD0*q!EG)Ow%RlGPCpch+(G~>#d{{Yst39m6eqzr>CHH2@8cCW@4-Svh*2Ib9i_-SwDJnyvTelhBNY$ z;0slskuYj@Q}!pby#~VU0fsMME-&>mu8-E3PL4l0J=k=t()}j$MdrIc5+!-Ac#laQ%K65SJC%h2F|9-}YMd*$0L)wJM5jh@3`AC5~>H5dVIw%A( z{k5LRkGXG=E`dVA?gf-sU!t8p%BpA(k$eskKi$p@h`Zh8GdIieEn94Lbp@@GjEUej z?Q*)DqDnZgD51F3Iv2rMbJQn#dUC?b%6f!GJTg64bDVT9EGa3et@VJmy0{BHu#s}F##s9AV-b(u<^-}9niq6)1POJQ#={h*<9OST?ag>PXg=gN&s*7#LBo_9Ar1vLg+@?y4l;-b? zq8GFC^5%}ViB*Z53+V!ABhu{)Yiey5*{A+dGc;`;UiV@OC^79G|2};#jZ5NIY;oEZ z%PpmvS6C=|m|#*^bJ6m7aPae;mdnFwE& zGD}!fP_>QhOG>&w^)H1fpr)qg?%lh${E!IUBW&;CvHm+az8=TJvu+wtg0%8!0H=5R zP-9GrSR-XCITGLPKRGfPDQ*5OochpjZ?p#AH&ROJ3Orx^A-i@RFS1vg=*L^!R=4Q$6@+;$U!*a&~iXx6oI`Rx8>yNVAo5_}c3(>ilu8Dck| zJxsm-(#034f%4sw?e1pFx3Dm3{c>Ac^(UK#hKBz8W0RmF_tV46g|fPM{@2yi$X~Cl zU)8tHzce+~d}$WT6fiEs95CZYCv%2B1qU9{GK=%y+W`f2RWj3P(b zkDu$KKUQ0;3g?73t3eg3J8?|(&*cy}%HXoe+9mHEbVc9oCIzJTKRbSUU_T-VeT^8k zk3;dUB%dbMDbhM*2pihHZ*nqeJZ^tGank?rSPI?WPEWjZ*p4-S_ak%0>CYN0HGegr zRgvCVR`b{Yy$}&kq2KuuFUTrAp-ANF;-Y`H*vVRO>Ef;@j5s@#6rI&BDlJV%m&u}} z5KHS8aE}qi!pf@0KEyUvqx!^(+9t6!)w7Yf=KF92iS^>w%C@D@@bA3T zTvZ`E`zQWtTOX?31ZjLQZoiF;XOa>z31V*2-mB+HAqOMU%^%a~0TJ8bXG zvA4{=Z@!xbiYbFVx_{YF7mcl9T`_@yMR5CenA`2mrP4b$)P9wtcBx_TPCk`K>2VH+0ht45 z1~|aWl)BQq($YL4#H8z{I|7weAIs@J%I$fqC@D#oTxorFw0&{$A&kzC#5rJ`JzA1z zF4`DrsOS{I5I&MDe?RPVS>RvO${F34OB)J}N^i=2;y#B$9PIOsWMzdvV{5$-YIDt;~I63sJCdI=H z2vn?fYBqtO)?+GVZ2etUVclVE@-u~=i}9Bc51@_FeGvsBU+F;NwTZILMFLSZHEk~Y z9b*JaDy&XJ=aChx&gJP&C;N2OuV+i(fB&}Xk`U}~ff-b7#>yVZaH#qe2e z^muH`nMj+!T}esF>vyx5a6p9WN$=pv7KaBM^~JC36Fb{4qWhWs8#D_m7Mi2=Puj0v zQsQAkD}x@r+W+Jvb21_g$^DaD8SyBwH+NI@oiy5>Qw(`%+}f64;yd&mGVyn^u!&;o znGYP-TrYaU* z!fzn~<4N?&vY~E^OT9*>9HQ~4hV-Mla38{!;Ze<@$2@ajWDNXDoxsF-u`a!=g%V}``OxG~?_5wok4jEr~jpTLKI z5K8(T!g))`u+0oRQuTtGg6`A@Wdfql-_A>hG7*~Hu4bbWuv-dO4fCig0GMawzA zCB}3;T=!fL=7T;vP60nwhc?IRE`$12$a!tj)%Ka6-&Y?#i9CK3z;gT8hXX&t2kU{+ z+CJZ89Ix%0&m=~r)HefKbxMyLyKNVH<_it+`?)axo5dmztd<5Yg<3mL6qoZfjpuV! zdeKVX#xSh8cSZl>GuM(|%(x56+}3MKiJ?TJ6}E?w?Tn{xA1}{_>fR_NvokGjHpdrz zlgo z@aKWO`Jla>eall_)fXEF<>s{J4%iYo_^orHOT$G*AivH$i7Q_G$s~CgB+4c%+O(3M zJGM7aMx{^6GW%f(jdtv78aSN~klah2x8_G?kloXM-56-aEvgq8tM9ybi-YMFGX9v#1O zk{6{NJ88(}ur5??7QnlGjHQ%RO(LSMe=Z&o`<8@DIOZ{@H+3)l2+v;Eip%{Z&$C9W z55D-Ww}+mN#Gqs9(555minYU=_SPSs0tDOP`X#R(N7n8~-5%zi;p5oFG?A@Xo1dJ{ zz&O$>habDOMQ^-B^>QEIJyX^Fk#TXL(!BbAKHuu3_LBaq4dnIh5$j~e`oMIIl8R2( z`SeSNl!2DP2Lq!4X@u}8`c8$oE<;`2f@}18o=gOZIGYGBZhd{SqCxhQ^xi5*`v27e zh=(Rb@U|*L25ThQ%MZq|Y`@keYZ#D5ilG-dTf{WLmwrx)Kv0Hz7q5`VwUG4s;7rS! z)bQE;XxhKu^X)SaQtc1@gqV^{>)j7n#)hvMH~kMj`dg?R;QRYrf6+A%Ts$G2E$Vwy z^k*#BMwf7tP>s8Lv%VE@qH`G81fO=?`F*MVqvUJ+jz>N9lD{TEPGlH!JFlb%8*45| z%A)t;W|SyeCWp+Q@2~yH^wxAE@n>E?<7CGvm-9&Vp3oSg?Ut`zoWLS+iZE*$5*m0o z^|u6HdpaN!P02dd`%N~#LjN(`V>&@j)0y5@+x#YSzSnPOOm9kBUBb8Z&oJOej7ea^ zhWNa}{HKkdD>B+8No4&uMh{W+*n}4RmCN%VX)_`Ng+~+xvD-;jQ`%L+{-%-za(~jI zQb1-9k(Pbuejwewh-g7#w0Nl{JtBWmODFq<^u{@N#C?O;)Xd>abjG0~y^BwtL^`(r zrp%Y8ait{<*$Qg49sQ`#PNJBz98jaB&=b_foh*MtJe;~B`k@a>b%2BE@`^wRpsK?~ zAl7=y*cQ+XG{=NbKhfh%fAmPF#>OI!W}uSte#F@#cCBS`feXi{k4K2{O~E6>CV!uT z*tafFJ(07>E$O1<9KAN)8%LBf$DQp@80ChjH(1S;aZ#AhyzAOQ%9c|%y2VzMdBC75 z0AJrY$4aVdIo(lbWih_JGlPqM5D+VGyc}+a;w&0;p9U#E{0i{9A@{k$kS`{Q?f($9;e<#RO_2= zc6wv}_j&GC$JeP%q1&^KA z^U`@nEfh?1hVx;ht;RWC!WE=Vb_8xQZd(TdnPv zF8omjM(XMHzgl_kXjO-FU_YQN6HDz7QPZB?RTy}9r?MEd!I@r0nzGSf4(pD6%8|_ySJ#VDC z*a89Rqy0ipy_YYK+ZmIEwwvyBer1aovgh5PR64j_M0mL!;;H-N-N1DMp{%Qbf6C{ZSDz{05l?zw=*~l0UL9iFcn2Woq1?ej_~ao{%msQ0+9Ekcm?K zPPgra2QJ)Wj4?B@xu-fnf~aqHth-(>^VbDQGZrs^9w_mRP;j7lH)U6zo0{`hDtM7( zRlu`oBXQBwDQ-piZ12~vUsv6zL995^w;vRgiP^O2r=)-GoUdrsxvXTPU0ht0K}`Ab zV)L>fCugQL*=?si`SNVhn>tUoV&`PF5X-B^_0Z$6YHFg$$ggplA3n?jZsAwyvTs-x zxQy}e^E(acIYKL|lj2VH>t2vjn7X_;1gZOr{^Se0^&dk8T19E)yWI0ChHY4i3+qcE$>$9uSH+ik~`r^XgR!&_$YcCj-^ayWuA%;Z5}p z0mJv_b!$(loKnzeKfdkBq{-xqvuT}LSGq_3UGsF2>Bsn$4opvM=Gus?K2YD3lOb0Q zAnD08RC1*!o+E1N6wp(?D@IuKs3>B~B_t_9|#_!3jfRaUrF`Px*?D_!+f zXg{e}ARQ6Vqst#v|C1nOk5GbGDX(&l=&+GvBV_-R+3CSLB_$<^fm@NdtQgW6)Ee%) zt`#jNdwMka-{zZin(c^UO?F-&gXndA0;ar`%G2#%{Rdq3@>eT=v(ZT|EQoQ3F$?Gl z_n(zj9UQ-8r0FW~6 zj=PDt5=^Obuz32k8;&z{lDm+-?`#aDqUTW~6|7u7Kv$455JwfCt*1p5rhL{qzS!F9 zm%T+b-GgztEd;Ymm2}Y`U3ZpjlT%tJE<5$OX>u;i{h_UKNi0cml#1ebF=@=HT}Iqs zBs%x{^8;avJmrto44Rh?Cxa;Z(edaDlauPp>s*V)k}g?$6pHO z%&n{(D|F}Q=Q}=vO2k;1)gm)T#auY3abwi)4;gqKPB>DDdL(SJxRW1Et&f#aiMSp8 z9J93Lr+~GqUMuc|@2waqG2N8_J>P5fpr~Y7ckUqJ-#EQ>>;@laQ0=sxrTR_Djn@p5 z!GNX_Jw!;YX<$F_+~A^^e*2|6p+N{GX++G8vytDRQiXCgnvcHsGxD47xGY1YEq6fR z+ZQjM1rtYpq?(mJ3);Uwx&+sL();qaZKa=8H%yar6o}0JIQ)5WHt5gM|hv$R{3WN0g4^+rO}=j?O*m zrab%P8MBGvRyHOkCg3RV`~o#PNH2LPSXi)$Hm^HGM@8}eFJNOfm%11mAJ;W7*t8Qk zMguAtFE+ugL)P6xI0+@y){029fvI-u5k4G;#**M%K+)$IRF7JDUk{44Yqt4hP_)%` z;08ziX_tg5jrTzkIDn}}A)zsR%LN`KwVIN%b+n82BFGRdpui{zf6$w~d^&u=1N-m-IZ>3s6^ zYbvv{mO%InMC`7fWi~|gzT!@I4ClABv>9I#{ZLcF6SvxE1CQg(c*_}Pkfv_ptE{RL z6cAWhU9Gq=pnZJr-n}oBg2Z^3l(#?`ikFv{hbK#bci!NBRB27k`6qHqr+*;a4pRS3 zwXuJ%W+rrNsL+j{>`?_#?hFPmW7G@4&IDXY0UiieeDx1yR0c`nhW|VZ_4eKP1Bcp*8hhhl*9)Hdx4M^V9olb00%ak>5*1GJk z2yT>rOHVf*DK-HG>#`{iS7+zr0ZoH$^^5aO&$@*;^Gu~!8#wfAy5*r*x1ky26Q`|z zAo?2h4E(YQd}LOg_7)0yhIWa^N>XE|G|YM3CakLq|8J zW1Kjec3H3Q*8FBkGYGCbjvnS-w%82 zg|Z}0IqD7nk}0`wuTdP3A)>=yds|@AfjGtxQd%MQd8`MAJMI!Zlj{0cDwgg z(fQXLyQN|~nn5o%$Ud<=M`iLE``=rimxTTA<3h2biGR=H_3k{O`HidTWwTNhPU99pGXhJ+-}LdLj8;Z39w2rqf+ z_pDQ{ctgjtPm13+0ujvFGIz9=LVb(|LCuWN>`Vmn5%&537 zo~JSzY-2`KQ^A5_HIRtmP}SX*q3wMs_U+J+f%~`D`8%k;rkr>|cDG19im9NlA4e## z?92||nay9X(>LZr7M(+Q+iOIF*X?UQVQt#Cm_->e%>{I9g#xI5(%k9%fu8)YKb|$x z?Tx=qi8Y&l!ob&_{~>TH3p;goJziWbK1SQI>rkv9)tYU>GdH66E@Jx$AH^qwPm$7-M( zZ2EBJd*UL_RRp%3=O*S=_vfYrtzs$Kp^B)`i`rj4{EpQVo^i5Qk2Qy78RXKGlZyJ# z(wnf{Po<*z)OlzBp8xFKfMQy2pdcg#V|btX`id>+>KJ{l)M900w0nO;JWpx318qL@ zu_@n8`@4DDt+(^6|IKJ0Bi{yn$R2;#%u4M)Am`5eB=_}?l!ptyL|9b2B8RBsaHR@I zP2IXBa&>MLK^0HVXf!8(E4|P;G+YIhCH3}q5P6;4Wxg%?selO{Zzd zR`BL!tV)q*4PImHo&LIgx3o2?s-wxv1(a~Si}i9T1*1MkR)H`GGz$jl%iQWyIL|7H z0{hT9L?I*onS)Hrq4xJz;(d=JQ@chJLiU|G$yq`7Z9By!`w`=+1kx zzZxv~GM5uR`wBe+YzBvO1%`n}=@B_ygV+R@qxySUSv0EHv?nP;F?w)t@D`QG83Ydt zP#oYk0}j}B)C}DXjZ`4i@Te0-&x>)1U;8c5;&w1%x?HKDTo6Ld%mt=a*OaCkj;u|0 zzX$JE_wf5fD<1a_{eNvI5K)PvlqK{qWG!k#24W)0O9LX51(v}BmxBf%XDM4pvn}M7d-?;V1gartnoS}_0V1b3hQnIQnUVr?szKqJ=No;L-5uBdoQ7R(-*+Km*#~q;DM$Dmqwv0}m1OeQ$e-Thi1$@EazyQRL`Px5LAnqYYT&bW>oeY-A1mBzA zciAkT{i0RTS2KjqH~!D20!eerZx(_ac6RmyCn13Mtq>T|p(`M8GVO|)-gmje?4zTj z@SNkzb{@-$2BQEk5kjy5Aa<>t31Gb;t_4WEFGJD5c|PjM-i*N#0#XQcpg1Pc<7C-1 z;r%CFE&Y1=hzD#hi<_pcLGi6nw?geD_mwrJyah&yRkPr1H~BK5itx%nWqXfyy-7cs z5q-f0#qfr%X~bq;#?ig%4mjY)YxnvTG3uwS+Y$p4{z24s0;k|=N?nBRBbGKdtt>3A z0(KVUwYsXQP17JsVHdl-rQWkVPNNpFAP)t54v+7tsUNKTBvJ=*HS4w-aQ~N}2Cxb8 z#Wod)l!AgUXl51`HA~yN*38VzU~)d?M1d%S?}dd{5ZVoH9z{NZbUPo@D@Dc5!`j1| z!zoXYy(PGHtK&I-KwLIt;vLpv_7#J@vNMJUFh6AxagtKYfBejBbtTY=gY;#WiwQu2OAsl-K_sX zx3Z>&#@zHY4GM|y64uRE20BDpMMXtHAtyUKJ0}Oc&z->LxF5gx;a?n|o{o)-JlD_& z?R5`=`4WXN2%uFms4N;Ar>AQBqa=c3Ta32sc$^5x>P|c?)b%hW#eKSh`a)HbR_@Q) zdk7>z$P4Mu(OP#w1X$ID--&{NdvAKd#~iMWlo-@`K-oQjwmRFzTZkYqK7UfgX=rG! zW8xu^$UkeN0InreBjxDtaT&|iEc|w`wG{+Z4Mul%d3kwpvFzPI&giIi_votxfY%ON z|9X%-SeYn$3?SqndklHKL zeDBdhOh?SvCsf~8OkX!`zhuFCjn(ExEz<~~gUSb`FDD4ZY8Sfw(2MOMg;xIBZu3 z^C5=F{P^+XGbY_4!<+rWPH@td7(jz|f1bMgRT=>d@C!E28`3qJzr)r)PEDt>)fso5 zj{f?U3PXaU|JQI{MuIl1sj11y)pcxi6!XT7hdMu@xp3E?;6CrTxO)LR?L2gNyUiIc5%y!kr=LXu|&YWjpvp zd4~&tIXOBPFcDx|MWKXcbFv2RJCD@3^6mbGh)9ls@UzcI_L|Kz$$!z0eY!$CE(*4z z>D(LU?n?wm97G#VLB%LEgr02;`RMKaKq)3AN??^fN@3qN4LTZ4*0`FQm{5v(oWYk} zu_b{d99-PoEacO8?LjcGzMn^^69ia=8E7#osZV_rC07p4FmB+{H z6zbQ21GS&;xVyltsHmuh9nxwUS7bOU9Sf;r&Id27mQL{n_T!n zdt2Mq;i2iu+IYq8az8rO2&!rNVEteLk^~*U5S2S_>X%tgBqSt!!Xs<26EPkuGLkhj zTLy-oh=OA6-@iX#X29O|tKebgQl)6kfMs~~>XojpuDm?9`c-d05fKr+O1qItd)EF$8<>(D zlEconwpZ_7yue1_-Q&qJ>HMmys!DKQh}v~+Z4J!pSgD!132#47Vp!O1Qqs07+NuJ) z@Y}a<-@RigQ6HI4`P9hak6e!1@X+Fv(^NW3ltVx2lSJOG)DEaAE#3R~>m%6T^iPBN zI*=bah7N>9MMdxx0Cf@80C|D0*cdLFh1b!_i91_cuWr>@PdBuM(H*Xj@xA>+9gqgK z$B6*spnVqM%apu(5w)+sbe_C9v8=^MOt06+iBmvJuiF2%WHqK zw|wPqs~pw=03y5+-nNC(^dyU3!uf!mkh=wSJTk+>!)@aQkRn;kUo&#j^1Kt4VAl&sP z0v6!x;&ihoQ4qfSs^MZp7CGW-9$^QWL@_clZcbD=LYw3qR#=2pc#7J~3s-aV)vYaS z8}9YBwZQ_tvAmbuCQ%%Em64gtuyrE*xZiZ~LqjMVo1OX(*ZuIwBwGAgswmP$&H_G# zVvx=G-HoktVf%^U$=D~LD@sN~U$`NCFVfwZNk@`HKp?J(8+M84#Sz^I+13tZb z0Hax5S}J$meN)^zF_Eb255>O_fRParsy%<+Ji8t9-Vv;h+u6~3H8nLQrJ$7#4*lw* zjjGN2q8?EAJZKzJtN@EDdjOVj4C)N&=;(NOH0W3W*Rny2M08T3T8}L_|WK7YU8ibMy1T_k|lw_hP&aeJ?#L%Z5|Bbt3zafPi3O3s4u7P~CTNa@umLh98c7+hUSy;~rZm9O!6k zYrlL6tqJcE5gi>JJ)&!k+BN& z0RevgEcc-(wIf&k#LN3_L|OUyV9?!wJqH67b6VdryUhfEM0-K(eu$=yPVR{v#I<9v zQb6ZQo%~|S)2$`M{ok*EG!4yKv;IuT=;&2DslFDwb!EPHqFAdaB6d#}$18{C`#Uyk zmGJF7*ba7g&Hq)PxRCo(mBB*%f1BrLE8UPZ>GqY{=^t8WgGo6XdV9f}1wx1y@cHvG zB=dH6c5G~H&d$!{KK*HJU4*sTY2BEryM!o*^+g^vfv}Je4h|0RcI}PT)k2x{r$!U~ z{pt^iBi0)l8i1zf;NWm|J%#_t?1Js~ymX|$e-~02U5yP5631NN?XQkSl`f|E`S~hqPkOr4?U;&-})nf#tL3L)ku*%b?H6G_Du%)3qS zB%xSg*T>PF_}JJOh|f|D)7Eons}Wd;m4RIN%jK07SmT%K>emr~pn+uW>FM!=MnUia zDhd4CK*r>jQ>0@g6yKzY@IMTCeMBXJq`BVb(I%@Jslmd=!2!(lCY-)&*RBNw23lBH z==^wh69L;5?qh~qVfsL=(^c2koS0tvG_TDlBJ8YUSm zlGK7h7@x!1aK292WSwVSb+sEH5Xnz??;RX0d()(Wk%cpbjey$bp7wUt-kp>bY7&xY zNQNN992@|&p3@sFK=PoZtc(g;szL|=E*zXM6*;-AehERBP)N=Sc2BOJu8+PWz`1r};CI=BtEX@~i;48h~ zuwp0S@(bDf_wNy6sv2+-&a`TQB-nvS0dm5(vSVYtrC&2ZP6u*_ySux%czD&0o0DK~ z6B7~;)Epc=jg22Cuwt~zEGeDQVIAOQ2I9dku*NTJe$MWU4OFyKqS7iu$TaF3hhq=@CM^}%+%mDABopMN(nfu z$teJgu!at+@XqeePT28K-DV2u{C0IqOH06{?k9Ui#l58eYuEw~I2`+JOeasO;GsG)X(=r&Pzdw?XuME6Xc9MK}=loS<3eAVXqC;+i zO4y~;jSLIR52lk{w|r|I5)s=ozR#E_phMnEtTUL=?d@&wgyv&E*J0LZ`}Ndc?*;{w zm6bJY$9DZwBD+GA#U_DWzjewi;mVHQg~%r4W*2`azI#DPL7|kX9rk{@!52J7Y=tet z>$u3PdvNfe!54SuG)nJQ-*qJ<_3RMRFDI_`IYbOLx>dWoG$Y3*D%Fhi_3&qsSQ)Qm*=UfSU=IzUY_oGYXEr?m3Ef@ zmJ{?Qo(q{jp89y(kUN#{CpPc%RLyWSexCTgDUk${SEBM>Ct458ys@z!*cR}qp)`_s z6SQ~4a<4*-H^@_G+7e?4@yM2^1N+JJ7wvRDp{X%4ZHF+bhz|~s&zJ@%ptO{%?-R;J zN~H?P0}5BzeF$;60_rNp(NV=J%T=zv4}P7PoZ2c7pwK6GVrb^SMO3nJirMRkCAdR z(s(HtQEr5Uh~({)Ij{pW-;Irp-yjnI7Ev*DKs=T}$kAnXZBcmV1{Q7zgzyM%RhR4Qw zV!0RFBNzc8+gn?c0u2DrnA!IHWIsvR6)a1s)zk&VA_0Ydoj*!TiEw;x-@fg6wv9F7 z3{_2VVj=0B`m7w74}{av)@xneabH}L|9_YfDVdoIK>cm+?%qM(=+Ar#*Jk=p5_{v} z(ct89BbDwn%g~=mzRgs<&@{;c{qb&fo??~l;Xe)?r%&8GBPd#mPdStaC5S#J zoxV%BSHH|5GKxtA3xoiU5u#hT>NW?7eRK0F@FYv(*B7FHdk1I^6LcCb7E`9htPjiX~(Nr_IS-7>Jb=!vnktM>DqU0p)f z|LVb$Ls<+)N@;22e<+9-l}?CKKQ$Iw!f8cGw8)>*Ozq5fS^+Hqwi5#A2w_Oc!q|+f ze*Qdwy=S@TJWq4guO0#Z#`9>}Pe9RzKLN~KYinyy!joNi zcm#@!tO7O%Bys^fb;WRgObF{dzqB6u{ks6jXW-)*W>31XpZ1T8j3E9L=m|dHfIzJu zpg3Bu$^p~j-W7g%)R0hp`!P0+PuJ(#p?QeHATmTDZy?0psHv)h0n^qVg~$tv{&RA2 z*!3#ui36WUCd2uL)rVnRM}Xo11m$Jlzk^*du?d0hWDkjq%!KW(!&oR9t`d;-w0-4%^ zEhz$<=?yNo>(!~a@?_WRIcDTUAC>sQbiHo#LvbN?q$#e8!n=?(dRHt>+xG&!TV*qo3Y{Hx7L*aZlTssTN=a4Y7?N(+h--))@l+DiJ^PcPy7iP zAB|s@$!*kX291aJVJx<3^PwDIts1A{@--tPIy5wtqxMLGB`Sx>Kv%aK)&tf|)II08 zFIOV<5gnbR$L02H>%1o8)jB#kIk~HZMMQji>0>4YiwzYqqdzTlo3N*(jQM-nt1x((47SSVvro>xX!le!K805rjZTqopw zWq~gP&f*TEvTmSOh;^#5T%At9~;OOAzrsPz^;{yAjSd?coW$hgzh%%r4z#Hg*` zzbE6jexCUB?KR9{Qy{3;RQhU;39!x$tiJGYE_QQB!PNO6w=Mz z9V#Q+r>%khmyZn!3Ie_y(A?7m{-VrGOoYrAikHuyGr+%;m@f@CjzQkpxVG20M!!{69df6pmP9(-B-0b;O4;Qn;GA>AMi(g>0g(kV!%bV$iv`}@xS-f_k`X0qaC`m+U1Ev>)MNrcQ-gq{74e$HQjcs7=o%~rD^qTa*{mV}xuK0`WJ z-^j?wJYm_6zvnZgS5i^}#2|_4D^$jO@PNv`Ik6g5$^9mRw1K@p6bp{r{4jcI z{{y_erIi&vi$Tf%gv_g0SdqyiBO^V$8C6v-P@V%A!@|Tg=TMWC1)jj_wPbFw|4Bb2 zs!%xZzI!4JZEX#nJxk5NT8#!i*Q*q7UeoSq=!6}tkK9&;SfIuMh-KjGE8@~@yu7jG z%N7t0Mc-Uvy}cULI#KWLC}AmmqwA+lrz;eIaP-4!ot&E5KRJi{`S?R!(8KQkJd+kP zzJqEJWwLj&53W`pKM1Nrj??+$2hCJZAXh?iO9`BefF3QwkpM{%`G2qC=FOY&OXxjF zQ9-%)oRBW&DeNKWh~iUHih-=kA6H zj%sj(G_U7hYHBL*>HyXUQ9rtspTub#*h6yd3IMdYgrQ3r7PVz%k?x&+B+}B-z>*iH zrfwM-IfTBUy7zPFBm)O7j8Y7;1dTH#V&b?T7l390XmAa|$;lZ%FL5KyWB2%&&xrt! ziya_`=kXI(hPBF#RnQ~o+BAuLyIK6cbDUMHni*Q?jR-vL?+CPC( z{U1EyPD-|*)|0s)%K717dP=Z-AMhQmm<~1BfSjq6t6_sA3=w z?wFeL1lV-%Rg##mkG1tC9BR<>KLkvnJf*w0x3aR*l)}u^lyeG_ohI04c6KEpA-!;( z0Z#$MghiX_03)N%Dfo7Xc_Z<%PO_U+PNXuW%HKC5+;1Qt)MUE%wD$D$K-#MkC`|hn&y$)ULe|7*x2VMp zH%%HUkG|ZpD_m<&PNsjuOP#=-m?Gn~{wYs(mrFl{Z!yEd1JD<+h$^Y70(h-y;{3+0 z*~)2=@_RhX_a!Bd%H~#981~g5ltD%Z{}va&aw1lqvPrf3(#(t=QF4qxU*SzAQ=>;m z6e@2XumF-Ik_o^$qYH+LfFrwUT*eO55o{32{o5zeRQ5vjr_UB5!oyRwDf>KP)S7q? zJw5Zk%(dc*MHhz%pP%pdlMO1V<%9t`2bB@hi3QJPlbZ<6m*E>PJCyvi%FS>l9%9@p z$0_y`^s7{e!zUnESb%!*7MtpBB^MoC)~^3o=_^7m>qD>^v7esWbRW+}b380h(Thy8 zpH(^$nPf|~PMiQvj?RfRwW$gH>z9!2VxN3^yH+If2J-kfU7eggJU!@D87`+fSsIm{ zSJ+Eq^?fXh<1)=M|Ldr*JQ41<-`9FiyS_xgUkHH<=%PI~@o>O5OFD&`JRBNdZ>NP> z@=4^v9-Yj5cD}PS^wkVuXeRXP2$?Jt&efwEP-7vzxBTQoxz{x!mkWV%lI;=a?a+6l z5`I&mTO%HJC9Z~1gYqnwNmKRI+p(W@gWq? zWz{Y-AD~WDLwmbQSX^)?Z zeR(I&R6IFZ9uuZ(m2>uEwj~$fi1_Q!QA>+#TFH!?1|6?mRY}Vr1aEF2o>HtCe3utM^1;VrtJ# zs-I&^<9YGozc42V$Q0zxz zOn$%e>nZ-7WXdpA`bdEYY#|N z1KEq5ckt^^FY2-zvKb2x)+lF%`7d7Xm#Ev!2pF19RUE8^Flh4fSn&9F91jkdp8HN& z7T8h}Z{Fh)vfI3wnm6A;^5DzMQ3|KM4LZ@LPuZCdzL+YWh*gf5W(Dw}f|epZ`+ORP za|5$2KD3tpba%WfP72e+&ARWqnCIA05SfTW!fB@`I_$Q}-WP#-C6#mC(u+O$7B+VD zER)#8%_#tF^QL$$ZfbwV@H3%dNL-4#-|$;t{9UyB#8;3j#y?~vr7)8WGgXN=tZxyJwPT;Fb z_h;$)+K6He{!Jrc32Z0o-VZ@^XK`~@;wpmf8Vd1@wsDbl(}v@Q3B@G; z$!?OD#Z!+JyYIGE*VcmBtB-LDy<#Ln8_rt&ujiQknkMrwHU3!EqD!&?XTFBPEXm&4 zvc_?!VrCwxX3$rnmR? zXhN@K@yTnmmN%RjeV~mES%*g#C!vKy7JsUJMT|59=#?{4)8{pznnEyY80{Trt_sBJzDIh zPucn~cBRUGZ%N>E`jT_9LA4@7lSqDw9$~mKnC||!*7u)+rPv%dliAB&TOsDIzDh;8 zZ-=^Pr~3^O4;sWxx)~d5TN1C0xnecBwsz}3J7ErLtwg+W=(;#Bm^%01FpFEXVp3zjWWzga(kY#Zx;Y;8U0|tF2g8Bz6rb z3o0FIJB?w{7v=0uXMzmdc+!lSM9e+@0*POyEgBkgPhI=gNZY{=YvxPAXpxM|(=zUU-@^woifpO%a(Fy zo$E&*&l@Y#F>0@0`%S*F8jV*Fsd;>-MTH#l~qhc?_}uu{bRMpk|=|1>Rl-WV|T;i;@D7EHN*Z-?Qt>$ z{|lDt&?weI@~^Q~J`Hgt#qvLW9`p|+CJ`X&#f{)v?u>P3NnJ+1+pw&9z0)Zawzs;FZIwy@Lb+mDaY1*{mb^b^Pc$HNlfu=?Wa}(F1>#DM$JvfqVtO) zH5zH38#H%%tJxfe{1P$sFxH4$oZ>%=u(7)C`sG@2{^HHCcO8`#rDcwEXEsR}`ojD; zh!N9(i7xv#_qe=C%lxYD(X5&e^78_x6%Q&%5c%@Aw=RK@7B)c6(CzYr$$jrE!|@|C z?Xg8_R!niBP)BZ~BKDctA07W<&x4H?hpvX~e-b*_(}p(N*@Y$L2E`q5WAZEp>O^9t zjyA21dkvmWNfmqQ6GMr#KV*g~1y=6Enk*<{$GB5nRSP#Tud{<_PT2kia;z$*iQhVt zqZ(q*%PVhCCF2K6LPDm1A7))5A=61|5iV7Q} zKfl?{{<#`Jt`>`s4S)yRM_Nm2Z*GjYAiw_qcvhV8mF z;_#nCA-S-ywit+@{S=mqjXK%tqlMZYpK<3TXru6?Ue2|NaQB$z3btCt&CyETDS?X6 zlScyPdnaEgmm35Qxez7ny{pm`H2#E(8x(@;~fb7RWM%@bIt zmo}t|1Q|b9k7lWHP1=lRTKG+IF#nPZ@r-Bb1Z5DBycAg{<-W#ES6Q*FyYu(KmwSw; z#(?Qtjhb=wKQ@xRJR?OQ&hD`n`-+6)S{8hOcK~0G*!kN{e{U=Rk4wBq@Ymi@bth{R zd(;Ky(B>ahWTcVV?q@;Oa&!(=%42d@tasFADAhBweSh&+!2fUof}i5_wQaRC8K_H~ zx-b{Kov@%y7M@_sy!=suBVk=eMTw|5U;VzI+yC@|aLv|h!>;uc3k&UqU+V#mR$Ygz zDXSdnYU@-917_bpx9Fbv%nmMBSH3GW5H+VbMOkgkZF0S9=G50So0;MJy@y4apIv{r zqj&lFdxGuCB)zfUc9Hj7qX-dy(*Q2Q-#d_#6lA@*M}7<*=L2i@krqqS{{Y zqi}M4&}wSx(%qccad2|I>^j4%EC$}1`k8{N?CIiTYBv$@k1a?1w>`(AMI873JfRST zL!ZgBowfh>3=^q2^ZpN|YFz9xd#(Zwl^ZLN-wdp*JwFv6 zcgl{qHV8>1>-63lc@bKy-`Oc>x*Koi%$&h`1h@`4$#TxGAq#1#CJpRM?9hxI9yf>m zdXq~9p*s9JvpX)M6?8%DIc_SGWs7ubL?frZJK(E-{i6C_UU*a#4I1;kWkUS_6_Um= z|Gyo`%0X*ncw*wl%1Xy~+s(V)ST=D=wDk1SQc@`GSmosBg5z=OuH&j0(0)c&cTE|| z&X@&l{fws2KI!o~F$==$b}75$C{HUXQNRfBHP{p4VHs_{l7E|pr3R`N7tVl%V<++{ z#yUN$2V;EDO)I1F{R7+~fI59`#2pAZRJTS-!!$d@d}kYW+8Rtg`fk}p zI3ABzKcC>`qF_E<%X9yFKIVOr>?E=>rRJj6kbXNv;%*4i^DyM*hV|zja>Kx*HGv&t z4TI({iPB2y04$5k^0+v4Pz-dijyHd9lrrn26qg2OYg|`V>2Z0vBNvT;T(;87+-%l% ziCn66vP_Hna`~dgJ)I4Leo29nPd1I!Iq3QcA5OK$Zna9LL^Pv2w4@(I>_7Ibd-Y7S zah0Z|CFH*aq(?e&9%-?D)dA5=yRo>yeJ_Hn-2t#9aTAF~gZ?c21{bMbKcVYE2OA$} zF`+(8fWBMUyxLW_?0ef(8EsDGCe(r_nGb}vO>u0*V3Fovw$IF@L{av!tju`^609YHuY=)4h8Q`Q`CZQI2+< zx*q1Z;>(J(_@-uNkv1-7VKsv6t!c+yXTYnddq|~ynM~eUx*#|h z6noW~8LJJo@$sF)`vk|>T%_N}vgCx3VpW`^LFtb+&)jgIycQ=iCLYWAn8cRPagB;H zs8z1XquOTd2~aq@(?`KUM=BzqA~teVrLvL`A#1fZe0$~5B2ovsaJPi&4xbg;o#LUdhzkl6|hTAEK^H>$H6AwdgVvyp?IeS7j z8yml3(kA9bjlF8p{a*8lOSanJ3~vG%&p6-9a#cMGb0f3nceA0UqC<*_5%iW!f=2}v zJ8fc`@=Oxd*QoYsk@mOGT}71%0vZHw+O&DzAbH?<)AX&cAPy zbi&K-r7Kd6&okZCGkyJc$7{&&XFqZdQ=#uY4!oP4t<1Gw<#4a z^!mCkZ<-}Gr1@Mx(vrzXFHWzxtos$KH03i-y$w#@9JJdu-IR%P%pcx+PPwmUX!sD- zD<$@a^Baw_ zUSzisUp1dq?W_Xtu6x#UZFAYgn{i<+9r0c+5{Ha4B_(rK!_+o=6bRp4tvakBtPNv?wZw~>`3kDr^o*AwAsWxdv?Z~JBq zDd*Ddns$}orV;d~sMu7JcIFWL<2ppbRk3!0cvL++CUtcS1yJP-Yz9M#hJmzg zG21qEUy?y@Rg1gBLF&V|QTL3k=bEnNZ=H${-~4XV-&_@+8Uq@*C3mj9>B8;|He z=E3B}rGmLV4qWRDsf#(Q(PAZU*I0`dzYlM2=GRH4h!Pb%#z~`HTzHou(mylWSUAnX zVPI~vwrXy>uxPmds=Z$-05|FH;TcNtrQ;0t6DSbB#cBQ54JCrOG6{U7Bl^ew| zak!sx;~+HqFQ2KZKc5|{IIOsiU=Wf=n6H@j&mm?<@e$nxRv5pfw0k3sCrEHVGUr># zoe-I-AQ)Nmu@Ft!Rk8OUAj}7Pj#?VxGMl3`)e$>g$GGvT!Yp6di@#KsSLNDH^+b~Q zbFou1`W!FeFuZoLSUO5gHP>-NWdFq*yoOr(`}ny|zvRBBQK^<$*auSx?b-4R2x*qX zlCYv}wSN^eV-`Q(U{z-|x=PG>8@dbz>Xv+?)lY4IY~QK*LZx=2`Q}3oJRCx)m{`r| zSPiG0D+qq)bwaH=M&V~9x7n}%o;{U4Z?8JBo~fzh@Tj&&O}8RtR7yA9c-=GVgtRdq zZ|!&Me5m^EKp}i~`E2M1N>hzJnS5(%AV~R0O`gf>c2fM}rIeGWvF-W==1TdUr2ZB{ z%0X(bz^7&m+R~pIbhzvF9X~aEspwJ7m*;Zk^6VUEvk{3F5OR;*9D5iaA$NfK=HRuA zlVkh@7(;H1cTNz^g9$Q2V8O1ds>>2H7^}fcUjMJR#GPNlr-qm8$+BOX1!I2rKL^#8 z&F#s-uHJ##lCK`qp;LV>8f)6c@j2~HOS|xp?-(!@#;S1R9H+!;s*N4JR&9DbTyHOs zB=tO<)2i1)1CDVI) z6rSO4-rZAviD$00NLOI%e&qG&28uFj)kE{uXs*5mT|j_bu~PP%mW<)T7rkb=U!L^- z7+_WWKzcLFqEz&kV8!dLks_Pf0Kx%Sa>#Xt*wwj~}YM8XDrtdFXV(BFRO6Z4(#kK3~V&3{X$Xvey7hO{< z!L!@#$Gf(3Tkn}fGo`rn&P?uyX&gmQL}@!c@!6rM>t~3!*6eRr5UmLT(pT%3q0|!I zhBi-~ybmJO&t-1&<_ZL0pSx~S4kFvM8{w=~qEFGZ*D~K`Xa20Hh{riqms4q6^(yGB z@6P2hi($V;pQ~nrRFz1w`x!VE*nT@cb4O0;v-8gOZ$7SK@bb<|e|NrVj!tv{G-8oie^E<)0U|9I8 zquu+eDVl#pUIMZh1qs zajV>tIN_VOZ_6tv5C%&k!r{*E-D^8=X%|qsE8al)s~A1! zLPA$M@bx=RYH|+LgJdWUTF5}L11Sy24pBG4FOXvGZf2=(-N{5U*G!bs+S+cC`uxGM zm1xatr1H>;O0L1>;)ohpwk5*^UP_jF7SUxR?H)mmz`RM~4Jza}iXRL}2W6j1EYw3h z)GcJEd)bf^{6rHuIkT5?(rRji!KdIkFN>GEldpKH@o;~1XH}fu4H>Bw`Y7=5n2^2t zp>N!y9wdba&dC>(%YSSAESSPqJpLa4Tyck1#MpQmd0h}g)O3{G!OQwrA3k{{W6`G@ z<7N^32SGuEM@F_>b)$}8WM;mFki}z3Nr=+6Ri!MFkqr)%;m@}+Y>5Ou8P?}3R2f;! ziywo7L1CZ-oU96mYyv)?)195^m*lhhNRLVlX6{s=7+t-79SD6LKXIPiAh~;@pX_fD zG8+{{z=n@ykn@B-ohDBJe}FU37=Ivw8y=+?iE4)z30)fbQG+B9RixEBK-C18T4Gx@}a2(OURJ+EmfQG-G0dk&8Q2rXZs4rPb5uRPqHnIaDyCfQck)CBF08+3CSl#)^znQ3TR z2L}xadb~jAffn$C`UnI$DWcwjz|VjtuU?Hq8+g4u1Fi)L18U&e9tMS{y$h;x@^EI{ zLta+4IlP!k&EK)-?CnAARYZhrbWBVeb~+{kibK<5$^}7_q)#tPP!mJ^I-`!1YA6>K z!mR#s8fkKjdx}G#@Bs!NSk+np)0vz9+n0)8A454T7G^vq-qShX@9XUa`a85m?d|Lk zZ=U#JVKf7EV_|+Ci0S^~X&D&{(76V6cok6ofHcNqGkK5^Ci)>HB!&a1s?G5372+RZ zAVBuB0vsrA8k!6saY5IciHV6&ipO^592(1BqL;vvfg&5a)32&CK?nc}BA~7S*9#K? zYAT?jR+$d~qeu^0?FyX1l3ei3XipYshmuY|@DHB|UmNKPU5dZ)%#1Ka?z^WXh@OtH zqEmup^x^*q&XL6&LQf!uN}1Ku-X#xS>bz9P&6UXAZ5~cxU)}nWPbo3aV)fW^=_e3; zs;wvX!02V9`pEIPuUMdRw7bPpV%P&Wr&d$#7*ue(yTL#f3=Q1^W=j;kA|e%fh@d$% zcAfk$ArqJ%u^Mf!<=&(EJr|g!btIFd`x% zB6=vu$Pz*AlqBLAd-DWrqwpyxMB)2z#m-AU^I=h$Xh3*T?`dUf>QLMB`~)rEa#YeA z5v#0G&eoO3Au}b!1L$fA_lsZvR8l}f(SF65kUd0^S*<%gmu!=P@!MixD5j~9`3tM| z!4U(w_i#6!j;?M_PEK7-4J@$Qni`x3{LfhL{~!XA1#rsQK<{wpj?YT6EAY05^O9b4 z0viCxoG>RvlKO5~2j&|P^mKBF&_>9Dds2Bh(laM0C`gi;Y6_Q9bn{o;u?(fR|1O32 z`w;C=+~~re2>O^=W8gEl|5W^$)H8oI;g_#-=$`4oZ^9c?7mpHWOBAjs4!O1BdP@1>~X5J(b@jw{q`VDSM#6KJTQ6-oTBPT3Mj2_>08 zXa#Kzs7A)08vwnzpnzpU)M4>GJRXJDcvQpYOfNj1h;F~q$@n||$wV^6D>M{49A*d@ zd8kFE#cT>Gm`&2YBt~AyHH2#=cm2K#qJZp16-sgD;eyuBO1kN0WF90Jdaxv+Y^Zm7P@Ik%9>ya<-{uwpcjGiTL;UrZHdk6|%ts%avcW#$~~lNyG_g!%Yffh7r?W^Ztm z+uPp<>JJ4z{uRXka6z@SwJ{z;WCxlN8!M}Wqa$!|D9Fj#4Comd83hE~;cY?$>tXy3 zdklt3fp(qGW^#CPG9g-x-}`o02k2ZK z-gVv7y7P|=BXa4-J)$8`r<#R$&YjDd=^ppE zxVa$gOVz&Ru}cTlp@;K{myf>w47@6!{Db@xdXgY4yo~^wyVXp6O=2QhN(TqPP6#!k+Sr5MLt&I~z$19wLUhiv5(AjKm^Q!YVN2h5%a(F(Iy5FktZ zy?+91F5uL;I5~k)(JHXDfc1mA0xoI5%LgNBCp9&+XBE!Z&sW8z83BnS;m)$lmoR&Y zNuS&zY+~CZV|B?Flw0zM@dVKv~bJClXUMc0C)l1wq4DgAk#3 zCbymfpQ?PWHccEVHZIvJN=z&pi@!Dsva*i?ztrdII}OUObciXP+g)hQ=c;chZRr$0 zV2b{~Ah;&)|1YxptgHa1wg1TOEl;*}v>#+WLhK(N(l!0geZOV$`AQ95M9(-afo|k0 zIRp)XV~g*;*yf(XdNAsjq_%J>YuYP^U{M6<2{_X@t)b8Ky90YKy7k;*PP~XW!FcGsu#dj zvTOjGnj*=|%Ko zgAGDt9?wLS4gTia>`l8+foHx&!!-C~oDIq9)Au7}C11;`sYTb!;0(*=-gshBQ=@M} z&&ZqqzR&H7#R(a8xlDFmkGvtRYuWQ}Xl%B^@2aPX?u0e_<^}z)ek2RakBTb@t{lb_ zUt?L75mceyn0>M=Eww$l_EJlQzJ`BA!CQ=A49&6#i@*=B$i@p)NdkyoJD~KDfmEQI zvv>(JXXC*RMu*_l{vF{xyyew0C`Rsb}f}mGv_B8cl`imCd*|o3(u2w<(x8%XFVNML;7fb{a6)XapX}x(;!Q9Dhd)V~p2z>2 zUuZ5e`%d&#=fCO0w|&sGRxX`8C-2_91Iabgeb3~NhHefBEWoPb$7T|@#UO0`;o?jX zX8;~MX&pO9c>g}uwQFc9sc>);XdQvth79#5D-!g*?HixmaPgyfjPA>zvL`7f{yz+a z;*i3M@=y8S49L{mkCJ}ko8BcK=HXy8TOa1;^Z9pnnK)1;wJ#`dKoy$eu{5=vn-gJb5!`T2in_8>Su%+FMZWLc+jQ10wt z3(j%y12Gp)uF6u$%gRF4qYkB=8FC>LX_JRDM02A?JtPP&Cqg!}s4r!2Xv6qf8i{EG z`;!xFk!GDWjI$0)sn@S(B28Ibtbcu9*;kMI4s(-mhr=){i4QIAZ(3*sW0k~Z%l%%@ zok z^0s+w41Izm48rl!{rpdJ7Qc}+pV2I%+b@NY70 zgYXHY7_WcTUcKhrRo zG=O(aLGjwwb{2AL(Bzuhgf|7DeHT1IWB(6Kbk#L9t~A3}B_$`riM+ME41PZ4VAx{t z)sE`n!{&(zlt@IamtWUgI9GtLo5F1o2_7Er--G%CXpETG@APza4V>!nAejZ9n3{^X z`I=d))A=|K5^!zbCLxc2QAAvO}8hPzB{Lr_l>y3*14e_gPLvdrO_g63&@*)OoB-u`$0rh+`yWB`|9`O0^K6E5pD!8!;Kc<>A79@~I6}uJ0)cH0 z%w#G7frH6t(0xNf-aIkb^`YcUU1GpQ3nk`q^)0zr|i%HJOSWAQ$@%I;*eE= zQVxGOCOX>0)HJwl9&$EF2pi#&h}d5+a&Qm@OG0@9jP+Y&*a%RZ!BxVl$hOd7j)648 z3l<^lUP#xWJY!J)Jlv1N_q^NZcGLctL5feTma3j2rp?}EU;IOtqcEp`v=d^e&nRNq z&M4*Xw|k#su~C~34Bz$r{rMO?idglljOIFS{+X;&*TCKfWlH9!I}(i`P;>;158~0w z7JtyU6@k)ibkqfu0Njcz%gZ2fjXdFV27fP*xz&3ff03mHgRxF{(Opetkp9CjZlDEj zD?q*ndOEn5Wrc@@m>@3@ zqNfie-y;`r$mB2YoBbay0A!q?Cqfw7*pNSXQ256)Ll^X_ARlmcacP7K5K0jU>7W<@ z8GEO&8lnW!O(26eoGd58kgmR@|JuHk0Jl4Juj)}JHap@GQ1Ib0nXTak5#!-K*1ruE z00`mX5y$&`aVr*UmA16Eo56iU;sz3_&yOD>-oOe4ryLr7eyx{&UBR+AFcR#4NfK5- z6xbOYeydyX$)9sGzTji*LFVt$EluqwevCpsm~>PR(gedXHCQ{aQ!qa*DLhkjJ{%Kr z^)A(4!!{W&Ex#Ly!cno67aA@Y$~H5;vf+8}){k<>7(t!4dd5A>m4UBijni7g`@!kK zdK{vSpdbhUkhpRNFgxy!_4L=$)YRsdmh{xrHwU#n{r$(gyHs>2oKme9VDLpuEK8xG zsfnD*hlA(rG>=UdYU^k#rra+|M*#ns6?tZF2@)5R zJS=?mZUa5SRt_}qbC(i0%)@_8zt5--)Y{yyZ_27d$dD7T>~io4joi2Ev(EfB&mswg7T)kkOF~yV-#> zVttH$_BRv)C1QOLDdLiny#AfLzkM7If{~@A07{8`rZcvBy{W1najZIxd*$7?{4TV< zP&Y>@@4cB$UpY+gQ~s2XsYH^$pd3=_M}orEYULE*zDGFY9xh*Iv9TSB{d)MRx-6Dw z>~pg>)N)K@40r6@czNaT`%LG@MFLe#e52wxAqe<*_bPV_>~I zVYW%c3^D5>3p;yNWhEWb+#LP^JNjh)+U-N>08&JN<*FBIX;g8v+xT zT6nAwB|*gta!gPp(^f<^v0Zul#zb2#NSTMJJ_uqbq!}gU64Iw!WXWoy2i8Mx<7BqP~Cf}B5{SnJ-ckZ zR=78P7L8RuXRrCgwaXmLz3$cZ3^O9J|GRUlSNe1E3#Bx+QQ?^*HZl;ysuQ(_CZpr& zH}OWm>y#3>(aIAOX4%LM%r~GBo2_%@;OB>_HfEsOK%2={Re>G~?Xm)Q3|SeBThOU~ z4S5Qeb03Tt```Qw;zR~IK}*{yObut>`QHT?bq|GAGPqs+7YhU%`OC#9Wd+8?v!yr# zw1%<@4ncq>augG*>=&e6U60`xQ5TS4fb(!aD7io`{bzM`98MV!M+XVh`RYRO9s}JG zY(~+Peu|qJ2`!#qVF`dn9PJbY*(^9P2sp1tCsgK{KcWHCDo{|sndbm53W83#2|Rpe z`9e>2PtKR*iEJ5E|7{wWdDh>2^>7Eyiko_LoAM!^e19&j~p2+Mml5Gr^%|ZsuWi6935os&f z{0O_{9+Hvcr$q8Qd2$mr!&^FDdyk&H0DK1Dg;m=^I~V&dl|Y7kOq7fa5Mu=Ev$U>s0T=IaKNi!s6dnByx~C}rqC0r zBAPCd-gb2mA;AYwnna`M^m}^}n`#Qumg!7F$u0fd(57i$6&Fp&24@gK0J*?!37r_} zRCfPlB%)57l4XcV?ci z1s#hSopkfpFYJF&*{|BC6+flLC}l!PVW`2N!D}jynd6X0#N(KwqrBVYt2J`$fr@KY z6Fg2J$hdt1@F|eA@;Ax>DAO9tc_fwaD;9v+PsE(!8zE0>1DgV9Y#>7&8O`JY?gn7l z^uN@fh-zOa9$UNSlZ_H-V5F=b|bM7BKBF9k@5TU5`m^pP{YcKl@JgP z-ePO_^pBA7-h6*2I;_w*{A*~BzMp-v(%h>AIpkhNKR7dC{00_?v$S_ld1^zma&HWA zyv-jhw8`(a8Y_$6>F;`|G98Y5_J$$v<1uGe!9drlOq*8&NM8efPFnmv_ewAo4o{kV z!#hE^ovZ|B4%g!anA|_>1`0(=OUvV%thj9G`G2z(RmjWt~kGNw*}WiY#U_ zWiqWXbVe3>A{%O=e{u2P(A4W!sxT@l^fqTrPhf@jzKn9lir@cd?~q^?_%asB(zM-> zA{vBz<=)r&W`AJt4LbD_cc`U75#dDjl>BQM1eD(;bpUYM=vlex#@I0iD+o zh`>jOi<9u|Ymaw^BbQ{i?L%|v1ec_`B32QPuaW11TU&ZPdjPxqKIe?h$Z%BUo8%{p z8xpYgU}WVhhJP+M46{~isAHIXEpz6|>zLxx<#TR%yfAQb;!d9LH1KMvd>*n%we4c;C^IQ(SY^Z0c8 ztS9$B9?o9=tIo`nJSHF!7|ev)PRf?J$}EHPI&qax#+J-cP4DKn11#f+;<~!Tj)lDK zOVFN!I`zk}-Y0J8`apItrthg}>Z__6_4pwp8(WqplEEJYM43R4192y~A3}RX=Zm(6 z#(e?;KZP5HcOfhHcIg=szk4%!VB#^&;Ul??Aj-UvsH))Hew>VRy$qS35luc;r>)fz zacvWF9NTsX#HuavN3R#`)fpLnGk0)t(NP*Ivl~?10^#Y5H7~%8D!w*vYgL!bE* zuc4&qHh@P@APyOc3^$IF@saLNU3nrsEb&h86tftYDg>mo?)@m&Mx$lGF2~y7pn3DR zKpsQO>4_Bz`u#UiQBg+lT$vgbn zGc#a|ih9OK>knT3myipHxo#za?-}ez^w^acU9^+kMsd^ft{V(C@jMuifp(9v9>vod z<5#k>osgk}w+$&78QL8WYQ#OadN`GzW~tP=??4ds!@@Btd5R+u=LkR%R1$C(C{AN( zz@NcAKwP{99%4&tEBG$Jkva?(c}or;?1m|;K44H~R0^v}$Zf}PpJVxsAvLMk-qDeO zmUmCQM_{IfLS$y~gDiX$ccV$)gDj%ky!U~Ocoekyj&719Q#d`ZI_y_q0A0Jm;1YsH zdF+CCh}_~_yFKMcX9y_fM_i%kOTu%2Br%2{1XU+>aclid<`eOg8#VR|ff$;+jo8^j zdiEbAsb8+o*FMM_drFM;z;L_(8%q<(gR!)@2tL^KpwCUuJv}`InQ7bi?|?$l!`T5! zGg?|OG1%J!E94xoL?##Yas!?b{1&9^=rR{NT@&TvproZ#I?*v7~##XuQ&O?H8BS751U=|=YAW6Uv z0?Rjap9$=>&~H%RZSI_xX5u29l+~ z`~q0Igc%_9gESLF=lv`r z?hnpW3d8J9B4Xm)@qdspY82~xUz|FBNC%^Apk6C%A0HiM^YK5p6V_p6V*_3xo@nP4 zzz)GC;Eyd#F9H*I(BUfINV}B3VejMw4mgEiL6Vnu^VThuPh^0EYo1FKcv<~{Og{bZ z6P*T+%64PI04En04Fx)r077N(rvoFF1TeXPxwgECza}S{W1hk?lA?YNhDOjV0THY) zly1tRC*NT-26(~VC$YGRsFIRr81WH5ej&rnGjUf^NY(Q7YYpp-zcncnt=RnIZx(Qb z0wNqyweRvcIv@V}vAngVWDCGV$D1KIh)j-mc2fDE62<-+y%z7WdlPB!t;ErW+A@J@ zk15U=fFwXZ)4hnjEdm%i5w@P7_`t-UUISbidhYSw51{6Q`vgZnsTUQ@@LZfO@Wdg%&K#$_dv|Va z4ef>oC(6Xgh&m%7q^I7{JB?*wLcGx?!CRO0)tSeIS%ZPssAmBi0(_htJj3wt9>L6a zHW{c$+4O2Fa&tQe2J8W!`f#}W+52cBP9Lq)mWPBDwjRB|9X~9iB*6Uu=zzr67tR2f zl=bHH+6rKH#_iZ|A3w4f%mhQyM|=E$ox;e2Q<&!nr;yTTVF8m)JZbhH(NMI4Nwzhh zld#>n7z*eJjjK?)7+TM4YE)na-j+qJpC#S`z+EUfXVKNUX7}^GrW-l^xXEEXXCZ@vlqP4Y&BVB>vyH?(~2Q_Yf4ol-f z^l~8)n#62_v2TlBMj*_@JWyMHNo``(I`xRumU;UDr)!2s-3odk-$Jvsa>$yO>JwNrC=#CdW zJTa^|=1^aIajW})l-slt$K331vdymVeO7&hVG{W(ae`kh)`}7Dy%4-$55z|8@TUA@ zd93lGh={|7T8EReiKnLOgF{0xy5ef1Dw-AuwUp4ozY|Zn*-d9wCNXQhQu%b_p96KX zM*-RYJ3aSt46BSaRUeb8Z6%FhrVyF876MU%Uqy7X`ppx8z*0S#F5JsH?PNR*b!1M9 z$X$}Y7P3Kd5JbX35}lZ6<=8sn1b^|pi^9g%7VolCqONE2xsB=3nBc1oWs}`1o_5q_ zu!6VD$6~XWo)Nf+=J{ciXsp!>2#RH1i02;Vic&5 z$f5a~+cw$~KjB@5GDhA@Hly!_X%zhqSCzev@C42I-~i)M`T;qYC>n$UQbNv4GRYw42{ zPqFFg;(mk({Ia(AMrsty6a9^F^ROn~NI60o#UmUy64>l>_XOA*VBJ$u+Jix<%kc3J@jHVV8$g{@* zz{SDJx(O5mIJKd$u7zP8ta|K-jeF$e$%%;te^q8B2gnX9|2lPre9so0P4tjVVJFhm zE>o@%WmAu0_U4i^aCF1(Ic#B+);V!9p(~=(P{F2|=ukc2TVCrhUq24~ru@zNo5Ey# zmr+R}*!uDF|4nwC(S}A*Lk`p`0EfVwKX*Vm7!=}x^aLOA8v>A=P1!bi156?=tEUI1 zYLh^6`n|b{HgAG97J>MIpjH|+v?sDx~DM`wgLT za%3bXBBB(cK2Wj%3qqTnL9|yG37!BF9CU&Twkf&If5Lo0IL=Lv@ZX*+dizQqXN?n3 ze4Xu_azDLF?0#)3%Nxfvz3Tpz@(@GPF-Ogxt})jZ)<)b_3`i5TieU5R7T3!-C2mP^ z3J%PN873#t@<{7b3A(&*%+Znp?=`gZI# z3UH``6$LDd0~o)t{ihH(JsoXrKsgAO+#5Fzlai4U1GAAp@&}}(%!IelrvkJGuT!`^ zZje}m!EO4gsuDL~NDZ_f79m-DIp9-MZOZfR5=)qWeegLK#V;P9|C(9Q_Q^k)Rly?dL9 zTeebG?{#aVM~9a-%dr)tMS~^hS65fp*7E9+j~?wnD{13TG+59Q-M^3au7}E;kr39C z6O<+mQjMaxkT3&Fei+az$RW`KB?t%rzWXx6@jg8l(v-Gu>M6keaqR^ z72Lp~5qt@g%Bq~S5zPv$@qA!q0#i3al)dSDJ=+V13_rLVaQBT^sIw*Ub|)F1sEuo| zplo99KcUZgyo;5!qm{z*!Xz{ z?^XcRmVibx-<2=+;{odjFBt7XNcWr{8d{JQfnWK`;-cgY$SrpF_PYD}C;;1hscaJf zfgBb%xFbO+vwG7Sfly%Mv8KEhNXG|#UoSa@X`FMMH2&VLF_KdI1&x_-tz=LKSk}a?ooSm8Z2lU0E z9Bc|}&7qJkR4;YaMHqZ*625a!*f849>VaA7&$rT#)==b*b=0LRO~?QLY_aRhr@T zf?Gg9yV`{!H@)q-g*U(4MU{nHeg_wT646!L(=>wTh0f~Qwcn_g(ILUsEIKlB7_~RW zC74G7CWcpg|MWDnX!MK9PXt%3!o%$;kBJmSrr1;vSZ4_bvsK3Q55se4wPA9pV`Oxi zngRl>EqIHaWcmZD2C#H9&8_{i5MGr*A8UE#3NalQH5%Xx6wKYqo#(V4V=k%u@ zi2FkszmS`MD&{qtF2j`b#L*y4ziXzHe!uhY@*ixFir+TzU{RRQz@wT|`c7x9%}26E zxEYUC(VKvP3k?e5|9)ELMZN;VbLkH(lyonAD#()Qmb70u#E}_2wbU@#2;Ik!a`;5) zSJB!QmV4KX{nQ8Ui=VDednGO}?sKSINv?x%!z8FpPb!KbH9>-Hq{_Owi?41MQ**A5 zarx@lsZ<@bXVygq1j?{1X}Q51u`wUoh}7W|YloMTlIojTf~QA|_miHjjQbLGX13FO z@7pSVgCm?7B6?Bh(i2YWJyVWW70<5*ZL8|(Lm(KuiltmN{24l5CM;){#y{V-oUCAX zie$eJoyT;>>F>(#{vkQVN6nTP_msqUS!Wl4aLs@82noSP*RHeD|Nd2`-K6uvRl(f# zuO6x-Ctl>y2SEggE8Mb64Z zj@nDc4hq1}D!)?OC*oWaC@F^E8)}Ei@Tf+YOYD`&>O9G4WlU?T?_Qc1l?=H}yvG)y1cbRpxyBFAnLy z(yh>Y#{ZQxkEH8T-}b1dKF!Y(Wo_)ZdLjLVZgKumYA8h=umPi8g9(=?KYx>i5P`6WonI5?`aOz6eEf`A4XIMse@`o=stw5V z)JDAYDM{phm=LRdqH9#^p;WVxhlf~q>*Efifj1fB`J;)wQle4OLgmfr!jGO6HPKSp zmg$wjFHu$rPy%v^VJ!z))+qNgP*vE;Vb1r0!y3NP&=;TaT1+o4UV{@@F(xdiU|l@W zy6n9P7j8gnyLRt>45t0>MZru2Yd}E)KbgVSsUFRrl$(o$QEdl3h+*MP3v)Z?UZ16# zJtag$Z4=*8kK>!8idzWWT@?_+L!6RAO}$SRrvKB}szJavg%PvL5PlL! zO&6T^KZ+C2U~fz%q=@`~Q8@sXU*p6hsrfM$;kP-LKn&1BRM<;VNak-sT6dJsd^_`C z5?W{&{{{yKqfb#;`AHx!9OV7NK6)cwy{S&{^cgY%njw*eqgz?3Tk^OaK!krxpyfK6hp zcK?c2HR7lxPtFC*Ke66CN zYeqjecG#vS-AHrw44G=q?|U>KKSgV?4PyVWC9cf!JO6AhmY8Nu*j<%q=6jxrSAvdb zYqh-`PaVQ$Ab=tszSk@*$9-2pWWXwY5%oAqL*Qe04%A{rH3!1Lyd2`cLUFGWc}|eu zeL%H1vVp-9y&VEH-o-2I-Eby7Pt*`o5({Rx zyXofXR^HooV;xRFqv-EX7_uNnb;1hY48kuIAs7b;kvXOzg$7|XVQYQZsX_9hmRA4N zl$7ny0z|>rX0z`gG{&)zjfmPbWPdSQ{b^S(=<3~C+MZ_Sl>1Ll%JuJV2c&M#0JkvB z&|hAA?89;D6eLRQfrCdS!1Nrkr0@MiCXzV*TVBflp4(}xavsE5WTW*U~o{`s(R zuIF1b`-hrS^Xj#7YdWh;oCl>3rZ=n@(F&@~e-tHKd&w{LRNcW%o2!*Tb|bvypvN5< zvp^Edz5(h1jil$_-mj{6Z9kgUa`~w_c{0UzV-Lm95yz-QyGRKP(dOS>WtAY-Pnav_ z&~FHLP{}A&BO)%PB0onReTJMB>4_0LQyrHyh}S={vFR6gRK4l`KBuca6E&1|8^5fEQ>x3^U_Wt}m8(ICEUo-B3G2OE{ufonq^`-xc2Pguz3ahWy` zD@mWekw=rEUCv>3sHS>C<;AYcMXwgy)>>*RylNG+t{1SbrW6C{62dG8oPS{=JRdK0 zQGEMafcrJSiBT`>p|HxS=>F1Azm{l^icfAoFnq1BMUK6$CbcNoYjkIhCi7**nB**%Mi>8Clj{ zb8cTQj6M7P8yg#Y?yl?$xcrq%bWDBC(R)l?S=tB#J5yKnGSyjQX!x{)Rb>`6WOV%( z1cr-q{XSnPx;uG%_OyQXF;330ymsRsNO(ahQx5sxg~*z42?+_osdDGha19QfOYw|^ z^pLO%q8#MxLkpxjbetN=S68GgtYX{ceT-ET+bXrQG@T!rCiwB3-Cy}drH zV#_xdcuKz|awv00I*A@(ohJ4-=s+2q?zFVDK*yAulynssI>tpX^~wKENzWXeJurBm zp@@tBED_SFyBA&Neyc__%Cb{>3h%2@Q|QwCc2B;6J5H}4Fre07a;Un+t>Eauj>;NI zV4Ox@70Yncf>$JZ=^{|kV+;Hpq~4mBFMEQp^92r$PKiAb^b^JQ+mLQPdHNK)v-Hd- z8vGBG&Q1ynRoJ8QG0_A}8ZbQu%W*zK!vhT;#-9e^rS9Sa($MC|d)2GYlohJKfdt!- z-ddq5%|V7Oc0HKz`~ENRQd(p}mAONqA)t3aEoef)ar{|XhyM`b+=)mB-m)nEtF^G8 zA0f8esB zjKB~Q;S#)xLs@=TX%)Wv@d8uvz@#SC4VBjoIv>Wu;#S7K7AsuC<^dF6ZL zRQ=uB{3)lt?FZ%sV?5)w$uyp``phxitveDGschns`Gw33k{rhF5EpZY9EBn#a1(#ubF$WYkkRGI* z`L54YXO+zEQqTmmHHg%Yiaugw3ph7#%#MXrxdSvI9y_u%kYEY}1uYW!27wC3L9sOD zSv)4*R^zCJ1n7K73I=h#f%<{4fF)5NbxvpbZUDv%`JyS+!jWO7zcR62-f^aS1&HKZ8vl;TUg5gi6 zU!G64BVtiNOe2abptD5y$L|O1@y7y75P%D8P6~A^qJ$}!@lCsS?qqf=uZQmU-ysv0 zFe@x7WO=X#sw7BlfLCG;L>?I6uf}#H+}(sp@?yB4urSKyg^i`&(9lrixH+1c^#T3- zFysiMbr45O)4f@YE3OFPa2i&Vy$?(a-tI04Wm zVNPXpF~9t~7pkWxmdwaND|Z>ED?JLz7M`W|DVRZJ)&4+{8u(9qd_2Trm>0(?%kG?L zYtu{B>H6_Yu+VT53A zyOSAS)&L=;eO7Z-*d8kI=M@Kw0Ke?YIA370(3yS5^G&TFzR! zI%z>sQ5moqVjMP98c_EKut^bOnk`M6qe$~6+8NUXg=fA8hac8im*OzFlob6r>+-&@86$D#ZDD99JgKY1YBUCiBw9XS9d{t>MgBBHy>S;?`bersQ z0WXZ^0lXj3EyT#&@Ngn#0VCZj=&2xb{D$XXWS)4T7Ee(p`XnN!48RzCB|ct|=nHrj z@GhDl?*s&z1=`7vKTb z9dS%d?9$a%setRDx}`f#H}Bv*^}vRD_kP=}^UtCvn9<%f;8w7A zs;}0e+Kdx*=m!f4fEhm&k8O*avs4C}4_@9zKuOezl5Ugm@@|Ni#6lJ79uKGHM_djx zOTg~2?rVl-F-D6~BfYuz^cpPyK0ryNLIp2s~4=Sv* zjdZ~9n9yZK79fn{j_=-j##t=WBVnHu z*%v%Y9^Jd8TC=vPBtJ;7q_;d>UE}3BNb52*I}}JhB{J(8FGX_Bm}JjCk&%}A!xW9X zH&t^B{?e;|b~i23_eu5PfNoRowM|N9sB2FE#Epi02~u*K>(@OnhMSBqv~R_`i6yoW zkKv1di)bdI8f`jfCmyL9h?_d-2;oKvRP4uyq!&?;O-M)a#! zSOthq$}lPKiFIRg*iv%p*-Q9}I7ixBpI&K{y1w-DeV4DcY^)!v>$CeG>C+VWrxJ|B zXtJl=I|v=@xeI)ICy9MVFZBxGteuiM_svUPc(veTKFc`oq}NKl-Sw;Uv|ujN;!a|z zy!ffA3jQL9ay+(th;-7+wD_N90`0+dhwS$G`;ZHodSwUshk<^^NrhU5@LZa=ugIJD zB!N`Zf7if^itT>A=_TRZ`vNjsW?9lvZ3kA)h>Kt1(z|iv6!R5GqNmH&GDoKn?&kv1 z>L``(WL`T!V%wsR1j0c!K|w(=u|uiqJhXHML5~Rsv;pY@1mqsRaaLW zYgV{+Em@!Iz4OTr%9n=8g$N^5DjRF}R`kkHzfB=|s0WV_dTwkMWQLYVHG)#rG}p=x zV^+Ym?TW??h$Btnm=Zg424+>Kjpzux_XY>Acy5r5P=1~!A;@ff@*ae=L{q*DDiFw# zF7Pd=f=N7VSF(?e?l%Ir0qQ~4;po=q=;ybEvG1w}@~IZXL~#(NqmWUuv4N4-m2cnF zR{fF2f{8g1SUBJ)#1K3xpV}%Qf>3c_I|(Fuu6uZSHEX(K*C&P~X^wRiVl<|j(aQ#3 z!4w0LWChDGdWv{rf>lMe2crdR8yg+N6-0aBbe;S2=b(^v3x=UatBI7shP8^ySG3wxfZfg13Gqc za&iMi1dS{rP$Hf^d*gon{}vrKI7yLT4+@cjnK(IyeF1A8ZUUYojm#lbIoNY?L6QRz zn=P@bX#&AFH#dh^M1;ua!n0&32TmC{#?PK5VID++7ckNCtxa*}K}4j(vX(O+As7Y) z_I=QC^k608wrFGr9anHejL0;@zJoeqC77q|c_{~nUIA!19r1m5FXaNvdReB| z@7Tv%LLW@%KD>##vicPL03HL#_dj=cO9~6?z4gO=V``C#f&yVPh)nJ%_mgJ60*&T{ zr(8R!s8EID`!iNs%`GgdLk?FD%m7|9@t&zd?aOHl)N^3QU4oJ4gp#yxRUx zJ0HliL?}b0N!*b&H8FI?hqLtJL(Z>Yy-@Pfs7q7~ z%n;>v7?Q&CbLZ||$cu>NBobrrouT*d6Xyd^)G~UGFk^^NK4fedfDaMXK_dcPpeWuv zd~8wWdkCf{u@5Zkyx;6d9sOLJ_MMY8Et(kORihcI^9q!*_t@DOaGZfkcm%9m#&pO9vjv z!%8G8JsoC6sIDQ!69uj5>6GZfvBY1G;8DCm!ZuL~%G(G}S?Ge%;@`W|1zrI_8J{oI zOsfKqb7!#xLyw3#0@`Yjn0siR@_!*ZtZ4{qU132`RCGo-26`tQ1A_}pFFQ0AF^h-? z%oyPyB_->KgK69d-35;zY3VHlIN-(L2H-_74~@RdL$iMY;~<^`JK$}g6+fxUMMq9f z{Np}D#K7NYLbuD)rua&|Dtz#sD&s}-@I8xxav-3B)hERgU2RE!AwjcDc3=w7y4Tx zLqqI(Xl7`->!|-D_)-f~8XOw~*$#&u=Z9w4Q4j@)WgbY>ClFP<^PB%m4FqAR1hf3{ z{Tui_*rNOT`f$VF>gv)mGam&9H<#wBjACR3Y1gRse0(;LspE%sl65ZDJq_?0+D( z!$&a*(v&fog0Mj?83Gv0)-UD@jR)1l0jafZBRiyd1fOn5YHjI2nvNmkQ7!+g5M3Pq zf0a~@A4!)Edx)zi5LmMazas$eOPUQWHqFO$t! z9=`z`H?^S>sL}vUwmYfJRzy@3$KPdWIWD&b>DXzb?b+P-tqBCq@|}D>!T*D(^A~z~ zZ*gBtT;mA=0lcfIR@8kIrRH*{yYp8crW?e^Fw%3`=f2z?cVBQ!z){zl1rOkdd~ z|L*I1;joogn=HdaPeo5IfbhKZOLz`26bGj4v=Q~jG2-2hD9H_KPkl*kO4F`Zi+>Qk zLswPH^G98Ti2TT6ZD6*QAN}c+JqL=u6rCi`eE&dMy~pbEa%V)8OnYqZ8m)NRvsVVQ zoa)^+>2{N|t^<&J$t}JzMN7{8*?!xHgpn6M!cSI-1sTEF(zII5=$(nm^R$HG%7`~@H0=yo zdf;Pf?di$Y?8v7tLqBW&fx8Lkg|+yBR|idPoT__@!`?dE0S@K=7Xul$Q#b z^s40<<#2KS)goHnCI0U1xL-ywYq4Y6X{nDJB?VUpzR#xV-h3pXXBf2>biU8I`ofTJ z)V%BJt3R=~i^kYS3-q)6R6gHEvu18m1+t>^x@0HST`q^`|Z+v~_ zw%5kbqZG^$A#r1s@5PG;4g6lOPl=rGJ{sLvck-&vujZw-9Q`YmVecB$^pYO!HC%C* zFHUE-oxCKgR8h1YcO3ENeQT$}iG1;M3LdLo>zy>S-z$3NK5w6iD+v7OVva4Ngx{Kt zLr&{CsUVj5ZK0Bm)^l6FPW=vaQo=QmqY+LisE_QYqq{bG+bW=hoWN!tOtTerli4oY zg-m!^<5Zl>13$+g!@^c&yJ9g1Wm~te-3}{};lDLC8O?gW^==tUFFme{Gja?W_H}(X zhR@t^@3sp-tMc)<87c8gE=g}DQ{A_scanHqWLWP$ zswc&W6UaKe_M|L@W`ld}wwTvU0gz`z4E{ z;ZZ;|grb~pJB|JVu~JJ*mS26BzMEgydS)i;x9ZWiWODR;Ksy^XJxzL%e=E!N8O{>+H zvfKTx9bR2^47xuqj+YcXj&pvVAZtm!mw8Z4k&1cn+RfsATF*a>N7rji<&DK8 zZqfBH?)$vOA=K7fPmePV`a8z7cm%{}fi{ zSA(w4baHA4ghPVo<p*eprKfMr}?nlQ$|mmpBxq z%4jTS?Rx`;?Et#8uCe|M-85FGh~6+g#(YKNpHs|(#l6SlxeYy~Zw?aRQjvuRGH*j< zqx)!t$?D*z4BT3Bex#2_9QFSGq4_q!8-`h-_2wCBk75e@4l-|7^(L4SZYcTSLnxAS z57_*Y?dDs)E2t~kPBYyi5wuD!j^a zs(meE$tXUKhM)fU{EnQ+y>WEI)o%TU=~maRCZ7qmunQ~YFEPU$DXv6(*EiFqNM8AF220AmmAkYLl~)lJpwAnt72}>a<%a9W6v8$=Ko+mjfwlI zaf7K$9b=Rt3O09lQRd_SJ1TNhI%+naQB1+8&|B<3vULBjiv$DWU@Z|~v&pYCAK%b> z{3>}mAa`~#zbWGJ9t-jWA(9FI43V9SlC-K~znLd4N#FW#YI zLCI`8B?p4AV);4#@w$6$;%gKKuYKBJ#lcRs|@D@UF9a306g0!n_8e6J94> zk6ttaa#d_OR(1IAd3Uhg4K)WrgV$&b+f`aC(=|jU%?bP%J=9J)Z!({`N!$g1)qoulDt6R_m#ncFvm{qo2PNWQ+Q_m6wH*5eR9t z3=BaHwWb??P-yzfu4RemxK2nI%+?9~uw*KC{n$woK#EELmx`Lfph1cI3=}m{Ma>nv zw_+B~D?jP=r&KQ=pZa7u_KprH!aFFPFGNCeNzgI#K1%T4bu$d@2bZMe21d-z^#mlo z_9^$yvuf}EQW?K|Y{jIDN(y6eO2_->RxqaslN1cSu`&;$!A{^cyS+%`B6iLMpC0HR zHzd2y%^75yp7rsO%xTA4go`&->WnL{Z^!@#MEm*YK$_Df9>2WxnHPR*roW~0m`*1aQ{7-M^$)5=z7KSlE8WyJ)v9df0n-6oSzJQHM$n`W;L^5mV*C zm;mEU0O%kg;SDE_K#<9?&?Une2x*omjrYm6ghs=t1O($~9psr-Krj%Z_WnHp7bYeq z0E>|8V5&&A2H*`qpqE|9l zyX`&5`wN5vj9f6#;XDhgO0@JhY;6HYXQAJNX5i9-g<#iP3q@R4uO`W}0Ff>Z2q0xX zE+Vqzx3!i~8wLSrR#sL5QZvm%A3tse2LcgKa);A++vzYRL9ay{;>ZB5Y_&5kG0}?%7w|DPe@H<`EW^$N* z!c3aEc|UNL)<|ClbX=wTn3%R&wAJAh!hZbt$nr7Bkcb^B@HpB!x$7!9`yYIQ4GZK$ z9+sx2&so&z=;<-F1i2MagB@u=8l?uekMo){-Pd=G?A*;!wY9l?oBDS29^y+~O^{+? z3a$b-b{Vo)8ylO1_V9(8#rW>_jyCtA<*%!((eG?WBi@{{nBG_K=N><`WB;x@;DFcy zVL*kcE5Du+Xp=oStD&~x0ptzemoo~QFfM|iq-~~uZnz;UGc#Vw#}htK05>5Ny1Dn> z%NZp+2;e|kT3*GjVm1pt9V5gLRme7gERAnk5!m{F{}vuI3yTeJW)2On+o_=W#86H1 zNi0iXxVEFLW?&)~&1oZyl3=lga1$L$#iAu|1@Qm;BSMu`#pJ`;@CoC_|X`8qg zdfs$jHL6smJ9u#Ur&GiC3~QT3lUgw#)L^;*O$Jx>!@##Ggn_df>#fOB%3EzCC!X_|5LZafo zS~ovP3z?lVcgmn+p`q>QJL1#pzr!ln8?7^Fa;%re4M#&^x0!-+adFYQqN`1|qjQPF zw-EL4ImQyGn|*WPM+)pvC(bO+|Z!TMF+g;`@QZ$Crd=0!gmW`1RDK$wFnEy zmt5yZG-Z|GaDu*DWg2uQ6I$Q1nomG5;Asx6W-V3eg{-{*f@Mqvf+rOg5rNMUV2e>$ zPJR!0T-gWUiXH-TA|>9ROni$mS*2hwNVJS1vOUuWXjqsI9+8NmcC`Cb8rr)gLKmF0 zRtV#;#6)x0{r-#OEG{kezO^7{9t8UT;NiphrKObWg_{5svE+d@fubM+mp+-bd=QL* z5jx6$r3TO-IE4#L+Io7z*PD(5*TTkvDX^6<> z5*ObRJ0OKfT0Dh-tnoOzx#gD~0Aq*C)S9byyTF0OxOFLYyLey z3jn=54O`j>Qw(RTIk|#$*AOq3#_v}buyd!=?{(-TZRk$@_hc89ZzjnHoxcMR6?HuK z!@>!K4$8+|&QjM$UY(a?pB0tRHatS`oLm2R2Mks}|66nQ*BZ+cKgAq(kpjv8us1q! zG|{gq&4jVzNL<@cGks_!IzC)fc2q5PmVK`^b)rWHSXQH3ymEx230@U!3M-(P%``8!ERu9RP3 z1}{xwR;1)w-k;k6FCUj3{`;y-Mf5}R(@qdp;27QYY|Eha&HlXsPU@;Co8^ ze|#3UFCvJ4T4fa+BJr>PJ{x@D0_iaT9r#Gu1J4jfq;uCl%i%r!dllc&Bku0mOjezw z1dWRN`n8IttGvv1OiWZ#()|3g18FY#Cz{koN&1?k()6S& zf%oV@q&fXE8Nb$kR8JKr7JIhLTQzVEiJ`-oZtG_G(FGjX+_HC z#QP_Fm~vQ?i(Fb=^<0QMo#D1xnbUmv@-+4S^fDTu#)ccjZy`(=OW*e{&C)o#uZiih zy9R#cX~<`BE!J0KeMSdQR=8h+f9n)YLcc zC8L~(K>qe>pJ)|54gKX`#1sGa$B(zZfA^N^-Lo|LxYPQB^^1RBSee6U=FP8{%Qw3p zx{N6_hn0i>X(o#ss-IjBgAf*#{MY~0L;I62c z*w{jpNN^Br`Q&b^@=;$1-F2~r>|UjVi_3%i_wAirgwBS2RS9J%u%FQ~FgVN{SUrI8 zboq1g4D;9i-Wo3xx5Af0ob0KMmDsTMaAwSi6 z&O>2nVO-?gp7Mr9mgqwQLNXKwgpM_}w=1$e?k>2*MHfkVkot?#iVBsHIPo-CJ^5SQ z72YxLv30J!&w#X{X>IzZy`v*b;LpP5cguI^9i8T6ZwFw>o&8=B`p@c%d>F*=!Oe*^@aNN(i`{R+Yp?9x zTT)X);U-o7ZdR}R=6P(ak6&8oyT86yTr97}lWJ$0b4e)AC7y9AENmaBuB5B|;%-xr zIrtN{p379yA8X1oc&T-Bd1V!>iYtsWFk*CHUdzNIO_}X6kV0gQi;A7uFS~0O57gal zEiKAP{C?8q5OBsQoPd0Sacb)OchV7>n3$NV{vfr~mZ~Z-76~XNlHL>*4XKSwF3C49 zaneNA4b9fvw$Ef84@4fAufOPmmxe-dP zH(7Qgqf>h+{!s1Nb1V=HrXIdkImwV)gqQai?}r3xS*9a&oawJi6f||*-J@Ox$eq8Q zs?s(zJxx!?IWfuoP>0wM5IXpNv-W0o7c+THdK4j{UU#K*3GeHbk;>lnI;QgnV)Al{^)@eK=;!q)T@AKb^AE9cZMT%cCi zH`Wk2(thCL4I7&y{L99Sp%-C)| zxksNn@>Ez$Z-J(u`La(>k1-knJOt1O&ZoB9(H0gK?O}2?!IWp~4UyO*aoe}4)3o}3 z?jp{)r4`o?%yifYD`?icO+9%~XEAkXq`%)#+rVw$b3Jpwbdq{%mfaEB!>1yb))&_z zp0+*3nzLk2No%)lX={Ubr_$AT@QFRANC|I**J;H*3tbC+m7t|Obaj4?jZOV_6b<}m zb@lGZYm%>0dHaO^RL}57r@wen@#RaHRDR;D9%#m2UgXfI_lGyl&IW-k3t~Zo5}0^* z4`WMft4m+M-L_jPFJH38)IWL@gr){g4#l1eMKNh=BOe$4o9JW}5auWI^#9 zdDUkqF?xN=`zKG>ySTKv(+~XD&UZM*TnB}|>!OIjHHrE@`()L)BCiHUqHDcLmgfK^ zJ^gT_Mjym?ihhnz-e|d~*24pBz+QCV^CMLi??9HXbobiEE46*Pp#^cIXt>qh-K|=l zyuM#EkUYrU%LCfFphS?usOPWpA94|4>ghg4tI*oojk3ti$tj7W7JB6G-;q_t!$Z=2 zqouk!rminH->q?&$Fl!+@)NdAW&?Pr#_P%n)b(iEshShPbu7?6NZE zGoFOf^7rq#KlCgz0a?#iHUl`ru8^8W@Nx zXi_dvPI;H5q>wXzYG{b8>=P6cnsb*Bx!8Vpl??V0G1J-lpX%#dpQi|)r=*R15-;YJ z`Db0BFm~60UD(L>?ELLm$VGQbl;d^Ti?E&s^S9f!t)C3)cPs?;KCfL|JcmP%BM4rt z``mX<<>qp5!^`}u`CE*x=yUZC57!Mjj=s5Z^G3TPJ?noyiO5ccFYun_imYRoT0HpT zb+kZ&@BG^bE_r#}nVIl>=`(vVU&`{a61m=q=oOGCP;lg1_eS5mFIk-&#dl$`Y9=$~ zy4040trLONERVkw9GOaB*Yf*T=jg^>HL$6fW+N+lL_crB=vIlmhKS*92XWS%cOb`q|jq*9GJMr)0(D*@PdW)qmNGs1c|n^5zhEG z5}6qKo0`JAs+;bk_+@Bb{8s(7oEoNHH{rF=6x*9O(n@q&JHMab2Rdb7TJhq(sy_P; zuD0%g&RSje>Cv#I`FThBm;dz^GgKZGUz%8fTuNZEhj~5{D{8H*_HxnS4ygna1A}o0 zZYfeTGG4}%Y}>ZYwzn*UgV5a>y0S>2mqq{T{@!{f<)h+5jvm_DIpqmdsE36OxVJ2R zhvJ=c%s=pm<&`#P(h`0lT#@G74TD&M`htUgpCuUBk5sR!p9m04e?vm19$G-F)nqjyzuMGkmJ!K?ovJ5{G_E9 zSTvtBX>WCQ%vWEOV9eV1c2t4nmDZuq>Ld>3U!%<2SukV)v&hFsI?B4>YkgIvji4aX zxPxpt@|$a;r#Op?y*Prbr$?-A-W0k{`MTw9 z;z4hb_OWM|u_<|bzqw(JcAO&!rJHTRk3NmU;WVvw9p!!gJK`BnpUwzTt;b7vKjo^f zo-dxDu1SmXYIyEK?I#KH_?*X&E7a@VDXGUACdLLPTTey^3yEmc4vh~O85^G$QK-H0 zE;;#kacKJdSGR$yXo+(k(=f|(MnFgwCjC2mW4z+o8?^zWhgpAtoNPOl_p_6*`0a>_ zQhfaR)S^VWec!zpVG~TjGuf3EUb)^SXYtw7V<*H4_JcpBIf4*qR$RVpe*SXT(~KYM z8|x`*(dI!7$y^zvg{viTugcD9^?taPgJ%b2L)bpE`PdV-z#rlnBeM*l!I-xaROl-$ zEv-An37*`@FqZYB+}1Kh79e`@1g8B*bS~?0KmKy$hYnuT>hOt z*XltYo`!HO2YZd@{mwoKT{=ScOYU^RL&M|Rx<&)vhRJu3>9n^P7yIU<75}KXH9Rmm zIrS}Nv&&v_BW&VzqlTG7YE<>Wth)r2+fw-z*&#ityf@A6^kg7haZNC!6}~N-eraS!t6<$6*;&UBP=C#&#D25q>|4$?RUJ}2 z3ZX^=%7dSq+5N-DK^y;_QrU5fM<8vP*azQDv3q;YN433Xd1JL8btSr(ES<{wxwHf; z@fTZtTrcu&J6A{g%Ei!)Y=ZJsX2nAeUH5JWWtMb$p=0DHLRx1UF z<(2JMNtlm)j_Dwh6b_W@Grw^sh#U4jT2R%PZA%6zq?<5pgca__PCe@kB!p6L^lGR$~ z)#r;h#>US45dYEjt%p^i?v=7J~H$LKLyR#N{bQOcT zw;`}ghSeY8gXnu$)BbxU6TeElO!J8nKH@b&_Zi$g@dDBEpFd@6k>|=EiNBrXHAwuM N^9pM6nX;z0{||jwK3D(% literal 52319 zcmX`S19T+s^F2JVwaIR5TN~T9?QCpYn`C2WW82=?wyg~&w)xI}{=e_rXU>_PX+HH- z-@0|H`j?`-1QI+BJOBVdl9Civ1^^&>006KaSa8rke`!+=Kwl8f!cwZRu(0d93Ok^m z*e+t4E-LosF78H7W`G}d_O@p9&L&P~W_HdN_AZwY-TVLm5kN{*NYx|rEX&Ups6zTU> zvZ+T!8cjF=07j&GtFW`p+C7c;{R&pF$+EUPE*(h&v^$V6M%gQGxCgX~I5ZeRMhhQH zUY-Qes|p6l4FFIH3tE2&f$1T!bq6Zr_u zAzjvg@bIV8Pf8gB%4EVhQ=Rt26(__2oxZu7_`mzYgcnmc4Kb7cnk%Vj$wh%=wgdRKl&xPO!%u>Ai6A*(C;|&L1%oCC@U}1 z@{C>!C?xM(J-gV+!wx!nH(4he?ccLhPHr_xYUi3cDvcMWb)z;jRs+x(&aHgv8LVvd zY;5FQbac8HP&LaMdV0Prl$4aOh0nZL`WE5yd&%Sme?mt#2%SR^p@VxlV-?|(l+(bW ze$ELVL5X3M;)J20_SNT8)stAUL1&4hibbIn?c6?R$)_%#65~lQ*(r*Q*OSQ9ilT-TsU9{@^i4Tij6CcqC`}F zAVE-s?>Xzv1sTM00Cj@Z^C*NEu92wiX_F#O$$# z^`b>C;XT8CyXf=(qZ#MDtkOOL3k#1R`|0e~cB>9XNHYDUmjSYp>uG8vXWRNG(5 z-j(*6>guz(M(eV$hGHpVl_RBT59H<7p63yjqL!s$7E{B9YblX-J?9gI{(jni&g@8| zXPE>qE9ciZ7|%HcJQB17CyvV9vC@7tGO9N!-LYPq=41v5HqYcG8&!%iqKy0@nt$>{mmXlXT+_SuBY@OFK339gW z{|ffnJ{S{ImQV4J!*EcQ z*HOQG*%Qr6@j_<%j&&sE6eETw^qw0gw zCgC%j?epX+U6U{;Rgqi!ZIMwKcZ*tl(U8quh8qxW2Z~hHZakw zRftw90hU-K6j8Iq&g2v+V~E}o->q!;fR!@lY>`}E0nniaHH>nh`?wej*mHxFZVe%S% zg88#o<7qvVR6Ed_lrC`VlJdO<%er@GY^%Ah=Pk@vc>3hf<{QIZU#8u3sip|b-{egK zfW!FrX>wQgo0C-&H~)l~`7e+Fe73cC<~BXI8u=0>By@CiF{Qg_A2}C_@p|zBIoa@< z@^YIQht0P8`znT3Q(51BiYprJl3}0CJ_(9}9BPbybgw9)uw@^EN<{(UWc9G&<0NVT zQ4G*{lJ}dddaOkSRq4GfX_rdoRx~G6_~x!7kBwg%iE!WDfDO}97v<5Y6H0(a!NK4D zMn5`00QkV+l?NVsw=5WXLrf&oap97$*+0mQ62QR_gyU9QcnnP^!>+HiXj%(Ezy>QK zlJOJ500R(Tz4~+zm1mnpi(4}tZP?Yk=vC0sdUfh!49?)WBelgfYFFvk+CRp2nsXZ!b4pHmTtWUX)GSke^`jf`IWKZl67&Kl0Ou{d?ugFX z)U9*2-IRIRLEwYeJ1I$1{XB96BA_I5%vqxHmNklRVgsz=ZVv7>NY4;m2nMoRK? z@_@ZcT@`8XuW_e-Z2tFK$B|Ptuh45i^QEwx$R_ zUVBmOqW|{2SXBskPOvplBA;RO(mn+7byt2oRX}JrERBEv4hpYtzjBjkFsKxzzY1c3 zDY7x+Ly6@<2kTb_1D?st@;m5QSfmSPJ$Sbw#v+a^BB>xdro;<+kDb5_0g4!d7T@!| z@Yzc935V@3bYvnJB-n)AhinYteb+QN+S zIcXYOnb(sG4}%4qIrEgmqnuCYQ9%O$14((Q#ejes!`l~9ocN_w>iRx(sFELUQRMZ- z9Tx6vQpZ~@CWZQpPOySbYWqN)=iebuOlT_IRh+<`JYIU?13w0mPKis=h8PJz#Ikyd z^S>MG}Ya$ONX>As`ZxKj)sEm3Cgp&AKK@sHwxkYC|1c;qE9gi~dx zkXr@{A}V98KGHs)v%aM9%FXug7hg~aiNy<}&gW622G`lYQY<5KE(_^pL#MkcF&NGK z=HHd1*=jH{_$k^49ZiUPJi6LQy$&HfR65S$vcvhYzQtSN^9`p>UTptv&n=swfQpCq zHu8NIj+b!0*XK--n(_--Ye6Cj6JSLiv&|IBdT!m(4`Zz5;}CMP)dx;RMo=apX+kPu zxTxBCgy|#)f9v3*5i+M%9cx~Q8#mL-4sC^I?4L{xZm zpH6{TQC@!XTQWg+yA}?^c9}ZZ1)$h=IQi&DhlnyS9?>zM-fi8^Bg{yXq%4*aQfe{# zqvGM#Tt(CAQ!5r>@UgpfT0=`!%T^Ge8O3A`2B;)Qj)1pux?xk`7w82iTCc!=sYMPh z7RV%{)2uBH5dO1PhV_;B)fDwk3ZjG$ch}ou_l1VeCG%qd0i6y2U>O_=`B1qSmG!v1 zc7Jp*H$lk80kJ1TT|CIlX)u)UMY$IR-~j>3VyIJev1lIrBqZhe`F*A=>*q_QrBq5g z)^ma?(c*>h3j=Oc>EB9n=Bx&DKO>aI3M`NRRw?#V2*Ur8sSiO1X1$lhP22}H@1l_jzhE89F8fwVr)(zqxk3dr1O#61P>9;_k=fPz$+#K6Gn+Xe@_ z2A0a)#k?A^ii&(Z2eH(?$(QJ`a^4=Jtr=!;u$i$9-&H#?l=XtYFPElLRPZMH)#cKfkR_<5iDR=>5GG@(J@b)BZ9RPB#GM^pI%C_`Z`~N9+GN_&)p#))>U%#I2Pu)EQBaDKP!VAPP!FgJ z7NUuxx_WwF2?&a3Er@FuP>BIiQnhH(fqRk;?a9!j%*x6Mix5#<0WYCoCp=Zb{SnmU)>&hB>nnpLQX=17-$NSx0&#~S|~ zkes(Z5?H2vb$I@Ekh_`0<>C<$8e8wsNTUmR8c)BC2QH5RN!)R|V^^oESqb*Fos<>i zQAzdh-L?Yf-@ZV{oSLb7_xgA&W6%cx_m`@|%E^e^UVno*z98cdqPr<#xa(1VKVW`H z#Z(v4+eHS+fQUY64U_QY`qf^ zQ50hEw)4X<&Q8BL2<>=7rtlyPO=*qSX0DQq+l{3fN7s)b8~#z*mGFRW@+{BV0c^;{uw;|EIf0}wsrsrt&@lo^ZVOD^1e(b&S#-CRjHC@%E< z6mT6(rC+~F^SWWZ?cFWDG1FPd#n;&BUo`B<&?fe*6QF|3yYmP-MKDAQ6U?eDBlSWK~qckY!qU zit5nMnKVa2KxtSz3nD7T!J#6G!VnWewSXZmq>`QtdSx}jLMk^B%PSQ(_=&?Vhu{Cr z7%f>jT<}E_9WZlJ$=gnq-Wh#oI7=m8X}fQuf_g&TKwG9g0T=JA(Y5%Dr;4nxqR$#6;L@e5z-eteC`fZ zpSyzH`eKi&*zpr0Zp?|cXvT6dnmv-H^Xt#*D0yy?D6MG;OVt*K--8w@lXw9&l_M}; z#BEbrD>jP}h)dQF__VUtND(Dmqxy=LLdeho9tckO^$Ntq=Z&jxs3oc5j|5zt#fO&V z{Ec?r#FVhgof#dzcJj&E;5g_>=W#Ev@QP3X`9HJcKR4dM@Y_ker9WdB&nJAj^~Yw) z8DTls$MK8@hkoD@L;u4r(6Dzu;WD#Z&bFnF7c z5|<3+!u%2@lIrxmRM5EzW~EO~$$}GuQEagj3(+tjqlOfqU9wsAI`lLj<;FsU-kXL* zD*ury7?_{F><=H%bD8>GR8=pOKc}XngM@`fxnlOJLs4Jfs7@17NYPo?o3Bd{l8s0Z zl*hB-Fr$8%Bh!y<8A7$fWf!6EPsuO6aDfEmQY9%D?d}o_hJ!;z;GXAR`=J#@oLE2r z;J-hevkszRzbp5{{gEe}roXlN!m3hWy|u3-SD?B%cPMLpV&PllDfW;%rno_n>$lKz zgnFYgrRY{J{44y62{##>5^q4wQ)41c(|4V{N#(f6h>fhdMl}2{uHsi;&A&>xNY|5* zQR4voEd%wY18>iYv)J!zJBww66DE!k8phimA}P?M@QurPZ~#4N8P>}P1KRGYwk!fj zQwiWmIkx>74cJz;2lQ8OHH%J{Sn&0T0Q{&>s9^3wP6V=&s>rQILq%yDSN?l00D$wZ z;wvY=A;XoAqm*TNwTVgDQ4p%Iw6t^v(?GxxT(O^rqFTrh3-Vs>!JF` zc7mK1ffQob6BS0J1anMhu&cUjv|J}>AZ8^7Z`7f}7%p>vvitx21LrFWpyF~^JAK5P2=>F~GEC!?>2<{XV zyf__*<@0Qcds#hX2xFCtB-A)(yH&7#9;zhegvP>$ExdAP+vT0o|> zFL;i>C!v1zonQVT%!v_9wd5{Pk=Z|a%w1x-*u*;nK5groD`l4?OQk4w#hp;$Y}$ej zFx643-!AdsQ;i4P#lze>A%hm_fuO(AbyZ6yGx4udv~nh$E0^Nj;FA5m*C0xrm9ph{!{37 z>q&IZ0tx_Fx2I)K8UKCpx*v9f$q;+uHl9z;p-cn|;Puvc*Cd-&C$Bd8C;Jd0tU0`~ z0s!J8#|}@VeURB25Uh~QrgC{y4SQ?l5EgE5Dlvas+Y^Bpyw}C=4B}jzWwzq$GCkqlrtsj1&AW7#<+r zl`xdPc*7stu-`~ql!z=?&8v6bG=9*9d=35&Ov0pLv%I1IHsqa`AOvd&8@n~rw^raF zU+`q9l>zE z?pZlQh`7Nb{G&fU&r8k^GPzh-cy)1~O4U-_UDgk?TFvYv7R!RwO`L{TejkmLN+wcq z$=t@At<;y$ne-Lffzn3(f<>!F?dYYW%?7uI*nTda7Ca~1y}xwv+<}Hy>Ie8-e}INv z;|Td&{M1XO92R2P0o^q2!yJU2buI!m^Qb~pYYoq}9F-zrD-QI~8rPQselI8f?#5MA zY>#Gm|0HMz5~`v@X>WosX86i)h+wF~cBwpc8+aRXwdT%(7;mJ_jysLkEJ_ zP;ss}9$IP32BuB{Y`LKIKsCl1<`M@z}fn4Iutshr%k)9_}FmM&YeX;%qibdT$6 zDXZoyYAdPg(xYbw?7OPAdjzKhbhA9F7OA7sL?Y0T>(?w>dIq765O|w;TK=4uVcy;$ zhfpN)vTq_~;nI#Q%nuI3_sfAf7J)gtmN_6VLSjew?Lh_1J4~`rDjVTeKT7gRAg10D zmd_WCVDhLG}m{|DZaBf?7X-MhxJjhWo5!()5g`T6llx z1>TRt%gM^3ilGUU_$~^_*DSlg+*!)zA|Yi6=69^0r}*k~UG?Il1x?`e%N##VMIqOgb)^_9(II- zbIhlriKvA3FpOdr4{^}Xso8PKGf04?Xma0#7E|Jkk&%`L5yu2m*GWEMSYlb&>lYu- zlAHI0?vLW&a--pxU-?w!@o{XS;i!MFp%LNi%3fFZ9;gA|gq-36P*k9!w}JWfqF|E0 z(~okkmKEB`gUWlUUhyLG8H|FMlr->Vuf7Ha-abn;PODTk+YBmwq?^Dnb9a7Geglse z6S7W?-l+fxD&d?#Zqbv{Wv!AzkcOjT&|(FOtejub03@R>SsM-LBxq5px77qWXJb8D z$V^5tH|#{FU&-+f?zM68e)ko=rSvTS3W(|@bLhgcoman|KSRPUl#dPU`?j4KPvVp}#4pMQh2woZ@=}yQ_Uh9m z6l5KKB=z-8yl{nj>fu_4FCE_xpAnXK`6?%qY*atTpk^LB3c5-?m{|#9_27Z?3^{e2 z9M&fTmjy%tgB^`Pv&dGmqY;lPj4BMfmwSl~8lvDwT-Zsg{zpTo1+B#yg} zQ{*@3I*AtuS~P~r-utE9;jGb@U#$Q6JF@Ei7tWCHqNe#R%7!d0B3R7BTq{f>j z1zcgCttDujyRkKzIKLuR3ZLd<^G|%usXOWHZEwt>}l*$`VnoW(DRc z&)2VD6+D%VfdSBvAtLe>GWHACykLXYHN08Ayxn7BTzaJ9=ghSY7ux%y&xCVaa+n3* zj^>z28Sb$DnY{N;ILPJ)s=MDnHfORzTr9zh@`Emw!p8sWVb=qJFKu!?M*qvioC(WT zvY)`>pFqTfMISPk{y0~x!ma{)FU6s~mkFIqz(hW2*ocD1=Wn103gFPe*O&p&>;;O+ zF7sbfz~L|6CD3vywt_Q~)<9HWxQ}<{-?a@JBTzqC8<`}V&@`MaqE5NI3a}Byd3yd! z`B5lvgxGinC^6*{2{952qdO!ie2t~!V!z=yB#Bs{W# zTrm!K!;T?_F%G{$qZ#^bm`@R?{;6>*UU7W1u;7GLDOjoH8g5m?tyAZntU8b0(NzmtzZYB4QtpGx&O#+uLXS**)^A_U2Rf5;*glw zx()2qzr%(Mu;Cp@c-m_V!%_Rt@)kJdR1Wh@aio|JOK z4^9nrGx7NRHtZU7s+K5Deor1UB~llth+7!h#k-!ToasqKC}dWH2Sg2AeWcYTh8B?z zr%hjmXN180ziC?w=m?shFV>}xARz?D3`!3U20dfX)1RFc@JA^XKcM&i9vofo5w!5| zb)pZIUKd8IDjk)na1F=i94$~o05GHlw7m^SrzOnwW`Q545)Wq>Fo4%s%y++ztEIv1 zX@ceZ;$NHBP%pPe;OYOoB&s<;8SvyXhyoL1N*aRJCpoDYrrN@)-Y}1ZyYTwaI&V#< zU75W|gi6tbjY;X2!3Vl-pJYNIMLAl`=?XJB?I|aKDru|jsGX_7=>C-BvzhVnmhge^ z^+EwK!?wuc<}jr3`R6&!-S3adKsi`yz64k9G8zAvJx}CD?R^IX zc%q*q(qKk(v_~!YJgQ)FmNJhDmI{pb^#`=6^agdtt8)*>G1r*AR!x5o7gzx!2?LIq zIEUA>YY-`tw?XYge7-KuEC1^Scw1YOt~f1QXE;tn13JC3UyMHQXLJhKjcfaShIrch zJ%SE%u0C63z*ItL4v+iKBJ6^Cu#!wzuIVw?7DFEWlN#j6XHt`1Ra!O7*o_pOQ#Lc9 z>e){BQEC;--{;RfCEKnKbuOba9Ly}FT$|V^h>v@EMSNc$(!5XUZMR5+(cb?2ahUyk zHar_Ps zIte=bo_Z6_7`wWSW;-?Lo}VS{lvErStBgJagXe2H8JM~Fn7MpkqO`)036Zmn|8Gv0 z(BoRMjH*IUH_-l)c;Pl>y}H10;QkV##JSIxV*HJW!-*^Blg%PB{pawc)7xJlEfJkg ztI11F+)F(6Vsma@x#o}0#`959FD#4enA$Kh;YNq!dmp9&r_a+!qqVuFZSxGgb&KhA z_Kf@OR;KOiEr6(`)@rPuaN5uOd6Ur}3PAc={5xu`pk(YZiz=JdY-f#r6=)I{7K@kW zaFFEp{&KO^WwzWr+3EFwCtx}Dt5VQFRuEKRhYp@KCxYaTclWF{V9>w_o7`Q1&sU=S z?E<>(^n2mp1dr95ug;f$tUuz9ki3=|aRcct+;{&l>X^)9P7r{?+yfbo=?OuutitKF`5m?4EW8m`XUnRt^W`xTH* z3ib2X=R*#_zq3QWIGBFpZods8ZS|v z^rR`M<)u-H5~oSnq`BK}i^b(A&ez*5rt@r0$G)4E@^N8l68H1tCZF<<@8I?sjEIl^ zzP&~xhtuooVf}E!ZFtiz76zd1*ZMN9X6^TU-ENz~VYl&QUE7oa-1vrWvfAwqbT_DZ zwmF`&?|$u)cVC|Dc!)HkT>t~_A6{&}zOrd3AXOpyWW4CO2$vo8c*L=Pwx4Lhr z>FQ?2p%Q+@etzwG2VAW;pHmbZkIWW;R_)hAk?`l#=SQAo@)oVcV{w|CmoH}e&`T=3 z3WqOv^apN5Q9YFQ#o{kh)1G!J^OEL1D_08^!?mk4H7`bF>+q&)Y;Kj5q&e(fTu;;z zMG$JT*kpEd<4QD(2S^s4)fm15#HTr9CU z&xOE&Ps^pTwC3hsT@Mp1Sq#*r>Pb`6Q-NyD)EaUz&6=Iw02|9xV2Oiaknq@y2Vw<2!2$iD$g4N&OA%wzIm;ZjYf1Dv z&EGIE)K%3VPF4$$fC<;Bea3Z~wnziaCQ%+S=pOPrTuM7R>8#2-Bg5P00_hq>^YGkN zrC*_3Qd%wT+HbS#G-UC-2M2WQ+Z%paF{F;~T@PsHiy)Yo7+0!i(2e)hJN)yh;90Mr zKzrJ=n={*htm%2g0Yw#|N0P07XSbMu*z%`KDx{gd;Q;>*Pk`AH3O=;L~Z*=^G^0`oC=F zyXLi{dmKYh7pSRePF>7O3P(~NU9V>H3M68|1m|_yj$F8vFl401g%KiUq$kW1y((D$ zV-Zo^B$r*cQ{I;y5CHcr-$y<7?M?N`w#{t9WqXm6u3%UdL4um;g9q0bFu+QqB|5AT zaOSM+?Ts?W%X~6*yv_9-8XyuHtIXytD=TXxl&4)%TPw*I9vjPng{Z?}Kk%pQGOZ@V z^ZX8bSs}wq%}i}EgqESknVp!}Z{W%($LG!{>&8eVjF~^oXCN97%j-# zToXBq?qYs)PIK>m_2o1)MO6eg8i&hxF};RD{tt=fpPO;D0`Vxt*iRo~yajtuXq{d{ z>aJXGv^8)m6X9m0{f*n(be_|)=`rrSjnQI~^N&bz!l>TkdCjmZ65++dp@d7q-^e66 z2vf@RT;thV^;MT;;v%=}kw#dSl>ut)-d_yCqp1^X-gf$9;o;#o?H;Y|-&E))&gQsC z`QBH71`eE{Bn?l%&v^NQ?|vPR(=dRX`{g5yAdTIuo@yzYKFw)y-*(-t^35rE`||O{ zN2kShdRhPpfS;H!VLm@Mor;9ZEm|^9PDWO#eft$5z&!J7lCoAxMb(mCyZg4=uwIBm zgZUI<6_cgr+OYK_;_;%RVGA-IFrj=-%CgMt4v7-#FgeMDosv7hL0UH?N-q4Hw}{-)HJm zb9`-|FN|Zq(2>17Z6#j(eq1>V{MN+>t>o!4Z}(jOaP;dR1Mz24h1wuxZCyL*`)wG7 zMuBA#m54S3YZT>pT!#*vacZg7`=QJ8KIgc{Lq_3tzSg9(Ty6EdIA4q>0HPCruJgrx zuDZN6s-7c&P$4tJguYj2w~Tj$yc>JhriCSZ&rbzN>^#mxY#*zSOA7}V!hOp-?5LYs z7+%(|lH&^;)=G7iieX(oFQ-46?Ob1DGwAwbajkRN0Rs?$MtXZVUCiQfSDwyK8QF*w z5}dEkIh_9U*nrnH|J3@p{k_h>st}rYvE<>c@vQ(w{X)U#t^I3DN!I5T-EuRKA*YpQ zuZd8ggZrVwedr(0buO_L;k-Coo8)lmS*WPif1WH3mZ(>2#akKRafkvCLs}f|Y&~vs zzx(I-c=Sh|!uG;e;QB7xyhYb(*YN{#n*nS(UN9|`swl{WTu%3F%lLeajCZPWZtLT5 zy`|GrdhLr<9S4WaH^uOiW8D0?{sOMFmzpw9K|I43<20M8YTB9?GZrE8Qc8UD`O13} zk^Gve83r$xltb^1EjM=V1~*zF2wjhcUhk?*9lrPR z_35s=QTtYQ0kIA)*Sm8@x;9^j!nF$Pb?4M+-K?&w;MJl}uigGhPh@QD1c~kDqXX|S zt*NN-#M^W0>5iMhn0a~ZTC7dqn|H>k?&|hm&(QyDWqc4*y-89mTUlDV&lv*>b)dX7 zXpuCE8IF!tb&peVc}nl)@wg&IDECa4cgC;Vzb{$E$;lZ?AB)XufR>RS9)T6&R*?0> z0|ZrlRt;=fuYES`VLyMG6_)(`cKA(e*=}^px$DYiLuJl&tj>0;u*1FLF^wv zhbKK-z3tTTLZA^PWydZp!m!y&>~e`VHv}V^ZtZ-T(aq=5mv(;^uwPzn$z0ASA}b zuA}oZ4b|%E>)YEdj1Dc|$uPOW(x+YfVe4e$@*Rvmb_TXNPwnBRyMEVo+fA%GFYDdJ zSX_P6G_Ur?Zs?D#b8DJU+fjjSf7>a!Y=u+-<{nVWl=XHtRgt5ADc5~dol4=l=e+!W zxj7Bg^DYE2W|aHcmivkSh-T-}T3I9&d=L>lxB_R42Hy;xgz9GlO@;Lb=%J|ws=JNd zzA0?`t5Bu{_dY?)m8lH1Vp9yKU1n{y*uuHSvu+iO&2sWb^Af(0$`da(Q> zK`kbo$#14X#ZL3N_wg~dl^;#WblZ|6%QJy@_``dBV*70K;^}HMUL2rZ>$Pi*dmR4L z;Nvk=6&YZ7XO?=$q|5eW^mM!$my?5!DNXG)7RB#2!@Xp{2!O@s=Fk_NnDe|Jy}0bl z%>ySg$Y|fy+MDgTUP7BqU;_@o;_wsgtE~9^_}JEvdo^{FND)f}LGfDHZPE~Ox@<9; zcGxdHQ1V?Qw%an~{MQHN9g*L=Nu`%Nk$-_F0`Q)Ez;kkd;ri$8!xz2oQ*$I( z?#d>;nodX2koTSGb(uBRJpzzW^47$qV0orpn!R2t0itmqZ`8aqLDagjUt1=RVP+u5 zs5HHzaN=W7T?up^Cz->#i|cv3?`2{c^{>6tbdW`@6vgtCkV`Oo9E#yLWYrq>G4v(!W&w1R`a6>OT^Lu#zzfkg&7)*{KuUllPOK ziI&{Bx1}ekEs4=)1Nyj&#jj5zZ^z$J3F~YB>x{+3l;vZ^@<;o?(BgE#=O(vG-W-le z8Y7JcGox|q{uo@Y1_>CU!|eXvmBreN6Ux3*QaQMI_=Jh>ut$KYnghm za<9hig^#QI%3aHLXN$X{+IWINe%peQ3T4saBnOJHxFU%s>S`p-Ke-DNMC{y|LJH(?3TK4xCrCK3q9U^ee!}1kBI7NJbwAIv zY!h}LWKVeUZ^Wh20DCX}M;DO{I-Yv3;R20|8VhICE4pllt=)O+hS;7~ix6tU;eI*J zic*S4PDxJ&oL*uX2Mh_0sOT&11{dazxTWr=z7Fg^NrKf959J4wiixqq|ERa)gjY!M zWTST6J+EIx_@{gAbQINDmm?R+@_?*`{DDUu-WpY5-%Zl{`Px3+(K4)lsTLJVKmz$Y z#8lsnP_y;#W8Bq`&(R{3?e~l8fsAb*Yx!bm;a%>Sj>gE}kDJ5Y7^AN3oVU?T}FM-w#q@h`gbBSiN-I21ozK^O^a|cO;WAdoxoC7&m+H-$O^-`pwa_CkKkKB1 zGHT%nv8co`l#F?~Nk34g>*<1OplAT+*S5Z!)o0uEXWdS4ei!in+UyecBW!>jR zWgN3m52fzQRU~>tj-QKfcZ>hi@{{CnammnjTO%wd-V3*g;~U$h@BN&`zcv`YPhay7 zfo?8kdeSJtydG@yS6R;+LIeu(FAlceetk&RtOWkmmk+7iPh8st07Jd8C(p|cFO?R< zgdeRg^SCJd*E#f1`htRik!NhT&;GpLYF3>+R{yl!OpZ17=*@Gzb|n8dBPH1Vz(WuI z-!M4neU7?Dj`73iOX~7D`Q6(*9b)$P!5f4*Ym*1L< zE%hW^6%mm%9cxDePY!5GS_#x7ctQZx6dc{LFe!SuDvyc?1nCOC71Xb|xMmnZb(pI0 zW)ZNxl8zb}-;!F{n5C|Fjo()gPbwJ380%E@RE2#CQ;PgST1b>zvBu*?@18FVN^^Zv zF_epvBlGa}rq>+_8)P#j*?yEi4vagA4Hf{FFW~kvaI3)@20UF|LC`dd_ZRBLy#3B9 zy9b!J<$+=D=Aw`9R8Cj-PO4k;cjm9>&dz-~WC#+rs6WDGnM5hR>q9udj11h3vezZpZ%iuIRB_&;H}rN=ytj0#{yKf zk{)J1d+{+?Tb&y#v&hLn{~*)i{P#@ua>}gnM(g5-h<)G#s62D#7i)yH< ze%D-S-m}Tk*Jj0P-()_Va|AYRr|8;j`$2HnT4+vZv7S3v{*bXQ&IffV8U8;Z(O(Ya z9eNF=C!9|rXz(OmmW@d{QOu@hLtlOL{#=^6&@!$qn z{NDQG%Sh*<+Gdg(Y>G*&Q=`5=4UIbgzS$tT2-?81Pu4Z zt&71=HZuimHx&=qh<2na&el>g$xK>TvveJB&n57YOfkRMyfXZS4)fpqp8m1^#sP8W0@3o?U9O><+DQvoV*L32k&%W z9siI?VKk^Szb{Y!q83ftG`v!~!`bpSb6<3RgS47f#{AQ)dGQq4^F4veAq}52^znj| zij|#N`t#9yxN^neZ;F&}w#Se6)u&|3adyu)R#a|E6oI$!?MsM&Faocq`(*=!lut2b z&lV?|lZ{NBCI8Pm6BL(l8NM|4!VPM_hts-GpN~aS=O0nWiCv?5e#4nO?G!Kx!kk%C z&k6#}5A}8Q*ktRkG5@eU>Q+8{UQ5ZJ-EM=)c)&r8L8V-9Cv3@0otFL?Ogi|y6otBR zr1m)_qdOBIa5*ZFpwfIhV;MN?E_d-U$hv3OLARHBu4V62H-C6{1G&vqEt4>)m}p)2 zE&6eeU1OFaRTn0#pV@keu2Y|oknrgR6!H*7r;O3DE;4K=l& z*v53wg+=^;l|(fWre_fRAg@z~;| z?2)l9r<MfT>^`E>(rZa&^G;4qY84D=oBDpw$uf+%92PTi z-j|)*d)Jw~X{`1iDj6L1$7@x?J%PcCk8cSHb5a`eF%dCkH7?T;#SA6v@+}Gp`&{VW z)*dYNKYT)z&bC)?F2f`Ywm5dDx<3^aFGlEH$E4r!$bKx#@XYj4-qj5g&{9#2Oit=` z`8;=c-m=@QI5fA224lYV!VqS2Cu6499xRk~e7*rcr`$ZMi23o$g` zCf#YVoKeGOz3crDBy>C7P6{3uPj>S^z6Fuz_|Ac3kjL%MokN|&%GU$RC}x1ocGupz zeb*4ybl2|CvVs5JC}oajqs4B-S6U6({T=*4EL{(O&rINhy=ih9A@Nl9DTRCLrN@Jq#JY z&E7m)D$oQJh9s0gVGIu^K+U{p80H zl`{>agH!)kK+g0JdcmeDa(T?=JGQih4&J@mB`q>DbKmrYAvS%gH7XE~R;BfM>sGMK zVlDBGC4k*sx9{!*y}v-oq2U{x!}F*fv&S^#zU4T4b3kh$$PmIkc@%}c{BS%kff@px zRoSw|T_U0!HnXYAP3HRN`7lHKBD!k(u!T|XkC%s2Y}gy7?aF4OIVd-RaPiWsb&|1zJq-MRrJMW40oreO(X(>6{`hQG zWQy9#%6OQV!|?&*%_hnT+FYM5A0UOPOS2i#YUw!{Bejr%5+Y#mOO<*|ohT+IW(5*- zTPZOEd$VQT{Xz#Nq5og0ib-gIdE)W$^DR#Kc2px0ee2EfC7Bi&0OJYe#axun&-QYi z(iN_XVmt}xV7s1DtYU$wy^wX1&Xy*7BGRzB@xqs(L$k$*iX2uT5{BFxcF)*a$7R{) z@Nl+T-ki2SdsWi!w6h?>c zTUfskY}qo;IK+RI_@SR7lh3l&KIIvHn|Ev521OWj-y+-G(_fnPw6(wC;)+m5$HwOP z-8ZfuPC5Q?e6XXk4He(lJFtMv4Hf3Px+LWgrjUrxbj7LSu)DGG$jkOmFu>C~ zEhC36HXB1O1R?Ac5v|Mp-!eeB@=Jep2ODlIzq^S*a0-gLgU7yf*ymxY|Hom`wRYfw zRb`o!H85HgH2Pjc03c)X8yXrIK)qto;(K#FFh%beYP=uR?`XrWb7k}{V`n3u&J-0L zt%l;lt#^f`&G&EoVoI6vlmJc8Fa~d?eAmLZbT014of)P(Jm)y0>L$&dxwB4stkzjj z{FACoc6MO-;m<- zpJq_Q7~5TgFM~_ly2*`b&Ntg6Cnv{_9sJ_dAKtS59skuepI=R$1|+;=HeCtg-wr9v5XQ6a|he zS4QZR@`Xv@KP~5rqjEgV%*+l3;Pwc8cEF^M!*}}=5)*k`kFA)nkk8g}C&*L3wTk_( z7hq;gMpzD7Xn8gr3l-oJwL}bAv*kV7opSkNsnFY**zP6;|7!GuKkPceRqH@aU5N-! zyvZg5p~>z*E%U3Ko)c_H90*}MpZ-Sjc|S}{P3eP>@no?=XSKi+wf79oFaUNXXSag1FKE?kUY6zA%gc-Rl zq$cyb<4tm+6$vNmf=?^2&Cv{xT{pg!aRGG^@3eo{K5J8m^2??Bw&hsOhH<)8UUs7x z?5ggE!Na}+UQ(t7Gr#A2t-<40x{tqtMy(?F{QnG1S?T3v^VlF#oZ_>!Q4W|c5Y2MeJs?Sv#8*3DCv$V~B z5pdg`RFqtjBG?JSqu?oCz&p>2k@DP(Q#SFroQb9t=P_=%$O)l)#m@eM@AIFcY~ND7 z`DSMX;8&-?ywu+ldY@&;w9kt+Eq?;C$tfxHT$*q99Hyd#1*FL??KArO`|+vgN}i{o z;UkS`CC{FNLPH}lsOGiVryIjE68?{LGb;W2nL*;!{v7n=mw!XT(`gKoMulG!Zf6QY z89NO13OR#A*>pVm%pSpt(y>mJ8lE$*iI>>Xp+I4LGEc?*AuPjXr4xo4F=_-V??FTuH89kprP56Q$vdSfUTNPYJHnTFC9LQk z|H2&DBLGGuuxVyVcsONtDbxS+=JdKTfVaWImruG_Zg#c>FKRodoo9QmpRyrJ7^eZ7 z@tB|~AWk+uK0--O4peDTm(!5bVS(1n*K)S;>E`_ZZ;FPR{9O^+;Wmvr&5l=gk&X_s zj6hAQQwL*!xXYB=#gNd18j?@t%}D4JoWB`Wh~5L?S|FzY@5DbRp)BnF&+NZfrJ2$Y zZg(@ArhF@(AA>Wj=E%s4bIGZ*QD;+Bu%I1Ia4##(uNchGUhqOSzs=t>bxsIRtAs?-H{YyeGk+J;TG)87r+x zQ^ys-IJwU<9ybv?F8A)Xxc>u}EWvv(R_ir9KD<+*JlL_|=y^^TGP4`;#qtg9N$&)^PkYWAPNWfL)FZo2ZXdqmFfIhhVyX$1fhfrgk)s}^;hyYu7y&x zz4f#DbTpEvc;>v^ zQRwkVxP_}baU3yt2_pXKe_QurXXj`-QJaf?EyS#s4&9E~pe=yZ5?Hw!woiEHCpm(-9k?G$2=%n6^M>KFxC*lhN{}ZsMoc+?6j9dq#Rjk74;@d;CMrV2*r9 z*Rc8jKdkisAqt@Jqm@>p1)$Z5mFWH)l2mvz9ZwP$7+tTor1Nlf9~~*C77?aD!XpbI zqJdNgS`~aUH;)@SbP}QY$QtW}&KybPm+pfOGLQVAUS_j3j$T|8lkt8aYGCV5K#yNS zV%bipsHk98Iw>jXFySFB%{VaN@e{z}U=E4FL4%tqv(?sug^U1-6laSFUi!~3pnj<| z3m{q>99pt`eHj)S`8uO}QagUBZ41vAKrKjgChUdTie`k`xZ(g%i%>z9sG;Tm4S1D> z6)Ej?O$!%FLp^!8SE;3C8?~9tx2D=zeZM%Vt+#Og*AM+IC3d22%l!ThEe%cHuNY%o zn)6g_Y?^x!y&(}LBSR&lx7Ql_Zr|4!k&o`rb>o!37$twbKleR-70xvjqx?Ol^Knm$ zUJGarLaHE3s+g6jsC7^*a{hjWIA7e!`36_ObbLC8gM)0x3X6cI+H+))Rr(>;y*?_- z0AP5;{(V#z_yOzuK*(tDX1CJdYCTbG%n$>l7t1oR=2GBE3IaW?(XGcEuifqm1L2!- zsK(O}JWM_Tf%5rOcM5f=LBlLK0Sw_KbU^6_=nvr&s$bfXeEw@G1c2jMRh{T502~43b8yU{1FwEovz4as<%5cfk{TyEtIGWP{MVg7U|8zT$w#y0 zMsw5Cb_?G}SPKe*Zf}J=p3LucFv|ev&Ce}fQY&aJLpy6oZxvptW@39H7iVneD#r3l z0;cBDUH4y*5Qwi^aY9@M)`Q&KpUfZr---Ip&Qs>fG*|;`8D2>;aQ&S~eFzvMORR zeH*9lXY!<0EW3rg?H7|?N6l=5SQ$cKDrsMDN5@lnLP^r8EIfP_yMscHwStr}N!Z)7 zD_D>2oYcihp2Edl=ct<(bBmC6`L^J`o3POpKUo9;yWtA;^U3k3T`7JeSA&vu+^swvusk;l>dFbC* z3r&gJvZ|3PZOCF!s<~qwuS0+|6RN8LGJw1(p%NN~F*||^9K=?6& z6NYr%;(&>qUl(Q8c=v?Y|2)PS2f5`PxTEg8DpPOaf{!0!SYCqnvm`f4cVp~NNQg0o zrT7tv36HnVYD``i+?~g>31gnHim~rc&}1N>QW(CG9$o}PlY zZEdlPmBX3pEjGap?7^|`B?J}DWQ58N+kovKLbH6go15UC$a|E}EwZcUTKeX->A&L= zSN-yuqZwZNrl@4{e=70Ix2-IN`)&$;ajUm8j-%7| zdz2jOAWT=3<3*Bqil=x>IdNvaer2Yoq`Z6k>iL*-XKih5ZtnVzKmr>Z8>U=v$wfvK0dFxCY)*L)sk2 zB(EUbzA%BFqe4QFIlYDXS!Yih4wevI9` zZ99|ci-t^M#}6EbQUJWsdno>G8PZw7lxz0d9jPv?e@QLyZQ0-4cJ=xZjxMi!)O78~ zcu((elB*aIR=k2}MUJ*AM^T#2K*ss{P?e31JVZDTr(F?P__Pav{_wxdY_~rDwxTgj z9__k6cPwevFCQ~3`A}@3d@Q|I)0e$T%^vQASh;>iCFZp0Yhen^X+4V!sGGUTvn&$| z7HPX1o8uKhwGnrRTpt-b9?s~uosG@icp4;Q%9=$c_8;Fjw)|7Cv{y-B+sPjs{B*uo z!>27-8cQyd{$DXzQ$G55-JsILBxX@$&x_xfQcmlX>lYen(Tq4tDM?p$sI^w13>X|Afo>rfC((ga_eyiwGUe>^jPZX=SHDsc8Bd; zrN{Yprt_%iQX|-FJIzuvqSBh z4|Dk{8#<@M?olBgMJ5yexF5fFjFTG*g<_ z;Nm=9(VHrE48c1O8%}jC(;NQodt1&~H4$aAaJI$Uc5$YUC$;kPs;O!9#uDK4gzX%O zUi)5NqE=yuiYQxHD|8fy!sWFRNn)fQ`{+ANn-7Wx2M2AdIynXP)q^Igb!VxHg6rnZtn!#1;~N4_*gZHqj`{XXidorywJiwd z`}1&CS~J^qYm2|~W}h3T8u8C|nL*B~=uMyxhlFkSOUkg0!+LWH4VpLSlNpaq1Iit) z@MYLtk}_f2-;;^DW6!*nx)IqDD|j|;sNa6` zC&;3ZW)ZcX5R-kqm>c{H$g(($BwT+--ludxHod?mSJM_0QJohj{yNbwgf6d@S0oXa z+)_;1r6|eEZ4P1Ix`P$iJIRyDZmf5rkNw!D4;>ud3oYi|u%k3_*Y!w?kWUUfe}^>0 zw+4h^XJ^pHUS88ok1k_P?>t%?GvG>D&S!AxmGJ&7&o?uTL8vOx)b!Kxg`P&N5}0Pe zplW=A(!~edz$x49p3weFA3Lv%D9#b^^oC47dGD`06pIvN_Ir+u_#?1RY_Mxi@V!YCvn z1M=$CtAmx+^_H?K@54*s&>d4qo9hBA1tFb8|DhY)aj61@yh#WS?j2uRvD^%;dzrcB zAoA$GDw-h#nFTY4X&c!t)qWlFkwTdO0Cp0fmO&{d9UF~CWu1Qc6k;4WIWyEt$f_F?6;4B0l2oqQs?jWzN*g zwLB&(_hUA*1+9gENtLiPygLOC_w1I6iHgtr20&;ZuQIBR`JEIDm#>F+#nAdcRLl&O z*`iJl;2kqvXdwqK}so$70X z?Mm&nq@|D_q@%_;2{p5(9d%_+R)DljE^HnQy->a948gOG!HD&08J^A+-Kq7##_<`{?S zd9bm=Z_K48$UijHgSQXdw9;rj^|BM*3HQA}#rKwi_m6g&umE1(@TWu0;?cpSr*aHk z=CY&mdxM4h)z)K{Tv~Cr;kL8%G<_4~s1b@Ox3>08hyT*y=-AlU$cQfN!qdpm(2$Cn z8c>guBrjl3ps!Cd0btWJNdWl6Q&iW|A|}kM56x@$yj;g42{I_SxB4db(I4A;ivZ-S!#bAEp0= z8b=sP4Mq`TUc0A(UT<_t2eK;y~vk5oqI^&`w#5#>e}s z>p4Q{eIPe1(XXf=aP{kL-vG?(b|M>wn*WG=FjVjCc$n98S&j^$6RD3RR$sPsU;FM{ znXJ~mIWyY;ue^?uybRtaIAkUwK7`Ky)S1R3EBMw7nGC7prQBu6MfN4t(+VQ83Av>X zn*-HcT6bMf4pOE$EJJ7==2xRPj(ian_(gDmUujb)s3ralA~4&h0lci*9u}J3X>>Ah zSDSZ4Wk7nJN06pbc)5Yosx+wEPSnw$l=Qp+I8$fm z=K%I$DNEEMNh>^8q?yeeEyCoPV@Sk>v}tK;dkB!uf&!5a<${Q?u&}f=3@}(~z`X(kFuKPkAP4@wI1)D$0Uc;)k&g9~1YaNApzoGYePkznCgLLJ*cZNT zqAMBTYD6`?yXxI4?0bF(%W6Gt=sWVf?16aS${hw*fE6~4n?HY*-<4&AA z1I@_#0GhG#{AsHvK35X#=Is(B{aQSKTW%}U*4pQ&EZ?Ojqo zyzOYH$`p2C8Uw%FvxwoU7%^|vJHB{M9Oi|3Og&v6gi04DhlNsgcsQOO$zng+w~5~| z;~7L=OCm6>_5H4RR;CDPo4%lQQR@-BdQ~PB>~B?7!=`p!L}-|mB3}SZxG3S(`RQqv zp|imxP70n+FMQY%UaH^S?N|NFd3M6#tE-OyItX6=snw)zV6c!bXdCY)9U9sQbQ_ub z4v?1(S5{X$%r|;1vr&COGU}Phb)@un&+G4A)KpYuWlhp2<9UFe%B=FfTR`Yl87wU> zdJdUFq_0x*@bK{7zV*C8_XjVP;vad;l+M6;Kat{KNC0jn0TD~1;PU8!SUsET1TWO; zCU4Qh?tuJPb4^W6TU(o@H3zZe?KHpRGIC1e7CAL0(e!m_7I>h%7#hQx2EO_Haum5Q z=g)?%73h}f9WOVZuPJY5@!ysUv>zACpwDN@4I6wYZxnbPqDJZ@5o9Am%95hs^jio5`F1KagGrUMHqgeIm%{zvS>`S*m zvfpTCMeMcJ9-NHZ0qgfR<_!3r$8rLh|}wWb#?K zjMau$_wM?G6~)r`U(;~|_T-BIlpRUQ51@Qor|zRbOr4-9mBx1kEIQnMBMMLqD=?T= z!u_P8X_d-{ZEI`mAHoUb`lX$>-)WIv!(k`@+1+bw-pP%4sh^`?Fw64Jl|}G;NTgVhFw44*bzG;`jdQzVp=uW+k zCa}3$+D&)~*bI8lli$wt9G59~vCg2(@i#;UBx{E}gNB z7P%AAkKRw`ta1l7p)}Dav&OG!FuU6+OPIFEq>N! z9*Ls~d?`szj^+rzo%0?U8JYI@BS0)DAV4%xZQeaNG^8W&>qdYZw$`B-U1#r(IMPx? zBaVX%a3b2LPG<_cH{3AW1si;GqpeB=gr{BUJlR@4X)r>&R<2i|o;8)}y>cC;&z+sV zmsixRcCr~X2@BWvuj%|(_OK&vFMd}A7S~5!9d-h-|5S`=qts2;kn$yQC~1%W+;r}H zOHs-B4;%O@TlPMZ<4p$x`fyuH=v)(jOeGPZ%Ng0yr%R^ScCpe&G1$6Uwnl3!I zb~SG{d*PSlPZ^%Y1t-43Oz%K6w7%Fcx!}}Ygw|%d9d3!B9)RsM%G-Ap!nBS`PD%o_ z#Cb0!PU3P}XYUMX$O|NZbXKq+ZKuI4fTsMVhdoUEi3*GY5dW8&8j=c8Lg z$otEspI5?{xn$D3TX=Lah>4I(k}JO6%2ZKgc-oZfz9nk6cLCNC$4f{r^ln9z7z{7v zZI4-nOjBgTa*cMK#893?+5esmoTgq|imtco5j>lCF%mA)rl~I5yKOv`t$2{O$5*CA z7;C(Bkh`ISj8LoFa570XwHYaE=6AeLshbs@q3+$TbIT5yzT~8V%r#>^%6`ED1ru&UPA6XdxWI%UotU`g%Zo-bv|BoH*jMUjIlDsH~BuUoGE?vlT%>1pcJX?xIivHb99Fg;;f2nMI}+E z$L#6IC`{L$A+n(~`U8YVr(mNCa8wzp26-tt2NrJ<5G}Y z7m_KkzA^WBngiKtd0?(gpT`a%lyjFg)a{m#E!D59eP`=dXBhW<_rK^zeMw&7<9kTw z^M4qeED?q*fWdw2W8!-WRC~XV&8A1;aOuaIo-FjOXs&C;W|!+E7L~{_oB(@eWqQ{y z&d%rXqwmg>#~PuBceC^=mf25L4qX6Dj`1>*G|&U5@TZdllMrNe7{aL@@8VeX__YEe zff`ts*IcPmHal0YTDdeduB^-B8TO2khMjp$p&t9AFe%=NmMZVZoM%5M8+{es|0x2Q z7uAot-CRW2w~g@KhfjDR>SUaei;#|6_o4BjB7zAhNy?${Zv9yruhjXkoBb-W#*jAa zwQgrU47{$6xoPg7$K5N~G`^ejXL1w`xzCDPR4~^IR!4liO`J@;cOIRn27&&1J{UWe8^?oB-aSSwz;1vS{158< zO_Rg;QH%7FVP`tnOlK$FC0oh|i{RZNJ)stM~?O#`*^NKD)+3LZxjtnd7n1$3U7u+ zhN=`x+z+zNpEs>Oo*2Xo4mAiL{5dk_ajU|@u(_=7xx={(PM*a%`nNk9Lgv51izI={W}F}2g#{PEG{ z*X7)@_ghDm@YvvY?KfwNgc6QN!*jF&a+vp;+1{R`5xmfaXx;Db7qZt67ajw$Y%$$y zfme*piHyXL)34(`$`yGv5odUBoB|oSbIibVC%;P?f<8pHH|g~Zn2d@0TiN|+BLr^0 z_5RmrmtFve9G?iSe06haX(?c_m7}Q0bky&p>D!hNp&ToAEZBjy!x-3_J>fL5s-!`q z(jnnAiCh9zVa(Kb{YH7x2qly2EYlxbwx`vQHCD zL7I}vm9TwP30Ut_k75Ch)9K|#g0>u4;!>DK($Ap^e|_+*Jb?l6$Sye!n^eRRfk zC-cff$}CdeUJkJtqrA7ug&(C>jZItgUdHNA)F~fjE$IZv8W3Zss-ro18Ly0riFW4J z_m6Cvy=Rmqy57X_=w_>n_F90BWNN;vP(ZJj3}xC<^x@ew3)d+6+*rg$AhLN^_DLgU zYRg3oXx%Lz&+-VGDfd0Q|xHMQouPEGP$17EdTU43OLM_0Q zW2nf+HqZ+1%m*fGEUqmh2b|C>kzqj$IN`YuC*A8c7TWw@e-7GT(~|8xOFZo{%lIp} z+Y>=Sq6HYt|DKWrKcmdmxX&h%B@L3y34GduR?iS_EMMV^KA^i?q+iq0ygk`VPk~ye z^ZaEN!@}NCAuV}{h|x=-!!Jw$5*PpP9s#c{-p#3sU@FTVoAkDj8)&GGwToNYkt-bj zXnhth`YEV=5Z6m_Ii{{S|J9etZ!g1*>r(!{;wjl{vj{knE3lq`qs{}JhgU3_B$t$5 zt3*-8#po3OO6a@@QM9*Zax~qD3)mWQanXqU=oA#D z2wDLm6PM>f6&Q1Kb3lU@Fo6=z=rcFXNz6VCFKCZJhR{JJ_}ONn?gjlkvvAOip`OEE z^|>pk9*Z{tUd=TJV#P7B4)Mzu-4pTm;(e^+-SvJe8{awRy0n{J>;XAJb&M?fp*Mq< z)55=O5;O*3)_{oybPSP$j_3FkCVta4S4C;DmQ=kYBHp@`cB!XicKi@YscYWl3#3&d z`;$QxoLItwf_%M10l(2CRLgYU7I}&QU&R)?;EtP%Gwto|O>=aP6F+h5O}NOx)>OHa z0lsBm)Wfzi#(9ZOON{dyNGEyiuweBwIbvB219TtYv7l;WZT*xw;3+LJ@JVT5%MJ`O zd$JoXex!2wVlvfd6hev1Px9}lEb?Ns3iI6JeFpmm4^|9SfLh5USF8CcU8zG0B?48} zfZv$Gwy~`g%tMX5dFlSx0|%l8G{Tu%O90drGB7qS3e5?gsX-qarklhnL7J%#m_u3Oy2rH z_}lFhfwH-|IRlZ^^?kcZ)fJO0k+xvzv#E~tP9R$bN{#G83>A*3oQi;crM4K)gng3a zMi&Tx#3!aCCnu9Whq+*ume|gBI5&A(uM>(hiKJv_L%c2a%jT>^o`j;y6AH)(srvXS zQ8kA7>gqO&YLFj17!<~L$w8yNkcA`PRusI)T(^6Uy1L|;GkQof)ge7fk-&IE|2%-A zWWGlazExWh)hM)Txgq@=>13>-X=36$XF?Fsa}oYFq8^-&24*2*)BY|L9}|}Y2)8So zQHGh)vO23LC|`B#o$-hM1cV0IFFNeEzO{`rP)r-`WW6p)y(q~-7eJi%B=Wrj5u=RI zF3vbk-vUs)7aIC;P8g3U6(a#-Xin7p;p6nypC;Baz&qFJG+u z>~pZG7|K*aNB=q^VrvoY+4{MZ#1;!iTBWYaQUfYf z_QlMR`1zj}4a>#J#pK$Y`HxIbjesukNi~I*9ok;R^xFCPWweCwmj}uH$oXNN z-J<_d(YjJVNX}R(jZ|1qfxw(v&)uvV^+;LmB(`opLgU=VBKZX6ZK2dx;d{EdgfAz_ z^2)LO%8?xe4C0J3=re)>iR2Wuqc_XMaW6O&1YPkD4_EUAa z>^3uLRnv-=2FVS(qIU7y;?px34Jog}nQ#K!UITOJU28)7pCS@ZB<~%v1_eom<56aZ zhiO^VL7gwJKE!Z#yLwqMn2ulBS@BM~hFR@TwH$i*8)zk(Rd2i#mEa7)a?GlpNu_IS zqvg1e_dYR01Lf0VSTTfjYkmBJm)Z@ooOBFpf{uVLUcvyJ;wD z!&Rk4{-C?+b8O0(S0EWf8NX2`z^}0Ysdj(%zFmj61WJh;ZU~V-esXBcvkg&Wtl>Uo zuV6+^jJoKfX29YLl9cVwbXXozt!UJ_F}c@T1I+jXpnk(#Fx+fKJl~2QH5@MVprd>SKF+FdO`jtv{ls zCkst!jr2u@s+{bMm<8s-MqKmRe?QRG7R|%GestPYcRD$kRhfH3+BS!~U0wrCNxY+S z*@2W}_FfSDKNeL{QBi^r<}^Z8JvCwvQPf8*d}u|;PHw3>@PU~y`5d=_%*yqZl`DC)48yNEph?v7@~3=6emqN9 zC;%L@@2N690sWF9`oXWRWuDVgPBfqp4lH6&aZN)*eLc{)Ok%f<;4qe@#@V7h6p@R? zzkA1eBR79h&U3Ej?3LW6mm# zCd6MxCV5MS!SBNEiE8{!q;N~gPvEjyL_aKub~B(xj@IkZSI5_u`lJ%VS&FHq+|_(Deh-1X*$(+vBzEj?%)`d3HG1IX^;;LO)bO=ByRqgVu8^* zn;zEEYnxWwykMlG4|yoG@Dz(BWSUSf$x$0y--hE#xldj$b^U>`LwAclt66j(7h;tK z7gHLFN6|voR33tV;anPM{BzYmyoB(_Z#bU|1HNMCZ9$!`{M>ZTbHP4>+R>oK&8W!} zo$sfjMstlh`~I^9mU>Oy{3uU6%%0wPVV2)sCD=4WzJ5hok@v{WGtVazbmhaXV+I=$TOW@ zazkNX)QTr$J;YeRTNDwKQ0eXwCA886Hf(d((JqPt9NK($;nci8?G3U6;7fu3i^|a2 z{;ShPD^(n|vFLI%-xA)?rH8hDeR-Ro_=F)zQ zoVH&{WMqzZVvtFl0LP{2xkYP776xt?Gf8NsbwvJ7~r zo=%N&mu2)p!;Whj6o!mCjjB5ys%=BIT^=j_kBXz_zzzk7mxslOc0W_RBE-ZlzB4LajCdI|Q{hEGcR zo`4t})2M%lC)CJop5K1*?Ueb`W?}nC|y)0-stbmQ09rv7C zTWpM()|Miq7TKzq(%h#`o28~O-FS9uO|g9G>MZ;97!B?Ny^?zT!_)Z*TxQyQHQ6dv zHNe5a`T252eDM{^0d)?ggB!8Lm%*ENhg0s2y{FUX9;e=a_+!&(k5U`pgL$2(0SqRyBY7EzGbfT+}(BluJ9+I%(U$wP9J77HS4x zn)qI*P4d3Bv#nkA)xJ&^qH0N((cm`V2{lM%c#1qJK`@UNQst;ptr`h{5oI5xFbOycSx^ajk1cAS}e5cm;N~pT@ zq#nN&zCtF^95a7Npa5y-8rrjNx4<74@3`MgS$;|pc|jBh>6sE_x5u*vi7?gi%J7 zm;EE_{U$#unb2Mel`d}C*@lXsxRTz@fiBO{3ELtudE11*)p-`snSAz3)ArLLK~3Mg zYh?I;zeZ83E_acZ+dfWrZ3$jVbdaSOXUh>^(_18S_Ntp4JsUA*#w_mwsm_zTwGet= zfT7)G;?hH=|H)%3iSGap1ey#%qSY4`1%zzue6=8{Su}jbtGW7EVP*o>kuqScSt`=8tHh)ATl1>39SAU$ z#9k39jScng^to6YTn@X|5N~_O!lWl)Ke(mbS+mm~t!|6DUc9Hi&-6hhPAD=F$9-_y znN}n4xNjuvSoQ5?S&e19ko4GY2BgB|bRlX!+f(J^gz(C)L~VRU7nj1u38>^yJOF4X z6bJe&M8Mho)*-rWO%Au)jer=+Wrevtk#NokP0ur>tgJAV;bUR@|JLr+6#g(fSp_S3 zVuAYYlCiC_d0E%yV+#vO2^q`@LKGBO&YxwG z`o(#*!Z)smI>EQ4EuU_S`YN+{h&cXbmb_=;HCOdEig5iy*{hC2+nvR$xDxRxKRv&3 z82QGF&xIrI)O+>{`$Mt$g6?vi%tb?^Vp@piYP+X8c=eZKclhU@3FiNOv&y#w`9)f~ z`nf&cSnLHlVRQ{9)x&)^1?Er9HPQH#0^}t86$xY};J8viTW(H zc6RJY)V&ouZ)$;EvZp2XQ8NZ)mzSgZ&bPnt~N!`0?TO~)gQl^SwjzJN20b>z}fLdhQ@Va zJjZy>su-&hs}ir`Wc8S&lBkj>mfS!QM(~{Vxx#bSppO7><5avW`qpaJWO}u%bHbQ^ zcY2~-iq=$QqF@?(e#e)Uo@Ukgt^b4`%^|)brO}I#PVcj?$REtT*Lydj(3>^vL+Q>c{PfSdjJv6eN=9OIZ1!zRl0_R`hi%=88 z_e;?AHS|n{L>+CDVu6EV^@}zRRuT=VpMB}V^f2f~*7-}UrNwnA7&1xUB<$iDD3+D0 zLMGy}_a%u+<~xz->b%t9P+~q=t&f(Z+A4Zti|J&FQ}E%Gg{-7VQl`(th!}A-nTKf` z0p1V%y@s536us5xv#o!eeN-jR2kP}M5W=r;+i(yCMDLsRqrJOSlbnE5e@3GM)}Zavg2@0QEk4NS1Q8#fPu$-0rZ9BexxhTa2H0y z2*Jj0%8DCr&f=Tg1PZPN$&{7yUz0DX3jBH&$=93eiA$E1k4y^uY8m}k?Wm*_c`?eA{6=n_ei$9tSh7 zcyGM;)t#`k)aS>hA>l)-ldUAtFdAKDjpp~|(`}hsQ4ie$mSed)rZqLS7RTO*Jb3$Q z7d0M0P*~%jci4+6qKD)0;ebFb7GS^C_NB>;h|FpyR%$5;$|9W_$cwLBcKdY9J`sjW84VY(Yv<*5#<MXYw+^RH&Q?gLtAZuy zi$VJ_qt20B?sP1bP{o^G1+5PeJnvKtAsKQgeR^y|dw{Z1)R!@`|u1E0TR`~#Z7 z1{6OIVHk{kZbyk;N}^tAKF!X~s>!Oclo4OQ@d$plJ+CW|Wun+d2nz^mMP@U_Hd^Fn z#4*=D3@^nQ1xG^Y>N_nj*IDrMJjNfn<$L*iZ>EYyu9Yfza9+N{Y6@9@#m?!J!B--C zuSuB2j~p>(T##aa_WkOCA91PpFC72V-2wuSG2?V&bkFMThnVB~Yj)+Z=l9c|JGxL4 z*5@=czv9S`Wx}T9h-c1935l!E++q}Wp%R~TaeQxSw`HDQl_;r*pBFQ*QvbMpHhMJpKAlCf2D7F_Y>mg5ZK&GJ`*Lm-Og;c_fq83}?VrWdi9;8VjCoir@# zz46sJl6_&G{ZpjZ+I76&9WweV`a8SpY?gdqY)5{)zr|Z^Nu2)YK&ujljE@vQ5~e|! zLbQVe2p5&eIl;gu&tGsb#Y{ws-3!#~%yBH5{i$o}5*Jp{QX$aZqg!G>6-%gfwW2j7 z!T?aOOzK>AtU%evDh3?aknbFx)OaaA=IgJil<4%J{b>OVCmoi1-m#eKS%64E++}Dk zT}7MKZ-&G6=Z2V-KDq~f`}~j}C>x}5l=|0zD6}RTvrg zLh3$Kg;l#z18!E436nSGz>$0XVtNFN8%M6Xxcn%V|4*{gSW7|SvZpg@0vH7&MN(M6 zkA1qeI@t^-PT;zfz2PA4q1yRnJC}`of}R)2jo@)l2}?Bt=NvLQZE*>-)^6lUm zl~7#aZ?Sruio@migu6Opc1+>9RoB0a``$eTW_T**(%s)}LnyTZAUZ7J4~^5Xuu$F~ zXkb2xzaWtH?@bUbU*CT;vQ{BKXeI#vk9sVjQ^@T?(&}A3lx;WS$S#a|l}vq_r^sK? zZZJIBLTFB8;l0-gkgH@FCLS&4)yYUc<}JHr6>V;?d)OI@@vMc%8>`KZksvbz>sfqcWc< z3t#|pqBsGDUfU`p3x`+c z%z>4~MC9|7luqP@D? zroSpwn`{+b-8ey@N~X*sJ+zIP&GUMd4KkA(&=7$)%M<2X30X*+5;1$X;fHJw?9=kC zNzdwueZ&{+R*m1hzBe*5TCs;t(gEnbjjgSY^Z7zmMH)GB9ie4+Gb!C#XFp--AiL*DoUknJyFRZA1 zTsC}_x9p4#OHC5$z~H0GC~dXCZX?ae+hxq(ZMn%=UQL&D<0gF771sUMkf zw{NA6Ls(St@$qZ95L;WU8`0>*0OAEaPS_NMeHekwbi$Y4C8Y*x5xe)1ALNA6V_KQL z5(F`w;z=ne(lfHomqouFawqKgn!X#DD&JpdyRA)6y+t$4Bao4tj?p3QnX^=}?UDIf zpPO4bB^r_W#K6d1kEHG{&u}f7g@Xv_V-(%k*a+010Q@Q74N&RlIc>2XBjfftQj~_E zX(=-!W8bZH#lGpt`rln=YQIpm{v4GpR?x4b@{7NIk+5R5c+rP(=ne0S^TUR`=K_5=rGgsZwKPCoruG8dygF)FR6RUA z0Avmt4#DX7d8#}EFp+7ZzkjDujh|K)pOHrg`PqLYj{oC;V0h>DR8-cfMg31s{~JDk zQblNZq6ptM-r|~vinJ1w>pU}#{CPcNVO!Ot~EQzg(Q z#l<33G|$wU|7*G-Nv5U6_v23zqP_6J97;pUs_-k*%S3;!}75$QH-Q~VUa41B+c*;b~!NOAZnAze~TR|eZ3v}g?cfAe0;=+&^x;91{P z)Z5if#VDs_SZrJ4gps~|q;&HG3h(+sH-cFGuk>_(NYa^KSlQYSDLCDIFwcxv2=DrQ zh>e3vu8Nhz%(}QAPUwht33dQRpn|pkXjk-=Sj-1afSHL^C0q_yT0BZF?$xA?6@gbx zZY&oGl{0t9GeE0idCJ9&>pmE!^Ax?;x^+9Qv;|jGRM5Wp68gLBg@kQz^CupPI5}CS z_%OcbH#LFbIjbPWx_qJmS*ZkC z(67gG{PE0$h21v+;O>&V9RFqee`axLU_kZKfeF_}v$dk1G?8ppbSRkNAZ-j2TtR>M1WAFVB&EoJdLrZ2CHo)9pl9+Y^I9hC0G#}m08WO51&O6=CniAm3Poyyefa9@EQc%(Yq~j%w zr5v#XglHgD1=$ZnacK_H0JI3Q`_+OgKn(PSpWtRL*VM+XyV-un7M|5mDpOb zvdK@ZG%#Llgf7$aFD%S zQxlWQ3Nc%?p+cJeuJih#tyi3!oLpSX4YvBN3$(PSvZX)(alg&g4ScKLwm<_B{s#_G}Avc`N7T zW?Iegh|Gc|%vn zV*UkUEobMtz75rZ*DvGt;a2mEdoC*4pq1>aoI*dJWXq-X~&=*t71p-gIwFf@fH z=$5?K_sGKK%!{CPfq!HJ5^XZf|H5%2Abj?VX$RV_hEhxbd4aE^=H2H0yGh^NA9B7y z0hw`z$Qa1q4gaNi3Az>Xt~%WGf0e(r?*}^~$qyX$IzJXviTQ}-TYrkEp>i5MH0pZSC#tK#0-U=vLK!1(ctYFMn279|0Oi)Z6BMv8w+UJmsrd!39zvEh`bq>Yi z`uopM4UKKbmhkX!MIo8o$$cwJ%d$UzcrWW24FVdx$rOR6RA=gv^BGe6wCLx|;1tU> zu$Q$wJ)eN*Jvu%P8`{3y+1Zhe$F^$z~^W`OnK?j6F*z zuaqe6eZ!nk-@@x#oOgIPet?L(aNizDNs`6T&l!CV=XC>n;O>FI08+>@HEa{E5lJsn z06YwQnV%FO$+HP%b6J*534jRkml+TwoQAmqX5G&rM))q(Rtbz26@b*T)2Ko) z#wu=Ws~%zyeq+w%Z(sjM!V3<@4-D$YpvXuir`sxhE|kCzkxXpAPVzHR&3wl*xHMI5 zZrUJlHzRV#di#2ZhAd#)B6H(#SR+rS@ z)OC3rz*5y=ttU*E@R$#y1krQ2kfr6mO_ck?op)K%VJXDpskAK)I}I=mhD5v8zJLfR_|m z;`PbXqN;C9EEotsdjQH`oR>HL;rWu2OZtDv^h)!oFlj;53<0Nk%;>R&_EaBb z8M%c4ISn8K)Ge`mGW9cT@p*Ju2aK}}#lWRkES73AFv_S0Ba?ZA0v;Z8R0FB3AQ=>( z7FXuDdMOP*y^8WJ1(c#`fixq)P~ywW!xJVL4h9NDK!NgA6Jdv#c*;QlWP&MYAOG6c zUt1_<@F<;bHSfeLi1XT7S2*S zfLWfjIdJLrkOXqnVW2EVmb-i3Mr>yFEz5D&dhkvxN&eQaWHd z(^0Tl&mD^K-7?eNEK<%Qnpx!d_`gAf0-<5%R#L3Um64+XyfbmHq@jm9i`{kSg;pT5 zLXk+hwH3&zkkBsb=S8+ahhBy|OwyULss~_O8m)-cW>n1UY2j=W$WM?2VSx_K1Yhv{f1Bd}{+A_#`wN`>NA>TG4-NuCBuYde4CK_O>g6(<3< zovIY0c)>H;5~f_;rbsZLBehad@q^vLQe4UifC7gY9wRUxi2B7Z>_Qg?DI+f~o6>e| zpu*UA{$#9MtA{$Xc^1wbj#QS(i#@=a2T-S+*DM2SeaBi<9Q#Wr`X_>#xQvqq$vhQ* zXhkRjQd6|~z#&;=s;E!tnZ5tvR@rmJGhULqqAM_HS5@*dRlwN-*?%n(k^?A&oTOU)y z9>mbc?Ds%`0vQ^IdTxUHOjMC4j2O-%JlMfY)&~uRCax#rJO#t$$mxfHGOZ7NdI*d2 z4|d=Kc^_~w0j+tj_%)N1UqBO05mE@?f+?4rea9l-Y$OZ;XICTZ`}0!JF~|Z~Xq*=f z6?K3Xi-ZdxwD{&|tZ{~bOBoOl#_IJdJTu^ZU=Ey^&##)|4xr@1jti85{>#iDD-kbw zv=KU6>CcKGE9llQ?$Mp&4s|_T8yQm+Yu(B(0L2_UWQABHit48O4qUQ$EgEHrFo#U? zeDgnz?SUG->f42AfTL1V* zOo3K1e>hZH!OS=FBAij zKOh36PmmvipYZf&N8!spoOjYHlrcV>xgT><&nvpd$fPc?KDnDs9_0ro0pe^L3V`b; z4D;;|{{?)Yv!Jm+R3onN*G?x*eP#a7f*T3=ucE2^zok`Tc&Lot@1J9T0uP!Spfe*% zZ$T4_Bm|DdcH0yy`v3Tz%6R#To>(E?|CsvUXTX8N1ZNHvN_dsVjqRIxsR(V%Bcbjb#2*PW~1Oioyv@ zGijn38tLO>cdExdK=2l4=O^lhnfxdK?U$MhgAU~yr>Vw=4UqTgJLxVp)=N^3CU7ux zsLlwtD&CU%GC*7Gob}wQ{s?}H;88t8sA|}Vh*jWT@4&@E<5sXowr5qH7yT!V-^o;w z7u{40{@uERqCfx=5&igOFzLP;Nrw^Djt@i;!vk43{-O1#vrEq1zKr#6mcCzbY3rK> z0bKZW{u}*U2|zZl{ALt_Mdyap0FUTCShEip-fMTupMrlx*P0}95AarBog)Fq3pj_t zt^zX|JwRC+kW?uC&YIG@8A~JgqKzvh7cZ%XE2V}B_sV8eQB@VaZ#s~={G^;tlKbty zFr6Qebz3^&7UWK?xi9!(+%cMpcJf8e&XO%2@n?=UHkGynQ?Sk?m#r)CYd#Ny^a1|g z?i%_Wf8D;HxwSANrZj}q`N_$6T^r~2d~P0lZqCUxatAa(7R-1iKw^!b*UajbhUNxw zjx}KC*VM$ZEnZK_R^!^(e~>H0$j!?WYm&Y%xa=cwUAiG^w9TVfSX%RrLIBoEJnQcH z!{MiCa)Rn&p#9>R!}}*%^qK_V@PQhCqoul)Ia==Ow($LeKTA-_B0H#NTmRn*@~18+ z3rkCmTAix_oWXO8CheO2^Uk}xXl@Ca)}h}-jji8fS2&l~jxjK(;QR<^4!u|V{s@W% zA&%&}R{Vki#lKH}EPn;_tyszbT%$uzy!Dlnmhid@H_YKwE_kUDAIQNa8%kD_XesR< z6xKTP<1gbCjB|eeX(S6Skf?xAU}%?oJ+aT zf8lt%oDi#jdV01ok9O;;E<%Qocf65~hI`+@0yQh-*ibCoAjAMMF-#gc6gU`5zxh2= zZm#k<4sMV}^TAlFa%bMlXBI<;3W=zvs)mM!{$Em~1im;C4Nc=)o@>j?WyF4mqUkH* zq^${(0J$ARa5q_cM{cmn@la*Lp8XxT@Z>WHNkrriy=fL#&A^+VTCBLV=-iV!H~GFM zq=Qetw_QI*F;bukNck{zPr`+^(tVCYy=s9$z{P4AUl?+cV3sh~#rH&K=WIVZgGUHeW<*p+huseXW#i=F z)lv`0@}^d$(i};UT6vtg2K0RsG;C!M`JYi4W+Vwj6+TLB+CVJn>nV_ggv)1a%@ep> z#>ZQI=VpE#+f`VN^X=*|brZSX2oKhOd&Nx^L38TYj$H=?3oOWt<-!Rz#~yRBy)%h< ztW{G0e^6V8?Uj1NCApeEV0~7T{`B7~-rI{J5rRe~!o|*IbPU#F)5LeKD@)@W)=iu> zF%*fWUg>xKm@|q0lxs~nlJHeqn|_qT7xRIh>&UA{htp3MkUU&%uF21*n)ccHYGl$L z{o&mP_2d8DO@YN2-ZL57a|~H-$w@QC!*WCYJKN+)K#eWMVMw0Un9>|_57yE< z)Iog)y<^^Ak|W;bcJ%Zn`vW?kd8N)gtCi3%juHy5^G*Bh)-D3F4Jf|gHv z&uHekhZiYqfoX{~9N5Q%s^+&rMVu5~J_C63bF3Jhm}m&St_}xyC2dHCS^|+|HVH(X zQ3tM2&zJir?hJWx_X4-7UtW#CP^7IS7D|fs+8>@^P**1MNGXjJlXo8$F5Krvra|IkLE{JhyuzZz-32($&M4GvCMP@EaH%0r^zgXg)h#7gUw55IX=N{`9j(3R#vnC)vq;!nz zIp6nz38p>tSZ-_)%=o^~Jc4<4ICtlkkb?|V9 z=fTpjLJ4cW5!KMrvJxEim3)}t{5cQaG+Z_C>@EQFElNKU*z1 zc1K#t*nl&l(b)XM^YmU=HSYK!f{QS*@qh68mz-81tQbj`H<{AHkjqo1OCi!1sgI9} zQXVS{g=R<3EULbO`5VrONqYmw?+^(E=A|)uLW%<9_%4zUWTDgTicld2`1Q^We`Trq zHBM!iw--2AA77PP_-+9b)+woSqjJ>XL=1`@$=~snfym zn23}Y5LQ65WK*l?70}EZ{lsL!6s>oWS~YDWENC4(e@a;tO7bF&g9b6srUIEo?~u}2 z8&4uF#WKxEcckY7nhxUR@Kx>CR0V{Y1apI=H$MNoEF+AQpdvHI5{Suz$NePJgUn*qO9R zOiC*Tg9F*XM;HS{GK&8cHf+9r$bwZ6miT(WTiF^_@aNpsN|sEUDH!_V+m z;Y3B8+-6pvAkVV_U`DcIl*v{TpGw&r#|Gj+;lB}VefR9?bEyW;^V>eHoZBvjlB;%l z1AkJN)9V>eNs7Mw*$#jrEv{D{Tbo`J+_Cud@#9BA#YqI;$j-k~mcJqnPwBcvqWV^Z zW_v723?E(Fz9lE+Z?_pXeLOfw8Az`)VlpZg1g`G)DmELOdZs@t_Uou&(IIimSq0B$ zGz~$$H{*)!hA8)$?USd&(X(N8czUQZi4ls(O9l({uUwQM;-sZ8et}bOnN(#SGFwCW zfzPyiXbhqG>1S)|m7we0YQRlyoNiXc zKc3MTT)7sUAG}@tp{Se5h3e0~WTWB^6W%#HMo|}je~pCGrx{mPg~3(_FU;J6;XMcm za*uOu>E?hwUo672Nor8r3*`)WISD$p{?mucqS} z(my!m=Ltf*KpxGXslC1Gu8FB~6Xtci=xS{=Qs3Wz)5Bp^yGCD|j^h$vsFZMdXaLz( zzx=l|31)6D$d(7mK!DHskTPe~HO$rOmR5WnYPJg88a{u)T>tW$+rV@tu`}?VAuRazt=s z;;&HZ<80J_2J&!3J{Wrf_gjEkGL5{&$UdJ)Qu^1r9fp+WDV;bp>Vzfk+lecg`6vx_ zXx~k>TGBf=eTZg+Ze0;3*r4l- zQfe_=-D;Df?n>QT$EQ9Oh^sPxWq zk8=%$%3|2r`yv+4GqLMP%g7b-nu<1ct*0IVQ7*1qvBCC*+j{aOe9;92^P_+9T}Dcx zL)54^q%iu_SUEl^7PA#5RKZl1^Cr;A9p~5G;pHV*#(Pkym%$x%=0!K%A0}2jG zhamw7D%aWMQIH1B94e}-p7BV8L|Mggd{-Al-&$$u-9%~=Dcz2IVgeM2RL!`ylVsI! zw@a|3$u+_8kvDIrSxX74(%Bn0GHYvdh)d(92?B2BG~q;KR8r%mX+JDXpA7|F+c&Fw zqZg4pdsSQ?+%hlfs7YQ?z4|=JPcDLcuLeYxrlX~C8u`<)q@pCF7^2)lsc7T!AFHaW zP(#SW;nYA>aYLxcv**{Ke1E-H4rm%byO)d6KpW~nGT-M*K$wt@5EV_9lNmoz_JN-x z>Ia`Mtgz6zn7sgr9Y)AZPYAqcP!SJfDRW1HqUqS(GkgS6?*v`eNJaPFta@U%1yS8> z1~LDa%vMcrbs2tmF4_HjD0u;8Oz9;06cd@;e|3C|OiI`ggDd$>q?D|*v@owk*41i# zXiqiOPVuM}L@C9YdK=I7lc(3Cqq6fSD=Vw7O)auV;+%MpZX>~p>;NZHx%I!{A5H`r za0OLw*fxSzstGyq)%IA}IM&h^136ms>1?tzKhG@op+7WX%U}M=P)9b0jQ7K<3&IRA zsW!`NRpk9MfGlyr=n^irIaO*Y#7`ue3AqT%yE)R3PS!*MI$&2qcAlOY)u>DjE}z}) z7Xy&E@(E;i>1jYRjUr{#l!yYu?&?c4#2h13kW7;Zq?gy}RRY4EDlRI%gwGjKG;%De zyoiaCpa5r9M2Z46S@@Cp@f(yR$_NQrOo4=8vV9tJS^KW4FHFXViu2<-Iq7kT(tLMe zELJ-6&(H1q?w+2Wa7{wK({@a(i_cM^(3{`k=utmm3>;;C7gRzGTD(}i#vhyF6wSPh zs8BObuhpTR=Mo)QwC3nA%G;3FTCp~N9Lj@pc4ADsYR6b_gg@Jq30y5?w2eO@Kz4wqc$aV988NyA-nHBf)l+na&Z2Ad~<7j82`{Z=fj7@Y{v& zr+zeff-vOCfOC(Tc14pFQlE1goXi-m$jb1%8?5Ca(3#|)k76D>G4t0M0et-tGJ=U6 zct=imTjYvO_%vbvhK_mwu8Xu`@_usv4H1i+;Zho{{jDRm<;kS-9_+;Zy@mY#>4Ey; zgHS)|RVJNDW{k(>VbfrPugM>oi#;@8B?PE>;sT&YD7fVLs{MoSyhRDD2!5sBn3ahg z_B+R#V5zJl8BY5!oTqUfjgco8`ERy|3MA1UU|X{f##?;<+y|aR1QVjUHFBuZK%-B) zr>Bt-lI~og;Eu>yRhy^w$Ia4E^W0|GUWmTB-?1K-qBZe&RTh@*JP;`x{P+$7ZPO+(sWl-D%F9=xO~z0;`+28Ubhk*Ag7 zN&w3MVL&l}rR;YK;5GRl7a($gNnH7J)Q^NDk^qQYve*gXA+8Tuf)RxEuWSYkl_ANF zTVE50`N2ba1yx&UB)s#(kj!3n#K9hz!dV}rLG9|j^8=@tw?-;3alC^{3C!cG&wZs3 z(Vt&P13L-biV6%VDAO^9BNEk|(lJe49jDfavy$FUeofv8Pir!>!M^98 zH6FGgO-TuOUq&6v9Y&zD$jjlN#*Zw*vdFFE!{Z>~HTDTm4Z0R5G?Fw{{5!O^M4wE8L@mCfq*mYoUuwPrIq8*fME#C89jbb< zB4!rE{lVjXIYAMdphzWLdo)CG?SD$Yjg(XHW?_|3JjO|5<#I5I{1L+BJ>zpg z$KqCtTXKjs;kZQ6hQ7`zqc6kNit$>6;sI5zm;mf^qJ*?j7c$j%+D{R@qch_kA};az zZmkOAQKpMDUM7r5T$ELr&Qn3Kla{zV8K0f7{QI5m+3={{7j3bI6(p#mRk=R=d!G%z zui>l()JEHG*qrhtF09EOWCMrCT3%GV+bWK=< z5)}nTB@&;Lu)-%a-WSu3+IK=y+q(3>oCdcmatV+{LImDsD~cFfTYRSu+s2RN|DFl_s6V z&?qFgtMqd9^#*rl(@bt2Z+h?tUmcVSCS=DHm^gD;3>czW&fHW(r5Q?15Y9a3`%1Fw zHLV!?i1+)-2xmOeWZP&q-g;;oQuA#%14*i{ikV7obH`qiol%&Y(GQ<2SavD6!e+vF zQcJRooU)ob_=-cju2`oHr90;2g0rw=qJ>o+I5W&B*idl8>5A=*b%(37-Ej)V=r|{+ zEcI=_#t-B(i{pI3W6i3`Kst8U!b_w;Br@6i@4EXGp{~% zx38?LWs1NI!Qo9#wa`^ZebaYh{l-genMT}*@4_;q02BA=ef@dlJ240}^L`Z8l<=Oe z6H#YAcA`zd8NoHKrBmjn5He)sjdO8|{|p2WDPw8hKk!&k92wmt^Ch(f4w?8-)|g|* z)zo`UP9v5MoM!?u6?2AJ^k@+wD_iJ&M{;MrQF*ave3Y-_iAN{k8;SvwnsqjTTSo+>*)>Wl zTGQ6mEfH}l5m=} ziFf@AP|9tttW~Q_Dnzy3fMDc`E4(Db1!tV=Vxxf*St&_AUCDUn4-m_M;6MYL(MimL z2Vit%EGlIw54x;@xI&fyc8IQS{AzvXFfZ=7XcX!Ae2?5d)sZQ4=H~@Pan2cq$yv16 z3Xb&Zr1nmTBm$P<{VY-x-OezVW?C8LT@(7VdJok_bu1h0gd1lE;!-K;%>ai_zSBFN z1{LX6E;o`6Z`hNVk$4W2nFYokw=xl>@bU-eQ~x5d!QlZ3IQ2M5q|g*-!(XLi4Do>t6rn6B5Oe6-)@Xxc zx(O(zW+@lkT;ZzBXclN3_&TEF#^xxZFQEp|z2~d8Tkv z4F2n+`U7W9SXE!9z>M~b-#-98ZLN0L#2S_c9eoVkPpFRtp~xDA)}p=l=&)>%pC8;M zlP3`KX7KRRJg&$-94Cl`PlhLmEzTSM=I$eF4)2Odxx22kX-&M#cbLgAx~g9i@n5VG zYn@VbT)MvWq3FI?U~aZTfJHh`c*)F+zSajY87pD{VE}tR=1bKcJ|>ANA((VM@?*MO zDR)Q$=*R9FW?Z5)Anr2hA8nV=ceC0>(9_*7Xce+c9&N)QLf898#kya*g;ks3P__#9@=NqDvE zvMNeo5<&S{_-TOxJXmSvsG1j!;{qTZKka~W>dFN-Qc40coiORsbmg=e9YoqA6mWEe z-%YMSc7MVqSh)g+KC6HPhU+e?mpWV$wDe63B0VoAg4P|d&CqmOII7fMj}(X-*~vdi3NT1xORbbwSe zhf8&J#OS!37zvdf9VUY5l;X1%x^t%DcKi*#=*wipZobIgrSyC zAZx-I#hgY*!U=;4*D!WCviqy77-?Co@CdO3++U7Tn~^|F<=e5t?@j|Dg6;T=1w{OL zrCqhN$J>rExL=kCj z^^wvAr>CbzgVCi{g+4h@r`3O?jsyhYKw4;y}xWWy=Ok z@qlh9N??}*bUfh8LwYwCDVWoH;Rg$gNC@)|E`omCSOWklEAh-ad2K!h&agOPEaY4= zCAty_?*g{HF%&g`?<&Mk_vgGyP8F$xI#b$J-w$s+j*pMGoiUiBq$Lc9Z>4}Lu?%6; zG}el8>rU7`MwCMNX+=ndJw_qoj5<^CWWjnil%w%{8eLLl%rKr!I>Z}W zg4$zn(aOq_<4qWUXmF`Pa?DLYQzzev%S5l~N$;xoO3(kO9SL6BeA^s9&yk@j#xpy3 zyQ=3%Mn;D_A_O5VHFnh2I-ai!{~k}I2N_{~3=ggcG(VV<@-z8u6K@$A1rk%}vlOPC0ucdt<-{~~cjsr#-QU~O z($>xx->$iAg=Q1vQoV(Fa{gG&FVq6iit6Zivnf zc?p`@N>59oqnU6<{VDbe7E>gmy$Q8H;cpk=X3M-bfg$E_md-1z4jzgYo>}PGpikRv zD1rMxX0192B3Wsi%o0S*PeY$bG;bt%Uw3ti$s6yvs z!{TX*JkDsCU)MgPwuQs;p&!{OKb}|p$0556;s=UcXb=?|k*+I>4BcqOfH(@1Q!2H% zbn^_KaVV4+S2|+0v(ug~$K25OQuz@0vLCodbvbF)?){C7NvIAf`5li^m$P1 z?t~=mxx7m+?o*OO6ErkB6qCNfKEoCbF{ax@V69Fe0h!SAaysQ8aJ9_E^aD6hQmU5b zzb)e^6N_2y#`N00HWWXMmzKowCaR~-RD`mRjb(97l74eJ5-z!9Byo=#D;G6erru=h z=JL{(FH7^7ZMN0gA=7*>TvfY8c4#iy1A^V<$c@H4PNX%q>jI8HO&=!$)Fk2rg zmsY0X{(6!n<2E5(Hu=3apYhlP7U=5%{56HRJ20tz9z!+I9Ar^2oTwHgwZi!a4cy*H zjn)nai&!Ws&Pv&n7*;uXrbBMoFa#K+``onbJDEpH*&@mG6&i5PV8g4|2>HDT>yNL_ z!?OfXs*xADwY3+VW;)y${KLP%LME`rilkCGonv-79#^D9Umr8kD~TjPVs9zDsEAR% zlv_$2)kPsRxr}p8UfxHqfxc!&q`?a_&-V0Rt{{ofBBfM{DP!7J_W)ADGn)jp+ z{WO_|!1yNiI*|@#tx`jPTS%hjIgboY2kW-`@ks1icWKh-FI`|QV_(3eGe;x)PD_^d zPV-|Y(1n^-1mnGGd^G0DrEE2^3T*`yJ&PwKW)^WgXMQnGr-odHkal<%{gyK!^lRV$ zP35^9r8pNBu5#_{18+fWzz!pjAc8U9hhI&QP&YWJ$&vnL&R9;VB-A?gF*5B+MlhC| zgKl1xByf+dO70`fX1ha#ypaZ`k8*7YQa$;j&j^8uxK4cFoDAXd3^or1xxie^NlpQp zBs^D#2c4{0&nqG}e<$Xh;ymQph;UeLk%4X(nnDI_X|kuxdUwR|(lAgRpu-KVa+0R{ z9dMzQJLHAQ8b21x?bHnEG+=(o&Q*6skaxTL@i3mi|1k8QhJW?m9|7btu|VTPlGp3z zB|*!(Xu_9*dHo6dJ#@r>uXttFPj^a9uDyRYZip5-q`i2N2uW}J%}$DjM%-#$yiDAz z4s(wEZ2!iJsg+b{57g~I3)S-7@L4@ zNbTzkCuMHUrD@N|f0H^pnVf=bi&@w6wxmivOg*4a=FNs^IXw56;@-xc+Y{d%P1!u_ zNR1PGOA&wNU%>Q`;@3K33})1jA#o6Kapl6!q*bfsD#X;4jx{+>0DN`i-d^mUNhl~q zGZ6&%=&#r*13-0c{8V7Gb(=8om&T1x*1tU50-@-jaJlJ z1Xwho7J_ut4*KAj3zsNj2FqH46z^z|RxlB`rK9Omw9pNoGFvZ`A=;XZ>@K6(dtGRd zfW**=-%?Lvt{hz?~*aU;yFo7Q#xsm&|gF)Q4o1l5ai7|%tSiGf?C zH5VLR-%WI_O^0Ng(;Zw$z#;}1?YRFGLQ=xWjOi{)$Eua7_J#3-DPp%NsLpVw}Sc!XK2h5iU z*6#sf;v~-!*M6HHm%7A0wA1nSM947c=sR#qyaDx5j?~oY>dns4F!7F|wb8heTj1g^ zfEb;3rnVsW;fgg|ilio`r59y!8J;Jrd2tPD`M&qSL2;4`<&pcCj@7SX!Oc^P0Z0WFB{r+2`+Im-g?!F( z{+>w(_&WwS;dBsP=A+`<5QKj^^C>2CmH2O1EhT2AEV^0*(cRxe8EZZH%mIv`FBWby zzba0(Pgwj}klgy$A0alcBUuu8?fY)B1VKLorCwj!?q0gITkO;p+CoP)X$NS-!~zudv-)K!a$zKk>QX6^nUZA2`RlgVymIIoK6hzYsSUL4(1vw6 zgd}?juu3AdSV002B#r#M=H?XVA3cv@o8~T0K|Rv7Iop*e^TwK!Mv8&2KD#2~p}Bd~ zngK*mv$=|_sE58d3u4Fxjp*jNE@XXHLP(j6hO(^>t4c=Gn z=w6f>W#e6t%oSJl)WP*U>#oI-0Z992K!4H!AKSb4RGIh<1mqIUmRxMytM-Cmpb&hfE0XPvummcYL6C)2kM=6L69? zzlv&3jpjP9p7QNqHr9CW>dzV;(Yy4Vr`y?QbjS>dl_7c5P>}yShcyxjW9m_|jHbj8 z|0e;fT`!e!XIHewjtSmR>2T#Y_wv;GCy8df>NT9E#$bUg1KRtQBYG!z4`8#HOyRW!fl-I4Rs zq}(sD^fn_>cNuXQ0c^BrUTbJ{J@!k7%Zhe=*VmD+tCDkW9pcZhQ0R#-EPtHMN>e1l z{&4r76G~Yed*Kv}`p1$Z1d(xjrq}vW@^Y`f;@$(K;utsD1B@GY;!vtrz)7Ztrb7H| zzhOIP96s3E`{zlVnti5%E7NGmR?eTE+w#~=zaCFUO_agrEoxIe>oqx&&rg9bXmBqN z8yZ@_9Ip?2H(av?X8G{eIXB!-?=BYe_Acw!giTyFocDUH{)_vtBksVN&D~-=%PUbB zjG56Mx1(yQ<=j3y8(w`8?WEjHc}`&I=~{0?0L#BFWD-NCSVpyBA;4FItQ3YumC5^q z+a{eeGZ#9J()+TpGQB|da`LR=r7q@#oFwgSsb*j*OpefRDxM}jNHRX|^*v#Vv9O+|V$(-AKi=`68 ziGdP3MTc^wE*8WsOxFUxxf2mTMsE+E9 zBY;G?^VqpB(AD1gnvk>cGP7}SE8w7lMCtsO;NJ&iUW!szC{;ie*H!E{qS`Oo3Nylw z77?}76n&g^Ar^d~3Q;jK21H9k_L4OEOS->IWK*`CJXQFsvpUe&om-bP0{1j0>CHr{$wB7J?7iRC9*rUG*bVDU z5tO{W7k%cBgsq&s_jk)Qe7zUx7+lEqq5i6zElu|Pu+U8TTHE+Nz8N>ZQtSdD4bl@v zf+rUzRQfk<4(=8faaa>Duh@kpWZC*9b9*@iYQ2WjfS7Tk$(U&58jrn(!DG=>qtYY@ ziE>gQ)9E#yGb2$1D{i7Y=U4mkaY0M*sffi1B^G|(f{fFz_H+Xw`-m)!y5< z)Q`??%|!!4870xRtc^@=Tn@;$&UeC?oeS*y2%wmB|A3t%=hTz{LctOa?v(!f7X{_x z_!*DxGimFx>+82;yRif-kHdd=%Ub+%GKHTv0agFcmTsVamF1>-_9s(+$myx{-9-SRwHPqs4Q^=o1Z0YsQ8stz_xTZ2 zXZZ?_s1Cs{qlG058xDhlN{s5$;oG9V`fUj|KcHp$hKUGQUaqDeiGsGbyvoN7-6#7#YpFEW$xj7DsiuyT{&;8d<*ir0P00-u z4IILR1k!|MVNCygBIn1zQ?vev-!orw#7LbGUg+Fk(sNI`myWt$+Y8p~ zKH3{fpEc*AfNyH*=v*QsjB0s_;7l5(KQ;el6E)R^AL<{^6uu&G!%Q&B>m1 z9k#IVnZB7*0q4c1@w?|$wE2jYm1mCvyGd5oMyqburt7(smA#(sLc%@Da*Jvg9q{J6;-{%>{lzQzjPeV zy;XGi4sPtkNObXMzK{n5sl0f6?~niB{cKA5vu;z{=dVv(fr*Z+~Bdp-WeAMXq_Z9J5={fQn>Dyj2*39ods>9}|1x>!5ZQ2&|5PiF^!p?jB z`^nq4ZN%hVw`ZqS+wLM|q#mzN#mT)J5W=dr*DE{GwaZU);hPv)%Q*O*Pd8qY;)2BF zZ;xwFQAzOk%X7yuUG|&iE0Re6)&$Ald|v+h*E>DSDJ=e2+^&p~5+f8JU8x0&vh7m@ z(x19>KQVVB`$D$D$QPp#@+D0{huZhYk=c$LO>Wdzc?SvsYPI#t9Nvz{9Q5Qy?`!%7 zjFr?LG7dfBu}*>2roE-@wMe*t0Dtf8q#}#Q1ieM+VMO!QS2r)BPwCX7=IRAT)LT$Q zHfzm}Gaip83EX*zeJd?4x6;KgW4|Uv`HiT|uDA8NUN#4x_EpGBsCFv!+C0qa9q$VF zlgkIpUyi<=dp!(a_3)+?WuChU9`GRZuL7Wh2% zb0g;TuldV_@OD_8Sxz}UJ1UUxSoW?9kbXVybN}Y^%j`NV;fZ1zAinbE#hhWjnl zYbSldy`_)TkZrbz2TWVBcsji#N=Vj$6GZa&vAJd7Z~JhU-{Eu1G+ga*Woe<*rK~Ts z+?sGiL13rmNAAhj`xn?QCnDfT`#zL9ad}t5PsSZ;UvSUxi-Qr#rY~6BkQx#vN_n9e zv(fc7wR?Y#b|*|PgtxNseS>>Xg)H+kmiSP%X!~-f_wm`l#b5ckrB=_b1tDis-#HMH zCLX!3_1X2edmfolHF%pzKy#mra`semqs&9_mu=;@kZfPeL;n+Arg7}#m}@CY|*q-ghetkxv5CdKRR{dhX$w6OC)>|IhP7bKozD~ z?tz`}Q{CcTgym~uD)gIY>;L|{lDUt9rPuR1Q6yc8xUjOi@4B`ETjZW9!?D->8< zBVFdKyA5HZJF4SM+Egw+XB%|POgON!xnsJHY18w1n85!gQC?H+aq_U)^7T^QYT)eL zS*B$3%=-RQWzlKH+pDzM+YJ3)p_!e%E5E<6mcxEdwpEm=%C3d{roZK;M{6$J6Q-~2 z6+5ldV$f8z916tuu9dwu1kJDh_%T^r>UsHD&FeLZ|JOyC`uU9QvIFMlEqmQtaqsVc{TOEe{ND{R(?&a$IlVs za5{X6cq`tDi7Yfz;reC!^Rd34StM|(e5iy501^J zX7NUlnAFpC-~iE#%5`)|=(=o!oGbh3ENzeoK|BQilikZ>ol2KLtDCtaL;jSI*Ii+f zm~UX&ZTeEj?On@-zTT?xO1t1|jwiVvBSi8yVx(C**0b@{waRDCK8A2>=o_dWl&ji@^}ur;+mDZ1nw z=}~7&S)g8?er8WFdlW5QrBkZ0Z%1LQb)-3C$vU<$Xfih6^L=jV7{k6mAH8kfeD)ns z5>^IqCP~U{yPUL}P z04QI{X3pOjAvt7}N}FiH<_}%c$d{>IM$`C&VYXSTB6?$;(HSb1Sze{*&bnPig{r{f zhbUXhsrQ=W4S8}UedP>M>H7NgaOFwt*!ueXT}k8OM7*rJRnzh7OWro6F=b#ZFOhq&N!l=L@V#iu z`Zs=Wj{)b#CtDM}acQKv3~pbW{~$3vCjMPr!v{63Kj2#%=#``6VLa^v>*=@B#?2Px zkOT1>=?!y=GZ{p*X!*DujL#Ea?`b&}x2auUGu`)scQ%;N9_3xpj7qizXv2rt20R6Qg_ON-8o<9`R#&8N5kGY>33V&tktQ< zDB`tUv*?L$NJ~-4!i$F(SVX61Cu!qFfqEE7DQkVI$xEwLTeI&!5jmj$0A3%?mN(1UCOUrbMMO$RKYKv~iRgAo0q$s4@ZM zm*gn6Vl5Q7MJJgYQPDQq?*9u71@ii{w{z?A<@a45A!OJy2Tz_qd7wJpV$L2p^=#+z z)wkZbW*{Hc_CIs(_`_*2{84Yud6?ZX`ud}{KKOc^VzG7Q;$37kpSv2w4kH9G!dngJ1pM8X9^FC(bWu z@HrJEy2mQ+|8Thl5DtanXc>QXVTYxRUt;l@-iRgS<>!dMJiT0$JdVuCvwDH#btEd17)jdEP*jrYiXZ&ug2`rZ@>Il zzdvwLrQWF7ll`D|_{>WOhkLytsx%rkE7(|HJ^KeM$atV>YpZAfa3$Pd3?oRGH(Q5J zzqE3q*B^RTtx>O#J_cT0`R0XYyZX>cF7z45n}bU zaCKgK)MTK_u7UwQTa_2|Myp%$(}{=Iy6MKsurlHOD3i%XVjFfnDaf7 zB{+}eBULr!)ePB^TK3*O63|Ji7ptLBOh)^->7wIM2Ah-qL=VTB&~ymSP6Ofq$OZn6 zC#mb|c}3{isxUf83T(!m4A0DN^*@g^7>4oh{_Vf1Rjbu%)wXThwkws2{Q%1{Ez7dZ z;6Kwe48yWa%06ZSEIB?hOzE&0eS%*OsSsZE2sSJAy5uhR#x(E0ssJv;54+bI5YqN z`hZE{AZzIHLQr4FE;uJKz2mqks;R=@V9PM*si- z07}VNKS%POA3gP?2o>Y zAqxPqdFS2ts2Gj(<|bTk3XZ0&4Jn4F9pO-yW^%M!(C>CeQZA#VX3q3|7Gv7RQ2A`hWXI9vV!p9vXbP8XXgG zsn?*;bP^@al~RvHNfCD;;2X8Duw<(4y7Pxg^s2Rjh&%vOWOr0prj;Cznmi9X1{(>H zu1Yvn8j~M4E6C#w(QM)4BVp_)>Wdz+qF z&BEjqySVZf{QOb&SqkWI`OS!S!BzP9I7j*VrIEOTo^%%3>Wbuf{5tkLF&<%c56^vp z+BjY+IP+O$tFu6<>8<+pYlnvhOp1VGTs#-9xT7DmAN)fbZR2okFrj+|h<4Xr`YXeB0ic0F_P+LowOiZ19SaG@1 zju~d>G{KQ)h}2&M+pTrvs)-FnE5u~R)Z9k-O@Y-+2GB~Vp6a8o2bV=jd>O-%{>rwA zMRshCmNUG#(e8V|4_L_MMvA_{2Ow!FM_K?)Rt(A*2@xt3IyvhzbKkqsmmLu(CC|2c zYYAxQvGkigXDwx1lP2?94*42JZ3C{CHZvA9M>Nw?E4lQD8`is7l&gG}qo}$ne7j7q z0LJ0Ga?cRP5aF)l@&_n?6HPzAj^Do_=>-SO8%N?m!ao5RegYus6PcQ2>-R512dm}s z*oJhgN)|+v*;PwUbZKrUyIjesPJX0v+q@x_i^a7GfLT@S-!~*F_ZDi5aKI-qD?L}s ze^(`En(CoQ)^7SA^$CfkA8vHUPfO#o#mAALr=Gh6sRH`s6T)UW_;=syC@5|yQpq3z0_*)8X| z;ufEiHXzvIC}J#HY?PUgGu25G+bE1%0|gdCvOOP*Sp{_A>UAWy2WxbKXJg_FvhejN zTUQLkV z>VwwO-=YU22>(HA?Z7bi%`piR4{;3S8CfHnmJM|(Pc}%m<+jKLlVrGCO|asWp^U_os?&op7k(Ux3{h{{#Zm8Y z2pB9h1%l0MHuL*aJAQpZaA|vE)6;gvhX(`1FmY2I@Ao#!MRIG2*E_ukt{Oxwyx7$z z?TTt&hE581Z3(>eomrN*x_@shkET*3e(!*m9Du+Y!}p$-I>Qwc(Ppw)xw0Uc8a-vR z^?Ni`^(tC&9s1d{Bd)*om~2#&J>8Tw_waruy!<;k2}Ke~7^&G>c7!p22lL?)t0EdMIO6&w>CkWMddF;U2W1>;x;_OKQMO3+kX$nu%kb@#GF|ZVqyM< z1AtGT!?=K-8E#Y)-42d;-NpZ2v<~MmPWV$~-F=j%Ty4I&s~P;7YYLzKbBo)>@@wN! zRDdN-+DHwRO6#e+)dCohm8zCvE3;LSMp68_&vn!xf|#`=0e7I(lvcJL6BZ};DRcvk zYFcTMwo1YyKB=t!0s1m4T(^1==%kN6cvDsNRduy3jwQfC6HOHAQ=`^YkG>bjTKPv5c z$Xr@uzAKsOePL7MKiM&pQB=IRyc`-CIlH)Uk{|>!Ckl<59>b4kq$Ifipbu6^w~S_4 z0`{N(Ko?9Exd{4_PXEA#E^Qc8?FalBhd4^EQEiuJ=j<(C7C1x@;R=ftVlR9UQ zwC-zwPn6vyVPotRVx}B~5{~mGTD>Lwk2#C%{nx3mNl2*d1Oxy%TNZxgJgmqWDpX|5 zUW^@Y%=7RE&a3PQC_cU(>c!S?{B*#F_q_dA$1%n%l?xs~CVt%{&Uz&xt`gkf!*#)( zqy#6L()Uy{uj`HjO%Gy4B<{NQO2+vzR|3Ev-mVYSE)uM~?A27Wt3V_y}v}AMY z4VKJT*e9@<`~ZAWI2DfbleW38LOCYZ(`_&m36Y1Bqwl}7 zG$Eg-3xbG(zQ{B9<{r=@luC#rRx)nfr)5tRwzY<9CMB&3N<>I(Bq!x-((1Kli}n5b zHD4V+Q}R~XLIR*&68N{gkvxGGcwviO4F7XV@kA)jVC(xw!SSIQRwF}cm7(>HC}V$$ zZ272s2{onfoeW7DIwzHJ1e03zqmv`F@!~d?yJOJ7MFr@@(zPE1N4(sSA<&$5k;Zzr zH;GQ2#qR0cTt~}{{#VH3Q-e+AHnFtHXIlg)tju_L9pV>I>+)^krEZl7@zDiH*M>lD zcz_NTe`=B1-G`UMb}7W8iA z?#b~O5$E~f{Yos*LnpotN6FqX85<)6g4`LBE_31+pA@4!@ea~UR34^;H@aZ|?7%Fc zmanIb`~I_Xy=L4a8d@`VvpCc3&cAWsx&_z4b*>Ms7j?lB9>^?2RCpg6qY_LTs#PX| z`CBIHN49aA!V$HRt83BMM)FXVg>c(}XGTtnQE))gn<9@G_(lSwlr2$2U|r4 z(x;&@x^a&mu7u}b@P+)IXT_i;@>Jq08a99W&;4-mzC^R@ziesflu*0sxdE zMBkP$e6yra3)nSC%>>YnF`%-RboO|OaK#6!4?UagY8IRv9b0``!FP{zjS@~~IwUpc zElql(Hcu=(wLQTcqCB={*`kXH7+^3&w$7>5OnlHAV(ls-r)6XWh}ijPYi$>)^c2i`sr#QwZ=V_&XV zcQ-nc?tT+$?d)aU1QYVQ$sx%1D0D6N9%!2?=+WRXe>p8V;m1;t)|l&P=`Eccur4Wh zNCMazMtq(QWVw6}s)qIM^bJnhp|sU^-aH2&_phb2@BW&}S*elLKi;3nRIKP+S=(;# z&d)&l#D6oh{KGGIcQMMxPvUJ9deqH=w_^dGT}Rf(6vo8V8Yo;I;%{1IDz@^u*F84GVP1^ndi&a=bWWCz!VMYbWmx9KY%~I#UJXQee}` z=+6VmOeD8)AGPY7Ew;R|V1RKBaevn%x&(rgz@v8&sGqT)!{i%EM3cqt<7+Sz8NX@O zrtoTQYPt;W07D#1*yA_IZg+w%qG>&$U%oyN1eDk?^h$g4}e~>-Hz;gJBe7-?}jc zL5qA9{chueL|#wJ@$hdW^~Y|mt7bn z8vUx;yENKwjr$y`&MKUmUC1A_D{XAXX*TKDF8#-^++{w{3CU1cMON2gQYT1i>c>b9 z?a-GhWyt!lUYl3Ez|YoY9jd$q>k``cxK~Dv^!p36(Gz9e8S+$Fa`@VUm)=|PSQI}S z9*z>*+fCtp!f5o8Su3kF9Ny^ltMV;c&fGa(-H&;`OZ}F*LdN*QJ!NRx_N#My9T&Le z=kV(l9VO=Ti%r(4Wnc;Z`|~^h%-+t6fYH&S+Qt;C{|*{cHyvYxHO7*cc#`1!?a!2wzk)SYV?8hGUr;#1DH zdg&LuX&?$HTl7_nRt}X-tSDa-3 zu@BtXzs%m!8na0`8~IYnrvwT*Gn@-rg#r^XNmIGj6&4YbU`rbS;AQ8UptrZ=jC-u; zkw+|1`F4@~?z0N5|cFe!X7b3?R~ z*_yK=d%ljI=N0}U8sR7u)ozJJkgSTFML^HOqF6CU$5K;MO>fC3u6%a~hdL6Mf&~nf zOXnTZ#ZRE|GBCq*!k~^U{c3;yF!7h7dDH|?EZL6N`M$G{Ug~M5MPG3n-;4jko&gQ; z*Hs_ZdDg(a!yu5>sH&82Bt=#j8)4wY{#-TjZ85-VNy;~=&AyAB7RJ@}9ZE)tK=-FGA z-aBsFZBZCtL#@Ng*#`jVb`HDPKZV8Xj>z)i!6~)ke-aNPJdf*%alI3%*GGA8Vm+;t z=B)lM`$u(H-2VPdYjFM$EVg8KJO_#FACu!SwP_Isg&jL&u=0n>U-kKQA|5 z+_Hy3t9>@a@YnP-2RDIYDvu_87;Px%SO{-r++CI4ia5>soo-fX>U+1`gvvvB?MQ|K z&Jj6^0P?%eZ5uC~qMv^yk-taCrPR;WPLOaI2(_6G&fe;XY?)|#^WQGVg@ue$L)Qi_ z$7(m|48{9T+`-#7vDw&@m_^6Y1n`e{L?8nyW0do7OA80%T`1~GGLoD$(i%d0bnR^qU14iE^|t)g zxL@A9nj_M1R0*-!JZbf(*=cHcWr2C7P@Bob1(Yxq(v9|QT`%37rGBxMR{a}}w2^8x zwE|}{UwZ1hh(Gx**AYi=4KpLD7@~l>J`*@O)gSiasPLC|2O)bo9WC7m16K*A3<4|a zKhWAn{*FeXIvMKI&~PLsarKIXF%m6bp9mQ%yQh!g82nfj@4^C{uONMV3)VEQxF+N5 z;i1lVJ#E`Q=9dE%E)81+1&}1#6CQW&Sbbz9o|^c(^t7PSBBcFKH#y;=ymwQ$Qu6O# zaak?>F(VlHA7xVwWP-&62tYA>RQuK0djP0^X-|FWJv+=^sEtJ%PaU?c=dg2Zy%9hdAufoMuh|FakQVM z-h`lgagBpQAmVbOexFgoILtU47!*_pq2Hp0q6h$kui5y4RSP6@8~@;x4R$AQGVFZ% z9Ff=%7{#?w4%vV_WXp>VS186ozLo>2n22+mxfUBhwXqZjs6^fM=z~H9q&h#s5;gLl zN10J3uxnX+m{?8JpeM~NnA9`R&EUd)Ow5twQPom*>ck8O}oR9c_Bfe zb=afy%C+WB#|3n!+gsj4OPnogli%J4Wp{<;jKl>UXpeI71nbqC3<83!<|efOIhKvG z4BZd+Ns%H!tfAaM=weHw-}K}-tG3)YA{^lZr&XslO%km z#pz#7$%)$r?Qsz>eyy!`?R;8or5GRlF0=pNtr|R zMwvk+@BtpfJ5v=RV220z8%sxZcp5J?>noU=4C-MCkdd$#`oO$L0LYW4u$fOD55q)l z^j=OwR2a7PAKbgMOT=O=H*)R;xemY9M|i6N24n5M&ckL0*Lgc4N^56hmp0hge+Oaw zf0B4P?r2y9HugDTrt63E{^DYo)Hm81Vo50f zpYE4yjn=#=?!4b48u`7Tavb#I#GJqVuD#c1Ut>E{7XA}*fyDbx`%bk1)T}H*W#vlc z)tbl5&438UZxJdliZbHF0btrf1ezX^3+Oa_%P)2S$#|4fx1WVo;yJlb9$*=s-f^^? z3v%XVmtjLfLQ*e+lpkpXGA|uP1_Zz+e>=(CSu9BD^*%peNhBJI2r>0Krl*lpX*7V7< z7nw8Wadgpah9j;))-}OwfcPGyRyYT{m{k!kYYAMdt^OwtaVXK9&21C29b6x2We&Jc zQye3WnuXW1W{e0uD%(0?qnTSg@Wx)g>fJLh|7w`tZD_A=en(dRWFDcQ<~or3XDUER zO^XPH0+h9g=oszZnjWZ6A-wdrWg9$P8I$eNU9SI_bRqRpdaO#0f>{-O^DtajhQh;V z{9|mnf3Rzb`&F`W-@54*%&DJdiG==@T3%HKa@F2Rj&zdM6kC_9!F zX97)5;10C^*5(2*;!%qyQR-5lK2hT$@}<+qizgt#xwa*^rC}feA``#ykzoZCq4ag~ zzkj-W5=UH74wf4_SpcbV!1z&qvj7nlw+@0*JiY*&cp4!rVzj)kAl{WVkChW*45hTV z;%26KvMGMDQPNO)j>`f2y8zoFWG^nv*Zh-4@uRKBV0xsZMh<<*zt0Iq!%f+ZPi$Zl zI+4utAM3A;AVKuHYDI?+34)ZlL=BmEO z;t~RDl1_5mEI-srNp+L>EE<}P4X&m#EFyXi*jd1_V7yBpq>cO#9R3QU2x5F%x{e2^ z+aS2-pHq9phH~lXzZpFZ%&zSGQLUJOL?M;{CM;GP7^SOq8YNYzwPe9LWuL!%BM<%o zD}3wT+aE8FDT$bMz7Ff~I)-vJ-zc#VvzI0Xcp4?PN@Xs$$9oN%dMpa(#2y2f*NyFg z_~@wOQ70xw3V>0{PACXs)_!-S^6SO6>RqZlLyAg#tDRt5hyXXHH6;}l0&Eb&l4}0Q zt^I;z-BfP!`r@Lt_0&yD5dWER8sybeT~+=;W5A=Dz)q2C9j@G{>&TA>5>v?^T@p9x zH$+d+X?~HU0^3_#P3G$6#789OVDj0&*2((5QJ@d^oJKQ3Uq3-H5`)6RC!mMO&QxRa(gUxyq^G zq5FWF^l=`i%E5tq0x>lEbHdd%SEPq4#9AkH!Mff1P6iyMB!~HOp>)_DyI%d$k<3s& z(~@`NVa~(DwcT3LLBLyTly6G$T!*(;4d`htfpd1mGp$$qEOX0ZC=BlqyHil!HkePf z8$vGVrc6IGCa54K*IQqVdY#7$vOw_IyQ9^2YXe@F`_5X5A95h%+?%hsanw`r>&l1kTQIPR@yYHNQ zRLI~_QBpdcT?!k{=k?wkh|Fj>T&iJb67bmz8n*gxaEN~;Ozq-`MB*a3m#HNXvxwH2 z=YQP|SzQrvm#sBgWcb1`$Xv`MS7Z=9SeGO);Rkv=H#rOr(tW6^;$93UYp}Lit~HSo z`<~&q`n(Vt1!OAc1g^BWZ1Ie)t@(A|Iv}8vI#T=EF5^dT@I;2SR|K(j@8 z`uK+(hmTS7c;lRIl5yQ5EE_n$Likp@e4$%0%-DD7~$% z{NKMpuk2u;qkH~4>rW@*uIGzTvYMuj9dsFMg|q7lVMP7^wE%myi+(r9lja1c%Qk7qq$toc~E@d!Q}Z(YRZ6EEM~MAR$g%T&4kd1*aWn4I6B`#w0^>xXh<6Y2e6<*=?>?2gm2!?k2w_tsfAF>it-dyTNJzowU4j-Wxw+b zf=JOjgvTJLTLleJ%cb5v{tlU8L<<6q6v&|~5(1U6pnv2P_%{+rP)WzoN@vr`#N?vp zV8enV2olAAoZo2JgkAO&8<21H=d(ws zMg^+om0HWy6=94KFw^Ly=DU!JOP zwa@nB!iKr`mdr@$}~Xp5G`bpM?+V zT;W!+eKCb#brJbPD{G!TK^BqBu_i(z79TBiy_=6o_3BVH}u5_tPP1s#rkW5C?C1b zjhr^3Y_#j{r;vJT)SoVGS;&CDJvkW!YxV9!2t3#?_l{Rz8HtntAd9Q0%+N;YX`=0F*%RFBeqU&AO#`ZH2 z0L+TAjMMqlm1}qmftTw}Q=P-|ItK3c``8Ng(HRI{{9Zm6(( zd4?(Z<=fA)Gy7~!GcqXB)4JEO?j=DE@(Y#{dzC9j8YSPVjqu(Z+ow}*QuS3BO z)z|Z4e=T232v6jz;*z9fy$f}{?!D!5<_G^ zEtet6L@K=SU>z4>_>e`=Qs$Hm3c+RP8U3P2> zb?oY2`BO3I?;j!ololuT@0*}}Bn5Cab)u_!-naE|d3W4=-v0&Pg$pR*67iZlXLM#a z21R(^E(m6XFWk*#O=B5;^(c7Ziz~L_HgrcYlMK$^!x?kd7q}YN4^qiM#^|ns6wcB{ z2UaVycl9-0?92&VLDsDj+7{*T<}g1em}n*#;$PKmW6u3F#5WmBI<94j0g_6mx7WIj{a*Mkwbmo-D8PQV53C&1@xiKpcJSR~xjr*quy{zB zhM%X`b~c$pzII-Bh1R>_-wmDC2=+)^e+qMN=Anr-t@o_(yO zGJ4};(12i_p9)Kt7I!g@cjBM6h)gFNITYVwZue-aR1|z9CugA$Omv?uv2#q@SjQvX z8$MD98N(zGu83z3P>NuPY_tHql|YaIZMdhaWTONcx~J0+7g*OEj-a*>3b;O&CYp+g zbC!E1v-~LP~M9=ad?z1H`q=5dOMfYB7b)qMsXy{&q(U)#q$et<$y-#%4jnBfOu0DlKuYl0^$p+JIDsB!=$1^Wy?7PBEKUk77I_TqAi1nc zh_+0)R)wi?3i*nW@Vn+-OZUB{?vBteNC_sq={t@8($OL};tWKUm4$I=^B?OME8ND?Z2yV^hYGrDTTMat+=c#;H{yHOX-j8I zemVN)D*1MuTe6eh*9~b^i?(5J?mhMeHjrMrCBbE1 zqnxQG)l8G5dzQC<<8v}{;v<8RYT{!k_jfiR_U2H4^R zEK7~S8;rq=6pGvoJt3|k?69Ob`z%YI2$8luM1N2enr?E)L_cT8WJ#%dYA&N>9#M z&Bdje*8IpWG?7i*+}e^)zW-uuEH?axDOD5kE3+&p3nN6G*oi)>4HUG{(}c zI`k3~GfoUy2dZ1mPK2EF{f@Nc{@8WARQ=1@0;6U{MHU90I0n0_c ztqv^}5@0P9DT)50tKeolT>PT7g>kNq-C*HlVC*&h9w$$I~NnN6FQZ zp3Vgvr_Jn+ozTU@5-z5Jk5+zA0+j4XHWuWIf(Am?I<5saN;C0;$PsBKUxwj&_ zK>ERZz7Yurs&ja_#-${|>*knLcMMq5!o=6ktRNVPy0V!_L$bwY&s*XnOr zdvIOa>b%FgOQ_+l1B`?THC4X$%(J1egjxuTW#9Bhp52Y&pme0-2#wa-Uve@uK|Poi zXwHsHCR{k8Q4nR{my?hkWX z17nm(tr2>2p`QG>)r@{^wolJb2u$h>^2+KZ@|duZ8^O+g2FRyXOZZP`%d z{QTC-^Ja6tZOnocSw=zEV-aLwIO5~FCw-=0mfssuf)2LQ$Y{ip4`*=-NSwo3uzVswzIM zZMrpw%XJU8XE-O!zFsSfEQ!9Sq_{p9uE*0K1S!C()Z@;s?`@t}5bT@16|03wDy#O# zZrg^67uOB64Ag*Q9&V10#NW|C$9tI}mK&@>w=Z|selNS0@Hs*zgn3AUM2%R0YFI2L z_s^d{em7*lUS_*T)A-^&>-&Tro<{};^Js^Lr((0sx6%P|Wl%e55Jjx5moxm14kvP2 ztlrct{5v{2+S)<_v>R-lj(2#4YFm?q!_dS8T^Kq8#KI+J#N3VT5)!D79I>V&pzB9nfz zb<=-#)z|#5e-IhrXZo&%njLlT`=%bln{&2y9-GjhE~TIPnKPE}x_dGRI0N(dXo3VL zn$=|I7=6eZUv5KiSme@8IXqpCrzft;1lzoxsyF6}V)d2u7Ok)GGJF%_;{G`3fPQbF z5N~;?WWadZL13Wr`icy=ZtHV!B8B-%9Z%;@3vJqdtM%tKEWqEqw*@Qu96~Kzw6bfq ztIq7A>1;LC5>W&%N6mGfY2|%Hf#XLk)YPu?u|2e*F(uC<=&pyxx5x=${ohEj3kvVMVrR(5t1?On7}vKp9&cdF0vD|BoOa5o<&#G}p3pEbFm|2~4-Zuf6pn9?qVxp33TO7uk(*{_%7?f*3njf~25tnA@7Evg3w7QkDk1s^TFWHsBu z6vI?iRbgRaxvU^VxP8~E%Ff09yJRL%04!m9y*5ir`JR_(=BCrCB|bvvjl`V$`u~0L zQG5iJ$nVK(e}zO7V6Exk2L5=Ku76Bn`RMj#`Zd}C-bkR(G*G#%<-OIc5n7J+ZF|dm zhUMH4*@nOrj+5hoP}}v72UUTi?U5<0u7~rzVQ)1qkK-9MT3cI-KSM-BL~QuuDicCq z6$G4+f`*Y37y3)$ksSo%0Be$J2mxpoyF)#|`ez3rduC~&UudvhSuE4$Zqqy2+L|d+ zEf^De(ZTIaw$#q!vRRzYmnQ-Per!p7kt8Xa3m3oMzk7#H%3o+r6w!wv^jLYl6#Tz2 zljOVO&!DihV&dSaa*2zH{SL)rSWaZC>9}e6$QF2o7$VJ?5jm)G(K@njzBbN1FIn>- z7sysW6fskx0a7EMiEQzMxr&>!GhUDL&GW5c1XO%XVq$NcAm<$Q3Oxa%zHmGS^~;kr zAu1}9zHkB%wD_ENmGB-IocUG)kZ>$pqQUtprTx0;OT8xfIOoEEDdJZA&%kK0)`H#i zk3A1@0Hz6sxHA8kVhY!Y57rQEk$o&YpwMqzhaS_y$(b55$d8|bcZgFOUf}80e;jIR zJAZVY#BSDpv+6Y_aFbeH0AkcivkODY`F9M#+uMz(i}UmBoE(jEoxOvDl0*G^>xF;4 zVFZC5cUy@C3Teo|TNXWHA>T)^5BGF3e)rRAlVSQ$;zQSmQq7uGpPQBSo*)?i#KgJn zkrZ&|FI$QF3aLB}zk{*hzpr<^JP!{Iou8fE?Uz)Dh>FrErl_DU5%KMup(ZgtJ}8>8Y}3=9D+BW}MWNp#0?~+kFGjfE zOGegel?{>BX|=f?X(=j>$;c*MeeP*=W&jF3+O<_hGs?>V1(MJ)1QUKWw-Hc~HR5i5 zhu~;xYAW)d1w7D$LR9O#H!1Xd`<|cQ`|1-)-i8PO5>&4Fm& zr+ZH8`AVOMYvA?mI|9c2!$Zg8`LNT@=+pTyi((pIo#jk%ERABaT>kw0=RiYxfx%bR zEGw9>oVMkHdb%ziv&F-Tu`Pg3a2ec`E0{2o;sFp%8>$T`(ZM+Uh~v?{c*0 za(lXdFk7bjEduMk#O=ca%%_*D(R8vzE@4k^@*Y3bWywc*P0Z+|KMMd=^2+Xm8`$->9|KWpjo(d?GJMP7& zr>ASa4`_gjs;a){ULFhrIu9{=%L*w00Vo*l?d`5D0yH%JoU2j_3a$x7ut-4WZ%S!t zX*@V0@LgC~n7E&g1q80RLTO$J6VaRrTwGk>Q;q3J0;47yC|zN1Sm$5LAGU}jcWP>`3eTRQ6M>LMT@;7VZvH$MceT)%@9 z7Z(-)$1%C*46gR9WgR%nBT(WQireHwJQ@CtYED?Z|k?U9CzTYnylHJJ#b3n_b zrHpyr$;@VW6`7ftxw(|Wm~rm!xwvMZU~i&9l_ln7V`q2z^Xmi38^+tsSjA<^SEIHM zJ6z2__J7z&==IILU!t$)#pFaVHY>b<&;A2D^9bQecZ1RUjbnBKTef0IF=$*~wW694 z1D_Ri4Gs<$Y8Dn2aK)Rbz0L<|%tn&0K&Lk-Ft8nLBr_Bqj+&gW@Aq_NGMu0bW(-Rz z+7}xg-UFN4+aNlsl+1v##L|A-?Q=9V@Zo#cU!8~{bB;&?b_wZ9i>dr7qkgcJte;Fk0Q9F0?+z+Dnk!ZeSX(bfKZ4(!pPst!W(CcbYHl2|kqUTT z)>=#{WC*U5>$bQY%+h_-_t=W3Q_Yu4=CA+_Acnx@&+1siU*LS@Qh6qf+3p@5{J?c4 z`RH0&s8X}Q51K{>jdIWgfL;BK$YYF{Fy?>c5fe6ue4zT#;3cTohXbUKkO;IK$7Yl-sIP2?H=b}l98*M1 zW|cIb^idAYBwBrA&@!8I?fcU zfdJmFcJyB_&GIu2l@rY_Rztm@sQ^=MOaclm*1C1d!)>P1g~~%$H!EeJwC#*#xV3|# zv;lG!rJ$o%vB7M9Km9b>@M=^*Z7Z`bfzXF$Q_KCbx7v5~k;N5HD0`^+T3o~>*x%U5 z6V^LfYoWT6E)hY5n2i zS#4{XFt?t_?gi(h*-}uNPent6LB#cEZEbC7$qTfDKqYt&Q1R$b-r(XY;hNMe{3p{O zWP(*j;LP~!|8|1r$nSPN$Zgew=H0t5paBQ$ul8pUNZmWlIV8lzZRRV5>9Xi)DocO< z{CRh=;|9X0$Hn$WUqsE)5uh|-wt3GB-T8QT0Rk{8yeMd9z(=^$u1w?jKAG&WbUaRW z`1#G%H=*aK6dz9)se($A?y*fEjH#n46T<=O=JV5ocG+yogY$oaajfG)W(~>JYx9&% zU?lkPC1Amt6y$fO>pft|0u8v>8GE@|^TQzF!zCgDl~>4Ylo*(Abl6y|vjR^#gK%-Q z)Uc)`4(jSchu=${Y$75B$YW3Itma~3VqTe+Lh7zu4ag6`uks5DJ`zWQ;IiWP@&xja zr+YA^YV`&%Ha6xz?Sx@zJr$9V=o^Y>$nZWN1UHyafS@iI^L#fa%G1+RuiYCoXuSkR zaW4DQMQSDLY5X2+G&DO=LeGduNFMt|1%appY*w?S^YinslsjPy6j!(1aSBdO7jS(+ z&bbVl`S{jjMFa8cleG@FlU2|T=jG=!Yt>3w*obFDUpT?~gCRzcTe8y7n1MGD4MMN` z%&2A|u>b>cJOYVPr$3bKqQ~FPuOJeDqIV1qbrcf?AV%*8dBOR`1;}WNC(M_9(f?CF zx2$FiE^5W}!-Lmj30wdby9iQ&W>Ct&iz6c$i;0M$xFh#!F=5;b(l>@J+T*mjhXEkPtOxoM) z>s=S#H^(asGK1BnGnN7_`*A(%!NI{G#bt{B3rf*kg?NkPWB$ulbdTE2pq)uOgCrt-Pc zpbIR~KnJ$;ent>+m;1duGpLs;^{HzzCWMEFo27dMf*!{ygyS?U>p)2 z-kQ}64FeO8CLIG({Rq$;fLwWsLsv=3pkXP#hy>(EGK6L72hC-r9(Zrxx`FJiu#ncI zW5L=MB)*&qgG_j2WMss|I`Md&$(&a8#)C1uPTM-I?hc?pfQzBC8INxXBYz!QHd{X*;`_C3=5d8(C@HbsNUQ(4m6C3jb&$J`)@hy!KDXn zlJgqN`o>0%wK+%f@84o34PKzrOEiK}* zFF5-T)YPW`euwCLpNV^WdxOo~-QDqo`W-PUCqF>&_7>|7K)$`y;&yU-dz&&4`HD`? zZwns`dLrKHdsl%B2;}pgo6(YScl`jXVRyjZQ~|?VdytQIJl`__s2~`DT0TU)oTA6e z4IZqlegqiK+1lxJyIZ_l8}*c zV$T!zRr*y+8tgLI?p8enS#%mtPdZ+}pO|392MN*ScSE+Ma-F7ZO7n$k6La%jkZ$kU z^Pm&+fPx+fI-nW_HehpKFnO)6KHL2RB?z4aS?wYG{QMkzguVLzQTEnRS$5sG@C70% ziqefiNJxXAv>+)R(p}QsDJ`HN-Q6jT5`rQjDS{v+(xG(2S-j8le&;vFcm6ns!Em5> z-}k=uwf9agY{V%wM9($_`>zn^c;!OoV zTiQQEEZ^Q45c1vsVTM$~k^{a0JDCUpeme%7?_{%iK%Z@Qb#(1#qa(uRb@&&8tTWsg zVE^SZZ>L|IWq7N_F92QKT^nO%W-eVNJv%#tzxJGz16sw7>ALd%Y#BNr?Lu*quE4U zVLub$q+*PvK;es_RebwI@$EfDJiuvB6baDUZ)3iE?Q;cP z^~4;!L4{2jG*N@rOfZ?YGcBN2{U)?c z{gVjTuJI^P;$ULh31a?K6&3x+VvF-1Y*j2(|K~sUO89Ssl(_#JtzFtA|AX9AnC$w| z8Gn1B){{3VaQyS4rbjJickkW%{kuCB#(?;#>$)%GCFmBL-u?&6*+=J> zmjGyS9}XjtE*NqCGkpeGzFR^-d7XOh0 z%M=d;$U%G|Lc7h*UInW~USRKASrK40EoDUrU$D#`=(W6uU%)bjO=@atN(FH5n0BUG z%8bS0SOTj5^{5MBb9I$GBat+o++uR<*Std zFdkUic^XYM1!D$bYI33cCYlHye9PE<7@xI!Xk%jo%oKu9@7J#;Ep0%W>P#P_<+fHkPNe^B(LgtJW9)%wVVJ zgiJt#Qqj+96B!2wj@bOuwktPM`JEYQXl4PzXRsSVrL9VV;S|Q6z^a!X7sqWrNYkiY zelmIvVDOS}!|<+=^SsI~gc<3FnTEju(g!ws$~o}3Y`2Ak^zPlNGLlUyP+(ADR0WaA z^UJ7ittD8Aipw8gL5fuPErxUbuV4&wQIe1}_+I!ddd;-JR^C|alfn#01Y`(ff9JMk zNELnXm3IaW17p&m6*GVaz9my&(IxT%Kycqd+MwbE(4(&#G}Y=qm&z>QJb=a*kSHN6 zeD>mFiR~UI-QS!#feE|-9WN{_46y@3vbwqo^08gxPgrV^)I#Z$m*5|S5>!M4Ppi(# zeY0`N(8vfyAA}wdX`G#%P1h+ve4K3$M9~LQ_36_m__v^-poN8niuc>$DJhe1A0C_b zk#v+;T3UkUer@1##f(=PfR2Fb2dQiyQlXIB-&vz*fzQ|3jC4Ib_%+lX_hiAl8NrnY zTkvG~9It?CbeXy+DL=p_1nuDv$kr>pkKM7ULcTt5&7h)QvJ=ojsN8?Q0fMENBk|n1 z`M+~x?@cla48S58_T>5gq%DvahJ;=e{oZ&M*yVF`a~w&fxw$W~?l9iJ9~KqGlWMRr zQ5*eu8#9Ls$pi`M;lsq<1rFAZj*cI1n)Iv^;^M?5BsjVtc%k}d*3^7^l?L|3K9q#s zg)KMfylQyGjLB= zARu7ceJKst7N>;WHlBWA(T~HliH~ajZ z6~TCn_3xH>SWZlS4b^|Ps*4Ja*?>?k1ZlGt@WsXXK`SVR;^N|O-n^0hq5$|zM8tot z7B)qHf4|SclxtD~+)TJ-_oO&jWu&FY-!x78!5sejWw_Xoot>SR2XIm4-mTi2no6U@ zTw~>zFJG#tsa3NwF*083dVKn~quFI+I1L{$PyVh$iG)W)h>3~q(eZNKnD7@1Gyzcu zRz$)BohFdCBUoD!Q&aoywb0Yk|Cws$Wo3=N*9~{LsID%4Yk=hIhRgCjSd6fcA>h!6 zE5hy;1PBDFfB7YS;N?ok3}9=}wNfC+8?{tr90f(Vr?=P0$OxF2z~jdr`(P#m;P^sU zmx^h7d^#hmvuP3&)f0mb*gM)+N&2bR;Z9;bT9nSc!uC9~AL#s(J zJY(bFMCN;)&Qo9Dg*^dneHlp6Tj|SpNe7_>ZY=~NkfWR+j%b#-K=g*_+cb4sHfikh z(=`py$^$mx9yOGHfE z%ES)fz$S92wgzofSkkl3#jE+ zQT^wdKuln`f1mV`ixu2#Y3ZK&86O-(H0v*DnaTXlmLSH9iUuS-b3vfc?g9V`fWv^` z2{Qx3GKhe@6nBXtVDJNDpn|@6O4aCjP%ca7`74b6Qqw1jfN>_Jr=No$yT3a60%pvx zszG&Uf(1ySJ~^4g!&Im&wN-M@fn3w*upn*r3>5(soi5;67v$>y&mtKo&K4lxc3=Q4 zfKtGNOY1eZ0RtoBuv|4pFKP|{SwUVzrSDAo?_3m~XE7WeUTcAPXjLdUz6)fO`JOQX z-v!2-jvj?)OUC3%h68@QQ>zKGY)r0N&JaN2GPRN+^KWFhawGHff|d>Ao!~1 zCe*P~yE7kx7z9zA4ipm02!5pIYQu!YKX)eg?%XjO<5N4xFWTU=a(T?Uo_Amr*= zFaH@gjZRemeV*}Y%70=PWwdI;QK zMh#eNA|y{|=h~$98K|v+;*)Bc!uh<;>bbFTZgaCI1S7%oL!WWo?x184#u+b1t|CA0S^bRlNVTyf8rz63!tc z57?l-Ktkk&&YU2fAv6h>m8zp@&p&Yq3BXqRlDT_FP4E13y_DC+B5VQ$|u?7#~W%~C3IaB$$Uot7Qh1-y@g zg9CNUj~yKe%+EhwpKNqAb8*>+iZ3T8Cs5c+Z~~G#aQ0HDg&@TxC0(ybcR*oMQ&+D5 zc^7Cf0}~Txtsz{znwlD<{-lIkVZUJ{DhvdVT-M#7A^_}>64EEoG@!G@goHYc4p)&& zB_GN#P*!dN$e)!p2XMgkud+R}?fb1@6-Hca>}&>0&>;S!WF8*6El$0DjaQ@sTv9b* z;=k*GO`DY`-E))A_wwsPBoMudeq>|>1>{?*XkOP%?JAA+xw);y6kCX|Yf)I3n6JBy zJ0N|r8$R*!dM|lTT29V{fmj2WpSyEXd&OLn0o1DZJ4%p_P@D@$vD% zJ74l0LD)W69gXOiyGKX&EQRM%zY8WlUlO`_{=vgpLE*ImgV$PFJrpo)X1abE>p~q2 z)J|LA^$;i1)6t>N{TqFI|&N=0aXzkdDVH0$sDxdhq{aE0I! z+n)_@vJ2tg0PPgKf1k?dzSx%p;2jp!moHyHTP3H9Dp4s0yakFATddIjxRGUTayEmf zAo0?jH;kBup`?V0z=c54Epg^ub|51s z7Xq~X@#9B`O{OL$5W!qQ2uJlJ0kRBQ z_V+@?99{3dQ4lgYuSi5ukOC(pAt50p#X@X9?0vsfiEdCocq0kF`e7ei0Ei9b_)BXB z8QF1#@7W6|y*MuRq4>eQ2ew$QQT1_VrnRBL4H7|l9l^hY)W;)|puL^;3XsLFiqrG` zKa;VkTy3AFlq90-BiMleeEcXhC=s%fZXE4=qt50$Dw`qZ-u;+6Qjny|;=fte-YXh4 zuOW++C>ez$RVyJjvU?a7J>kWR8Q`Qi(QJ0*-x&1zI(9hjKM4s14LAB*v*o$BALHsWWPQ<9_bjh60)h4XmhNLQNvwSN~z(z2U@3bpsH zBFr#^)s*rk?~^*}GtukXQL>jUlyK(=9m=-T7|FV7q0|Ss`FYCdO zMCH>TV2i9ZC42erED>gw?D@Wp`)+eT}kkv|}50;6$obOZ`sc=8=W z1pJVg0dVg02=)i6u$o%DFb&`}_yVn8T`S%H1th3M4wIhNi!<9r+WGJQI6g98;EMgb zP9AK?SRuk75L#Prz)LO_UO<|jZf-9_LWB-}I)aWkM&3QY1$7rDq6pv$(_TAr64?)< ztS9SObeg#C+!19U01a5_pbRu8KCr{k(C9Z4Blz^Z|y_l<6W*Yq*rglD(7cQNQjO-yr)PM4Zy>Xthr9=?KPc2Gv*S;z-`<#lO(64$h^N0L?&G zcN)s>;&?_G8EEwJuuu6?G9TwJ zB^(e0J3Bi-aC39>OomlJ>X%-OW`!&T5F$9^ioTcY^rlBgN6%bF_McE#h5}VElXTwj z>8V%F=RvNi(km%!xCqS9zKQAUG=e>{(o0J z?@?6+6%eXuVsi3k03IM2xPTgo2;+5LRs(f(rrw#!!|WHNdlc8zsr~r~!lg1n-0RnD zKBtEOtoOa3^a#2KR4vbs27JLfHe~ndQd!lzI8FeB21{{wI;MAliXW;xm6t^D1?+vG zpm42#QZNv~4BOTGm!fm6=X(`Eo`49#=B*PV9Ak4@9)!vi9UUF||DHa)CcWvqL=Fo* zajkLH8NNNde0 zO#c5&K6a*PFo(r0^!Ug(NXyikf#pGp;^pFc510k~685#?`|Vv_2ZR3J@z)#!AcHZ(vF!E5P?zJxrlU3(st=Q~)5_$@S`pgkW|9#lZ{9j}y`LzAIfeK+4 zue#5LtVZkK%;_mK7B7ae;d-r1Q6_~QF^^yj!CB||w01dKbt^qg5xmZY!=s~zMZ{{rV;qzZV3uqaKkkS1$g_or@{aZ1UubZHu-75u}e5P-iSyK`p7FvG4oeWhM zkr}Dgluv*9#V@_SCEX~^o7aW)E%iy;w`MulooL@#>p2ycz4~|Rjap_90zx5VX={7I z?49gKl0USwQ&Dk(U|14aEd)^f{{8##XF1R1Os!m7j)(*;1?c?ou?J4Yzy;$dlLGVZ zcJ5lOgjs$H1M8a*;mpD#$DAbhV%znm-3_s>X=3V&wv&&+zqfbRETmtUzNfTcc;va# zJlCZr6XmX~{wLuO3s+vLH|g z^^GOW%{44mHh>RP@NIV$Dbpju%<)cwqi>Ruun@>s{~aeu_YZR$n{*HxA@Uj-8ft#f z^;|0*3%tEM<@wR?d);7deU17%a}(M}!D=zT6fCBaHhel3Nz;D!f3n^7^<-b28)YA< z`}_Fxt?PrhbltT{$86zSmZNgDD9I{IR!Mlt?@I^poBi`wZ8PpXEWeMjPRLh!_+^qS zkM^MrnJQtCjf$GKsa|ohQXNO)|eF6bfD%5t`pB1SGafB5zo(VvOW;c~SiIWq16{^y_v- zXvnpv(}GEg9*a2DdDG2W($QgSZXZ1jM)C@TVyRF3Xd33kbg|`h(UIcSpDCV1+-i$> z+AY3)MpIqhpY1uRghxwXzfc)9xS}_^{Rx?!^nQ$RjS>-1X^2>o$@?hx2!DpJ2>$zg;1`GN0u)^mSr-N_;H}S!@`xE;s z*hlQi!*0QJ2X4P#xZ08;+86FT104lbtD24*Wz(E4=lTx1BLDRQ>~-Y6&dnQbd_Iw{ zIZ)|;L-ss)_HW+>#Z9!KPXhxpy}dGwxGF^|!5m^YBy0< zgs>uRhfkhHK3Cowi}p6V_A}3w4 zQAyhZ?Q@G4$6nLZwBBYLMh_}l(&H-szHQ^Y=7;WgJV}qgNPWdmhCD=l(F)gVuqTxi zZN-wU{92Ymp;FQIwoRQBOJ#B35Mx%B0T|@K&4*C(N``=~5dk+n#3CKG=aJ!E^MGY) zM%S>YqAk?|n$pWza(f;K8_{}im~H&AeVtH`z zD6+M~crk&Eh+b&eKF4mK+xpa=)!j?5Z56xkc!Y%$we!jUs8!I{P)@&p(f(_=VTXaB z;tiZD9w_Z^Ufw(IdRCG^{bH~CXG+Grghk3*!UPMYjZGGOx8N(n!WG{{m^MkS?}t;A zGo0fi@SYW4vUG2X{YaRuo+)+U7iB6u0E&P0#L1|g&_cll6c+${ow+WEFoyJo{;kdh2X{~` zORO(R68~d~$6zUFXl@2dz|X@|x3~5o;2Zbo`w54^pAoqZo`;m@U*cA;RJ@3O@9O(H zCH~$^#V`r8S*$aLYVk?!-sQ;g`$+^vEj9KGdDh=4^KBR$52B2tj(*WxS05Z!=$XTQ zXtQbcIIh|C_tfbOB0Qy`=%z33-7OWaqHG)yBL6l?3zn!W^#vbN7`MRd!qQOn;ylpt z`bwk)gMj1O-=6$ca<0LNMgDU?+A={>bVcDm%j_>~&bFG0`Nt}{I+yJ;{)+qOqkBHR z-t5gGHmO}u&PsUPh57zY`5!N(N$oMWC60MGIqXSS>?P~s=2T;p zcT@Q<_TAdcx#N}S3>Kytud#?tNJyX^I}tqf`nuv9a(JTT$|x79h~cU}8Z#{wP42Bu z@pItoRKe=%{_J@K;)i9-A#1-VBbvOnc|`Fol91rXo!2idRYu>|JEc{+O>Sl#cm7luZDQe1EHGyW zAame?d0xnc&=~&;Pn~I1ICgxJeygbk1*vIm%{tSeCvWeP|Fkp8rIatNXx|V}7$U^* z@bH$LvX20LQ==!Z+IgNu`PE;x&1M!E^w_?>KUhtxo6X$j{1Z++WStxjz84nz&k|7T z{_y^3R^06F`oLyA?)Wb9ng!clpCW`lw?=M(`25A^bE2U4rytQRX6S!@Xf7h}>FF=u zxh98>q)SeeGUVUKjnyo(E+UpXxrJ6Qe!HUoj26P@9ErWc=~TcK5iA^r$l~?W58A}4 zd(LtrIs=2oye%)8UbEeeqzmPY7QL0M;=pm&@JnwWDI`gHF-)k`l!gmnHp(rRpYB1e780&Ht$9J2;M@iF5xw{iFM3ZEN+9sVU}W zYbZT717B7CY@3jO{>$?!#hmE_U;XM$5{nE{mOWa&B%|6@bn53lS7KW~)MM)1*^TDg zlR~p=xGAQ$x5;x0F~0xj_xZNU-d;xIrtWn0P1hYC?piK&8jB*bQ2i zE$$ER=NuG*_^I$N{_!kdu@UT&nU5iKi_JC=Gy}S6e58kWFb<5TY zA5SL&0+%jg+lVoa_ENu1$fJwkd6TFIS5#CK6sRi>vE)^^+e-(=k(%E6DmOadZ2kJO zWJY2em=vJ$s$74EU&Ht6+AV`8S2N2mr*i^t_u`jbX~FLHo7Jx}K_Af#{4~B4Okrw@ zW7X7XiLn$C8b_P)y1%Sf5+%0hfRZ9dQs1Z=O}W8Ei$J&36|2;HCcAFUB=cP39LjNV zgr({zNbaz3vnSyz4^HOR_$q8|6(L@rmfYNN_D{hcTDgRKHxtRsoShbHcH6p>SzgIY zbnef?FMDv$v(&TFdB>GN{LMY7Hw4hCCvI7rt5!lQRVI-$YR;uu2DO+%ZnEV3E_ttS zi_L)dA`Gdk+U-o|*PJ#{Y*Zg)DGqyueXgM2YFqZlnXVr@4W$&R8j4%7G|U<8y!NR0 zx|VS;m27E(2D1TLOk{8^mINPLWqLUD1FH}`L;nQuJ`M47>3x=5kF6g^Ne_Bd)m5CG zR@~<8=T(jM_somszI{`9x3f$}M-UE@WBA5SeYp06jK}T{YxB&X&6C|EB+!eAbJsGJ zia-JA>FI$Ap|`g;O55b5)}1$aXt#+XP=xQi!3+{rPYI*h?@TuYl$0x=?|fdLwW`m- z&{uN3x%V1pFfIL!?fre|S!#tU*}T%DM6@m7wQI?twjH3Z){cuo@t{L7Po9uc`7 ztqq!TCi=uH9ZuH=ZxZ@7p{{sn+-7qE3S)4=eWT}AZdxD=?{&YQ&G|tbQ^GoTnc}F3 zB0)$;mCmpRCi%7e=6K!Lao%f7)ti_SGHe&CJy>j#cz=YmQB$z)L==BSZ8v#m|W`{;anQ}>(Z7Z_X){$HdIzzkJte=D5VWDwbhC~i^nMK43`6QwK zG^qOs1)!MwIssSwYWjCTG&rqht!@l`dN!5}d?7^~gq zf{3ByY_azWT=!sZ4il!)sIy9P7BK(n_?5~BvhSM$uYv;s>h-qQ3x zOMm@(Rx<&Wp9^nIKPMOb5Q~;t+ThCYFw@{R3}QCWq4lfIeV4<^147&I$jGIsW*=Xl z&$8A7Bn@yW$;ru;m6Ujbx^h`N0xfatsO*m#Yd1L$1(P>p!1mZz1m*U8KSEb3E}4{NzrvuS6MajbYto ze)dyM#)>_O#I%KFSO$+bxgRBs=@5IRr}Eh==oV|7AW}D!G2_`EL-o{W&>?x%bL)*H zfUf6qs0f1$Kc2+L!sL_`s5e}SJc)@Uz4XV>O#({bU)~WDlHb&^9ZdyrvHF_%s;u#>t zX{p2JRKM$Slu4(fKcH>RwtoRX4q@#o^)7TR&acyif{2adK&?=rL|b@ZxQZg1#e zONCR7_8!cW3Oqj4M$FB>FRF6+KO6j3^JL|Kz9(dFH;J1;lJ}M6!KdPZ8}SUuTqCgo z>)&xcl!%VBof6aCKi(1G+kCv4UG+iRnqYX8olq?|h48D*nzbwDcwVt;iV6l3CzMeQ za<<}UmzG$GWRjDUqo@bak&gdtFxc^Z`VumgjksyTGGK+iIf;2EU!h0^>>*Ht(&3aY z&S@)tt7d`)!AgU2yf#r559+eu{`~}kpjO(if(##+w25Zd3NZhK-n@H$_Q#iV#vzjO zQG8egn8Pn!=LhRQj8v>rn^k89ORxH=Q?Gnxz(rm+H19>ctu*Q(WYKyy?OqsC-#4Rk zFtKJ5Sz$GhV?hFQqT>I{BWXB0MdDgvxvh`)PSW`hihOkBRm%F{)&kFxu{)uGmG6o0 zo6G7eaWj$@*0mlds8S+$gqN33Iy$$sG?VjGe(Br5Rs4YwwlAyD?r#;~R?ue+qA`5w z6A%<%M;iG`E#F?hEP< zFUqldX%3OkEK`+S0nhb{z*ABl~e*;9>t%lZ}+0aodiaN{ID9&(^wPkL9v* zVLcu^@M_i0bW7Vsyh+p zL8L}1l5H~=qV&{y}M{0+%*)V!LypE z=~m%WQSJk^96auq9suZAf%Ppc+y=riSO}oq$k?a2(uV>q9j4@R;)-L9kP7OO}9WlS-rHK|zpp=dong-gqKjOohV|l>p!+Nyk^r;i$>?Amh{Z$VU`tIv~vY~kuo2yOS;EVE_2@uV~i=gF_Tt5ac8X1?eP)BJi(ukJi!f7zAmra24G#Xk9yCmKq$JP#fSK75#KJ0l3s?J2TC{B%E@A6N$&VAvC@rJFD+P=Z?y zIz)h%Z_ErC%u$=?bU4XZcQs*X@%lbh1Q<;q1$bI1S53yURui5V#&vmQ$fzYZS)^u8 zmW9V@=Tqwz@~8gKuI0)(kv-22S)4Dq+$ALr_oil!#q2-r)lVeo&zxKwn3@XY6LjBx(!4s<{x%!c z4{&qcG0X5x5r2P;NLriNCjr7})ZAn=H}XQ$BOhR|{Sa=V=|8Yyd*lP9 zUjH@$)<40HsApw|$r(~f`q}BFYtox9$Jxa6LUgnlJhZ)jVM)rH-9uAWU!6WWA>W z6Zrz=Ha%#QegmR+)8YfN)lJrho))m3@von-El^zlvH-3L9%JF#tpzTX?i{mz-=d&JzaTG<-6wH**<2^`KO5+RKaYa&qG9kd~w7S?o9|j$==*ibyNI-a~ zEdJ4<0Gl9#^7WExAwu&df|~mFbMCTc{O=nYuL;ghkBzY7_)h}64sA9TcEW3@DVnCn zrtZ9B=dnr-kueS~I;5RKRRf_JI?CU%KmYjAc`{trok7hx@s^~I&pFflue&dbKlI9= zAe$vYvi^vuSQ$@_YGS8r$2hu|0bQ*5-fEKiZ0B4fRdKd#{Qc8{NSW z3LPO)VPRE1hCIr-0()D7F;2BgXMOo=U&)HqL%)o4$mx!}|09hXjw`mGmavq-L=+V! zp65>jR^&dcNpGE}T>vgElIbw-&@Y9GB@7SK-4QD6P*3TwV;M1HPXpbv!M9uW@JrYe8eUsZ!%OeFLilbR7 zjL;}X+7%G^o%?Ez-K+i0L7ZyC`R{Gj7@p7>`S$HwIG4c5=Hc~MF{>(I8EI22!KzIr zi16=ntQ866WMdRv&lZ-Y3x)n5IGn%`uwB_eJNC8ay4%d^HE!+=d7a0WQXZ2@;n4?# zLC2V%_qRNK2g=^nubSav@84`BRN*01LE6#7c_#i#B8ygtVYpGS2R#aH1?km6> zpSF?XEq>R~%iZQlV#Omw`+;IhwE(N2CMqhXHuwq_r;64?2^m~IQ z4V~wysB5$B(?9emhttAM zaN^=@ev)Yr8P|d(8XA>gx*%9qkJf-3SxFYRk%^ykrf<;dj?jFwM3CC#95sA0T&y;0 zo5ezv!NIofucPFBVPUsVcC*gYgMyqWFXu8GoUZlY!{Z^p%5Se+XAv#6g)(yM3QFd4 zu}1r_3yK!+CSmrvXua5AG(QB3RZuC0=i&HB2QC7WW+JkNlV zfo88<#T=GJ6hdRT>FFqyJHP`Tkd@ zV+bL-XR7f~HY9bj=f(liLOieK7fHG32i9WYWb73Lj#}*QtCXsFZ~Ix#lD) z@@PPH{jqv`zk{&svB8_dY@j#V9?nGW{m`R`(nCZI z4mT++*B`yw^Q!J6<~3xwT2ZNg?ArG^m&I2p{;8EW;Xx(TeyD>J^0pcWj}^0P%=#Gc z{wE)KF&O!-`fz@4qW|>Q>SDpum)F-;-YqGO)^QT{#ff>iQM=PtHRP{oS{NPIy|;ZQ zlORYzwR#uvv-dvBr=N1vGnXuOEj;w)br$MvENm(&7U9fHG4oA=@1=#9U?bi&0!9|( zG-?u%io2y0~Vn6i-WVs zZ)m|ZC__t(iMF{(lU{uAqp<-JGy?dHnMZ-bWepd+BoKTugospasOj3>*G z2{gXAYFh`KtuP#C$-TZ6CKlu6=*ZXDXk*khp=hfiLN5AAA-?7Y$yG>qz__4TGLgx} zylbJ+)+A(e;dY#^XL!_r8H0wb1M8ra`bee!1)Byp&DMClJUc7O7G*^;-4%fWp$Z2G!!YtbcD@J z@^A0tw%{X%ixQRlza4wmG+R8I>hE*%Q&R+J@V&cu6@4AGZT)RJOhRgy&i=8-RY#Um z(Y4}PT2q!PjXQXl(lWN37Pn>-2?)eW8(!#)4t*!E7DyzeIBxrKBk(j@NUc<3>+B$j z=lg&-KVF)WxJDFun+Voa>e-1-IWKc(%m9LYt00S&r{#E+srhS}R%%Z`hDZ0*VodYb zKKnH3lm2hZuCB!AZcW*)g$%UcUDt{p^=W+&eF6-Q`miLpvar_iY-@)vc+I z(=TrHz(L?jFIMnu&wsx}qN<`5Wh?)7i-?$EuT{ix4|8<}hc4d0H4!ZUwl(Vz3S_YB zX{z$Q|9SyzzC*M~6l{T$l3qRQ_M;kpe%B+lr%V{a0~f`d5}T8gUzI>riKfdk%U6Cb zD`tHYKA!ldYH{aE-c2svXPt$L3fk{&rV`+E99SZ}wu?XzORK95e}8!kDEDC(dS{fA z{p}%s(c8#tM7v9N;799>bsJJfYp}mTwUa^n_KwR-yY-97x&lj@{;dB=tC9v+-Ecx~ zQwE%!?BAm&-8!iaGr8~@{k-Wc!6e6rYARovva=zYghI5w=Zx#3ko?lyR(njJt&E@I zCcjB~O?>>f)m6&#b1XfdmBmFO*rGQ9X>c)48WJ zVNcL`TiSKydT#cL@Xb+3HizS`o~N=PNaokCdG~JF7yPx=2uX@&U&RxnVCH%4BHxN~ zMaLR-_;ywHt+zI+&zI=MuJ~y%TiDp-TQn6H4_m;;mO9>F&WqtBH)OJM(bNqe+Pov0 z71}Y!5QqEVD65rt%3DNoImhgoeA64I8<-4uVaRND*N1)SBwtX;T6`WD@)a^@U;R2? zr8UJvYg_3MfHsJV_{A3qJ745c^}AZ`ZVaU%nHC)M7x5#+wpa26Pj#NZ%mhzsC*3$2 zRuPv1b3DluZnL&2$@iLCqjv3H^?DmZ^5&RFS)`4(OIIbIQT^W7xPn070jE{k`#>|) zdKVQnuita&MC2)h-#SyxuE%?NzPr0ud^VAYG9xZ5K16loX&$S)9o!Q5u{70O{m{*G zgliDtvODr>NnW8H&RXudgLYX8a%p3u*W!Kjae<@5T+C(?XR$8aTL;^ELwfV$1OIFG z_FJH@A04@KbB{ig@iiNIL7aFW&lnpmUfaA_%3WQJvXF_Nfk61KA5rFy(fIMu!H&SG z*d6!xQ4Bn?2D?J)^vX1s<(Vq-re*`4N1_i{UBdeGTSjfTIXjyI8skeh8z`J)nqrze zv)VuYY}t&pDp9Jwx!65kqC@k76M5K_#~(2MQe?P}EEC_Vuh9mreIAj!GS$65_j$z_ zyYt*IP-6-W*)5@R$sn~yTY8qEz_6-G2@lvwOMEZ$9DKvb~%34wy?7%7xTnV#z8dfrv`!nh*?oG5Rw5pI$yZI4eJOZpi z#e<(b!}f%j9z0F_U=ugoeytXg_GlxwDMT{lv-#j#1FN_kT!j1-t4YhCh^w+J+26Tf z{4mW!%RspspzBbD-mi^GTBsV9W2d3^Iz?rzRtji#59S!^z2dq5bkx7*?zP9{*O~p+ zo*ZtXE>1F$VYUb((s?B;maHU}Y$autMYECIMJr)UIzie^tiptQgzES6qW6L@^_gj!E*pxG&? zIYa~>LC`{sYD_pk4qvCFIX29JBS!=T&Y-v8V0X914tuKM{s$699I;{vZ?~4xsQZyf z%N^YryDgzE@qJ8!jsv`fDad+|CBJUB6(%8nc}3=n@lAoL}jx#Y#s>fpw_do8zg zWJY2F!NT6h#87?P69yu&sHIWw9kZ3MkBWm$IR;~e@>-qjrAZ3zp7P$le|)spMZoC1 zj}g5!#ox}#)TvmRvaa?brP^Lv_Q&(e5xT@tzNqnqHMIc4cXzLSjf#jcyOzjiaH=f- z^?8d|V-eQK@Nhh<9`sAjUA7sTnra$~!9f_8?R|XhG!EU}Shs@FH9}a5J075GV7$;s<>4td!2RX-u+`Y-KmK{hZgcGeT~Av_;+_t`g?bJ330kQvxkLc4P^dc zdVW$P{a)jY2lhcIC?X2apJz3@j&ag}`b|r_0OA?+Ch;)dfHP6>Z{0%l;aCrFM?!sX zQ5B8T%*lz1lio3Fvw2;<-F!A)an#_TVmfK?{v(N~T2<$UT%*i%6eSCqk^8sSmhL=| zxHIHEiuG{;tDGFS%_=_Z1S2%^p|TIj5#BIYnNktd>D0?K;bfYzRRRfbvL@T-Us7+k zD<8`+t&ZMR%P1*T*JHAlU0-ysYM2|jvJEqWN;M=jypxB;LDwh6yBfy#EQ6+(U+=l@ zSj?@p6J5&#q4F7TgI-+Z3ybY5?>)2xvD3ZjOx0!_LPqO)B>E50e!Ryv%B+j^yR7D- z=VE0i^ZT}Zqj7tyc6tXt0t2b3@g(v74z*-M)^`j>11`ZEm%M(lXn{PuaH)Ph@Imc+ zgM*omf$GTY=Cr@=MZ_brkuKZwO1!XUaxlHH*g{QeKCd(j&|W!uDT)NX=tL^|34e4lms@W-dX^a8I-FV-$ie_)KofOb{qN22id;55b`Pb90 zPpiE;C#dv!5HODOMiLV(hr^rUL+5hLHkJJ&)t z71kNCvCZR9x7c52d}u?tbn?Uui2hKhf`kPkoEY6ar($bLxZa{cxHvDkC311b#|?i6 z)upqIW>Kf(=}c+X`PS54F}kyM!%OtTm0imHvT?kdo~7TF5WGz@WAOxKote|)Mb5LF zE9q3^IQ%xaz61N_EQU|}bsD(b28EqvQX(oRX}LvtCA+uB8S9*bKeTi|gC;9ExvPHA z?@aE^1pN$S%9k~-R^MNV>^VWAH+(PrpmQ6fxTU2fnBoXheF>`NXEt+e!F_$Qi{O(- zhrZ*}=pn(h;NbeC3>lLh&;;WzlD z2|02mb{DmGFZ3R5C(T3kL?G}9^#+sDiz2KW#}}Ta^5MZ%)Orm%lU|3%Q(N}u!3nKL z8s7?aTaZfj=5@{I^EI7qq}?JRLUMAS(Do6gW)8IXgEtyK4V(F z;(Tv+1P29{uUMHHtIqK{oMs3P`jfSa6O#G8-|cXC(dDTXZ{B1T(7w9PnZpm^m5Pv% zg~(UPeLE*C>`cq~70IX1<-Zq=>M43=uC89OyNJ$^+26E|(Sqr=V1lQy+7otlbYQg~ zzO7v({WzD1|3q+FH**w8KutFM#p*^8%f26)GZafrWO?JRA@t3=x*kANOxNennhkY2 z9xpo4A_CqYPK)YlH@I15zZDaI$b zze~huIeepSiFdaNYo8uuD9qLwT6!ISj?GwaN&Uu&H$|osqUKF@H7IE9d}oH6y4)pz zJ-AABov!buz&6y1NLUOQkXJ1WOG|J<-A_0O4Ib)lJ)PQ}Zsu|XJ^Jnv62aOJc$pJR z$azgZQ+@bb42N}fytk|S1xI2gjJMt1QPf(jx)b-aTRh{{$Mx-jv`0{c|LS3}PDuWp zj=Xg6L;mX0Fqik5TGknE?JMpKFCOb2qjnLIa*j+U{fa5~6!Qx{@nS7C97}>eFJB@Rxr1F(`n)I)5DrQk6r5hd_F`hTNu$X>3HN z!gzoJE>B-PQ9<7OJ!??MZha~pvitY?>%Vj9&4J%>^9>gZ%o)lpVvalsRCrL3ScYHi zOQ^!$_*jTLA>;lnI;p@n6n1*$Z01tOdl@^fI)$sm_m3Q&mDX3DomXV=7fv38*jW89 zuHHH-%5ZBR9y*5xVdzFmz@bB0y1PS>p;M3!>5?w#?gjxtkdl&aK}kuK7Et(ZJm zwZ8vctZ|-a?$~kdy{}6+scl<O&ua1T&AcU9?$w%k?!&|d(EmL7X5ps4_~ z17st(gN#TvmtSn2p;Ky=us$ZQ0Q2}Sk4E@(<)TfeW(QZLDSGg%wWbYKwuhS^QjLX3XM+NxNP;#rZq5#ENcv zb(?)y-zFVJL+12avoR@TP+@S<8K*RbW6No3YJ#%bs}HY_-XTH!&CMqvsFQHV+hEaU zrhZ&`Q`&1^^Gp>mC)U`?4qc^k)izlF>+KhG7LmMtQ>&9qVp=ns^2HJFoG>=>xZ&3c zoih>y1P5K2x|3Wzn-vk#W`WHs$>w*u26J$y@qtBxL?zX=_eIwZ^C%rwG8>=$;q(^3 zQw@AIrJWoQzfegS8H7#sxk39Fb4@L72{7D@q#=j-eL@qSV5vYPT{+F9*vJI>hHAe2NOl z6I_4)vh?yw03>7h+1>b%*bO&Jc7ZSYqVj!hXF3tor{AEC^}dbRr^#KORbXm&LRU&J zD=iKG$?fI)c6ZRvmeXYQw7?$`rFZ3P{$wajhhIQot=*lKiK*X`0|LQZJ@;aCa;ouj zUfG|(nTwpUXpXqWKLnjNjREo~^p@7%y3IQ8TrGd9<9|x{K6kt-WPSa+hMacKvV*3U zMiYsq2?OJ2herF6iri0)V}QZQDu;>Y#Ta|-UL3#g7-fbAFs!{63S6af0E9lY%R}QwFD_w_SwtR zF1KuWaEGjPBA5e6O<9NYrBE=SuutXjrkxj5Z>FLJxmAIz7w-m5twJH{oc)U_J6YNgix|$j=`4$|E zr&H!9c=N(G{Xg}sz^pK_LwyM4C1oe)2(UE(k!y}(NZD8;y(?R z8P?jCI*)EoOOldSVt;1!tvlVh#;gUUOl?v>%dKVY9qV)n{5epGSqiUNZ~NVWf_tD! zF+li`!R5*Ok+D^ZEKA>)sFY@C5Jy$!7jK!md@q;k*Ruh22AHia#mhKVerL3r`!>uq ziU*sldi9-XyC>ZZM%L99Dyl+e1gOE**#}L1*z90kvR)0X$^KBp2DmYzi@~6ytDJ~p z5?mEU_2%a0ky*3G|C>NwFB+oqNKh-~V8f0#Qgv7<^(`fnv>&=cf&^jXaev5L-~9RW zCtcV2!6q?1)WVz(Yl8_YEa)s^CHy!avjOcU21-IsjjZQjBIH}ydf`;H>F?)v1Fdg# zAe>&CB&GBV79~G*HUXULtCtd!c5wKl8Zo7V>WW_5@3A$&QAUq14)^}n^Gur$#bf%h z3Y6!0xD0Xrk|=+ZZ)-zx6n(6lg-%3R#g;r+tt70sL|fKhQ#`74BTlnZC~t#*%yY5R zN$#(&Pks3^wipQ9g#Q3~`lxF5xhxohj3A>lmD0)hsNui{IZX8)`tiM9a?Id>d36(jKlVVVdVZ<_>ZM^}A2k zZpKv|oq8?N9H9m4pfa7BtDmiN zG7Ao!jSmAYFe;h7HpQHVCx>7%cxRW6w$u68bLGg8ruZ3)e*Z9>pFc;~JzDXIAgW(c z5yf!Ma&rt7qE43~$jT)oq)>$TK=`4<R>=v|7^FKC$`2dgyQAv23pWV!F;Me!fdl^6=nV$^bD!E7$Fc#fP^aIm~>H)GJ9!5 z^cvB;Uu8Mw5@7Rwjdr)Zd^ZSEVYwWuG7t3#sg90z3f9eqa;Il^TeWv~O5XFaWL@km zNt#*;e;LpAG+!QQDrobcKXu>%oR@$ybLIW)-R^1?Yr^->%$P|m!l~RtVeIGWvy90=#WSNM-47HBF{xp2IT@+WG^8fW= zKNhDf=b#EP8lO{Ku|?I$q;Me9Ua>67g@*t7<)W^hT$9WN_>s!8If;VkgiuvyPzgxn zkdT-Z*E)1(Cnqg#h>qeuvp<<^3Z^rKom%SLO{{fBw7CMh>7U>52^gMHbEF(_ zoN38^>Np>jyy%woo8iDlvGut!gQQlWYzS%{oh#+o&p*e+fi&ZgzFrF_$eKEpM2`i} z>1TYp^MLPNdw8A<_HIQ3d@`zuZNIr&q(uV$Iy#<9b9;LrGJL^sa28Bm>PY-)py*`$sDgfC*W}UcxvIupB!6TIZXdOgCv7oT) z|GdEzLI>8EYMa1VUh@1XjVYNpQNfFceE;yU*!9X=%rbRt@@;R)7oKz}?a#mx0oE}l zZr1`LwWMfy?J~RlU8N`apc$l|AufwMSR!(WI7!Pbd)Cq!5oO{@F1S6J&u?gCq+>2* z22CNmc#4TmeJqr&GQSl!zuz%v)gVcyv6-#2?%9s{5M>=TScsaTK?+rhO_Uhu-}MWX#S#1CWLC+F$KF*&PKQ#naztjjd} zfcOIPMu7>;WV}?IO|kLu$r?r(FClEknge7p_kZ2!$8w}4BUP*BF6rv>fBsx1Tp`5ooW*{5ijQ4EmBKGao2q z5|2Reg5#G6P?2TXPAQi-bz$7;%5_AEJ3YC}C;;PbhM)JtD}@iTVi*9AcHL1xJ2GjG zucA|`a8f8&j9KXVRxln!fr$uG4?6N(B|{}Fs(k+ZcCA~u0o*?JY6gWEfL!r6;616x z1>{||Ei}}S-KEf80{Uk_815ByYpX&CVP#PjhgI@2X>r5eKKsv=?;Sp#qtv8+S_O6Z zAJ-dKj&LJTj*jpWhO8xFxf!?J5_JnWsQD@inGb~QXjmcZm=H;4cn9EU1$c2QNMsz8 zQeh5-;`Qf_F(Eb1#uQyfUmNkt1gg7ghcm8UAUj22c@oZQ-kzl25mRsY?u=2q`=ChT zfStga=Qq9W_V;(f-8-`~n;C)KS97CsuRNZQUil0bSbrw!#2&A-{@NWe`=Mdu!)6QK zxwe!4&Bx5Z+H)d;P7O|x+uNU{w?86R)eGwC4liYd4jrAnT3Xs;7f9VeMk-EIhZ1Cm z8IKYS882i&4GQH8<_m)KJcv24w|CF~jw3@Gkmo46c^l^~#tVn5U_KQX;P`F1K1h)>rej7)M3Guw?+_0w7BOOhdP~x1iVkXk!2e15XSWa^;5y0mOHr zkYDF@f#S)ALjKpySq023ACVtcmu~_>tLhB1mgk!f!?fI1d20o7&L7##Jp_X)c^T7_ ztK`L=OWo9IX;iDL-#o5ATBc8YZ?xan4Ezew9)1pqP_XFPu@-O)-Lya;gtNzCQ>Ha& zyxiZh87aB2#|_L$*Vu*x`9&wXcYmavh*iF zgo2L#BTN)Nt8XirWQLY)_qw&G67hULPst3L+-cE(6RcDTGGmO;0zfD-Q%1fd3Adie z3V43UKRZAFgoo}{KvcjQMg?iR3c?_O2;o8A0d8}W7`b#D=NwAqoR262@-ZP+MX6JA z4q{i2he)+jRnn*i=b~*#YYK0xbi+8{l@JJ^ys}hOz2D#?w|3Bd2PnxbG+?PAinB@Q z=W#Fc{zgdC-<1Vkvo7P6IBQ0P{e8JzS=7}f4m%=k+mdbw<~e*wbH+@Ct=J!qj2CY_ zYQxIHQcszBHCrjJ;n2*+1{TD$fAB%T-?k$SZzu#P;{{9h>@M3cdbrHN|M1)Hhxl;k zNI+#|?q5Otv3taKWw8kqFq!1iZUP#H?luGe477dt>zEw(=PK{+s`o z1VZQ*i#zQ{3vK>t{`d7(ar#qv)!Z`j8cY1R=F#E(Z*SZ4D6iwbTBr~3Z@_c*KHM%m zL2}QQh#J+eEYU|u@XZEr324G%i=NV&8XK=H8Z2m#C0O;{=D#h+0wx3Ep_jjK;MuvV z6Hs3$iCo{^Ey2&7}edn0`^HHA)KKfb&;WH(N+`e1z%buROxS0pG1+^BGj{Pp|iR9 zS-Uu{Q2#eT@#coiMk5YW~=lT`!jE5y|4Fwprar!v0<)(^|QJ2{R;DpE-aZ9~_PuYf3F? zAlTS=kDp8)doz&ZUjMzcqDD47{=Z&;jkR}d0zW^q5uxR{HAOvN&Xu zJnlAOeDI*2!vbkGa$G}Q>RO%|8AFRmLiM(MTIlS9&`Jcqf#fEjGd-VxSU%=nJS5q- zi&+sjR90OwaiBni&m}S@eA30xVrAoc6aDD}IolIEW`lHJWMuHx{U$esC_gpA~T( z7u%0X4|l{3D%N^9oI9>h7r&2;;51V5&HwL_eMv^Su^X)FR_*~0rLO!uOPw8iP7qTr znLobnGP_x!%<>oTx>nqd#AW$d2GeK{>*h*tCm!U{N$?S&&?PENe3Z^2uxN;ve?SQ~ zlBKA<<$sRPTD?JvdN(c(I_&R?!yF;ivge6M$;;)bBn~bXBV&Vffy?G#=XszCV3jIP zLfOwg)32H)uzs^&?wMin*D6#Ts9MpZG9>;83wtH~X?FIRbre+Rfr9eXGZ4-E$Luy_ zFKTSg9Eb*)K;>hopzXR21rAB3@|GJI5RbRGY*-$%?85t+FsoU0W_|Z^+vdxb1vAY% zGU@?zUmh_rY0N0uj=~|Ljc+)KnUyLmBT}PgAo2kOP5Op>6W! zhn*16VPiA*Y8BJyqE)IKNa2 z@s#=H&0B(v%bT*YGKW-=65#^n=PX2V7Phtu&$Ffpno9P|EB>aSZuSpe9LapRyZeLT z-Y+lH`QZX7J<-ZIaM@|muHb*3tg1iUm3iS@0WWN_7cd=dBZn%*0HuzpvaFS+X=K}I z?-A5(z`=OzZFO@&AHNCSsHeK|H&?|64_Q@}9u`j+zh*b(JOk~+#`;`8UO zzZb^67L>Zw7CkDG(A^bJ{lgsnWGa^rL{+6Cocb^;14snHM^_WoqcSFPCV`8?S3KFK zGvbZG@r^z%H7bK{&MOiIjU@lG)R|U&Tc6cP_~}VrNruKZ+6c}fS@`%|19nfIUW-BS zYh?;9Qd3(@JLR7oN96^n=75_L-d6@xA4TF&w1iBC+ONmC@3j0 z5_yOd+N`-U#%P5<;y!Lx@E?WX>4qjrMu?}PM=q<+J*L(0YM5GDB8?e%WFl17E=kq( z0?ox0mZO(O8*V20zx4}QtY^yCB#hd6g8|QwQRhf1i06y-$qyg?y8~E9wYM1)B}=#U zbRUliwd!aeGG=Ee+^^_|Q_;IMs=irmO=N@ybw^B`xG#-~`2>)Ln`am3zWJzZ$BB5T zVbqMw#r7oj-7^vp^hL+%4Qe!4(q__!U)Q~UW5UhKdkA72 zx2&tKuQv&Ru&CGK7tneMJYl^Hb82?H&{2(ZYU4~?&;%pUa#jt$uTJZlxYz_pBoV>o z#h%Si#r32AYZ1ul1$Mc90SnnVo{N$xSeI^I>()%0{gK|;ri5N*5Bxwty*$Uh;5k;) zI5&0z=2FyDiY2aw)xUI!`hpI7kSdsT{|OgQ4G)L;kmVYgn@`v*XjL%zDn4yE{ub)n zv~;-jEZR}3fgXJhtq`XsUmR}2_}{%Ns#~mou|^_CkE4*iWij)YDOqqAW!Ux!Bws|9 zLE6^!6Cm9!q<5lwm{gk~r4#6sinaZ1S?JZtGamAbtM`BiclcQnn#dvKul(H1t^ip~ zXn8qfs?t8QKzPJc$fvEX;vKAwaaMsWEz@@rvmJK%^i+x6<^O1og|!WF>no z5hFOV|2?T5B$WS&TTfK7qstZ5wH^uguj&_E3{&bbO%8!X8Jr!Yp0l&!Rv#4D*Pt5M z3k0!F>$rwhaDG|twI5I!^zxd}|8U&`QWOdYp5r$oMqL4fOqJH7RoVc>H8pK82w~A^ zdADe*6x{pkW`^pLfnLWNa-)U$(J3e(H^Io3QW{}(RN#mB-(}^t+BCo0(7xcD2wEP^ zs?hFkXwYn+Ac?V_#FWn|*-BKnO!&LF+4(XKJ=Ado3H!OhoX`x<++rh-q(ipu_BUgO z);KfKaptDsewq1Qy{~5tavG9Ud}@{>j=FK1OWnk31N zFYt5*$|f2Gg6w8Fei))Dq5875aLJc*X|c2g|GG}z+%GMgX+uhL*zrFL-Niup zvh%KHH11V{_U){8UR?$oGX*kc>WBc-9PHqL5-_Xczs3wadm6|loaH?kA<(5cL&+hs z9ajQppC8g*zdRYO3+kwC^wHG5sW3{sL!pitFeHgjP0}Z(1YyCCAGxRB%^%p~UgRVC z<#8%;c+GxR&RkIeW*oM-ag4k(@A`ngd3edM{~5WgM{!D*4Cm3Vkf_1@b-d%w{>$Yh zzaC(KXhl5Ab=ZHd-dMnwQBq+GcJq|g-ZBAWT#w#t>mdb&(pHxJKsZZJfM_MDuZ_2ah)r17Xl_@3l}u!}!$(bhGXo`t}>$Rq%xk_}3r zh$j_f;uQGeJ9m|eoLvdx_5Z@3BJ1FH)adr)b||91wblL2-fE#`FKLsmtVUmfT(5NH z=ypWEJ877cEfRa&C$uulXaJp=MjfPCzFpmvf@>|IwkdS@y3`<0*m$lrrR(|!b5^L? zSp2*#Z#jwUF1S>VT3lRnz9+g1E+&QyInjb%0*>^g0K zC7=?vZ~RqB2gG1rmw+xu&+TnEF(n&M%CV0=Qm!?1xg^OvBy;QAD+A-u++6ie6PlPq zxwC@x*H1$;W9TAR6DN33XIWYpnveljw$f9TNB zCb&F5uje@7;S=DTO04v-u`e=82C zK@Z~q!KT34)YS$NEQhJmg^1cDdHo!NCuKm|~%)!x|kO4VGN_^5t-F@cP@g zi`!eIgrTnY?>WDo4y)fWwbM!gifaOfi)XJJ=^&DP{D|i55IP>^SPA`^9@pp6YoxDz zlVsM8)11mImx~9OJMpd{d~(u_AiZ4ut>}L1UZ3NTW^;e+hBW zU_Md5^XMol63k?gAXybw%S)K|)dJfK6h(rNXDXYXW@rKtFjS|3QgaOGAP>6m7 zC}8hT2morE)nq_CA$C6r{`cl`!6;O-;cqRK(MPz9HnA!fD79)+7SI^gYSJ7w7078#pH$`|c!b}&)>%JtGErD(GRo9_Rp!7IhtocbeH?~9~>c8@3m*W|e z2h%B>_KrY2Dv)@Zq-B_a_R8;V^V^cLyjymNY*82O?;hT)?0&H+pldh@!<7frI9{VA zG)=|z#-W!g5xx#f4`M#&R<)>e{H5CK3X~ZYwj0Ss7EeJBRl>XWq^4dK77#Ey=0j+F z`m6-7y0V$Q==B(&oK#UUjPv00R2c>y6?_5C*~b%qYqY5q0-Y~(iZNAgz@bLmJp>V)pz4j zQbHhNU%3J{C0A2@6|61SA2F6{0-%L6a|}674mGsEs7d2cY$=PO;f(|k-W_X7N2Rjc zr+EH4%+pHNNmteJnfhBHO~++)2*@e_0IK|?Ag!9nD!tw3Hcd+wJhoLA+HO8Rg{P-` zHJ6WRQpieYG&utl2+W>Mj6P>e%{M4Uf^wh%TzcUb?O!hYOxl%YXt zhrNPEY^Y2`=^PeUFoExI5-ezl_D*Oe^K%FRtE%pMq&lg%No0I7X+rBaM#+iaOl|g?lsP{?Tnc25Oq1!>&ZN z3KA4|TC~Q)1qd4lb>b%Za8q@v=JWZ{2P;~xZ}j$rUZlSUF+W6^Z`zvr1L^bG1dEsAz@1NeJ`GyKg zIH^$)23%9ynvc5`LyOnXP$0ymrmil2Hc1YdWTJ)5zhV8OfhKJ~WG`K)-kch0FZ0%z zS&d%1ls+X~=s4jvR<@&Wz5YrynABqCt11eAxcDBhX$J?LKvLuSy2IPo*x1<1t8L8)^DD0+9x49azWHBT9h2ux z2Xr|0lN&bWyw%4*!v$yzoWaHA#O3!xvc9lW&uqohK2g(`98!BnVpkkenPRdxI2e9~ z{D>^3tpyDbE;^h=Y1q&yjB0(@zc2Yk4%Dlp0#VhhKh_bmBv?LILpmlUGk^^Jl1p(P zr%T-2-XN6BVUmj7c&-DKMW;;>wz-V8k^uXQ(`j;TE)j@-OQa@$0)+*OeZ9KSx{YjR_6JY`>GuL`w)v#D7|a{eRXr`K2rK?H2Gp~OW9Z9yl%i#S%0$BXq>~yLBO>dyT`f5OMRSIB3u#emHcrr~%{YjgE#;9V> z+9r$^09o(-t}5Sm^hngtQBtq!vTgOPyZoiC4VQeQG&neTaMiyZjK`B7FLqyYpeH6O z2Xu;+1zP`kVTabUZ@Mo(@x$D$(2`=pVAM09Ixw1ExBU201vkzx=gFN9OOuBES9am% z>TM9u_{7Z;tW=CzMWay5!^d>6@27ByI88l3lei2W(?&VJ}$uD=3-$?asj+4 z_{zXPL(T%x(-yQoIggP5=QlL`A#@c*7JNqubvaKkVCn1B)cnsYF*TPkWj+!vf8n4g zD_63Wuf&*>d$+Iu;o`{o$%`rmsPG*7$8GCcX)|OX^K~1@1g-jYk zck#4Z-mh4{8k*g{Ta`qcQrvVt%D`L<6na#)FB{MW;u2#U`6*QPYz`H`Ak2HetGv3sTSGdJnrgVw@9bE-a?N@< zmts6Xfd5s)xssawaPNH3$`vBywv`yYrz1iTd8IRiEs;FXKWIjBpFB01~wOtqV zztvV~rV_?EorhG$*VbY>W+>;>03D}syG{Ze+lQu_#H9M@q><3x1h9hsfYSgp9aj_~ z6lV;Um3Be5z}}JF^Nb2;0h~Q6OGRx`qK5s^5^Bbc(`03%G7a@AMFMNTevK3YLFB zt^&D_P>d{)prSWF#;$I^VLXu)9Ta#SV_5b&IhFw_lsO_yX%iq&01XKpPlVZB>n#;e z)hMB(qgU8gqeDGnWBVcBeytaso+6|_Z9N;|L`fXU@3A%M&!fi1@A`LX$mE}TE%W4S z#`#GA9*g{+RFa{SRoThHNqu-q)&O;OU<8Fr)wcjg`+NkL#;sgaI~1sPL9_@C=hYP) zT|@;PP5w0aqs*iGYh8#Y3Tmz=zhbDdD@Z3-Dan-aM0`w!aN0tr0sb8OM|YWBG70P( zsdmz#qQ1UtXbXIDYK|1)?EJ)I7c*xRbV+VX22Y9P|0>5Yd4wvJMQn8OX1q44YaQfc z9l0QB5kNc`U2Hr~v9Z0Gb$AIqJ4m*7ObL1j-M-MS)^*|`2UKz2fNxQ}m>W;S(!mD7 zEDNhP;Fv=TYHbCYg%OBc(n6d?ZPMPKk~J330KXxNEIozdbnOVL8%~k_?-+0L>;K1HAq$x*#Ahe?+xlHHlhzeVT8eV(sm{1w#7fLTfv_Mzb3u{IiFN zb{73IfISJABzA-SltzxRlNehZMw~8n$G9@M_J^%{Jp{0dM0T1mm%y8c${n6_sH*uu zyIYq!L0C95>#YhDKLOIyhfkZ8r(RcEyYKzS28|zGi}(;Hv{L4uXiHXv(F>eqOR+HK zuF&n=wh{X_69g3)r)4RjcYZP;ac05utWWZ(IF`VpUTy;aw7Mr2fXT!V#0&3J=qa5;*t1Tdig@gCOpc9* zK_OeVvL%FZ7oW$z=(T@%=bWk=jF*LEd;7{bPVeH1Ky)(Xt7P>O_|L%wNKpUBi5a%M zR#dse+uvYs78(|%5Is8?F8s0#tIO<`24#HZotFAF{hI(i!0UqzPHA;hPZKn&NeSOe z;J}EARtA(od;(&PhF0j>ux6}OCEGYpaV$>@r?2eS1GXu_ zp>b$-xc#^Au77cg!lq@`LalWtJ3!a$zx`MhT{_Gnl*;8IOu%{q#Mef=rbzg^-1f)z zjKi>WIznM62-z&%e~z@cmxsYqDf5~+q9s#dnP7zz?8CErTT9Q;>E0-hb3~VjfOQ{jbbSJKYw3{M$J){+E6q4S?h`;nmfDS z(oQaJ+G6pk+oW^km9nY26Df-Z0>Y0Tq5)I(ga<`ohAgJtV=!t0wwN&LMX$|4&(4QX z`2i{KX76vnKOn41df(u$3-rI+kBy5nu9aKD2L6Nn0TOY!UEy4KK7FJTY(xLwYkMXR zb80+MH-DNOzvM)cZhGh#_zh(UR(nk1z*0H4*=Wol9BccegrWo4j%CssIaSHXWu7m@ zwrA(V!+(Ae$)8#^OJvT4`tASag>(cwcj$rQyQ0}2;loml3NPK4whL&6MJ7?%J2M>x z4-bXuBOM#QKf;^8H;R zUy%2j4jQq_{-5!e*~hkV+z;gKvdGcS7bvIjtH`1go2#_i@ocQhr!5qiFlM>B z3TcCkag{I%h9qd))lmX4|Kc7H9X-U$Yqa#G6cToj{-}}}|QfXem`rGtW zn^od}ya3?);-@Vl-J=)D93x=l&34xPe`_3b0Nd)LqV)-G%_E?cC;aW)^3Opw~3gy5;vRdbFS$FU$OH~7q* zi6tZ`hy#>$r(wi#7-;Arix`jHt9TkgRzdN}`Dlh0_L62%KThN+)JOt(f+aE7=;x1> zCg3#-r`9qvSLVz}G5ju$eA&oivTd^{EZ9(_9AdCOTi7EyYTBJk_gWLdF0h z4GTJjA`4q#jC=E=!c2vSfgG&DLX3;Pc`R$)u6?%CVaENa^QHSTF=)i#Nnw79!rzgq zeIQ1VB`>FoVTw(8!Ml>gl13pm@wLMf$St(AwfTzCRE83dWthytD^W_0tH;5L5X-27xL}ZEzrt^yqN%F zg5Uim%;^YrkB(ZFxlyNxS4V~a#p~!E7J2<&=bmr8!_tA9nd8<_J7bp6%fE-2)m_fl z?4k3S#g3q|qxC;VLO7+0b9~A+w$|{@RWF;_;JWg=1!`TiSD&6r7rYq_!y}z`*d^WV zK?Zs~BT#1JQEgk6w0XFs zkM!+R;!~>zZ+-pZ+rEA27?MEk5@635*51|ELm*8}O%*zTlI&Q_Infi-ithX_zKGx{ zLBE0Reu`U8Xn54-PQJddx9TqWwyjACQub$&^Lk2-&3G%>94roovWn*xh^jAoljOL$ z-+^lJ=CSt|C&AUm`g)hkAEpqtR3+~8(Svg<7Zilmew5pN{6J6yoFKr0be`wPur&1$ zojJNut}M6j3~!-&>heDohMC^SwTIc(cbFNkufaW6C`r-@Me14adpho%y23Dp%gde4 zkv>`j6oi2oeO=w-5+ulg)ztUX^UF(Pd-{-!pw_ScI_sDrt;(2Bw?o$*-Fen zAeR67_hbPhsMJ&A$19;gL_|bDvP=|p*^P*jMNUPZ-Y8eB{`d(5#~lT}iJ`+`n`tTF zd)=}qbd})5zQG;67EG}C zRCp16>$dO?uo|FW0w829nwVBNDNo)1?Jsq{;Ot)UGkKi-D3{U%aXL>DcEi7DKy&ASNZk9Q( zBd}%aeEPJbe0u0!rdm2PNj2_ z`Lpz(lQS+=@*X0Q`1e`#S?@Ov9WO%#atmig)I-^M>od3VkIFdz&@q{lJ932nd%AJR z>OJH@L&6d-*gGaV=|k%9V!0NZliC$J*qk>V?hO%MDLm{ciWBb6V#a9}b9> zYVN=}oAoMQdnWS$A-U?KxM5&iE{N;+qy)(^Dby^ix0D_;1TOaPU8MUrg)r%Xy1j6U z{9k>`GtLVx-m18IaCsT)Q7V@t*G^DJ)R{^U32K;~DZ3M0oz+CTsCwzrur#@YH{X;3#vT-ZF%odY2 zM_#y+bRI+!~>$co-`;QoUl)A^GFNT4G2O!iMO>F$BI%8Z2%KaINIp>+aE4^S(A(V}_I z2ZuYfU}1(d|HB{<>?xG$hGsN1G^e7rQKDYK0Y0Jp9gg`yT5@0~ZJW~xtnMD+gWv7{ z@ARKax_h>s*;i!SzQQm-<2;ZB=p+zL!f&tK|tm~@?`Rp|~4X5}wY>+uL%W=D2pRA%-CRw|~FDQJ$@+ zX}J~3e48JJ3Tiwomp&k2BKPc=y>RxZ%8drk(saYcPXOgj6_7hPf@50qFJFUE8p+ix zRg42uP5Jbxm(h<$%OGB9Zl8sh)Ci}9yJ4^oUmM(VEfe7a^*bvT127n)fKrt1_4j^L$3Sgx@(3_ z(B=39I!v^C)F3W;#Lea0z(B~!y+jJcf0Y6auUqo?RwS&;5wG+9g6=y@pdcXA-L;%M zR`Wts$Kwo(e&Z;qjJ-w|-=9$l548g8-{#X>%50pSf94wg2>gAog|ZIUaV(xNBGP_| z$dU2SA`z%b-e={C)i4?wq##f#T1|LgGEJAQkZZT1b+ELZHtXUTP7PKc;~pD<(|`{{ zEWQZYJ;oWLR0g42MI(Tg(H${4o=yi>>g@uK4||IQ>=VEg#fVpRc%b~p?YXd~W9LVy z*+q>bQ_qkj6e*pM`^I!Q5ouW{Ww0>u5Ty=+hpB}ds2m-YK_t_k@f_P37!bnw_!{eZ z>U<4kdPns!r9RQ>yxtUYT}~3S#{MzUs`aUCS&NkIF#j#QgwGX6%7`NN{;Kk1l)}lw zZFKoNrY$CQ_xGYePG{4?)geV(?!k$n#KKxm)5J6~wMsqrH)B5)9S2#*m+tA6DZ9GS zF_&9kO3A0R8;eL3sT5c7yDv`+9Z{^1s_gB5cKgo(CB0(wYU)a;&x3eD06~I`)P(zT zCtJT~`sUK7mp$Z6oYR!}^d=W{XOfXk%j?+lRHAV(tqiDp3AwpG<;H8zV5HsojTet0 zoz~kWZSt@;9W_wv*H@B1NyLgDsa*miW&9w_N z)c5_qcz#;UOX`$RM~yFoq+Y@T5IX#L9O+%Z_P-$nMkwjOzmYOW$U5uHppWo{ioeN| zejl1OZ-5!1!4p?`B^-DRO<2%BKmnEqY`gpyoB1H_uub&ysYdLyl|k;OUt)$&Ds7>= z*^(te!Zj1NErXy-D1K-*AI_E_l=k6U_c_{S&84tjv64(U{%i1$-COW?W(vI#)|%GP zKZq78uHg&2I`(Q6V!GLgxgExr!Nyr1>|3Cb4I0N9oLlxj79|4;j4p?aw1VrLpg#w= zRj7SDf+!{2cN%^ByTPZ$#djYuieD8}f2_o3qftLQlbzXX*I^$Ps5~=C?OF@Pz@L~X zV`bHL`5=1RW`4sVMKH46s6hs_iw)UM{W8B_xn({|{jF8ee+uR<*wd6=zi}47>#}>1 z(s}MymPbIeu9W9C{$$7G#JPl*Jqcw9XZy4BFL8>E(kYbqO#^bNTS?p)&GKgR6SJ$t zR8}kj4VOMQ@oz5QxPGSn2m9lZa>y{pGvjFSnI12L&#DkdgeOtm_as>Q7;}=9;m9#R z{cC0Yj0s&5=;1w^@aYdnFCpA?%X8!UQ|{g#-csKGBwe(-*Q+ej+|XHPv|dYq{27O# zriJYr+Lt|UrUf)QbmJJU-Esu|@o?F{9;#uRTvhO%Ga|I{j5JBzIG~%Y#BALFB;6Ax z=XE`6Qwir_Zml}7yJ>O39|l!-vQPF+oW73)n(mkQ$Z)b}6cV5o7{$F4LQ{6Id!WBO z^!!q|QL}b&G_}x#SM>`{zk9lOEp~4e(>sMPM9RBMx&mu0uhF$05N)Lu{jv4 z$^(o_C|6UIism`MjRQIN$Mt$~<_LcYMi$}y>Lyx>s6De9`cfmOBu-yDsRt!e6kgRe z9d852or|t?NYBGVUM1y)n%wd(OiMX=PHGbTq}o=}tUZHNgN^9m@}5Y(crcRF7L|a& zJyw6|XOAYoSsBBXXaciK2>*u{Tzr&}$n(jdq)xbhI1{Xbuug#j<~2P@6&tUF3jA5I z1dkP-yjOl@st&uNXSL1n)C_S>o?tze?f_R3+fbRw>G=zF#owCWPuPX-3TM?TJ@S)o z{=&b|Yr<$>a!c$Od^uXwkXX$x;=w%aY(IbSy7p&kC&^hjIdSt-;wqfy{SV?l7SZ?M zV@VNE0$dFb61SWFf)8i*0TuP?!ylZpeoDY8&iTCtPMbY$dy~BwqELJTKzzqV?@AV?ag}U!1SANc%r;|) zKb7d60|r|FBL#ZIrIy&KNkwHtzY^C;&7VJ!>9PMI-ohL}K;zCG7W5#mxv+EiC4qec zD|J(z=eV%FSOvwmllYFoY$==#FKCD= zW?|$ub3ERFbaZCvmHiw|Iqw;oZUnW9>)TC~Aqj^Tig5SiKL^CaI?|Xy&o(oNe5w3`W)u4xwk>Fn+1((VmMsc@S65BrdXXZ%?rm);t(0+<)OU-e zGnbzv^My4%ilC?uHZti@LLL7_>P71YUP(*K-RU+zOU6a4lW5lr*YPcD8JWbZE}f3c zvGY3G)r*18*xWZ#FJ4A4dTIX}btHH~79k{YXr^agrWv;yABW$Wc2~I-suWk>j3%gI zO%AQZ!*M-);)02ZxW2;^^RxAA`DmKvSNldG*2pOr>u$j7aLk#+1uV43pHpxVXrgAB zO<`?RCP-1*W;HJF8}g@E-6bmSVZzihxkrOJk$N41h0_GdO3V|v{-h8*S_vh4;n?!| zpnXzI($S*L__yk&E%Ggm==|Gw5(HN9Cj81<;ht|kN~z^xUPw8$5J!_v7!w;HBqc$(3>MpcfK9XeFs8$8Jp0koA zDKY!{_*AzdW74~pxZNqCWU+L*E_epm6<=gK~Ly^q{{sMUKSG- z+!J2|+dXuDX3p*v*;YQBD;;Mkvl|hT)F)(8e^s^k#ldw2Ngtx0KcJtF2T;AxwR(NS z_0{U_Z|ur27AG}xcfRwzHy;0V4Dp<^_g;IhwdR@=1khj#r+=$k($%>ee-7r+ZIAv? zCl>aRoPIuW0TJY_t$2A`tcBL$Fm~gwF@TT#dN1HCVl&1h=xn_sWw`PA6KvRFY~H+L ztZgs1OCDzd|jaC?2&ix#{L^?JhZxX$-|(&{ko{aDKE|6#90I!D26XIA}S>k6Nx ztfC^-#Ugx%QJ<#?_U5v)X6T{%uz;4)E_@DH$qOlbPH!g!B#-}MPLzTJ=vPtu{N zEPv8El_Uc|!J^?s>oyTj)D|bk+p4({gakb#P}!kPnkFj~a|#BR*q&;C-Oa(56aPan z+k%Ts^bgW_m>@Ra-Q8}f4%a)!c}IFuQ1*{dgdYO$NEtEb*TbA7Eo>lW~oX0^Um9I>)VD<+x1k6R1|6XHE*%Qp#?P3Fk(7iDbDqD z6#)cPEp9yc`1lZ!5Lay8Q^_Dd@zi-w>|M<{rEuA-UO&AA!aY(ikGxa1MA3R*IK4QB z7usjg)xZh&gDr(nZ9Q^CeQtgprt`!lxM#zSsp4Q{!m0`iL8Vuf)kH`C31v6_FKrDF z;Sp`o?~#*j5$8G1%f6<;ivS=|sqE^6Xg+C;mIGvdek_!EofD!_zIE~vT`KAJEyZ`E zzdPdFe8^@FfxGQiN*dbdd~LEn&d;qRuQ5-aCicso_V23STTwY`g!%MvVNQ1nheS0Y ze|Xoj_E2A#b$WQr4=~&&sX}%tu|)kq6l^Eb$e2pMJi#iE`85j!@JOu`V13r(Ly)qwvTCCjXyYa7Ug9hr9xuH$rMt_J53ZF4gZYIkcQHk#zh2uT zS5DfauRRcrYk77NT>Ap6+yij)en|KD9Sacs38`N~&zeB=@m7|Xd+QnycH95rzmxvx9i5^%I%YinU0=Ef2xTe zWypavGzOP5o0XaH0=pXA_;;^7VAi|)xPYewo)tCNz?OY!t>dJB%!o7XePd&E)TezS zbv3nu0-GJQVBtuGSo_mh*H1^V>6ZVnknH3e|!NKn$ zmeyJXYOAWqkwpQzn3d7OhTZnn1EcyHA;CVx2ycYH19&>UHBOL*wswoNXMqA;lXgXW zyR|pe1IF)^pTF*9?&PEB;NW1@{MNSur9Ok=MlN3dI`ERFlO{a)@4PUVB@egN>Qm(! zRioAhcX?@bt<<<$7z<&MZlmNk01j#}*_eG0x>@hjihnby2xx`G|0u!Db()tq*iK*n z&2aVX!5c_RitG!Jz9{qG+MBCezuw!Dn)%lBXkHMz8W{u*z5DkdJfw&r85XIm_p~%1 zcsnWY`>5P;k@j|*w)VUxbfcVw=(qN|i9bI-Z@b#mUR8CDopmqn>6wg4iQEl&9)u(F$EfWId&q_af%JL6<|enxgCm4wrtufiDo4#ID=(0I87^=uGl|}Fs?=?DM=leOLmEh`YqZenj@TtFPLR}7U-$XGT$w_`*@RvbSs1t z=EVHD^8Tg$^;Ph3&b4ywT?4{xv{3KWbG>WDQ(OD^cogc~Q8g^CdY(2*;q;YFBXq+K zQ&de&owl&R^=#=Q^1bQa)O_XILgSstW8x2!1AhTe_#CgBvBvot%j$*DwY}Ec@tfvm zC%v@>(dzs0RxU|bYF^&%gKOY_SX~hk#5*`_akebzy<#cE2C=2|O_HE^SGGjqHZ}TI z152!Z{m^y|ZnS}vm6xA*pTiVR^Thm+m0trY6_oJ9J8YOWwr6npN(aD+0itM|Ze`B~ z!ODlbrx$>LH(voJva&=&gzk?wYumitF96Kyu`nZm$LlZ9iXhVTxC@P`7;k832sbVE zMYs-LDKDJ-Q^16T1g`yajJ?U)0RZHM+~OJYu~cCMpeyz{qag+{`b>Y|ZV1W%TfAiQ~^FH|Q@8@e~ z_VoF=`}4%w1VDpY&d7MV!G7yMa3XzLM2mM`L-Cz3IpurR?Yh3dHLZ&#l{%^E~bwLvO!i`_IG6ZvKcJ`ZNT}vw! zOQEA7mDF0#@^WM(z$&{rfgI zzHV4GBVR}Ivj$HZRL76(9K3pagISWMw=MvCsaplQ^*cx6`Ptd#_I43u%~7U?5K$76 zU!YJ)&vd!H%gb=+33@|4vk4vw1tViAF;bU)T0tqN5yGd~;`#B+R=0y1^1nGJ&_z@$ zGGbu1op|8=^_?kR(!NX7R)h5sO%QPYg~^30TfhQ9pg^YZ7tXFNb#%6lB=NGd^8*e` z6zhNp`_h&}^Zu0aJQvQm(jF>-2piAF-4h02Q(Il_FC#|dLPy+K0xY-6Tol&;a!2?? z)o)#?>2=1Dx29zr220RNOjhWi4EMs;$WCW@jZ|IbR&~gu@44BYse}w%=S5d_I~o7d zO>MZ$mfE6YGcgDx()1Y(KS7ew&k)A4&)K%6s>16k?M(|aDBAbfP7rGy->1tqtaKig4D$v7V&{Fyqo1KbPHbLR}Sb7X#S4vS( zwgMfdXoa@7<&`w``ki&XnR8j^3!kg26jpT%(26spY_4wqU||X8Cz_M2Gcx|Ujf&XKR%wM z@I7c}f`F~FN~c4)>BLJy+}KAL$CNncnE+mi!**kDkzkyzkp{bx`>BDGPGuZb#<*lO^fx z^vL&(QQlh+2X$<0%-P8a)VZvky1Kgt_<24*^Vj+p%OnOb8m!7AXl;B;$Z=u$p%J2=!pw&hM^}}6GU>Sw8#;`$kwiPg{ntvezkdZc5%a@nV;0v^5e>vGYYs-~to&pWvm(=l~sNeC`E zJKbbsxvPW4au*TB|8oHzfvCtG<=Cvv=h6%3^Y-HT&0+7<8tnd+hjjw~;Bb?hg@c0` zT_BV>hDoQswul3|?t9+{kR^VO3hV3v2@KG9fA7@MM!0)zRzqD{f>QIRq+API`zMDP zHUl`SVAVNM-9EHg@iyZ#l5cN)L7Yy)I}o=X`YPSi_NT8Un%r*y#^?Bz8uKE zEM~oNi4H#Y_v^jx=)r&}jMi4cBqSTAZyRLD6vZls&9>fX$s-kvvx&kho?+z3`B)td z4K6SJ@B{V&D=R^m9cxKCBZ(u%qJzg)sU+`_HMM^ZS5%?}*d5*epd z{uhgY9?R894kktKffEonhlc1I2TtxD*!Aj98A00uvoj)Woqvnw@UJ>zL zj^6A0xf*}OLNc!$&`C(v$oG52?gb8*-de5aos`h!uZA6bp}S_G*SFV^9Y*!nY2RmX zq0f%`+FKsk@!{d~{ebT=u#9QIfcEly`{Qh(&yD)qHRQF8Yw4*t>-ig18>QTrU%n&L z%tm*R>90JTZn^4hY3%B^lorMfpr1EC>}>kd;mFk{SN8b$759bA7e^-+kJn6U6X(y zTN@Q=tMk+NY~v~(eAnL9tt~Eki6g=(RL2PyxHr?VhgQwlaZu6G-~Eu2#Scd)?D>d_ za1hY>Vh`t1O3ImG-U!VIjb6@7`BoqUAT;(5rgyn5ExfVC#s05?x3@nlmx^!~mb12+ z%;fJfT5C^o6nxhjT5BE8+C1}muSla?`LN7wF=Czqakn!I$i>8TW>hYK zm}6LvSlGhRAo@d0JI=eEn17&=#G(BA?S+$**U>N@Fq^Av|w|A6ns{(q!;8vv> zisui`?~NVGhxCpGl_PZ**AMg?nx zI(wiMkYtsEev}wlsB&t;#gv5&?BtN1Umy)l%}LjTB5|uGd2yNxw}A0kn~9$|G8}ua z0Nuo_Ub2tmwAJxq)jGlxO5z%gzWSre?J zE|qMz;#QSX2&BQVmeHVj3Pc4o)+%1&J$gS7@zvqZ;e)#gi3_XKzvr+AwA_EbI>AWf z6g-#{D!X1$N@jRpw7nQn9(yLnntZO|-VQ5W88!)#T=sIe7gSxYGg0?lP2%KTw;nZO)R zHPx+#EG04arIBU(ryp#SXgVgAcEswYS-jPb@{NDTzN~`It-eg5?_jj3AJr+3e$T%( zjric=^4C~tXp1QJB>wC&11Nb$H>pPfiUxcUvvRJb$2=pA0(!_Rp9D{RdRudfgtzt8 za1r``Q$+2a--_(SrDC)!0pCU2ka|jhm9=OLzr$hY{gbB;Ad>J73^eWSqd$QFM)+l= z+O#yfPB)>&vtfdu6Gx+<*fIpKb*cFhM)Tq~C(ETZ@F%w3^7V__gt19C&)X?1|DC|P$ei&&Q6qd)6z6|TORX7-aE^IKZD7IgD*1q>T{&ww9@T$xYq1LCA zPgTm23}z?VSw=j=m=Ua3(sVc<;euqew!eGz3&G(GU+sF4y1Vg!0XZ~|zpRhZoVzWf z=V;KOW@ZY6VEhSUxPQqHwye|vM0P~7@~Z4-zn)J_dPCa)op<-!5L?q>x#;<^i(uHZ zsAEAVR?xH(^S;PbRSWEfPP|6nAf)xjC^U`tHkKUjYGYq=>5CH9bkQdi>dJ7kK?FoPM0VE3 zk|BC#dF^k!t|w#{7SBeE-_d{3-0Y6k-wFsh(BV0OI_}3yP1oA+PKeKLKuvj`zT0^| z9V0NHf2?=ArTDgOd{9?AVFuUx(Hkz>?@)9veXF#jt*`UCJa4yrlNBKz0-)8?6)7^p z{c9c`^1g>gJwD%;@`F_=1M53IG4qYNGQ<1M9=@LL?pZSJ3|+!SB70Gr-Jdc9yxf>Y zd!@$?t;_hIwKaZPj5qkjkB^T7)G(?KNgXp#=+`tk`TS4wT-RaeOK}atX+rB~7Mh+(8l)u0hN3XFHq5uy&HD6n_&e=kZFR{hX|p@V5g4E{AVXvYzQ*+4s(i}Z2x z^(@%hHUW;zzH;zsgTXP%HV=10p_ol8Urdj=i6Y97PMlL1Z~reDwz-Y8p!Z4lj#lvC zD(~rq^1u46hy38OJV#sK2^i4&Au+L8){k+caIiP2-NTZ0+LQfig;|K_C-wN~@QtLi z0!M4Or#xMBkhYE(R7@G$6)yq|<@ayz#pDYp^ehr`vh=V9zdIvIBF)jjijYCOgwz~0uAihwpp;eeptjLQy$v{|jK!YQV~Y6} zy=n}#D7(G;hWYPZR{(RpDZ6FrFA_~}qO>US@t2d3ktnLl{l7tmW5Me9d74l z(dMVL&jO`x(eIt_v(M1%F-846<-P6Fd%6;8N{K|*z%6K$=f*HW-BU&uy88r?!*Mv_ zi&m2)7HjFTL+)Y}^5*X4!VT`H|Jeqn!|C}77bGwHbE?~LXuH}u*L3} z@VGjx;{t?rJsqkF{D<=hFSih?B)eT#Zd4TYFQXS3#PXm-_&tUuS~rMn7oXzo3eK|v zeK5-D-Hphnue}&ePmFzw1eh14*Tpq}_|B<<2FnboteE*he;*pQr8N~2`tjjhs<3K| zXKW9V#a-gA2|n73w=U?Hw~tFC?I~6VegDHl>6(ylA#(2uPutZ*R1Rm#`+wRDC{dhT z*i7h2&~Nuj-$0n(5MtBZk1`PMI{mw{k1;Ex`AI!qE-^aJ@WLm+cm53tVe@+dVNxv_ z!3ht2@3Hm|(bdbD)Diz<)ZBK9hE(PxAWAG6+617fNP5Gna#*qO9KN$G5-p7w9b(|x zj_zB=dFC1x^h1rjWH>|(OE02Bqz;K?q_nBU52fBzykKC+EZs~D#}8#k`&ZZAGS2rx z67zT9ue_$6(S~aij+?VkOPS1GtOd=(CD5x{l?f5Zkx-fiR-QUAf#>VKd6u=|;Sri^?qFBw{nMJSejV370Cva( ziLb8E_0nvoEBDe#J0N7p5)EhGbfim7o}Sgz0)8WV&ZvEN;XFYG{(H--cQcCi8z=Lh zSM6!h)hxtmc%$ae?szG)~x>`lFA2cl0ho|RiwSWs_ijc2~|%m9&>RhHp_Nq&*N zkS4O7wfSr$Qn~C;m=&TzI=Jsn$F$$>6(+hq?~R;>LJ&ahe(KVD?#xp#R6u7Q;49S? zIe9QPKh=Z3A3uH%@)u zd*%m#JYeYj*dw#j=Y4)~SlG?#$^|;DALGO>LzzhgU?Z}V{uOiLU(J8aSm1?Zk!cxH z6lx1E@fvhC{FYzdXETg%D(v$x3f1=(CLxDe90qjda>eHVB>>H$eJ@#5zM!AFZtA{( zLlPT7B-Yf(XtUdJNCAQNP;Uk9&jS^cK6m%RO!3T+bGsFs{|pe`x5+ zwSS#&*qXG#2l>@HQhyNi+zEL*-U%1o%k0rfB~-TG8*c})?=hx@+^^sMwek_8_HBJB zeJ=tKurQS;xguqruXQiunIdJ#MN#C;+XL3>FAU5t=gkI;p?|gV7XK9%5e9Kp5r)$PaJ{LlE#R=ze@)l zAw|4Hb8L_2TeD?XpM4Yt@l#a;7g1N=Ri!+&GRn;V?y_8zo%=u|`5k6lG@cR;Z!Dn% zag35#D-|?)t766y8aDg1mx2;K#bCOSg=7m`m4%{9Rd~hDjoYEP`2D2CgNu51uggX| z^bqQ)P96dO?7CT;J-ZTgX}eS5))~|g=$e{(Ot|55XAT36@m$s0hFEE7>5VoPu)PD= zX+C?uWnqxIuSKn3wA(+()O*i7wGvwuv#XGm3={3-e?WEqFib=fQsSmdiE3t5jLN`3 zJk;Fa712#e9;!PCQ$_21%S<8KQKC8pXf*5U`{elpXS*W?GuNYgQVH_AA9eQk2iG9Uf1fgX zcS1B@S?cjqP*N(bypyXG=|!x4PAT;J^{WSLM0cl4JVZe4jrfDh+0pveR>KE$TJR>+ zs0sOe{URfqi0kcC$%_g$xqL4R_RM9c3t*>_zWD-vPZ%iZl%;fNsHi)uEgXgodJ^Vg zMRXz>8g6rc4w%cC2js==!=DakEo;KD3iFyOt1}H^h?@$&oEzDvzfXJ&ysjkaeI~_c!%iv@&E~no^D_6h#)I^*v7|6P1gGGtp=X*-~?*x zyHiryitjJYi=PDodEQB2h5kc`z;nc6VPN=#`E9A?aV>o%3nNJ;nSVA@m^!~8!xRMq zc8?II{zwolcxo0v{a@C8t3RB&xp5i{u z@r$uEF1ZR)YE6U&@A0g6fQd3IR~+E{gG)olNUvBt(_bJ7nwTaz+C5}qq#B{mE$$22 zO~j++l6Pbz0!>VQU1;`%;CMlUwzzs)SLu#u;)C3kU7lOfo01P<74bTsvL-L)p5aoRDI zHdMT-NAjqZ{k+;9QdY+=3_WKR5fOon5hssbg7WYN0czY@F%Y zSEM6bQ)u=)6J)nLsKGsVWcWo6EQiPAsEUeWTzt$t7n@Ea#UB}C?~nqZL(VOrLm{Ge zR%BZM2E&o8>8qOnLK1)4Vy}zH-jp^j!%;O6c1jKjulKfU9C#!WmXbbCX4$TRsVw*J zN0Y%$4>C+Lt1n*eG!BM_*oEwqt-pn-Bjf*mvfLldXj}(YW1j*ScgNnN#eho6N6Q?b zkC0=2Gf7--NV-RmHTlwIGSWb@w~0M5eVuX;LE_+YB@XBNB7Oat4+%ELY1fMBaeBrJ z)?fN(yT$uQ$JcHNcuIPMqgy>~2E0+G^2x_vug@|`&1sD`P`Q*(rP;s7ntOX*IA@+hxA3cO9?x42sLk zLsUEqPxxHb)#rhL?&?`t5nwV% z`uxw>R6FtS-}~xjG!#^W)V<({q;Ii8+}=3voo_nbUnB57i(m#x<{==2lxdSP2wC8G zT>l)u3BzW(J6`e;eCb~CbO!-uL-@os>{dOzSl?njhf@g&@per}NJ!|5%}3NKB;lyK zduqP2K$o7&#`b+g;=t}#yY`wqSM)|E#$4=euzrWBsmp1N?S;>4fiW=@AmC*|oq+pd zrl2Px=-~ljfAaZR6vWETey`IfHZ;_-G@}sVLugTYeKYXj<_-|Lp69n;flwx&l@c5* zk%x=xG!O;M(|;4l8W#vJVc_B0au`jC{v>IJakg{tfg7S{Ubm^f^D5xV9x3@$(#CCn zct4q5R{D!*PBS_BZ8xSg>x`)ll$oX1xd!1n@!|!oBb<*hGpo*Wa1+aEeHW8HuN5$A z7n!~%^$tAAPPgXPLJ0JvM4ngo^R1TQ*|~q|=68E0d=+~{lro0HJioYjotS)WyG%(e zD2Rq!ljT~GzudyU`503PQVfkw{q&gGxBp#$gia!2nI%l^?CJ{F$t|YrWPppCs7{F; z`tK<#^N}DVikQ*;URqk=e7LWUXr8UMQrF|>?ZnDhu*9Ff06H2D>wqyMO$1{E~<<)A8qo3%ba{B_AK+86gMd|?pXUk<{j;uuf)X}lc>PW)@{=txnyC#qaZc^* zW3BOa!f1IJSyF=Ia8Y$NJ-J;Dzz=t)sVNQN;;e-H05*M1Lg|51OAmYNREPvVq%a<5 zrNe{XdqRIMV?8-i2@p)eV?muHIw@@k8U#nSCy}YPj)3*e>xvti@#kQ%~ino)zqM}|6SAoSd!L{OnPA$3$XZkvJG(lUt7J7%Jz1C=mo;%_a`6 zi@ut|tgFm?gcnJ!)B5_P|i}XeS2$b zdVacZ`#+eXZ}5q#5(l#hQ%i9>egxk!#0Na)FDCVP#~%>jmLne|WtFEy*Xm*=fw3|O zHa9V6E-W(OGyZw7#m0UvVO?IER@jEM*y-jaV?jtrfZ1dxrg6_Mg&$iMkQd?U_$=6p_ z+WJApijIlXYilZDga@aL;VI2+gx6PJkU;B$)my;ZPxg_3SoDUZW#o+0_>%ZiPs}9; zdRv-25fKrH2%?3YAKxX&tkk)e&Mnvvm!x)40M z@w`w{u&iG1GK1XQ-IF7^-Y0h`%y$}%+-3m%WbD(9I~+8tId()&%(q;SYq_CcIMNlx zX-`?DDvF)nW~tIv*H+Sn-k0LdHX>Yd?oO2RtB5}YUo3b30NWRXOfWlyG%@~1T|*-E zw@9MGthl&9L`iXRI=ZODcxrQVOTe!a16ed*VXks5TU0F}fe4qNDZ8{58?$$%r?#>( zx~xP}P1W;q8zrQyBcKV;tIu8sBEJaQE(QtjcGe9M2B{z_=nC%n;o$+M6FP19JG$|0 znWw1j>^KGZ+b0OT-q;{K2;YK>izZ)w@B zRlEeifNSLeazO8ZWLjF}UOe*GjEoH69`Ehz3wieu7G!>ak50mqN`S9?Tcx2OZMTt& z30i13u8qf`za1?GR&g2(#)MB{bHD7_d@eMO{+FLGmQ;E8d3tK;@OXFQY)|W@%-}A{ z+Hntolf%BQrR)6Sl8KJVOIyunQzgEtswyrIPOExqz}R1;>+{j!Xn)#rn{#W?{Tj?z zZr}Gx6Ql5OteF{=Mw_)EP7ku+&Hcm7_;d@S?6Z>t`>Q!?KBPV1dsl_-tU!F<+DSm1 z*4ojFP=b$ycGcj6JcaaSen=lJ5aLNsZ2-UU%9L?Jk-zJICnAz6e$>?SI35ONuj2#8 z=yh3%DG4i3D0E@rx~*imd-)w-oy}H3lJm{OosHf|Q*2C%^Y#J?KdG%P7cNmjdWYTQ z;DoTK=;m%Y)N($AM8GM#pvEA!d<+P)FRGRzBG3NdRxSyvmDaaTe{WA#Ay&djm#6U+ zl*B~P`oTuQKlY{1R05J~jSvMbpi^`Obgj`nEy!87e%2iyA504EKD6dm=|)w$x$EkHD9 z9PORQOUoB(ZnFwN(RE=^y;2WuPcY;ooVPbIy86{-AJp{>6&2NutYWQ}%(9UWFt4{R$}r@> zX!{?4bkywFlGmJWaykapB|SxOcYS`@wSrbNc4U*&Udfn$`vtHK-QX=RrlvmI@wnn) z!vEsCVa5Cpwlg-~8fW|q;szn3pjK!%T%VR74TaeQI(6XGhspKu>CTLYy^ghw5lcet z*iDvxwb-Y@%m>W7NnClZ^$VfFtV&yCyPrSq?{$^nA0`$*dUHyOiW-Dgu?CO>#69K0 z#j{25$l?%vM|LL=Dp=oq9335J4!%CP--U{AjwCrhKYJkuSVe^nj*PS>cp5HL{kqyk zvRNQ#@P^I>H8p){X_03f7TUQ4ODao6XMy~DUv)X$W6Klr`}ADU0T`lH$7(mSTU9h| zy6@z%Kh+nGit6p{Js_VB>vv=MM*78o8*~rR)6mjF13A>x&_0O?(RY{6+_a4j?nVA#njLi%%*@_@q8e)Bs6fE+ z)<{k<)){%&bh;;A)BNwj8!3)~v-q{pGkRTLJ0?CofP9d>m3~r@*3;8-wyr;0Y;=5F zPQ^DOI#Nwt844WBe%Z7qsSbOp#+u9KnwqI`5-pf@iIb5(qh&K!_&B)RJ>66aDIMyS z;#whDS$dL^sh-te92{*0y&tWBLpOG$3B=Vv2$30Nb?`8iP>bkjzbJ0MYIdggUVmFR zmfF)3(0}-ymP(*EG+5@TxwpAJ2)Xu1-;S@F`RDc_<^v@qRU)%yo9UW=Ho}#TPC8s* z!2H`47r+FR`z8UUJ9N4Rd_A4&>Otf{>agk^^Vz}@7Z*q4k}^&e{^DLSZ(BumNJHO8 zgd(LZp#F7LhtKK#pZN++8rqS`r1+HJ2vG&&+1>@SGZr;j&i0#nrL6cYt`3qh}lE%9o^EuMP+- zVYN{59>VjwAo-ysv7`|Yhwy=|_wTP)w9~QTlqN2~ zA!((F1&AQ-1t?A7KOR0_kY8&WuwNVHB&D=0r~7aCTu#E|rA6^Sev+#SkBkz;@LDrF>ib==F2sE~`gHM3PyzWOgpDPv<_2Z&oHD4(XE?$=zR$`$fR zN)csnc5m1fLee86c&J!d&_ShYOpZ>@(a3MdiQi=8oE@t6;-3J_UH@5+@Z^2Kv)d&#x}dBKX(!h2DcsS4ZOh z{#E!(M#DfEfZw}?0Ppv*s+=`;4753e4)|Ej3H9v$}ezMk56Bm<|{) z$Lm652|Q-dba_;7Z-0MpKdj$>Hd4zxAYn{udLH-Vg)bE>EFgU=BO_z;l$aEAGyRF_ zY2}}fZqIJYJUp5zm%T&E-@;JLT%Ye!XI*a5p$#@7>v_b9z}O#OfAu|gC$IXIl1 zopU1KwCNZ>`#xTO1Z6{fC>6^9Dt5yyV?h$IU0^z!>^=77`Cr!-?PrFRq5>EJm z=qD10NY6mWPv?#dij*Y-{~cmr0A=TlufBY+Zr_8H#t#x|=sP>thYp73ZX)eN0KsKS z#diXWzkjQ1WY{5Dldx$bkTi7fy$@m$8#}+~pJSI~WQbDRHn~07IQ2Mma?=Qah2GmSOc zuHC3}&e<*-nH9a=+q)Ymp_&XPc{306dr*F&qLCo{;?+bL$JtGC9X|Y-&g;IYu6+a7 zL)}0>GT5SF8$z25Bdo1WoDqVDO@sonx@*jtGSi4NH@C=UepOC8J_UQ?pc)6{BREpp zu#6vZ2I+Lz$I*Q<5wa$%t?}2j+Fy)}jl;&mIs}Z1P8^fFM&*KngXhb2YJsbD#@>B@ zA_s};ZV4(&qMv1Gq_3d)@T|M~0(_zID0CpeGeoNO#=oZugb;IH-`uQU9qz=V71|}% zu1`T(r&m|M7$)kONmt=2bFkgJ0VPk9*VWk@gsog4 zPVPNC;R?|Wf!&WfbEtUcZF^~`$1-_dlr#RoRU|FDcHc(XSXgX20R>A%K+@~G<Z&vY{plj!a;G~hjjj$7#?m#YhE8>k zH5Cpr@FW_1d^}5we2oqDuN>|U(sr1j87_7vt?EY|$E%4PF`aZ`E9*}_ib$P6DL(5& z?y0f>Mz2x9kErugtyP}ahs@NjzybURL#}>YVZW_m0HogmBQAPi4*|p7(SiKv$an8y zvMVaui;CR-oDO_&adl0Kii#>J0dyqKBY*vZFfh`}r`A~?CFb<}uCJ>by}=MR{R52K zD$oHb%GKh!2Ica6x%1%Aa6>&KAUmqkD0uuNU&HL95F4Ai z%V&vLBIM-aB3N0nYw(RjMy>*2$lG7Q)m{{U0E1O{c)@Ye80lDs;bAV@74+mr^26;f z?03Me0X&v`x*3O(O1yP|lF~nLYr~uI-ac?Jl~h!el(2|Uz}|Ni(V_se7bxpI-O0#E z%e2R&dD06c(0!VlnfX`1ftOKkkQkGg$VO!AaeGZaUO!0M!BgvKvrV{vWNB_;r^E@k z3xm#q8V^XHm7r3W%csm=9z6-DQUKhuYqF`FZ0swUJX}{RXaGWZ1orIg%+e}{0R>>_ zKqdLk*7i)J!+v^0ET)K4RYT)ndEVF%6A}rrkf&N$By0-N;B4Q6*JH3>XYc`i*naY^ zgthgrU)BHq!PBNShGCZlh>6nB(9F!vu#TYq`nB<^=lAS9S2p$oP@*P-hDJjcCnXZd<<@veI&?(V^FZ3qjqvChnU+mk)oln$o5 z@5pTBqk+8bKImWmh}v>n=9rgCICU7hR7pw6kWm7yd{(viK!JKn*8aX~T+ zjE(mQh&~#mq6}w?1hxqX0Eri;VGBltb9#E&@zdQ&0;KfEpGW{^0_MXYVKp^GlEK`k znVZ|&x%RT2TqfN*yI<>Vz^~S6ax{GV)($@6v@)}?k;D}L`EwXhp%+o4cy#}%SWRv8C4hWYSC^||FFrx= z@bqA{#u>UU5{L{hYBj2m`X-;tX>|%e?#pt!BffKgC@;46o$hKz z>s=J7ko)<$;x39J4&Vcaj)Wh~r1^5kJBom9*!2t|u`U-xHLl6%flnKXD_AHskCgo( zv!N6Vq!=K~c4H{hS~D6Rvy01BFFFb`a=L)Gl8)?2cmBwTTA3)EdYSH5Tak%~RDA8J z83lDNPBwnKePmD*FJC4%?oC@s3s8;%(3=*KrITi$G)}3zV#KhklasWxG-h8f$j==s zNwa^l>-F^|Aby6OAz?`>XL|)A74rIJZ?lSPzQ!0xQ6J)a^FpYa2b)^B;e=%@mUfw; zu&{wu)~Z06Jv{XnJUq)X0FN6oS{Ef7Yw8r#2!Uh@+nclDUSuerQ9X%8>*4l<53ia+ z?6=h#R@cBlQlgKDXIVQquCzU-_$1yOEC5bNH8D3A`BYk0*YNX4)qBkrtJJ)agg-wD zyvBga^6K>T*2Y&jXG5^}-f0_x$o^`KRoB)<@z4crbnVhWD=(kTVhb1y&a19Azgv~I zV(y;p;}Li<0Pek?5}|yqKmzH4Jzh3?0KEe|0@pKO-pxKX0t714ZPpeR&c3$)c&Hii#b^+-wb&QNFD(hO z?2gvpXvTzR^e-P~-CcDyc4Fsc1raD}8yoAT8CgyXWlYdem=B@6Fh}e@KEQSg9dWVz zY@1n}#Rd_d6n^OI1u%I)z&(C_{ddu%)+WziEMn}0vQiNJoz(hy2Zu~mHCRxK>^bO( z*ogzBo)rdC)|M7C_SB{(?uH=(S^(O1E^B%aHK1=oT~8~@yxL9Y(NTk^?oi-G z3S=`J?sRq4ZaIKj0>j~trze;1XkXtua{&GjB(1>Y%uIK8?)J=81&iFWJWQaqy0VUr z_1^lAxru5=yM~&~ct7ZfHye!@5`9}~v>{ktVKEbQWSP#XRhHxKXb&WgN@Os>KskQAP-wrZ*0T^>vq zy1TopFc=SFZsdrCpduraBlp-wot3DT9uXaW2)bywa8^^p3t*KD$0|~>=qW`+PhkT+ zh$76kduggXgI?+y>VXCUY4|d&3^_5c!*OqM(eAE^T*W9*>i;GqquU;9zrA43kkIX* zqM>m=+;=sS_?wPlFiBlSMOFPEdRk0MKmFX!RlxrGZ(@Puc;qsp`qv3}%|E~$K+`u6 zD;=w7I&QOCV-2#th*{4@pp}!XuLrw2IGx|6ZEc|6hm6EgPD1CqnB{SWz|;OaUXXU1Q~q0oc=E>9 zRxK;nmLS8_#hzQ_eM>Kbfl%}n0Y40 zW*>Y+x}q{#zt+|Ob63e39$%JMv{^FctE)4mbFOi5a43=CnUg;=joM2YQiyb24WX=N zl7hX#7bxFkWo4DJARKacw?CWt>&j2SacM{`nuqw4GZPAG2FzLuzn!VEzO4;91)S*3 zVVAS2AAI3m0+LnW)}i%YN}e5_qU5*g0gAiZII8bt$11hQ^xZXnOIal(kp=T?SfNAR zj^<7*dFFu%?&6R1POudKXdOPP=Kwe*m#Q$s^R}9Jsnv2XzT*?%DFUc%uxQl~fZ!2= zn+glc%5YfcZO_-c3iAwOl^2X&{zIoLZK?R57fzv!3^G-9tfq@0s34Pjw=-z1vYZ+x z%?W>kj1H?1xx<SkNyOAqf09bJPP%3ltEY_fEmz8aSa1 zL2#X*r}WA2@O>t~B03nb)kNPf5bLv-W*~FA!$-I1fp=O+7d=wZ;G%L>#p&4im;pfy zvIGE)0KwW}s{mO7_ok`$Urnd~YvwV-5Da~_;x)gB+PwT=cfi%O8k=_VxQRQ|&{)4Y56LaHR4pi# zfJnC9H8w`Q#?|4ZgMj<5!+V+s1`?D&k7u>R*obxtQjN2CdY0PrQ_GZ{V2 zfI^p6kwTb?D~dm0VX<+1S?zF*E-C^<4_AQZd2`b}aGvPtr^-Hl4Zuf$5x(CIjZ-Wv zR>m(vLd@vWpEz(rgv*&WW9N;OGgT;_xePBXDcR0Etq3nnP@)biO_^V(?d(hR2Rzu~ zQAzpR){J-+WiFxWHxK!WYb$vHmU-PYX9 z!^x5{Wnf|OeC6;gH}zR}b8l;}{dO>Lz!!~WSn>^%Wf-xlQ58|8Ltl|I`T9L# zhNRfrgc&g^|h0;SQ67~9LIZ*U9!ntYXs0$&KeZH&FbT9F>W1UwkQd?0J^e7H2!Jim zRzrCjBAF5xag?4rLl`U=G%?Zd@R4qkVxlm+YS9R)(1(gD^}l`3b173oDJjXcTsm62 zu3j2OcU?L#Nl_EMuW`7$uFj?mYI}H)dS=QPP@%=Z&z(V+SYwPHbaz7=X?#&}+HXU5 z-oGSqX`zEqLvr%@-gxbK9dMe-j#X(gKh|!0E-9RG(-|S26%z8a=^9;!dM{N zaHbA*)2Jy1v}_V>v?-o+#m+oEjJP`4zW;0Re?KfpkwhC6**O@QiC6?-uSrI8HH3?5 zoXCS}9NW~SpOf78cTG~0d7GAIc2^_!HtGBbytl}*a0meBHw^!{`NDCW139E_IIN^s zXU9eC0QuU2rf5iX|sF>yJB4DM{jB4egvm1P-rWw6$}1zBNZo!R5iJ{OUahoS<~ zxbo0VEOh_!UL)dUuJ_qBLV>4w{&C`paQpzT6o`6+^OAWFXtbZegQT+g$ zM*ach^U-MYJpS+~I{3lAl8HF(6M3o03eH1-21qSSHhSFmwv1Nq zMzRw1;u>N`G_Cr-SU;9?b*HbyT33Ca!}lMl&C|&aix4PH5c$mhpWWq%hH=M*3dJBr z<4;>%JgrocC{);3p3ph92Jn-YT1i$~W4Mb+Y4BdIxn3`sv0`SP8#bq~)$V}?4@6i&z>)Ud|P zzN6-WB2~Jb{zi-OOF^d=-H#m^w9yD*jrLzYOAk||2m9Wgjg!n*YK%VzhYe;dSXgGp zWpblI0a76PyxXg}j0W*4#Wr1s5LyU8ii6m8MWPrDtx?X_Vbxu%i(P7QWE$%;V$*X)BCz4CbFb7wrIiX`Uc z&7I1>Zb82fWYF+ldGprl*fCU0r{8Fevq~WVR%zNNJ7X18G?>@mUYCL%5w2-h{5bHb zEGrR0hhY=={U^!ASTr$T=(Dgbih`md&LwOwJZtF$dYxtyu_MBxN(iNPP2|pd*q_$R z!#0i?TA2GphmS-W1$}!u!=U`Gm0|1q0{x557N%*!MD@==imBs^iHnFDLEo410Cl4>_uR1yE+d?xmp>s1-o^0)$EBg=Gs!yzjI!w z%)AI9>>B^YB<70<7ZR!UdCr^bWEMtLrtWB;Qi2%KktQO_7c-!`!YbhTqzoFtN(J8l zJA420$|-}mc@0o+aDO%klWtE>Qt9%BR9t*ejgcQGvPRa0JknRT@$Bv#Cn%H<7Spu( zM(kUzSROeIjk_NpR`+7H5V`A|r1zybm?Xjev2MICX|=u*e}3xdAG(Oo_w-?~O8h0?+!ARFUi^XdP}`%tA`SwMO=@YOs$c)$V* zZ{FurMWq87<@>ENIfbZzunMla#_nQZ2#j9oK98&P*+f{ zYjT|hB3IR@z##qw5j1bVjVX+#xQVORbK;4SZUo($^MW{)o3_jI+RZBCJ-)-2Wx8W3 ztw^Z*2?AJ(UiUw7l{8a9hpCNaahkVtsE+8evR)6sXx~xU6lw0@veqgihXb@x(aOFN z<58W&ODaSuMa*?l5ID{gY6sV7_c6L2TBgxesz4(d_quQ{?0o)kT>Sl$E)rycmlFyV z5X4M{K{3OdkA`Rz4V~a% z;}Po*>rIjaGdY>x@?2PMks}w-CxYM0CDjp`q-|W|&oP#xNy$<=ld0+puk#@|xqTwM z{Oy&8!5J3yI18k5N%e%x)94OO7BoU53HcL&C9p_GqXdG}SeWpDX>Y^Gtx$Y$Sbx@v z6WCz&hW938I8Puh#ZpERv~T{j`{B76LXTDB?S4-Qdq~wgGvAf3PSe|tiKY_oLX$#E z{E9ttlYVv6v8Qz(-P9HXtoeqVH&qgc`tt)ZWn3Om01(LK{+9m1UrW^%#WT)#*VD2a zr?~pFNQN-+`R6uy%Ph6*nd=;`5d7z^j?E2QIX}{?dxj2&N7S3lgE%z+ggd^RmtO5{0JBc&C zt*_Q9vEToFNgjc;LpklVNKK({6L=$3a9rgIs@o{cG9BRiY89iIiW;>0eb=nQ5=`evcROpzv3&eYpNbzxZ$!$1)8)GF__`7v9=-&nNbUNKsL(+> z4kprejaMPLD_PTe3|j55!4oF2T9lxMd}-n`8(WIZ6FH`tTy4(SRd*v1Ar(a~BFf0d}pvQRLZxQ>oxXk(zme5b}M z!=XEW$M+d)W?EF26Sx! z(MiSadhstN#}Hjz`>=9JJ7;Hm8IP08?UnfH`ny}Vd;AZRkt@9uK9i+!I$EcmA61B5Ztub~E_eYn`FAuY$n#;M6xF(9$q_l^jK%I=r16Q;&{gZ(#* zx{t$r+8gGQAo98Hr*lpZFw!WzVKEB=t*;9q!uBL2piDR1B7@|p(w_n%sq)&U8xO8; zPZTP4PJ?mf5u|2ZP4-Y2p$EOBq1k~%EZ^5zp|2rkDG0;%T&0wHbBGjx46b~$s%(sA zjN}F3`I%7%v%^}Tutu|a784;rs!JAlWjEPKR^6gvh-Jrxs0L|VH8gyg6@<{Tet<#a zWC!856EiCZgU$B4T2Is*D$H$bXPq&$hknimvoz%#{in?{g{@Z=3sG+(G{S$$J_UD} z4e5{eZK7uNVS*SYL_torrR9r@$*|-=d0n+fzK#f^s4s~g2LyoYCIg3-R)N+oF zMO(}o=%8!8QBBGNP%L1pI8@I5_vZUrkEBG$Q=B`S zlVG+>)<@Wjv%R@bv`B#2+p~Br1`X+mZ*7N`8dYrP!?Xh~&bx~OXUD9wR_3WUI|?$6 zmsmn;2X-Gt{3dPBAt#}|%B!`B|D@80lr}Nf+#f2OCLGa9_#!!Y+YS_}>mJrxe)}_< z|J2;V@0I53YR(6s*1bCaBePudF6&cK`L8)Mw8s4!3L%S2yK}wEqNw&OSbU(P%lDue zFV8Sft_0GhbVwXNacvyO3XUDo;rxsH{?z)j9btG_*cbukF5$tP_axo#-VwHXRs<9- zAc*O-aP;et^iN&M@NH|V;_vo8jM{VE(w?WkNVJ0f@Wo$6+kWN>x*=I0U;;Gh5 zq2tqngYFEG$$AT@jcrIRMN2&cy`RwYWGNLf_^M`so%*u@v!wH}i>Al?_XsQGJQ*~v zw@RiXXqUX*@e1_X)g4;8m$3^B&nE4+%E@DB7YMAeb)_Dytsg1irs1dAI0$m0VWL4{ zZYWgT22uMjV`kxs*NizdppuVf+a!n0ktQjs?uYF@A!EmBKb77a%S}N6T8!9#5ZASS z&o8C1h`HI)yX^HQ#o-UdZn_Sy{XeXgo%lDr^`YG7Avm;#x4bML$2&Jx!T&JCuGndwR%nv}C*cXt`)m0HOEo-@%@QwKnk&xXD-T9QLR3L8eLG z77wGc3MQdJqx=hbmZr?ce5JXep<}Woq56@WI=c-JM{oeMWAKz5jAvkzmIO&qVr(*w z7B&9{Y(Fl@ctHH`xi2WoodF6!y}R3>l>NLr`kl-D38{Jv5+GT&TeuT~048_>^BzD@ z2>a%FAzj&!q<2+r4CaBVUpjjTsqm*AbbXr^wxZRC7N0^%UdW^xEy?;*PVY`HPT|7I zpn-6x>}h&0R+IhLKQQx@t-t9M{>wO_-SG9@hfBIKsEyOjv8X?Sm@Kmm>#nXZ=Z=vG zN9Zu+d}U)B{F@U9t&RF=IXUO(;#z1L;K^iN(6r5Sb0K4BZ8xD~gTLAHmK!QyA!(oI z^ZPLgeWZLtXt53T<*ODKbLCVmRDjY8zk{#Vnjs3_ea*bGp^k~aESeWS1Ayp%;Y@?4 zXw`B!n7iN7NR55)eES5)C9@dWx;?%}9eO6Vzs$VTyTf6$G2vEI$b z^rF4DvTSTh9S9>=A5}wjAh>xFMZwLWr-9K-IUFGRE9mfn4sqHwp2EaCFD5Q7p&C_; zY|J7)8a1gNlYpRZYdHiG1k&#w#=+D^O-0Ywd0fu9pE^Ab^(vZhW8*As#Fwl(_*d&7 zJ08St2n;{bc(UmACa8ksjBD$%-jeS%>!`m8Bf!9jTk5KwJU~xG7FAV|*R#v{oO?2i zA)PKWs+uT_yI4OB_acDiHJYqSx^JbsbiZvNzy!@FW_`JmgZ(VNcFR|FaMw8>hX`MT z36SEFP_K2?4kA14X^V*+b#QpDw0;cm+Eb|9V(o>8lEF0tzG+orygk0??t51KF5T9P zhhkW{{9extCu%bTFmEHDu&{r1rDFSNL+@+J5G!`{i$acI#HL=Wy*Sm`njI^WNY& z9u_P=$R1;oTIB~2MEi5LJXYEScGwt=$~7%R2#&qTW~WYCCndqGeP(!-9mFOD)9$RZ zb>>BTmnKKwbXy3}_9NL>;{%ei7A%>jY9Fa3HgrL|f|-n!+C&L#Uotxpt0LzGH7nLB zf#UMUBVsv#SZ;!TeP`vPc4moUi%Eg?*rtTZWM*|Ew4FG(=TBjlO+rUcq8&M#!VE(- zMzn1in{Gqg>9+XD9jx`wrOqmQe(WM=O;`cs=5i@f%;t&C7$=Q^yOn+w@8onImV@NW zV|fH_`$t4ubcrwzSm1_-hW6_myu31mSUH*wWa}Fl?Uy@|Y#%=Zr9T!=PClGqz< z%sODaHnD^Vbo(?ckZ{fJNTNA{N?n@5vDA5Qu3wXF^gA-b=lyBfPLE#IqNqiIr8rL> z)x0=8^-G`{3|8)(B7TJZNxx3ZAw`G8ZE?EL0%gtiuoJ9ivxTkNq@&@45X*y{*UkjX zZL2dhUh$DL!wiL_har*e9dx1!A9zSBGSL|hQU`%D9`!XPHVCJd*AmV9)vHtaEH!hQ zE41UcaaSxz(SLS%o>yql$7M@bsDH*}k~K{m&9V74F*f#>H;rjVG@Vhpbo8E&g5Ef0 zhL)a_9v_JP6ws%@QN68IK7em-sty>B;{B5go>v?VVdr7MpiJF3;(4y3o0%GPbBGe? zGicrq77zB0g9H=+Ox$(Bxl3*tT+!cO;CWNcGVq{+4u*rTUj6>iuOJfJrbnEp5aRMF zbNw<%r+T2?Npst$+L}*HXFJD3=%e6rTux1Kb;n|_6l_wqHX4WwXMBhTjKB52GPy@B zguZhvioBk9lo3(c5GwGonbO(mG$V~b5b9qSoD&#k-&BeM+A&LvYafbnOBxr>Fhtm| z2?;#Y4M~((oG6+~;3}N$wqN1vfbMYiKCf)jj(%IB=o8k*fqK8$5<7^vO4u)BTa|1B z8dro;@YVc1Se!ZhMY0@5Jz=vu-N8+-sg+>+i~34)I^sb9q_!+1edhH`wKSm%EaSeK z<*T(JlqS*Q#_a(+`r_C@&)y-(kv1DDMR@o?|KpZN(K7X)SUXR}IPnx=4FdP*v0jnT zh=#jZ$bXa&;LehkZOWj)f>V($_1T8Nm0XQU)@6i7QUy~{4FQHJVaM5-T^EP!VWH=glYKRU*aj&S`kzRNYKXRV5{@#ey-xb%!Wns!iIz<*#L9(&6FIUcSH7 zn9T;ve^Zy~r8bw(Zwh&1X?(o9Q}6Jt0x0z~OS#t(tMlmv*etxHJi=>@fw6kkqg1sK z4hs6Pdv7`$gkWoKTm$m@g0j9VD{qT{_}B~qI?%Jc!S_*-%cqj=a;Ae;w&l`Octh~oc14L zRao8<&D)n!nXtK$f>%Kt)UIy*87e7;X&pT!V8!u6+Z4Cd@4+~4A4ZIrF=p3wmeZ_3 z_k6v_3B#UKN?_85N)~;Pm5j{7J1;#wI+36ZO`KCPo2esss4ouk3wJh5RER(J$7pd| z=|t<2P`czu+JPKj_+Xw05;?~dCXREP#C%A0w3uMF59CzZyQrawSuG~IRHjp=9Kp1f zchAz1Wm0*&4wsFp{TUAE@Rkp>)5cWe+N0$E9d>ZxG4s9oSoGa|KV#&RzQf7VaVnCf z=~LvwOLs*L!lx`q-?jG(SIce<{Xa#TCyUT;ooIyUSBpuK zL1W^wbKLkqnNM4U(T1Wbj^Z^PgG>uhA+u(WuJQ2rV<8Gp3Wr2hFr{!BSH4LUVDHb> z^1kzzKN+TOaE`dUtERqZ0d3heAP^L4p2X_bX8-cU}z%X#r!7(4fUwifEY zud*~}gvZ%<6B$Prp+bfd4nvN|^}>rOft(yyoi+k`8L@FuRqNi!fKrK<6RLYk@Tks?@~Ztxb)wWz)-di@k6}-R|@eg zOcr=0X(YM*QsY+(o%n69JS&|v6WoU~qEpc`T1D^~23<1#zMW6bNmB{Q*#IHumJRfN z>)UpNFsLv%e`g;fpNWfM?!hN6XbaWbcP_(ulll2G3OHsCf}WRWT0R{qlb z{bzL;s$uR|VT@>K*1o;fsg2{|B46teaQ2x_S(GPUvG>dye_`(o=ET@ge7O`Zgu-&}>p9R<>Lre9!KJ(o_Tc;_9 z7LPQ+b#kh^gGK6gy{nzE?sh-+D616`r(n>iMt_-UPhi51(Pyvpsd2&ySS%1XA zAz+)eY{Du-4m?{S0u?yRNS2Jv+cLj-?_$i=lX7RDUM;&8+s)T}?pP^j+iq-Z%t4UU zsN*`XdT6RITjw*M9B;MXP#|X2Hz&f)>hRmGR4Tjs_oYs?NrZrQ=@r$cmT61Q5eHcZ>M+94H6p!KN}epL4zA4-4@5KH0}TC zHibXw<^3eRK`4-oP%G#BF4ofmjF%u|)|F*=osX_NkqAzGiG>xAP(J!r%efu>4miWf zx8uZ5l}q(cnwzuXu*~CkAGU4MWm-u5y;i%pv9WO(u39J~C&yflygQ!S^!9kn!m#h( zW4uz9KVPl#a+S$pJ70aFJr5NWPqZ@q>Q~xbGjBt{V+R9JC)2&m6q`^;&v3$kNyF@U zYS|>U>bknR?my@I=_xsv?djl@3?>Bbw3k`l9izJ*K|V-GNGK!(@?!!DGV;-C+1+ol zulc3u2qizJr>C8#%kn2xtJFUspJ~viX1CeD{3+W_(1RP%$ucuNa@_b=HDvn|Fq8C$ zB%VLuzJGh+bA{^4IfCJU)ww!-Pq&~}oxUa)eP!ZO*WKBCg~3PQY^{d?ckAu{bLK5AF@UBgAD5uA|t^#xn-00Jd0g^ zDKd4k&B(ccA~nXevteEyf&bAR~<>zK#!cE5I=>eAtCCklhx zVPm$?wGHAN*>Sdg1~dm@_Iwqsp;2TPu2J3{0NOjpX7+kKT2{&F#8jB*0&; z*|%G)-TY;=*Rs*W?{Q|>W%zY0l|Jst+U*tcKX3obP;rv3aQ`kr3VF)6EOj@!zp_#q zbuE7uxn|}o(>$d93pt}TI(?bjyxta)X%=|lCa%9ZCs`45am2yhOjapfbW+=H+%wR> z8~$SThrr`I4;R>?Dul|bkng_>PEGO62k(x_@^LZQ*!zKh+W#gNKl;k(VAzM@alKh4zQd*S-4toqM<%)VUZI|&V*p~$mbVE8YUpd~W@ ze!nD!88`8t5>q;Y~`_80vb6As?udJsNTPW8usA1N%lmkO*q1aXqFEr zp9ei|L(B-iaM`VSD_ei590pS&_yN215Z%n|oW?4Hwnh1imt^Z7YakC&~$V@;=ergRuFhcL?7^{QX}8|^y}Q* z98IJT!qOLu?X|-zo?KaO`P#{mx0yM1RW@W#L+V7RjN zsUAe{st@tX?0z=Lay}ACHhTNwAgI@{ol$Y_R*P{~3^d)IEeCSf==WMoZ5}%?qS6q zKj_q3bLp{-U%?R4faRn@eB1i^M>*?p3^yqKMPC11c+$M&zs)bEu|_Am@r>y_%p!@U zl{~Iv#~sUcL|UycT^6nZZ0jo><}*i|$cD0Px{TZt9qDye)oW=2Z>^VqI>8me=?viI6>l={YUAOFSf${$^PIS zyVUm&4s7PPYbXRyyJ@T=Z+w9(-AFVTvE-k-omw1=h4Y^+x$bZth~G&kXEv$cZw8$% zQf2ctEi3z~`8Z)^Wo2z;R_gQRv$gQ={?knxo%tdhktK*lcX&PH6~o^tG5(v}moElI znJDtcLBz$QC%QNG>@{;Uoymy5db8MKwa5H0u~3Co)={xNc^7~5FxvK@Vt^{*?bez_^uJxc1e0_)xoLdq?; z*KIeNje~={2vUkHNNc}Kno;)tZ2g`=t5%bW@4vDSb6P&}1v2PR%r83g5;1{R&CSYG z@#~>pVA-j+%asz*vGVy$;P~Zwv2L#hcChlP;rU!E4)>-u+fH0@c%?*O-qHjTK;xLt z^#(Zd+Z{*0{y_vpW4LRIxYprbI*qrpZ(u)J2EvZFdo>Nby=u==BtiyZI}kvl9B`ke zJGJ(8?44d>em{TMe7hx}N7QNZwuSNpf;@<_VegJ#<{Rr;Zyt9~QP~wTNh7r;lZIkW z&4Ti)S=`V*)GJlRM3x89Qo{d8R{vKb#i1Z0qiugu^M3|Q=^e3ss@bcTmbwt?()^%M@c+Cjb$`T5| zlUSft=J3CVKW&fkt;_A=FO5>rM_+l6ZOdF$I@mz8@Q8!fExPQ|{}sd0*DlR3W4xX$ zTvVCY(gZ=|z9g`H2YZSXXg`JteBau?*%*-zVs^d6d~oH?SLTXZ7Rqg){KKA^i48I@YELjjByrK*;b5?^WC#ErMcQ|{FG z)s=}pZ$wPWb)?&d0scSyiEiOz{<#uzoZz7whOejliA=(Zt#NcjfF193Fq#!*|V?*S$kMpvWORHwvkZ@4AGl%wrrBB}0nVgG6q5*U0< zKzZ|~C@X*cmvc8<%f^j&^P*fg&vaakb#@gt%N`K~XaK<{JW06M8wz9PO`2{g-G9(frCWJPaGCIkOwdOai^{73@=qF6@ z`4BS4qx>&Q$$`e_ZW$yXZnCsANqR5$&$7?s%aiJm=E?B53^#iA<10sV_{{iWt1{G~z25@l<{78!R^sbJ8)|xR*h@TKFCA%`d;-gU?<@RjOCmEhNib zvZma0Stuq<_!&P?1WR9DZr1Eq?hW6Sn0}=c8ur1E@Th|Lpp`9 zjdM@<)?6cYheI9z-fJQOM{;P))B4NW!`ZaS{kRS)d*|cffchQF<>0rcfX`Skyr$w= zEwvMyt1UjtNe6yWYb;2t@C^bygp138fnLThA}H;@hTWmif;{8)=7ny`xb3?vC+SG3 zPYj!Aq7tmtc_RHHDZqmGEt>@;KN(l}`*1o(r{?Rj9+&Pb+E;~He&f(i?-;F8c zJKBZja&C8mRm;a|avw5Xb{*&8>t;LOOxML8;xpmX!~PMVZ3q2o(;|Ly{IiA9!6JO5 z9;~?5=XSLJ6kAxA5Wo-}`$h#;1teG%1U&ZexU5s_wEB03b-BX+_<+xixBqb|(sXZL zNh$C7NrUr6Od2y(5ZYk4WN3uY6@L%D?GPv8hYy*YHnVFTt`Nq5e@4ML#1aX3%$2L` zD-kiQBcwBe$Jr{~kE_yIdcNl~MZINY&-Gj#_!u=9*l2}%HDIQ^^d2;cLIFX(Jq>-Y zI(Pdld(Z9L<7@;?BTMAcyGAXi2l>N@jyPga0K&=bVR|}9#E@+}&Va)P+WyONLw+BD zfV&@k7ywWfPet0CR*(#%Jd)kbWgr|iUAM95)^8aG{_S*s1yQp+TUw{rp@oV5=x0x^ot|Gw_kk4vh}IeQEY!X1 zeqet7YleF}SAmhs??KzGZLj}aR3gHp+YAp#$Kr~)Y$dte-yd=#u>b}T-=P7Z(jI~U z-B^BP@pZk`#=u6iO%mK9>h_YC1`J}1#3K@2Zn)+Wgp*$S1gTolrR8JS1mAa?c zb)|_Eajwmx-}?-0^(znh_-6%2903=mz2=kjw{MpMakTsicHSjFhlf~nFSm<^Vr;Tt zgQQ}xh>L-|mn z(`5PM#aBL1f1_Ep*jA%huFLQz!#>*Vi){r3c+AWK}W)vyAux`Hotq&PTb2Pa-~hhA~dFnrSm@YAOH(cp5A zR{s`vYd8)cT*0(T`x*s9FFn*Ati7~gGwA|B%l3v{9*Wav>l=9gZvUYOLkCgC z^xfTF9xavlzP-L+A;179n|*HyMA`Yixo`4cWm%>|6VG-rYyD; z4Pj5UMBsaWm#+VT@hfFt*m5=YgXfbp+YBd>PKDg=SgPmQ(n8Oo9Z+v}Z21(f_6IgD zyIQ-oS}t{rS-HjfBFRKzGd){Xe(aFLiV@pRN%M{JvTvx(dd74(7O#l5_hOjf>Fs58 zbMyT7ABxMuwx^!uX4!3&Pl);KFHJYci{ouWhlqc$s#rN)PcOY64p{60iG)q(y7`)< z5lL=;rn)6%WpTSdmigYD?(|Ka9%q+0(qdAvMqlSxii_Q7<)YN&gxVS8lKQhpqJGDhdMLBHGWVXEin;^Xzh zZ8l5-vCz?M%j(o-AcI=z!~q+L!&^UY-RZo0^)aZ<09 z>E6RcSC@a<)%|$k;RJNJJC^3}k}f98!my*V2O5ja?< z*IzeJ#t?+GI-%#j8OAWa8%Q;G=mrMFT#x2#fO5m0l^;%faBwi|-QHD>Ux&%acBxc~ zXy+;|Vr26b;NkyyA~vT(#Ez%XHEkWU*v@ou&R^Dn$`k{-HnWv1 z&`AXE_cw*0;I7jHZ&2t-Jdd;ZX?7X}L0VsN5>s%bRCwWlEk9K8hmS#36FSTfC$>t` z-@wKEb9%}Wy9|wTu7&o7b1~_YDobMjQc6ATM=`TaRbjj?KT*vJ5r1klsx2bryJ z)42jT-+hN{-HOHnE=OtN1<=tkL-v4=`A>kKbs=< z;#={E@9h!S+i_i|`yuUJ5emx3)1}@?o{xKXC-cX@zx}X$SZQ#-nzT!IH0-)oXxilJ ztId9RsHTeP?eadI?EumE+#Uqno%L8b7n=5B3I>A>o3DJRTBejs9vC285;Ly;kSQE^ zk!rjF5cEj0OZc};QVS%9CHPX7V4fvO&mYqVu?%_@a)CErpjt94tBenw${ z9W?c>96VoKKq?|4lDGfz{7lFrDD;uAN|mm1WtJp>P~detujlFc=1v5t-&zgh&UV-; zxO==INlZ<(Xju{8n5#dCw^%^l}OT)pd8Y z-XOooch#GsY}cY|HJu5D1{ayvef)TBC)T^}7MzyuSEq7c9#QTs6r*kuxUwhDdj-Dq z2SLot%xwB~{o9}KtKDpt%DXjtDXn2xtj_P-T0J;82!`79-p}=%uylRpxDKq^%raVp z>d)=+RHRl@Pd#x$`1|*7m)p5UpGuRoq8@k)eZaq)5T_Bv3|f-;L$}=@^yZe9x-|=6 zT$9Icxzr?ikHn96#eNE8-Dh#kowsc{l`(up2tY&ME8~h_1IR?evz-Pb!;`uTPILBy z!zaTJ%uvh-`Y z=gIvAczrycK<_z$Q!cN!?ZqrfR-5f=xlN3wgFsH-mxk|WJ0lcS6WKh|&Le{n6@t?+ z=}53ZRw)6uHR-w0)p6%u%?h{8My1~LA{dT4cFTJH#DsnPa})%|K5c%tKdhc3M#sb$ zHMraiE9&vPo!t&5jLTI%>b0I~x0!$v#iJaMWu%)&?sQ9N*7HzWlc4giW0`XdfRO zG3p&XM-J!{+ul>mYCF1;7AXS-u`;fD()uF1o3s%jv9_tTm0-c=c} ziqy)v%;`CI^Unhk5uT?rUA8wXU&9fFJYU7T;teV_>x3*;5Iev)pj_W8RCbF!7(%}~ z$6;w$G}+L)+6=Jztvnv!@es*Gce%zH_Qoh9Hf@yNM*D_A`8u`UO4P~eFw+T^$92yi z21qVbGHN!j(0`5TFq(R@6$U1rY+w8D!n--FWfqBhn6T|$t^RVj^x07ROn>ySgV=iU z6@u-$qbvWOp01T}w$2+b0pDUj^Bf=^q6Wdk(^j_^Fu-sRj`7%TNyw)w8=d|HK&#-4bW1SaRK7AO%V8+vE=)r0jP)IX9(^j?!%%VO4y2AemMx3-mdCj6=@tio@lD z1^C?$9oaJr%5estQ7)hBV5d)=)c>-#*Z`#aJ@KpW5Y$C}iV&=Jy~V!GEmFE5_&7a3 zql(j~A^_THNFP6%>0kpn-1gl2QN_8T;o-;xj{&Nxmv(i1Grb0@4QA3TdaqYw`RP}J zC_oH0i%OOHYO6hD5cnKEdxJ+j2g4ynOUYbkJl~*zs`RHh=AfsOHu>w(tDU2RgJx6RELGBr zxZL&`3Cg$CSV;JsGRn%E;CqAS8Pc)+_-L4fYChHVs?qQp^|)7IZ?foAf@~IFJ8L%y z{HOD}NR6z2Cl;O~;V-?_@YEUg&D5&3sf{4t_%=ChTh{DNWQ{tnl}_sMH#=3$l<)hu zh!(4mtlgmi3VHn7T~aY3#5}_RmsdEPp=(r4|3 zjkeydGFUlp$K|xpZ1Upc|8#wOdCBi{au43Z+eScvSxvAyx~bYphJZ?Fz7rnWncIPv3Xqn&zh zri=pLK)nV80I%=a^J}0d_?{H(n$>G-%;Ij) zuFmbci>**A3wQw!0c$beCnt!mi`RYd|wd~4^>v^xV(YaE7$8?V#a61oQv}2I~A?*EV zUo4FTQ#I79@;PW50a{pC_~q#iOpU_H#IZ@?%^Qd5QPz3cUZH5}ON%MW5x zuh6GsWK`(=c|*XnkMgpRm^sQik;lk65{t&^-52mO0%d^uhnOvhBYgoU0GirwB{7wSPcPhM)l!n z{YL9liz?_p6eqXg|1i?ag5DW4mJjesP*_bQ0;+86pC1hjX&Rfno_u`_&oKM#XI7 zyG&zm&^Aj2uc5MP?Ci~o*_@6u-I*_F)|>Tj_Mpm=5G`Xw=KLru26ftjY;WvZ_eHy zLj?Qby~`O6AXDt@+v9ZZ|Ag#jy~xZ?{x?_byv<>~5?pVH1%vMgC1Jb_$lx`3j{GBW z+DA=Ey%#7bARN{(m}~SahAb>`9IoRWTA%uwl2}} z6Qn-GK`&q5ae*r*%=m3>@2^GW&tKOlW${IBi>Vdy1x~eS8~Z-L7fRp1@3iz)o9cLM zXc_4-CGdDIg5VJ*9Ed74xhi$%%OxTbz|b&&%WiE9>UKv)c4;_(0Ima%C%G3Q)Di!G z7J!JK%VzCYfM-Vz4m7ZFbT_=>P5_Rz8ChBM`T9xU@j#``j`Op-nRZ}O_vJ6uB{XIH zlgO*N%ax^K`dc$5pxf+db4xNfwRMuK@{?7j!mHS>f#zXmGWy=+lgZU1mr@r6`48|D4qW3J4wgQl5dKJ-Yx2EQ zE>m{)j{lJ$tk&au3jnbfDC3%L=Np6L<6W|Yu%F^{e;?ljiv`CWEpp(pQ&3R6z1nH9 z!ExYRYrBYZ#P)oj&+56D=G8$o#=DLC(a0a*oj{QV{N^ehS{vcdGVfcK?(Tde`% z^cCn5>qAsj;A?O0c6$YfCH8(Hc<^Z0>v#`IF6>8z=Itjfu;Z0sg8SN)liVSe6PLi( z{kn0zoy!li4H8c)Eq15tZGndg<7su;Egm<~-GT4~$xWqlXBd<791YMf3JwI@t*G+t zKP>V^`~%=WKZrLN4nY9aN_qG=IDNP28nIO+#+0)B;N+8`Lc)LQ>FV0$a#6iaT$ax0 zt&-E{`4VtBclb2|xy=@2a>~MxzZLN7&5QZ_7qWz<-KxcQzr_88H@vsFJUZXuGCCRyJP5% zXM6wO=lS&d0e&)bX3p7r?Q30Y?X|A`qtD}Pw^E`|y;AD#OseZGg{p6Jl+hH$~3%c$~45^?ZA*&8k!;?XqSHL|K5b zGdJl1feT{dSbCKQzDZR!Q}o)^SEq){%PV(RuRR`Yfv6@KbJB{Vd`g?@9WwOWYDzWP zk!S$~eV^&{k~PxJs}y~1PvcioJ2mXFLjard4wUbYyPA`4kqkU-USbvsVAkLsdv@kL}w*(YmFdME8yT<^X%5z}N|A7O!R1n)hFStP~9#l=2xb=qsZ8cC~j zd72wY5}sq=f91I0#dsgSyn^_doy{BT<|kogA4c|ed8T-S==eUGM!cHu!~ZqOM^B&X z{psB3pST`KetWt*zccUIo2&-N@(o62mpQT}aA#cBVX-wEamM4SAF;dr<5nx{AUk84xZSa6cE2t+9NJr;rO?0dh^=E z2c~z!Gz2Y99%%W^lV1#I+2Sp_dEXXW2I6_$Yn9gkir|ai%d*lL9*%+M$}o%Q=M;}5 z=X5xcz!sHI>)pTP-o2&L^WtxkuA*QQl@J&6t~y8>XVkKpt*Eh#Or5KBB7Rrho`d{b zT3-I%=v>er9j{2WkOT_OthSme8z7%1dVSX5iq5lldD)qrB|vgMm-!M~^uBu4!$(jM zQaJEDx6x56(DvGzHLsbhjucPoTQ_B#p$<@wyL9@))*0a<^~La9;Jb@^+#*iVj*rYmgrVz$!ce(;Fmf5}%=v{Wm$V`#RY z4Kr7+J^NHBVl1YvZr06Y!0x&~yPl+lqJ*pnpCmX-NZcJN=>zp~>d z<1wg=K4ARle&IOqPlYTih(qv>Pgf;4@+7w@f}t?6vP{eKi7SK7yoGxZ3kxccQ4vD1Tp*U z+9KuKZ2+IwdS52<{H}Q2xhI>zF}cufwGCAnO%q469Xwe_Y30LreaGu zO?T6lwlcO;wdB4Vf!N!JAJ0iSZEz_G;?4U<%@m4t=X|g?H+FWkR<954k|T*2ZnURT zS-iCY zKaoQ%sf9Lgq3;hPcBu5rk=U-^T6PiM6h=MZ61 zgMxnNp6@|m&f&dc8p`O=m+%&fW74r0+HpVMR(yry*;Q$EyxRH&Yok92UH|H2%W=K0 z+f{V$TBY$jB{E>uv!@&LiR?62Cwp}Uw^ysH(&W?pibLB|0ke^}yWOc(oi|apiW5<< z8|H|V=DlwBFjM3@kL!4Y%M1?HzhS0YU0TXVp8H+cDNaR^Vyxxq z<$iwRLf9qxK6k`==69uO`1ZUF#{b@mhqrM=dbZ23R$43k__DxFs>^=@VZNaxdO|Mw z-&-Wjhu!Ot{`*+)LsBCh0uTDXZ;5UuT1k*_d9Y4%-TII!AWD0A;$Cy3v{vd6R=HSS zn=xh)TTGXoT3&|JoOQt(qIOmjr8L-4yr)e77lN6X?9Dd9uH#T-IQ+E^!lTHhc#K&! z1wSu+3B#Ip=Wo^eZ2>&^;0)u-fT)llM$bS4eTDQkDpm&iuZBM=^Z4}D$Csi|{E^Mk zUV+%6sBzRGH>bwUj>woWJ_`9)C-DgxR6AFLY#dR!i_Z{?=gekEgIV`5`s=94~I+Y9_R z>GQcK&@mr^!dHa?Nxi$lElAYzNXYx`Gt{u)KcXbQh2wp!xr5#uHrxK7?Js*E`$-rpCLM=ux#qi1ZDQJFUamOiRE9)|MYe7QuMZw*}5hv{-yV*I3 z9($^VdkY^?Cf5|0pPgY2#TV(Rq+W*z!J`JSgsC!mW-DPCx;Y`k`J1;v4|~y~-__^C zVAMsFYrKBq+GoB*Whn1Zj3u}x8Nyd;MFSufJ}w~?v&tycq%I5N!`iq)v}asi0sOo` z0Srk@8y!zB4F7K4Wq-2=t3U1Dae36|>hjY4`jkLKlDlL7+Onx?MhJX!l!GjM%>Cqw zZYzGJ+Rqdj)TlbsEPNj7n!^k8Ln+A@i>^Mn)jgSLL_y$aJ}_hV#dtUbefvmCLi*G4 z5mqY7j^-~V=mid21OpD~8}592Tr=Y6H77rElI9HTweQc(zp*JYc z;H@-2u6ES}HXb8SvNJa`Z-er0_4QOfz2~ON(ZGr{Z+3$ltnDG41vhSsu5w~tW#BbW z6zOOkO;rWmc~C^fjIoPh_`VoLi$_g}&3Z-@hVj8S#a{_M6zONPxROgEC05{J^b0}w z8rMoKT^o--oBo65HxuT(Wy8u|Jj&Rw0`T#6i*)Mh=g`37x18Jd7JTHqJzoA%Qv~BM zWKWADcJrdXp_)SPcK55p{dSg6ep5{0Pp^EuQ z8=u{tPd46D*z)EdhB8O8kc6Aug*>GCnM_xULG&LQVQyyhb2bt&Ef^i?F5EVvTCeiw zBwY7~br{~-uT4`fT#@68`J#%wX=nnPa4)z>Q6!}}i_@J}k;xzykpT+YUZyg43Vj13 z;#30~R_m_?4nHBt#dirB=);H#ko+qBz_($6Oz@!pgww~n#(pIb&0p_FlRI!}u5Tbh zrO!G|_N?^uJAcAS-&1H*TBtPW>Qzcf5?6%a9~}&*S1?iWARiUm6Oyp3+INI8{h zQ3yr4{7p;M2_MPTFWfs0v-he^F$*d2cyP1$DK0-6OUJ^+b}+p`)~`<9*F%f4GVNv- zL;fU$#oPS!gkXT!Kf0?K1L+YgPK?Dv=Ha#M!@^~f$TY5R;$nm%6ebM56S`^M%d6dn zsY4YXzT*jgIv3{nim$|=p)tkpamI8fWy$8claYh@4+Pm(L8(v4P%dYy@{v&$kE3Th98Cvi-TUGQBE1T zn;dArc+or&hZrfniIpXO9`0xbC_;99Zj){ITG-f zomSRyG+bg%Vl*pTDHS|`e^gu#X}njI;HtyXkApTdo>GWKL(dx71z-+)SY+2*Mikw3@y56(=ywGm{-PUaQi;3%Cx@86>*1t z;0^ru@3#5#*`+ zBS{9&pg}xR5>3X6FkO7A$VXF(-}HC(lzs&O)1InxZPMCz4wN6S=_}UZmwDJ``12h? z?a`c4>ASg!Qw5FDr@rleNT1g90q)fOea#@^r_n3!x0dl!gB=BHz~V2rnu`vlr168S z2dpb0En$#(&=!I}CriGa-OcL{JsWi*{!y?Unr6hxDAae%*V%0Wt-I;2yRlO}btt6$ z{@Qu(@7CGgOs-to<@CuyKmcL6=^dr-KnhP>3q92;!HeE^r@N0tg4GiG*O{N*xkl2q zSW}{Gh)5{yr+mYB7%fCSDxhAi%CfB8Sps3b!g5i&QjrVTp+{+Ukf2yptE$#Z(VwtT4#19m7+$pQyy8Ip|9y!I=>@PpKBm5)flKE)A8iM`*R}Fkr zY!%ysO$EFz3`=_&tg%Lon)M%Je#YNjE{CWrblT3wq@<8Pe#UlMsg}7j;Uk0~p;{Ar z7{sBB#{ysjbPZn}USpjl$<;bv@<{N84wU3OjQK=-v=pFc^%#2+`KeM`HNe=ve^2Z@ z_Os5{X>2ZD2V&o)uqnSE&P@f0pXaUuQl37J*|ZGMe*i<9jZ>I5;HhnMV&f>H?a&8Q zmieASKQ(@=z1OjRmnbsSZEm`fCO_y4xuEx7{x9Cg3kc0hch7wZ#}^-Jqc)R~j4Dkn z*b?Ohe}GMzx%k&jB*etSKkbc9A8Uxu{4Uh_{!xiTPP-qb-XY)MAvdpE<7Vb{ z{^DW}QD}!3UK@+)ab;3o9z*XqTuW_k;r>T1(t`&NoVI4SA_YO|Olz4;6;sNoJ7wxd z5FWY1P5VPgSorf>*`(ds8q(&4pva5u)6<pS;@I}YJtdT?bf$*G7ZqH)>OZW!52F>Xykos}C=Z}AeOP$CS=?ei zGLBG9B904F?)juMfh1Xs$#-p?mI1{f{JrhxF!3MKyW29V^!l`76A}W>xxr#Y;tx$L zOQob>TqFdt7;eAT0Qh$DIg)iAEByPlu~@x~=dJqUrA}?)x4*v(M9))NT3U)5u0j}k zB_b$1jti@jI@nP4t7dF-bLkDnJont~)_V4Ht>%8;BAW1g*fws{)0-=_ssi~1l`g9n za-89)X^c`*wH2-ljm!dizsP0_r8jJJcozD*E{yN|p3pb>xV2t*cxhqeJ(qgq%l@B@ zzhEHRISe2~oTMRC=X$6TQPuWLVAgbMoyBd=*jb*nW$&j?zt(%;tArYv{77;1nv1)y zM4?W1B>jU8Z6`Lnv-I#SF=+jkPiN{a5Yvuh4e|S-f@N9L?M&_rE8;ih@+j}OOLE=~ z+xZWn6?%w~b%v;$rMwE3wR@MMUVf00mcDizoOhk~Dwf?D2O#Gts6VkUI5L7TV@phL z777>dEn$Gd#gD=2MHQ9=Pq%hnNX}E?D%fGsUjSl%1%>Cnpk@Ys%^k5bbl1&IIao-j zk*jI;#<#b-8$|QpUUaJ!PwbpBXqC0gNxuK+cQ}X}w3|*f1fmiKpk1pmeV%gHLpc?D z8bns~rgt+XI^poGL(la4f@9WL*4vQiZvxS3u*;B=(1Ax9E++M*i-|t;)%k4nbC1Yk z@@lv(&*%oHqs&Efpl%DaD4aKWv7dD-Xt3~8dS7#MCTCX%BvWi9BmGUjmNCjkpL~OWpY#0n!i4p{F`d~!1SI*sXKbp+MDL7-mz zw9(65aHJ}-6A4Jksh_MF*75Vc`SllGEQ5J)US+KA>2*p_Y0<#qP@xL87TSu}9usfbH7|ys( zPyKV5ZW!N8ljSSENQe<){UI--g1dBrFS%0_Ub)ijX~q&UkRLU0Nwpj~{V)uPdFb!3%V zGjpsZP%}ddMxEkn|F$uwxOK^2;oB|skAx*mVzIaJK2;`2r!HG+EAXZt?I_Zv1?2RwYQM%Hx~C%!BF zl={#lHEepGS8t~k)0Ik}62j-n#p3t380-8oU5%~XA`(W4V>I<6FAWwJsUg_>hmVozwSM@se`aLV6iNhccwfdHS+!YShpEWn%<+tG#~SOV_vDI)#&W=)4AWyTDb!$ zY$URZ(q!GZK}IvbtsA`?O-8vyF!B`oOplkp^x`JUh5CNG*4CKF`uJql!*cEn(ifZj zBKe#EdAG>zcP5lV|G~6Qz;(@O0~vBEiqK2Z8j3CGa-lHoTTe!ZmAOZws#6&LB|>CKWfBK;ShMNK|u|@d|0RY5H0KxY@qvQ+pyI_r-;(DP+qQ9hCTBk)e}WI z$W&t;6j~l0lEwy+6r%a=+R2d==<*kAD9=gVo*5YY@pyLMXFtnqsT%KYgpp^L|3wv5 zq0S}1HAxs)g`)Q`=L80<3R5XFiuJSV4y+&X34VK&3#Xf1u1;sgh!G@(J^SOGp5 zkg*1L%b(W1>Eo|0P}y$H`V;zdLxTYQKGi@`$ALyYXIi5VZs=zT5&Lh+z5L>&r~^K- zaSOUT^UT$iFP!O0|Ca;o@dM$t(e=P!CzCQot?alnV%HflH%2RwKVqnH;LD#&!}&LRJ;gUMR*T#T_| zUQe)J*Xs(5V5_rI%Q5cVr=OTv}4(`KErRB03stxayYSWQ5Sv+C_2WY8rU}!ExJ<~=!m<-uP`XGTPgmgjR z%t=Gjys$7+`21h~Cb+{;R+8&2{N4wuE);2Ro{EQ$^O!;p#Xl6Q<@3xqdr#@V4|M(` z@-QY zf6AKBdDK1m$<}Y}ROeVlfjfmn{LXl4$(NzGtc|L-Occ#HXxEoPG|m+>L$A^^j{VHir%njs7@?D?2j#XB zVGeizttz!Q`hv+`<2%>TH`loCX!+ zU}8e`CXjp^_NfCNXf(81`i63+jT{5%FvC(^Y zaney!o0Y=fTob7<@zNzC+GWk)t;$v>N2@%Z*K_p&wC8Yv*R%F1W&>j=R)fyAiV&~s z?l%raY28WyWn$1Krz3SG=QFK3Qjb!v@zUGKt1{*?CTT64wg4?uRD(l?(x zl%^`aM?JdS2zXc)HYljK`EMT}*mV@6cwk*B&20rP+IRfXd$=k9Sko?k@yWt=$|aFh z<9jNd>g-;AyctK-d9r#O1>XGAffvcFy3?ma+%D4*43G<~2enzFjcMDpYo7nAL4c$v9&ow(WrBkiBJWc#``e3`tx*RQs zBf~p*wb21Fqwr$cCl3?@`A$zc1@7!3s**%8sC4yNF8EpNjuSPs7Q>u+Y+WLeKkggF z@)MTLIYwesZ)gc^wN_5WMlzTr*-H1&Tup21ol0fHR&7e=iS5UB5yR5E<6jK}pD;9w z?2+LtG4ums^j=+(FjHAUvC7d#p3!G-_LaGX)9dH*WT!zy4_2|@+L*E(^nG6CMck$)>~H@hpPqd-kzf0wcY#7uvxFz349;jsc*KK3=kMzd&OI5+useVYTj+n#F{khr(%X2gb zkNe3g*O8Xr{927~SJ?l>=CmH%Na{}?=~`|U^uq7<@XKQPHRFmeXOqI@hXs@F4g(I? z$$24vJlFml=L_^uV)I5GT%p_TyFJna%d^K^DcQOzO+u7sRpsVi7Ba!2G+=DKyBzu8 zD1MeSw_QI%V{tS+0(rWji=(G)4>0!hi<$2sleB==$$ zGxv20RUvx!e=_`=cwOj~F|dZXSKpEB%2J?8H{D$wW%urTFui`wd^`R4Dd%5lMsQL~ z@zzw;j%)dN%}eg?O7|#?;2|u&W+c_56gBaONl1?G<$s_5`4OZ8Kj&FMVc#XqaNVnf ze^%q}#3jJzs|}8Qr|H59QPMZJp^MwON3XpfAB?lpzxEMuaY77#ul0LKWx_B)rvIl? zfA@4S=3>x9ai}D@bV4xnyEjt7lu;2$`$X}6+RNZr=f(dh5VU49v1&MeuVLLW7Q0IhA}{k6ECGcgE9W@3CK=ZBtdx8&>*E)--=3XXx8K8|g&DsSyQ*6iTK? zdB}Upg)SG(<}YhQknUuuk!|KngU~Jm&@QV5$6in`sz2H%^4#Cr83$-qRoh}2p%X+; zzg~FnIYRvm#i_@ogt?P-nv}>RDs@f6Ix1D=on0j~CmTxMyoy_C<+n10h%kK^kvdE@ z$WDKdyZwW7oL9r}+9yH$q_RiAODqkTTfm+8T|Fw|4#N3SCXFd{^7;uSxQ9@B}$eAKXPNvM5SvDUu zBKNhhlK$}bU)WC6p;BEUSymq5?zK!7U5}Nne?*OEZ`?~RrvewDm7!Kdqus=s8qesq zqF{Tv5jEY;##x~UrR_^f}kq=$Axh}jT(Y(uBqzXm&6)J0pD^?)?yRm zNJ}k$BR1LA8;@~3MNG>zxQmIGjI)n8yt_hLRrpb_Ma%0Wvmv1sVfe5GyJn%Pmc@NH zD2aFvV|n(fk3waryga@yp~3i%AeMk{^)UT?*np1|g(^^Zq;SBk!*L-k;83@&c0_mG ze@??#**qu>vIW~xF!IH^yMcFVM8SugGP`e;|LdH31oD#I_2L+=RodRYOm)ZaE?_1wt-HHUb8VcT60oTbpsMFf}`%BfJ+(S%b?{5TFm8rEr+Fm}%?am=-v1`6g zRS2ScC(g&3r+D|q^nQ$!XCiez`^--#e)MY(u7Z;r0!wQ)t{{?1>CR5tY z9QTMH<25dyq9UJn2NliUe$rD~vLyf_$)L8ai0An6J6462KDl+re9IB9uRJ#aiy>ADgDP8& zkkwUwOZP2^V)m=LX0`4bfdBtK!AOtGA0QYn`co@U#>BSDFD7S@V$gfJ8y9yfLrj-j zjevnTio6V^3|nKq!NYY&HF9BNkH>jOgRcKoz^9Hg#w01Hn^junq)M~y<9fN=6|RUC zt~is}V$479!C7B=DkR~5yimGWCEsTao3U+so3!2TZ@1Nxx<%5idw-d-+8^7cyc8JY zEjq44G--9!#DpMXVHBzS9;4OvMh)X+B3(2&PVT;Q{10m4qcG(HK^%Jw2S0YP+sYU$ zv2Gbac~j(LAD?><0X2;_)gK=VGK0ZEcvNQovWx`0+Ecer&24-acB>}onK6bG!{`~nE3?_a1oaN-L}hpsp7P005Uuq9X3UD1zr zA&lINgp7}IOI`)d@)kK325Vlr{LL&tqu7|KOO1{e2H?B={@*?X*d5vgXwKYEVVPK& zh`zrVajksLfpZ~zAlX4h)pGe{-0<{38C|4_?J)aj=%^l?0?-R<1M`AWSVj7;+6I4F zHk^d>#Gev9P3VC;Uu;awYB$d*gX-GVREbnLkb<^mrhg1>xc0;4tFFe>2he_5zA$(&_2zvl>eOeD!gz*7^Eu zPYYA_1%SzQY_ulfa*upGlnk}171@~{n0^wA$786u=%eG31AjM4@F47)oknlfq>7v5 zI=O`?l_5w^K;o{^a?uW}Ai;Ih3`x>ft+0z7F>OcqqQwTr6=XOW0(qb$h^hGDU zH7Zc0hcx0Ays!6$hK3T^Et&Kh>l4nA6~MG`JFZul4QC4bqh-Fqea4awt^p&rJ)9N9 z<7Rqsums9ZcSiHR7Z=-tawpsQdTy6pb+DX42@c%L*XRD$6+8;PN4>5Kiz$lop@taQ25X}7U-MberR;OTTva+%& zE~x@uwX#VZNJvOv!@U-C*toZV#wZS}NtQQneu37vuV24@S>Wg9o?2MYyF_WfI9&1f z2TGu5EDoz(KnbFi-NvmW5w>Gm}YqMV0XYAl3SXd6eJk`a2kkO@< zkNde1YKaMAR^G(pP8k586@D1U>218)Ger^jagFFt^_ul+H2e7`AuS<6355_ej0 zhqC@if(_j@gLl@t7N1QBzRm1wcgXgNI;q9uz5-=#t=CA^&nqn_Qh8nX50=^rRd+x^ zYY;B^bhh+U2vL7LkmhrDIicqRn&eE3jr)?h37gLseD3$E7Vb_b^gwt1bcuoJSDTYg zN}t`S@{PV9tYr*>$9=3|xM*oeRWQqM=a;dXqH|r0^OU8I83C z;*fIKEjF8vCJIa~SGhVD``|ii+Eik#6 zDqB6k)>gZ}qvKH||M-!&s|O$e06|hh!ZSib6#bPy;h++pX>%DA;v?B@4rR>MxeliC zUoUrrZY#Ugd38lmfsT}&@xqavQ&gSLAah3ye?l;TToXjdi!KsB*j-`cT=H{vuw-q! zDzvP%r0!^l9c)&|xCuh?$y{$={Pz!`c?_1B#bk*=5{LD-Z{J3{)AYPf$IvM~6$&-k z_4F3N4PArjd+_hM;`O|_LD%WvAfm8po^H6|m2BeAku5e7oKAZh@i3NW*zOH?;1$q- z6z|>#?8V5?@aEvS(^r{63T=s@eP8G$)2+)hjX*C&@n(DpUMNmG) z=XK>2XYvm|0mWET((}Gt1ARA1oVEijVSm#+ms-EHA}B~n>x?=hfYjmc?k<&R;O=B8 z4L3J8JA0+u@%ooEF6-%vl9Ce8YX%Hs5z%zdbhmSRcZ~pw2jqf+O~Jt!=S@!7#P5EB zieT)vFcNk;ux3Z|lzZ+nM1#hEDWdp_XLa}VOxL;EZVaH_eMmA$pjFO+0BHxH0c1FS zl?k%49&hEQ;bLH1fY0TQpx<-?9>iqOiv$QehDWb?cNM)03bo(4bG{3q#q*lDEc*13 zqBiFtRU`wV7=;gXLBZ0zh=dxW^}($J4AQJHi+;z%!^+Ca&VCBeL;o2X$kMyi%`Mph zF7c})oSKG4+KKs80vs<`ZrZO|=VC1`9;gbhRA-o)n&L^p6#`QdW8~@OHCGj@IRYHO zbd!(I?bT`QEqGJcs_OjXJ7i@gB{1vR6nP_CMY;|7C*R8pjHMt%66gDsPmg)+jOVc~_Ndf^3 zSkUX&IOT>NA@YK^qgEWO*hU;lV=eRhO-__3`hBpZz;@6L_a8!MlqrFdzWB#sJ)U?iSJU@zpEm$_d`zINIYD1-G`gGU+(n z-Ckdv?toDSZyFpJXat3#?tP&AA(o4Tf~hC7TZ}x3aPV)(iAA zkWon5`pv;xop%M>%+X0CRd)Avf&FY}M! z(@cO$02&Z~vwOjEX>DsmoSXdXvrs8AZ&sTB_UOZh4{MANDR$t)atX%7Qyc~ThhaxU zuH=s&$GF1W-QC?h1c8}FILr~AZo`W?%>Nn#&jR|U)pjVtDFwZIVraX&yCEedB@XN9 z2l_xqM$hNAQb}bqRZX!Lh#U=@0eKTTUsNoj$M@~PQSSjS3Ov2vb7L3`F>ospFHhn^AD9IY{(YCG>MmYvuS(fT{0lfn^$UMC!Y;vI08zCW;%cFq;7YMN$eDg@IPvy((Vd z7)VKX5Qqif=m}rTLC<)c%m7YP`rI6Xd8%QSQ>M1Jw+GJvRIWfhYytRnD36VUbGvYV zSLL+z7mywjc8mJ^yXzi9ZoF`SlT9~Az4H90A3uHiWNMnD#4ZIND*{*D-CXWXS9*ZE zh%H@%fS)`|yT5?}JoxG8`koAES4?qln=GDp01Ofn)stcH1r}kii{zUej;jB(jP#Np3j|X(b*SU(K z49?!Wuf?hXS~US467Ze5xm{!a`Ny zDvkL-LE#z=lJy?F?czUdzcrW-ukU>9=+oG!QE#O|GAUj$t!plo z)FWDc%!CSJG2PW$x}nwRBjAnsszc8KIDkk5Z~qFAISLz4ik?)RQzz>Kr;Iwmw}N^s zbF=BSrZt2fRBOM?aBJ2TNFukLKHI;Zw|M|cpWlNg_}4EY$4=uAm$!oC%wS({o-~0a zwU#~J@+jKpwExoxhcmakZFiNr8n-7a00<1s|L+oOaB`l|i0_ztoJbLr3=ePyJ)%<_ zJ<5&rR0JZyRSM9*3?7DkK7no)vMh>=ma*gmh{X+7<;Gt%qSU;a0jtz3`q2*?Os*9d zC8a}7M3G4jDOY&FmLQt+l0uI1)IFK3{b}Re|P-05tJS(Fm}!w{PEqKBpY{ zG^UVcux=3>)JA{8zJ`P(3V6AjSLTah`jAGFaeqVH0euLdas*bv4RFvssUY%T(5!gF z$OvkX#M8X5%mMI*)Ssf%b^*p`+LvGtRwJMcKUiTAWZY$4pfd$jwvUBjpx>$fp8IZG zZ$2YU*uQ4YzW6`Xl`YyVNOTEEpU*+vw%7*!&rbh~XKx z!z%C?S7&?I7b}q?)Z$>?FeiR{!DAV(WX={B<9ogV{X*ArU4LavR@Cw(dI|CuU)S3$D5^@WE z0`fILDN5H&A;VA9?|3FvmT4jocbym#Pr{_C{;b1Nv;Xrq2+YX#3VrhkW;4uP&;sM=d*rJyhbR2t>d1Pc4! zc>#4SYHI46+greUe_Quneh13iy`=0GkMZ#pn!Im;o37E@0HGZKj@b%xLf`MN<$;(! z4+~2Pa6-(D7t4TAA~ERHp5*1GlDst(1GCn2v5W-)pbiZS19F{iXHzg`Wo4w@nJQ*F zI;jRzkfs2TT9C>M!b~vxViFSIEO{O7#gnZOz-S+0U~G=TC-!EljvH&4n{NIZmRe1g zWPm^k%|8Pu#{m;CTWI9>1>s72d;0@4G=al*!XP}#0S}w`b)aq|0NiaGo}kri^P!sZ;=BwY~30B=pl&+i2WaR0lV%kJbbfXubt`19SVk^f>qp$`fpx$=6Ao;B{1 z;0^^0+k?UX|GD4)pSV%w6BdXUd2D8@K_t+o^Fk7fI9(Swe7m#6@Oj; z0^kOK%s_l*pBE_1f$zIMN8BTP?s?hSoxy?t?7d90aKH2MXgvt40atnT;ze~6ldaqN zoGWkyn|H5KATX9-+H3*lIPuH@N(1;`!LBWshysnvFbX%jryv~)Lat9M;hau9I)K7} z_ENR^S2hH|JKgiCqMW(g=A&1($B=744p04DIA(UfqysOajl1ySC>R`|K5G2&T==jZq9Nwxwv2cjk$AV>pr{0~bXFmymrW252H z@k}XvZVrI6R%lv_i3KFOfbbgF%^lFGaoQY0YL2Fn08jb3m!H3Wur3BwABTSGIoEbtf>nGaUd@M5QeU9t`XEWan64- z0=)61XY4;qeGh6@8O_)ikH(WM{%ts@-bpc4`(Z8SXUdfV6 zVT+Yr?w9UvMn6M%ExJ;#Q9(Y({hVbCpw;zZsJqujo8Zaycv0p$?5D3!{1<}#bm#MKJq<3w)oFcNu9>jb{ z2I1gdt;3oWpp$SFI0uL>0XTug7>W>RQvoBIm6hd|O3CB&ri}$8Cr-xSZ%-62l*8mB zRzTbd6n}OO)zAQYc%gT9hlDDNBH(n;i0Srb=ZkKgX`@TORi&m>>0l?CM~%*mD0!}| zq?=KtrYeKhO-JipYE4yNiWJLjsWZRH;=9FLs9=}y2F4^Xg^tjtuVoTSjJv;q z0RayKMv0ctzpbr}S-U#wd={)F5K`>?BhE)a7B8{i^n-)<#;ez_;S#myiQw2zo!Zsp zZb$HWz>@$V0ltKDH~GNJ$0a0uTI~YH93k`L-M>VtlzlN+>7AXOK>Jbd+fPdGizUF5!M@y^ zbnh{g21x+NfcV#$^b!TN*#k2MOIXm8{SU~2^I?3EL7A^|UEtRqvZy4RY&x&%-^rB; zPGoPG>ND>*m9yk<6B&(psK^|dch=p>>OE6`xBJ7RVDuL*3z5#3^tppK@yhYS(n#MO z789rV>^({_2Ct=V$fFxLC!P-b^BR_~in-@8x#4^wXel;!%hec!Znmmr35F){H2_ylN#>>E(c zL@&FWpU>~pl@_Y|9ZE#I5#2C#vBp3_9Ae#=il2cHp31Njy^dLO9t;{80}*X>iXt(G z7&6}PX}VJ5^;*mtxpLlc-8YP31G_cmP}_l+28Qig8NUxo)u0`R-*H)BL(~dB21V-B z?JyQyXbnvhRIAa1Z4URtz8#TOPvf>`s83 zgI3cJR&XPM;73AS9CYdyKdgC4&7??uIDxwWY!I-*!NseV0Z;t;b)l(I^!m%42cnCv z?(XL6B`@$Uh&U}{6!QnXmO)kt-iXNMgeqW$0CTdZ$U^}9!DrIp1ot>dLBZeB-PMIN z=2W5qny#m^nf&zz0TxK)y+F`$PGZ7J;C8eCf@1kRjl@bcN3a|~+Z8}xm%tqa&QEU3 ze`KJM-nyn$%Me4|FU5?)_&N9=lh!ZH7bqy-Ou%>Ff;%N~Qv!lQ`a(fgyS;J24$!zk73ALcHhLhL+B2&hNU=#U5ISKi#6b+@o8= z1ainz6 zxa35f;4p!r$;zwkgn8dI^`)O>dm&~f-$=r|tj178T0cJiCa3=SK@wl23m%2wABdm* zp3bwD?4@sGf#}3Wp3e*H<9El2NQWaCeuAf_2rq6}pe8!f5ut&k6%E03mR!J8d&-&< zfD8NoN)q%zNkW8hD29rG-Ew7tc#l#hdyRHPqTtBB3qR00qfN9mZVQd{s&z`v)bmCy z7kD6+XE{ewnT9g|(>b3gv>B%?a@NG9L3%ohHVQAc3u{n)C1N*^mmyd8;P5y{`uFWF zzC9b0!`;v#UIw%D-wV@wBARDE1YxaF>)Dh-B>n#=?2Oms&qL@ZY%2I|Ho*GXEtt`q! zTl}PyH|2L>wa`YR*5#8gihdlCC3-k(ePgCgcV)XWSexW>wy0;?Sh}{72 z1EAo$_wW4xEdeyy4rESC_8;IxR}(?f^nrfdUvpR|-&ae;OLcv^2cM9pOrIl(>~ZUf zxWvUMylpq`SCxhQ>td!#Qg`r)z(<4GI4pJJ2YRM3%*j$S0yft0aO!2F4Q$<*W!^>g z)a9%JG8uCzNn5Sm{BJO@?5j&cl8gBnSCz-qh524*$9NgShqf>i8p!J(ycv5N*&7Ep zi}53Yson8PYfN;o+xTvI6q(m9{OuRF(1IdP6sX2@`sfxAVQ@>f1;A8QRszhI$fT=L zWv<{*7y6P#NGX2z%Jc~PJ)qb zWW>&VZ25twh-iJwlXq60yf7!=UHNVgVZKts)F}8gdc6>(N0$hOPyl zQxE6J;hJ}3;tJ%TEq3I7xuIsGfCLV&+rx1mC1q$jmCK8$97dzfxjo{~A2bLBh4pZ1 z4KXAJ>UYt-WQx3${IB&-pZpZld8v4*X4V(hlCVLvsY=5;(1OG6ueV=8J0frp6O)2C zp7c2Gz_e>{k|skU41%S{kG{_zNf>c&e#CF|wWyRzWhyql6EIsDJ9C6L0v|Uh=03L= zo-y#l0KI@$U;qdW-a((_le$7XeHNjh{f*1>SV$F$<*UcW&ET2|MD37Q>ALP$fTl2j!Niot({kl57pMT9jkv%IUCO~l?RPS&;>8> zw*N+MXG|XNj3fRUN2F*(qp!ixpVwURgDub3@?@K zA}<3q-|pq}fW=LX&MRQRMdPn~_wRa`>2XQz&NYcK1u*rjz-Y~%#s9Mc*-XQOWTww_ z4sn7#MG;!(M;K<0>|CU)jpkE@8Qxi>=Wu>n-OOF4u8!8h$BQFl(h&-2xSDptTX^rE-}vAWOXHESFFJe)#7v)jWk`?zGxXqI5S~XV>Q~lIMfob8><0^AekZ^>zD}H>$Bg>r(O& zcr95xFo5^sb2c2icbr0J_GR_CD9(mP>^t6^6apNCm4Vh~#9D1P?{ zd9Gl?N7^DJdD1{_JpJkR#_wuauqBND`MJ!TMrNGKE;|on2XjFC$E$GS($E#pa^|

841Nh6=f73~RH^B|4R1gGrJ1N#Q=j~b3v2r@Rkc%Zr3RBFOGSTY zS9YQB+XN0q1TlJC8`gGlCp!f>BRdW51jN`JIK>9d4Z6ciAn_*TFz4jvrXhUjXDHJH z-iIDL`<^&~%0>^z~h~as!+S zJPH_D{7u1AhG9uqzcwgYKg?z!RB_muaU%`38Lm3^m2&gw`9t6zx)@v7H_`JPc<4`E zRqVUk>nEP*y*8InFn2`DACk__oZ7^f67VJHd&&$OWi?v;dB0Z|8K$s?v&NJ8@SUcocnsLxV zra@oo;y$&sr=uCusG^u!GxYN-;FpNsAj zzYD@#IL7R*=Ix2mq|_%Ztz_|TZ^gxSSwy}OhDpR08h$CHGE;sNIMI;e6kFwXsM#O# zsr4?GCqX52308?H^od45EhM3QL<-KaXV(|XmOG7u8h9gs+M1A-cJKFm?YFtP$+PH! zJ#wz8@2V~)CI%)rFgIVQ@Gbr>FF(26&LU+u4PCTv-7jqf$r6v%7!^p4X3dgnszXtC zTJDb;ffn-;`8GAZpw4lj#y-=J+Ea&ahOU$90Hp|dH~~2duntH54Es8-_CPp@+wqc+ z#c(CMR|!^fP5k+D~p7LWM99TC`$Hk62EYt_r;>XyB`Xf+__O$az zeOBAK`lt9KI|Pkf#=3vi@Y9`wf+YTsf`YI=tx#5YxJr+$D!c2R83b7zGFIv1 z4U;9pTOzh=3|A!ZN19rxdkh3>ra9_YLgocsXX_{OW!P5F%WLLiN}M|`86 zTI)^|dg}&5h|TG(cS%Xfyszw#<3R8U~OY_eY|X_rsgtlSJ&6M1Q0KvPSzmn zluKm1ogMML8sr!u7IZJq%QGAODFJy+MD#)x!Sgm(RD1$D__Tr7Ay6l=Gd_XM0w~TK zR?&lsBNzUcpe$?T`kUXwdUgnj4hU?(tdlIyy@Hof6O)rKD6tJVD|((EkNp64DJUwk zv9j`52|#GLDRf~1O&386I$*2{6Q|%XAB2|}+z>;0^>`^f%6&3F3LHZeP z!z@4<$d+r{zIxJ=b)Ga9IYr+J?`fP$&8twz^KB%2fRg>ji9^5b_DtQNXmVW~0aoWJ zw%jdCTT8QR1}OiPyGC9CN$mE2UkvxV0N>$@0zrJ%wq^HM8ZlbPkh#}Rb_ig244cUS zjn*%|jM*@7Y=;BcfA#z!U{JIH3$5S<02%%YY|Bp8!Ixcdgv@vrMj zVv8fN7hd*%6wgvJzpJ&I8#knNS&91uE`@fzyd+@QIGlZPXh>64f+GYt!+Nik0f+PIqfYv>c=ST6mVGpBq9^C( zzPn>OWe<$f^ZG^zxY99L{a$HR2pOH@hS~IHd7QE)GTQtK==N zCP~D$XKzw$vI+0s{JMv81P31y^2?XkHJ)xKFhup1F>6MQ@-4>|~g4I~_oorB6L?Hd2bf&TiN*od=c{AD>5HL+m9~ z_%&10-`~Fnj8tIfOQC@);R+}!^a$xqpd@~7P6qJA+;KC+Kj% zmAFfSk_aWWPRSjJ)0?1KeTZc67ge#zLcHzo@pPQst%fUsT{!t0w!q<`At(Z}@%3Ak zw7dl?t=mGYH0L25xxm`lM0lyCXu~Hi*2v@9`0NXcMnAQR%J+@6sUaWzoz>t z`A(3Em>v1tvteOtjQ&%e&Q=BW&rs>aStHv{_26WNV2Hf^q6ZKK*b0}r4$Zh|A@g%{ zV9yoZ-I;zCasUT6K)k@GMJ(#yPpTF>C_JeVOmaDxtL1GnflST+Em0GH-Pf~GF~uKi z=U?&jBw1Q9TvWyj1Ouu1W2+$6y-|t&rkMA$XxyvZFSZBg0{(~ zET(iFhEh0afzhd@<;Ayme3YW{vTVkL2pD0a2R_8XrnvDD)n#f3rs*N>zr(qWF3Buw zy<_p%sx3@|f*9xNY5uY!x@dRe&+rc;ri!v7D=ZvV*GE^^u3SDwhg;{!!o`=R_Q56} zSeX!ct;O+rZ=e5Si*6Af@p-S%@Q2TsrpVwt8$Wq)RAj#7zc;}OLb(jH<;Gw3Qb2S^ z_iW|Hp8?Di6%Wd80l+s>_K>TRw&*m#RJY)SJPQPi2>@wG*Dd_O`Ay=vLkQ>T8zag57)>8utFB+DMa&uOxc&p1&={~ulr=CK#>x-@ z;;ZoRc9M~6N%%T!n!dZL>}>KuF^o1=$VcXn{aOu3H3#2I(@K4n^;MvZV8sd8D5xNq zP+8BPXOlmzySn{K|GhK!xo5)REgOB;<0KbdetWN9?h<`pIlMLO;)e!pi0XfPI6M7D z+N>?GvRhe^zU9f=OhEy);-3Nt-D3n_fD+J*?i z{`JGjKbY%2n3kKlPAFq2lpKv#nIoFt1{h>}7R~r^6#fWqwwK;_eK$|JpjmydKRwJS z9Xu+tTnkU0?ulnJ!*d??6I|>P=LZKu>QNF&*pf4hL+noIHZrWN#zwmwT8uv<_Db)Q zD#uaZ`v12Rvz1ju`~5vw!`lkYM4#=73H^M%V`u8Pu`K+)-q;0;{enxBSDr2o|$x^n39JBB_Puz5dprO1bg(VAuZaF?26V-UzxEV<#)~I)D+N`fx z*R#TW*u8aDs#h>RB$0wts?yrPFXg{B-4Xbm*^7d(c#enp6{9G|$u*BTTR0{a`$Jm2 z+z8=&%1&D1=Udwp-?OUBI|cV;Dz?4Vh7{c5x5(K(Qur~f>y#cCf9mVMBCVh~{+#~b z56VTL!K}@An7T;Ytc7~*JnNAAVkcn1_RXbSDtr-a1tP2NN_D&a7YUsQq_eD3DGaLX zb-OenKSOq#%`*fJCIjU4gv8ymHSJkn;CGb^Sh)g^2-N=f9J!M7sJs(}%B^ER zb!)cV%qcmrX(Xg&CF_%zY2eK%zA)_t?FDK49m9quik~RsUmW>SR5h>v%KwHtf1ZF( zj(yW1&_o+C6P1tlN;%Hny(eyrS5&h!8FVubYk>0wWYRg?4 z{VK`@8hJZr#sgRqW#dr!s2a%fDDo)$9-b8c^8yUwna-|M=P98e-(?By3MsSfT!^av z_}?PRVS*8M?@Ao!_+>&_L057^3&R$~P-N)w_?oReHX$ULunjsot~i^syRA@A2EN?% z&VT8QLw3Eip@DxbA%Qp#)1@JXAD2V)7kOYPW6? zWwF$dn<^?E?Nn@&gxrF|3hArU$Dd3vSCcvvkKLM-r$vruy~g;YwVIFC)2HU}(AW%j z)MbA;(;#B%?|a=j*riiB=*0^R<|ABV9`W#Xi`hR9p1|9A7w}4@b_%R?z7Suy!OAhGT+(s?s(<81aCg;T!Bqb zO`1bAG0D{uz9>rWCqs%83}=Gd_?-~toTk+-&u221Huybs5bQ_Zr}6y!aJU-$i`pn) zX_R$LBYPSb$Zh&K_EohYf@pQ42+9{o*q*?<2Ap$lhczJ09~>M+OFv4~wf6u*bQ}sD zBjbb{hj4wbjHr)~4;2>q{GyQ5|4|FlMRp@IlFCZ{=|n>0jasEgno|71YN&8)tr~K? zTRDR(o%nDjymMB2SX6(Uea~iuxhgsKg`KufBvsd2s5`|r}@Bai9#Hz5}M2tzeg5XzO(*P+8& z=u3&%kFU-u`iq)dwj?0Wr|)do8d+8Vb9c&~a_8(U00MD-EkItcM-^vj#rRDf2t3{|ah2EQWQ0Ficlfl>=yMMO@v_ zKmYH66&(4iv@1OmPA0>hBFI>}O3W1&9Rf`xQDA-7jf{*x&dC!YL@PvJQWr9F+QRCK zi`Vs>=ZOua$38p=Lg)ub5;WCga*NqFiV|9g5ztn6gX;e%m$O?I<8)Tct-xZs;_kY@ zUe7qpg7a@g3MJ!Dx9iYSr{LDd^ zpRj#fRN4Th9{!N}Mv`RUX{E3KhR+E2fPovL?<$?o`KW%IWOLViB(oW87f?u1zi9uB zwkD%F9r{g_B&qjFdthK7a7P27myMG0{gX&L&^<$dJRcY53=+iPPUDw(OExw(&W($J z5CK(xw?RW+LG5e;8#cSJu;09D(dT+`QGoitU8YD(jCMb%t_q=RfYOC+$JJFt#DG+7 zDB$M%u4@*5N0THHRc|w9 zF12I9EbWhO6<>?}zS2g2wW*eE)Rmz3_p`F>KPDL(1F73o?<{8Br(PeWQiB?1{m-y; zvd~bir6+RnSLu~Unk&X5ve~|I)O>Y34QUT#4Rcx$*kr-m0{j85%RO~XO)&EHrzNLn zH?HQy)YQ>(Yb!V%Yv=7boWg;4Us_)72#A`it1B)p?%(YzkOeedPU!+y#4-@f0N(iJ zy$gys?m+bm$j~o=WY+@z_`g2;H9GryFJHl+0w~kwpAcY8j=%~4Ec~1v(jBdJi*CBW zbRBmr{a_^&lSm$+s7n*0^;qayX1rSz`J7D18u@ocs)9P0K|ftkml_14 zM0^F6*uXTjmx(DE1IwDvQ$~=EbAyYshadjV5F>K)49RX&w5uoL#%F+{v$c!@qZ%JS~@-wvO*-HN=xq!MSC?#N*4zPAxNkwB?Ry@ z#3jxZaKS$1#Asd;-76PJMg?LK3Wf5DGx`Mz@l9)_l}8dPyG7!JNE*9_2A>?shBX<< zvzv1x8-27{w)XZKQ8=)xz#R*m zL6#prjDGXIpln@U&T~_s8kVo!M164%^#w25i^!ZC1Iu5N$9Za68YxK0UO(l%gfG;X ziWc0QW^L>=@Wp&fmtgG+ly~59?(0+I!7GRI)I{M?>Wak8x^;EW93IKJm6a}y1uSBV zer&aMx+OT5*vyM5lf2XUF)gJPK#U~G%j_wSCigEvODD*Y=6j1EEQub$LfyVne|b+> zb27e2#9kaML3CgSF<`iblZFPj-_yejd;vQi zD(3t5Q?UMdxVh0@bN&V;P^~xJEWkqjYp&wwPYSFsP#ISemSD}L?y-Hm4%c%OCy zC(Xmtb!+QEt~xtt}03x<41Xpo99Ao69mkA=6%r|8IBQnYBeytW6+Z64Cm^ z6)w-9g)7{8RCbtXvFwkP#c^4}9=gR%Ec|GQ$6Y|o(=i~n z02@5^sVDNfC-#HpbEcZ-uG-p(@nbwBZ{8UTtmT_YruaJmi>vO7t7~ZyAcYBI zXc_>jt7%XmwEpr>lv^zDsw66n*;7co4k~&`yii^&ynq>oLNtOs5}1-mJT?IR@}L@R z6fpJx)V;wA>A$6t{*SKTU&3{(=xc$9{I5T4EOQ0EHRKuMzwxe7$XGuf$lWo(+rXeF zufr5VxHTO}M1&=_Sl6O{=<4VYM|0v}BqpK5XuP&6PGjBJ;}VN+5r0JTHxlDR$oYWq z@ts2SNDPNe#K&7KNyQ-P(E_j(XKE*JqT7bUqC$QTaUYIQ zOVs)l#8+-EN>04SoPFh)I_c@Hl)Cp*i6`_TL*%ebbfY+&9A6=Wv&oz8HrKA`s<%^x zK+I~w;TKb>^o?oHAVdRpe&V&(eX~rdH@W^d8$U5*e~I4^ZduOPJ~yi&FKSgpx6`Nu z{!o@k>&wFp^IPbBRtos<+KWS}N8v@$@+a9$m#KhOFEC`2Q)O|g0ze;3oaY6LlW;)h|z`;7i-u zSNmnxoSn1XO56yGW+qL8vP)a-{aN;gk2}<=v{6JNlArO_&CA{z>T9&N(Np-C$>Xuc z&elAXg^>AMmBHgdR#0>xjAC%*A3)bsaQruT;r+L^lpC^EH#@ahouUlfMsy&UdCcnk z{66Ft@UZj`$V3>h!l%VeKDE=1;?uA{8ayMu7w^XN zW+?hY1^N@NK=6MU-V(yILkX+58ty8>3T(G@gRo61n$xp+Dao)@UKkaPHKhHW9@@Ti z=uLigi+KFi+9ipW;Qryw+SDum%giCs+^#o<*@f5inqFe3DFUOZ4fsiXt9jF z<%wPF@OD`6Ebm+U|L+Ot4#5%2FyK!JZ!Gh(FC0JAb%&ZwGC2M~R!&p$jv?%=qN!UR z47M(QPq-$b|8*q+745MOL@_=?62L&%V#wg`UQli_avFtQ$~e8@)=Evb{O21ueEHa- z__F3Jeh4ZmDqz;KKSNBqTfG+=vEf|r>rrMj`jMeK-lZ>4`<;PmUxH$76z)nV z#t%B9{eJx(6Q6!ETe@`TH~vIpICm_lJ6uTDXu6j>E(M=2 z1@US<;cRjK>~>tdWPzuZK~0E)jf!l?)ShD~rqbU9od;?TOL6!tH z?|c*LZ$zee6wId(seU?R|6#|t^0!&HKRb+BjiGH)e1tdO)*!1aru>wrENL;pAzL84 z5u8qw!MgT%-|s^Hy2@ArG2InZnlR{)O9A{k21K>4RYzW8w4?!b4Gnlk;G$0?Fb?K_ zDDpyU#<5J5okeRhIOfSb&f9-0;Qs#U~d z*J`h9=6KCJ#?(0_wtNZqL?50taJ4TtR^3+m-(v>?j@(xZA--4*MVEp;fy4M$xa38LtM1baWaU#71)tAA86g%IM##*ZvEL z^o!L{(ql*jkR%Fi0ecMv1w=2dlf^{X?kqONOUU}C&glt8yS?AbtS5b5 zEJbb~@Nnq*s;dQ{ZcJ&%r?TI=?9Soh;guNFTs8NPVEO&{T9f(OFs>{ITQEf#d1cbmAnYP%k;L8H+dXdF|u@+;!kL$#18#=DN$y@Q)|cL;~Ec zhop;@+xtD(&94O;_WizXzZO)}Jzpv#89JEZ{0}2!E64YmwYhnT?gUAygs+OeN@x5M zCu>OI`4#qy8h1Tohl-2#U~?^$=x9XdmPEvocJlDmU>Z(Zp~g}YO4N5&%V&k zC5f%osiqnVjY<_DIqMGUVjj1wpRC^mDmfZQA{zlG$FfhvoeMf%@7#buNI^O0NQdWF>p6lV9g$cISBRJEp}=SAQqNCN@* zOQ4*QVQ2cR&mupvd)V9G7fqs)U>Q2b|2lGGV@9X={+su$)6y*uEx+RW75eqlvCMM- zDk05OqR0%_UXqWbx@mH>)JK_tC)Y;J!Bel+0oDp_;QrUU(JJ*C3qUO+UV3o5z3h{J zj*4Vc?Br1*nSY!OCDMoq+0SIDGRLPU#Z&szdL6ny?!=6=>0;Cs`rX$L*?$g<6c)k< z+sT?D0q_FXFIqW*j~8PL3wpD8efXjn<+I=W0?9=@9~EQE{A%=72&ND&G*Hhw(1O6t z#Z)q@CWfi{P@Bw<&P-{^&Vm)H7*>mPvp`Qd?OFTz>;hkpb+^Dnlo3Ll3>_LocM zFPu>c-~GRSsZ63jk(oC|bc=U0Q`k1NUA25Z-+ZB(gJmt(##gYssDse!zG zJACb~A(K#Bd_g(y)JNp$`X{69&`nMX6wkJ=V90F4_d(K<-=NOuw6zD?IaOcfB|W7< zjq8k%;`UIUZ+zn0|?!vY)SY;!QGwR)&TO)yfo7kiY1yG2~T9#Sn@n!IEj; zJPxiD(YNlNPm?GjHvLyaB%;I#bkDQ4JGC-%|9E}~xAaULekxSd`+H+S1(lX$NHcH7{*0MDpsgmd?UMfRT)oKsJ;7LM0jgVTr zWINUh45K0THwz`p;ye`9hflWl&kbndZ|Xl!W?hv$M*N#f_xhU~ zki^7ku^G30U2=P#Sw=e2YZUJ5^0~F*Gqk1MLaoVcNx=I_!bobr-UJxt$EvVNC114L zs~}w>Z-xvs(L&GIGD zJ<(zE-ZTpn!6zZaF_PKS(@Yl9H?9NLkV`|gL&N83=|7XUEClR_lLsBA;IEA0l9QwP zJ9{diZvkU@>YKLcP+ay@q<7s_oA`LvIhc-Rqxgxl!@=j;dO5Q!=ewg@YXywo-SnUy zkALcQ8PB{YESdxAn|tG#$ZPIazMA7?f!B3Rn_qe=k$X^E*78tPQ=eNUveV1s6R$q= zri0@orpDgx@CdB6^z?M!M;AE!~SPYV$O^4^FK zR^$QLPd5FZ77U-xl0fkt^|A=o7P~ynsfxr`%K?K`WmGK&Z`ALdx}Z?Zn5Eb8g4=9{ zqNK;=+sd`?2*S6k*KV$7*l(83hLOnbp}ppKPs8GsCnwGX-?&_AII6 z3syR>7sVYkj|{pRLc|y2o|09)4gS=8I@e7))~))nBjxOho|d9&JH$NqWGs>O0eANC zZ+UGd#8&7o$>1TLy*Z_VH$>4-fWc2X;<`~mj@bz>dgzEpgG=&x@y)`{<5Bl$>zq+7 zeo*QjyF7~j)ZfGV>E<6;ZG<%3jh0PiPXh6r5c7_RAI9dZMuyN5sO{0`5Bj%`aWZ9!{+l3zre#QSwc-WpjYb=&I#9eR_q9>ZA zI1GWTIPxC-aXvN7%7SYfffn_bVuDb3c0y=-a_KWRW3C-5lN3Ij%_?L*r_X-4O@lXM zST^QgqCHv=gLPbrrzeJn;O&U4L@K85=8|V4R|5we;Fu~$S;pK_?|dDHMontIKQ5Cy z(luQAJS``5{N;g=y^gv=mqfEgI{)x@N%i{G>Xan5i5Z7iOvt2zLG50Fa8c%-vuRIH zzcE75@(z!=n}%;nU;5bUR;UQ4L@1QZJR@ zKHE=!?xLE<>$Z!6&Mg>od~Zb}a;{7Lp0?8RJvCc>t$OpdbFE^DLOX}1o&GI zEQY*V6g|wk*3)KQkzSB45a9k9)T`rad?i|zJ>D}iTK_&pm3>t6nHmBP6DL`k4IHHy z(yazsXdqL0WqDwmd`i~R?duAOKQ8+5z;EM5&PVI-YvLDY%x;l9D0F8yvGzE;VoM(% zmozr^1T1Q2_qx@4niAkV0ntE_reBrAvH|4r4mXxOQ_wl$jA`1y}TRfs@ zE1fwKtIboC#)E*u{zGpbeh_1~(G)rpJJ;{Y>No0_E{ak*{@a{ebvkr37AYsSbTrN% zsKK^`SO@60F^lSz6xhF-nC2o#_g_9Xtnr*IoGf~}J}h))oPwGpSF8JR^{O177s3hM zV!AhtypwmTf>oJs?-#47KofgbESk1IQ1{*sY3^9sYg8!c-*A>aHS`TkPOhJyOR4?? z?Tm`n#O7r_Ei^w57VxRDb8u{rWGTG`RrgurAp&ET!dntrP5uYpiWuWaH#7v>{GO6I zLpQ%h7OOli^=}n7h5q{+5{-$f$89Ggz5;d}c}GZm=byyKlzM8@`L!LBkHvOO_h5B& znfKTK1HUQt`4Jg{&#Tq=QPH`xFtkk~h+Fqt*WxC`#%c;I8^4?5FYSL1KZxHd$8Dz1s~8XlHcyv7;fq{$_9N&J)or3S6+h>V zXdPJNBc*`&#1icb{?jkU30MZS?#kbbhPwy)fSXH!C#^N5nCaB{g{4={kKW`mOQrM zmloqcy9iDXCyCf*X~_#YmdEQTp2T9k-BsQbDjY__X@7;^t){yJ(%;{ZbRo#ae6E5L zTfrXbpSM_ME{n_GH)+%G_$#nFwh-H; zA4TX*V)(qeRwbY%^um7kTDS8r#m9nW(wkdEoDXAu%g$|Wo{omH)!_AUhBh)i4nRBKE=UEq-R2y;p{@HV1p&e@po^$qXPlrKt zOQwJVH5qyb_wT%?mCuRSwtxKF5f<;X|CGtQqvWjpmOaOeZu2YNrcM2`n3~IK-aAXX zbjIP9Y?@PhQhZ(l%(+krjUe=|y4}>ay>&fn2gpCJszj0puSQ#!IFIVQ;PuW>eg==t zGNC2yA7}@BNrRZ0cIl^-92+b)J~Xg>J|g+7>C;|LIBKaT@Yl3L3U0JK0R68ZfoGP- zxOQDJp_hdn)q>8mgnBF@FLIA$N6C`IbD};cNw3l1)!+iwah)H>yw|KJ8myz^daOyK zX5>Tn_PX!9;}nY~lyXxI3h220j<36SV1ShEBh|}2;6f9pjfQ-@Kz|iL1maapN=aa~ z8yOf-8quT2=`VOi4|B9D?^g5%aSpmnZ&zkkJioa308rkDuYo=v=?J7>`)sUFU7)m? zdnSmXBa_|hU^*Cl+m#on%gS% zW^lLhb-wVvkZxR4e>wdT%_~S8of!XzwoB7jV{Tjl6B$0;0_GmKeXxrKK{^m1(gGtb z1ubpQ%99UE8n$J{o$*L7o&xfXpJwe+5+?HVRj&=#H44IvINm>+zdCp8J)iyDuAeUb z>}>2Y{v>WS7j|%_}2XRpF^0lTVene9 z<|0Hgw2ANA<7hP<{aGM>7BZ{pT1&_bFEt&xmMi;A3i4{&ie zL-!wTUR-z7o9R(2PT$!LC$tI?=x-j*+~)~U_NTQ{GHl^WC6k4&P4m&h+on&o+R&_(I4 zqSpCHCLme$DC!=I-XZApbR_9dgrnyV#QW`44j~*<3 zs&Z&pynHW_$f{0Laf#HoG14T13o3sS3;E%L4|hXx&4fkH3;LH|d>hKQ9#ilv3?p)s zMgmlOTMF48{|=UV_-);N-Nf@c*1LvNsCkAWa}3bW8b%{oH2YY>N46N->tC2%$1_qmv z%sX(|!4xnowhn(ouHeXB_R3QgD z2};kQrH4zYbA@lZk#{IszrqkdFx2^`$alp%b~Ea@Y)^#wLX}8e&dA5!KUYgK$^%tS}f% zW%7Kfh&Q|rdnlhSCu|NLk`@jg8dMkV+USAs-bV}HKNkr7_C(ECve|JtlmRP4Xf5+1 z^ntbYpfC)*`>c*I!uiIP&7r(Sh2Cjay^H~!{phpT=Hc4;(WnsSSEnHQn?C!oawK@w z+>rRzxSR8DxjV(cL!tawPQkwra6X?)BIRwcgL8J*m7F21;qCPJ!VYi9d9>tV#Rmr< z4}^~C&`|kbV-ZZNlYYe&wRMI>wz3*;#w=r-Gvbg*Y&^I9lAe(7!;M?U@TOB=_DUke z*3ERUbj!WMTqT$*-^H=K85OpI0r9PdkN` ztQeN<7VhhL*t0G zqt$DK0@As3Ks!up}(y~$;lUG2z_Bz0rse^(t~ zLxy!4w>IqMJ81aMGz=0qhVuAIOmnX4w<=G5;LO*{FuHTaQ|J3=T>Hx(mmyr^q^=B^kl`SI~ z3LF2T)rJY(S49FaLu?+3g5p3~;!8qhdTe@5R8MU4!PvfWNt^A;U%B)PY9}>*>xEIS z{zOgKv(C`PvazMQN=SLAP6k(m)M(+_jH!n!Ti{r4DketQbQ|KOoo$vllO4wImKP zun1xO=4x5*PatW1Zi!|RdV|(;ST|w-9($!N^)j$cux$@^aWHjIzXa38Y*P+6nm~t= zvfp&q?pN4V%yo?{<%p1q-aWzCpTid&v{MgrYn>C!BnBG0n1>1JolZ_wuHR;(Z^{(H zkKT4Gi&kV%mc*N3en+G`a+<)qOZ2HN_VnU{XtJC}i~1V)GM|2dI5|6!cQ+_81dJNk z@>MJcFhZ}##@YG*(1c|;rVv$@Hq87sd$zYXpS$IPxcXzqn&wRhbTSj*0F)1xSUQ!W?MGUzMe4Af{fLZ9pej(KXemnBM~7M(TS$%K6YLCZWQKHSzUtY1Q=qW9qDf;^?9*K7(6;;1D3V zTX5GvaDqc{cXuBo5FiA1C%6Xd(Ziu+L2&4 zsZs3@%`k+ZRTg&%B@XOPw2nR3EaRX%pz#o-DZO63P2aU8f_;U$L{P%y2R_C04DmcQ zg5xiATEIZ;-}(V-DnyJhwEkf1b&7n+hK$7Vg|$p^SO3l(GHSu20vgIPhwsRNNvZK4 z<`FiqhW(q7u{drrDujNK``J`lye8wi{7@2Zbu2g73b~jxd(#?(9tJ=>kLEqV457e@ z{XH;W)*76blY{++3UeWo8ONWh$b=7z26C&w9tu)(BAqK1VszT!*uu|>$m}4H?Qd?{%CAZc{DyE9AvmzmM`vopkUxD1acszf zsB(*rafVFN`^oj>#NP?UIKEI?f>2Z~Rj`J77L479OK_`kEtR+Uu<5N;4=D6CHqgWD z9V6>YmVe=4Jq*w6YQ>>1NxHR>Ob;FK7o;j>bRD{7F^3y$YS)U__SgtUX3&b9!Jq@(7Plvqtv(Z+%qkCipw1Au1Fg6Pp(r;S99Lco^!cWrmW zxgR!Z#9-gOCH;Tru3J~$2L4SdH*F;~g=RuSX`KuSDFi6fhs(>-jvwdCsM#2%c*F#+ zr_@FGVjVJF;jO{GfL(UUZAK5^(e0nU1vI8lfKOJdV*1rm4uDZzCMS(HvXX4@G;W6L zpLZ}U%JkFjX7*3^b+X#c$CO5flpeg4jHJJmB-#0->k8F6*QogU(c!>8mXwqPkU2_1 z|1}b9g=|u#X*A+1`*2Z>&+6^dN97agJg@-h>yH(+bP4e|DhRfrm9#lGNWzMjWEjX8Y{;V`FS9o?T8gq%U51JkNE)>YtqXmt>1>b^pQafmrlHgkz2NH}v>WF}YxVCoc`N#eTZbk!=u>gpB zM`?Z8<`Lk12QI&JQy;zgaP!p3jnZ$eMaJ<@GSh$Y(7BIi)ckw7UMD^^{H9cr+q*)w76k$=Lv_C=tGO zsB)>Li&>HOeko=Dr6G$|=)A%GCNva*Pq@`{WL*Ydo=tug=6 zBNW0qm^E*V%9K(om7V$nJ4=2yUo`ChkNrOQ=U@om8Un^|5UJngxXTD1Vg~@?dbJMX zGHNUW7CMoayV3Z=hyI=(k=9z(Zy#N1XJflZl47d8lUWDYTo`QYj0G)){A2hLW&N z%lZ`Z07qu@*K7Z$KGm^1sDs#0i5M)E){GLXA_eLc)in*@*>DN6BVTIIQBdgpw#I=Y zHP+>z-2|yDP1DuBvufThw}h83WGVaX6}S(N0Is3cNUNDpYg6Wfb%PdhAE}LGO_72O zqpY`8{H4+F_uHwKeWk0VsNidP^uMnrScYA1tl8gYIND19 zF9WK*sWL7uu5slI}|GXC|#-$iX4ZHSr?h#D~I*C~8 z9;9gEv8Ru<!`-i~Gmbz0?CS%8$g%wF zwcQF+o37$=mxSmC`iDx z1`uJ%w(8w=ey}4EEA9_W_Ol!QIbAdMgam6DNw4B&YHE??p9duRRs$M3n$S@cGsZL# zO?8Ema^EPy6Xz=mM9QzfGc!0q9UpyNz&|e8D2$d<&Jvy9I$VI;woo?VO41R~?1NCi z8UOOW$DwW1@TKs#ve57``Y$*?*V;$^G}L-2RQdd?;?2bLQ3>U{=2BKKh-P?M^vLl5 zs76Bs_O$%61EvbTAR^U;m>1n0m3??3EEyio?@fmEIQtoEBb-z!_V+{}4!z8Ssr^GI zxsn+c!VT|_he3m9<4w$fmxq<$&ehk9iB5QYHFb48U^4=E1|q`Gw;OUSO{M@^1E9}6 z1DJPEj7WX?OKuZ&7wqqwB8%CsXugcpLv89`KHT~S3-8L%GkDl$GT&P~Y1WE3j4{NtAG&(6o#v-fMadLik)B-k20a?8caMPB~QzW|olqJ3j4$!bTKiAa!madlF) znmc1vJvgVmQlHxwA!jk^O&)l2=LSw5!ptl+1|Z4vjCnz1s+mO57L?CMz;q8k}-K53Z?mYE}2dB zk6Tw8$VX|<_#s>F6~Of_h5iAcNC2dK1NS+zn?;vV0P6>!UHt)|ut4SrpqH)GX*|9^ zs4}QF3>@47-0>~09wJ0Yu!i!4el8WDtY^)qNP|PlQCoi|cZ;(r?Y{_@BQQB?O@rLT zKct+-t6Sk`FwnnJV((Nrpu5-IuU!ILzkRXYqxnK$cBW36N#ocl>((t<MBy{~oCJogp0z#45~{?lh6gc4{2Q)I0GHJW z!4e-%Sf^ujQdIP4*G5M-Cf3Ldo-HmC>rw7LK4w8u^7h^1e{0OofBU`kOUKg~p>E)I zp!;vx$T!7t!8z3Y)}-|)6i|`hv&)Q$%x&OXP)B#K2;K|DQ9w94j%OY9n@6mK#G856 zgqiemR!sV7g*w*ts|psX4pdm=iDo!n1t;7PyG6!k1#b%;!sE4LgEg0H-q+r$ z6_7SiCFDEd$I(CtZguR23xOy5atcgP3JXoTP6@veic#vL3A}1B%YnYlz&CB$m?CrK zMrPb9QY&pH9+`DAt8lDF#iSD62xkhT?YKKgik%9tu<%Q&5oYX^!$b$G*gFmN+=QHY zoUH`Bv8=>ja8^$!Mth8z>|*ojtAp=XG0}o|I$>d0H3U$_bvb!u40*0qU<#@R0?dv0 zmVg$9D_r%IHDCqPR4-hk2P|$j&j1_*ja1MRAah6JvpxfkIG`p{*VTOlvVH)S0ayPI zpttRAUIWT{wD5cPK2>-6LNgw9N>z6C?>~VBm{mwLEM|DbyM!N3Q@0$U_&2^A7nvR` z_i2F9KrhNRda+G-sEbpMnoOWDBi!Ks9E6_UqW zlw}5Q@wf$kLvDBDm68g&5#{vrTqd&d&_UvYhvmPIP3*{*A#XY7G>F6+>*|10-zAZl zT=9W_n~GH3n@(OOCP}Hf#XOm>j7A`)XWM_z`<|T$%rX?o41Tm}1Uhe%{y=kca%JtN zSoIcQWs-j5o;6{GY~qa#!0mOr;MsWa>_W`oe!$}B1rci40t9J5VqWFY2iYRvJKfU; zp;drh`}_P}T|lY9WY8{16lIPnVFaryT&lUEd$7)WZ8tl4uIDEgIOz=Ri-Vs^uygCt zj%>1d{5lMtmrk$Kf|D~-4fJ=5m(!DMGbR&U5b%at4OjQ=5CI3%grsZEutV>zJhQz| z3#QxGtwa`*-LiadR`f7c`!|vcz=G8ad`;3p3}#6m9t>Nn4m9enXUg}d#VZk-0NOc* z`n02f7SLz&+b_y@UDh&r#6w11X;ELkA+uAO;UByci?{pw_EOGDz4aHL#CU;L;G5IE zqfS^`la1IP*%LHhp?piBpA#y{wB<-!)Ru$8j3d}aKYn1cn z_dWG@VM?D%LjK0H5hnNPArYQ_j>!?06nA&AUK*M4^FH}Z4RsvZFJwj&8}U>bc&Qcd zWYzD@Ng9*>?0(cV3c7Cle87ZK!1&o6mS%neLFYseR82Rndyb{C7X_SM1?X98Ycqws z$-2U~g4{`?K6P#M-WXA^s0QWxYh$5RRFy$(_qV!Ey&iARYTnl2q~ZOQ-P#Hc+=B2i zXU1IWfLp{*W!<0*N=zWbwq;ll@sE%9Tvl-MgwIE%U)iY9r)?rIE+UASn1nwU!NwXZSxKxB&}K+b#ihV;adrj@nXLHu$pV<)k=9P? zx&MG&J~27E`U^*T+7A-MtCXb5KkVl|Vwyz8s&qxn1NI%Dcb8vM#MuVmlX0FCLyDw# zHp<*v{(gk{hz18ni+mJ36oCN|=l5}dYLmOk3dqQ%#aPYVz}GCINg-Y{87s4~yD-a=wg-&j=O!@$0U`Zcp2zQ-Fu z3g7jz!D{`?O?@D@P{mg)D1534Z;8r+ucu7CdH~HrFOF8a$hBjlQ`GH8t_sZ0+k&dP9D&;E8r*|fYj5)i)p)*zn|D1p31~1R&34(vIk`6*piH5 zlY=RRL8pjoG0x&%_=v0~2wh*y=yCKkHI;_4cf$8(*BeyOcDCaZgfu>sZ@j8Q5N^Tm zI$~k;^PElGpqoMPdevU)`1P}TzlqMFci(ZQ6(#fbSI~JT^HKLdo;r3Ww$d^;2~kP; zfkAi(y6-%N&3(-p^VvF8a6vZl88+6|n|4b?dW3$cyZOiy^d8w<4jR3-E8z&{!-fT; zjWvvM4FS${89y20x!&6qxV-oL^TTecu2=1k^19gzTnNw z%(y)t1|uYvW%Uo>yo2er5VO(E1$O}(f}-?*U5NzNUP%6Bz1RXf+mxZt;+cq7{hm%nMv?-l*JRh5=vx~$rx3Z zJj)jYEO$moc3nraHl`u?px8?Qs{OgA(#$A3sZoNg5#vXCzNUsk*|93-0n@p=rH>H` zHFYWQ;Q!8f<2|UcKETAP3A7zt^_B2&n+O$dX?w$o1%{GR@{krT)2lhTNXkmnV1R~L zIDr_WJ`QfxU!$sG0%J15N#2i9wOv`LnCkYAB~xZ?AJt+)F0Q)`WNwou58&J~WLoAA zL*#LHCUHZCk=4?3d^DOsyq3H#eAiZri?H;C%2(cG^c)%W$J(-pOiO4xo9J4AaU-*J z0c*A6Ld9aWOB-ERx(Gzz4V@LhTbV6E&fFaP{s!f1od0+H_0pl#1nzExukX*M<2I7? zWMw7OCU^!{!+#XDX#j&2icz-L?usj#9bxrn0_e7J=P4$r`Xfc8l1Dq*Z0Zr5Oro0U z7Y?RFbVwMPmQ)M2%B1SS8Iy`45mDd;S`!FnwIEN zuPsxs_oIT=x!EYl$T$T_5NWL-fCrIt0+l>GbxOWu_TPcG>Qaw7 zY9M%CVdqmLmPcH;Sx48SYauA#o1Ph++D>pw!vJsQY9c;o{bwt?V+r`vy^(vam0Mp0 z`mn9d%^##b_5(&ZvKA;#W?}_#Kf*(jd@DD8Vl9+O*SBjU6l^$YK&d>lR5Db7-MyQ4 zp51VwM^$PHTS|Z1y&Wy()-VuENu`h&GVmp}p8WA;&gbTqd!OUzp@x%VLMw^3VQY4S z*cL}TQB)iY3&zfhj2T`ft$}mQ`OB=MXVwweam?I!-vc zB0M5=1*=@D6q*cKoC&&c33hj5+9YPLe7?TX_t4aFX^yy0h=YpkGZs9FpD2gLYEpq| zxZhG_Mak5efFtQmCtuqD53DRYJk2(RHMnmc{A_qd@@^MKiy zzknt$&YRZpt+%Ra<*Ey0Z>Gy2LvM$Nee1~;`DM$O*z@<~W^*ImpCmYYqN*a4hw zBDWzkV%e?icThWOP=f$M;EVs#dsgUq#E0Mz-LPVKAX%t z$K}MbKvyv$!&t1dUXe;Us^(YlR7nqk6}{PJ-@m1+TnF z>Y`4$f{L^j@ZO7-+d95t`j_BgyJg&$DtvGE>nM=rP6|9nu!sNnc8h<8-0=5h z$Ct9Rw*XS~R#2kJ$f`1;1fifWG<<#nD~-oN_%EA;ganY&Ma)x~L}?{Q8jWC57T)Z6 zwg-Y+6J_3OjIbE3|Ekx-J~)r?eGeksKY0NE7jhkx7u&yUu1Ogh$|fkNOAd-BW@`Ek z&jgn49AR0%gOGWG%XMx9J7DwA!I1ofKGX>0zzzL2+wO}JWWWKLYYno4&xz~j{5%VG=d$`3{@pmt zc2fgB@d4}&mI*X24JfqyMCmeIGa||!eOJ$J?G(iI@V5beqC2t-5fQP>>SaDW#JmUx zt_C_jZN7H+iS3{ZyT>Dprme=Hxyt{l3~?BMGZXM;KB{r7*oL`>g)8 zR9pkhwQ%2e`^)Yi{n0{Lrw0!^ybCZDBd%UAoTQCsWd|4Z|NBZWk^dH=QDmoP5^VM) zh#@A*JArGM`mBHM$q&)`hl**U&PhWKSTT<7&#Ycr?t@T4uE5aM^^}=87l60`>^|u8 z{Q=tFu{wnnW`)Unx>Z4CZ<-|ae|_JOI^-7eVLn_xSIHD4|7#|qrT-R-D0N%w^~lPh z@$Ax1#0b;;TipF8X2!$c(2S&=&gR* zNVmthm1@94W3Uw;@Z4B!mi*N0K`b_x3OGM(@t^m3^6GVqY%TksJ_u*dXoYW$TS@%O zny?B!a#XOA#+n(s;Tu3zu_S)GNMxni8x_>q6I#9hh7N2$dl2=PvAA^m(mV#X&CA>7 z;2>Me{f7j0is*^YiRAmotI09x2WeHdW3gYvOp>8+Y-tsxMBMcnj`W2PGR%KJbH!|D zK{`quyjXjA+J#U}YAGjP_RL&A2tz-;G8Vb)!L*QpW3<;0>Q@ja=dE_b^2rUy_vpM7 zX}EDZ&=*J-s!>w(SMdZg0<%%R+%cy0u9gu~cF^Nneq8mz?|+=Rp7Y?UDq!W+9ORG2 zH9zzk`~r7n!d3?pO0PUwq|>*XuBuO0`i}i(t47 z>^z}_5WrRcbov+L75|%849;CSc?J8SaD6j36Lq-S#fM-jxiGnnWSC2mES*ZNU}P_F zRP=i+(=)%E9UdPqNhD|Y^S~GDA$AKrQ9zc$y2|{YZ-#bv%`DClf8_JDj?eH=J-uiS ze^@>`-nq^ou_`QS-W&D@Ih@En9+(K=520m!h)m~FXG{(-U&wW^pWQ3@d)_pB_1)tH zqGifcmq{!St=Z_Ci!J=rc=^0@;Ummf)WoqlDiZfo>`9{J1rXV0aF<;*Uu<`nzJwA* z5Bzmfhn-6K88NEvjFq;fi|uUbC0uLgV7Emj7#LrH; zjl-1^X0?VU6-6{|GA|)01qbde%rdU+3sbEq{wiV|=p(tHkMPTJOBk3*zg0GlDpcmv zPs@Y-bMGP!c^7$Ubc~{UO@uc32Od{0dNqi@`o)XqRqx*7En~MBUftAwBeM1J)O1be zyqVT-6AfM+)coP@se0*-fkY>B7g`YhW4<3cKuZVk;V{Tx{bd6J zdPvg!E7+~G7&q2NSuCH{*SSITd=g#<#|xKhNqT1&idJvUa7Arm^v4KW&wu(-%7JH3 zr3}9G`#L!-yzu*cF~~`2*ItE z#}__s4t$F~e>~>`cSL1pc|FZdg6Z}xW0%Mrwyypy1zcqmf}Td&yH;*!^V<4<;y@1k z{^|UBhD!NBZ^zm24Rs%8rc%m;MHFHEMQQTU zI6;`kc^x*|V}iU%CWOu7zG`SkCYJAEi1AfqR*LeIbvUr7$>BecPM(Ia8wY4*yGISw zfRo<91&4u}>+35@!sEA;4IMc7TV1VUgWpB+rP%6gXdD~nTSvYxo1Zy=mxsRhI@5I4 z?%toy*%lJ=>4UX-bCL3P%uJ2<9lMhBKy2+s9^tH6TdL{owuwAwf!m9w@yo{fkW4F(blt zv7q$0(aU-XI`!VKeD>^R#&>=F!me!{iE!JZx-rf6PV7^VkqU}~Uw`lOpgNN&bc9XICG;?z`^MoiR@2}1Izi;=V7(1?{ox_L(SEk+ znDqgAT|zjS<_j9ho^kHqOB-e^ON}owgFXoh^;;=HJuS8Loy9k-^rDK~xZ2wsZl^F1 zHYiabdkW9D((9R7T@!4GqQl?4h1|Zn2lpM6m`~kw?dNeQ-EIvE_&*h8LZ2rUXP(`- z2-TR0xp+%Gna^(Fg%_-!AK}sM?8*iRggTCClAZ*ee3K<_Y8EKNmT@)^F6-IBKHZM9K*@V<$~B+tMh{P2KFC=VRKk;H`4 z+<3+~f-4ANBB!>(9iewZvtXhRjLmUY49e{@k0P_|*^Ge!dAKw(06*r_IyPY_mwBarvTVYdmty2iuwX+nv4b9HFJ+i-Ne9 zUlP3O_+%5fe`_TeR+K7{OF{sBKrgx`nN~qV_>^#>&w1c8+BNO4C*bvEHG^*$I#*tw zJamNg_ckFmtbd+8rPj1@l_UTIHC&s_|BtpEzr-~hhUeZ*kkyCNkkgwK{dKV+Cwg|5zP zEgXJaH(ghiA*;Q?N*ShF9K!_U38;In-auCiDB_7arg+yZ$#s4Mnyi)fELm<3Gyb+x z=!?rFv4TReeQy0#&cN=0`&KD}x6?*#^z(l6ci}nd?%B)qmsWhxIRZul_gWrq5S2ty zjLL_&Kcb6!EHaLuwYj@yDa<;;)u0X#NEBX66y|-H=(I&=FS%*NN$_$vla!=#?LOLc zbr^aXtz3M~j^UUCp9QCp$$&+BTIQwpST7+thl5vf4MWh zJL;_dyWu~nE(Y8H6Gdr;Px2$egAiPo{wUaHEm+{Nm)BjSQ76(HVa+b&%XIH|mtHi- z5@0_pzHxSxJ=xQ-*UjAVVLqB@(2mECbKfU9TX?)>b$@q^S7D{XN#042G@HNv2*_Rw@7>_C z6s?$Zr4BwF74~VOivWVC6f);EuAPJqFN6-i`~O|j-tchk5fckrs~y$%zdbdY!E@(Y z+dsf1^`T1kchRg4{5(k!y;QsD1$`glZ-z_RkF}d@NvB+mouaELhiTb9*w-np_{rf* zbUxPAAtRP=!A1edG@7djJ7uSTvK6vE>3OkLUU<|AbB>wjV^XU!k4Z;ZJEsKHvTPXTG9a=qVZ%tZ~4z12>HwAzmeU zt%&Ur3kyNj*6f_SBQ~hd0mMRwqQ8K7xbb-dt)n1czbOq9kkUXO|F|e>ly#2$=8vfJ zx-cl?%?c~NE&o}{Sk*gw$eEPJy7jUCeTP86b5K@Ro2kpzmU$x8xnJ?{_}iQ3)3v`3 zHvw8}nUQu5ZEm9(d>9WIivk{71NtYePv$f~-FEQu4g5;p9H(h;L8s-Re+wpAJ9^`T zYU!9_h?yS9EWr?%bylk}8{WTsVk&|dNnfSeD?(H%YrTTwYq#wJIG4wfe;%e9(RJ8R ziNq%v*3iVSz?RDql+D&5>BuW`a}OfZDtSw5(2es>ZcT{@qz0pT}FyyUed>jm@YR3NDv7wF~{(+cjuFi(SP@bEDZD`lN8b8O26q2Gq{z*e$#r*@VhJ;B zs_mmAdx__?O+T3#?HPVGnwIj&RlyO1_O0G-oy*j3IwOm#P(<(pvKC4lJ*jxCZrLI0 zOF6a@!Oat&>?TY#qh=+8`d2F5+CPR8=&;$SU(FL`zi$;#Xy&ck^`O&Y=%p$Obp4^A z4Cs{s5S@+Nwu$(eSDtir<`36)9fg&Zc1$gwab|Ex;?@S#v!3tgX(Ss1hS}divleMl z8n*T`WSemsxiuD~f@Da1a`Fe*Kh9w1!9|l1ch90!>(Np&=Nu$x>~k*i3t7qohfJE< zCN*>8;(Z@Cy84M=7u?Nk9Ap!M(6oq*Yj*dNW8`T7@+Ay-VS)dSffQ_4 z>BzFYE-?RJq(}eH+!bL zAMk+Cy*?lZwTvLpzTRJVI~U5JJmuH~A;jQ2+US(O zz$rd}A#K3N-S!c;ml^e*fYOvAEF55}HW~ zPgek*C4rds0Z)IWuDSub%%n*}ZR;p-#RmS)h9ER6*z|G&w3 ze#X?r1`8!6n}bSGGK}b99i}>t?!=qeBVG3qMKZzZC)A&HE#^0@vK93WQWkUbe=r_= zH+`GY4oj)p>@8mAlZAA~XMXqyk$OVVK)7)sA+@DTTZ5X}zb=PhgB%~)Zqo1~Tl*p@ z&W_+jP=OB@0VBW0@1$(mD?{_Z{0?sT0yBh+tpgTD4T9GJ??5FS?Gms!Ct9QD` z_2LfbrRGXz{FxLE_6$CSVPT(O0zp>D+|#DP`mi~>ancoIgru}=+^)6>S^}TJ_wbi4 zq651Z=h?_}?4V(YuN(4xDP*Mzmyu2sy2aVRRZkcV5TsF8r3D4LE&&=IN7droT+`az zo1SPOaof()a+MdIpFEv;ahNZJ!(>!DPnZOQq<<6$*O$T4vAt*zd z_W7~XK=DAZqQYta<4Gj2Vr4bnVpTd#I=HnsUI`=) z0MI}`d8rzrxoBxN%qM}nWa%3ED#FgpO^5{$*s~2z(=Q_boJN$g)^Cd-5`5--RBMp` z5-@Ks*Mt1amvBR-;+wIIrOdLb&&_dEgz~xP+;_8Amhm!*&hnhG;PLVCHgDyxU$K`2 zJe-_3tl2D74LBIHq>25=${@1Tb!`jI9d1xMR|(it?l4Lq0N4m0GonYIZ~wct3@XdJ zO8`Tu&cR?bR|3(d_R5L5t|8Ps>ihRp&~WK-p8+jZRX}vyKanS7qw00l>OV$_dvXezMSVJWfM+N@YyFp1g85X8G?kNK2C_Rpp@?F&h z)3q(jqaaM&rbfS~cC~ifae8hm%IqG?l9MS#HLaG$G3h829Rof%3PdF{exOdzjvGGx z;2+K>KeM1e_5*_kuW`!;(#soxl*-7Sl)6>tpv&L*ObEiSmN1A%fwyrA47%#Lvh`bz z%b)XTh!5qCqU>_-gfpZo=JRJN$*9hj-oPt}e^4($t zQp6@@XfxFkJ$$w+ETCt*!;DI8r^k^2pA&g9MD?7yaRIf|YZsWt`;%@{8cu0d)k@u- znTi>wzp7UzF--mcX#vot%E#s*j|Fn0mk&=shZ=bI?C{!W6#lbTZ$ZTa-P-FsFo}7t zH!8)zSf$vmshB;8mwCKSB!YuKVKr#(Zv1rgoc26*_Zru()a}fD(uuo41(9JV=DSWm z*K_%Rsp9)d1l)lzv4dfr6=D|$tF%I^v`Zl(!^P|8+`oU`Hjyb%flZL|$~|`CeszHT zn5xG=$z=_MEidA&E*9!8*TnffvCC~g-TUIKQme*-n6$BWkEe%>n#ZW}=WUEDOeEre zcBLgA2G{mkl#5O@YvER$Xu{AD`3J1!{MJQIf;B3Bl=OR=w^J248ugK7S0~WvpVJkv z`)UCiUn}>~C60cho(0+BnuCI3n9eH(p3V48u3#F$v*p&$ZLhg69$$@-MN&gkLcu>vT>f&Hd{&Kl6i0?YSi6i6sCcwEN^SkaCC z_`}XMiY4rP!Mr)GB7pH!V!s8S3HeVu&z_Coy#?s zM;D>f(2DMNZ!eRpy=8ZH7P>0n*QQks!I8$+;jI#F{{1amaC=}g7&Xk|Xt61n>4T$_ zZqy_Z8sUGVjggGGRM`Suo!P{S>6d$d+Uu%B|H#4WfQ@F_>(Q6TB|s9o+={-oJYx{h zR#a4UNiwQjJr_WrPo(cRdLEP`N#4?Ho<}jlrVL{_)}apajI#J@i|W|0!^0ZK&_Z>9 z{s6(z#zg1P&o0f62T>2!WGFI3zyVcMgH9Y4669=dD7BQ@fq%lZ`bW5RSZ}vz@WiMz z8ML9z_rvpJ8;`E;`}p@~hH9VwvVa*Y@}qh+1i4#!HR?iH$q}pzj&=k-`j$oV$X$6JRcXpGai|L`c0d zg#m0*o;<-12mZ9v2_5P#hcB#=X)ve3y&U6NsT znBsD#FH2s3%oE?<>gJw%w)`6_A86Dn7WE#2v)Wlx^3vf9a3siPSf7v9j_BP04k}N3 zN&#KB-xb{5)LzTei%m*a`&PZg7{bBlVIP!gID=IG5%-ruu{ayxpDFAni?V`j(v7K& zrE4(NP)xNL3plFzkkY0X{M^oDkSYLn3}zjgzy?0e@o>BR&Oy4DF=nREs~?zMHp^N zV__Sg1H<4PfQ84iTt)@w%O}oF&&bMNb83&@_np3-4Tq;g5tDrZ^K~z7!%h?m&H3Zq zd!HF)IfXi7EI#)Jv^-UnX^uW0T8KDprxx*f_5Z41cxfXbAt50oYyxQKuepJD7dy#k z=m+|Krwv8N-|7N31+t+gLy11#-uDj=4$XTs=WVU4zzFPh8vxQBWN6}nJvk~W>h*5{ zhPYQRiO1n`TMLlI2jIVX79E4#GJ%lCmk7qn-$0fh=<(PC+Hx@>z~iu-Ax~2U$U*@$ zK7D*YkZT4&C*Xm$WtKNXs=PiBSF|l8Q#85qxXp6{#0m_uw4ikWsZW4lH(a~c9Eg%U zW;D2q`1K_q-~|X<3;<+*&kxWSA41yR#Im1i=&;45;(s&?C(G_1Rt^uX%~IaaI5x0F zoHy7_T5XkUb*%uMqZJNbX{>zZe|YYHIvSX)btH9}u_~WZsCQjL`%QqxW}3aLi ziO8~#O=c+tY_Zq11IyW$BmMMQi^<^c_AfM7s3(k7t=0g0A3ZW-5OYn6un*P?`y{Ql zN{u9Rm~n!tK8+61yf#p09;>sJRG#~THXb_iIyq7WeCK=N$%PY-9rlZB+%cu}v4U@Ej5Dcu1| zErm6g`HQSlnZ(ZL^PI(z{=4@q`=oMKI5DizZSo>%qoEW#pG0@UAA2U?m02F%DRjR3 ziy8B!@p#GYz`b1mX{RdSsb*vG4QcW_^Ej%f%Oa7s*F;IbwZh%(WB=!{y5#5a}nFu(wBG19A~x9!Fm|lX(z>I{^**CyH3$-T)ksCLnrD zui4dVnZLmsh)n#b{0L092t(%@?B4xl1L*_#rq9pMf}rIFyM>O94(eoGW2Uo*r`Iqu zz%nHX`$}Yg0oLO^VETRP;b~W14|m$yr_&$=t0l&q{uR!4IPM?j5E%8o&8>wf=;?i> zK~UEW@y|TWz1kgMBzM zbK+#Gj|eFSVeaROfe4ICA+$2Min9EnoL&Q^M)w2X*RX7CrIdsC-E~Bbv>PVy7?9jF zxI;_$z30l!xJP?_N}}gGR1=V-w*kMeY#q z$x%rG&L=XW#F>f(biwnvQGW{JEcBd;BTuR|C$M2!A@sVwDynH7i1@W>dA^7G-?7GC zM+=@M_Ihu$t-L(V=l(mr5q`;3wcvG*CJgmDs-Jny^Z*p{MnGkr{kTbc(sClqem!5V z9=*I}+Iu4#4EyNK&pv#)nlt7=-(1jB$}^+Q(S zwUBzKG%YVFO|h#vlV{Y9GBUkPf42*wa+CFJ1aa%9V7`NATa!kWcmO$E>ftu04qjl^ z&3J1g%v&{_hvl|fA8sgMn~}&7mECm~)@a#2|DZQp%<6mi5fS$liFw8N=itmhPrvCe zn&tcy&Sl>@Gyy?wYD4X8t_^_MdF^0yN0(2~*XLAZ<(I4mLW%n@EdzVn?&lM%5Lj5a znkRXcnHl_!hm=Ock?IfAm##SQLP%DjVy5gwBmhz8jA+=$K&kj(k}sA0kVaP|W~KR++8Wu**DrA=j%6lREenFe)y|7&O? zAV$CRK60oG0em|ALclMX8;W6yliP7$0f=3_Kh!hdN#s| z`Z#vwfYJ7N!rQd3Fy&faHOWn)^SR%!b$X2OJ}5>)b&g<%KHuk4AB;!coi*_jT{Rxh zoILE|pYP7ZIGKGOd#+bM-ldcbWfJ>$wDO~YIuH^cxgcxSc`eBF0a1*xaOx9Cgbe12 zPjk1aa|A|A<4Hzr$1rOPg!JK0o3`u*AgBQug3`vSenqnzhPcUqU|D}cEs9BM@>J&h zF7OE3He@F~Yk$FkWXCarf|i~2o9SkGJ9H)5JNYSo;4F6LDYR}wEE!1$OS#GfKYhij zmW|5})%8?V6?dHn>8|7)i75CiEa+%dntsD2jxvYHTNFXt0Kv$KK4{ZG=dHNCjSb~h z1CR+6qW|E>iRGLKp53_+x*U@*ZSJ3CRBeB0zWfxfw%&bX(0r2kaPWDC*pkI(_wDG# zjGo655Lt-PvC-c&>l;of-C96kMe*>_5=$U8g@#VR>Dh_bkZp<&}%qGxHCT*mG|00!|^D z!j+Fie)I51;&xo@Ebr2u!r0)7L9oU5iMf18^D*duVIT?UJ$ysuXH|;O>iaeb**BP) zr+C598sZN=;poWXjH}6URy3ch+DbrurSd+VFoxvxoWp&bbIp(TCzWh7Bj;$;T6&T; zw{>N|)R?*Pz`3WxNc!~n{-^`qfkGMoA}%UEjBIl+h2B5X=(~v4;YMSJ+uHmZe$4-a ztVJDu4(t4jxcm?E^frQFkK7L61FKlgje55+Zb?R@KBVDDK8IC9SZF?!68JMLrtGd8 zXr48n^}HjQsA}-SxJq<+-kJ(%rIDq8aAmh!%_m^>aNb;A0@<9fKn=8qOq=1j+7Sq3 zoF@O{R?6ge12Sbyx%nZvxw&2!+dvj}R#p~pAFQwTr>5Ni8wil{$*Suz%tc8_DRpxW z#0CIg+`zOoDG4vss4uO7Tnl(f9?jP`E_>Us5pb&H03PJ;K^9drukOI}2_Uoy$e{uP zCY_pZ8;5|JNxMF^B|S`qQPV%Ss_F(n4Rjlr{R6?W`TU{F3@KBDda+}(y8d&p%VdZ! zj@t7O+>Zf{?dX}U8TCU8mOH#es@D&DLdUmk zGBGmZYF8H4lefChX76qJ&9Wg=8tay7tQ`}4%34%B=^3ip>lxK>&>?ef=GPUPJ|e(c z>$CwH%hBn)Iy!QrJ~E<-f78K%#5ZcpneeGkwNT#5);5DqymEUb;`Q8N)@p5ad#PHO zInmbguxUkW;JI(Hzc0&s)oJJmSQ>#9h6$HjQnII-eg6+5;8p@On9Pb1_7^bC0>1#< z*w+kGV0T>}A0J;{R*cK5IPiTsFn~Uu5AF=7&rDCd19@Wc{QE*a*Sa1{ZipD9Xb8ct z*%3R!H+(oqoiL7o3=$}~fK%teep!{ht?eUF)IUTTJO-K724K)dcmuH!EI5V^{&p^Raku=Zn)Ze!{AG;=F8p5O?F$*7R1lCB4hTqhcXvpKG}0|dr*ug-2k!WO-@R+y z;U8GQS}?Qc+0TA{B}K4(-`SwCdi(;)Iq92ONm;d36l92ewz}HxVm-#^d-Qfje+x4r z#(K%8A_HYF&%@!%Y{YEvZS9|qbKQ3jau9&If9K=;(=p7TTVr{3)fx1#LPCywYbQ>6TXmCrCWhO3`;qs`!ub=o$8Tc$}kRlts%`X8INzq-v$e7F(>&aSTf zV`D8OB))fabnsU(3l;J`9N_AE?2IY{ARWcN#a1HS$fu*=%JH$E9bH9#lq+IlH~-&| zCM<8TQ_{$gGWy%2eMwc-_#+^enHjOYjN3mNc zYq?PQAe*F>8U`nLSW#~0>DhRJN%KN!k7%+C15x!)4g#i$Fcbv=0wxQYngDwMsXu*= z3mg^a&ot>+7hw`2GnkKHfmY*b&b#UKY4&mDq&tMG*#TGX?>7SU6L3j8N33V3n|V7Cz%v*d43(XlIUW za5gw>W^5Tw`OND}#_l~Hvw(;69i(@8z1Md~gxi^{Xp8&@g^WskBTR~8)CxZ5f1iH7 zc#wpU+&+c&O)9Zz>TI@4OmyH=sixhys-@qB+1;U7_Li$88T#gN(n>(N4G9s=|{&auJW#r)fnke)07COjnK>ahwhnIS! zjG7)Qjax*3CD3n%i=BofF)Hy+jA?7ECAd(NYaz3^j^F%vcZ>4oSEY$tgwW`{mnCL- z?L>Us+32`+J*V`?1~>P%bgG>X3xco7-!gcHfysBUw#RrOqkrWnY2{e( zZ1m$GS~2BvMSL?o2)k|liMHBu0a6n9D%bz8Sl|OZW6fwwsd z_jl2LQ$(b;WDkHk_8R0+xL)_cY9wLSe#vGs@rDy zdCP?(h0fhGELKV`mMi4>-*5VwgP_g33pGvROg`4sK=iKPs@$o!?$Z@?sHe2qzU@Ua z=98RI1MzE*^)uSUfHGPJQ~Dr?LgDjFX+zc$p2Ia&KMnv}m$fYGk$|Iz$Uz~a#!~rI zy2HB|l%|cDrjKz6A$|9rB14}(D3*MM|1tllSqz7c?;wjNtq zO&E1(st{z^;HQL*AT`c;_W7xipC=~7!X@(a_&FPyevJ1?ZhL0dI6ww`FLqaPH*Pwc zaq<#ORV3^&-$m7(RtS-0DXC~8bH8+>EwIj#BerJ2Jp-~#aIUT>qs)ns{GmISzv@BZ z8_C!hJedF%oWp`)H^H!c9|K9>IO+m}3W#VWa+;&49+z7vu#8oPy#zy>x4_-&&rmD{ z47sW1sO-rX;Jfw>ALQpnw^TDL{fGM9T@c|f?4`8mZI||J?bZs|JzR}ENS9 z#y-7#f&rA+L0nIWcLU$EJkMV+=WB^5xG8-uoO1k28zwCsln_uMo)DvGgBLyedOHE# zUX&$IBXC(bzxD+Bcj+P@Q5uGw6%uVqF5$ zDbWI(#h9{=qOVTST&7cj0R+LAlqHW&FtP9_*Bm99Yao<9IZBELVE^giPXvVmfwgjm z+@HF1YnyOsO!c*nErLyJV&Q)aDR27#2^Vn1xOLsr=B?xJy39)8q}tXrg%T-c7F*bXtN0QyLMPZkiJPW#V3k= zH~2qLtfG?aH0Nck@HUP60{!E(R52efg5$|yd+{?hAl?~$__bp|E*MiEH-zxD^sbxP z0-Yag>_x>sZH;VsRialSFs?2;UXr!2fl$_T*~<-CS%I3qh}s#q4`{K>Xxdc31bLj3=)CX{lxgTY6z)X`bhkYKB-J2xp{vrWL$(HVCDyKn`@UK);L6S>_=P1F z8|WIZ0b+3=B82n}8B!qgYlX^<$m{ME-Fqh2m&%aZ?8wz;{eUtR&Y%V2E>>hC|5s+T z)wQkF>5d!e0ZM>{)@qAmF-bILVlvc{@NP^KV8V$P{@S)@3#w7FYMmFE#e}mExasIh zH%$3RmEb`@W4bY4jZ;i2KT9@{7T(`>@r}2ezRSgAf8;lRu!>oE=+dZYxgq@443d7u zD2H1AuX?=(pHj7{VDy04A}zfGe+FMGv0p#+4H1h_uV>Q!(Zb7EGQvLQnxq%g!NbZ+ zW#1{h#KW>fcaI*;Kl?_2P;b?Ze&gzqFKnC0aiRo@_M5x4Q2f47SawMDs%VYwQ#w|^ zR5(Xj)2K#iZd?5=Hw)BwW$CbCdIt`-s#7Y4v7 ziHL|U&RSdLddWULunqSj%q*l(<%yv(6acBObaJ?tp|xLozwXEKLN_51tjWD3vRWEy z!iW>&X4igL4#A?S;dz%{V?L9D2 zn7FhfY)m8flZ-_!J1k8n--d}>v(#jo6L{5cO_-oJqtn9FKix*})U4m2_@NMjDl8F< zdIkkvzy+pUzuodAWWx*hMWH7DxZBJRF80*PBjc)2^v?hkgE=)K{1YTE)!TNHcIG{H zIe-tB!Abs(trgn_@gPX|x{b?%OG7bmkrsQHP$wC_wETYkx*A`C;D z$+h$4?#-M=4qWEXTVyyJyFXSFNf3vXMZCx&MPJV8Rpse=_o+PF%uI=YW!@ij!H}eV z8dvs<{1Gss{fXWUGM~t*v&|Gs{LvQm_vlll|AvD?59rSQaD7Go8>9%IO;(`3`vPd4 z2#h~4VIGpTWc~v0tYXQJ^P8c%AhmZC&E*;Etmtss@|~1SEZi&>4a6|Gqpq%v;9xtf zRyMgOuM5Q7xrhRCbS{54LSXTQsyM(z67mwF7RdC1JF3swstQfq0Ot>oiZoJdfKIeG z_`@ODg(igmR>mJg45CESbx(WYqwXw7_y%DV2LXE$g}2`fV;w@go;%?ry_i2{Cs8n(n}`lMJ9-7bl(529v9riSi(z} zFVsztiW_eGyt?= zBA$zU&sW9o5W8Fv%Hmt~`ZJjTpM2!Fv*q6YODZ*P)!c@sG_4q4bOe#zsp^5R7%{Ol z2~2+y3yPXhAe5>nCzTSCaY z;Q@0Q28IT&_xMS*Pg$!iMh&~ISUooT700X)qq7+?pafDi?DT%%{0kgc+U=gWfH|M> z>1$OiYR1NE0f^|}KWW1DNu{FvPgtKDiNUK?p7$?*CS{2Fy;GSma+c&1RLnyiBA{Ex zkH*HeC@YNBt-}_Wxc~SebNG{nw6t{3hF-&^!a#bfLge`C@kB*N_oMl<=*%fm0vlLm zjPFpnY*9TEjfev~(l*H}dekj>#e?YnLPYgrx}4BQ2oh4fl@ug`N!I_)zp;@Y*l;SQ z1?!z$X#w{+*5=$GSN?e_M!H&Rf@HXyJfu)H0d5ejKzKEV01vk}uuan~m9hG)jq0GP z@BeWDxav83?&vw#<->65o+$YU8vDo>T7+*^nItXiyqLp4NE%Tv>BGtK@wQ-;K@%=Z zBfmHIdj6}89`xNPWEf#wOZPk*53x$XRwb>rQ;VbNw(hs%(s-nZaMlwKRFn~1U~+K8 z>-4?xtIv9P^7u;A+N`&27Y9pA?S!n&s~%-Dm5R7Z#DE4q!-3yhP$lR4bdjA6qC%7H z9=or1GhE6#T?VqV{GRSWEU>zY!<)1C9Iu=SP0MrdNBIzYeoOuN)SJdK`qLH%z5K>= zFPnkTz?UpqZ#eB+K^V7|PfcnNkW^c)-M%_^t{c{l)Q`fv@diomm6aM~qybgzijvJY zAhcz#qJj<8G;<7|?@XMmHuUG+_K))iRe`aJTh<~x>-)ON7(xDU<|S1HiuiyAM&Yi> zb_jwPm58t;Kn(P8kuc<1@N@eDgC&DNYJ?bVM?t;S4|O!A(~Rt(Y={k1o>fzRiiz%9 zm?dB`s!cRB^2=QsX^=Te0fw^)*L6WoWEXIRNd1nWFc9Yuo|r_b-b%OFIVf_=F@blAf-?}(Sx0cysVwt5X@{RG!I*JeP6?GP(NHeMMmTU~6|DJW zPLATRTmn{c4dpYk-oR*DCHm}J*ur0jw4z8VP+FD7XP@P{LlTzvw4eR7|6>itA*F^5 z&Llx&x5dT9RxsOMk?~@a>e*wV)^d>D|LHd}KgV*d=;~elnAhk?Fk1JXr>(nIhRI*GrB9+8*aaFHf2`qrmYu=nPY#SGNN?F9G22 z6Z@Yj-0|_Text+PfllW=nD5#?EAz)Lz~Vzr<*E9QF#n0dk4-2+QB*MmZoe50Q3dsXV^4gFAzO?2tc3I_1*76crF{l5b4qeiwdQ9 zmMuKvghE?b;@W~(zSgi86G;B~C97NiFm?Zm5ZOFIU&ipyOCNQz8QcNN_}ETK>1WOw zKfQ05U6|Wz^5_WjdD>3XWm-=+tB2vzsW!ZLkt{O#1i~bktzZ)UXArwvYI0Ozj0aPd z-hqazAbkg8{onYp-gX)^e*>8nkEs(rR&!N`8jA6<|K3VI`&r?;t$6D!Pb(Fb=sZnf zvxnx`JSNchp%ui3KV%zr`obiz-`0aD9vJC0!r8g33yvt~s*R~aB^y7kc!AmW|IlAB zaQ#217tF9f%l$@4NFS@2(CJXOt{c&8q845%1${>8t0()O>CPvqRy%ZyFku=4E;jY*z&NsF*NiVN(V5V#BgB1vAn-JsxdoE?KWK zS+Up8dJcmQK&`O4;>_j?VM-`cCIoYmjhlr&@!N1*X#q=#YnVEKn4pLoXeqYoP~lu>68Gkd!&XXjP(nH@lq8Ti7~VfG3_hL zWYp_&uCROFkLvFe=kHG^D4@Snjuyj4EdaPzbhvoNBQ2O?Zk*{8pXlt!3}px2d1loAOJ7OKIh~60zx%U-Ppcj zfCuP&`Sa@SW(3d9c;*8bKWz+x?fvDH9_#*K=KYyD)dMjUOf^JZyvbMp*NrTL?Oaz!{Z&&c-x^6X?;{2%Tmr>b3SIBlJsKPe42idZcv^9RuPcl?rTt^c_VdZJ9e&ynwls0`6rOUI%95_Oz*9LL43&Qyu zsyE+#7vx_wHHfDD+>gR?5yt=DnF}wIbO`={`PQI5<(7#G(&Arl;nTZVh^El)>*d3s zIdoC<8t&?M zaWwL%?~W#rl<>|f0`bFzH^YaEsUX7HbAR;_uLk1(c`AB)dw=`(4VzL}*QP;?dUAeV z*BHD+O+(ihN|9n`EH&S;<^YAIxwfHxp}ve-=g-&PW>)6spP7u3Mia*SXM?y^odF?} zTEDvW3Y%+AV6l54t+nE{T7!~Ow^aCJW@cz488#j(F*GZ}Qnwp6RYD%g0{yk%IiuSh zj|By(P{NcaM@RIcZl6CNuXSb%^WUog^-WFbc#$S5@#<^7J^8J} z>c^m&Oqrf>G8=`wNtQAPG1kSpa2c2ywG>~%3F zK+z!?i=}^ToI|?GdD$Y$W|VrjHL1Hr?0K5&Np8E%F2^<^AE()34zi8n zhcW_g^RYrh!(`M?z=C+&8&I7HCGHAGNqApa4v5LWGtdNn<^sgTlv7!S-9QBuc(NH; zOxmwjgFON7Tx0S+ma91o-g+=>t;xPB_dw;%e8?dsI19r%s^}6T!QZ~pi9A8s%W^le z+U$owBc%`X)fjM13E9u5d20feLO}=^DQ`;gKk#1LN_0*fe40a40qx#5xXUXbJ+a=F zeuWYQhxxU``^<<8U1RTpc&tX}8xEVXu9@^F-rg)b`d*}qPq=}^#Vgxn)qZ#&*}!?o zz2hPiWLNbZUK#npuB5x`>>pcM3c!cBJ7EmuT>DS_zRFOb{a0s)HHW8M*kSXDfJ&h6 zTO;rcEGBQ>CHWei(7*x-DeR1w1C{)*Hv5OJp-?!Ju-qKODtqg|oy76@`!BvU`CqGE zM*CV02FI3T$EriX*AX_5fFLLS8u3?J(O?Wj4~ZQfe8j$JMtn7X2|BT_e~1}={xLjO+GF$LVq(}I&Ly7BDv;l{;K2p6>Cc5l z)!x}8j>xW_|9()13)_uB1z6uH$VxPli52!!3#;vrIB!bm=WK^5aMO#$z4+EMxrhto zd?RM+Mxxs8tBp?r>B_tU0>$cb=Fhcv^E)atcBIzPJU0VnJz15oatr3g>+(dutn4MQ zof>N758EZlu0~7V1}6~Xne8hp1+0Sb7Ngpy!-+FI6Xd*E?^|c~5sE^86~LPS{{Y_O zrnL@V*u4dJi`(%cNE?e|TLZH&!Qkzx)`K!kGX8&zIRW$y}VFZWF}$WnV$`ek!^OJkcas`aNz^k&S!{4&E6{ z-@WnzDSKI72c;lkYtF*Ykm8C3pWJXn?}t^Sao<%6y^rQ}wO)TLsiRSeLkhmP&Y9+f zuqz59(7~PQJHK03rClk((My2^q5P%=3wi=tp`b)U1vj+?VLLa(z+O|o+Zk9IGgx-y|IYT*j;*^gSM zY*ID&g4$E$c8F*;B(nW9;U6m6eqZ zYv(QNB@73A>q#wXUli6&ugxZ1NU=2(F6ff1rJ&qmTJwy=^D# z*fBlLnb9BX5+FQ@2P;D1PR^zW2M57D z<{xdhpGd1@MwW_sn6HS6pw{n$h5n=B)0Lf3WPzFPiSjmF>_XkH?pi;UiDF4n1BA?T z1TSxg!M}H<3@#BZ-%^@WFGblFr3}uF6d;zT)2h}nuF95{vNjZTg%0%*2h53}vE(qR z;xj=pRKt=83Jx59-mY5%nZ67JsxgYFIpP4K>f&4YusqpfPGk=2j}eTGmoL)qyO|Q$ z=tvQ95V|fx2HxQ$oAx*KU#xe3^%u*LRlB6OHV-x}*mzuplgRr3Uj-#LIZnm=)*=Q) z#1Dg`)`$@!yNPQ{>q8%0=rQLriD^7yP^hPw%b{i+gqUMc$$c&Q*-Hl?T~i_fX=XX! zedW~>Ot_lqn|}i4x=Rt^>HWAq>_N(3BP*_}^V%bQov;qF(~~EO8f$uc|FBk*hf05) zve{|7c>M4|?@wLu%xf95cmiRJTbD``M{DbnAKn7%o+s@yzY4X=8;P-hQ?RSG|2wmt z_}={ZM-j<$-y)vMdh0D)^?Nvx^2?_afe{JJxbqzdUjw+o%c}GW<&$pLlC<{Y0 zj$UVXajO^oj?1;D^?ew~2OL0R`n_gNCUrC5Y*Z(*nVZi1WeV}O`+5WTHKhGOi?U4oJ7gAbbZfAqCPYvfHR z6paHV#rqb!u8A6f`^~A`wjgld3^f;9H{aQ& zI{70J2?~Y!>#>@sY~62Yrm9U%gGi8&!>peF^FKhnipme-wY+L14#QOrJ~yiwag zu@f1sQH*)D`T{tMw?zZs5y*(8VjmM)n7V#hIkb^+*?V<=&`X5x3KIe3X7dn!>e2_+ zX#BA@o>49;y}G(`Toyz?0QhlpcgC*-cm-k0;m<;emYyb13^_9hl^BWk>B9-t-rpqP zSWz5~(|A&yJE&rXj8pk}O6As1kwIg>bc-pXLBjmxYEKBEz zl|KT{)wK4{cEb&BnS`Qr3ZSE-mUcs}5fHnuOOUr9H;<&~{N0M}P1mitgaoi2q!+tAy#v1{n;*ed1@f-+zRUV*>a;s#DI@O)T|v2vOdS^kd;iN|D{q96L+Lu z0&4F;@s|3BjYqA-5gL}{o*{Y4_Z-iH++vJhBhaYAxuR2SG2h`J9)&s?PL(_fRPKF` zrM=V-u|vEdEgG=m8m}S`M<4u@=$VB$0P!6}v%x5qrYC{#l>n%}%&WTRs7i>(l4@>6XzLnVcw zM1vUE3SbNc!68UT2g|AbOD|4?7H2IAAq*c%9>LZ&rI)z9@&3MJq>i{*B~w4XZ`KGG zUq08~{55q>_`G=f*6{c5;{Cruu0_+Su8gTeG0Ng*a2N;}{h(UlwzirSQimQU>6AD^ z-F(z^Uxu@+BdU_q<4g4C{7W`k?NNA0EgP;LjuA2fk{pH^3nP!B@^q>N_w?H@WmVHY ze!^N{MEvjFY5L1AV~P8vUS(Ne6nAU(!_5yrzS0K$oI}#T-`QfS>~)p*GbFiFgSU?6wnZ#9vW+wOf%{ za`F7TzNQ^?@df(73~x&rfP1}r8Mt9k{@s`%URY-b<7=NsaAur>rtg@N#x>bs=Wqt` zZavC34HRqJMStJyaBcPfiwVdg~ms84;(&kf|SF7mK5h6*OJ!^^-k9U!7N?FGyr`#FEl1+alta zOZ-vohfVn`N=@ay6Sx|7@s_U|&SBq)W5}P4m317}<=v}+ci89l^su_q_pw=>y&l4F zY4Iv6;&^J_5xmFr4|Dhj{3H*oT2J73%v|lzWU+$u6hA$r+D@F$L~qOUuTCC96f(m* zK&)H5^hHWS986(9tY8?|0~G_F6;WK_gPSgiEEY=Z@=8U#Ttqd(PehO9{#P*yz2&A8 zaVe;bL>{Nm5iKqVF}6rSEhm32?EAIwgSl%$*ydUarGgcF@&r#7kEjD`@ZY zVFn*_OCQ%|>*w%?`#;{-k^m7kydpR1yRJ5Nlx5m~w_AKOr>U*X#0B1uDVdEg8J4FQ zXReCHYSp6@al;WFv2C=>V)={lyep5nIoRfO(Qf^M{~*`^+ag&hI4?kN zc=_?lH4W0ap=20(!+k8ZrMlLe*Iv$PWbb&A#%bpE84Dp~nm;UjG?PqnO{}R;W9Yf? zi;A5d3*yEOzW1zR1*?x{%PD@(R9pM>J5!JCyRMjC_XUm=SF3HgAIZFIwOp{E*8_dWL&JBCW57aQc&y5h$CzVP1B z(dC_wwb~bx*aPW%`P3q}5hhu3&opHcy_1hvTucaEq8M+X z>au}ZM#E1odU!kzmoB6`9rMlwCS?X&Rm6{R4$LX03)g9~-L0AKAC{y=VVCslz*g*w zSA-+@rgqCZUuKi^*Bznnb9p_Co*yzkV-a~g`U+rVdV!CxQ|%&tgLjbuJ&2K zc;FM`j8EzdOds@Bvpu7M7ph<*Z42$5uq<4kJ%!JF*Nv2O?BCejZl|F*IyE? z2EWY+iahZ(8jhEkr~)4WRU0XRfY73(dXd2dk}Q^{VVKDmQr6lB#fvN}EwJkh#KyT+ z=*fzO+dNJB>04>`@$KxMreb-TRL_SHHw*CZAHJBEG6#;CWoh;C2~;-G^PIz)B8kk->(Ts){ZKY>oD7PDZ7^@QtK;kqtcuCnkL97hu3$gqB+ zAk0_6RHqUY=|I^XKmz%uadARI}{OaQRiX)-+i@-(T)qaNkiq zpHT(hODnzO78x$q3xXZ2)|FNmOT}=W&g2bu#swDKYqgrZE4^&cw(Tl>xZep-P!8)s zVJZ-ELRG~-a+BruK>dg;`Qm#Iix}vD0DR~9{$mC&?=Z=yUY8n0ws7oimLve@LHRN6 zpwtMf??MO@$V1@>hast(BEvZ);3K@pr5%W}eKo=AOyZJB1KAX-)#XVmN@mx0BSh^a z{aK%p4)37J+Y7n5GgW#@bnb!l_ZI<%TQ%}u;Q=^L*F~-#yY%Hf%P$Xw;XTgR66|ui z^-Pc2yg3bQF_Z>qJ*EHz_pK?SjeSbOApd*YAT;FyV^tHD@dyt;B+J`f=hT2i^ItyiSC)sZqsWDv|NIOE zsrCxSD@~~}o*Y8M4AOz**X1&?2Qqy})siG}fe6t&Wp5m0WOPE|*#t0~N%QQ{VpYzU zUGgF%;o|WC)X$Ay^WKF5m}Ho82&GO6f7}s=h_5TY)C08`?*f>_@lBiH^VA7-!~KxJ z3CjL3zHY#(wSsx4um^P_8ubwn19!q+ilI0KuWgp~LClY5^{ddjD(aXpr3x2u#e>ZO zJWb*ahf=BJ?JpWm97f($3x*QOwHGJ_+*TG~Q7LTRL9wZ<#hI;qnVpFxHXdpiQ@gnJ zG3Zf25g8AOs|b@#%q@*MF6etNBDL7Goukls^&G*$(K(feZL5tVP!A`|z;D#VF*!%H zR`+tamLrMaTX2d$#Jlf;{mdiI5>=t;0d}03dEL>m@YdT5`m>f_35|cH@yw@r2%#AS z5<%SWH|Uk%d%lb9d-~NFcA&%Aacfq2-3j^?fFRRvJ4g0N3V` zv)`eo<$U6IE82P4()m1k?*D|=n3ZK1_2JZzIq zPcp-lxZea}pHj~+3l;6S>;oM9iOtPXm+MdT{x286^nww%cR68Z!C)4{pCj+jY>?dO z_cZ%{L27A9;Kt3XBZ3SE?cG4^EzXO84^P6HujI&H6MakZDMt`e)P1y+?E1qp9g`!u z&#r+hBFMCh%k#4#Eu!N>z+3Ne;FylinT=704KZ5?50R;>)fNvPYHAZl0QNu_BWO^U z2}&V+GwsS+qA@I6fJ#K4V7;Y9NH2-GZ17nV)T@6n@1GV&w`NBBCN{8n_Qw60XX2vB zK0GfpwJGox^iJmE1E~}TnwG@?X|_+gp|B?+RHK;j;Q^V{=bUf5WtAc|%}R(oN|WVx z#rp2Gn>(!8U2Uy`rR8QSf8cNHL$=?g-`cKQGQQNnCj&upkQ}%Rc(Oc9c|_03(WTjAEW{TITT1_C^ZVBHxu@e`hzt|)v$2Zk0oCg zUej(Ph#nrma7S2!&kAD(k9aZI*f!?(gt0X8WL1>zdN=;eT72%U`4#7@hMd{iEvrb7 zs(<3-j#6W~jV(u%X6o^4^xT)nkCZea!*A(0h~|j|mq|W0>FV6EOA%-G#xf!8>g!BN zbvNg0WEhN?jP9o(fiw$%AW&t{=J868Ec9n8E-q9Ki{c9c*YdyWst1Ms5 z=e}Z3XmDQje#3Tmb@c&(#|}`8gp7prxBbSb_7RM#T5GVM`zCUk>+kOmd$>UlI8Chf zDXgxpE-u~$y^H1Paf4xCJj){pC?cM2#j8{q{+K;><1}o&1jVM)q@Vy1+%-Xzb+udY)Z?KC4`E0mZoNu9sTYRUE3w`lNJXdd>mkV(es1w7G{mv%9 z-E+Lq3p-C9nlp}8QBIR3#ptatXz>^!6yQQHxIU8Wc=F;l8W)HmeO82AUthC%CYsuG zcAA6Vj{(%#MvfQo{9vD})WLx8g%XFC7dntA>3jh6QxFaA-2i8uzL)t_4BewDB6nM$ zI2E)w`P0(UQvK!Fo)eTlx}w1eo%QI)u=LEg2&>It8I62 zU_RbfoC0tJj;2B8f){AU?0Xh&?6XBj<++>b{`xg{RUl|<@JQjld$%ux zYU+y4){=yJj{NxeFSwkwZE3Y$g(ZoUA=jhBo^Je3FZVUHD9_1v)JtbF-JdUXo(DuL zjT%^*y1^K;k2ShXVYRw!7vG6X2bCtIvy)sjja8*L1dLBz_Rp(-WH^N*W(8!r#XA;M zTWiWve>0mPeLu82)t#Y2vMEd}m5Q6WwGR6!y4&;L%zy_xRa($XW8}eni>j-U+?_4&Pahe&@TFFKAC3Vy|1R&< zi!4#lRU{C2URi@tgreEl+k1mhc{T{kfx26`c@X*qvAT;F>tIz2@M+%53m3VriN?gn z#)BhA3lh01Re{`si`o~&enB6M&by^fnEr=yD%hS3h_<)>v*B2FTl%neKidRC`JgF@ z(ZuG*+@N4uW0XsY=ZR;Tc}K(thu04u9Nmfb-oDYiZCiYA!Iue3yIv(`TsAndYzOS^ zXti{}&v(|=M4c}8VwaEhhKHF^g`cajVV$DQH{PE~>{qCrr$ZN>6B@*2;^MSY1T@Md z`{RpADivUvVU|e`u)|Dc>y{phF+SOlcQzXVVoH%0&5p@@zzY$tlOIUn# z)g7{syY_Xqbuy*QvMoA0HPF-RGf_S3PO{Wx(~G7Vsbw1p7N^Pj{3C2R`d6Nkd@BN~ zs3|d$6G*`T_D--*g{h)n(#2k$Iw3gKR76^~uO6Zup9f4dz5i(Z=e3YzbnUdvgS? zb|po{y{6aBTZ16fd_JB1q^a+GzBNP$`M6;q-hs21F7jnl)NfNik2+z*pUmXep#BE; z?j>p_gI#VvVc7{-Y4wWC}Q7LiE>c0!fR(L5KLC}_ipfk~bRVe>G=SNdpZn=~De6h;JEWpFX{KE2}61Dnn*Y2#s1A}XZ(UGP}nzIfbL z>wHnwqlJ${2}1(VoaXUat-=wxL7(YNqxv5`TOLS+?-FQaaXfw!BH2Lk+L>>GY?bnQ zdZ^56g12~#uKaI|n|kxJn#fIm{{`~y+0WmYbh9nCa0&2l4r9HMBmoN|qF!)NPa4kZ zFUzFw4!nVXvf!}XX~YM(6m^KEe+Tu2-+g(As$(mT(|?t`jB8y1Hd!~v=y=S!V~gxF zL8Q+|++Z!C#n}TB?Z`)d?XtTk9VHv1qJ{J-F?J~=vHja<>P0~+<-`3wnqyw%>b@(u z-u|Uog8muoi&G6?*7QFYYLNATFZE@ICwppq5R8JU=a-45T zg8@lYLyTX=sse|hZ$mByM}fNRg7WNP&f8T_)AF4Xd=f%VtzFmj^mMUGHenyz-`Ejv zR7nwLG&+DBgI>*Y`9N>7?tPv-I_jz0U>Zus5(jdhfqde+btEi|{&u0ENTj-GwwC=% zn3@?rc?nA3h}?Z8s+IM>3lp7B+rUxd6Q(fdu4NYvUF`mqJ+~k0*#tgQS6+Ja@SfiL zj`qebxO7A;R$-1rTXmd5D4QTX7x@X$RlHAfNUOdzU8c-BCF|-|=%A=OS=vF0fNH=J zUlWc?{@pp&G9ZW?ne77&U}E#uqTxEuYWVkGEbAK#`?D6J;Z>twm{n+Pb>7#bxXi>c z5BKMC-37Ah5rXDH;-jsfl{Ngn?(c_?J{vr4SQ1;=gpiVK_+J`hUl18DH*?Qd zwSiPykS==zb{-_;RCaPMBYV9n4O+8Uw)^Tj{Im1g+FGpwRZ%Rq60Z+qNtWLZZow}h)9EXf zKet+t*m6`nqaSXDb@Cj!J~zzp>})#JW5-{NhB}M5B2gzk^v^qBKaOC(rBoS1))O5x z^SS=FIOO^>5|U%pJfFD?WAw^kek%IZ)#x#SjL8@G#vfWEfOV8)Y z(`+Mq7#We+`y0KcxX#@_?416Eg!q6aiw(~OclUlkH#Oc6F4b{IWvV1JyvqeKe3y&Brw%h}G&MhBDC9dq85S)pBMY zrqkZ?JE9`S5Pmo({9q1MMvKBv3RqgoTu}c`jy8qFoMMS;?@mx66=WRF7JmY}VVN>I%k8)?xz_PFmIyem|i%t$p%1qG(62N2sJq~z6A(gTBtvM;z^OFHTw2;tCoOx& zHa$`=oY;6Vl?FP_$A}}BG9Ng$Dr4j1T+J{$-B&H~b;+efv^ZbqDBkmmC!yi0%YpP! z`BeQ^(HRpe!DFVcY)fOec&&e-dv^VJ3sB4ZPfv$i3#JpksT`Wq7Q^|aCPJtz75RgD zFq_iB=At{&v>3e>c&CnS@a1ooCr!LOc~7B~M9xFw=NFyjXgJX?!B;z;Z3Iw;f(VxZ zbBc+xbJ};yE<&`aG<@N=6rT6{OkEC(GYfM%zbd)^`M?}tyG3wE@GelDAevnDR5N-scGdp>g5Qc~z&N2nq?|d;*Ct*ra z=bw8FM`s>h-rlUTBkJ?j%GibMHaAeS7}}`W)(bha@*nMcr+eo% z4ToK!`i|dvesU@Rg#-)|_)-!SjDXvZ_V)Ib4X63zYq(cU;w;tZUTC^|f)XMMOn1`i z=|h9Kju)%_x|mJ7@FV>@)mLU zl(0qphU@az*|W%^IALo^2qIZB@9B{UC92OwBTe!OeQq8fAK57$i{#>_!H|lro7E}7jYmoy(fMYfF4UDC4<+rqtk} zK#TK%(VzoKHT9+pSzg;rk%~cdx)}O6a6>Q55B6xCCOZQY7n-M253Xc?I&aQ{B}gp7 zjZw4uzo(1mVSS6YW)U(3EmPaVSF6^Wq))BJfwCd`A>-Kb4Mwf8AS_G=Fuq|e-E+pEJ@l|?hGGO6K6y#0VX*T4JhG+K{?u$`x zblSiMeSt#k%|=5q(~BKnzRIdyZ90aLV~l9KWTw|L$2Zi;A?MpZwxwLK8vAU1w?2XN z5d++|(T?GhBd2Rvqk>I17Mn2aeA=9!UvG36N9JNzW~x3#kq-}4d=JG=CG znznn>_n2$GY@c^Ylmp>@UxSw>dAF4HYEi9~=GmiFNnVwff0Xq2&%5z-F}>V#Pp~LqA)MTx9&qQsjH3+aQU6m?P)rrSf!d0U-)2A|) zT8k#A7Jg4MYLcghy)?3@d091A>2x^s`KS4W!c-pQmPjGZ!!U?!=Ky2qN9)Jh=J8dA zwIcbK-+_x0T$xDG}dX&OOUHD@>02`si4yCqFgy ztOHpQ#)DJRimV;>Kd<#Vj#D3`ljf|yXGlZB!SmYo)HdvFB{@lcs6$%&@! zWwXulUNO#(DY+qt+iaIqSi@K9b$A-F$bgY@2 z;DoOOoJ<)AjEhU+?GfC`y~D*shvBVOx_@9brjC`OG^vz6-Bgd`QnSHd;kl?O*Wu?K zUmz3Faa#`#e5uXYe*@cGT5Q8>WQ`nW?Qrm$X2$BlT@|OnMY&nK2n0SjH?eD6W=K&J zJOTbsw-n4e7C~e3#6GUFj_fb?^n-ta8Y!I)bS^Oc<*&refHK||nYMOL>N*^6?&`2tHe|;6+=_t zM$^<1J2r%*G1F3Q;aTi`(GU?Ytt)r->EY{XIDeF&{d(X_{h6OBeE)Fr*&`6EI}D-I z5H+n)pXDlrTeV9@G2B-TzV00+JZk8c(F`eH5o!r!LaxcsA!MYa)baedU)D$)#2K=_S3La zUy&U#ne#19nVWjJY0>6TGBY@#YN&%1o#q`hwlPEe=ue6KezpVPJ(*3QkSa6 zjXYVoz4zbjzU8mu>~xKv<#l$RS*TGprTI7Vh)qCuuyvTrRJs`X>NF1Xzs^BO8kMZA$Dem| zh|%>=IJg!08(upP!^QfRR_~Uzvb-E&R<9?>+^BqcRVO3$IVf#k?P`|Ai90$*&oiTp zzk`-~<&erl@Rd9YR5dFvIHPvmwWi>zNbTU8#7FJgv=nQNw{jA`CukiwwTHc0NhVsa z@z5$hm3fKnwyVn0cU#03TxAJA>*%bFTB4H1=(bwgA)z1`jP|{R$J4j8wIxCI-YrZe zfci92lSJw`4R}Vp_S|SlCI#F0sPHrg_mADAA(PlKuyw0N<$mAeg#kSTpF*@X)o$wN zm=`<;S(D3zyxvA)uvgaXsY6}8txNJ;^ z(ahJfj8T`YZIx10s#qzS;ZZje{Q@CJYSwAuJk+}J@?>JBSLm_4lXiw86%Xab+Q?BugtlT4sQ1^UME26!9Y7~L^CE8e$VEX+0KnI>C` zQqzReX=zlSM=vKgvekynET-s8TQ{<$_hh)D>LH>B2L%HKTbsrRrb<}HCmVfWN}07U zq9I%fMpqGlE%`_R(E{VgC^nwl2xE)aZVATRo1rbYJop?bxkH2F8* z4?FqHJO&w&{m9y{Y%>9-THeliZ}Ig&~6%HQ0bC*xc4uuUg-aWoW>7Qnjs; zNL>^{L^(s%f%&!)xzVE!LBCL0%d)5U*)tQI@AxoT)ZS4W%I$*!8ajH@d$t97c+VQo zq;MpKG^C7enNGTHMnCLV7D!P_ii}N@wsG~Iw-sUor_GEw zwSgbf`8pW@(TDCzdLO4ww**`d#%FrEIk&30WwfDo{SE_ zXp{`Po&dgmczF0rbo8Rtx6jzcL5>K45HqW4adlC%v-y4>9-PMli#h#IvJXjou)%&) zOz^x0WDha5mhp~Eez?y;qZ4{j1R3X*9)9QuSChc0 z<6;N;6$;wGglEm}AyAf_K?Z+~reJcFFBBplV4z=T1PwBJE_HnTLw^K|V$^L$#`q1s z!)p1SBwPnI(Nc*oPj*JebVi^hq|A&G8>^#-)Z+mr_a*}#2W{yEoCM>x-uonZE$Z@^ z0-=G{J!3_!=E1j>+v*S0gPNtYR8S%;TeA^E(fYRt2(XYCT%6BZlj+38_?ryk(2Ye;uKjTVB5 zSCMcnU#MTGUt^g2f}Vb&j?$7jO45oTqojq!#U*jzxvG?6nL6Vj#{YN$UWBFYNiHwT zgd5S|^4qVA)84YeQ9rlT?5}8Wi+6n~&Wf&GLyXMukym~~$WJ$psikJ-&@m}RX}u+K zWE|Ue;>r|ij=TXegApKz^0!kNeIok^kCHLN1i2fC_l=U1M@(jAUan`?Ap85I8k-*N zM;y&Rho?zus9}NdQYKJ53i05pY-I1>ItvJRkcC2tNKO$0(A~3qZ+6?^A~e+v=ZRjn zkJMz-@quv`kSMJim;YRNfGIy1Vh@6xaYnhv`Gh1uP%lqRfMx`ZFOiYNukjGp01R9P zgfKsR7?bB+E})GRI_;+hSn#&K4b-5w?T`0IKn>1*TqkV5x@>H31;OMouRpKy7;IMB zo{0H%b&i1Hy|J;efEE4X4PcKaKMC7A?_LZ>QV-59e@8z2DG^ryfCBsAV)o?3N*633 z7`2W$*6(8Q@VFy=t@D1zFWB)5xK6xrfo#rUhI|lJc*+~2JMLa~ZZta%^p(d6 zqoH(HdeG?DIuk#(WCYl}pL`!-?~%~*i~HWJ3}>5Yfzf`v+H`5M@f~@stv7PQUyYx! zV~SgPQaCjEhi8+ky?%Z(XCe3Dd2R=DHH|Ai%{n!z=)w(<98o2GtLh19`q03AWiV*6}Abo8Y!o|-y*MU11Vx^;PeW~Rn^(Y+(^H%e71g4;kGEnsDCk7kaE+#Z~t z*MGYMocH#PC_xG^*#yX3tHp1JX_l3o#%Rml|Cax+u=`p>gd*Z+8^Ec+U5$XW(3k%$IbvVO_qR7LImjlOG-#XUisQ(L zBD{~p0s>p!%OVwz_u_fR7fzvpEwBI4Otatoz@xhhbGrF0wK?Q})%UlO-NlJp_MzgM zJJ98TUV#jmgU>B%Z8AN|K%~Fjk!f$x?IPx9L5fd6e|r&Gxy&Vc!{2Awqg-vLx3lbM zY!yz^JV<@^;E4rn(CP4-Bt&#n;Y6sRBO)Zns(MO_Hg+@S4+p8nrj|oE0%{%v=~!UZ zu4Anv5W>uUGd~mkpVNUtme4ieHgiu}NieCqGz5{rcr#gXp>s|$xd=h`Mbq?^ZQPo# zBD4R6tr{2nqRPF&6@9sSd_!;&X69t!pGh*~b0tm&F)Ab)SM*s$X?lXb1MNHCkVLLp zU#zcTmJKUNSrou`>{r^ZHjPhG3#DijHuXAmH6FLYI!lvkyx3%~@dtR3_jy`nMYpRzqD<=f&KwZB-p}Ns{!8L-cLbCkeqbxL?nbf0jb+ADr_U8qV|{t z-+*uUAbc_16@(52*IX2&Ct$sCuEb( z=dCV*Nbll$o0fR9s6SPzv$5kQ^c#Hj#I>6xpk%WP+??4yoWO5vyjXnTgc$W%m`AFx z?Irt^FJDT?*QI6M%evVH2yVp}D-S%zA?9mfCSEX`y0ghqXQSRGLPcY6B29jQBZ~X_ zrOx#4?+j+Gtg#pohk}GuVww{nq#r+ znL188!k+i--J+#!^@t1L^7Da9%>#!of_sO-RO=^M89~k?0-oUO!sJ?$x!{QnIP;FU zA{7E+dA^KOkEt(1`wr%xzu{4yycHnH#Gpom7$DquW4&Kf>>;z<=#7jZVExKh9b{le z37vzY0|^+hHOF6htl_{@vS4OGz0|81q_A z)c)v^)xG85eU`og+#aMy;IsdPz^1uvq<#E0&Qjml98Dpte8$yfVgR125w6Th3rS3@ zO33(P^W6T$YZICo<5qPf;pc6Kn*-=pmyb7_#Ys-ifSZhtN&1eBM8$JJKP~7$b$gNx28-XX7EQ;ygJk7QPh-p_SSf0~zxqX=)}W!e+5nm;rA{QVto&aAV#XHZlI z3X$kE521l`k)py&vW6lYn~y^(JPc2S#B07-Ngo;xq#<%+hT^z^5eqd!3M`PL_LZLs zoT5dSA%4m~CL`h4!RFpP+!w9zNsDU#o|&v?%d^XElyPpo<>e4Vv4ty|Uk0=g%AkxCtO+86GZ_KV|^^YNzDnP}~>#w2(iEP)|-z zuyObFh}+s$y^gQAM}8jN2Xg^+AizPR`?}AB`s~U23YAOUb#qmQUncAwL`d0?jX-7L2V`v_a*1VB3M#o{z*TfOrR$a`@%z(pv%V$=Cs?K?d9Qfgtao@^YsK|dQnQn`esLLf`~2TH&@W>rNIa5TrCchtfJIB zOp12_v4ZG|NhYfD<3#hXUi^&|hujSz5>f~_9gq3`Ub*U?9oN}S)VT+?PDIQAw%SlNHD%dJqwjxX{RaD=YAYnh8Dh=ShI7pI;b$q6Rjn}gq=)6jh|)2#>N5% zVsbjZ*E&LtwIKnkAyM$8CXJsdPz7~jz8m~da~2~sidWU`67n;RTN)Ou09YLSOx z`~7=92jzgypx}n7DSPF66xfQbq@#TGlFdJG=Y7HsfPeN=Er3t^BQUwa{V$>L(xbIZ zz2b?*WL=V94NTZi3n#$;I5aPV7IWkkpId7PD9O4X1@s9})3UH}0!D6IVD*N${9U^4 zCAD>OanS|4EMU_mn79KR)6)_kM=N_S*s>N(3bygBvun`d_SjDy{oiv{*we=En0>3m zfM+q#&dN;zaw(XkY|O(#7pjUza1G?WUi$6Va>ZziCNo|bX1Z&Ip473}U!ot^9_Nbw zWm*i1Lr~#tf1Egch<!l;gIWZ+Tnravil4))z`0R3$8tl|?(9Mjn3NlPAB+Sc`Sn6SUa!w_?47gz}HpU!w zn9?=vlV3s9Ic-n%0@mF`iDu-!Es#rh^b05=z{}?KC?F%m$M@6-*4ZhhT;8*B!kvyw zN-x^aZffdcRZn1xofG?h{PWPYlgdVpBi3(=AKd748<^2G2in~erC}K|_Jfsf9nU!0 zII3A>hily0rbCQCTLenb5=Q>gu0pZ*;lj^!UcsXKp(;X(|FunW@Dr=ly)3C@qlbO#CH+{>@q$A{L}Bu4_T%BJ7dN&V_||%cbp&al z$&ddclC8b6h3Mb$m?2&Z^YYRUrKHDiZvwGVR(tXI_?VUuTWx+B`L&)_yuou-b?eZU z8_U1qGj$2>T|P<*=1Z3@jZ?cq&K6uGk-r96zi58oov<}OYV&T_{&DVW-MTlP+fKm8 zaEK&D7w-&4I8_}wZWuSDlzQo2SIdrD60f}1E(Nh7qqJBE!t+=N0Qtn+(z33^OeNPF zDTj4hBp!RAo&Uv^v6WEfO@0r&bqwwEl{Ac7>!BiIg7G5SkkXdUF^D)cE^t>XLkaa* zg7DK~|Ej4HUiX@vN$+T3{%qr{8y#y50*#@*)i|6AEow`s3%!*~KNk(^)TA|i9XjOqN*;ti387+kjcUA6=il|uI@4T-{OXm;h{9m7RD>;moh^zq1Tw+vw6uW*9|M8| zZqIPm?ELcdOY8XS)+s4FM~RZ*rH*qT!Tv!OF?gWzOpP`pS6}Tm5f&D9p?`>oTFo7F zVkc5c4&i!h`vx_VfF_Fu;dp&+PIt;$W*99>{ByRC0Gj^dYhTHblQIVfhnw%)pP|V5 z@H>j3y3N0QcE+!Mx8jLfFYRdmn7&(V@Gva|ogsBBu=vGqtV5B$5A$PK&){0j@&j0r^E9{Cmc-{5xYn)}L(vgm#axW8nJMSFjZo5=n)KRbG**%b(3zu+V=F!{SBqS%qa5}ZWam>9$S7!@gB zN|=I%fJfN!G(+C-&&3>}c#D2yfpe*?xx`bmZ_&GPV?@h$sgy}<#DPtkoqmw>~Nf3yxznZ6ZL8pB<3I^<37b1#~ zn?6%`DFYdnljoWXqjO^D3cfqGGe4BdWg;i6l>nQA-+tgCKy5geXIN+$S_BWZKQUyb zObO(iZ9-48u?1gaJ(tgAfQ!fS;4AIiX+@0%!8k6>Gd$6Wn4Y2{Ln_CAyjDcL2&+qi zTsjG9N)n8Ad}K&nexe=w+IvCRx?#x4;qSYRBpysnwFpF^j43^DurZy@PsWfqFj_q> zsIu8XXo|CgONa&DSmU+IXhy_df3=`1uA`eG4mhyX%+Fm7oHWYJ27(ZL8_zj21Lvx|*qlVo;Sh#`&rn|nQa0hpSAbs2s z#x%#`jLn2BZmE6LwTpb1O$EQ?8y(EYswt`~0GT@h&rQqQdw z-nK%br-{(S6$xYfsbjTZ(1JXX@0ppSxfi>!t#G1$#7iPc53l(gp$SsKM$fVe6oAV6 zMI$pS%Ch)-v!Dt>g#-*tIfDM=d^^y<7DnFLJ$X*f{vtjVTRQ6_j$4I-1RFY25Gt?m z`oFzWMo1y>2T5GWHGS6_N0=c}v^0hFAf8{c{R;oclQ{$L-!GwjvJysR9EUX<{90Q2 z9ikkrEAzOIqjuaZebD`>R3WD`UER0J(<5*z$gks6(=&g%6u}h491lmaDuKS6 z$T2U7t5(io&?I(prs|~5RQ$DI9?EU@OkGqT_>2l;WS~L>h+@#bC_iK?7YOm?&{h?u z_M7qg8jMLVcybgwk?f-TN$x`jo;=Y6#sin;hB@Z zp*ttj(i?L+BRcs85=k6ca65~kJ{}a3hcC*6n1*+7%%)DjnMb|)jx*c+Z2)LCEKm0T zkdcB!1alCG7&hj_*f?@FIQsGtsZ8Bj8l3VPBRZpJ1}#kO;q+V~2rst}`yF{8WMb&yF;y@tM`%QpN+jQ(H*j1vUXM zaA7p}G!0UE4`R&N&0@~pgc?LwPEz9Kprhxu>VRuhOTafqIU)|mZSBzeB$h{u0}ZMJ zUOx~BI9y%*IoSI_Oa51FBEv-2__>V)xm<~ zl-ogf5h&s6<9nxxO7Y$%RL23i3fC=Wd@z zV*wB?9X|D0FpDLl$K7blA3H+5r~m-#Gjk>??=pfm>HCpl35+7G$nFeEy9w2GS}lK; zfF_=yTEkNoDDmT;v}!#fQsx51_hEIuJxba?{xgShm4N3W&MB zs;}*V8;6*vMEH$|Ypea0E-e)8kvE6CtE=vw=4TEgCQ_7lMic}}o3(t~KlP?mOEqD*Imi%c=^<_MapAc6fSqi{&uBrN_@%e%T% zEzn4}<*HJzDw`zr@n9Ab@w1Bqqnl$v96qk|VM!Eb5A_ApQN|-XlWBqSiv6^n*y~7YMQ$xV@kE#9m62;&(HX{WE z1rl6`dtuL;=i*d#EX;AoXIWVSA}%T_a7r-iZ(q3N3=2X+644yfUlXhBZ~y!!irDnO zLd)~;{Ji#eS0`IT$-MS^KY|?b<;S>YaIik$tk3oga>@&ldZ>AI`ct&~u4O;Aw72`_ zFp_Da`@AQw?5YC3+8_FUy*?KlCS5?v0Kp>pX!I0%0v)xtNr62Fz9Z5xG%*hCTu!;8 zKSg&%i1iX21J}KBShb|vCsNiY3nVKxSHJ+gwDhw;B=OD*h}P(hZ^qz*TwEowjJ#|D z-mC5UAApg7M|r$+-fc6MAU=2ys47L(rKtMMui|TSy-O(~17hGlT6EuY6om5uzc1Zs z&tubZ_aFai2hLW2*PWc0h{()%cUQoV?wC$)-4Q;c?H6~daxPSQaJt%TSAmqt@4d}KDOMb0o)u3|VHMy?$#Y|p0Ueo)c+4>*?NcpE`EYYd?s`r9n z1Ts{gqz#R!H{NcK=>Vt5B9IQHMdIVfcdj(?dA2>MQ3aqC>Z=*ju%FpQ^bH+WirtB!wbNU(p>j(w!b%U0s2Q;Ihu8AO{Br zA74tcj5GkCss6#w$b$gKtS+4DEvIr{sGGp7_z`DmLe&*6!u>Nt{nM}eG@jfG%Rog2oV^!2sBK&+l>c!(# z-xI5<-!y&11%&YjFQ-y0L08?rI{!Y$3$#Nj?89mL_pgg!dqM+TL2RSnxHfjuRwKyC z^;T-t7}nlQJBXczw`)e-Zay{Gt0{dq9L`?M|EReTb}3j~bj>s|`h(7z|3%Kf;L?P9 zT#6p_7^(01Rzu8~x*8=U*BVJ%`I6DECpOSTfqh|Yd+48U-p{xT5o?oc?ZreY3o{SXTA6K+>Au?mAJm%x?e#)o4tJ(l{#!t|TsiZx2~_k`{@#8}7%Q zNa+)zXk0MlGU}jWz^-eJGY)^4_QVbb-GcQ%Vg;s`zkv4L>5u52Bgc4uGutlmcz1?* z>;C^MxIFu^hb$p877b-)mQ(E^tACr1bbmONE*|PO+AO29w?I1VBF`h`s~BM*#0h@h z?fnC-Y|`C+`-7#nwzd!ja<%jRFF<$*w7Pw2C7!E>!WhDViT-GJclY362>>>)uK3KW zK?u|qG+Pqtx~+XxD}!VRI9mWo0o>Suv;=05|D;IcN>}FR=a+#T6v_MRETcgY>CYvGH=|Miy&e4mju%U~wyf7z4%%{O*!cQMCVBWNf zxjF`IZ(BWK8<5vlP34_w$6iuzD=E~qL-OwpHwTVbAx!%kzrynll54sQ{TQe#=eq*{F$H(UhE=wLkuZNgTlfnL@-Gh?2t4~W0xkPb=9+$mIH#iCwG|h#jv`MS5cfY` zfO#a5rk%So_8l;P|J;Z5XRmCxtg@>xc`#RTL=y2;fOWYR^&~eWd58zBG12$G$Q%Yr zYN^=<(wE7p;tyeo=2PP6W@-^OmCy!gtuj0#`;XVk7~L3bq)RQ|KYv5~&m@yIYr93n zx1Sg16qB#T#>FDzPW+m$9M7nMQ=K$FP-z^nNZ7nsl=T~9LzTT<&HA;(u2*VBr;Hzy zG+Can<*U6x3nD9$9vVrQNMg~##XtfjR6sTwjbLwUDl0<=&CwlC^GiSoJOHc@+7S@C ztOH6fukRTz1n@te$(PW$JzQ@;ap#M(eQt!0+{b_dz&|%rec+ZEJ$yzOfIG;iA=^7k`|$63!bt= zI{u!bFF8mHSmkm^5~NzReSb7>>@@tw_ksnF0o@q3O(~5A-I$WHdq2eNuWx6>(Nw>= z4FA>14y6AyS$>H}Geg*tErGg@Zgjxo{S@>R2EneAg&w)^+P5q zgtKEKqEqaIp&QxR#VD?LZI0|3WKeuQ30F``m}xY|=e9m^BZ@}$_U3!^f;ez7jt=X8 zM!Nn2`wFS}p$ig-Biij{d1Ou1DJ-Y8rEpfcwPe*KazY93m^z%&CH(6mD5W9U2V-wY zwt7y5Y-=>{e8AvV*K=n)x7E{<8ZkPuwNR>)t!l_ZdxMnn`Q$_oo*)kzB_w2a-?SX> zSzxFBsT@npW`@F9`qR++7+y6jX<`PjCq&_llL|E|WCSutjk#3r&8|-srYh1(A+Ipb zPKVgR>H(ywnWKNU%Repv%jo-vP170@74G}|2|&C510=$!s{4s(pL&q70|ZrAUdbX@ z=6b@O=jWR?T1u%@Th6j&k8Ph_v$dWpcYg(rDi)oln7k5zR-f3vcp4&i_?&*4^1W^J zU2L$_(9_Ev+FEG!bY1JztoQ|rv~&OCoL_RD{q*EYX;1^qn6i=2mLM1m6qOaPvymr= zCsqhG5yoG@13u|{LB9xw^uYP|#USPBsjsb@cv~^Pd?>g-S4ClDlz;p0h+5gY0>MCK zqTz&+zM#hdhgDS&yJ6<7H0I{VL-}{#PuX)b5f!9F8TP?tG8T&zCPuNy5Gjz;1EQM3$8 zv!SAE5#UPyw7u#Y~DH)z&6?&23$ir35k4s*55uTx5w9-w3ya7v$nUpdj#aC z;Njs-wjD`A!veXHi%M3Rd$;v}06{ z4}6nu^&gW8Q)?VWK5*m%wC;{n(uMHRt&bjGrkRC54I(mc}o7jG)%tmG-2N`0Or9w+au+0Z!5hSNcOg)n7WsHJXFq zYiJ01etG$KvGGG(0XXri#TCc}`3qMxueqFg)y(g4ge>yGuMU65{HX%XA=1rmbpH1e zQUM$Kgrkjma6(33_j}1|jgK|qvw3M)d7ZQK1!!|-T8>UjfBrB@{8PIB&_xeaK7&<~ z)liuQ{BX?c7cNBK-uvAt+(YYTjIXl}8|_;SdM8a^U-S6YK(5j83JiAzr$67chuw;ag% z9SZXD{B`hPaZ9>tY9@8_pjJle~6?$sil^;=ouw+GEklr13jcL9(bYya%;aYZL!=0yE;D zM*Wh_g94UU6z{j}5h+oW-YW)EilI?b_SSgN@s(q$SdgxNU1@q*{_xm1Jy?Zyvs4*Pv+(7F)=Ty=I45`z(e;L%=8hyJ z)893X&m-&uU+)~)LMU;}tgXEdYWe^w0=Z+$A@(ZEVH32sJOJhW52)#Q(qNxE#{uHx z129Ki0bfjTa4?8@>45{e{UN0-H~77KR#jOUe6>M$a8lCvZ1UV}Xv_{z>-nTCa8i1M zV4GJj6)fyyK;+nVM#Jb% z<<#%XXw|~qLQN8n8W-9r)-M)Hg@hOyK!lRhj_uuMyw~{6zUbpUo%AZr{OEhdcJOv= zTG}j_a-@cwxgqk8dJQ^k2A{rSlH?|YoLX1^37O1-$JHcoku2$xQ>^eY5w-6aM4rkTIvM+0BIuz~k1W~>r)C#fj#n}7nGx{WsMsjiI^x8?-|y}0%-EFEaocl*Bo z4(1z=`eVOsNJe8|oRbNAaA!OY6B1Y?9FN%_wBM)0$3R{7e~que{(P3iePk8(rMG^) z*cpHfOfjm8igtfeO_P$6Dz)m6Ishg>18jmHKYraD^x4;55deVK#H|B=(@9nZxg3Mb@>e-NXeM?{vAow(G8EvMJB?o|bGj$g(SDNZY+{_9sJOX{fHs+wY`^ zrXY=;C&c32>Wy;s5)E}KD{ReCwR>i+yWe3CFs05fnyBPbxe9A)IN^mKRX;d!K&mHx z2|CPOx;ITI4J!x9A;9Z{bg2vS0Tv%ww|ih`Nj{XpmCi#=xp&t|A=9G2ZHdKlaOlljZvxfLg&7rJ*Uou{yM>*Thj&0?CIX^L|N;4KUx+i5ge>EDcMD9D~`+KssYQ~t0 z6T^rL2r4QH3Q>%53PdKPuv(RQ0*RXK9R(y-40vLF2UVU9{=sMiL&AD_41b6IU6~}D z7|Jjl=*ybHuU{=HONcsom~c?ME@m`J$KI=#R#uMcm(;bJCgY*ZAiMnYGw5WnwhuE% zL|`Mt2zY?fe4UM_y@F$43k>sPc!$Hm0L6vF6@Rw%bB$%H`W)XF1uBILXJ}^7wU!e5 zex6+Vk>bL!Xs0vRdinRV#T365g2m`9PEVeO=%YTvoh*TlTv&X3AJ)kdmCf;Iwzt-} z$!?FLJJz;cQui}lJT$}*|DFg1r0$Mk48cG|#ClsBg>%JkNOlO2Y8GuZwZtVEc^rhQ z*<0YTHFmnPX;RuK*&JSL|C-0bAY6gKcs~C!r$G(w0HUF?fy`SX)YhMrZfaEixz}*y zRVv?8CaL@04^a%jiQg?ezUDr5+@{+fW z`H4N&*4@^rxXy2siICy0mR(n7JW&$l3~MxdW!HsiC8l{QYm^jOC6XssC0#pFDc`JI z`aU)W48OO+Q%FS<%t7YJD{H!A8r($o>zZZi?n-O~ccHKP1sx+)D5Om-mA=Q_} zaiM^xw_n(LT#s|EJy!l<`IT2y?SnN}P@c3j2|1L3HB;C`#wgD-p0|EBrBtQZK_^%R zI+G&zjGmWsl^=ymN}DQPz&X_~HGu3_N6!UQLSE^OzfBFS^Y~w%4kcxfB?B9!n1A@8(q^$lO+Y`Kg;Vd6A3jo9R$xF};q zIbq7CmCK{Az6{s6v-D}<%C3*3dv+ftlTnK#+f%|A@xo)n_Kypq{4EG@)R&4Qb9`p# zKGa0OjVnf3Xx*fvv9fyhTj4a9%Q=sevzmwWNLtn=qBP)U3I40k$RHy(edoy+1&`+6 z=~(C&X}{jV`9lK}^(~!pJC2idXNrhfau`i>_iNVZ$Vym@ zx&}CY5KV&b1e+iG^P!0m>?h+6n<08N{h|cuG((-CofZwfhy7BVB3&>XOR~OF^6IXK zv098^`1;9qd)AySF^=ysCMnL&e(HKHW2EiKaVR-O5fZrWWPWj!hfV_0FUG9`{Q*`+ zegtE5&(2Pvt@97zjZlT|hcd!yc)R8i4oT!kBhCP&is)E7&ZhAY6w<$9EY42YE>7_u z4XMHksnUNY^=Yz@G1Ak;H5Hq>J^S9`WgPvI3A|`BH#kbkJu8|MKH&=kamTOHZX~|+ zsIj9Nd%ng?h;dV|ilb7BfEyeQ4?1uxt#E7}*%J5s`sZZQJHoE57bIAHJHK22jw z2y_WuB>s%BjQ)Jiu7~Sa!TeE3UqIbh)RF7V@81dnh(v)0GdI0mT4?-3$}jD7hzJhQ}g$)&1tS_jV2Ql zlZ=cE8@RNA0lMi|rly7q$Hv7GK_+MtGPWBuipKBQO9oXQRfM>!N^(a!eg>DAO6xoU za;cf^RL%~$g4sX{6>g_X)k3gu6OL`;{z{^$LR1(MxKsJ-7=LEyI(#t%8*tcLi?Ip*NV?J14&$5j~O6V7i)G#Sux+;V4>oG7%`C3S20*7-5 zLxkwpTeS-6c#(8gbNphyW0oWwM)sr057P#MfS;)TO53>7xb3VU?EYAvVy) z4XMd6arCh{hu-i+4a?SS+3Ez849jF5Tr9{3Y$7%)CDv%MrqU_d2L$>)mp*we5AMMV zVtkK}E^Qj0(2Acc4(Y3u@G5hJia~v#S)*&nNlByMKB5a{MQ;9yrIwWX^#TUuCKqR7 zvmdplj`*@mY<&Ww|@Nwg$3Eqa3A2GH+zRhagdlLPx7dwx#Ja_p9-1$>>WyLXLj7HiH9k zem*r$=<9-+XAP|Kmr^ty&keY0GJcL~9VmtwwA;S=p1hG$xl3a{CfBr+Trcv{gKrkM zk0Bza1qo24e&|#xMWz~R8o#_b?Bn>o=4q0+I?nXhf*XB@#&yWAsYsp+^5(}?0y<13 z&}4pn-7us(wv$d;6mx#v{RJcxrbS`zfBJi@%(sFEWLljE6byk29`8Tcc|aI1Ya6G z(lO|`CL4MjUAS&MGBo@QOBgi0#jHjwr(IoL!3t+m{u6Fw`QPq<%zS;s*DxChQE+dq ze!2LKsNW{7@8r@cgvuxkTB6ikX=^H0dF%w4M=mb2eW~j5zw@JWM)xKNi+h|&E+vDm zX!73<8)942A8mOiMIVc5H{TOjyQW3VEp8 zU9{lk&qg(NXbx^&%~w>Hq3VT=Pte6{3>*&W%cZBH`1mEFTeHU9hgH@G(w`b>Y0)4( zR$lb?_xCzNbG9Y@5lqly6B8+HM|6=kyhY4b;)7;JD`soFrcO`zdTaWy@s(rs%;(4G z9`Kz=x_?;^7kJ>M${}-uVSc>Js%mt6T<7R+m7ridTBjjfejG+}9Pj(<$1+K&pwxzyTHu{K7kA|m#I7J8F^9*fZ!T}su6|0z_;iylzR^RC*-!FyZ5lY zn*lxm3kwV6_fX*018u#Ow~X_VI`1PN4{v4Ia30|^>Nrl&s6?@c(kv?rDfrKZkuRma zE?_`c4-hc%yLz;6``$g8(UuKDMTYD8?3lD?5iz99V~P5PPVDMwwa?Fes%OX7r8n}i zS3hQC=&;HnS~|C=S6CfK5QygaJ@?2N43=q|o;9aPx!V+p-R@b|rL5QDe?U#t@p*lG zqyr+Bk!$u*JM_E=etbi_;EoMqIuRz)=cIcNNVPfn5xAxFmG9kF)T@H+yvzO(lKP!~ z^pT32KswFJugSIUx`!xd7kNL8YEX1f4C^aXOxq~7aKq#Jv8fa`gN+~|eD>$pL416h z?v3*G^Zk|=7=SB)&7=mD-4dB_4JEfe)Swg>KCllXTp=;JS^yj*P>zHKBIYm7lS1#1 zdZwnA3!%iFS;qj7t37#Av&3d-Wb_4+q+vh=FCci9P^0e5lfnMM!DfhGJv)=TSGd-f z`sB~Ap?d)+(md)VFA}`L4bW4rrm8vsXeT^d(tvqtbxEFY*8mi|)0ZmD!^4BJk*o%< zt*ya>C7w9|)8yLvdJtHNX^FFh;xv^m6eC?})Gr4zCKC@@^BI^PHnctz>t3)JW%@BS zC2`0;RcSq-EyZ))yj|Z*=VcgC zt_&b$xI73Tf3spM3AyUz?A-VMtY0_fX>G~_-Y&p)8zLSZt?H?nQoP+Bu;Y=Y+peTY z=I!cvrf<=1zFGb=tZmq;Xv7G7(_?!t<@c2wDDCfy`uP=KseLi!a0my@)R042Syz}! zO7DvhSt5?w@E8MBbXpGp;>p2s70v~u(mA74!frv}?>zkd8#*MgEdVHUtq=Hjb(wzK zE%0ok2o-8sth6&x#nP*@2><;g-24NXcTpAcU=F2gy z%B+W+KvMmHF7VM&c~>z}(Vdwu!ka0Xcb}FLPc#R?&#xWtE{3O|9ILLb29jr^;GL70 zb1x>l*n#LVwUw(gebhU>3N9h0%gg7=mX3_BIP6Wz{HK2Mxt`y3%xS5YEwYgPm--3{ zQ^YaM($Ztv1*C$7WExt3N*BdAWZ!IR>5{NO3(-!C zRcD}I^h#<$_ZN3GN6J(VU*pms&Ofm<3s+M?Mlq1#xjHydpZ++By|Cxlzk|rCN7r;* zh_g2$F!)yrrMXy9?%DbKn4ZInm!@(Vg`-2ixPtFQp92$RWE^H4KKp-K0Aqg;JpiJ} zXIN>P%Nvkl}TIQsLV&4Ue)5!^T;#Asun`O z-1umtDEp&H{Vo97g?6TdTpZ{s=xvVFn)bx~m_`0_MF~Ol`s}KJL?h@ zkF-1F-X@hNSfA#3%l(ex9sey(vqXEh=zx68#N;e9Q`3hH^y$j%MunI$+6_a zir$^xEkYq!wf?%E!#9+zor6WVJ4x_-UU%Kx{WM^Nz?Jd;-m<2=aW{lOjOCfPkiiE7 zdgn=R&K{Qc62`YnOG{DyIkbIWNdr^w|2zhB0edCHxY(g6O<4#QzW&EY*HG6xms2BK zDszShH>A3J!Al~KHRJF$7eD{Qrt)HO1PD~HXuNOJ@W+O|1e?*TSFaF_W^SX0Xm<+h zZ;y^5w~n}D&@E~voyDdh-SaD?J)$}ep3eCd`P?tcpys4#Tfu+s>beW)F+uKumxr{8xvL5oA-E;UuRv1C)$?}#OaA#{E4EfDk@q(?Y<$PB3S3gBB2)N zBlN+!FhLVY4&x5^WU7~?o?5J|E#TRzqJP(diB~fvrQ2RV_P%s(<2=@G=Wg%^y>AE*~_5%ng15@aoSvErP=Vw2C((F*Jg>1_oCzPubJ zZrP%f^xSvw(^HAZp(!AYpWgWfkoQOEYAe1(#Uu=_2b?Uv?&&Wrg{Ze<$m!=~`&QML zapyNQ3($^@0bp>vJF9lV@lXWbj5alsKHC$rkrj1r^HMHTwZ+zj>gjcm&kDMuSd7xL zGV6bH#Ds*O>I$!><#Hm44!=LYx)4Txfr8lPN~l<8O7jXMgou&-{e+n4*c;J#$Q4$t zHphCYUTk9x4gI8j%@o0iIZpUZ@|Xg_z#bQ4xeHML@s+fZO}?NxEGeyi`}S?pK(blI zyLI82yR3Ni)0uN$PkpJHJOon>5q_t9D-DOCIz8&W*W@%~N9Fi`qTwT`%bypKZD1}1 z7c^mcG23wcoOnoyHtNMPLKv&qvByzCIsQYSeM`N{ppqdL4X2V0LHu|EiFAuuk1hrX9>>E(2iOgz zjA``yJ&Mx^G!nca1K?GcG+GEi(QOeCki^`A+ZF;GAVsvw_$j25f}D~TUS!W%!8Uk{ zn_EJ#p$Y}Q8PXGdEqm6tzq?gPPu-^1K+afrgwu1wSMsseB>a#$@@5)t0_bzn0EFnk2u`Z{fp{IrED+x#;1#ZYLaEAegzS$%Ppg`|k-HCRlbZ5g*&3}5R$09o zo1bq60SJr$z~=rO9|v1(Jl26cM^7DvzP0so@#vnfirWCL?q!yPvUW$q)E$;KG&St^ zKBhm%f{bF9Yqy8Pe)b$NJaE%R(NvJzQf%wDccXk9M3JYja~GRoGs`7WK0VaTjkhGBQAX_NlC_3~bkxmF{3jot>T4Dk=vtSb6z# z&^74X?15dZqG9(dfn>o!Pbjg}FV8Ppi)2l#RCdd>rj+|9u7MkekM#XSkRb(wMLf^rK0&R3O#YpUX zsYQHFJ7Nbh0+rQ;<*pbIoNZ)3KTaKU>OXFYybl^+ z@W&qAz+y|d_#N7uJ#_JDK{J+>9Xr&9g_@q077trcgq$9ah>$SV(-U%kCHHD|x_rMp z;Wtc)vn*Z?g>lceNuxhstTs#FREj& zMkJz@%*DRdSn77o|H-c3c07%@q}Cw-k}e-xoP!LZHLWFm-32#ff3vJ2KHdC$YCPiY zTgcA3PRL75;N#;%MyI9{4|2^X)$=<(F+)k*5x{8bZbp>M6l4U`Pd({t5M41g_}Mtv z=ZEMPLPxi`MnETICiXpX&5n{LIFb=Tv)0{bWu!>5PaKRSG+=ogpQL{F5-Z7PQb^qO zGqrxQhs|EeezEkt4XHqAYW3$>TciJI!mS3fR5Gb~L*LtiT&M4@IUR*A2al3u%=UZ!2%>YgFvWvum4`Bz3bO*Cridd}FTyK?oH zyP~~G_kOYZ7#T;uj>nB&hNq&hnwM(i9&EiCzAN&HbGyo41}qFw_WsUD8dFm(y;k|z-e9U=x?Rg7x|{$O^m;Qi zGfUs1&@JI~OG~WeRrL5t{;CjhNo2ug86l9Xj3F1PtA^r(2ip-hRnv&9z!R zIhYIQ0+h42!$OxKW;C8(ZHj&RR*;e!cTcB{cQB@O&8^eOgo_8tqi38H%MQ1??uWDS z^SkMG)$p2tzC%|xAJ+l_yO%WqI*_{@wAUz_$Rk47V$$nAXp`lC%aT$^#3c1>=^fK| z=`fZlTdWn#(|EypFSd`qdx_yRgNg4i1qDSK*P@|e@+}^oC*t&_n(lWHEkxTG2sSN$ z!^<>M4s2)r+n;~q*%kj0V5Bg)2W%&AHN8 z5EKU3FqJln>6SdwzQOVMHZ?(M5}b_z$r(iPGNmC6U%yJ;K+rQ{%m(8ih+k*FmY7TL zZkN~%RG@fz%KV^0j>+n6OGttRk@APZipB_*O-st)@xAlXg6C5odTb1W{=?rMN(>nBV7ljiTdWE{!uOGPKeMq8JYHG+7^$Qk{bJ< zYHyz4pFe+s(jz{e?2`c~lN-9j#++_(a*`+rQWK>0ugOPH>Hg8?^vG=oh z3)Mi;o$G7sK)dAG4RvF0yk-zNz>dbXs#q`>c>%jH0RcRSebWUsanJPrGKP z_C4V;xenIH#+8*8MtqE|{0AZ3A@}X=2d^#}5EXt#60hWPSlOnvRZZ~#!CPCOj)(qC z^)N41HN{7p-Rlk*ZHgw0-S4Rk3M2EPD6htvZhGo3ihum_1y+gv74|9tHoMaB_g~-1 z(cG0|^VQe$A?2PyLH9UMs>S4QAc z&}F zI;}_|-$Ib}MHia-!zd@9|}RGQx#=+MocWRsBWcQ4 zE0TLAHdC2OhCHmpR`i4i$eGTabnXcwy8Bp(i@!c9P)yH#@dB+$Db5s-UMD&_0I00S z+%#YDS?6i8bIaMF?YpOygnbnjLwqR0@>+3-7qQoNPnM_=B>4~M0}8G^&o7<6+-}7P zgO4S5H0mze(dH*2cP%+eEy=I~NS_$yW>%e}1!EcB;Jry3P18uTNGE^kFG(5CQW1oC z0wXCv(!89UzB>^1)vztp^!f?2wwYPrxam`rDAAwzrRP#^0IB0lWl@gt6?$=T@u<|# zv__w);GV%WHo77QdY6`c{@|-CsixQOMRj+zIgQu^1W2IsLE)#KyY}E}ES5-Kzh>@7 zhN~X=?YGY8^iIJx^+h_s)o2urYuFkH9@(<~^o|ii6v30u9s`XilmqL@nRhgEoN_FwY&`lbm?V0f{RN_ zOQSbe|EjU(Zu$hMTs;{kTke)>k`tdO3wt}mRovm?eDy^B@X5vX&W9ZAvJ38QenzP} zL1-5!>jElr2j!Z03bQ^a;Hz*N|IP)#r#R0TB_ezq3zarE-P%J(Se~_?)s0VL0IPy2LjPatiHA=l6oP%A4cU!>fZtZ^X+A zMU6eig!dVrLCJ1Ho<*!^2=oS`rAYsaOchRF>%Tke@EEf*QrVuqG=Pgd>KfiqU3;Xl zj}w_!lpC50^$y(-2AA1&i_t%TW;#l+zb`I+!)dvcoD{|`iHW>M)hqB3F@8);_(FX~TEAWW^m8Cj01;3@ zuEQ%KjDAJlvR5$G^8tH;%0E$l(N5iFJ_9bA_^(sKN!o+FvZ_IZqG|{T=9u%}s*qRR z5WnL@K=xQK(LE^0T=qpxUELgR!jljgZ~j-gRBbJGwkAZ6H8jd>mPvWvqZL~XNf=wQ zF(&@YC_rBzhoPk>sgku7@+{x>+ffE9uT=K_j)>V0vSXP^A9EL6oGA`io@49CS5(Tr zqwQ7}S+Z!^!(;x)S)p`o)My#pG55fH1&bpZs(BIq*7TE;-l*V;nVgYPDj6FeKR*YZ ze%aXa0RocnJ_C#{b+Lb6mINCI=dqJhtuGOIgy1iUsncB(I%@XR4hC4|hn;0uEM<<; zyKPlVNHiLBb`2RdM$=6BC=xlX9=WZ24xE}I=+UgwM}X*{b54${hPs?dN0Bk&HV22& z-V04m4o=na$zq}w+yJ4i4|k4m(UF35`E1p426rn)2gq{twRLk_TNFD`^>98Nqu0)# zk!fX!igu|qc*~Mp=AbXcj{YIOjh3AIIC!ks+gZMOJ|&9tvoa0+L+P$?mGi|H6c%ae zPktZr{xCp*n*dc&8N!&Dl!QitnbXj44qxou)kK}q*WlnZ==FL0cni{r$TIgKkGRIT z9AW{xk;rp64U~1>b8(P^yjRDm@X)WPZ#}e{o}Tv1YF(pWF$wope}wkS+6#5&-1uo( z+i-%q+J18R0R=*p@|W;`1TIW;Kv8UJ`WhfZv<(kpJNVQv*tM^O34d#IcDA;?ihA0H z)j~kWPiKU|%uh2Iq^c7pU6c~%l=Jw^@FO>}orWR8I=O3kV`t~+{66=)WrR#TYx6w) z&|x?6e(p^fW$XlBXRE3^k2>xS$K~KFahowkV@H<-qLE$MM!X$!dF8znb$brbMo3}O z#rvj0BCd)6LS6Fm&j>_R`5t_y`nxk-55^~Xjz9iQkg3^+ME*X%gxW+KA0_D*v8*cb ztf+8oB208%WV|;69-A7;(PPfP7BBB5D~&qCq7+AOaL9Z3+htP6-=m;#m-Ss*o(oF` zDM9g;a#_x2B<9LoM1*SfLT&+>*uvhd1M0mi$QaUm_lhCy3*YPZ4;~7IS(HC)5C?p8 zvzRHuPafrdE*dc8O^%LUzCqm6ljI`ymQ^M9jTH`WBQAs;4s5*&G9(~IT1e-2cSovP zxkvmK##bhlT{g7J`&RN<<{T~M-VL6XzAOg3e{%CuEvTm(j4FWGA=@r~DM_Ef7s?rt zdsc~sPw6~WTT)rM4}dJ{4oFC$n1^ryz_A{?x`O?112F7_BMt$r6UaPk{e1y`i*xV? zg{_~WVhR0Y-U!8MjaKAT>p>7HZF#ibrX(p}$SrQ#S4m56V#9^f&e)pblq7k-i?z|T zrd)rOUmg}ur(}OEw}XpK;?eJg6RWZ>!!J}{YuZuxGV+El#+-1-o^mJ$4^O?r znuyz}uwrRp%D2I4u|O!APGwl<$G3=oFsfNY<+H&{`p=DS`8*&Y!3yRd6B4g77qC@P zQY15YcV|@4YfoP)+t>dD~}!B^xqto3@`$NLwrKXb6zr(Z^cnVY?Kqo!n zK^UR5{P(e`u`{$08JF+NcwfgysmHxzagt<2Ai5Oh(|4F&=*lB=NNQ8BnVMpUpikYt zoq(Z$z|Cm1iLhj80aC^7+bNqSk;Q@4U1XZEvGLch&k(-kFATUIjtMXH#Ya)J;>G^p z@Gvv?YFOwnH=Gm~ZP98Im$;y#y)TX>@geZi4#tHAI$GYM4DI({5ik}xk@rVNxX;GXJ_POA~pocpGNS zAsr8f=VyeWFgd=%_3KLWWIBAV9b_}SInh#Oo$LgP5=UanVS3F7fB&;LXILwZl5ZJt zORahk7HIkI?7sy#H*+qtdz`35R@eKs|E8db07xeP9v@+-*hBx` z((JQ#`F?qMDR)^}G=j)>E#;R5(>v&~@803GwEhmPK*;Rlw0ze|v|Ht%BkOKo($(Iw zByu-oOINUB3OjQ5`X=%s=4X3*$3YNLCf#}_)g_j!}vAye9PdCn{uO-mF&5(AWU?<&%CwPHygDE5i+K{WZfzaa@9R z$Ge#Wpv}r!zX)t4-VeD|?PPH9M5FlZH8B;MGRdS=9EHV;+}B3owhAgCn7&PR-yibm zUD)~Zc3hQy;Prq00;M$)(vO$FOIQ||P=C=c-b>Clcs}N<%M~BDvc4k!iBv;j?G8N= zMp#e{RU*3^6PulsfIzJOgE@yBPv++ULcWS;UoKFbwdwte&OrU^)eIh@>U7Z3Yw#Y? zk<9Sc=1R~34kHFf|hFUsJJ=tM1+h@OgL|we@cxik$!b$E~YGA@p8NB7dKxV>1QLMl2HBP5lC8$y8Njx zo>BevZ&KAR8{ZPG&K&^(^dmtnzaqiQ3=uwMjUgVMvW+ckrs=#0I^izm$z|+R9^)l7 zL8)bhnL;`4LEA{?JL12z>TK`W1X0MD^wY>YM<2M;>+@fhH6p4o9K=7R*-pyHbl0yt zN)!@URvFH?)^{zV4Yu;1SP~iRRI4_dA-MXU_o3N^HF|D-aFl(?SZ(%_yMRGI+@1}8 zD}hy+Z0h+VdZmrU{R)=j(*Nk)9^^ig&AwB!k*KqFL(*4fk5nN+5$>7XXdhU|HkTgc zm6$gTM=txzmT)L-P}^|U64VyDzEha`=OkSEne)Jm`#Bf3C3DG)V7v{t_E6{MaWfw6 zYm=lhj+=a64F0;;hOiByGfKN|Y>P8VOWzC*6%M#WR}M8l3`+58jk#>NJw7zS_Xh7)D5lC1U>VZ%SDAwC9pBSeJS6uf7l2FQ$n?@?B>54* zNZxx=SX?a5&%akQcts@>e`v8InAloPw!_Qip{J+LJYvf!q8zB9p-U>-bB<-vqIt&) zueLDvrFT_xuHOLpY>wPh-j2+BpSW+-HOG^(mbS{Z(GC=|E$qKs3OZQ`wrv}#IH zfMIyn7018H?E5DpOhogq*SOLbjj2?K$^}Cr-aeLZbc))@9AN?aJB9>DazN(=UJJoM zh`VQWyf}KPF-C)Hcq`c`IzGlZ6%+) z%{4RzI-~ZOBo)pE;zNcg@#~yVsYpGGGK8oWA9yam56CP(8;?p%8y|hZCiv`@d4~mc z|3~EAkWFOkYAzV)X}Sof~7}f*mhyU!WpTnEo7;LL?n#39}u5s<B9 zf80Fid0mC82$1RCC;N*4XhXFyA9PMl)jF4T76024yk zUMx;%V`55!;d_x_C~{o)|Fi&aoqH}~HT@K)aP3K!AH4fo`fPV*#Mt=Q!F?zvhl%X4 zK+8M=ThpWLZu|mViHHNpz_GZ6-cn*B^EhTHx?g_Vy3eCjyNkuo&o8j~<^-X%?_9r! zWQ!k`urKLVr69%4!xFqnUBAV3HpJqBfOw@qjkRwab;|u+Bf0K3Y9WXlq52x=OZXO- zR1Oc=uOq7ggi(9P_Z;SzIp5_dkbaOr#>P7A=#TgeKy(fCRWW@t$P0mbgeGZ#MAg&9 z&_08X3aq%!HNX<3&B0Yen_COXf4O_E#z?pksX(pz~r7R3iZbj}ONeun@7N@@ow zM%uY6@GHvb-Kt|fyp5W2qgIx<)h@k+@M2`n#|IC>8-zfhOA5~e&KpS&&PSj)Q8WCi4 z?qfD#%laQQkZ+zy+P3!fb|3{_n1S&E%ssnbh`2`gVML*bft>+_3u=PbzWWEG|^e z^Pe=ywQOxsJu{R2b8X2&!ZLuAgeF#8faEaGM>+Vr)2DdjRn9+DElzd=8Ac{1YBoE= z1!}Xdf1#KKa?LJKP3Pb}fl!NyeHf)rz@EOhv2i**e+32VXdt?Co2)Ji zFb+0$pWScUccyhdJI0<Km>*JGih2cJFAnI$FRGtN#9< zX|62rq~lEn^Zuic+JyOU1=F{z@)MmIYPzB}l%i68Ds8e+{Ax0@XxU&cI5DD~028ds zqFN7`Nb2NC@lFMKQ*Lp8?AITv$26Chq$42{9fsbts%xoI&(EL*zQ^bOeGFu^B~x!T z@7}_x5KdeNXI;oTV&78G85<$JK&)ofx<_@^_|3I-T;Y#^_Go)fLdm>4FCv@K$nP#P z8t3{40O@vjcR`F42sh7O^FJwMHCRz^&$zckV9K9zx95-h(?n77LbzkDS-_0G!UQd# zEOZ8sJibH4K|K)Ccb=?$FsxcaIX|KM(?Tc}6}k^WYeB0W7i^m0XmXg1z%=Zx6?!e!52;EG!-MT!~tO#!pvS zXG4YG3YrKOa3Za1y5el_3R<&EvpA9kBvy%CGk;vD97S`b;A6~2{3@qpAdx_hZTCcu z`pxgZiIxk0U(`FL{mX~|v&tcU>-dpVi8ZQx) zjCTfk#Y<|M#+^Qq4DP(KwBJ0nj{p?~IVI)pe6uStI+}78Yr;{W3Cf=};hbJ=<-#ub^qQKth!Z(R z(Kh+8d4G#83I zq5MHhWQob{LnH#y(N?LM#US>%sI~5@#K_C2)ck%|Fc#g+$U$!=D}0nd?_c$=zp@3P z)ejH}{XrDHEFKLg>`Ec43dl>~_9-o_;WbRg@qLY1+3`u0yx+|7 zgf$RRN+M_x#&|lkN1WM8;9pp=ZW^wM~^f&nB86$EB*O&c( zSR{fvRXSKl6NLdKn3slX0(?BYEdR|C=g5nO`O96f#y13Bo^Jy4ON&=~mlKvSx|C#%(YJ(VI=)$Gqi0}fs3+nBVfbFDJr!2iNZ z!m#Y6UqpI^rW&QemDI{q0WLFQF8nn)!3K#@G*MMA*=P6ClAlh(b4NDS=5C90TZC(L zFWI66N3NkEt2K&r%3s6j%$!hQl#GQ8S!c_&V!M`$TVbKEK_-+))b$!o2EiC-QFU{n zr$qea^_&3uXvt){VaBoRW&t`)&`v-&3io$lQ=^ULCp)=d(f(Y4|yH{>{=W$Ht%Y3D~5)D34$h9 z%p-xLo4cQ_Z}$p)NTv%A5cbIxT1v8=2)+}!iBz~l`hHE11Ko4tpKA02>AF}%27B6* zleAz=}a@ppwjZ%B9m!$K|p6oszO{A)cj9(vG6~s2(TYz_J}l=L;$^{?>>kT&j3|NSyYA4hCVd<)ULM5^V3vr zkXG+?C)HKe#U*5;*+}x0YeZ!M9RL{wB6EF;ME`)GRQ{YU*KyWe3nanJD&2I?Cq4v+Z0CyD&kPRR5i8O1*%0h!elv7 zc%wOfI{S`E*@B`v;DuS~G*$|XqRL*CCg*jM9pvM&)z+2s=i7+HIXT70{+NW1_qGvijJM9_9-A@UBTp`o+G36#=V|2Cq zv>Bu`kb$S&)CCx$ftAS>8QTX33I=Zmu1nDmG!;la|C4vWAcfM)@F2zm(Lr==sNiLUMV!ZZfX~$sByjMw=U2*;a=cA9qF;Zum zseJdp51M||K688!j!)5)_@K3#cOq?Zy00?%$LGsE+`n5lJk=$E#1)~(VIw+I3eNW5 zjT?xQ=fuchx3?41Ii&u+C;<1r()m`Yli~x;qfu^9RTMldZWUrTOb8uyx-Xq;N zqGEv`-8#__7{`dbU$|pUiIMHq+lgH2GEuy;$$AVgyu+($d27?jmOc8e6J26e_Sje% z`D{Ydo2d`YPzLm&oOj;-w&*26M@##&!u%o8G-QT>VP#~4mz(?RQUuR?Rqt=moI%7O z@dqf^0N4(|HCHQvC9zxb^Mlco#aC1xAARwJp*AWCf_z;gX=A>l7TbJ#T~}AWFR5^k z7#W?yOUP*;;|@pmGofH`9HIU%V(H~2B`O{>8eWI6N)$CVHiEwL#|oE6!E)}6q!RR1N*2)a6@f_n#5k=CDn zy8=}GRb4kQH1+k5VZB4m4v-TCDO%(CDhW`;=7gZ{GHOF5V^Lu)Hvc zw9F%y|4y^u7=K&OpbF6sK}LFtG%;Ea9_O(U1^PPgxYpWBeuWpCW~%y@Mn6r*R`5r0 z$uMbT5!Hp&t`q2KGl@*dSiSE(vPRPCH~9DIj>=*A5I$(=arm z3`cNN9)N>`CU|^{ftvaRo>tJW3yF;%`2Nayts!-~0(SsF9+#lIvsnk)`>G92PM=9z z)PN5uLwPr^67d_Z?dPtM`hcx;#pw0nTfj?AuE-GCOx~?z5)de>LRhI`Ud+%@+32Jft z7H6@&>H0lTm(X`*`b;^NWZW4lL1e%m);_}nI~b@t(1SG>6>)qYLg7IW3JR)L1R!M~ z&FmB)=s}x<(4^di8eTQeQY_gNNk326b4DG<%T1m__nU~A*xKqUs!|TPq(UK7tvvjD@U-af!8bmLl1m?Ljh6|xbCJ7HTSqz6AwyNH ze6Sy;$PPa#h(4k~YQG#=xS>%($NM;&)@8pW&xV3_uizItvRYkTO`>t1n3+)~kuxr=W-<472RBdjck>h&=Cx+1_JFKGnFp zQwzg#PXfnHNncHm{fK*~AZ)n-_W|m&!R-i9KOAFqTKDx5ZH$bJ;HaP}g;CeIoGaRe zR}wxp%6bSRJS3)$p2IxMK-2~Q{pj5Qe}Bm1^n}PlbN5y(+Q=w5t%TO?CFew(gdeqW z!oCR{(j2l)?hBqtc9KKm4&^bq%J(50P&7?Q3pn81yYd(fWy#%r8%hl`_nP(z85tQl zF^st_X%O=980BBHq|A^kB`(;(+ap%2i5+lR7>JY{9l2Dvu{A+nw9-wgMc&g7lXQHX ziI&zupYR~G4S~8m4@!n?0|FY(SlM+lIO2clTFZua1Ogu=ebP#t1Ak)0cn zn@3Gcd-gZz-(SEPVtT70<$7=@9m>*M4=qBcsq9M|ll!Q(LTQ|_Ry>nv?}Xi<^qBjv z>c@yMht6*&INqpuw}2WCc=cpkK!lO3ef!w75?>!rHSNxsohTa`cFP$W>brEeUmJ9~ zQV`G z$GGti{`U6vM&WiphKJ)<7Qj()34N%EtUY$%8>%aA#rV8kjnuC&YXXZQ4C3HdHT4=& z0Pktl`YDt^T>{dVumg2n1|Ibz3sCRW2xdu$mI@gj9)5kp|JT&xilg((aH4PPSpk5= z9>E0z%>{OwO@n-@oUFK9N|iuEgok%0!#%f@Rb zcuhK+5vEf?_ITE#<70G$Ve+cqTx+#0THpThZTcP0zbA5*i*M*RA|HuA10PN@{c{d$ z@}fM45ZO>432_gB41^u^8tN7Q`eq;)8h{}Hr>B$l!TEoK@5nWy)KK=A!L^MW!)41a%u?*yS``w!1*(?#zTTe@S`2wyme)kAi#7+xbi{aBurwmL`|c zZK{-kdb7Cr!FQdgx__AhnnP+dF~xYnN>N=Hi1L<58p2#oL?GQ>k8SH}h}P3Xy;tt9 zm&=3@xRymc&BT=Wf`-^BZ&s{X)|iAzSbI9EJ=C9Z(aNBT>ns=~Tav@fe z9`}t^w#BlE5hXo7JNpZxjWe~)K(=cZOo&+BYDKY#ecO1&{3P?B(wCxPD0W?W;nX8iuqNx^>qr_vdFeHliZ$2(%qWm*vLUB^ha1^TVY z%+223elte}S?3E59-R4PjZsi3cu$K$PU7tc(Tl+K6pGCOtIJ5r`JTgR-szA88I z7)ceEmjnMGHq}T&VjH1+{9-Dp-+^C{jiUHZ!2?NpBAmhB3=9kq>rorCdMdw`$&0K( z+{D9w8#1|F-!j4>N7AzRujc96f!65Xe?fzNb4ot98z%cdu}-p*e2kS5Z^9xk{*>gY zNBRNh(>!I2TZ!)_Z3kI7||6_GTr4hKM1;T7bHh>7vgtF+J*!-{;lVi}<9ZTN4Z15xM5ikMNEU zz#^s`7+2GcyMLcLmbPCY(jw@4ibdt__eeJzAut}fxVgpHskrkPU)_DSpxi$A`ju96 zEqS9hmoh6_wb4>&>b+wfYz9rdSTwi^wxnMNs|O!rXy$bzJJA;9L$L&~LrEz)y;5H$ zH(RrdOE5G_rkJzw7JnLHs+v43D;=l~eEV%pM~Jkr(MBf^)&bR-D+6+ijkl@dK&id` zzV!PPJM7wx<=>}PDY9gx>-(p-WlTqRiv`d%@!lhp5z>3KDfscNf$!0t&E>>(EeE@| zktE!Q_=hTR?|&MlTP(RwA^ig0y!ncAYvN|ved zE;ZH2&@d$-0RrmCBldna_%~76{8KF$KIt#hEql97^y^7T7jf-Pi_aC>!?;EDLs7xE z=0&;pGg)^*v5X>KA&|XPx3spl7E%Z0x zhn%*yHrXT{%&H!VAExVE;5oqv29j)JNa<$OxTD}Q#y8_DMPk)k(H2a5o*LafgSeR* zRL)Eh*m)ed-EJ4$mM_jp5I^h*SY-C=^$5Zg*b^Xpv24uP(9q$NF(LMSdI~oIvT*J4 ztc~Axf9_azKmXPwz)gQ|im3hI#n~=L)YWec1m~z@-o5LAg_KIZlr5;u2S%IE5D5x7 zvM?jUAbbQy`|!(Jg7%Zw*&mfz<8v%|DUs4w2gJ3gNc=E*X*&S9;gi6WDH3X}_V3L< zzj%~q^A;ukyuQUt+&yp=v7U`CS=@Q&y9J}%#fKpW7Q^l{!V`R4e8~%Zt4eqDkmf8a zfjBKra`ptr|E<4M32||xdkP155JDi`uh5sAqTfe zBh$Fi*8@&NFkgd%7-2D(bq{84iA-0>5$TG#siXvdT4|VDft*VPd#wK{A+Z28i zkcpTG$nb4giB}`QZb$J7+mr30j=*lfGK11M_qsvL3Mim6du&wI)xnf?pX!zNd-H&u zPcRqWJ6_nLr20QCz=U4o*)6dVWHdXPqxR@l}NK(qNLpM$}A_ zssD=a3a;Ew-@==33&*~air7Deu36L%nyHy!3L;W*89 z>KQ4{pcj4xBnObVV+k1+Iyxf|BO?XN0k{E1$HvfP?%!{R@2(#HRJO=ul;#?ww#6Sm zD*mgJ2B|re>{hbv&B1bsYCX2FumCs)BnSS$2;<}9!zhoU>i)q;n1P&e*lAH~Jf!H{ z1IaE35~Te9aC&OB_$?{yf0u%P^bfU#z%&jl3Iau#qbgltleRnB9D`J66r|@15Kmv< z1BAHm{sNHrXbaUyzG?740AU417_T4(36dI8ANX9HczpbXqN2g%50+k_tjthCa9>~q zA)ax_;m`S{8&oF1xkojx*52{%0^>NRIFRt z+S&@MheL#NjHBGO_s4AuzmI&;=-76;229h9Yi_mPvURF964G3nqiQRkBWfV}}Wmye)g zfaL!7^{Btt-gc&@9A;@_Ks{5ABZYCSMu1l3-Mqwgyn}$Rc@bi*5f%{U1C<8AI07%G ztdSu;1cfZnM9`N)>OKVl1LwnP{HRt3{v=iCm(Jeuk`UAOhoq72RnMP|0IYG`x^?UJ z?Z0sKQKoh<>Wn%a!BVaH;{;@(@A+}AbC&zZzI1PyYtCmr&lqIlyujs&Ps%N*ZAELU_y35T)7x=4xtcJ|gVR z5OrC1c5ikcu{=g*t^oRU2XVSLn?G$kK8Y0>!<)|K6gC{iRhMS*Wp$lGJ?_g!SNF|a zY5cIZ#zsLFb)P`nKo$X7&hX_jn45Wi&toC***z3Tz~DBVU%h^hUftap^|UAHaj#z)sZk?37@}|` zFlxrFUE9EozKC)O^dt2RdB~aYfZ@{f3k#p`AY0Sa)WNFU%^L#)0~Cn_3%{VsnTAax z6UI-+#~*)v;s9N2?dv>(@Vo-8(#dUfq%#Lz(s@9JA?;fJ9Swm9oVu z+c#dgX+p1yt&T4I^eKw(Fg~;XH9cf?fN}Bg77ji$A1m``@>ozAEznOmWy+Uo?=TLz zw)N;vq9?xk@&Mr-2wh0l`MSd8>_4yN*Zy)OV}}lib4)TOFWhD5w5O(~pred$i#Mle zG|Y^P(=s)EcM6*hIRBmcEi5gY8X9VJrdrVCZWC=pn*z&vGGl5A(a@%*NO{zN;uNGN zT|s&R>=a4d#;s0keSU8I{QL%&C^>*nz92WO1a$DdF8<`#udiXfy;~9E?N%)Z2^1Vd z7k(119E)T_?Cyw$1F$M9H8I(@tss!`*y zpH}EGUL|$L4E){`sd6HdJ#wLLWOBaKYOyY!KTdjSBb&<=d~dv;<2?Pj2z`kuf`Tf% zY>5q%gg8~DXmYz*wjeOVGFQBobP`M_wl9Of>WVm1-=OhNI*lByiZqd@RJT#orzl%E_=ZA1AYM5-B2z6OfR{D+L37q6 z1YIK`VbJJ(+&q4{)X`pCYz5<0p7Cs-&O7+7hOtCbi+1y7!2_f7XhKAvP z7|nZ8ac!KZ6$IpSlR8lyJQ9L@YHHsK$i`mb<5+X{Mit&7SBq{xt2=Bg97%d8A~Nuv zj0EpWhmTJpyBfCpoO%xMh#-n3pRHoB(`SO$DLXqGSR`Q;cpJmX-Wj01Z)$QjEt@X# zqqecSi;o}O>Pqf8BRM#>e}gBDB(9V4E5hq1F4`DgkweQy5^}OPP`waMF)%jf3$>Ak zz)2WO*1*tE8sGCF*xKM2dkwM)=XZImJ3vK=zd6hS<0DM8Lmt(i(}nN7eg;7+J^;>w zo$kEj^56-~&j^ae?|HG*ArALKQ1CxVIjl%DOaK%<01yr*c=ovU6$sBx0o<_`NaIaG zPMiW_;|L5qU=5rsQbjT-d}y7VNO1*#Fx4}=?;Vz)oj@MekZRubwAKQuudBlzBI5Mj zogJ9jo;$e>DF`q<%g{d43egOt0MOmGJQT&#IgwIvjK@buDn*)BXc#PP_;}ktoePY4CRf-2=IYQeH$N?}@oiosBG?p;`Sa>D zP|(GE!BavOts@abTE>8jl7F-Wd@Um*8}s3kP?tlJ7BGA#9^y+)q3_!7`leV7>y;%C z^?mVqIKpG4mYwy`!9H@*xK?07n!Z5tv!${~*b^fo`l}qKcXIRww@1(d)=A}}V;OG` zdfb%DZv|xra4>gT6FH2orE8O~n>26Z{++Wdh~ zM5A^OLEX+ZMAZ&9`NKSg*^L>6rn8$zG(kkpzbZ!)Y2zFicf~^uJtOF^IB*$0-AL+q zCRsim;)z#os&W)NXrWu)2=+!UtJ|r5P16j52XP9FTW=?@n3IR`Oy0>Dmd79p5tJB+ z9u)JXi)@Lzzi(PtSpGPw^6__xNMBZ>z%z@ab!=ONfkC#7aMb@>pC?yYkSq)2Sl2h8 z_Zlf0w|1{q9oeU$rY4lT48Gg2K0L7e?rzY(<*@Gf=4*%5kFCPw-CRc?p6c?Z=S^8R zIH8+;3sVe%;2Ve;awRU*E{)$h z>8l-$BV>MaX2$8q8z9M@yrzb;Mxi@k46wla`IA|ze?R8)6mkkXyJMwSR#RUjRmTuX zeTjROBbQG=Nk|?LJD#Ie`o@=)|L?~M;n$4BgRp073O+vgOUZAEO}8GLIxt|tr!7x~ zFyc<0+}`{76BKX@yeMQf0m}1oSR5g$h@7N8?Zo>wD*BY10ZRm!ft11`)a`ff?4z1C zg_pVfdMQhb@=GPeJZMikDCgSq$mOdz)LdS2~RYP2JsWF9z>+8J3S*2N%umopPU&gc1+S{$fRui7VhD54uv- zo?;~phmyE{7Qa^T`6n}CT*Wx{M5w4>0(}D22zi$lJA)4Koh21k%18%w3Vh}j^!HZ; ztVfK57j)q#;NB5>QdTx92bO4bbd#OPYjkpQweej7#ImCZ`g|PK`+re*`e)2ooZh_j zQn?x`=|ZZd+V`n%WEyUwEe-TX+A)XX_X)G%W5zo|1f4Xyz@tI4M;p6xez)^!q+8Ys zVjIYZc)KN(SUEE?0PE2oj~+Jtgqqaxv}?t&*@(N*uu_AyCZ>-OD@-OXIl15GyT)P# zRL$@a8C`X5(PmH7587x>?mGWL8~|i3M0ao94mIaV!H)c$*1vF^W*|7HVx*zW+Y7`0t(XReny6WT`gNnhgiCSL$0L!ST&5NVv$U zKF1@6ki4TiHvO%3uV+_Ptl_od(Yy0AhK-6?~ zC?%&eCOW&<$mAd7Sdvv<~ zjTW7cpa1>K`PWb^xVQ-k2vh*+4NZtNP|22-Kj75i z=eHQpH5NJJ2NU4ThEHs4ETn&I)Uw9X<^EuL`^(jC<1wOb@c@cAJ$7~v z;OQRRzYitybA*1=i&>y3z6<~@;S0%`)=0i*>Hhj+yDYWn3Lx0P`5a<<( zZoL`B_AoKGs@* z3WkaSnwOkxC6qpG`zq*{ZKH>nct7Rc_XZLehmbJ5|N0UrnQ!8_!K+9IJk$xqDVlJ0!0HL;6s<$OJiY33wCu0R0ZC*H)-p5X-`y z7b8fM2DmMtoQB9R-#&HR18&^OygBsyaK{fT|c#*cJ|?`>`lA5&oIQGAL)F>`dR zDKEF{2_YbrMM3oN(7bzFwEgRB<*T(o2|h#jieuz3i+)No$pU;4#yo{;{V7Av!F7}x zdzskJ&88jt;bi^9x{dQ~d#6?F0_No7wzejO+qdrFM~rPgE}!=4%r5uWT!@q}=b`vq zLilWqQ3Au!#>U3hb_cmrg5x1q9G(g&g6CUbaUe>jZJVf)7VYK1d#_VIoh9nR{Bby+ ziaHJ+8O$AwY7E*y3UPq4ge^6IJP%M3XabReh5$UifYnx{p8a>_?cKb6u>8O?21XjW z;z)z+E^gmyE{@Xd{G_SFoYs71C8ZYOIeeF>w6PicWce-MjknV0v*>GRoZkIdtlrwi zleHt3_?T#;UVUc0q0JUN*}6j;N1!8H2ZO;Z*eiNgL_AOT0I|?!Co{Bt0t=iR4H#ae zn_w#jY6bvPVa#P=XJ>ZNHuxMM;^EzE9%aD7AVyBx#N@!a1$IuTza@PCdL8&dlpJ)` z9Wa7Zw>)vt9Xa_B3=Sn`(vYDHoO}Y$O(q-|vgq7$<@3-3cNYppGYEl^kEV8q!aq}O z6Y#e;5Rbh6z$)oz5@mE1nt=z6O7HL6-;v$eLy(b>sK zk@`6A)9Qo;{rAWRD(D*Zsc;fh`0!F_G9*0_7~}Isb__7?17Kw6v;hL!dwmIU&f^o4 zAY%fzCdkG>dD955yeO4AVJ~!&lhf0J?nmqJJdi*zG<^+$1`UQUp-To9`M1Zl>@8y$ z3I`|~#(^K;s-o1e6O=Y zn;nEjCI|?(g(t8HT@*~x@%9#fVsSeVM?Nkc=M#P4C#@1TQL?hNIx&5tl_i;G(w6b< zy|*Ib8icXR@qzjsdggtR`cLJdis9?-G$z6CIegjUj@;Ye`dvWn00h6+Jm25a^70;{ zMW?>+?;d`x-{8<0!hUAmnQfWEU#vcsEiBx(U8UceaT&K1`80pLU~)UpC@M9B=amtN zyES1b2w%PJ_)pD3ttj?;RI*dDwSR7HPcUAc#;V5z+?jU`(=Qm=m=w=fHf=pV;37-Z zA(f4##tvBii;shl`8&9X{Y?(Gxexp))_usWj5!tixGTwTPOH+mjT`}KzJ9<$F>t>z zRUfWYCN&UZ6jix{7pCkJ{qb88Rs>Vt4MomLvS+hG`Qzw{L_4VR%e?4NO?S!2rPu{x zF#4J6qXCCTL|3wPxBR}8(v3%{RFpp1Y_y%S$C4<$k5z7;E3n@H0j$SHjGgc~1 zT9;Nv~g-%CbJ#fuy_JyGTP{O3m zb%nPK9lir3jIt-Pb8)={j|NP>V_G8jmRD2^(=FfM+mpHHwm+w%rPW=n7-k0S8yFK; zzE_r)N90=wQsD39N5M?r0-T>X0a}IY^XTS8k1iZ5w4mj2waKm2$65P9Ba5^>Igv7D8sO_ySB)c^GVsvm2slBDBzqN))N4+x27#-;>Ku)xrdaPc{ zoS2jZqjEX6vpz=NebIEag;w@q*espPl+&(^Ex^MA7#Z?(`!&pc7K(?+SIuCGoPOJ1`Ct=L16?9WQ092 ze(dtMb7!Xv{wdo5mKd1g`a~To4vw)b7=~C?S@mOn!s5S3#1$i5|&Z? zwAmM%o$}@KHQ5u9Bx>jRD&B!vLT?+44u%`e8r}-9JPIw8{~&t?UI*cav^xR;3RzA? ztUI8tvbDFbDy3X$8;8>4H#pns%)b*s>LZ(G`814U;7cC?A7$d81;klFg0KkU|F0-s zZ3`lrh&Q4aIfR-R*x>(RT=uFfU>VldYBI+|U2w1a1M>EQR@~iP6!8JF+<>G@8s7NT z`N1hlF5kd)@HyVS4vQ7pWX|TTIE)Bx!K{1VtBCL zmYSMs4Ls_DOf|&e<@HUN=>ZB&(7i+X0S)`2y|5>HL#{UaxEbP$wE!T>X1=hRAT;^0 z06wCju~D{(pM}K=s$uA79KMMYaVn~-%il&aCnKW=Cmuj>`CB4EY~V}sPV}^}w-vdG zs42YmV7TqZi3d`I3VgKC$J+qbH`ylYV>o8kdc5JNGJR?_=+IghrfPy0Z607M8S~GI^FVDu)Vo0IAOV20qL=xPxEHk z9|(D{h4xv8P1{b}HUgVQr}%f*L0-|XlYfEVw%m0qMm$;n*%x8FIpGO4BT1(E zA_m2ij{@c;!dR~!+&Id%Nn^&AlJQ-HuLR{l3}*E8O@eIS5?Jn_Z0P`E51DXWSomqh z5or=a&X4Yif|)jyl$4hBl;GOjeE9C=1TtP3@N^O9b?hFbEddg^!+$tQ0krV){o*Oy zh(2qa@N4`3SM|Lw6&EsSapcjy#~+|6iX<%V+_{7PC}qSlj7P|zFcYADX}0;h|i3wpe`i*?oiCGfsva^w24aaf3*OdRqLA~NsraKVM$h2AUS_} z2(TcbYlGkxGaf10Q)`|vb=&_>N~ya52Y%+2o50rq+tbm_QV}<9^B*N zn%+GDT%IZs4eXP`@Z3Ng;c>E)Y~m3%5-Ya=j5Qz~ohH?QIy{)G2f54RVm0JDBmTHX-b6&cQ!*0j9}Dv99y+!wkoL|8BTEEI!P)^c z)TJR7W&k}v0Oa+AXaG5@7b)OBvFMIW0<8Yc#>8_0X|$dfmm>~4yE`a;D3}yAhV^$p z{F6w_r3|6Nc?$db@#ZH(+}-fP;WhJD3lzskQ@rYLkNo?g^0j8?%;3yh-(+k~epTAD z5^9VKV;r#Cg!!@$F08fJetz&&mVHhptGUjD3=mWDWDby&ubp4W=A_Hcc6M_fBUvFl zkcoZk6!z=#=BPG6WfXKgA(7S}bg>vnAx;5F(?D8Qn1gg5TBpxeE@|eCm&IFJG+xU- zKKqISgEKdIvlQkg&fEHs<*Nxj|AYL{vU z&BmD?+6l}RY!5bb-Xu@XB26~Bsqn@!tl}YB!&AQ;0vg0hp+mDvw6%0|{!{c}D8K`W zQ1j!uymbBh%=96|S&WD0<9o8TsD0mSj-D^S-~4kX_q181Fz2`}|Co(x@Rif^O=i=o z{Oy=OcV1qI$-%B&^B4bnaEy3w?&YdS%GvI=bBA7av946-UGpE=KFz?IJSv zU$LDkW57%$@5f6K8Op}Z9p>qlS4;F*kFM)<+tc@`1B2O3TXD=fi7B zV)m&k9<~@JUuxm~CGHk|GH0rE%HdCkEr~^lKu5tnEFj4mT&G1@Mm?ga6qhTe&TqV? zT`8N4;S>27;^-k*_xrhUK=Ja8P-Z%6}eH_Gtx%1hq@Zch(?dk`CbxWU2pEr=aYmaEEsLy zo+v{E%6knCnZ4febIbpQtYXaG(CK3;OZ+|jcV3UxbKCp++G;FAYW{72RX6xCC8Caj`Zw4WCfdyxr?clq{3>lC~01wQMf!=coP&LE9~ z`$IwZF|jM|;uv6%n{Z{3s3_dmQIR7_08sSb^&OB4q-!yb==akPe^qOK3Y}hiyZBT0 z4nM;Dr#BS`de{7TID2?R3ofa`uIbAhJ}YVB{5~r=AU*8d?#|SOx(`}jz3z_5^ar#)D4aV+9wTar8aB10J%B=mEHl8%R zq(&>Li`c9vR22@XwD`*{30r?frw^aljJVW=yKS&!$0z=KWO(dSwxX3ckH}h-QCQZfZpX++Msh}Lar>DPq4Nd`224ON#4h4-#qJ3+Dnw#LC^p=+d6ug< z0#2f^nL(-7oXM-J#6BdH68{g;c~qassHjCM8^`#F5ZF#(GZE_W)0}*b0)fQC%EZ?u zGNRb13bbD)OtpW8`yDgkHOtl@Iy^&YMDBb!(llgh|(wAP=Z^N!D157(AeN<~eemEqHMIenhB$yX#KpRcS@vkH7d5xGYkD zkVGQ7kVrvjAl!HcB}qmL|J)0c|KY-; zrzLJ>J&n@Iy)Z>sgu#31A~@ZlJE0~k{)|XeB$Zmg?~JRHDFd@F5811u-!MUo>@w?< zic2;KuR0`)v}EFnvsEDa)fS`^*&SKQK~DU7QSfm836j?_x@*ZDo7{xSsv>yKUF1QQ zUwuJMpp;Wx;L*6erbbosNBATA!Q7&b#eB)sy#RE578_I9reN){Gji#53puALsB=eAYK(lFuV?i;|1~Z}U_6 zazWCYlFWg1&s;T)o@|lWPUd%|YjC~Tn-5L@2-GmSi!yTM|6Fs?6cFPCAW9R45-^Jh zJjFV0EFIznXbiJGW9_>CcIWbQwKRWSxfdF7eamh99*eFoPwPBiATNTGxo!A*=*Nn^ z3ei!vla>H8BV9ci>c@RUo)j4*Ko&^JP{E^Y?J!?au@@cv8ikxUT+(O`yH;60o*__n z<`4GM65P?BM`q)dbu?%Swm&ov479fnt7o>a-bs(%M;3TRr26046EImP{$O4Xu~(m6 zaSV>&ah*{~4Gi!N8A#sHnH<744n^I0#ua-St$$)G6F$(z6!$&39T(eH24DZTnnE5? zLzn~$`DY3hfn{G7K=PPTJ?8t)*6EG^-0oNVRN+aI+04XJ-N!np5H{0d%)j z3_rynWtzpEB}dAhaSLJ&zfp$HT~k8pp9J5ktrnikmBf39Jw`y`c_6$C%!SKPGn5qG;u-n#mHVPKIJr^AFZjF$wx z&h^yDEXC>H(w?ZxdU4&yF{<|zSqq^64cq|dT%#{7> zn~uHWY=*^?VWZPAH5o6z!VIc-kkz06kd2s{rVESN8ty1$@>=QZO(s2bF20c(_1WHv z(7*0ON3Gp#r=f%R1MSPqc9mx?XGgw`-<@CAFt5t$D>xjgWngfTJ7zf|zR{)N1X!#t z6z#wEJRJ40TI&5J*;#*+mg5b}=|}W4$$(HMBeuQ(m6#OdrEpMjPKX`LY`&;J2yTW; z5SWk+fH$LN0BAZ}>E)_Y@@AMbtdWne}I6Z_en6h(uDVD}1?&-Z7#ew(<|# z{H7WFVvL@fqk^a;0KxT$6kdg@T{8<@h*G0KuE9^?*d__3=(tFD&v>~TZqWX*3f`Qy zq>oyW!Y>wnyX)h+A|#pONw;>kU%B(gt#Vx{UFh9~JukQ!5mMs2 z>eDo!6r1zWrjKf1F;K)U_T=d#T)+6E^&*#Txx(!^1@rO)UIL%8vsw zi{RfPI3JX_IkIp?IkHy~=wCBaa(a+pk@ry4GMK;lv-1x$I#(X^O@Uaboj)WFmjl5< zS1W&4HH}H}*sp)>0yxNEJaWXxnf_>1Zq6y&M#U62ne#vR*jRi1jDFg^q4Zp-2E9%) z*p}}eVMhEiKs&U09l01NyYrIU2Jga7+Gq$G^kU6&5;Lth%3!PxQ730JGX$bQD@?7peq*-pw|Pnq zdT0aUTEoaF?uv8u+X@pboAF_@Sj+Vz`%~aDj_qF?QM@E}K;ueRVfsKqjF|efL3f7r zTT*JC#jC7P3(JiHCulaO!!GSW-b1T#skfiLFW|r$6Y!~x5w6E=`{@1c* zOp!z)#38vPq?dEQ=Ilx_djN!NHT(Nv*^M#;I!orQtWP{2dFW32mCjGH8QlF)n7Kx@ zV;ms*IWSNphKewT5FOC`uaCY&Qs zb8QyUA1*LWjZPweXa8vV*UVqx6tihP`QbSJSAus~{aS{di1to#I?KlI)%(okg&B!) z9P4tqub8?X9j!)2%_&UWLQq}Tk@)C*yg;#fz=FZ)5sa_fP2nG3Lb?Sx95AX&;%x5} z2(I0C>S9%3-GijKe-C~B9{XO~IlR{W3Yk_ZD-SiT#&o|oZ5NY~ZA6fB4~>p~wH6%w zEPrPft;a!&v~b!sJe=9rW!2)z6Hi@TOBdzx;SH(%;A@|Mdh#7v533^?2g`P-!t;!z zxwDs8Vijt-klRy}*VH76fe%l_`2$%gkdFJ@J7w&9^FCRa4k+(_) zrg&gOv?bn^jm_Bjl-pBSk@)5Q9S`I1k)+KNkFn|Lvy+op#?&nP!OsHowXFM@iHSDv-7dX5e!D8m$=ye|x}6CK3AQcT zgBU3`HY?U11tB0}71vl>3Ygl$0(FauuIE8U|5~H|XVLhI70a*)lDM0CnEd$s0s@Qz zl#~Rh*qD%bXX+lya~oUV>B|4UmUj`(Jh zv(x(^;A6Q(Zre!pem*Mi1DGiLewPx56_gK~7#N7Rxh9RL%+2p=u#=^xQf_^zPn@P| zENiex8r$TkF3}z!!wi&oM1#Fe(7CiUKF*e?q!-+W$-ydd04KsqXDrv^1NYoLsKWI>f;aS!H~D6N@zJpJvOt1H9TzX2!=2Oq`k; z3cjVJ&3*f}cXGi1O`O$E*52=FN<|KYzUe1s)l$=>4YJ(w5Fn-@e~Aq_Wdf zS$5Xep9fQWd6v&E{mm^$Q+}Lybc#9+nSB}FaE@cd!+W7r2)kU)hpP&?%CFW_)`wrd zXxJ#$_KfQpKTeO!%M@x1E!uv(l*L;_HD&v1z~Jc_;$05k`19w-2}+<$zE_1^^X0d` zLcp`cuFFpWW_N{UOlZWi=Kf(4YMs?(91p91*$G~kL?u9o?96Cikag)g&eJ;mJVbxA z_iLv}Q~Ggfu6_~s8OPb1S40V~Ia&JA{a#gn>r$d%U>!JiZ*+QYZM_A`0F~b~;P~R;?)3V#%0XgAMDl1c zatj54O+lZi=q+*A$vcjU*1IqNbMWubHp|>A0EMN81sAh1nAgIW61TA2`uqizr*^ z&E)ogzCqmbz1uDFANkk&`**g<>%k=I=Nd7)_Ui^g%a`*={0JGTK?}Z0-SoWavIM07 zTCK+fXlQ}>J+AX@j~fizO|TG_E>yCb?d>;8waYZi+x8dndqk+c(NU zPl`x+g`w)TszNRurI05~Q%g&Ah>(jqyekZ$N;Q8nE)@YEczTf$8RaA`dIetv}K^Wfv+w`08}3E{CB5@@+>df^t80iv~#@d2uHLR!BehsYieMPhw{rL69&pfhE8`jQIhdA-7PeDxw$OY=|l2Z<7h*$;*Dm;eID+gy-j7Zym^TAp5!J6@zb9zY3S&;qaqRE zS}@2M*u&87L8IQ)L%)~@Jv^v0`%Z74;OzvNUPr0xuv6kwFidWLHz;FR4(L-rQE5uO zN$`+>p?hnILE?nB6H|m;pnz#li2sAe1xfXH#P{2zr#u+B3@cb~MxI~wma{0*zxh6( z>7vNx_s_Zzov|u(bX0`qaDSgbGZ@n|SjB`=g(s}sVEOh8VT!I7^Yl}oTt1m| zsLuKLfMX5c#ERpV>wTae#zix{iyj*pb-(9wVhE_hD}9KPlTCMa@wiCIh&{A3ixTz7 zRKokNG=|FU2{n6qfr%0ak4c1C0~JN-l5o3Cm-o9sE9#LjUWERcnnDe6ALCtTfs1&} z@vmPy&X)dtzxZQ^b?WQ?_i{SPwBvMc7r&>%$bIqDD*G9QrJ3U)_!FNapn3ffN$Jsk zu z-LBafCjR8&YGVyzw7wwaWH;ykA;v`$X zzy_E+9JQV*L;pxC)tsUbgxCYSx6{2O9`^7+)&)pfb7`;-G3`Qh^X*^SSyA-8;A?DZ ze2|F-)@QGdgOw>G`)CoCuypggSQNio|N2;|R|ghtpGK>7E+ywp^WjTtYKQASd7^hO zQ85wsQ%d#y0~*AS2TTrpMXd`5CT|1HQv~8`b8~TmOW_rFsD5@HCkiumo34F2wQ^yi z-u&X^B;Mw3o~ejP!miXPaU0ef6f*i729zaDO_=+_NZ7Pv+*+yiRV-m0-#dIgIWU&J z7^*ttADgXG%aaDD+OK?Kag>WbluMidk=03`17(HDOL3D$6jNMbG|>zl6oa9?VR(4z zHw{M5Ni|2`^cBDH7&s~t=32n%xfA-y(ZbP?6Eox?CfGAm2^DC+n?@|XIUXsMmDS@i z?moEKE>it>y;-adV$HWp*QdAAe>R^_3_pHM06O5y!+c-31BAWNAa%Iqw(x6af6VZ6 z(k>){%6L6yq31^2acYH~Fu6UQQ887eOj)sZViP7vaI?65ctL|9fit!dh3RwYG#<{w0xg>kuJ@%aEvFfJxf-ND=D%(JE-n2t=W=3@ zO1Za^-@YT`ZuUm(5#bMk$I5n3!gbSAW53URg?ege_ju4kD}FpBF7G)v{tn;fD{g+9 zxW*qw?b__IN`0S_;*VYGgn&;Q|YB4nGt9 z(A;dHZR{KSh9m%&s&b>7j%qk~&5Aof=LbWbSyvv&L6-Xzq?RYe??%~P8FyakxXUs< zA_RS(^)HS`F^pjy1tHpjocKNKF$cHTPYvQ8IluYz^KfDb?<<0&C&GI++41j2O&SKm z@0r92M^=MNB%cUk*gK4-F26rw5A#fuLHJQ0BFkXPEX%CM zzH+e@y%Rr9k@efoH__S5IU~_huzg*4olu6&{+e4?dpZv6v#e89u68pqM9$d!+NiiFy7z>y=VQP4FcPgTIgL(UlQ|iLvgzlN zk0>kFzitxzNnm&PQXl#~LnC1X)4L||8B{qsT(c4xq}z=*-gZ>ojw>ZwrV?Qr;|6OP zJr<&<`p?H?9kc`$W~M9q_gLBnpN_4bW7=t2mTdH{#BRaU}#@zU3F;T`x`L7B7F z1J*2t6}>milBbEj-7L9*Lh!GXV$_vrkGi5e|q}0&FF&c zq>2{8)a}B*+O}-2{)dGL>*3qEo&B=z;6hP$_2Ze#F~JA*xDDuwroK(a20Tmj5st?C z2o{;Eb^Uq<^)#=Vs~#G{Zb5ni%64Kr9MdBZ;y)?yz{Jp$za35*fPdq?y#ZPUu)cf#yd0R?%73j<>C%bIa$k33no|#1M|c7#(Z7HZSjLS#1^!Vk2UxTq;_N zT(}lZ>SdJ%v~6EgmkJfyl-O4bpG!zyiuovI!cPLcYbYmvJd@@wn&i2+iD8*wfdUFb zGEY@CR;c-d|HwRL^*ow$Z~`KRm9$`HBiG+aIB|wV^q7xfMkwKnfGT0{d53ter7UJ3 z-8om3lDLyt&Waa}K@GsM%vPLLPeNy`FjiBkJ;5DuP;g0aSE4mdE zk1#2<77od+CZ(ss0q>=49V*_UQ7rlD@LmO=bz^tduk^<9XUhEfjKN>u!}UfL-M)B| zVcI&e$3PgjQg_GccN@jy#b0XqeR1_jss*1FnR^UsR0=a*@>Td!JC^ZAz1gN*V6ZuHZ>RHWS5J?7v~C}^v! z8+FJOR1^>3V6+-iSI@j3MLUa2x^^?fa_fkH<9;Uhxp=VFEYzN{iJ}MMU*@JNG%$Re z5uON7+OS?@>Ac6ev~+Ij3q-GuT#OR*C1vduly0$VzV&6nUJWI{J`O;V$C$g!V%PJFhxJIg>TLsV_>{i9YzZcE%hn(fi-fDWH*L z7#hSrcO0nU37Tmq(YX0+F+!1w#0b-~tvuStc)Gf7ggZTs{O9`S0FO^~GP9tT(3Xl) zA?cd*uO|qE-f^urOPkk6R+T17mt%fuF14h>TVqyb!|L9rwGk*v@tQovoHLRr2*R?A z33m&fi}7|c8bs>%`|bx8<;+{S8%Y5RA=U2=>LO&pI{LJ$%`Re}{i+^80RH z19LvJ>or%HHof@i$&9$TxRY}zA&9!cpF+DtewFko?(5faP2VbeGe_4J{Z*+-Ee;(e z<&v_gZ)o4p2I-OtJ7dioDdW1r2rcu}e4_J1@ErviO)w*-_IYTIv*iFwdX%8D@*UVcG`Vf)efCOvC=YPo-4e%IarwoC8=iI+c2Q}^cmz@zz`XYGzF z{u?$OTib9Igc}WJvpJ)?$1f)4v{R7>Wn&rlzwH|~(3;*p$D^{9_%;3hhVi3qsrtAB zyHd`7e?mP+yGvne?e%8#ozmZF5kp0VLm$Km$jIb7PDit|tMNoI3WrS{FBp@D<%h`l zwkk!wRNgbn*}ga(cGwFSsI0z>>2tesIW4MWIEsQ<~O&dszuA8 zq~B9BCj&0zqo2p)5jmMAdk5Eb9pAG^v=#6W3Z+s^7_jw@y)I!HQ)X$6Zh8zlVRGyC z%Kpw0+nwPo;*xX}=Fwshs2$3gudJ_c`2&5!m`cv6Z&CkgWt%4MfL^B)=Ot}#>)eYb zkoYL>zR3SCe_9g&=z0^N;}bwX!EkY1+|fAf-`Jn0}EOSsDVq}*D@ zFLc#O{p+VeJ?NK`T2yv}-J+rsqmSQ4YoEP|7pWJMtv-BkXY@F@bgS#TL^UT9lQzB3 zBVx(RYyV(<%Ibc365{Z7(|F?WoOX$ai2aj4{s|ftX+^Bzhi};nK4rbADgBU@BETfw z^~TsVnIW*9g&jw`XrKoS<{NQW$R2WsSwSCmo0efbD<(Yok{q2)2b-x(`Y(PH|2k!JJZ3u4L5w2}_InpG-mU~p zITe+Hn=H9J>Q8ulmBP!*XX5=pOiWiiDY|^bzx48w0zv!Az`#)Nu}*tWzu(fV{_L{0 zmE~urtwF%QTJ^`_!ld!cDEE|`zK`Pl@@oU~66ZOeF3zHv5w(e8g&80Qb(}J%mW+ zH3)I^yV<@kiyMVeESL(LF$!bcFNluvu|ls$i_6G=LHc=-QcX{tnmMxJV`zFjh?`Sist*-u^GWVB;xF58?DqzaXl7KZ;~`LRy5i9h<$zqB>*&q76@ zF5Dqo$`Y5&?#x%3O4@cQN*{~R>$Gx=kr5^|_|vfZp;|q`x1~6P(GOEARafA_k|c`X z(0!MXwOt2wukX$Q=sErq7Ha8~O%3($*IpFzSH58$a!o4S*!+6;!o&1!#;-U^eij?) zJF>rBoBF0Tk-9?AQr!O6@_cvu2sb>hnQaJVd&tqew9HJCD#sbEO!_U!M?$3yOf0j& zS2m77)3pD-Q(Z=(Y#OPMip?iN$J3DAaVV#x#khI;;|%|XyJVU65Zi(3 zyI<}`_U~@8wn)*fb@Y7k385YQc@Pu1#4oUZN}?64Mc00q+42hbH}2W(?F9tY0TV&LQ5@*t347r7~V zv_}_Vi18VZsPPxYM0$VWpHCCF7;Kr<1Vly&8Ods!$eAA71U$JyrHf@_qB})w(6=u1Fp%X}j!zL)6hkeq_?jg|qS^-_9; zU&|tnhXdB64hcWy_$6H-p^j46j56|(LYbZ27LTN3e=G+o8rrn!ru~0i0(d1rhG26_Tc|g z{t{n5{`Z8i-@&($vemqf@#(~d zSA7530jAf-%}AL#3fy(VI|4*xttY83P#;fJxvA0EU+Q1LsX5vnGym^?U7>kJ%}3YW ziT$CRY4^2$clIs2$y{`Cg$0D~7^jtq?CU%hbKp5Cog|A>Q^MxX#+>Eo7HE;ZQh#El z4zjHz8`VdI!Vre!RzrKzme8SqyIv!!^d5q7Y{XaBBVHKfu{QT7+OoL%-qP>GroSYQ zkB@U~pOw8oGkx>EXWyaa1r%_5T!?N>0I$9oaSVO-jvuzRa7z7Mm%G~G3s}h;n(c6R8;vNM-Ez+mgwyw!tO{tk>``MK2+VOlV$RIG5)*Wn0EmKDR{|2 zVQuwMsz)hXaPseIUKaeK5H2GGcNrAQi zqzZu17*1nJk=}dYVI+F}V6-0W;S=kmL6OHb?9_Ig!;0rnYtb}CiKT43LyV1tg@=8E_GMRvOr97|9WMBf zMfU^AfM51=eahswqym@WiqgRav8)TCQ#oS0LF+3I&u<5{kfY>LqU1}gtn8NRLY?j- zvFS!Kgk;qvNFTgzmDEOB@3?SqeEnKLe-tLM@E>LJqovjqC&~b4DXyNmAq_nR8QV`4 zZP^uN(L+}DUiT-Yc(aK_kxorl$GH?pp`q4%@ub^k?LP1ou{CZeL{{qZ@^x(!g%@5TnWytXx5dGlIY5J%j?Nai(Ar{?5gjis#5;V4 zI>yGvl1`BK6x)lj@DskI)-8=uQ*oh=hH0nsc^Db7pByx0XB(tj@i|bN|5(iwbla;O z&I-;VSwwI8>YPA-5;ZCNH6h8(#c83@nk$GLsPP<;W-m5)MXKb)8nkBlS&mDR1hkvZ zCOB-04m=HfeDud0Wm&nqdKLL3`fYMb!sN`v!NGx&oYKNCKRQC#{@<)5|F?$69s-}> zPxUW>e81%u&Xi_f-;j-s_fv?czFy$!2(EM!@Jv$^2kK*^hXO})#M(V?UP1rPP{&Gd zZbG5lyuAAyMp6a$?edud!Sl&?+U4K5M@M?Rfm&Yx?G>LxdikLi9)RqZco|$iT0m!T zu_fzR$G$|XLIZDKd43Lc2;-o?LkN|@O(J)~j)-fokm3jmVoMbD8u&euogD9a zzE$FudZ|O7#t3fm-1(1 zh!d-GM0Kst&CNA77L?W1d+BS36O?C(c=*rgB@s~1*Y9VF`rac$0f$S=OG_pV7Fip_ zKO$_^!6z@BsYpmn#!Dhk`>>E3mdNb{tyu#Bl4mk`uc+P1kvv?EVhS{y8VmG(`65A_ zoVA2R8Q>mcwjrr=*Sap61*7DLSC`+8S~1DQ7AoE|Q8Rw47r)Z=LTZf$(o0#(ynXaT z;8oK;%$wY*+JMva2K!Y3etxUE&fEie^?{3!iM-whjfCD9GFj||g_=baM|Kb;-zVwrH@~M~lc}_u~0q<}P=I zpirbT6Gb?x_wTY^W|g9@?!5P}sOy^>KTL0jrMe#t4Oe~D*piZxrP>SQwja>=vf?_IiYDP-dAFXPbL_$;}0#ikd zOuw}y8gh#~fvA*Je2MR49w_Mm{gG}L7tGAe3NAZFr)0uInp(53UnM!ZF9zxwfVzd| zrmm{_Z6&pnleF+GlF?Hfveo?8ob$)mSmzVVnLg=)zbH2}01_vPFv&hOoSja4uM?&4 zC2@K?zXliLZ?>B|KCJDWi>7C`_-HYIx!zSU{2^3|W~v^y#aEZ7#R$Lq#}7c_7zY#t z=F|Ekoy=)MJ!&V4sknJsIk-9KP@-6L?ZNa#Tum1z!cViXSbheLvV3TI0o;5V0w*mY z^6O4%`zPabL$4tFf*-xzbg`*I!B`?DJY7_j!_4K&OCsP=4BKAGd{e_970hGz$^Kr~ z5?+XROa4GFEWBirmq*0c7%HpxrlGC}`XnyiuC%q|VC{zrF=;RCSy@+9dn6|3xOMb; zfI@_i3;}q=eji{Qb7=5arKSZN9*OL;=Sr#3q}!f1+LEiN+~oWn)zvl5%4szg7bTzt z7T{QZN_Jv0>%=q;xk?6~Dua*^5jrsJ#KF#?AQyk9_HHQP9{**CBrP!TF#Jr-!pylm zZ0F~pjYl5wBgriwKurF97&Xh;{f&#DE*w%HueLuT1t`BX+YCxD){p(3k7NsBLKPz_ zpfL|JvbC!p7@6sJA|YJ$KeW-dELGbR0xvq=L-rN?Uj*E z6l1X1F-I;J`f>FB(v!L`_2!SzIiJlAyH{36xMrla++Tp znv@XiH#|6y&>JWCtFiv)M15*^Rc$pZJ+rTtfzz%tJsn+PWc7H&_&|12bCb^$AGg(r zcDn~$Lj6=M>L4cL=aRzc+WLC(*RP_^2Y(_Ot`hotwv(MsBTEJpe$HrJ9f`5Cb3WYP za4FZd^a2SoH>l(H(>wOiu#(T5Pq$>m(mt9P`>_Z<8x3oysRI|XE-2v%A}7r@U?{eZ zy13|MH8ip8<+4XN?ZP2Q(*^U9g{8c*q_n=CyIRo)leo;mYAE1*&E5OGw~WO}sG_Iv z%9xSBPuDhoDrrq=FQ8`(o?xza^v-uIZJ}hK`_|ibRsenV$k?(s=LNsl*p*zzF6bA( zF&)7Nz6YejL;6MePoWtt+*hx-h%=WZyE;{G;+CqqC=wXJT>%EjcwbK|e`oGr7gNrUnq83K=PPS673mSao%+_|(%lecM0vMd(B#`+NJ!(P&QmdTaA8N2G8a z4m3l)g#Oofd{^7sxT=^Qvd?`)MOXNShs6U%zRBpyzXQ=Kb-qrLK}hPJHOEdKtU9$ug} zavvm_(mJ7HB%(a}HZD;Sm%&LkQaz0vB9ql9L@bIQem*8Dp<)37dB{UR*lp=2wx%+I0=2^2D3HSaBpv4 zU4-|!(A`niq9V$f{feA|ii&)bylpSHMGtN4Mp)LtgXWfTCRPHLu}xhnJHgYTPiM!$ zG1(J1=x<(bx@c=(Pe&AkPRq4Tsh68T4Q5aq|2F5Gi-)71jlQa`hIJ@lX=Vo3n}%8J z80(XGQKf^Cxw*v4%`cS>1_mn+nax0F$=S(mF`(maZk&okUA=aD$V*-KlqV&J$5S-m z^c8g9>eCzFeT(W^mqLh-gk(6^`1|mL;&_b77zlG3eBh0YioCeGGHh`rfG!W`Ma&1x zAV=qA;QI6&qU`LXzzbe&cX$dQXg7aU5P&W;SL3+d@;4Ylp1yn2@HwDi}VD-SDRx#_e{ zxTBDC^)+52B1&lCGoxan@9ys>sHcX076Hfw%a(LCYb=Xa0xR!11}UNc-Ey;lre-C$ zvyK?m<9`?oMsr282l_ruy65xnLK_Su8-P70KbhXi~Xh50`G%-Qz zE#j*CmjH3F3i`&0y8}N>VP!e$(#MC!QUC2fW1j@CpOpegY5n zr~8l9KgzG)=T5J8C#Aptkk>Ktm!OEG4!!UXTs;*SumO%SFR=>t*}~JoDjr9F?Zz_= zi7n(8g7+@wb3hOWZw?}dI&SM@e}{B_K%)wyBCM=f%6uPNTJk2WLO(sEPxDPqL`rR} zzgdCC=I5<1H3RIcd|e->Oi9V03F?VUJAJ_i-@bqU112N%#ZV1Q9t4Pyan-X_(Ercu!hp%$hzK5QXfC0) zcT+U22R`rOrbyqn*@L9f93Sro98&KWNpuKnGJDEyJeqYKu^5-&$4kRaY|PA4Q|A`F zh6bL(2GY9yokP^TtO!X0<;+8XfZPSpW|nTku;1$I=MOcRrj5hE7$^_7Y_!qaNnvSe~~ zn!8&n4pJ%F?v}iHHn_s!}Fj7Y6i)X&yeY9=Nj{3r7XN^YLfBL|&dUHx@rUR}-*B6?jWU>F>eG&~A_ z{Y&{~&6xG8TqXr;PuFmaW$)klwuDZ6{PEPA@QpZ@6vL!{aN40QA#7T)7lIL~_IYrU zDhgx~hS!l1(a{mnh>)mg8?49{3M7})^SuX3fsLk!0=d?#WdQS#EYG#3v*XamN3|Mmu&Mb#4kDRU4GIQC0zBeI6csB~s?% zUedr3jtv3Qk9&peiyjl><|bB!9%tV=n!$(n5ZMc_9T6w#AIjqTpsb98%FU}M!Nx#j zJDA(?c6gY@mN;`@km+4w(%5GsMGb#{e+>6aARI!7;OXc%cGY(}RaXZ<7Z*1fNR0S% zrpffr%uT)1)A+1g=YDlg&&cT8;J#sEg6dXRd%O(=b_x1;+lQooc#j~SF7+f3=n?=_ zOG*?)fTr*ZLUY^$9 z3n3g<$6w?$is+G6-Cvee7@Au~m9tq!M2)_*bd4Sxn7IF!bQ0FnGl&;_ch_%aq^hb4 z>gcqnv5eQj(?e?7Z%K%WndzBd;l5&I@Oy=W^{i{(_6~y3W8|eI-a#?S$~U3X>KxTN z=|GH|j1@W-a#WL+-kq=gJlBXggeh|Zfbr+1ymWg zbvX|1s4IL!Q!40H3p9+Mf@3J{ro2cnL^{)yhhxmW%q>OuSz9kc=6eJPnr5lC7?V#y zN!}9(9X&=`y1RDU_vXFR4Wrlhh z>0eUK+AVMxC*9rLT1zU7jgUn2rM|a5ymfMl-1bF>fCHD2sp%UwtjH%C@$q2ebadAx zBXmX>7P;6i&(6-4j>0|pcM_et2BsR+ZmNhL9TS7@<>iTph*&j!(|mP&*KbDo6`*Eg zz%v6Sz5C_N%&ASOCuD}Uwx!XXAK!VXlE|t#rf>VklxoA;bmB=d_Gc_sht;(-G`^(d z(?P0KC{RZR-!R0^&3#_bw55pZ>&7^_v_#3w%&j*hE`gK!itA4tnMgF!zcXwzbF+oj z1|tffcmK9P=?Df}@>pAI$`yat3E*Ah`|$=6&YVG8Stm929tI~LS8KL!*Sy^uXG!K? zBmVl@+B!PSIP1ARtXUo$f^0X?$$_)!uk8{m`SZA57I)EvDi zhrEuQoT>+f%>g4l|L{cTPfpu;$ytp}T!&`t);3 z_ztFru7%dm^b!-`(Es?GaUd;I&(-`aQgL6P3cJq49993UUgT|Gz9hf7bAnGIRa-@jo;^*3?v& zS7`gRU0No5yolQ~$<5ZPCzE#PVMzp5$shC9=4dqQgm59Z#=tvBwu(1@L0P*>mS9px?{jEsfOU_*MBAj;q{TnHl;B@;AbR)zEktVBtG3EeFm7>B>QAII&JE1PXk92q2!I?v_4HZW68h3`6hWi1Zr}%gW z`VlQoZVqjY=`q8fd6f-u2ESch>*T46K|;@lZR%>N#x1m3_x-KduS6ul_mBR)!0WvH zKA1TQ0YKMoHo0he8q zzputCG7UHI{-wd;d&js)>2cl6>1*pZndxOkLO~;g9 zQQ;KT@jZBvY55q>hZfT$L9p!LE4qc&JJWH>TqG{ALjF(^q=tG zBT7o@xqANLVbDbq2%YzTEPNLJ41t`6$L=~Rw%FL%czkBUtVJWIxX6*0JurYV0G8xv zKuS6U2wEn_$%nE^Z3Fc*SCM(A1*5Z*GB}ykyT70j0qe@I z<;r29MN>*oLHZ5Tp_btA!btB`L=nvOK<$d+`03TLSYwtS9oPQPmAugCK`o8jkl*jg zq@{H5^@np##H3vqI*$L;{7@A2z1Gpxtam%3g^VnBj55=|e-Ek6@47zyTNxtzhc5cd zg~MUZ(o)O9Y^AJkI5s9`L+nr77`P>*V{Yj)01t_%a+I8KLkX=}nHD&il84AoPDw-# z21iG8+?n2}OGp?TMe&HDqDFzJexW>?s`s9BTl9TdrN?;{CKT;Fl19NAd!%%F;+P+Y zZX@*+Vq7f=kPR_l&CfY4A{c)$({zSsFgq>ZPmhcoX_5nobVz7ug~1B}$1!a^1ztv8 zR$4|A02?5aie;RF8ugjRd=sF$>junN3F$#!CesG&YQ!W5UY?CP$s#_Q`uRoV0qaWy z2U7j`>|8uE<1;o64(*N%h{Lg;u$jxyxT(Aorb&tCUS9+QTF2It5w=?8|K?yAkZ8E?8_7yF`o!oDeBl{is;jD&ekB#$wQh-G)53-3 z%Jgcze;iKGv|lrm@nmIXrM}(B?|q0R7Ba5uTpQSmYG>=sp{BogSJ4Ar=&g`iYhuJU-Ize{UH-FarFAc<)Ild&rAI1u zmOOZKhu`D*DSXZ#`g0+@ xXQYo=+oG!cO65tZ4oF@TT@aMD0#2=Q)CL|#6CoiocRUv5<^grPz@o@kE diff --git a/ros1_ign_gazebo_demos/launch/depth_camera.launch b/ros1_ign_gazebo_demos/launch/depth_camera.launch index 2b63afe9..e60fa396 100644 --- a/ros1_ign_gazebo_demos/launch/depth_camera.launch +++ b/ros1_ign_gazebo_demos/launch/depth_camera.launch @@ -2,7 +2,7 @@ - + + + diff --git a/ros1_ign_gazebo_demos/rviz/depth_camera.rviz b/ros1_ign_gazebo_demos/rviz/depth_camera.rviz new file mode 100644 index 00000000..6957e15f --- /dev/null +++ b/ros1_ign_gazebo_demos/rviz/depth_camera.rviz @@ -0,0 +1,147 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Image1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 423 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /depth_camera + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Flat Squares + Topic: /depth_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.307931423187256 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.024829570204019547 + Y: -0.440496027469635 + Z: 1.0747597217559814 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3397971391677856 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.723598957061768 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 568 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001e2fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610000000272000000c1000000000000000000000001000001b8000001e2fc0200000006fb0000000a0049006d006100670065010000003b000001e20000001600fffffffb0000000c00430061006d00650072006100000001ae000001850000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000196000001e200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 405 + Y: 378 diff --git a/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz b/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz index 73425318..9161d0c8 100644 --- a/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz +++ b/ros1_ign_gazebo_demos/rviz/gpu_lidar.rviz @@ -141,25 +141,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 4.168473243713379 + Distance: 10.596034049987793 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 1.9921716451644897 - Y: -0.8546587228775024 - Z: 0.7135224342346191 + X: 1.855783224105835 + Y: -0.6233639717102051 + Z: 0.7489486932754517 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5852028727531433 + Pitch: 0.5402030348777771 Target Frame: Value: Orbit (rviz) - Yaw: 3.5535941123962402 + Yaw: 3.7535903453826904 Saved: ~ Window Geometry: Displays: diff --git a/ros1_ign_point_cloud/examples/depth_camera.sdf b/ros1_ign_point_cloud/examples/depth_camera.sdf new file mode 100644 index 00000000..27fbf207 --- /dev/null +++ b/ros1_ign_point_cloud/examples/depth_camera.sdf @@ -0,0 +1,316 @@ + + + + + + 0.001 + 1.0 + + + + + ogre2 + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + /world/ros1_ign/control + /world/ros1_ign/stats + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + /world/ros1_ign/stats + + + + + docked + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 20 20 0.1 + + + + + + + 20 20 0.1 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 -1 0.5 0 0 0.7 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 3 0 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 0.2 + + + + + + + + 0.2 + + + + 1 1 0 1 + 1 1 0 1 + 1 1 0 1 + + + + + + + 5 0 0.5 0 0.0 3.14 + + 0.05 0.05 0.05 0 0 0 + + 0.1 + + 0.000166667 + 0.000166667 + 0.000166667 + + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1.047 + + 320 + 240 + R_FLOAT32 + + + 0.1 + 100 + + + 1 + 10 + true + depth_camera + + points + map + + + + + + + 9 0 0.5 0 0.0 3.14 + true + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + + + 0 1 3 0.0 0.0 1.57 + + https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Construction Cone + + + + + diff --git a/ros1_ign_point_cloud/examples/gpu_lidar.sdf b/ros1_ign_point_cloud/examples/gpu_lidar.sdf index 1a8f514f..8a4eff19 100644 --- a/ros1_ign_point_cloud/examples/gpu_lidar.sdf +++ b/ros1_ign_point_cloud/examples/gpu_lidar.sdf @@ -1,7 +1,6 @@ @@ -267,10 +263,10 @@ 1.396263 - 1 - 0.01 - 0 - 0 + 16 + 1 + -0.261799 + 0.261799 diff --git a/ros1_ign_point_cloud/src/point_cloud.cc b/ros1_ign_point_cloud/src/point_cloud.cc index 15a5669d..8b4abef4 100644 --- a/ros1_ign_point_cloud/src/point_cloud.cc +++ b/ros1_ign_point_cloud/src/point_cloud.cc @@ -233,13 +233,17 @@ void PointCloudPrivate::LoadDepthCamera( // Sensor name scoped from the model auto sensor_name = ignition::gazebo::scopedName(this->entity_, _ecm, "::", false); - sensor_name = sensor_name.substr(sensor_name.find("::") + 2) + "_depth"; + sensor_name = sensor_name.substr(sensor_name.find("::") + 2); // Get sensor - auto sensor = this->scene_->SensorByName(sensor_name); + auto sensor = this->scene_->SensorByName(sensor_name + "_depth"); if (!sensor) { - return; + sensor = this->scene_->SensorByName(sensor_name); + if (!sensor) + { + return; + } } this->depth_camera_ = @@ -376,7 +380,7 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, { this->rgb_camera_->Capture(this->rgb_image_); fillImage(this->rgb_image_msg_, sensor_msgs::image_encodings::RGB8, _height, - _width, 3 * _width, this->rgb_image_.Data()); + _width, _channels * _width, this->rgb_image_.Data()); } // For depth calculation from image @@ -418,17 +422,20 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, if (fl > 0 && _height > 1) p_angle = atan2((double)j - 0.5 * (double)(_height-1), fl); + if (nullptr != this->gpu_rays_) + { + azimuth = this->gpu_rays_->AngleMin().Radian(); + } for (uint32_t i = 0; i < _width; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b) { // Index of current point auto index = j * _width * _channels + i * _channels; + double depth = _scan[index]; double y_angle{0.0}; if (fl > 0 && _width > 1) y_angle = atan2((double)i - 0.5 * (double)(_width-1), fl); - double depth = _scan[index]; - if (nullptr != this->depth_camera_) { // in optical frame From 7feb0b4a5178fbc70a9e4e0182896f7e1b082cc6 Mon Sep 17 00:00:00 2001 From: chapulina Date: Tue, 25 Jun 2019 06:41:04 -0700 Subject: [PATCH 4/4] fix RGBD's color --- ros1_ign_point_cloud/src/point_cloud.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ros1_ign_point_cloud/src/point_cloud.cc b/ros1_ign_point_cloud/src/point_cloud.cc index 8b4abef4..1627add0 100644 --- a/ros1_ign_point_cloud/src/point_cloud.cc +++ b/ros1_ign_point_cloud/src/point_cloud.cc @@ -380,7 +380,7 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, { this->rgb_camera_->Capture(this->rgb_image_); fillImage(this->rgb_image_msg_, sensor_msgs::image_encodings::RGB8, _height, - _width, _channels * _width, this->rgb_image_.Data()); + _width, 3 * _width, this->rgb_image_.Data()); } // For depth calculation from image @@ -471,9 +471,9 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, if (this->rgb_image_msg_.data.size() == _height * _width * 3) { // color - *iter_r = image_src[index+0]; - *iter_g = image_src[index+1]; - *iter_b = image_src[index+2]; + *iter_r = image_src[i*3+j*_width*3+0]; + *iter_g = image_src[i*3+j*_width*3+1]; + *iter_b = image_src[i*3+j*_width*3+2]; } else if (this->rgb_image_msg_.data.size() == _height*_width) {