From 23fd1ea9500aea9c9330b5074132f00be5683395 Mon Sep 17 00:00:00 2001 From: Jeremy Zoss Date: Thu, 30 Aug 2018 07:15:07 -0500 Subject: [PATCH] Update advanced exercises - update CMakeLists/package.xml to latest templates - clean up minor whitespace inconsistencies - fix misc warnings (e.g. Eigen3, missing xacro: prefix) - move Perception to Exercise 5.1, to match wiki - Move STOMP to Exercise 5.2, to match wiki - add new Exercise 5.4: python/OpenCV - update instructions for Ex 5.0, 5.1, 5.4, 6.1 --- .../5.0/src/myworkcell_core/CMakeLists.txt | 43 +- exercises/5.0/src/myworkcell_core/package.xml | 79 ++- .../src/adv_descartes_node.cpp | 11 +- .../myworkcell_core/src/descartes_node.cpp | 14 +- .../myworkcell_core/src/myworkcell_node.cpp | 14 +- .../src/myworkcell_core/src/vision_node.cpp | 78 +-- .../myworkcell_moveit_config/.setup_assistant | 1 + .../config/controllers.yaml | 2 +- .../config/fake_controllers.yaml | 8 + .../config/joint_names.yaml | 2 +- .../config/kinematics.yaml | 5 + .../config/myworkcell.srdf | 8 +- .../config/ompl_planning.yaml | 31 +- .../launch/demo.launch | 14 +- .../launch/joystick_control.launch | 2 +- .../launch/moveit_rviz.launch | 2 +- .../myworkcell_planning_execution.launch | 47 +- .../launch/ompl_planning_pipeline.launch.xml | 2 +- .../launch/planning_context.launch | 6 +- .../launch/planning_pipeline.launch.xml | 4 +- .../launch/run_benchmark_ompl.launch | 2 +- .../launch/sensor_manager.launch.xml | 4 +- .../launch/setup_assistant.launch | 2 +- .../launch/trajectory_execution.launch.xml | 6 +- .../launch/warehouse.launch | 4 +- .../launch/warehouse_settings.launch.xml | 8 +- .../src/myworkcell_moveit_config/package.xml | 1 + .../5.0/src/myworkcell_support/CMakeLists.txt | 14 +- .../myworkcell_support/launch/setup.launch | 19 +- .../myworkcell_support/launch/workcell.launch | 4 +- .../5.0/src/myworkcell_support/package.xml | 23 +- .../myworkcell_support/urdf/workcell.xacro | 21 +- .../src/ur10_demo_descartes/CMakeLists.txt | 6 +- .../5.0/src/ur5_demo_descartes/CMakeLists.txt | 6 +- .../src/lesson_perception/CMakeLists.txt | 0 .../launch/processing_node.launch | 6 +- .../src/lesson_perception/package.xml | 0 .../lesson_perception/src/perception_node.cpp | 324 +++++++++++ .../src/lesson_perception/CMakeLists.txt | 1 + .../src/lesson_perception/package.xml | 2 + .../lesson_perception/src/perception_node.cpp | 25 +- .../launch/lesson_perception.rviz | 237 -------- .../lesson_perception/src/perception_node.cpp | 371 ------------- .../myworkcell_moveit_config/.setup_assistant | 0 .../myworkcell_moveit_config/CMakeLists.txt | 0 .../config/fake_controllers.yaml | 0 .../config/joint_limits.yaml | 0 .../config/kinematics.yaml | 0 .../config/myworkcell.srdf | 0 .../config/ompl_planning.yaml | 0 .../config/stomp_config.yaml | 0 .../launch/default_warehouse_db.launch | 0 .../launch/demo.launch | 0 .../fake_moveit_controller_manager.launch.xml | 0 .../launch/joystick_control.launch | 0 .../launch/move_group.launch | 0 .../launch/moveit.rviz | 0 .../launch/moveit_rviz.launch | 0 ...kcell_moveit_controller_manager.launch.xml | 0 ...yworkcell_moveit_sensor_manager.launch.xml | 0 .../launch/ompl_planning_pipeline.launch.xml | 0 .../launch/planning_context.launch | 0 .../launch/planning_pipeline.launch.xml | 0 .../launch/run_benchmark_ompl.launch | 0 .../launch/sensor_manager.launch.xml | 0 .../launch/setup_assistant.launch | 0 .../launch/stomp_planning_pipeline.launch.xml | 0 .../launch/trajectory_execution.launch.xml | 0 .../launch/warehouse.launch | 0 .../launch/warehouse_settings.launch.xml | 0 .../src/myworkcell_moveit_config/package.xml | 0 .../src/myworkcell_support/CMakeLists.txt | 0 .../launch/view_urdf.launch | 0 .../src/myworkcell_support/package.xml | 0 .../myworkcell_support/rviz/myworkcell.rviz | 0 .../myworkcell_support/urdf/myworkcell.xacro | 0 exercises/5.4/detect_pump/CMakeLists.txt | 198 +++++++ .../5.4/detect_pump/nodes/detect_pump.py | 133 +++++ exercises/5.4/detect_pump/nodes/image_pub.py | 39 ++ exercises/5.4/detect_pump/package.xml | 65 +++ exercises/5.4/pump.jpg | Bin 0 -> 309489 bytes .../src/myworkcell_core/src/test/utest.cpp | 27 +- .../Advanced-Descartes-Path-Planning.md | 102 ++-- .../Building-a-Perception-Pipeline.rst | 377 ++----------- gh_pages/_source/session5/OpenCV-in-Python.md | 516 ++++++++++++++++++ gh_pages/_source/session6/Unit-Testing.rst | 43 +- gh_pages/index.rst | 1 + 87 files changed, 1703 insertions(+), 1257 deletions(-) rename exercises/{5.2 => 5.1/solution_ws}/src/lesson_perception/CMakeLists.txt (100%) rename exercises/{5.2 => 5.1/solution_ws}/src/lesson_perception/launch/processing_node.launch (87%) rename exercises/{5.2 => 5.1/solution_ws}/src/lesson_perception/package.xml (100%) create mode 100644 exercises/5.1/solution_ws/src/lesson_perception/src/perception_node.cpp rename exercises/{perception_ws => 5.1/template_ws}/src/lesson_perception/CMakeLists.txt (99%) rename exercises/{perception_ws => 5.1/template_ws}/src/lesson_perception/package.xml (96%) rename exercises/{perception_ws => 5.1/template_ws}/src/lesson_perception/src/perception_node.cpp (97%) delete mode 100644 exercises/5.2/src/lesson_perception/launch/lesson_perception.rviz delete mode 100644 exercises/5.2/src/lesson_perception/src/perception_node.cpp rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/.setup_assistant (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/CMakeLists.txt (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/config/fake_controllers.yaml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/config/joint_limits.yaml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/config/kinematics.yaml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/config/myworkcell.srdf (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/config/ompl_planning.yaml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/config/stomp_config.yaml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/default_warehouse_db.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/demo.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/joystick_control.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/move_group.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/moveit.rviz (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/moveit_rviz.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/myworkcell_moveit_controller_manager.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/myworkcell_moveit_sensor_manager.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/planning_context.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/setup_assistant.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/stomp_planning_pipeline.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/warehouse.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_moveit_config/package.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_support/CMakeLists.txt (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_support/launch/view_urdf.launch (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_support/package.xml (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_support/rviz/myworkcell.rviz (100%) rename exercises/{5.1 => 5.2}/src/myworkcell_support/urdf/myworkcell.xacro (100%) create mode 100644 exercises/5.4/detect_pump/CMakeLists.txt create mode 100755 exercises/5.4/detect_pump/nodes/detect_pump.py create mode 100755 exercises/5.4/detect_pump/nodes/image_pub.py create mode 100644 exercises/5.4/detect_pump/package.xml create mode 100644 exercises/5.4/pump.jpg create mode 100644 gh_pages/_source/session5/OpenCV-in-Python.md diff --git a/exercises/5.0/src/myworkcell_core/CMakeLists.txt b/exercises/5.0/src/myworkcell_core/CMakeLists.txt index 4793d23c7..39210cf5e 100644 --- a/exercises/5.0/src/myworkcell_core/CMakeLists.txt +++ b/exercises/5.0/src/myworkcell_core/CMakeLists.txt @@ -1,8 +1,8 @@ cmake_minimum_required(VERSION 2.8.3) project(myworkcell_core) -## Add support for C++11, supported in ROS Kinetic and newer -add_definitions(-std=c++11) +## Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++11) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) @@ -41,10 +41,10 @@ find_package(catkin REQUIRED COMPONENTS ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). ## * In the file package.xml: ## * add a build_depend tag for "message_generation" -## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in ## but can be declared for certainty nonetheless: -## * add a run_depend tag for "message_runtime" +## * add a exec_depend tag for "message_runtime" ## * In this file (CMakeLists.txt): ## * add "message_generation" and every package in MSG_DEP_SET to ## find_package(catkin REQUIRED COMPONENTS ...) @@ -79,7 +79,7 @@ add_service_files( ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES - geometry_msgs + geometry_msgs # Or other packages containing msgs trajectory_msgs ) @@ -90,7 +90,7 @@ generate_messages( ## To declare and build dynamic reconfigure parameters within this ## package, follow these steps: ## * In the file package.xml: -## * add a build_depend and a run_depend tag for "dynamic_reconfigure" +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" ## * In this file (CMakeLists.txt): ## * add "dynamic_reconfigure" to ## find_package(catkin REQUIRED COMPONENTS ...) @@ -108,26 +108,26 @@ generate_messages( ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if you package contains header files +## INCLUDE_DIRS: uncomment this if your package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include # LIBRARIES myworkcell_core - CATKIN_DEPENDS - roscpp - fake_ar_publisher - message_runtime - geometry_msgs - tf - moveit_ros_planning_interface - ur5_demo_descartes - descartes_trajectory - descartes_planner - descartes_utilities - trajectory_msgs - tf_conversions + CATKIN_DEPENDS + roscpp + fake_ar_publisher + message_runtime + geometry_msgs + tf + moveit_ros_planning_interface + ur5_demo_descartes + descartes_trajectory + descartes_planner + descartes_utilities + trajectory_msgs + tf_conversions # DEPENDS system_lib ) @@ -137,8 +137,8 @@ catkin_package( ## Specify additional locations of header files ## Your package locations should be listed before other locations -# include_directories(include) include_directories( +# include ${catkin_INCLUDE_DIRS} ) @@ -182,7 +182,6 @@ target_link_libraries(descartes_node ${catkin_LIBRARIES}) target_link_libraries(adv_descartes_node ${catkin_LIBRARIES}) target_link_libraries(adv_myworkcell_node ${catkin_LIBRARIES}) - ############# ## Install ## ############# diff --git a/exercises/5.0/src/myworkcell_core/package.xml b/exercises/5.0/src/myworkcell_core/package.xml index 9dc42a2e2..dae520abf 100644 --- a/exercises/5.0/src/myworkcell_core/package.xml +++ b/exercises/5.0/src/myworkcell_core/package.xml @@ -1,37 +1,70 @@ - + myworkcell_core 0.0.0 The myworkcell_core package + + + + ros-industrial + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin roscpp - roscpp - fake_ar_publisher - fake_ar_publisher + roscpp + roscpp + fake_ar_publisher message_generation - message_runtime - geometry_msgs - geometry_msgs - tf - tf - moveit_ros_planning_interface - moveit_ros_planning_interface - ur5_demo_descartes - ur5_demo_descartes - descartes_trajectory - descartes_trajectory - descartes_planner - descartes_planner - descartes_utilities - descartes_utilities - trajectory_msgs - trajectory_msgs - tf_conversions - tf_conversions + message_runtime + geometry_msgs + tf + moveit_ros_planning_interface + ur5_demo_descartes + descartes_trajectory + descartes_planner + descartes_utilities + trajectory_msgs + tf_conversions + diff --git a/exercises/5.0/src/myworkcell_core/src/adv_descartes_node.cpp b/exercises/5.0/src/myworkcell_core/src/adv_descartes_node.cpp index aa0b59116..c8116fb20 100644 --- a/exercises/5.0/src/myworkcell_core/src/adv_descartes_node.cpp +++ b/exercises/5.0/src/myworkcell_core/src/adv_descartes_node.cpp @@ -25,7 +25,7 @@ std::vector getCurrentJointState(const std::string& topic) EigenSTL::vector_Affine3d makeLine(const Eigen::Vector3d& start, const Eigen::Vector3d& stop, double ds) { EigenSTL::vector_Affine3d line; - + const Eigen::Vector3d travel = stop - start; const int steps = std::floor(travel.norm() / ds); @@ -61,7 +61,7 @@ class CartesianPlanner { // Create a robot model model_ = boost::make_shared(); - + // Define the relevant "frames" const std::string robot_description = "robot_description"; const std::string group_name = "puzzle"; @@ -127,7 +127,8 @@ class CartesianPlanner EigenSTL::vector_Affine3d path; std::ifstream indata; - std::string filename = ros::package::getPath("myworkcell_core") + "/config/puzzle_bent.csv"; + std::string packagePath = ros::package::getPath("myworkcell_core"); + std::string filename = packagePath + "/config/puzzle_bent.csv"; indata.open(filename); @@ -232,8 +233,8 @@ class CartesianPlanner { auto p = point; TolerancedFrame tool_pt(p); - tool_pt.orientation_tolerance.z_lower -= M_PI; - tool_pt.orientation_tolerance.z_upper += M_PI; + tool_pt.orientation_tolerance.z_lower = -M_PI; + tool_pt.orientation_tolerance.z_upper = +M_PI; boost::shared_ptr pt(new CartTrajectoryPt(wobj_base, wobj_pt, tool_base, tool_pt, 0, M_PI/20.0)); descartes_path.push_back(pt); diff --git a/exercises/5.0/src/myworkcell_core/src/descartes_node.cpp b/exercises/5.0/src/myworkcell_core/src/descartes_node.cpp index a69f16af3..8a3f39a25 100644 --- a/exercises/5.0/src/myworkcell_core/src/descartes_node.cpp +++ b/exercises/5.0/src/myworkcell_core/src/descartes_node.cpp @@ -117,21 +117,21 @@ class CartesianPlanner // We assume that our path is centered at (0, 0, 0), so let's define the // corners of the AR marker - const double side_length = 0.25; // All units are in meters (M) + const double side_length = 0.08; // All units are in meters (M) const double half_side = side_length / 2.0; const double step_size = 0.02; - Eigen::Vector3d top_left (half_side, half_side, 0); - Eigen::Vector3d bot_left (-half_side, half_side, 0); - Eigen::Vector3d bot_right (-half_side, -half_side, 0); - Eigen::Vector3d top_right (half_side, -half_side, 0); + Eigen::Vector3d top_left (-half_side, half_side, 0); + Eigen::Vector3d bot_left (-half_side, -half_side, 0); + Eigen::Vector3d bot_right (half_side, -half_side, 0); + Eigen::Vector3d top_right (half_side, half_side, 0); // Descartes requires you to guide it in how dense the points should be, // so you have to do your own "discretization". // NOTE that the makeLine function will create a sequence of points inclusive // of the start and exclusive of finish point, i.e. line = [start, stop) - // Create cartesian path from line-segments + // TODO: Add the rest of the cartesian path auto segment1 = makeLine(top_left, bot_left, step_size); auto segment2 = makeLine(bot_left, bot_right, step_size); auto segment3 = makeLine(bot_right, top_right, step_size); @@ -156,7 +156,7 @@ class CartesianPlanner for (auto& point : path) { - // Create a Descartes "cartesian" point with some kind of constraints + // TODO: make a Descartes "cartesian" point with some kind of constraints descartes_core::TrajectoryPtPtr pt = makeTolerancedCartesianPoint(ref * point); descartes_path.push_back(pt); } diff --git a/exercises/5.0/src/myworkcell_core/src/myworkcell_node.cpp b/exercises/5.0/src/myworkcell_core/src/myworkcell_node.cpp index ad258ede7..50300867b 100644 --- a/exercises/5.0/src/myworkcell_core/src/myworkcell_node.cpp +++ b/exercises/5.0/src/myworkcell_core/src/myworkcell_node.cpp @@ -18,7 +18,6 @@ class ScanNPlan void start(const std::string& base_frame) { ROS_INFO("Attempting to localize part"); - // Localize the part myworkcell_core::LocalizePart srv; srv.request.base_frame = base_frame; @@ -32,9 +31,10 @@ class ScanNPlan ROS_INFO_STREAM("part localized: " << srv.response); geometry_msgs::Pose move_target = srv.response.pose; + moveit::planning_interface::MoveGroupInterface move_group("manipulator"); // Plan for robot to move to part - moveit::planning_interface::MoveGroupInterface move_group("manipulator"); + move_group.setPoseReferenceFrame(base_frame); move_group.setPoseTarget(move_target); move_group.move(); @@ -67,8 +67,9 @@ int main(int argc, char **argv) { ros::init(argc, argv, "myworkcell_node"); ros::NodeHandle nh; - ros::NodeHandle private_node_handle("~"); - ros::AsyncSpinner async_spinner (1); + ros::NodeHandle private_node_handle ("~"); + ros::AsyncSpinner async_spinner(1); + async_spinner.start(); ROS_INFO("ScanNPlan node has been initialized"); @@ -76,12 +77,9 @@ int main(int argc, char **argv) private_node_handle.param("base_frame", base_frame, "world"); // parameter name, string object reference, default value ScanNPlan app(nh); - ros::Duration(.5).sleep(); // wait for the class to initialize - async_spinner.start(); + ros::Duration(.5).sleep(); // wait for the class to initialize app.start(base_frame); - ROS_INFO("ScanNPlan node has been initialized"); - ros::waitForShutdown(); } diff --git a/exercises/5.0/src/myworkcell_core/src/vision_node.cpp b/exercises/5.0/src/myworkcell_core/src/vision_node.cpp index abcff5f5e..b779917ba 100644 --- a/exercises/5.0/src/myworkcell_core/src/vision_node.cpp +++ b/exercises/5.0/src/myworkcell_core/src/vision_node.cpp @@ -9,59 +9,59 @@ class Localizer { public: - Localizer(ros::NodeHandle& nh) - { - ar_sub_ = nh.subscribe("ar_pose_marker", 1, - &Localizer::visionCallback, this); + Localizer(ros::NodeHandle& nh) + { + ar_sub_ = nh.subscribe("ar_pose_marker", 1, + &Localizer::visionCallback, this); - server_ = nh.advertiseService("localize_part", &Localizer::localizePart, this); - } + server_ = nh.advertiseService("localize_part", &Localizer::localizePart, this); + } - void visionCallback(const fake_ar_publisher::ARMarkerConstPtr& msg) - { - last_msg_ = msg; - //ROS_INFO_STREAM(last_msg_->pose.pose); - } + void visionCallback(const fake_ar_publisher::ARMarkerConstPtr& msg) + { + last_msg_ = msg; + //ROS_INFO_STREAM(last_msg_->pose.pose); + } - bool localizePart(myworkcell_core::LocalizePart::Request& req, - myworkcell_core::LocalizePart::Response& res) - { - // Read last message - fake_ar_publisher::ARMarkerConstPtr p = last_msg_; - if (!p) return false; + bool localizePart(myworkcell_core::LocalizePart::Request& req, + myworkcell_core::LocalizePart::Response& res) + { + // Read last message + fake_ar_publisher::ARMarkerConstPtr p = last_msg_; + if (!p) return false; - tf::Transform cam_to_target; - tf::poseMsgToTF(p->pose.pose, cam_to_target); + tf::Transform cam_to_target; + tf::poseMsgToTF(p->pose.pose, cam_to_target); - tf::StampedTransform req_to_cam; - listener_.lookupTransform(req.base_frame, p->header.frame_id, ros::Time(0), req_to_cam); + tf::StampedTransform req_to_cam; + listener_.lookupTransform(req.base_frame, p->header.frame_id, ros::Time(0), req_to_cam); - tf::Transform req_to_target; - req_to_target = req_to_cam * cam_to_target; + tf::Transform req_to_target; + req_to_target = req_to_cam * cam_to_target; - tf::poseTFToMsg(req_to_target, res.pose); - return true; - } + tf::poseTFToMsg(req_to_target, res.pose); + return true; + } - ros::Subscriber ar_sub_; - fake_ar_publisher::ARMarkerConstPtr last_msg_; - ros::ServiceServer server_; - tf::TransformListener listener_; + ros::Subscriber ar_sub_; + fake_ar_publisher::ARMarkerConstPtr last_msg_; + ros::ServiceServer server_; + tf::TransformListener listener_; }; int main(int argc, char* argv[]) { - // This must be called before anything else ROS-related - ros::init(argc, argv, "vision_node"); + // This must be called before anything else ROS-related + ros::init(argc, argv, "vision_node"); - // Create a ROS node handle - ros::NodeHandle nh; + // Create a ROS node handle + ros::NodeHandle nh; - // The Localizer class provides this node's ROS interfaces - Localizer localizer(nh); + // The Localizer class provides this node's ROS interfaces + Localizer localizer(nh); - ROS_INFO("Vision node starting"); + ROS_INFO("Vision node starting"); - // Don't exit the program. - ros::spin(); + // Don't exit the program. + ros::spin(); } diff --git a/exercises/5.0/src/myworkcell_moveit_config/.setup_assistant b/exercises/5.0/src/myworkcell_moveit_config/.setup_assistant index 372315205..2f37a29d2 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/.setup_assistant +++ b/exercises/5.0/src/myworkcell_moveit_config/.setup_assistant @@ -2,6 +2,7 @@ moveit_setup_assistant_config: URDF: package: myworkcell_support relative_path: urdf/workcell.xacro + xacro_args: "--inorder " SRDF: relative_path: config/myworkcell.srdf CONFIG: diff --git a/exercises/5.0/src/myworkcell_moveit_config/config/controllers.yaml b/exercises/5.0/src/myworkcell_moveit_config/config/controllers.yaml index 6e8ef19f7..a2479ff01 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/config/controllers.yaml +++ b/exercises/5.0/src/myworkcell_moveit_config/config/controllers.yaml @@ -2,4 +2,4 @@ controller_list: - name: "" action_ns: joint_trajectory_action type: FollowJointTrajectory - joints: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] \ No newline at end of file + joints: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] diff --git a/exercises/5.0/src/myworkcell_moveit_config/config/fake_controllers.yaml b/exercises/5.0/src/myworkcell_moveit_config/config/fake_controllers.yaml index a7300cf48..470ad88c3 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/config/fake_controllers.yaml +++ b/exercises/5.0/src/myworkcell_moveit_config/config/fake_controllers.yaml @@ -1,5 +1,13 @@ controller_list: - name: fake_manipulator_controller + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + - name: fake_puzzle_controller joints: - shoulder_pan_joint - shoulder_lift_joint diff --git a/exercises/5.0/src/myworkcell_moveit_config/config/joint_names.yaml b/exercises/5.0/src/myworkcell_moveit_config/config/joint_names.yaml index dce3623f7..11bd6762f 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/config/joint_names.yaml +++ b/exercises/5.0/src/myworkcell_moveit_config/config/joint_names.yaml @@ -1 +1 @@ -controller_joint_names: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] \ No newline at end of file +controller_joint_names: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] diff --git a/exercises/5.0/src/myworkcell_moveit_config/config/kinematics.yaml b/exercises/5.0/src/myworkcell_moveit_config/config/kinematics.yaml index 969ba1425..5e9d57ce7 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/config/kinematics.yaml +++ b/exercises/5.0/src/myworkcell_moveit_config/config/kinematics.yaml @@ -1,4 +1,9 @@ manipulator: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 +puzzle: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005 diff --git a/exercises/5.0/src/myworkcell_moveit_config/config/myworkcell.srdf b/exercises/5.0/src/myworkcell_moveit_config/config/myworkcell.srdf index 3ee2945c6..ba7d13f1b 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/config/myworkcell.srdf +++ b/exercises/5.0/src/myworkcell_moveit_config/config/myworkcell.srdf @@ -12,7 +12,6 @@ - @@ -39,8 +38,6 @@ - - @@ -54,14 +51,11 @@ - - + - - diff --git a/exercises/5.0/src/myworkcell_moveit_config/config/ompl_planning.yaml b/exercises/5.0/src/myworkcell_moveit_config/config/ompl_planning.yaml index 4dc5746f8..5a93de273 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/config/ompl_planning.yaml +++ b/exercises/5.0/src/myworkcell_moveit_config/config/ompl_planning.yaml @@ -121,6 +121,7 @@ planner_configs: dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 max_failures: 5000 # maximum consecutive failure limit. default: 5000 manipulator: + default_planner_config: NonekConfigDefault planner_configs: - SBLkConfigDefault - ESTkConfigDefault @@ -146,4 +147,32 @@ manipulator: - SPARSkConfigDefault - SPARStwokConfigDefault projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) - longest_valid_segment_fraction: 0.005 \ No newline at end of file + longest_valid_segment_fraction: 0.005 +puzzle: + default_planner_config: NonekConfigDefault + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) + longest_valid_segment_fraction: 0.005 diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/demo.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/demo.launch index 0fbfd476a..ff5aebe5b 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/demo.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/demo.launch @@ -8,6 +8,16 @@ + + + @@ -18,8 +28,8 @@ - - [/move_group/fake_controller_joint_states] + + [move_group/fake_controller_joint_states] diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/joystick_control.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/joystick_control.launch index f74173527..9411f6e60 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/joystick_control.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/joystick_control.launch @@ -13,5 +13,5 @@ - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/moveit_rviz.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/moveit_rviz.launch index e70fabf89..222f1ab53 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/moveit_rviz.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/moveit_rviz.launch @@ -7,7 +7,7 @@ - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/myworkcell_planning_execution.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/myworkcell_planning_execution.launch index cd8466f0c..524adb168 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/myworkcell_planning_execution.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/myworkcell_planning_execution.launch @@ -1,17 +1,4 @@ - - - - - - - - - - - - - - + @@ -22,39 +9,37 @@ - and uncomment the following line: --> + + + + + - + - - - + + - - - - - - - - - - - - + + + - + + + + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml b/exercises/5.0/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml index f3dc28191..6a23df4c7 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -3,7 +3,7 @@ - - + - + @@ -20,5 +20,5 @@ - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml b/exercises/5.0/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml index 8f70792dd..9996548af 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch index 07efe1263..09ef8af4f 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch @@ -11,7 +11,7 @@ - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml b/exercises/5.0/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml index e4bbdc326..02b00a51a 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml @@ -1,6 +1,6 @@ - + @@ -10,5 +10,5 @@ - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/setup_assistant.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/setup_assistant.launch index 85d597262..112b0f1e9 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/setup_assistant.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/setup_assistant.launch @@ -7,7 +7,7 @@ - diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml b/exercises/5.0/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml index 430ce2f2c..a40b25f9f 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml @@ -1,6 +1,6 @@ - + @@ -12,9 +12,9 @@ - + - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse.launch b/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse.launch index ee814adcb..4d163e27c 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse.launch +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse.launch @@ -1,9 +1,9 @@ - + - + diff --git a/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml b/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml index 967e0ff4d..e473b083b 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml +++ b/exercises/5.0/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml @@ -1,12 +1,12 @@ - - + + - - + + diff --git a/exercises/5.0/src/myworkcell_moveit_config/package.xml b/exercises/5.0/src/myworkcell_moveit_config/package.xml index 11538d364..f9573d757 100644 --- a/exercises/5.0/src/myworkcell_moveit_config/package.xml +++ b/exercises/5.0/src/myworkcell_moveit_config/package.xml @@ -17,6 +17,7 @@ catkin moveit_ros_move_group + moveit_fake_controller_manager moveit_kinematics moveit_planners_ompl moveit_ros_visualization diff --git a/exercises/5.0/src/myworkcell_support/CMakeLists.txt b/exercises/5.0/src/myworkcell_support/CMakeLists.txt index 42505d9f3..b94eb41af 100644 --- a/exercises/5.0/src/myworkcell_support/CMakeLists.txt +++ b/exercises/5.0/src/myworkcell_support/CMakeLists.txt @@ -1,8 +1,8 @@ cmake_minimum_required(VERSION 2.8.3) project(myworkcell_support) -## Add support for C++11, supported in ROS Kinetic and newer -# add_definitions(-std=c++11) +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) @@ -30,10 +30,10 @@ find_package(catkin REQUIRED COMPONENTS ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). ## * In the file package.xml: ## * add a build_depend tag for "message_generation" -## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in ## but can be declared for certainty nonetheless: -## * add a run_depend tag for "message_runtime" +## * add a exec_depend tag for "message_runtime" ## * In this file (CMakeLists.txt): ## * add "message_generation" and every package in MSG_DEP_SET to ## find_package(catkin REQUIRED COMPONENTS ...) @@ -78,7 +78,7 @@ find_package(catkin REQUIRED COMPONENTS ## To declare and build dynamic reconfigure parameters within this ## package, follow these steps: ## * In the file package.xml: -## * add a build_depend and a run_depend tag for "dynamic_reconfigure" +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" ## * In this file (CMakeLists.txt): ## * add "dynamic_reconfigure" to ## find_package(catkin REQUIRED COMPONENTS ...) @@ -96,7 +96,7 @@ find_package(catkin REQUIRED COMPONENTS ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if you package contains header files +## INCLUDE_DIRS: uncomment this if your package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need @@ -113,8 +113,8 @@ catkin_package( ## Specify additional locations of header files ## Your package locations should be listed before other locations -# include_directories(include) include_directories( +# include ${catkin_INCLUDE_DIRS} ) diff --git a/exercises/5.0/src/myworkcell_support/launch/setup.launch b/exercises/5.0/src/myworkcell_support/launch/setup.launch index df2c2a03a..eccc254ad 100644 --- a/exercises/5.0/src/myworkcell_support/launch/setup.launch +++ b/exercises/5.0/src/myworkcell_support/launch/setup.launch @@ -1,23 +1,8 @@ - - - - - - - - + + - - - - - - - - - diff --git a/exercises/5.0/src/myworkcell_support/launch/workcell.launch b/exercises/5.0/src/myworkcell_support/launch/workcell.launch index f11ad2bf5..717abe47e 100644 --- a/exercises/5.0/src/myworkcell_support/launch/workcell.launch +++ b/exercises/5.0/src/myworkcell_support/launch/workcell.launch @@ -1,6 +1,6 @@ - - + + diff --git a/exercises/5.0/src/myworkcell_support/package.xml b/exercises/5.0/src/myworkcell_support/package.xml index e37dc8ee6..d6ec3de83 100644 --- a/exercises/5.0/src/myworkcell_support/package.xml +++ b/exercises/5.0/src/myworkcell_support/package.xml @@ -1,10 +1,10 @@ - + myworkcell_support 0.0.0 The myworkcell_support package - + ros-industrial @@ -28,20 +28,31 @@ - + + + + + + + + - - + + + + catkin myworkcell_core - myworkcell_core + myworkcell_core + myworkcell_core + diff --git a/exercises/5.0/src/myworkcell_support/urdf/workcell.xacro b/exercises/5.0/src/myworkcell_support/urdf/workcell.xacro index dfb952acb..623454123 100644 --- a/exercises/5.0/src/myworkcell_support/urdf/workcell.xacro +++ b/exercises/5.0/src/myworkcell_support/urdf/workcell.xacro @@ -1,10 +1,8 @@ - - - - + + @@ -23,7 +21,6 @@ - @@ -32,12 +29,6 @@ - - - - - - @@ -50,7 +41,13 @@ - + + + + + + + diff --git a/exercises/5.0/src/ur10_demo_descartes/CMakeLists.txt b/exercises/5.0/src/ur10_demo_descartes/CMakeLists.txt index e12fdaeb7..fda897516 100644 --- a/exercises/5.0/src/ur10_demo_descartes/CMakeLists.txt +++ b/exercises/5.0/src/ur10_demo_descartes/CMakeLists.txt @@ -7,7 +7,7 @@ find_package(catkin REQUIRED descartes_core descartes_moveit pluginlib moveit_co find_package(rosconsole_bridge REQUIRED) find_package(LAPACK REQUIRED) find_package(Boost REQUIRED) -find_package(Eigen REQUIRED) +find_package(Eigen3 REQUIRED) ################################### ## catkin specific configuration ## @@ -32,7 +32,7 @@ catkin_package( include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} - ${Eigen_INCLUDE_DIRS} + ${Eigen3_INCLUDE_DIRS} ) add_library(${PROJECT_NAME} @@ -42,7 +42,7 @@ add_library(${PROJECT_NAME} src/plugin_init.cpp) target_link_libraries(${PROJECT_NAME} - ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${Boost_LIBRARIES} ${LAPACK_LIBRARIES}) + ${catkin_LIBRARIES} ${Eigen3_LIBRARIES} ${Boost_LIBRARIES} ${LAPACK_LIBRARIES}) ############# ## Install ## diff --git a/exercises/5.0/src/ur5_demo_descartes/CMakeLists.txt b/exercises/5.0/src/ur5_demo_descartes/CMakeLists.txt index cea5ffdec..a1e8c6a37 100644 --- a/exercises/5.0/src/ur5_demo_descartes/CMakeLists.txt +++ b/exercises/5.0/src/ur5_demo_descartes/CMakeLists.txt @@ -7,7 +7,7 @@ find_package(catkin REQUIRED descartes_core descartes_moveit pluginlib moveit_co find_package(rosconsole_bridge REQUIRED) find_package(LAPACK REQUIRED) find_package(Boost REQUIRED) -find_package(Eigen REQUIRED) +find_package(Eigen3 REQUIRED) ################################### ## catkin specific configuration ## @@ -32,7 +32,7 @@ catkin_package( include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} - ${Eigen_INCLUDE_DIRS} + ${Eigen3_INCLUDE_DIRS} ) add_library(${PROJECT_NAME} @@ -42,7 +42,7 @@ add_library(${PROJECT_NAME} src/plugin_init.cpp) target_link_libraries(${PROJECT_NAME} - ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${Boost_LIBRARIES} ${LAPACK_LIBRARIES}) + ${catkin_LIBRARIES} ${Eigen3_LIBRARIES} ${Boost_LIBRARIES} ${LAPACK_LIBRARIES}) ############# ## Install ## diff --git a/exercises/5.2/src/lesson_perception/CMakeLists.txt b/exercises/5.1/solution_ws/src/lesson_perception/CMakeLists.txt similarity index 100% rename from exercises/5.2/src/lesson_perception/CMakeLists.txt rename to exercises/5.1/solution_ws/src/lesson_perception/CMakeLists.txt diff --git a/exercises/5.2/src/lesson_perception/launch/processing_node.launch b/exercises/5.1/solution_ws/src/lesson_perception/launch/processing_node.launch similarity index 87% rename from exercises/5.2/src/lesson_perception/launch/processing_node.launch rename to exercises/5.1/solution_ws/src/lesson_perception/launch/processing_node.launch index 7629a911c..ea7675ff4 100644 --- a/exercises/5.2/src/lesson_perception/launch/processing_node.launch +++ b/exercises/5.1/solution_ws/src/lesson_perception/launch/processing_node.launch @@ -1,7 +1,5 @@ - - - + cloud_topic: "kinect/depth_registered/points" world_frame: "world_frame" @@ -15,7 +13,7 @@ z_filter_max: 2.5 plane_max_iterations: 100 plane_distance_threshold: 0.03 - cluster_tolerance: 0.02 + cluster_tolerance: 0.01 cluster_min_size: 250 cluster_max_size: 500000 diff --git a/exercises/5.2/src/lesson_perception/package.xml b/exercises/5.1/solution_ws/src/lesson_perception/package.xml similarity index 100% rename from exercises/5.2/src/lesson_perception/package.xml rename to exercises/5.1/solution_ws/src/lesson_perception/package.xml diff --git a/exercises/5.1/solution_ws/src/lesson_perception/src/perception_node.cpp b/exercises/5.1/solution_ws/src/lesson_perception/src/perception_node.cpp new file mode 100644 index 000000000..254554656 --- /dev/null +++ b/exercises/5.1/solution_ws/src/lesson_perception/src/perception_node.cpp @@ -0,0 +1,324 @@ +#include +#include +#include +#include +#include //hydro + +// PCL specific includes +#include //hydro +#include "pcl_ros/transforms.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +int main(int argc, char *argv[]) +{ + /* + * INITIALIZE ROS NODE + */ + ros::init(argc, argv, "perception_node"); + ros::NodeHandle nh; + ros::NodeHandle priv_nh_("~"); + + /* + * SET UP PARAMETERS (COULD BE INPUT FROM LAUNCH FILE/TERMINAL) + */ + std::string cloud_topic, world_frame, camera_frame; + float voxel_leaf_size; + float x_filter_min, x_filter_max, y_filter_min, y_filter_max, z_filter_min, z_filter_max; + int plane_max_iter; + float plane_dist_thresh; + float cluster_tol; + int cluster_min_size; + int cluster_max_size; + cloud_topic = priv_nh_.param("cloud_topic", "kinect/depth_registered/points"); + world_frame = priv_nh_.param("world_frame", "kinect_link"); + camera_frame = priv_nh_.param("camera_frame", "kinect_link"); + voxel_leaf_size = priv_nh_.param("voxel_leaf_size", 0.002); + x_filter_min = priv_nh_.param("x_filter_min", -2.5); + x_filter_max = priv_nh_.param("x_filter_max", 2.5); + y_filter_min = priv_nh_.param("y_filter_min", -2.5); + y_filter_max = priv_nh_.param("y_filter_max", 2.5); + z_filter_min = priv_nh_.param("z_filter_min", -2.5); + z_filter_max = priv_nh_.param("z_filter_max", 2.5); + plane_max_iter = priv_nh_.param("plane_max_iterations", 50); + plane_dist_thresh = priv_nh_.param("plane_distance_threshold", 0.05); + cluster_tol = priv_nh_.param("cluster_tolerance", 0.01); + cluster_min_size = priv_nh_.param("cluster_min_size", 100); + cluster_max_size = priv_nh_.param("cluster_max_size", 50000); + + + + /* + * SETUP PUBLISHERS + */ + ros::Publisher object_pub, cluster_pub, pose_pub; + object_pub = nh.advertise("object_cluster", 1); + cluster_pub = nh.advertise("primary_cluster", 1); + + while (ros::ok()) + { + /* + * LISTEN FOR POINTCLOUD + */ + std::string topic = nh.resolveName(cloud_topic); + ROS_INFO_STREAM("Cloud service called; waiting for a PointCloud2 on topic "<< topic); + sensor_msgs::PointCloud2::ConstPtr recent_cloud = + ros::topic::waitForMessage(topic, nh); + + /* + * TRANSFORM POINTCLOUD FROM CAMERA FRAME TO WORLD FRAME + */ + tf::TransformListener listener; + tf::StampedTransform stransform; + try + { + listener.waitForTransform(world_frame, recent_cloud->header.frame_id, ros::Time::now(), ros::Duration(6.0)); + listener.lookupTransform(world_frame, recent_cloud->header.frame_id, ros::Time(0), stransform); + } + catch (tf::TransformException ex) + { + ROS_ERROR("%s",ex.what()); + } + sensor_msgs::PointCloud2 transformed_cloud; +// sensor_msgs::PointCloud2::ConstPtr recent_cloud = +// ros::topic::waitForMessage(topic, nh); + pcl_ros::transformPointCloud(world_frame, stransform, *recent_cloud, transformed_cloud); + + /* + * CONVERT POINTCLOUD ROS->PCL + */ + pcl::PointCloud cloud; + pcl::fromROSMsg (transformed_cloud, cloud); + + /* ======================================== + * Fill Code: VOXEL GRID + * ========================================*/ + pcl::PointCloud::Ptr cloud_ptr (new pcl::PointCloud (cloud)); + pcl::PointCloud::Ptr cloud_voxel_filtered (new pcl::PointCloud ()); + pcl::VoxelGrid voxel_filter; + voxel_filter.setInputCloud (cloud_ptr); + voxel_filter.setLeafSize (voxel_leaf_size, voxel_leaf_size, voxel_leaf_size); + voxel_filter.filter (*cloud_voxel_filtered); + + //ROS_INFO_STREAM("Original cloud had " << cloud_ptr->size() << " points"); + //ROS_INFO_STREAM("Downsampled cloud with " << cloud_voxel_filtered->size() << " points"); + + /* ======================================== + * Fill Code: PASSTHROUGH FILTER(S) + * ========================================*/ + pcl::PointCloud xf_cloud, yf_cloud, zf_cloud; + pcl::PassThrough pass_x; + pass_x.setInputCloud(cloud_voxel_filtered); + pass_x.setFilterFieldName("x"); + pass_x.setFilterLimits(x_filter_min, x_filter_max); + pass_x.filter(xf_cloud); + + pcl::PointCloud::Ptr xf_cloud_ptr(new pcl::PointCloud(xf_cloud)); + pcl::PassThrough pass_y; + pass_y.setInputCloud(xf_cloud_ptr); + pass_y.setFilterFieldName("y"); + pass_y.setFilterLimits(y_filter_min, y_filter_max); + pass_y.filter(yf_cloud); + + pcl::PointCloud::Ptr yf_cloud_ptr(new pcl::PointCloud(yf_cloud)); + pcl::PassThrough pass_z; + pass_z.setInputCloud(yf_cloud_ptr); + pass_z.setFilterFieldName("z"); + pass_z.setFilterLimits(z_filter_min, z_filter_max); + pass_z.filter(zf_cloud); + + /* ======================================== + * Fill Code: CROPBOX (OPTIONAL) + * ========================================*/ + pcl::PointCloud xyz_filtered_cloud; + pcl::CropBox crop; + crop.setInputCloud(cloud_voxel_filtered); + Eigen::Vector4f min_point = Eigen::Vector4f(x_filter_min, y_filter_min, z_filter_min, 0); + Eigen::Vector4f max_point = Eigen::Vector4f(x_filter_max, y_filter_max, z_filter_max, 0); + crop.setMin(min_point); + crop.setMax(max_point); + crop.filter(xyz_filtered_cloud); + + /* ======================================== + * Fill Code: PLANE SEGEMENTATION + * ========================================*/ + pcl::PointCloud::Ptr cropped_cloud(new pcl::PointCloud(xyz_filtered_cloud)); + pcl::PointCloud::Ptr cloud_f (new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_plane (new pcl::PointCloud ()); + // Create the segmentation object for the planar model and set all the parameters + pcl::SACSegmentation seg; + pcl::PointIndices::Ptr inliers (new pcl::PointIndices); + pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); + seg.setOptimizeCoefficients (true); + seg.setModelType (pcl::SACMODEL_PLANE); + seg.setMethodType (pcl::SAC_RANSAC); + seg.setMaxIterations (plane_max_iter); + seg.setDistanceThreshold (plane_dist_thresh); + // Segment the largest planar component from the cropped cloud + seg.setInputCloud (cropped_cloud); + seg.segment (*inliers, *coefficients); + if (inliers->indices.size () == 0) + { + ROS_WARN_STREAM ("Could not estimate a planar model for the given dataset.") ; + //break; + } + + // Extract the planar inliers from the input cloud + pcl::ExtractIndices extract; + extract.setInputCloud (cropped_cloud); + extract.setIndices(inliers); + extract.setNegative (false); + + // Get the points associated with the planar surface + extract.filter (*cloud_plane); + ROS_INFO_STREAM("PointCloud representing the planar component: " << cloud_plane->points.size () << " data points." ); + + // Remove the planar inliers, extract the rest + extract.setNegative (true); + extract.filter (*cloud_f); + + /* ======================================== + * Fill Code: PUBLISH PLANE MARKER (OPTIONAL) + * ========================================*/ + + + /* ======================================== + * Fill Code: EUCLIDEAN CLUSTER EXTRACTION (OPTIONAL/RECOMMENDED) + * ========================================*/ + // Creating the KdTree object for the search method of the extraction + pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); + *cloud_filtered = *cloud_f; + tree->setInputCloud (cloud_filtered); + + std::vector cluster_indices; + pcl::EuclideanClusterExtraction ec; + ec.setClusterTolerance (cluster_tol); + ec.setMinClusterSize (cluster_min_size); + ec.setMaxClusterSize (cluster_max_size); + ec.setSearchMethod (tree); + ec.setInputCloud (cloud_filtered); + ec.extract (cluster_indices); + + std::vector pc2_clusters; + std::vector::Ptr > clusters; + for (std::vector::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it) + { + pcl::PointCloud::Ptr cloud_cluster (new pcl::PointCloud); + for (std::vector::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) + cloud_cluster->points.push_back(cloud_filtered->points[*pit]); + cloud_cluster->width = cloud_cluster->points.size (); + cloud_cluster->height = 1; + cloud_cluster->is_dense = true; + std::cout << "Cluster has " << cloud_cluster->points.size() << " points.\n"; + clusters.push_back(cloud_cluster); + sensor_msgs::PointCloud2::Ptr tempROSMsg(new sensor_msgs::PointCloud2); + pcl::toROSMsg(*cloud_cluster, *tempROSMsg); + pc2_clusters.push_back(tempROSMsg); + } + + /* ======================================== + * Fill Code: STATISTICAL OUTLIER REMOVAL (OPTIONAL) + * ========================================*/ + pcl::PointCloud::Ptr cluster_cloud_ptr= clusters.at(0); + pcl::PointCloud::Ptr sor_cloud_filtered(new pcl::PointCloud); + pcl::StatisticalOutlierRemoval sor; + sor.setInputCloud (cluster_cloud_ptr); + sor.setMeanK (50); + sor.setStddevMulThresh (1.0); + sor.filter (*sor_cloud_filtered); + + + /* ======================================== + * Fill Code: PUBLISH OTHER MARKERS (OPTIONAL) + * ========================================*/ + + + /* ======================================== + * BROADCAST TRANSFORM (OPTIONAL) + * ========================================*/ + static tf::TransformBroadcaster br; + tf::Transform part_transform; + + //Here in the tf::Vector3(x,y,z) x,y, and z should be calculated based on the pointcloud filtering results + part_transform.setOrigin( tf::Vector3(sor_cloud_filtered->at(1).x, sor_cloud_filtered->at(1).y, sor_cloud_filtered->at(1).z) ); + tf::Quaternion q; + q.setRPY(0, 0, 0); + part_transform.setRotation(q); + br.sendTransform(tf::StampedTransform(part_transform, ros::Time::now(), world_frame, "part")); + + /* ======================================== + * Fill Code: POLYGONAL SEGMENTATION (OPTIONAL) + * ========================================*/ + pcl::PointCloud::Ptr sensor_cloud_ptr (new pcl::PointCloud(cloud)); + pcl::PointCloud::Ptr prism_filtered_cloud (new pcl::PointCloud); + pcl::PointCloud::Ptr pick_surface_cloud_ptr(new pcl::PointCloud); + pcl::ExtractPolygonalPrismData prism; + pcl::ExtractIndices extract_ind; + prism.setInputCloud(sensor_cloud_ptr); + pcl::PointIndices::Ptr pt_inliers (new pcl::PointIndices()); + // create prism surface + double box_length=0.25; + double box_width=0.25; + pick_surface_cloud_ptr->width = 5; + pick_surface_cloud_ptr->height = 1; + pick_surface_cloud_ptr->points.resize(5); + + pick_surface_cloud_ptr->points[0].x = 0.5f*box_length; + pick_surface_cloud_ptr->points[0].y = 0.5f*box_width; + pick_surface_cloud_ptr->points[0].z = 0; + + pick_surface_cloud_ptr->points[1].x = -0.5f*box_length; + pick_surface_cloud_ptr->points[1].y = 0.5f*box_width; + pick_surface_cloud_ptr->points[1].z = 0; + + pick_surface_cloud_ptr->points[2].x = -0.5f*box_length; + pick_surface_cloud_ptr->points[2].y = -0.5f*box_width; + pick_surface_cloud_ptr->points[2].z = 0; + + pick_surface_cloud_ptr->points[3].x = 0.5f*box_length; + pick_surface_cloud_ptr->points[3].y = -0.5f*box_width; + pick_surface_cloud_ptr->points[3].z = 0; + + pick_surface_cloud_ptr->points[4].x = 0.5f*box_length; + pick_surface_cloud_ptr->points[4].y = 0.5f*box_width; + pick_surface_cloud_ptr->points[4].z = 0; + + Eigen::Affine3d eigen3d; + tf::transformTFToEigen(part_transform,eigen3d); + pcl::transformPointCloud(*pick_surface_cloud_ptr,*pick_surface_cloud_ptr,Eigen::Affine3f(eigen3d)); + + prism.setInputPlanarHull( pick_surface_cloud_ptr); + prism.setHeightLimits(-10,10); + + prism.segment(*pt_inliers); + + extract_ind.setInputCloud(sensor_cloud_ptr); + extract_ind.setIndices(pt_inliers); + + extract_ind.setNegative(true); + extract_ind.filter(*prism_filtered_cloud); + + /* ======================================== + * CONVERT POINTCLOUD PCL->ROS + * PUBLISH CLOUD + * Fill Code: UPDATE AS NECESSARY + * ========================================*/ + sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); + pcl::toROSMsg(*prism_filtered_cloud, *pc2_cloud); + pc2_cloud->header.frame_id=world_frame; + pc2_cloud->header.stamp=ros::Time::now(); + object_pub.publish(pc2_cloud); + } + return 0; +} diff --git a/exercises/perception_ws/src/lesson_perception/CMakeLists.txt b/exercises/5.1/template_ws/src/lesson_perception/CMakeLists.txt similarity index 99% rename from exercises/perception_ws/src/lesson_perception/CMakeLists.txt rename to exercises/5.1/template_ws/src/lesson_perception/CMakeLists.txt index 3080c2db1..c79433ce5 100644 --- a/exercises/perception_ws/src/lesson_perception/CMakeLists.txt +++ b/exercises/5.1/template_ws/src/lesson_perception/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(catkin REQUIRED COMPONENTS pcl_ros pcl_conversions visualization_msgs + tf_conversions ) find_package(PCL REQUIRED) diff --git a/exercises/perception_ws/src/lesson_perception/package.xml b/exercises/5.1/template_ws/src/lesson_perception/package.xml similarity index 96% rename from exercises/perception_ws/src/lesson_perception/package.xml rename to exercises/5.1/template_ws/src/lesson_perception/package.xml index 802b35f41..c1e60d1f3 100644 --- a/exercises/perception_ws/src/lesson_perception/package.xml +++ b/exercises/5.1/template_ws/src/lesson_perception/package.xml @@ -47,6 +47,7 @@ pcl_msgs pcl_ros visualization_msgs + tf_conversions roscpp sensor_msgs @@ -55,6 +56,7 @@ pcl_msgs pcl_ros visualization_msgs + tf_conversions diff --git a/exercises/perception_ws/src/lesson_perception/src/perception_node.cpp b/exercises/5.1/template_ws/src/lesson_perception/src/perception_node.cpp similarity index 97% rename from exercises/perception_ws/src/lesson_perception/src/perception_node.cpp rename to exercises/5.1/template_ws/src/lesson_perception/src/perception_node.cpp index 71db5285b..4a7022883 100644 --- a/exercises/perception_ws/src/lesson_perception/src/perception_node.cpp +++ b/exercises/5.1/template_ws/src/lesson_perception/src/perception_node.cpp @@ -15,8 +15,10 @@ //#include //#include //#include -//#include +//#include //#include +//#include +//#include int main(int argc, char *argv[]) { @@ -118,17 +120,6 @@ int main(int argc, char *argv[]) * ========================================*/ - /* ======================================== - * CONVERT POINTCLOUD PCL->ROS - * PUBLISH CLOUD - * Fill Code: UPDATE AS NECESSARY - * ========================================*/ - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - //pcl::toROSMsg(*cloud_ptr, *pc2_cloud); - pc2_cloud->header.frame_id=world_frame; - pc2_cloud->header.stamp=ros::Time::now(); - object_pub.publish(pc2_cloud); - /* ======================================== * Fill Code: PUBLISH OTHER MARKERS (OPTIONAL) * ========================================*/ @@ -144,6 +135,16 @@ int main(int argc, char *argv[]) * ========================================*/ + /* ======================================== + * CONVERT POINTCLOUD PCL->ROS + * PUBLISH CLOUD + * Fill Code: UPDATE AS NECESSARY + * ========================================*/ + sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); + //pcl::toROSMsg(*cloud_ptr, *pc2_cloud); + pc2_cloud->header.frame_id=world_frame; + pc2_cloud->header.stamp=ros::Time::now(); + object_pub.publish(pc2_cloud); } return 0; } diff --git a/exercises/5.2/src/lesson_perception/launch/lesson_perception.rviz b/exercises/5.2/src/lesson_perception/launch/lesson_perception.rviz deleted file mode 100644 index 18f5bc106..000000000 --- a/exercises/5.2/src/lesson_perception/launch/lesson_perception.rviz +++ /dev/null @@ -1,237 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - - /PointCloud23 - Splitter Ratio: 0.5 - Tree Height: 503 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.588679 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: PointCloud2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.03 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - 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.01 - Style: Points - Topic: /kinect/depth_registered/points - Use Fixed Frame: true - Use rainbow: true - 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: Intensity - Decay Time: 0 - Enabled: false - 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.01 - Style: Flat Squares - Topic: /object_cluster - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: true - kinect_depth_frame: - Value: true - kinect_depth_optical_frame: - Value: true - kinect_link: - Value: true - kinect_rgb_frame: - Value: true - kinect_rgb_optical_frame: - Value: true - part: - Value: true - ur5_stand: - Value: true - world_frame: - Value: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - world_frame: - part: - {} - ur5_stand: - kinect_link: - kinect_depth_frame: - kinect_depth_optical_frame: - {} - kinect_rgb_frame: - kinect_rgb_optical_frame: - {} - Update Interval: 0 - 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: Intensity - Decay Time: 0 - Enabled: false - 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.01 - Style: Flat Squares - Topic: /scene_minus_box - Use Fixed Frame: true - Use rainbow: true - Value: false - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: world_frame - 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 - Topic: /initialpose - - 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: 4.79058 - Enable Stereo Rendering: - Stereo Eye Separation: 0.06 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: -0.174017 - Y: 0.0337533 - Z: -0.323589 - Name: Current View - Near Clip Distance: 0.01 - Pitch: 0.929796 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.0354 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 784 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000013c00000286fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000286000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000286fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000286000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d006501000000000000045000000000000000000000036e0000028600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1200 - X: 378 - Y: 86 diff --git a/exercises/5.2/src/lesson_perception/src/perception_node.cpp b/exercises/5.2/src/lesson_perception/src/perception_node.cpp deleted file mode 100644 index 39c5ef6e5..000000000 --- a/exercises/5.2/src/lesson_perception/src/perception_node.cpp +++ /dev/null @@ -1,371 +0,0 @@ -#include -#include -#include -#include -#include //hydro - -// PCL specific includes -#include //hydro -#include "pcl_ros/transforms.h" - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -//polygonal segmentation -#include -#include -#include - -int main(int argc, char *argv[]) -{ - /* - * INITIALIZE ROS NODE - */ - ros::init(argc, argv, "perception_node"); - ros::NodeHandle nh; - ros::NodeHandle priv_nh_("~"); - - /* - * SET UP PARAMETERS (COULD BE INPUT FROM LAUNCH FILE/TERMINAL) - */ - std::string cloud_topic, world_frame, camera_frame; - double voxel_leaf_size; - double x_filter_min, x_filter_max, y_filter_min, y_filter_max, z_filter_min, z_filter_max; - double plane_max_iter, plane_dist_thresh; - double cluster_tol; - int cluster_min_size, cluster_max_size; - /*world_frame="world_frame"; - camera_frame="kinect_link"; - cloud_topic="camera/depth_registered/points"; - voxel_leaf_size=0.001f; - x_filter_min=-2.5; - x_filter_max=2.5; - y_filter_min=-2.5; - y_filter_max=2.5; - z_filter_min=-2.5; - z_filter_max=1.0; - plane_max_iter=50; - plane_dist_thresh=0.05; - cluster_tol=0.02; - cluster_min_size=100; - cluster_max_size=50000;*/ - priv_nh_.getParam("cloud_topic", cloud_topic); - priv_nh_.getParam("world_frame", world_frame); - priv_nh_.getParam("camera_frame", camera_frame); - priv_nh_.getParam("voxel_leaf_size", voxel_leaf_size); - priv_nh_.getParam("x_filter_min", x_filter_min); - priv_nh_.getParam("x_filter_max", x_filter_max); - priv_nh_.getParam("y_filter_min", y_filter_min); - priv_nh_.getParam("y_filter_max", y_filter_max); - priv_nh_.getParam("z_filter_min", z_filter_min); - priv_nh_.getParam("z_filter_max", z_filter_max); - priv_nh_.getParamCached("plane_max_iterations", plane_max_iter); - priv_nh_.getParamCached("plane_distance_threshold", plane_dist_thresh); - priv_nh_.getParam("cluster_tolerance", cluster_tol); - priv_nh_.getParam("cluster_min_size", cluster_min_size); - priv_nh_.getParam("cluster_max_size", cluster_max_size); - - /* - * SETUP PUBLISHERS - */ - ros::Publisher object_pub, cluster_pub, pose_pub, vis_pub, scene_wo_box; - object_pub = nh.advertise("object_cluster", 1); - cluster_pub = nh.advertise("primary_cluster", 1); - scene_wo_box = nh.advertise("scene_minus_box", 1); - vis_pub = nh.advertise( "visualization_marker", 1); - - while (ros::ok()) - { - /* - * LISTEN FOR POINTCLOUD - */ - std::string topic = nh.resolveName(cloud_topic); - ROS_INFO_STREAM("Cloud service called; waiting for a PointCloud2 on topic "<< topic); - sensor_msgs::PointCloud2::ConstPtr recent_cloud = - ros::topic::waitForMessage(topic, nh); - - /* - * TRANSFORM POINTCLOUD FROM CAMERA FRAME TO WORLD FRAME - */ - tf::TransformListener listener; - tf::StampedTransform stransform; - try - { - listener.waitForTransform(world_frame, recent_cloud->header.frame_id, ros::Time::now(), ros::Duration(6.0)); - listener.lookupTransform(world_frame, recent_cloud->header.frame_id, ros::Time(0), stransform); - } - catch (tf::TransformException ex) - { - ROS_ERROR("%s",ex.what()); - } - sensor_msgs::PointCloud2 transformed_cloud; - // sensor_msgs::PointCloud2::ConstPtr recent_cloud = - // ros::topic::waitForMessage(topic, nh); - pcl_ros::transformPointCloud(world_frame, stransform, *recent_cloud, transformed_cloud); - - /* - * CONVERT POINTCLOUD ROS->PCL - */ - pcl::PointCloud cloud; - pcl::fromROSMsg (transformed_cloud, cloud); - - - //MAKE TIMERS FOR PROCESS (OPTIONAL) - ros::Time start_init = ros::Time::now(); - - /* ======================================== - * Fill Code: VOXEL GRID - * ========================================*/ - //input clout must be a pointer, so we make a new cloud_ptr from the cloud object - pcl::PointCloud::Ptr cloud_ptr (new pcl::PointCloud(cloud)); - //output cloud - set up as pointer to ease transition into further processing - pcl::PointCloud::Ptr cloud_voxel_filtered (new pcl::PointCloud ()); - //create an instance of the pcl VoxelGrid - pcl::VoxelGrid voxel_filter; - voxel_filter.setInputCloud (cloud_ptr); - voxel_filter.setLeafSize (float(voxel_leaf_size), float(voxel_leaf_size), float(voxel_leaf_size)); - voxel_filter.filter (*cloud_voxel_filtered); - - ROS_INFO_STREAM("Original cloud had " << cloud_voxel_filtered->size() << " points"); - //ROS_INFO_STREAM("Downsampled cloud with " << cloud_voxel_filtered->size() << " points"); - - /* ======================================== - * Fill Code: PASSTHROUGH FILTER(S) - * ======================*/ - //step 1- filter in x - pcl::PointCloud xf_cloud, yf_cloud, zf_cloud; - pcl::PassThrough pass_x; - pass_x.setInputCloud(cloud_voxel_filtered); - pass_x.setFilterFieldName("x"); - pass_x.setFilterLimits(x_filter_min,x_filter_max); - pass_x.filter(xf_cloud); - - //pass to filter in y - pcl::PointCloud::Ptr xf_cloud_ptr(new pcl::PointCloud(xf_cloud)); - pcl::PassThrough pass_y; - pass_y.setInputCloud(xf_cloud_ptr); - pass_y.setFilterFieldName("y"); - pass_y.setFilterLimits(y_filter_min, y_filter_max); - pass_y.filter(yf_cloud); - - //pass to filter in z - pcl::PointCloud::Ptr yf_cloud_ptr(new pcl::PointCloud(yf_cloud)); - pcl::PassThrough pass_z; - pass_z.setInputCloud(yf_cloud_ptr); - pass_z.setFilterFieldName("z"); - pass_z.setFilterLimits(z_filter_min, z_filter_max); - pass_z.filter(zf_cloud); - - /* ======================================== - * Fill Code: CROPBOX (OPTIONAL) - * Instead of three passthrough filters, the cropbox filter can be used - * The user should choose one or the other method - * ========================================*/ - pcl::PointCloud xyz_filtered_cloud; - pcl::CropBox crop; - crop.setInputCloud(cloud_voxel_filtered); - Eigen::Vector4f min_point = Eigen::Vector4f(x_filter_min, y_filter_min, z_filter_min, 0); - Eigen::Vector4f max_point = Eigen::Vector4f(x_filter_max, y_filter_max, z_filter_max, 0); - crop.setMin(min_point); - crop.setMax(max_point); - crop.filter(xyz_filtered_cloud); - - /* ======================================== - * Fill Code: PLANE SEGEMENTATION - * ========================================*/ - pcl::PointCloud::Ptr cropped_cloud(new pcl::PointCloud(zf_cloud)); //this passes in either passthrough or crop filtered cloud. - pcl::PointCloud::Ptr cloud_f (new pcl::PointCloud); - pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); - pcl::PointCloud::Ptr cloud_plane (new pcl::PointCloud ()); - // Create the segmentation object for the planar model and set all the parameters - pcl::SACSegmentation seg; - pcl::PointIndices::Ptr inliers (new pcl::PointIndices); - pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); - seg.setOptimizeCoefficients (true); - seg.setModelType (pcl::SACMODEL_PLANE); - seg.setMethodType (pcl::SAC_RANSAC); - seg.setMaxIterations (plane_max_iter); - seg.setDistanceThreshold (plane_dist_thresh); - // Segment the largest planar component from the cropped cloud - seg.setInputCloud (cropped_cloud); - seg.segment (*inliers, *coefficients); - if (inliers->indices.size () == 0) - { - ROS_WARN_STREAM ("Could not estimate a planar model for the given dataset.") ; - //break; - } - - // Extract the planar inliers from the input cloud - pcl::ExtractIndices extract; - extract.setInputCloud (cropped_cloud); - extract.setIndices(inliers); - extract.setNegative (false); - - // Get the points associated with the planar surface - extract.filter (*cloud_plane); - ROS_INFO_STREAM("PointCloud representing the planar component: " << cloud_plane->points.size () << " data points." ); - - /* ======================================== - * Fill Code: PUBLISH PLANE MARKER (OPTIONAL) - * ========================================*/ - visualization_msgs::Marker table_marker; - - - // Remove the planar inliers, extract the rest - extract.setNegative (true); - extract.filter (*cloud_f); - - /* ======================================== - * Fill Code: EUCLIDEAN CLUSTER EXTRACTION (OPTIONAL/RECOMMENDED) - * ========================================*/ - // Creating the KdTree object for the search method of the extraction - pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); - *cloud_filtered = *cloud_f; - tree->setInputCloud (cloud_filtered); - - std::vector cluster_indices; - pcl::EuclideanClusterExtraction ec; - ec.setClusterTolerance (cluster_tol); // 2cm - ec.setMinClusterSize (cluster_min_size); - ec.setMaxClusterSize (cluster_max_size); - ec.setSearchMethod (tree); - ec.setInputCloud (cloud_filtered); - ec.extract (cluster_indices); - - std::vector pc2_clusters; - std::vector::Ptr > clusters; - for (std::vector::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it) - { - pcl::PointCloud::Ptr cloud_cluster (new pcl::PointCloud); - for (std::vector::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) - cloud_cluster->points.push_back(cloud_filtered->points[*pit]); - cloud_cluster->width = cloud_cluster->points.size (); - cloud_cluster->height = 1; - cloud_cluster->is_dense = true; - std::cout << "Cluster has " << cloud_cluster->points.size() << " points.\n"; - clusters.push_back(cloud_cluster); - sensor_msgs::PointCloud2::Ptr tempROSMsg(new sensor_msgs::PointCloud2); - pcl::toROSMsg(*cloud_cluster, *tempROSMsg); - pc2_clusters.push_back(tempROSMsg); - } - pc2_clusters.at(0)->header.frame_id=world_frame; - pc2_clusters.at(0)->header.stamp=ros::Time::now(); - cluster_pub.publish(pc2_clusters.at(0)); - - /* ======================================== - * Fill Code: STATISTICAL OUTLIER REMOVAL (OPTIONAL) - * ========================================*/ - pcl::PointCloud::Ptr cluster_cloud_ptr= clusters.at(0); - pcl::PointCloud::Ptr sor_cloud_filtered(new pcl::PointCloud); - pcl::StatisticalOutlierRemoval sor; - sor.setInputCloud (cluster_cloud_ptr); - sor.setMeanK (50); - sor.setStddevMulThresh (1.0); - sor.filter (*sor_cloud_filtered); - - //OPTIONAL TIMERS - ros::Time finish_process = ros::Time::now(); - ros::Duration total_process = finish_process - start_init; - ROS_INFO_STREAM("Point Cloud processing took "<< total_process<<" s"); - - /* ======================================== - * CONVERT POINTCLOUD PCL->ROS - * PUBLISH CLOUD - * Fill Code: UPDATE AS NECESSARY - * ========================================*/ - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(*sor_cloud_filtered, *pc2_cloud); - pc2_cloud->header.frame_id=world_frame; - pc2_cloud->header.stamp=ros::Time::now(); - object_pub.publish(*pc2_cloud); - - /* ======================================== - * Fill Code: PUBLISH OTHER MARKERS (OPTIONAL) - * ========================================*/ - - - /* ======================================== - * BROADCAST TRANSFORM (OPTIONAL) - * ========================================*/ - static tf::TransformBroadcaster br; - tf::Transform part_transform; - //Here in the tf::Vector3(x,y,z) x,y, and z should be calculated based on the pointcloud filtering results - part_transform.setOrigin( tf::Vector3(sor_cloud_filtered->at(1).x, sor_cloud_filtered->at(1).y, sor_cloud_filtered->at(1).z) ); - tf::Quaternion q; - q.setRPY(0, 0, 0); - part_transform.setRotation(q); - br.sendTransform(tf::StampedTransform(part_transform, ros::Time::now(), world_frame, "part")); - - /* ======================================== - * Fill Code: POLYGONAL SEGMENTATION (OPTIONAL) - * ========================================*/ - pcl::PointCloud::Ptr sensor_cloud_ptr (new pcl::PointCloud(cloud)); - pcl::PointCloud::Ptr prism_filtered_cloud (new pcl::PointCloud); - pcl::PointCloud::Ptr pick_surface_cloud_ptr(new pcl::PointCloud); - - pcl::ExtractPolygonalPrismData prism; - pcl::ExtractIndices extract_ind; - pcl::PointIndices::Ptr pt_inliers (new pcl::PointIndices()); - - prism.setInputCloud(sensor_cloud_ptr); - - // create prism surface - double box_length=0.25; - double box_width=0.25; - pick_surface_cloud_ptr->width = 5; - pick_surface_cloud_ptr->height = 1; - pick_surface_cloud_ptr->points.resize(5); - - pick_surface_cloud_ptr->points[0].x = 0.5f*box_length; - pick_surface_cloud_ptr->points[0].y = 0.5f*box_width; - pick_surface_cloud_ptr->points[0].z = 0; - - pick_surface_cloud_ptr->points[1].x = -0.5f*box_length; - pick_surface_cloud_ptr->points[1].y = 0.5f*box_width; - pick_surface_cloud_ptr->points[1].z = 0; - - pick_surface_cloud_ptr->points[2].x = -0.5f*box_length; - pick_surface_cloud_ptr->points[2].y = -0.5f*box_width; - pick_surface_cloud_ptr->points[2].z = 0; - - pick_surface_cloud_ptr->points[3].x = 0.5f*box_length; - pick_surface_cloud_ptr->points[3].y = -0.5f*box_width; - pick_surface_cloud_ptr->points[3].z = 0; - - pick_surface_cloud_ptr->points[4].x = 0.5f*box_length; - pick_surface_cloud_ptr->points[4].y = 0.5f*box_width; - pick_surface_cloud_ptr->points[4].z = 0; - - Eigen::Affine3d eigen3d; - tf::transformTFToEigen(part_transform,eigen3d); - pcl::transformPointCloud(*pick_surface_cloud_ptr,*pick_surface_cloud_ptr,Eigen::Affine3f(eigen3d)); - - prism.setInputPlanarHull( pick_surface_cloud_ptr); - prism.setHeightLimits(-10,10); - prism.segment(*pt_inliers); - - //extracting remaining points - extract_ind.setInputCloud(sensor_cloud_ptr); - extract_ind.setIndices(pt_inliers); - extract_ind.setNegative(true); - extract_ind.filter(*prism_filtered_cloud);; - - //convert and publish the cloud without box - sensor_msgs::PointCloud2::Ptr scene_minus_box_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(*prism_filtered_cloud, *scene_minus_box_cloud); //into ros, from - scene_minus_box_cloud->header.frame_id=world_frame; - scene_minus_box_cloud->header.stamp=ros::Time::now(); - scene_wo_box.publish(scene_minus_box_cloud); - } - return 0; -} diff --git a/exercises/5.1/src/myworkcell_moveit_config/.setup_assistant b/exercises/5.2/src/myworkcell_moveit_config/.setup_assistant similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/.setup_assistant rename to exercises/5.2/src/myworkcell_moveit_config/.setup_assistant diff --git a/exercises/5.1/src/myworkcell_moveit_config/CMakeLists.txt b/exercises/5.2/src/myworkcell_moveit_config/CMakeLists.txt similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/CMakeLists.txt rename to exercises/5.2/src/myworkcell_moveit_config/CMakeLists.txt diff --git a/exercises/5.1/src/myworkcell_moveit_config/config/fake_controllers.yaml b/exercises/5.2/src/myworkcell_moveit_config/config/fake_controllers.yaml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/config/fake_controllers.yaml rename to exercises/5.2/src/myworkcell_moveit_config/config/fake_controllers.yaml diff --git a/exercises/5.1/src/myworkcell_moveit_config/config/joint_limits.yaml b/exercises/5.2/src/myworkcell_moveit_config/config/joint_limits.yaml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/config/joint_limits.yaml rename to exercises/5.2/src/myworkcell_moveit_config/config/joint_limits.yaml diff --git a/exercises/5.1/src/myworkcell_moveit_config/config/kinematics.yaml b/exercises/5.2/src/myworkcell_moveit_config/config/kinematics.yaml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/config/kinematics.yaml rename to exercises/5.2/src/myworkcell_moveit_config/config/kinematics.yaml diff --git a/exercises/5.1/src/myworkcell_moveit_config/config/myworkcell.srdf b/exercises/5.2/src/myworkcell_moveit_config/config/myworkcell.srdf similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/config/myworkcell.srdf rename to exercises/5.2/src/myworkcell_moveit_config/config/myworkcell.srdf diff --git a/exercises/5.1/src/myworkcell_moveit_config/config/ompl_planning.yaml b/exercises/5.2/src/myworkcell_moveit_config/config/ompl_planning.yaml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/config/ompl_planning.yaml rename to exercises/5.2/src/myworkcell_moveit_config/config/ompl_planning.yaml diff --git a/exercises/5.1/src/myworkcell_moveit_config/config/stomp_config.yaml b/exercises/5.2/src/myworkcell_moveit_config/config/stomp_config.yaml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/config/stomp_config.yaml rename to exercises/5.2/src/myworkcell_moveit_config/config/stomp_config.yaml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/default_warehouse_db.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/default_warehouse_db.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/default_warehouse_db.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/default_warehouse_db.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/demo.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/demo.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/demo.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/demo.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/joystick_control.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/joystick_control.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/joystick_control.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/joystick_control.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/move_group.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/move_group.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/move_group.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/move_group.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/moveit.rviz b/exercises/5.2/src/myworkcell_moveit_config/launch/moveit.rviz similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/moveit.rviz rename to exercises/5.2/src/myworkcell_moveit_config/launch/moveit.rviz diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/moveit_rviz.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/moveit_rviz.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/moveit_rviz.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/moveit_rviz.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/myworkcell_moveit_controller_manager.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/myworkcell_moveit_controller_manager.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/myworkcell_moveit_controller_manager.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/myworkcell_moveit_controller_manager.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/myworkcell_moveit_sensor_manager.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/myworkcell_moveit_sensor_manager.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/myworkcell_moveit_sensor_manager.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/myworkcell_moveit_sensor_manager.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/ompl_planning_pipeline.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/planning_context.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/planning_context.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/planning_context.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/planning_context.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/planning_pipeline.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/run_benchmark_ompl.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/sensor_manager.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/setup_assistant.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/setup_assistant.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/setup_assistant.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/setup_assistant.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/stomp_planning_pipeline.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/stomp_planning_pipeline.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/stomp_planning_pipeline.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/stomp_planning_pipeline.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/trajectory_execution.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/warehouse.launch b/exercises/5.2/src/myworkcell_moveit_config/launch/warehouse.launch similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/warehouse.launch rename to exercises/5.2/src/myworkcell_moveit_config/launch/warehouse.launch diff --git a/exercises/5.1/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml b/exercises/5.2/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml rename to exercises/5.2/src/myworkcell_moveit_config/launch/warehouse_settings.launch.xml diff --git a/exercises/5.1/src/myworkcell_moveit_config/package.xml b/exercises/5.2/src/myworkcell_moveit_config/package.xml similarity index 100% rename from exercises/5.1/src/myworkcell_moveit_config/package.xml rename to exercises/5.2/src/myworkcell_moveit_config/package.xml diff --git a/exercises/5.1/src/myworkcell_support/CMakeLists.txt b/exercises/5.2/src/myworkcell_support/CMakeLists.txt similarity index 100% rename from exercises/5.1/src/myworkcell_support/CMakeLists.txt rename to exercises/5.2/src/myworkcell_support/CMakeLists.txt diff --git a/exercises/5.1/src/myworkcell_support/launch/view_urdf.launch b/exercises/5.2/src/myworkcell_support/launch/view_urdf.launch similarity index 100% rename from exercises/5.1/src/myworkcell_support/launch/view_urdf.launch rename to exercises/5.2/src/myworkcell_support/launch/view_urdf.launch diff --git a/exercises/5.1/src/myworkcell_support/package.xml b/exercises/5.2/src/myworkcell_support/package.xml similarity index 100% rename from exercises/5.1/src/myworkcell_support/package.xml rename to exercises/5.2/src/myworkcell_support/package.xml diff --git a/exercises/5.1/src/myworkcell_support/rviz/myworkcell.rviz b/exercises/5.2/src/myworkcell_support/rviz/myworkcell.rviz similarity index 100% rename from exercises/5.1/src/myworkcell_support/rviz/myworkcell.rviz rename to exercises/5.2/src/myworkcell_support/rviz/myworkcell.rviz diff --git a/exercises/5.1/src/myworkcell_support/urdf/myworkcell.xacro b/exercises/5.2/src/myworkcell_support/urdf/myworkcell.xacro similarity index 100% rename from exercises/5.1/src/myworkcell_support/urdf/myworkcell.xacro rename to exercises/5.2/src/myworkcell_support/urdf/myworkcell.xacro diff --git a/exercises/5.4/detect_pump/CMakeLists.txt b/exercises/5.4/detect_pump/CMakeLists.txt new file mode 100644 index 000000000..1923a3d96 --- /dev/null +++ b/exercises/5.4/detect_pump/CMakeLists.txt @@ -0,0 +1,198 @@ +cmake_minimum_required(VERSION 2.8.3) +project(detect_pump) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + cv_bridge + rospy +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES detect_pump +# CATKIN_DEPENDS cv_bridge rospy +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/detect_pump.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/detect_pump_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_detect_pump.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/exercises/5.4/detect_pump/nodes/detect_pump.py b/exercises/5.4/detect_pump/nodes/detect_pump.py new file mode 100755 index 000000000..ec800a24f --- /dev/null +++ b/exercises/5.4/detect_pump/nodes/detect_pump.py @@ -0,0 +1,133 @@ +#!/usr/bin/env python +import rospy +from sensor_msgs.msg import Image +from cv_bridge import CvBridge +import cv2 +import math +import numpy as np + +# known pump geometry +# - units are pixels (of half-size image) +PUMP_DIAMETER = 360 +PISTON_DIAMETER = 90 +PISTON_COUNT = 7 + +def showImage(img): + cv2.imshow('image', img) + cv2.waitKey(1) + +def plotCircles(img, circles, color): + if circles is None: return + + for (x,y,r) in circles[0]: + cv2.circle(img, (int(x),int(y)), int(r), color, 2) + +def ptDist(p1, p2): + dx=p2[0]-p1[0]; dy=p2[1]-p1[1] + return math.sqrt( dx*dx + dy*dy ) + +def ptMean(p1, p2): + return ((int(p1[0]+p2[0])/2, int(p1[1]+p2[1])/2)) + +def rect2centerline(rect): + p0=rect[0]; p1=rect[1]; p2=rect[2]; p3=rect[3]; + width=ptDist(p0,p1); height=ptDist(p1,p2); + + # centerline lies along longest median + if (height > width): + cl = ( ptMean(p0,p1), ptMean(p2,p3) ) + else: + cl = ( ptMean(p1,p2), ptMean(p3,p0) ) + + return cl + +def ptLineDist(pt, line): + x0=pt[0]; x1=line[0][0]; x2=line[1][0]; + y0=pt[1]; y1=line[0][1]; y2=line[1][1]; + return abs((x2-x1)*(y1-y0)-(x1-x0)*(y2-y1))/(math.sqrt((x2-x1)*(x2-x1)+(y2-y1)*(y2-y1))) + +def findAngle(p1, p2, p3): + p1=np.array(p1); p2=np.array(p2); p3=np.array(p3); + v1=p1-p2; v2=p3-p2; + return math.atan2(-v1[0]*v2[1]+v1[1]*v2[0],v1[0]*v2[0]+v1[1]*v2[1]) * 180/3.14159 + +def process_image(msg): + try: + # convert sensor_msgs/Image to OpenCV Image + bridge = CvBridge() + orig = bridge.imgmsg_to_cv2(msg, "bgr8") + drawImg = orig + + # resize image (half-size) for easier processing + resized = cv2.resize(orig, None, fx=0.5, fy=0.5) + drawImg = resized + + # convert to single-channel image + gray = cv2.cvtColor(resized, cv2.COLOR_BGR2GRAY) + drawImg = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR) + + # threshold grayscale to binary (black & white) image + threshVal = 150 + ret,thresh = cv2.threshold(gray, threshVal, 255, cv2.THRESH_BINARY) + drawImg = cv2.cvtColor(thresh, cv2.COLOR_GRAY2BGR) + + # detect outer pump circle + pumpRadiusRange = ( PUMP_DIAMETER/2-2, PUMP_DIAMETER/2+2) + pumpCircles = cv2.HoughCircles(thresh, cv2.HOUGH_GRADIENT, 1, PUMP_DIAMETER, param2=7, minRadius=pumpRadiusRange[0], maxRadius=pumpRadiusRange[1]) + plotCircles(drawImg, pumpCircles, (255,0,0)) + if (pumpCircles is None): + raise Exception("No pump circles found!") + elif len(pumpCircles[0])<>1: + raise Exception("Wrong # of pump circles: found {} expected {}".format(len(pumpCircles[0]),1)) + else: + pumpCircle = pumpCircles[0][0] + + # detect blobs inside pump body + pistonArea = 3.14159 * PISTON_DIAMETER**2 / 4 + blobParams = cv2.SimpleBlobDetector_Params() + blobParams.filterByArea = True; + blobParams.minArea = 0.80 * pistonArea; + blobParams.maxArea = 1.20 * pistonArea; + blobDetector = cv2.SimpleBlobDetector_create(blobParams) + blobs = blobDetector.detect(thresh) + drawImg = cv2.drawKeypoints(drawImg, blobs, (), (0,255,0), cv2.DRAW_MATCHES_FLAGS_DRAW_RICH_KEYPOINTS) + if len(blobs) <> PISTON_COUNT: + raise Exception("Wring # of pistons: found {} expected {}".format(len(blobs), PISTON_COUNT)) + pistonCenters = [(int(b.pt[0]),int(b.pt[1])) for b in blobs] + + # determine primary axis, using largest contour + im2, contours, h = cv2.findContours(thresh, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE) + maxC = max(contours, key=lambda c: cv2.contourArea(c)) + boundRect = cv2.minAreaRect(maxC) + centerline = rect2centerline(cv2.boxPoints(boundRect)) + cv2.line(drawImg, centerline[0], centerline[1], (0,0,255)) + + # find closest piston to primary axis + closestPiston = min( pistonCenters, key=lambda ctr: ptLineDist(ctr, centerline)) + cv2.circle(drawImg, closestPiston, 5, (255,255,0), -1) + + # calculate pump angle + p1 = (orig.shape[1], pumpCircle[1]) + p2 = (pumpCircle[0], pumpCircle[1]) + p3 = (closestPiston[0], closestPiston[1]) + angle = findAngle(p1, p2, p3) + print "Found pump angle: {}".format(angle) + + except Exception as err: + print err + + # show results + showImage(drawImg) + +def start_node(): + rospy.init_node('detect_pump') + rospy.loginfo('detect_pump node started') + + rospy.Subscriber("image", Image, process_image) + rospy.spin() + +if __name__ == '__main__': + try: + start_node() + except rospy.ROSInterruptException: + pass diff --git a/exercises/5.4/detect_pump/nodes/image_pub.py b/exercises/5.4/detect_pump/nodes/image_pub.py new file mode 100755 index 000000000..62a6086c1 --- /dev/null +++ b/exercises/5.4/detect_pump/nodes/image_pub.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python +import rospy +import sys +import cv2 +from cv_bridge import CvBridge +from sensor_msgs.msg import Image + +def rotateImg(img, angle): + rows,cols,ch = img.shape + M = cv2.getRotationMatrix2D((cols/2,rows/2),angle,1) + return cv2.warpAffine(img,M,(cols,rows)) + +def start_node(filename): + rospy.init_node('image_pub') + rospy.loginfo('image_pub node started') + + img = cv2.imread(filename) + # cv2.imshow("image", img) + # cv2.waitKey(2000) + + bridge = CvBridge() + imgMsg = bridge.cv2_to_imgmsg(img, "bgr8") + + pub = rospy.Publisher('image', Image, queue_size=10) + + angle = 0 + while not rospy.is_shutdown(): + rotImg = rotateImg(img, angle) + imgMsg = bridge.cv2_to_imgmsg(rotImg, "bgr8") + + pub.publish(imgMsg) + angle = (angle + 10) % 360 + rospy.Rate(1.0).sleep() # 1 Hz + +if __name__ == '__main__': + try: + start_node( rospy.myargv(argv=sys.argv)[1] ) + except rospy.ROSInterruptException: + pass diff --git a/exercises/5.4/detect_pump/package.xml b/exercises/5.4/detect_pump/package.xml new file mode 100644 index 000000000..9deecf41b --- /dev/null +++ b/exercises/5.4/detect_pump/package.xml @@ -0,0 +1,65 @@ + + + detect_pump + 0.0.0 + The detect_pump package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + cv_bridge + rospy + cv_bridge + rospy + cv_bridge + rospy + + + + + + + + diff --git a/exercises/5.4/pump.jpg b/exercises/5.4/pump.jpg new file mode 100644 index 0000000000000000000000000000000000000000..d896570f1dc39274ad4c7aec239fad8589325462 GIT binary patch literal 309489 zcmbrlcQl+|^f&s9!RVdn1koe9(Fcj%I}u%U(R&#LiHP3G7`?Yd4WjobK@gqMMJIZ4 z=lgrty7!;E)-CUubKCd>mH!`ff_yA17== z)}9f#cvO$5X=tCYb8vET3yX+~LB%B$p1)93QdUvb(>E|QGBz=_v9)_`@8Ia<D4lr&z@Q zFU|f>#r`k7761Y;2>tNDq<}1NjUoH)$!Dn*t>Bqa)D%T&R>EM1|E+(vzIFdCQER!) zDSgYi)Zg}`Y~XUf-P_Opdk?C_aSVm&Da7Yxu8DY(8vb6K;fo=8-*2d3hy!?fuAg+c zrHv4&9sI&=85_1Y7La+$R_upMBn>KOJrzdYlxXA7gJF#6+3mV~+ljV!7o~*OvoCBD zZBaGOfjQ0nuivo=J`CX}IxN|!rLEWcP``|EFC~~(INto4e_nNM~ zv*$~#@PYL;H*VR)J2i0Q*Si@ZXEhc^cO{EJz$IIlFx?U|Rk5^7+JXnAKG6GQV4_GY zJUfGnNj_Z+*qH6=L^E@;O3{wD{-6-pi`^~y`u>}>qJ}|>!>6!-2}tMv$cUay+K*HVv)faHBj&h|gETTR#eml%T4nqQekFChs#|~XTL$r(bO$l=GzR~Q z&x?F#tc-&gZ~^RW6&kZRuYQq>F66qVmb&5DLZzryn3GGo|F9h<9{UJnkdT+^rufIrHNoBDi_kQH_=X79&MtaWsHl2J%8EZf^nY2 zsr4HvWCUeSQ$g;EzOmtlaOR5m29W-+Aeq5Lr*KGxyI0HkynZ!aG)GdN&PwJFeistr zDLAd$4(5i!1$)Nf9032E``}=!eZyKUQi!?fjl>OWbW>&?^4iN*C|^d!$bOX9#$xlm zEJ^c-a6QJ^j;O$%zXGG=9u%PP5vC*p_dGS+09XCY@)?#Ex=DcwN zmfldCQ*|eznlzsO)4c<$$sF_wu|hk-TT(V%dYWP&PCcbhi6uhlxnzdUjfab1>})XkI;=!=2C0=N*G z{L7qVO)AflxqL|$6BuJ=)6(P!hmIUTq)W-T!>q+3pTeaqvlAZ&OWD&%mmkv%Ky+p% zvFs;SAhmLP8jtIb0)G~|=0-7;ciLMGGf3b8HKa|4JSnP4X*3rX<+Iqh?Y9>cm*I7a zVR%3p>yoGBMKLMr*yqqN0%!3FjQRpOkQXwz1EUOX-(eMDQOG5~6k+>FdpbEykS99B z0;l7ZBUW`t0Nn1&@8U|`X_#jwe>LnpHufFh#HddI(*?#R)A=SwnO#&vh4EutIK{6h z>kIwO6|>~t-sO70XiT-DOTTij=t#}Eu7|};uvUFuOqN})N$6q3HlYyWaLe3#b(B=l zl!-|$cLwUF041y^fEvHPceTYE9VhfjH*U~rkBe_%*mHeO^%-JF&3x3or-?l+`!#`W zGg=tLwr19nE?5|^q2MZ9_uYE=awCl(E=PG#_LKBmIlnfBF86sPcDN6HjsipV>QoN< z-eVhTaa}>7grirw|pi05!JPEgfvxCS{kxMFJ5hyKHM0EhIs&fuTO zAs((s!`{)h9{#Z0?5^x=zxyAd2+{>Z`{4q=N~!f@EOrddMHD?XRp+;%)MqWP8s&w zP@Db`)BdcqdWou!0*pTUicSq~odW%S^%Ws{Pimh1B`q_R|NSBNs&b+_AdkD5`CNP0 zk2jMe_Y$~3Vtr7k3wMVNdc_8(&nB|lFyC5NjPh1@O=$jYn7`s2CC|MQN8%PtKfT0e zb>L{NFpY_%Z%%)2x*#)?iq(aA-tT?;qDsujjt%BDBn;Xy{09)Zl?3xDrRUFcFcWs?SUBH&j!obd5K~ zPiFccV|w*UwkI&y()yRj9G$bh=8tM?JJKHXy*`97N*CM%k*q$Qnv2d=KmLM$u^tD7 zLMrCU=N)|))o^-}`YjUF1xhZ>b`aI8^*5ol9)Z)&k zCkUT~3-Mmy`>S$l3Z(R#IzwmWZQ@)9G4ZAx@Ib8Yf!3cW8-j3jm8Bvaz!E$-(R8<7 zy1k{WJc`76vo(t*B>lPWAwfUqtMl!cI9ApUg+Z#*8uK!*AqY7Jrx^);{B4{?XHNms zCPNl=7NtoWnSw^w3y1UiVQZOPVbEB2AyU!=2T~Gb5cQ*o`EWv=0B-x8|!f&TwGilbWvL`yOu(GZ)()PcVV)L*DNaNLVpIUjb}j6-~$NPWk=dug419TG+*~nCHbCfjY$3Q#ld)SF{ z&0iWCUNtq<4@k4ZWYd7qfNQnCxZ$TldM!qCQf=BVd2I;<@~#O3W1_>>(ry_ll-N5r z9ExlrHh3fR`kjB{ae{k;dG3H%^A=eCp8-+L!vJuMPOk-TRe z1Wmhx{{Xp~l~|zAem#M3Z=Y%q_BqC(>+Db`EU~hj-h*#`lJi0*)|3+{h~)%or5}p_ zlK2Oq9`$tS^)AfjQGEQPLd!)1vU{w_@2<6O9;MzI&R4y%ppEx6%`$`#2z$2LG}w!C zkALcHFlpPwytq6R>4_>NwSYQPDK7ku(6_xc+O@x@YF@uN@jHA}t%WIRoxQh&-Yz1c zKK|22B!$X_1d_Ltz-{BFq`^$wLERUxoePN}wDZP(9=f9fS%*{J@t*G$%Apgds;crB?x zA2v(ROXYAA50!_R0}T;*>na>?RzTNtFN&`X2bLhIaglSez}Ddf{^(~4`9ODA_1Lp6 zBeE#6{<(+j{VJBJYWNfFWQjNrQ&!`;rUVE5HEnG3lrzIPqYfpfjLA*J8z z*dcXQL7lXV@;EB+i|sGl*Y8~!VYxx~OSHgml$vpXfp#HcWg83?f158gfU68I3s)#QfjuJt`oAHX9miymg%seVN291rQCYdNmi2RzH=h-NjBkV z`7;~G6kOWr4W&sfTmFQO{*jcc3u)bG?q%(hy#BeV8p;IoMnerhU61g`H($?TjD;bn z1J`2A$df9`38v^_!@WH-o)wFsD4Gf3rXJtKo2YnBa7p{=(w1Lk?t`;n7@fI{fl3*j z>XKO0W_)yE2$`>S58vNZAmzGLC*`P>>7zl;%Wo->j}N9rJY@;Z$Z+LDDva9&+|O)A z+|Z`t$?@^4&t}smN1I!pI?kMnnomM{*WXHowV9G!6K!P>yLqC$yEtWgue0PZT8nzk zK}^vgqkuOjN9!lLOXqX3ZN$Cr@5f4r&|cn-j-#F^|J$od0SCRh8@XtX>6eP8t==SbupgwcX_Ipixx2g+~HesJ8`j-3F{93<*T3~PQG+UL>WTU){z1S5+wbUtbk2&__oRHQ^`J7Ln$@`4}CnyL|@se3+UDkva) z>9XRBvy;rh+TA2p(-cy!d-IZF+S!#vmh--C)+PIf<0%KG59O zKl3b9!IG&Ma2c%_Q55qj%h5xnPc+&zAR)Q3=sHc`AJ2HwHA_umFYX7( z`Uho4HS#j#Czx&5GwDnK$r}92>esjk2e6xl9_FVdylTEGh{6Tt>`VLtT+4uplrcf3 ztS`qfI^xQ-8$bH1ZDfdr$G~lW(14pzuAZ(69UR*WM#r>Jg>tvaQ?+OmMv|?jz3%9;*zreGo^k z^HBYz*DIcjk(VG`8Pg`tW)@DNzG=CWGA4ph930c+%@5U!qjg5dj2Li?;^?)&AC2#} zI=O8#a7wWTr!ueVpPgPHaU(2!`q^PnreggR{Wv~pr$;|ky*Cms$(b;o4SJ~c%4O$`smnL&w&g~O1a-XdhLVown!^OJ7j6%y=-d5I*voV_9ed+&{z#F*eFvmHrfZyCQTB*?$# zI-T%FmO~&NfRA(46&V3|s#wGJm|)tcM&-@6PA)0pV!cASrI%>{E=hgqPKTjYEP1Eq zt1R9PRqC`NGr2AQhUGa>S%rjN&xI>1pL)yAGo%krzg#}ZW3?Tk@3v<>{G zL^xaIYADJSlns2|kHgqW+S94P*m2*}sXlu&4l917T$nx{6bopJdZ=gkE}c(QbG3ee z57ufre%AW62yO(F1Tk{vsug%Gl_G}+4-E19d+b+}W(!iolW})uw6Rnuc8K@|W|7`Y znT+4k>|)yhIaHYl4Jim7nuWys{2X+5U1p+emgw|5vCx|XJe!}+Po#RniIJlenX;s> zL0f50!)AbT>xd2!Qcs6KC85XtfKIZY3R@^f))oLy$^Dz=H%y?cb0I?0AP(%z*lJ@b zn%&P2HYyHxG5f9k9BjThk?e6it`+kkUZfXfaS65&c3^9R}WY=pURrP%`h zxJ#NpNNh&zpA3@Q*@{NYw4bb9sEQnh%zV%`0zxyyb~=^#amgmvp1t(Uf0%)*mSlKA zTzVISzhWseS-Kp@{A1EZ`CHd3eLT1C!_DX@T=CIr{LDvE4mSG0nGzOUAodk9jx-y9 zbICr_CdP?W#K0~EA!_sI( zCd$g{<2OVq&U}Qg7ot&ulW?L`SSApBxdCT&NQL94BX@b^2Ybjz&l+9@ zYGdQXtGx6jo~?Sh=SSXTqj&r&G;b}M8}}V)f@a#JBP005Rz7fR4TruG>J|L%vBjw6 z@k%jjP5wJ|e{Q^g&7j6fFn{7PM0$Y7dc0?4{DpR8f)0$DHmvtI^XoWwi6p&$K#xQ^ z5gu~AwX0_2(c1wWGXif)HT}kT1Ir4~Vf+P%D!hEqX(axdp^m4r`CIh9^iG_IdGKcy z8&7=Vj1KR=jGc|&cwBjNJOzPpZPm;?NU*O`o*RG&58>^P2X*X<7xh`(D z7@F%Rq<^w1AGRH_Y~rkNZ~ueD7*QE@?P#_Yzbh>h@uYcd2moDw*mFX7=c=BOzIXA) zpF1!}{w0Q;$*;GprEmbF+L?YzrTgcwE?zZqHb3IhwaCuF-J_dBoZ@pgH@mLJAQF0T zsF99eSIIpfYER^ms|_yx8a0#zqf4L`ei0z0Ljh$2wJHk$;oef8@pj-ep6JYZ$34=Gu<<4&}s4r>m~}Gt$U$ zjlgFg?m5riq^<8Q;cfU3QdTYccE91+NIXB?VcJhcwy_1%%6(KE3yplt zCgK39$qDN-Jos=9y_Xv6k`_zR;pX#?h?sk>A4Qx++?M1E8IM~S8vw!hQhLVJWJ-%n zKA{O!4>P6?9q3;&twz9fx~Ol_LR@5eH#zf-wL7pRiMSkG6puIP-htNSs3mTQx>cav z<3F_+Uq|XW-6D$vH9z5|VYmVw@jRp7Xov8Wc)SM1kIlAtFnMsHQV2_?2vKX<& z%MDR_PCfC|6qrzrqI|#H5TfPO2wLcB4;V%g;>+QA#O2BJXi5nJl@WonuFYdj@|iT% zYOcNb)R^8hNPNRT-9#sy0>?(Y)jcFk3CBS{{XgR<0=XwbM%Bw;Qsx^Cz@jNa)FlZH z(J>;y(rW;>c%%$f?e;!@#GEKW;?b`;eb`N$ERMwAuV!&`0U?A|iqBv`9X?{sASmEN z$&yR=(4dGl&8sile)5B7ZjSyj@@jU#2Hso1%|&pwv`m$n``v>2Y~KXp2hs-a`;;1hCRA_g0pvyhq@#u z6Lt6Vqx9--&a;_&dZc|yG4hL}R2X!Zvwrx($CYSK*AP91zOx&~!!Iwy4;Wxxe zmZC$Sq$@6?^8mW0_*?^7@`JsH{H=UCHN%}~n}%<&ZOy`BfPJ>vtitQ!K)b!!(>)yi zr>6LKLth-Ou{~oWfkv_7yme80t~NwM_wNcT7X(~NIqr;L?`U3P$h2AMpgKZn`74vg z*(CCewL9Xe@JOj7^uWbOk0~rh7N39o?Pb8E^DX08InbusI7UNo2+(^eDno==7vp8i zL(>le`@{Rcwh=E<$B z7IVo{^N)@vM=CD^B1;<`f8C35q%h*pbWwn|Nv=Z;0i2edM$^ciW&(u(+4qzORI9`V z%FUy0(iI#2+)E_E_04hNFh(unNDfQT2evDgQVY!SWYCtF^r?BL{dy3lxE=kUKjk7J z#F`Pycr4L+=h~1QM+7dyTVDVik7#VQJL%r)CdunF(zCv`tHcmJ3E_FY+DEI8BPMt{ zISJu#KFNbF<4~`y8C+iL(Q?}09S#u}{2PE*4kv!cr19fA=1qx2E zqFQe9X;6(XKlI$%a_q<@-5N3$o>B>W_P9Y5vIp9(lej!FOZN!@KMu7i8@g0JP`3zO z$w%^?@bKC8Bh&_EFVp2_sE8tJP>ev(O>0^hv?sJ5XePz*mMHg(yK04Nx`1t_x)==gGw114MbTE1{v$j)g`1LvpdwKt6CpY`7wOvJ=!`X+@S+~ujy>~LD6Og>-Lyuy~Uw)piQ`D$n&GE3G^RN$+R!3n0O#=%C_ck&2jG!a>ed{ z6DSuw>Z7k8WY`6JY8YyDbaF6!e14laj!%wAOZao1mr?z=H8n1NdFTK}o9x7J<*}zD zvS-r6?{!+H3Fd*1^VTY??VP0^;`Mx{#CujeY-xR6G`L};XsgczlXt!SyGx9?vy9Q-^7 zZNS^~pH=RYJ zyytrmF`BEh?MU?x=pqDcxmT4vV_!(SJj*4MyQ-!U$q|vXib38x;rh&RKlg|Q!i6Q@ zLwyIFUQ8wtkFh%@RJ{5^6vq9r#?6?@F>n&AxNdqw+>g3A{aCG8G8LTQG}6+-DW0(_ zWHP-hl#O&G`dfxZDZar%4R2>$%SmK(=4LBD zNT&RhrIqQs^ON-C1X*Y&B3fjA;;)P>Wt2W-$D^A%~Gy!HLzPs z(7utxu3P$M#Ap^SXwl>AaxHM8RjlwVk~uia!0Zo8^OPg2TUHk;J~g0I#w;Qv3h>nR z#}@RBqDOG2&GpU@VDuu~LrsrN3cZpQA;l~>i&*ckhL2&4e$RRvhuKNz;-M81F}*#+ zB!A^QbT;A!had<=Zn65NB+=govv8@1Hy~xA^+&R*m9pVah6&!1ADRy=JgtQL5DaJKoGN1;Edlu zr=K^{@%}GU2@xyJ00^VPELaM5P3m=k#==sY+V(wxT`mT7E(gmd3B3!v#jE6i7cVA}qS35miH}`wel`q3 zni{XV2TZ@}t-VYPoAC@hU8qo7E03hqM@RDyoM4VSt6_j^r=|3xvEZT2#h7^*_A=bF zG`?M*%-?i9@Oc3JDU5_rALYmj{q5jt#M7E1lRItEd&N13=PCU{(OWXPwVN@M0@$AM z^fW$K`*R8Qm6&;2^eVqwabhZa!ERpbtBSM(#_%^fPmlPXLNVogw|nl^y03EZqPTPU zUrQJm{{U{_%b&N9$f45eE|(*>pxENAW$Z5XjimfmR`{Wfc>h*i_V z&ujc6DaVFSrz{l>;ZM?kVeHfd>XY?0ABRFjd|ZE}@Qh3TbRPN@q5;6V^=;fIirIhK zL{1g7sGQ;IbzPKwPbuq$lv04~tYJkY{Epo$iz#tG?UG?KE=d=qH&sT7N;0W{7A@m4 zwBpzed4fEhrnId@gh^P%znULJpNBA34$QiH&iSGf0o{;n!zc2g`q2xP?&NXjFj8u5 zdhGkQX%j$vF&T~SK0Z$tP%s_KOQi*B^uU16MahjnsQci+@MBfhIPp|cHGKpgB2XL4 zf;T+ZR$D)ULgeL38qoOnHQ&NJiM8`D z;YsX=9(foRo&+g_=Kq6mQ`AiG)(FC3^;xZWffqHi&#=B{VZl%>mHgM7QA@11w7^<) zj{6d()J)wT`PVI@$Z3|gT`796^bgEI26qhF$5xxpEKr#OTe*b{# zSM8=x8*Bn=B+reos#IHa`T@_cVd2*D{1uAg%!Z9IQLg$n!_t&9HI~}>*D2`?_1o+lKDQ;Es7DgZpRC5dZf&HR!!q%RPm}KZ zV|WgZ!1sYbDR%;~KmXAM?O5h_L8jV1$(lx7l9o0T&QD@pyZx1an#U^3N4!$1<{6I^ z{Ow|yXBrC)o?W#kPKL;3tL3O=#*S?XU|u01Rnz26qL6rK=?jS(>$D+3?;@X%DJ-H! z;8`SD!#|+S_?>0I7$EzU?#4NzyPV4ZbzEV03{5vixbxKOA*&f$LsIqpFAcS&=tLSa z)tr1?BdN_9J>mVuoSor;m5b}roUma=MSnK^W_1i))wnx6;4S&HpSTgg;b5Ds}?~+d(#xsZa2Q)^T;vs#T51c^jN4^67r7m&kFjKV$g6AX%JD|{F zIqxfM%(v4H0gcJ-f482RZJS={hyT(}(d+6X;E$*-m~h%W93T$-{@UF)B`(*eR_#

w|Etn3HPV!56u1Mh7kCoU;WP2DwmBPXZ$Utkt^ zt-$G3o5YBSRpVivAj-$CLlU+=B?QNdxjVCPT6pwGE$S6}?20X&l1`-A#am8#8%U#@ zzw1xbV!Sev*!cSQ?`~3 z{0MJ$_lWSXnQk%I97bnnWmtFyFHHT}2hVZ>2GOx%~$2UDfZ zac>A}JoGH6j6-LZ_ zI`_M_?C-I6)0vyOq>Iyi{XFao#nh7z zp~5$>6eZs}oycCZzxbHqFM6e#{$%-$_fRk6TLNv!=ER}U9npa-QA1nX`-_Zs@}((^ z5=J|D{gFW>PFJ*s10Z_1z+8&O&*nqDJDTe-)NzcP@Q`IZO|jm4QP6Ph_%UNxcT4jM z&#CZ2Rd!=byb`Z+_s$et7PwrN)JYE$v2qKkRFKcp`}`5MQuxNpqDHpi(LE_q@4Bj% zTU|gc2H6pLJZR4%ZTd?}*=KPgwtAdNy0&$ness97%}lgN0e=5xGzhG{Ec{O04OWY4Vb} z{J#A3*Z6N7g&S?m>OhZ~9pPSYq5vu1a^w%b*EetxCniGG(R690K;U~&>5#R+pqvWb zkQOjIp&xn?AP-) z9SL`SP7LV9Xn2HCqxx6fGDfQ%hKgJSduBPQTwYIpiowiLsParr&?I)&=LWefrd*FP zLFXLmM7}lWrv)>`L&*vW)iQ)^OxYW#1bGLHzJ;F^50f|;`4Z>bR7vyWy|>SDY2gM73ohCR)3b}f6g=U~Q0LGqvV8%Lth22e%QSA&+Dx)4X%2H_#a zpC6#~h5|{M_s5sp9}lK)vVmDwPn>SjK7nI{t=VF)R(GK}O2jLpL8?c_&IRZf(l;ETF%9z9AhlGw6k?5D6C}`8)@(lFL^g*Ji^Zsp%K#_-48tW$8XyKyk`T*HKZ$3evNDeczaF+cL6lHWm_6FUIS zbEvE)eCp(WvD9@Km$DlB>y9D&KHrZvT>!6KzZsqX(`U?QyKZ&sp{G!2KJh&UFf3Qm zl9Z1hr1;sCHf+5EsRnc;$Us>f!?#nSc~*E4MfDfb`^UfZAMPK#H0}iLw=4$WT%;K1 z3@v5L+3HEuK%l`@6Pvy4N7xV7P5N^f#WI^4aj6Jt+*-X$f@-_fD6mYZI2q>&mBIsx z^m*1Z&`zobx7J9P4{D{Rfg1*$n9a8xK|#PsB;NO!BSa$|7$H~rjHZhN`qzN2PamW7 z42h$fi<0Il;#*CtFrg52=jJaCM4_`w@4Uas`~&us$7nIU5dMsf7|Zep9qi+Q1e2d_ z-|*4Jqt`{Bo3YjACZm!jw_@{<^JK58Vmj?iz<%oMObE(`s4&~MUaagd_FAv}kR`X3OE2b^aG)A!ld&Q^@BT`>umg;MSd?lp}sO6BJU;*|yz z^=|zGD!~Y4hBELN>g2;4RvQokmqP6A7Gc|nl=qGE)YFDa6Rn}h$l>A?m2j02P|6q( zP<}EB2jU(?r`Jx}D2H_eE^4+>8t=^#p5;xYkN1#Zd!)eVZ9_@YhIwcPr*fXX-882p zo}=9T;i#QC!VFxAP|Q+Yv)ZGf{PCE#n{KpH58QI=ujAGRG$B$xHESmQ?I0$$i*mxZ zICr@OlMo^V8J{0c;B@CY+2e?tVEY=L)|W5c-7BM|9XDnlcd5t!#sb_sPu^1xJr2C+ z*J64*$xl5FVaEI2-@w;`8$aJKHuR2*Tk;%6UlmF&FXPRM0F|RoDjs*MV+108{-Ah% zBfm47z*|qCN%03s@cg9l8$LI9LiG!A46_-~LRqBBmh&?FP?zUpr~vzYWsHsMD7`^NPdlKBrKfWVp$O)0Jz-+I@rfz{)|@6ba-GDR0F zNp0{9h}v?=PnZU;cBnn2pV^^XQhCB7nT?UYM^(B#i#yvhAhW8(n{N zqH*;EfwS*^0gZ9Y?N3+5WjoA@9mLO%+cKYg*{C5>+i+?5QEip=`OWCxUb8hXc*oo* zIaY`bq$}emMc(s0oeB7mr|?QM$DLMsjD|i`ALI#b@8_Gk?>fOPG3#i1(J5mh+Yb}{ z-ED#9QeQO12}Gl0Uiu1yFw9g06XP@`|A;WROkiO&NibgAxUw|cP~{B`C~7>9;KEfa zdVJb#J^*KY{XWz7a1dEc#?T)Az!jtAP(-+ctw=3(QPNm6+e{}jiAVY~-T|cRNctxw zN_tQ=sRSX=v|<&xJ74xg9cq|nW{*dk#yCH`^>wXTTUy!yBs1#QT9Uj8?Y>d4ozaap zQ=xc%;wjB-XN+6*$QSTbxJi^C#}}e@bPJvby$#bVd&72oMdxPFj6*_jY4DbW^p^ z_Xh%6Mb!~6Ism(>X292tTf)-CnZTq4E<2-LY0ZG#wTrQ!+PB4eZUFt^Ci&Di{}b$@ zqrF_YHsqx%sXmQD$^fx=r6Z>8j+^){p~9O)xpSfTNJ=+; zv8dO>$Kfz?Sf2OWpboL zXQk5I;fY9Wp{NPwSUI)?_TMCsD+jQF{W-)eQT!tR=skdeP0TtMi?mI%!=j5mIMikH z1dm3*HYd^ammmX@o_tKXS;#WrmB5&M(_LzFrYCl&DFXT{%vTEyx6ujT=-Rr(*@%~Q zC+kw2D2wn`;%ao9=024Qur~f7e+;dKPa$~!%kh!gH0Ts$!KfsIZE}_j zb1s;eWZG|`!OW1S{{YP949zbOMO9Rn6jTw~`S7jwrpwx&wD%qlAMWjCBfm*Hm{xgl z+IW+sOIfwZj(6IGW7^UJoCUG}TYdc0HQ`TQ)Fq*$TkxGYIpmvu?2Xc4!HV;gg?T$COQwz$(p^Utcn3Hbh|`*%GE*0<%& zyc{Nqut7J8Ih5aF$Ugv!{`&o?QhzhgKL9svGckslGxzZL5XMx+bfTwq%_;VKG2dTz zd$m^v`lY>tG|gd6T$(uWp8f${>E`fMY~xw%8y`X$=>ioxhx@=e@>B4}Z1aYW(8}uY zW40Zy?e+!9R=#7J;lF(7RHT~o4pdf_r^;o%jlHC*W#G?4a&_|H{nnw4M%1M2`yNya zk|4-gl*W+)#h6Ci0CA{BIrd^IkGx{V+bWyFPzsR!DDx&`hr?OQ z*T`f2Jj0Npf^(gwLa)b?Bp1gpT5PCCNvD;M$)-r&VrkgjUv zaSP(^^}qNe@dNPa_iwVm|Lndi8F$rnj_Dl|9S`KAsXbw&<&>5NwQ&O!&* zc*LAhx7uZ6U1r)?UaXCt9e>!*2AsF{Pqm=m*>}bFI2=r?7a% zE>Ur`7m+8r4=L;z0;`lF&E5FbIU|-KoZ#Lfx79Zu70!dEy<^da0E zp%Y@ftNh>-Br(ld9)0Y8y8nYD#{D~* z*djROu7xhNb8LF&xvN!Ad078?Zx|H-sBe^K;o=+@| zOuF255nJQyB=omNbxJ2xsL>_nZpPIIC(G+cW$6nnP>AHa{}CpEPCN_#TH49>3(U85 zf^vUnjU6p&0_)yNYB1=hvCS~^10fI~{y9#@hT*2P--S9IkDuqK-8EtPOL#EyB}0^a zD2|g|xUr^|i#8`RG$6* z2ZZjW#hr+6z@-eT7MaU9X7imxI=Qervcl{SO^sYXOe4{E(7f=?uW3Ue4D1l48)4AK znS5{D1K|rci#`ZzsmS5yzvHx7W^XqUZ^JJ4h=2bmYp^Re3uHQT0QVHHjKy!B>R7e1 z*<*Kn)%umE<7-{sCA-t1^z8R&c{&?kXx`tiz`o19P5_wV9G_?@yYUT5tyY)^1KT;~ zmEjh^A;s9}H1~3~uQ1OPI6l00qz!LUTf2YuuU zT(aN+K8_mGqT|iwxC)x1u|mC;QsFQ!Xso(_X=|d;%!XbxlP<8FaQb-vGPO0FIW`~m z%I?ZvpLg8vcVFHG$XGFt2ZCW#-;pI_-%u;rA6ZDe&QQfhkMQ~UJtoYi+lM_G6By87 zQa~ZK`s>_6*^m}WWq!QiCUHotequhTh?V0+7-Tn`;IVnDr=lp!vw2mvndkACNXrIs zQE&B#gAvV%U`LB?VN>I=EcIehTb>_lhSW}E3dGMO?EsGs<04^XiIH2&6E$4H17{~5 z+19N9pCF`~Eg77~6OI^wvlDK!PtOoJ@fU3wC{xtsqDrQ3rbhHXhTpKj$*^rTqHd(X z&qq@MM)B=zGcr1>p40y4e5_dm)Q1exyCC(PM{X+}@5}H*&!OEDQ0WR2&mFoG;>O3n z;9k?Utw>z_5j{s;$m@PN30x30{bhG)WA7Jh#l0nc7qNQrK_tU2Mo|_#p4dFA5>N4a z((pxD5v#bzO3C{v1MZll6*wz5HACrn#TQnw7xZV`qfzq4UUnwDwQ2QgZW9nyz8?3C^3e+dU)^Hz``$^ z-_vUfE|M5dqWynxc3$ytJYLwJwOC!WSkZe;qDE&CETZ==dhb2RA`+3+OQJ1_-XnU8 z-fIv9(N+nfmk{Fj&j0gyuiuOJV(#W*XLo1joacO>=PW;Xt$1zIiw-R5=V9T2bNH8T zxzHgW&z>M?7*BXd!})9@4TN(x{b{Uh4HG}`X_z)v*p*U4xHE7<-t43OOOn`rwJb~0 z-22H5lh4)OyiW3j!fMa+@e2|~wk5EUI?GAgBUd}gTGEQ?c9_sq!%ca4s9Zg;UjGrV zE;@CbknM}_59nc}PKGZr@1W>Lg!|=XJ|VkJ-=meEnm9qK6C%2Uqxa02<5`oEv?MRU z%lg8ZtiaiFpd{6roI@!I-#1MEqClo1>$23%4olQ=#+gO%PMks*;*3+D(<=Be48~WriiL$Fp{QkC$Qt(g58a(X;n^q&vn%j^!uXm@ z(7deJzU-QOb_Q4(kU56wPRFpmUR6Sn3#VJ=J7IizPbNk}Se)|v5yT$D?qpYG6tn4g zYKMLZszaKuVOmTjepg{&WM|+Z4u2E#^uz+o92wI_^@B17z-sXK4=m)=Xe z%dm#<3iZR{UzQ7;_fQiEEhMWec3^S(X!d#0|2>aP#gxx2X9c&)cbkqzf@ThqxS2*J zk)$zO=}?Raf-GS%SoLU=Q&mNOoFn;A_sL3!mW$$Oo7)HymUGfi?#9o`&*HG(6!bHn zAaey++N6gcle>o5F6w?B9{we=lEH=U8TrN!nfD(4$lh@J; zm6oihO)XAPOx|A5Nmmk5&c@PL^v1eKCG7KvNQ^9k8kjmgu47@BZK+Vw{9+OEo730| z%9Kt7XZ8N)*R97#$k8TZD?zrrh0G^7#Maj*KaYuGKEzxkW0xk`d&P-DuEWFQ{l}e3 zT!jR(;%iNlj`!SBuZr~HbvQ$}66q|GD~E-t{=6N;>N!i@!3C<$4CU`P z9vD5ddo7mA5Kr}5e<+_^dnQ0)TiIfVt3Ie~OT}lU{ZH>5i-QkIrJtn(rin1t?m`q& ziR3=qIVl<~qgPd!D`m9ByZIT>V5i>lAa^pA0v9YUpH1{_LJnQykFpLfL;(N7RUVk856B z+4+Vwe_756IL{|Hs85}UF&v;rC$Chq4NT+dA)r}h_Ss3IuBtR;F3$O$#IyEm7x{z- zwhCvD2xW)%%>=8rSO)+G$B&H)aJ;lNGCT`KVOkdG@)XXJicTab+D(RbxTo-Yfkqsn zs1*_VFU15y-Th|uLw3o3r|@p>-ShxIj?8?_Y3b>?6TauV_LXv=$o2S*mP4Fd);WsW>H|80^Cj4`|?Cc8N2u|&8^=xBk z>mUF0^<*{fR(YDzuuZMkW3ekruHgo9^B_1`M&m~E%5_t2CvI$z^$*z!NUw_ifAiT$ zOWF#^g(y&OC~I#0tzKIHMTM)7!o7X=CTP^lk2O!O-rl%Hj5Cu|?lgn#aXcR(s|wfs z4~HCNIbc>yZn^7|R+U`2vKK7Kstp$oM;QQLGlB^0wXMEBSq$FCuC$Z}o9p-VN*C&> z{PZ3l52pb;ZLsIxG!*5j3r$46_q$InGQsP^bj$w>%xjAgbvS>+x_d~+K3(?mN@ z`_*mi_eB4-WImbGhWtQY?EBiU>3$p8nJjeH0>cCRBQ+PMo}4b6X&KzOn2X18GTN6- zw&)PM3AYa|vyPIzr!UokRHF_aOS)QDVR1?oxyCs{B-r}Vo_0Q>!gUQBu>cbsR< zY(IYv(?%UG5j!A0n>_uBmzK5dEDi|x+0x=(tzBg-#mg*2w^L+xHxno0cd_v))fk;y zjxRDS3iQp;n80pbmA|}$KOXEbes3tBrxX{vM>(X1W@=y4!TS%W>no>zj76S46(;tt zyvREEOD3|C#nS31+4WZk@3OUNaAkNp@jRZGsIk< z<$1_(>B^lW+>m>ot@5380Lwi-#Alun<-GiT1a**=I{vqDS^xbXDt?1=HKp0~8%-0c z+UoA_X_4Mk@U+R>ja6QcTldvUfXm!p!~;)`N)=WU5aC8SJD&V z2%FLm+b4LxMR$%98zx^ij%i$t+UC!|4i8{h`dsq)WDI~%yd(r*c9 zYG@+^2+1jY`F_6Xtx|OQ4={*GgN$|@% z4x6q4k#@F4qs{2ywMad#Oz*A@5vwZZp3)5)Q`iiR@8dTaI@M=z*;XA`Qt_MMLm+mC z!7#S{aX34k$z(_9c?4el3So4KSqu3qf#)wT*pI+IM~OUAj8@__`?Mk{OsZW%PIvRH zKlHD&pnErhEL@5Rv#JtfOvtPi8jw%Uqy1W(4mLbASY+9FWkHCWzf()IM_5uruj4IQ zqFVBiBOMER*>>huN!ETu(}3r^bb^gcB}koEj+zVzrI&6uu+Un7l_5%!YTaA{{{et6 zv5|`(^FRU|s)>+X~2%@m66>)?`yXc5w{CPTk8oi#lTzvQ+;G#KAH@aOo= zQ$unV{Y`$L8P3bk%;v0V)5BU#>yL&Xw>;KyJ2MD4fPOSTK<+Y9OjYtKG zZCMFkeH6pCDoD!wofjz&jy9YtVxfu(ck%xZAXv3}a;=kdDGGTX^rF;tCMQEumS02V z*rR`#RNxt;x;}aWl7G4iM;r=k1#h5;M_W7#uT9P?TE*XZHHg!*Nvl;&5`{^&&)TbTp_2!7 zt!mdFzs_jXDHsJ{jmm(}9m$nxh8ou^jDjTN{`WAEwTg#gkl^<*YZNOr3%}+rlll6Z zmwxe`yPNQkDZo%XIOBD_)V5;EfcNS{Re=#MHa4G`IJaRz2}B3EMA7x43<*A?Ib$h= z;j7vjV>8Q)UHle_#U|ON{s%gGl&nZx8h2W>4;F+EsAFFb0XF`!yeF0Rw?k5ATG9;m zC(q)EDTyy6w^1B%a$73oN^u$9$r29}j6QrJn4v(QP0Hx0SN{rnBrK6nprgvses*{9 zEaT+u9|8!x__t+233NJ_q}&)3Oq?N)?BX4X$_t=Lcoa+QWdUgWX?JqLj`EdC9v6Gq+jmq?5jmaqIl0LZ)1>hr<}}k6 zEWsW?m`4zFbZY^{<*#gU!_V^6Ge?HHgd`YU#vKzq$5M7mpj80E&|aR6EHsJ_xnT+@ z=KBU04M$Sjynvn*HY9vX$K%GppA_R#7*z z|0~~m7L$$Fc8-JL$PoFkfCh&Y?pd?_LX5*hf65Np)dHX%A;dVL(H4l#)&nl`xhjRK z4^!+6pG6_7OIH)lnR+UWer8j_t;DgYLIiDp@DGwgxs>Zo3{W;#f?Hn!-dsy z9QES+sHGwuJ^y1k80RJ0m(SqYHL1w^Wuj#{e&)QCX8P%5_GA%IV26GYiMVfcWP{r% zOG>b=;KVIES!9@^Ot6rY6Fw7nKS+;kO}khGK{d=Sc}DDq`B_dq@_Su)m zUwPjLZip>c3t=#65R#Od5s0jdjhE2G_o4GrGelR^aza$D7w>|p7I~*Dkfnq|ba8BF zZi~C0??1~j3Y0m<=M&-QVV6Ab2iP+lSvsdv@SSH-UD)JtWj~R}z>yShEU%b`IG zHUas>9;_@_T&E~k@j#L%$za6RCj;F{mdCo9F5lAX)`S>i0M7Q+cGf}t?y?6C!)GQt zwPL0Nb0pDp4BHqz6~!NG7x*ZepN$zqlch&G&7^-A5;pau>qt@lvO+qQXpW_v8wv#F z$dhWwraw-BgR~?A)9iVUoOrm9W|j^;Tohutxu_U}otdsw>1Ur1!F>I$b*RvMGFZ%K zQiM<5k?`kd#Ez@9R>xrHAx7Bs`Oe>5o*-A8 zD3V)vwnPoc)MhNco9t9amvuvqe_j^^&IxQXYf0;Ql0|5JEk@ybOW4ZQf25Dm^V!uj z=%#OhotEh~t`nt5-{?S}Itc&Idfd66&O8j|Hc6V*a zz)9k-eqaWG&C=z;ttoK@e54IN7B2TiPF_u+k;9DIY{`Y}TZ7!IMSv!ufRx|;=;*2Pb$ zVV9s*F*HHhss$@UGEF1!Lus-KQ2&Cz#&qkLE&N(K zBg^2PV91dM6`2kXXxwe`R@ohiK2-J#MN=+~*pnytN>&#;k8C>0%sH01ktC-W=lI0r z6El&YD80SEqGm$F&K(e{l3l^5X2{N^3f&T0|1$X~&;LsaT()^U=nm&3j$EL!2+1xp z1q=SNs-1>e80cDyDs;?X-$M4dCkT2=&AzSB2)iGULm4s=Qe2-Z`XLF2{6q)%a_w`y z3-FP%kbOO$buQ$#-7;-UP$)~wws&B;r{bg5e7bH3u|mlHbHT-Ww1mCpgPiBf4vePiOFseeQp(}aqkp=vqQD8goqJiE7t3s3r@@)b7%vvS ztC9WQx}L;aP+74~tA!|tQtrqV@bB4%kM=Fi{`+lAaZ;g2arHcU$L}$ITWkqN=9*79 zginYd~reNc(=NQM2>=@sHx}VJ>aSdfd4sFSA*BT6MVb*3qK%J;p zhZ=5B#kc(?-ADZ#cVf!EFy?eFwQ<0?GqyT2!jXHigLus{ccP+Z!b2qM^=1dhP%pnjZeIZta7u$vFi5r-Y`z6|k z4mWSh+-PpYIa0pH$MCnnPp#$Xgy^|O|0PG;uigOoKvwc{p)Md2>_rijZOr_b5~%fC zN=UEpaKPa@5@;k7=b4aeaB#nzP@uET7la;8;WJ2aO>=Zj`e4##r?(BS)7C#=ahl@4 zcu=O4K%30lt_h-Gq?jw&|&;y8NavgH9DoM0-|9yPbk-k$> zhh^jlHM>2QG!;RS?Tj65i)>>oJ27WX^~xMRBsEUiDrOBlm6W^S5SFo)uCvGZOrrz_ zYTv2_c)iadOXsr~q!Y+bk-~|%P++LEWwK*PP`D^c)1;4Lr(>j_Lvd@MI9O|=XJ)9& zd>e1aK_E(bVg>P=|H$i#BQZAXXTuSx#v{_6Uba5%07^%c+{*v5 zyZ+w?At(~##Mw=fs9UKS0K#grc)k%lR~N@Gx^;)e<04pG<}{dBMKsYmFl*(o)f4eM zqK=z;VM1^7^seTMEn3O5`2ASrwOg#E!nFSbqElbm<>7JEIzO=7F5e>?c#XB0#4-XA z@l!}f%?R!=1Mrlx>NnZUy@`Ob7y8=EPxz~>gwXuBHSNo_t;EIufPn~mGowzIl7jHn zIx`hG*^2|P8`#A;(y9F%S?%>GMN~J#(G$=6PVispS0EVjK%4effBLuLPEfWGhutsI zmjc$5@@qBB4T*i+Nqc!T7tAYEr>al7C#Q%`5^3({tZ8lyPSq-c2mS_nnhZ-y=9BMv zZCKyl7rCUn^5mepHLv>`JltdUmh7WlqjdxVX<69R!skL|C z>zT;yn5$ljhbHzvrgGK1`KRv4;jNK1(sII8=6|!<>?l__1v{kex4x2!2CpbNO#0ZP z>eJ>cxA>I2@BG`7@2rn~1`i^!jY&VQ8u{Uy+*=I|@!pc>)}gmUFDlBk{sY7kf<@=l zz7T>a@P%rh*A-vMfdY0XS?pz;R6*ZnhH?w*OI9oKjl9L^4b``n)nbpSR@6;ym$tdZ zcF3X0vpXeL4J3_4^YjU_q=5ULHATRFEP)vVLXi zzSPV`Y?+00KcilzyDkOm>!#8_oLu9(Xo?I7A?x-G0W-UHVk)acl5RFi-aYHu!AOYB zEryAFx3@96&$KY^whJN@0g{|VQ{vB#d7zW=ZxHN~lSNXpQWgg$Z)?nJuegJRm|Hjk z*gL#jI&mzAgcW9LsUhnpzvi`YD!ET9yo1g4@<>=E{{sTQ#!TPgDjICBCZp|*4zrKt zM!1F}k%KZiuyLb1$ahD`v!_Jg8m}zNhVtv5-qD;N)bu=jgv;EjzdxwnC`Z5hWJHK4 zhsg)QENU9Y+?F0y56hcwaE~CiNV$&$qfgIyj|20_h~hmK7Aa z#mkGmi_V^LsfB}dB_5e*%ga3Yj;}Y&)nm-(kX03&1*0VS<$+xtJCDyyKX#2Lqd~+P zXTg6@*~<(C8;d^qF| znb0GqgwlFR)Fd|*B*>KQqN^u^!rwY{#wndK9CEPIUfC%Uc2mryM+L(gtZ`!=K8TWy zH^OKY=C8Mcs*_U_;12txEbVB3&)BkE7)QrFp+X=zPKj9aq}XBfb%uO?s{4*i)hEv6 z`?KtK032Hc;neRM2q#50PUG~_bxl$OgGMAFxI}gzb=2qveT<*_Q1jMdHfJec6Y1)A zGECvSM|*M0E&G4$PJ;2HF_LB5c-pe9+n+L!abbfs%Kd=HRRqo&o;%r~SbK8fV@XLy zpOuyaV!g%&w4{whf$3Fr$wJxFWQ9TC0k8@-nFn1s!8B%n`i$-?*{7h1&g3a??c?yd zR>ExjtH~{|YF`9yJ^zsVlLtB-1RAiu>yhul_S+M+eF9 z!YF6n%=1GLLccyRpX`Oo@x!WOru7hLhx77i@ow@l45zN4la{pq;e>3A-+Qy7t>q77 zT7GfB-1m0NU8@9Fg=FGnDao7(Z$kLBuuul{Zt2dzJjNy(tpAPZpxb&OW- zXfaZqGJkiW^O~n%Ze%2#8Ye1nkH7W!Pn3tihJj!WqeS&hEmKsEUS-piD9X@`G+g`n(K_=xm3RHc5(^ zkKw6Yg5%Mrj>CKqMk$b>p`Ram_&x2UpY3xqZY{KBr%L5Zx^(MVln8PnZZq<`4;ad= zO<##rFudf-6s=r9H>%0|>ocxOXVW9$fAzz<%(rb+-KTJBxG9}vYxTRz>B&aXLGmN{ zhKpOTv6GTT93op>PjMlE2ELg@C zMM-yGO$rrGs$TJ+HqmQ*KY@=rK5S;v6SA+@`la=DDG{_BsOM*ER@SP$&d>1ZBKuUKc#@c6 zgcq;%h&?d|Dtm$;NWMEC0NV>O@uYHi{Rhcke5}6cr3{fIp#vn>8Rw$HfOkkf%meV$ z?b?sCMOjCT5q)_5lm`WvC94k*3379T?C-#RXfw%13ZB6`7n|TiKEf^5z{6A$UH_&dvbNxS#5HBmM&(D0Q=>2<>Zg z17Xc#^y7C!`7ri@(E;AI0^c|Z**(S*XZMTWFjri3MU3R0mNSlF5+&k!zxO{7L0v`cef%@cvlgAuGqa4Z!VR1Tjp5@VPtB@&nk{cST&MR7 zX_VSlP_ia&m#OGV)cqYAM^deyKLeX5b*)TYHf-`jm1YuLFPh@2*=&ZNsFsOB_U`TR zQ_;q}k*(9h95~`70`r(&tg+G7-lm**!ZY5ao#t^MkfaN3AK_nQr*Km+ytz3q;`?LNqI3B!nt>%P;CQ(5M+l6vH-ANtBc4fpR9?l_CL zZfd8DzG5T+iR9##u8;$G5&K%^u}eodg2DOto;F1xgAvY@phzKoA-ao%1vA1tFX)>m zz-nK1X{-y%zCTow66oD$b3U#ZU%wUlk5}Wqp5g^Ky8mGkJ1UOLB&3rvMmWs0jUi@k zm;ZY%!NQ<6Q>_fB)Vz{z9^QVln!D5*XNZ1zU;cr6@=MBu+&aX)3AiAxPr~ewNs4(3 zW4OyUx8GZd^J2F3;m6&KK3(~+I+3v9ZqEiI`{&7tB{GJqKikb~Q{yUFSk~V|7p5R3 z^`+hP7}x!Z!{zwABAq6_6f$qZBjfcg7vkO)3i(B$v3|4T}QYv9kYoa4K5MbKef%U5Kd> zkptKc6AbHvyW`E&0lqfX2{OM0@J?s9p!rR%`^=U)#I+YzgjA5Bie8O-8wnp|uLgtM zgoO`uXIiM6>44e+J_-1J2Jeua4%v4ewrbe?d_tLiBE_01JtcM#5AH16#^1@i<9J$- zCC~^Ct3&zCV#piB676;;cwZ%vZEX_iXcU_#NKfHqI~wbsCcvx})E+G?<(2ju;VWx3 z1A(&6qewNV+&RQmXq%GUswZiHE_OG1F$-Qga@NnAp`X-+r3QW(;p5uDnc5%NoeD~D zcZfz~jM-&>1+q7)Rsq~u2CpQc=LJa;P~1O7?)4$iydt*i>>#OVusleTFl4!_CzRwq zEp%@p6G~O5T?LrZfSA!F$e_$ddLT*p&RiOQin-0&DUU#rFR)X}=nVO_DT#aW+hzJQ zjL+{MA6s_f@MIBj`#ry5a1JcaDs8}&`BSZJRJYzQ=WH>{vTH3eL9V_n)pOg^r)wNw z^1G{s}G{*80ioq_?^)n4^F+1`Eq}AQ(Bk( zLvy!yqryV(JnQdhcZScdnSbD#$H>2B9sD6QitFq}SXaXAyx`Fa zTJ@vnxhjR4;OV-yugf$ml!N?Iy9yA^ej96u8+ofzu`fkhG)wOUb0F`qyZwbq)_LksaILL>%&r9q0 zlA6U$vnXBXhS*KV&KbWHGO))1pjD;`vfrvVCuU~mP+Xr;Pm4?_r5$U`1$0KJg@(@M z8qB8X%j=-Bxj zpXQ4y>8E-MEz1N9G@!3m(G*v$!CNbcDD}X~YI|A1ZUScJ&a*^JJ6O_ye8A7sMB0U!>eM&NDX@isyUS4dczM^$|$nnLG>n@ceu+~ z9!ZbyA);71QsEq@?ZMEg`kA?B*Evza`im%`#p#D1N0P{`q-LY~hZo1l!P;~-OMR_x zG(ql?_nY(3y`*4h3Laqhj*XTVMKym_9$b|dVVCGB0lXl#lCTuT&X63R+Us89wZ@3+(9sxiR#-WbE4JgU+YOYNaE)r@ThhF?=hFfN#|k^ zZdMnt`rt~xSMXhYkac6D(zn7ia_y6RQg!~mudFY-m0#M`ytZ<;;=fugR1md%zS4&Y zkF3GJO8pOj0e3wSI7a4=;iP)X6M9R*yN7xxx$RG#91)4a2&urcworcbj%cO_dkI{m^v+SoCo?BSGcb;RGC@dY6p| zV`|?DPko(^@U!Vi>(Rk}?W@N@2PG$PQIT8Kti>lBF^x~PRz~=Dj+pLNK_;gU7IXsZ z`)L&ZFUV31cxm__a8G`%aJBYLuXB+c+tp4%VQu&?n&qZn4QKOxomUdkmyE~EAF`}! z9#s#|{Qf;e{_i~fw%>IX-tJa4G#OsKj2sJj%q#XbU_;Y(w@z#`ep2s8KKU=$#_BDj z_VHbR@tgIMUQ;rWFB%p7@(D7n*V!ABw~SObdcj$X=Hx`gq;g#H><@Ds1~>FN*|WAU zeNBsO{U${R;`R{211P!Kt6GrMsQvf(j#HB(>wUk*<{AEzB|!x27MJKa@j=9oJbD>7 z>GA5|KYGoMl5!3+epc#@)6~FDjcdw7*&=tINl=UUslCzp?m{X1z;=D%k1&-fRq%Vm zR@`CVLGBc7Gu7!Hj5+4~d;ME7`jQ4falT2rJ2TyhEOTDMAJr8b2Vc zT7Cn(!zFuuQR+D$)7Nkr%jUjmGh?pXq_Q-{RKL(JUbg&XmA4k{U(vXNGh1SV`w*-x zbn*<)-W6R8hH4Fj^slT(T9>qALes`GVmeOwt+lTnmRbnPJIdUEB(?e<%33%mYiM{C z?is%!CX|nPp^|z0KqYL{H7IbXx`G5U;yjFRy)G^jcE`4fumGJz6)k^4!2)M2uTzhqTYBxbHW3-Zc%sv5qGAOa1 zKpM_(cf6zC)XU+DJZNkb2xBc`{rB_p1c*<|xqkka$HCB16VcNoTJz(=_By_Xsk!E( zF>vJ+nzZoa%&<1XMLBKayeJig5I9I^?H` zC(Yg~92;cR45I2&Y?ORx5z*joo0*|-8}9gEvrCPYPq zmNA)%Y6GBu{}&qx75aRfQjtke(Pt*wXzYc;qEO^&hq91BJ{3w5tlTmMkoJous29`3 z-bz4(`&~LmpICRGBsgL6&SD@PANs|E(-N7MqQKp9P7NOmhcO1rY*%Xfxz|#ju5FhM zmoAm^fdd;I+-aoUJ4cmJR48^jiHhw$V4t&@kZ$CmGCTa|3JxDvebi#-xhlGh-QGq$ zer>=oAcd7IPxbBZS#yH_DQ{xp{A>~#*u_ZZ#`Tikq=)%WLDY*W*fUP#x4_{;SK@b9 zAL%)4gnfniWAipFKYu960%XbDsEn=(?xn|dLcu`L-P%105gJNLslT8cWR&QeqV`)k z#OsYrSXNqGgBdP`L#&idm~Noy)Zr$YDtrk=V9N;0o_Nync!CeE;jEt=CJHFG;?OZ=H^^w zno)y#cv5ug)!N{Kfe*u{n8M?Fpp4r2pDKf6VS1!yd51O)?t1hV0AQ4n)jrMg;~1Ys z6eGhkm2C-6)Qpv!I66gYEue&US%hxWZ(NGYi>H=u1I6D8Y^h(;yN-E7A2i$IOZF?X z9YIH}{N{>cknqO`2ntB|g5Zxy?jlM16r;Wzn^Qb-x6IrT8~<@l5`pna7>M8xaAn6Z zI7J?)3-mym!H1PFjeZQ>ATHB)uFachNTLsd#%$G#Amosjhy}=Ct&6LDa?kHN&Ne@+ z5e8B*$vr1}`x8Z-mSgX%o_yuqvkQ}Yz_$jOdp zEM$HZU8J*@#lzfb-tB0gL3JQ*h3)R{m*PE+F*`?Bl67CPQAprRX&4VbD zkHcU%2+kL$?a3-hap|2PST(P$+C3rSfe?-v>^pA(6(KMY8H4Ob-`ga5YX_j^aX~&m z=QmhSX()50@kx9+SyM_5u{;AR|9yCVc&eidrqsAs>7INvTH5kdL#($lxF z!*@aQ0ISA631^xePI}s`GAX-9P|d^!M0~B^_T#?=!`VRtOuCZ9Qe>W4;5|E^1H>PyQ@&&|RoT6Z}Zx0CArqyan2zwEZOX;s9yCLLl=8UO?QFd_E3HAbU#y-R*mV z!sNa#><&9oernzBPKo*mN||@{e)Gk=PY-FG?Iw$!QlkhxdCh%bxL}iHLaX4p;@A}G>lIcu$bPANuA!1z61QP>QE=^Z)R&Ia%eGZ-jP|-7L;blwI6h}u*ejgl~ir&A*m&}OT~6{uHrn} z$5a`J8eBFqZ9S^EoS{<%=^A$@eut#e{w9MGJNdud5~BN`m4x`Aq~>Be-?5!ur^@&s z=zl-CH=eqy>1aF(J+CZn*C1x7AfcF=?KO`wN(v5Evf4mR& zX%iD{)yuE2$9zK3i+myxVQ4Dde-_J+W&FqMz`7c!3Qg9j^GE}{RlRv|#)i5cNgOI0 zhN#R$$Nhq#jn!lKsw9pI@@r%W#Kt|PLnfa5?_*7<-9=tNT}r) zIbejkkDL$ujm-%tpV#HlPWKyRrwKIFYx5DI@Jcui)?6LK-zF}%GOs|cS{A<*HSsF(sf^m(RUc;$C zP%ogCcj8nOwPm%HwBCW?={{emnID9u2;&W#X}3 z@@BZt-gPsZJ@@W>vL^o^{^-;5&!77Nb?=HHj-4ukUtKl&M~0X?7LhEpt2Z>}`F=c86>ThF(%=9^;s z88(B~{1CY46CPqXPiWbJ7DZA8-`5jybb@v+TP6a*EByL`8ptX&6)4Q0 zEG(yV+pSk+lM6=5p8#X$@IvY>(;2vxM}dfPH6w(7iv- z)3XzaEGJwGcNvp9SwuY`O7RV*jtpX;`Kx27`f{MsB}4ONXvSWPfVU8WsrE+t%3i~} ziJVy=nERxrU@d{iBSqp9eUg8T#1-p$>3KLGcgpJaq6GWCRrdWKnd;R&+KN0l@e>7< zNcMEpr00bzrOsOpZX&6sU9-o9SDtQqe=-hd63|lMR-de3PwGQ0tSE$@-e1ls#WHrX zLCviU`O+8Y#=0=d)z3Dj%zFJy*9Va$wLVJE1i1o`u)}F=pjRVwFkoR`zvUP2*(`}g z7%plNR52>++5)8cm$GjBNK&RI=w{R)3^NNk_v)3ztu5Y?1Z=SUR&Pn`gjjqF{dK!) zWN<*?rri<65;bi2v;@wmMkB*l7Uh%v%V!+A z?}s>W3*_|pTPADn5;4!Yv7NCXIFv*a&^zTwuEQ87xsKg0*86B2^to*3zCw`f0J%>V zt>N^;sr(P51^M!GC;{_@_9W78r?NZ`EGktGW0y%4xD)(e1h+S|YF6yIru_%diV~Zg z2>kNyT*)VW{SA_qE&<^9t;V&KxFk!^fA_I^Q4tnCRV7a0$D~~mP;G7augu^4nM9`{ z|EyO&x!(&7iK@VWAm(kwuzeX;3S;pjQOp+dk3d(imb8%uyV9!u|)0Lwnl}ACQX4y-_fphX6WQWNX^P? zlcOA`j}I-Xt8UbTKV7TK-lTI^A38(-s{V_WU#rc7-s%?o2$Q_3*>Lt>T7ad!pHWLo zJ-Qdn5J+2%xon7PazS#3IWxhpeWBHd+V0Ri;ZQH=e)bO``gxWFOLJ9`dQQOIAK6Tdq$_`gOuwvcZM*vVRz zYrKcgmDjKdw2NQ;u0Z1!9@D=PIhIVajuUOeOv|^tm&MS$=T?N5lAqPAN=mA51|Pq- z`d11qo|hB7I_smXUwqve!0R`srdCN@L+uvCy#ELkOB%#~^Sp6;VwPdow~BN+ zHrKV484Z;A>t9tRzGgUAlaZqa--rHNS5Ssj+r`VYKsc$y(o~lUy{-`T|OPV3riD zq;}dvZ1W^%hmi-mZ7F^EBKIWQE5fL$@}<*cD$cxwtdO;$Qod=-^>YUQjl#Gd0{m@5 zXo=Q2WPR~v*E=Mw@RA+uBjdhf@7h4F$7?|xa#{ZG+zm~p0RI`&RrwK#LZ-;flz%=M z-_m-2K%0+-LZD@Z&o;rp!&EL?&e;V%pWV>vKZgjjY)XB;#WbDi-P zEr9khTKkeHq2Vp0r;Kx*t+5&1Z($x}N{l1r4<^&IHW_+gv>S>?xK~^+^}l zodEmUZv@&ra_;_Mm&XE7>i`Ug{f{;~!Ywz@~h zglj~Fr(>gyDsp{66(T)w57xKbiB*PaY7c%-%BusfO(SvZ!=i^}NfCt^%hdm5c@K$s zbyGx;hxf2vvO)-g(VHF1 zHGsSj3pQWY)h)0kkDiSqoZoN#eXp!>|5k(bm)aNwEVJ3UHE_##w>m$OO^MQnf@+sQ zB64<7a9|-pR?6^2OvV$UlQqb)@m$5t<4GsaaUW+oMJE>H)LVlqd8Tv`vC3coj6G+P zr6c=bbW;#*u^OxUDg7No>VajzR_g9qJ(n;!JI&D5aYI$v2Y|9oN32ZI|H>b9NJ+&dSYgMy{9U+!=)zFJQO-zHpKaMAABUO zYMxjr#yl;d$qYY{I$8Lz$+0un@|b6+-!)kD?WWDsrwIcnan7svFGW>o{RWjxjpc-9 zExriEM{8M=SpHt2l8@ntxZmQ)S-`$T4at?O3E{}3VtSdY`f$AO!x`b`T>kOcx8+y< zYd1zw!BT1nX>uzt#-`)J-*Bntd>MnTtKgo(uZPYj^iN*+X}#~+#Rbq#G*7Y%P0MiC zFxUA+lrP;}AJ)FR=c-|iXJsLgJbSj%`p#g+qhQ&@X-a>|x~_?X3k(Z=oxT=p$3Bq= zKQhl)w0du&l*SOgZYmz}FkS_+GcT4JzG0qu+TRL>Vf}t|t6FSUGF*RvWvgv?%p`ej z%g$Jl_48%uwV}HmO4FkDIN_uJwY`MrEQE12uI7;gyFj>PsZG=O0K!lq*jN6~Q(y0E z3dBu69mHtyH%!UVDM2Gng}QFOorlb{^?Uvh{9iicipr|eIe-pW(2+(|8- zNDYSc{YA{$k&(ST&%h$!68!?t>aIAEvv)Ika7#0N(+Hx4_$8#jco+zIpZ`l45G#xRnmsrFK_!r8A>tHg%5-KY{4F7okvvIz+?IsVSX4tME^>pkB{wp18m z-kcddv^Y3gL~+KgaPUndC1v8$KN;b+qSp>2_YK!zvVZ-~FUpXdar{(+_$YjPr9lgu zO+8gOf&J>R1j97)3q$P=BdM{m|FD2JStvM0UPSoN?JUo<4;cyA?HZ;SgxO$Wr6rWs z^nU-V(lYE*>ECiUx@_k0-~ma&rG;+-tpp>i7Rqdx2P{q&h=9PYKpDv37%B3SGf4_b zgeedm>-!B)tf3L5Jfy#e0&VnBCio{EiJ!}!zI~8Xc1D5|s(+|Hh3c%AV$`%`zuS~TqvJmJ@Y2{WMfnOP@WIoc4@z9%pt#M)!Y0UNgG-Bu zIhuK!ncj5B+weRMW|t+nGx)VeQ1Ey{Du^0Ff%93DHvL}C9)D5I;1p-S-e3j?y733yHd0gWTS-fn~TPZ=g~_4)9F&yITJ zrA0AzNVI1O;8>ipTut)?JF6!^Qq?ld-U5p3y%;L^CJ{+q$FN1B=j^TqKdtVhyS^dg zLJ9$QO%V|0s>3sZJyOsU)|N4}JRSZ&Je_4+lkfkHzNcDDJ7*_Qo2h(K}w`M zN2)kRhlntwK}tyh=@b~!T_dF%0sa2(-;@6Xo{ZNv#`#>;ay7I04uv1={T`jf*00#-4$8`4qq?)sw_pSsPz zv_%TzL!SG;x++V*Xo(|YY_Uh18 z%Q^wMdX>gd&P@gF+`65CQB6>@x|pkNJ|%apWo^G_o1)F;V?h*qqOr;gPGWZ|TUCT? zbKOjuLQOZY!1tLvgSclBJX z&EPV^wez!1Xyc-iRQ`Df32Y?if3_#8XuP=adheP3xD|#_EXZZpF?>q*l#0AeTy1@Q zF{+ux2RXyWlX$l)R6V&Jt^X6t(eG*Jb)?8*IUJ|WN!Fh3JU^PBPIxfi#L#L*;uIpZ zJ^n@Y1pk40#!FTZwuP>Xzb3fzFPG56NhvrJAIy8}8MAseJM}aX9`uG^2u$afLd!A& z&!PflsraO-o)b^{fEwDz-i5*8EXD(Uo%NBC2F+lU5Gd|t8oVQzU;0C{Qr~Cx*HI*b zZ++v0mGHSlaKfD(cJu5Fx)%s=2_o>gC^#u0{^+gb$lPK#lb6RhQ0VR%##@aw1-_2t zxdP`BEpHedp|Ivs$H{!opCtIYuP}NjM~~zpEIb}%%kUJ%jRhgkkopG!38N)aM_S@m zb_>zi`PR8syW40+7lk$9PuC*y&Hp-LbhT~Xl4i9w!!yi*Qs}mKXe>=eN}4Pn_Sz2BCk2H z@%?_$&C-H`T$Dt-wsrvSz<;{Ld-~KZ#~j(`3>{n!0pi;!uOuE4@sou>r?bRgMNhR8 z0q0Vo&sl}xO$wIr9&~Z{=KkEw0P{ILhYy3U3Z)bJ6oUw1V7*b}Nr>>g^~FW$)`?6E zmj-Yt-W%3nCMm);8tHfMb`&%$&a}sySK+o-Dk;2UG~+PJnR#>>*U5|#3(G%=nuLsz zQ?^i$v{wq(Uy?`O()E`o`X8Obz2k4;bC;U7J3};N9diG5Nd3&lGBp@e6)g#tp{8KeR{s_%nZuv^c`gp zU9kbzQ+^CDlJ7HX05hXFChDu(GmYX?cQPlnzp66`9eUh4NS8{XyR-Md=WV+^;5iDO z%2`m$A64p?s`BalcducpZiDoJ7izhFoZyT9mr8z;h+qVVaf9E`NL^~5%w*ZdP>Xly zXiTb3$g3!=UZ(G?YA`Sn(1c*8=+2kZ0eoyJ5379t1IYF0G?;aDLO)>3hHt*r?0x@H za=ldXK7yp~p_=~&rS1LeID4P6r@Y%+Xp&WWDg0E>5rdzh6p4zi6r;X5Q-o4ZFjn=i z!QvLoXQ&+Y(ls~}E4>D)xys8+@?39-F9VJZdx@+uWW+ux(x7T!dt8j1W-?S}Q8|D! z{aPqjq1%4LC%7!>=w*DvPE87z^?A^or??;eSddzyR?}wA)dKL@X zgxYQzvuYoM#0pl|VM?)bJzP|@!YG0fmzqqrLrIQsJ!fo$9y)ZsXYjVB=VKJy-(6H& z!!hUI$zcC+ZXK|2#@^_>WxN=)wCH0_hu|)t?R2NoW(|8)U`QdrZyuQF9KSX`+*`hs9QAk2! zZvqoDMIr|deRQ%Si&(Z{U#FuKM%h($qEEyTD@(NMr-1r?zlLj>8+PkAvX@u4{NBBv z{&%Y%K0?m#2gd!j$nW`XwnKJC9s|cygpi1OW$4;E+kC&a@(62jGmGa`zw3WM1C1~a z)wL50<_ClYNFaSf9)9B$5dO5pCk4_NFKdz-4Y1dq!De0GXAa(Wdp?~Q^*QsclCbz& z?Pn42MWRY{f>e<$pFWRG%*uQ~;%&Ze&~xj*W%$&;2W|H6XXMxRvZf-OAJHtODAcj#M*9WL&kfBj zYn1fc&F+F>Nnf)S+Ex|c!nSi{$eBf^yy(~mfpOuR?3l%+A)ltCMb==Gj5_0v5sg~4oFrlJs*RI4cgU8|1D0|myKO!numiTL z`i6vSy_agFjpIl6l^0TvP<0SXL8;5=$j0%KXX5%BC+D=X{xjpegpiwHlPq5yn>`2z zxSgW`r4M^Yz>`!<@L&d)f{?brY4x?M*`V5PN5AX**X!ry)}Id>?fc>SFjh;+1!na& z0e3cty+Uk&{|es4)5JeM_9&GXjbiPQmTB?L4GQsNu#AC5fyb(hJmWDF7xZwI!9AP3 zl2G7#4(wKfr~0SWW7}_-w1xZM;O8D%z@OjbWUjiK@e-WHlH%^>WJUF%e63e%QcZDNzvspj^Z)+& zC^lG@F!8>^+NOu{Ls`cUIxGYy!7SD*L(Cc~l{kvs+PHjT4L}HjDhI`;L7dWWbt5zL!h6k_k;o&Hc@9jQ5rEPG zp1f7rcAuEsDi--J8H$3r%8!my?dbXp$dzdeG`r9QX9HeoDMSt%KG~seS{XbrS)yvD z$A7yyC$dvT_>MZICkX2z!6~$2+{$`X8D03ZQcs^oCCp;)#~P1 z;1pafb714?8RA>Ax$kmwqOkBrT3FdTB2sjxYCvSi>yAF z#{o_a>aIne7_cF?$6SVM1GFnOTyy+jJ)VhWl`24HylJltvPJ!qUJB(r@tWH2;}i+K zK74S@GV|_2GRdOlt6K;0c(W}kkE|Xv%?Z6~F}3}e1AgJpkM@7wIyy(t)(46O6_aiy ze1V@>M%3}VseFCGIFe+bJY}W_UpcE=m=tOD_0Doq038*yo$5b1 z-wZA$rx?^1_BRIJKas3nHhw1}zj(&s4}I!R`Nw4aD*8i8hv?z8qvTrats1I*xxchU z9)m}z)4ZMpx~->Wl#rwBb@kZl`{A78=dgI$`y^+rUtq(FX7Zu@F0Z^I>E*7`KU5qN*)*E%bY$DOu>4Km2@54Z+DOrjFiFvTzXu=nsz39llZDzO)5i%4_R$Gx?Dc939Nhb)2zK;5fbw_Sl3dE*~)ov!$&73nQqV;?u%<5AEo)hfhYk5cCmy6(WJn=r5#I@ zdk`tF``w$$dAC}&M`S}x7EF@umt{~}2wF>>;SQ%9CW?|J@amwstL^KTMx9G8d0w>X z_&_ZX1c=Jk^D)$RvhY@Hqz+2(FUBfvW*k&<82a{EBf1?E~52rHp`j1rRgt149hfu(olwQ23gS*M8R}s*u3(w#FhYiWGR#(3v?5<&pep^3l&uaT&&PJ3(AaM2pXy z0&@+Yl4NI1gFNn4g$8!+>ZZumz@;#aO8V~#{Go7E^FFW600{?a@{Y_Ht_R^64J!A% zj3mn~1%wY~Kf(O~teTj$lRu=4wJUAiWER{ryhRo&BtQPb_#zetiO2r34Q zYs%1Uv+N84wZB!_xvqA2CCc^&dI6c?{Q~qB!aIQPRF3z3eOjub9lnU-jXv&YljkX( zUOG;rk8>9%L(=sKBlo~M2Op3=3GF_BBgYQ~XA}EA-KRgNFu=S4;$Y<-yim5a={P{ z4iBLyX&+rxlDR&D3pDJ5Nb8t&OT%O2|9FsGTXYY!FIQOWKn=TWYiG4Y?!bSX}iC8N)+(C6Oy>wAK*0 zHnpsNyE*2q^s75G8blLon`rPrr_;2^hf8p$I7KBwsWrD~I|ZC^_J(LuR)pCqg+>du zRFJ_YD&AfWChq|WryPAQPOiKzgdo=jnN=ecYzUwXpiJF&{Wkoi)l0|BgpJ>49`Q&$ zcuBOO;8lrFTdeWf3U0ma4-BJEoA-1iNI&%sp0DRW>Xfe&Kp%@@fa_Slra z+s630b&@lVk{7p>4`|PSp=+5na(dQzW5|EjoT-oi$oTm4$bTr!0RaxY!@E~+RM z0gYXhs3N6C55?RdcYbnLgGf*rqnZSpjVq%$Bt<&+0pMcQ+(&xv!`s1&QI}W*qe8mc zDF@aQP00GvP_tNU!&}rqc1Ta^viP06yGS6|gAy)0qRBEJGw+jZJg=r8B-hTTC$$jU z0Zyh`C-^<3Z;d4Ib_b74a5qE7-zSj|>*+S3iB+$1oEVCh2^R~o^Jq)eqjTJ?u$8lkJU(2D|dVf31ee-cF>b8k|wi!~-?( zT(1LN(&)Vd{h%h!v13(E4QXB$IcJ<9q2~kr3hCTR15i#{oWUfMkMUlipIQR1#2^Y; zO%N;A=7PZ6IdDIzOh6oYplk8WAMCyBF<+c^!Hm96O@J#Eqy-}j^H)b9f zXMv9`d^b2PBa>K6+a&EI+GgoEb)9(;)DTy}?-C)J{IyBPY43DbAiv2bzG%#gkz71g zdq36^AY0L7W}>OW@U2NqQEep1EK2=1X1O?KAtnNdkh7(S&V})&Y%a*@gm@g>t0t^= zKuSuk0^#XvnGadsfwKfo|3xL}p5`gS8ODPD0L&qJ>(M~!SD%sTcvzx@S&fC3j%>~D z9{<8mE$)Xj5?QEC%bF#GV{!>^RlA;z&=2>Qu{2i~x*b@!QT@u-8IV^Q%LaU>$G^zC z3D`mpQ^zJV8k028BOdjWp*^6S@39?2DXU$sOEB-!<$RbWrr5~VjdI5M)r<@s5$3tA zxA=hvhbJjNxGT!D$aZa5oa~W1|{pNK*@~H?{gk z@EGKJuW$mhI$c_?Gg~VJ~Goo>bem+ zlLEe~DK!sj*BL0OjMERx0y>c7$vIv~XMm75z!)gfzMS+Z8VoYut`;ZE-uxKHBlml+ zqbwb#!2HMS@(&<^AhbE>G)TTUHzOu5uUL92Yc=`%6TLN~?&4*g9(}eU1aD>5Ag&?v zOSP_Q@p|%D@%KqYT@ieZuaA!`zk3$r!*BHQafOhlD@D!={R}p+8Sx31JlI9hTW);z zoA_O^yvX^q-=D1s)9n*p3!+EFqKTdW!)m$-irdd)qDxaf7?ZT}Y9 zWn$XEgOWs(L*Hvomguj5eNv$8%~LU~wvz?=(5j2htLK)rU;^8h&i32CPwr5` zb|}~!d0N!otz&r{6ZkRjyO(8y0-m2#+=Sa7tgPAeceBnmzC~W=bi}?{k-Jr>*w|}} zr{-iiLM+bEjZdPh4?lM}&ei5(D}Cpk_K$*%K>*jR*~Ih@@^L}3odbOJ7t*FNmNvPy z>68z`XK5g34av6>&HNv=9WFS&SBhS`HER3^gt^pRb!^O3&-K)546^shU@L7Tp3)O3 za{28kvYNd-rq)7|bP=*ly?W8TM)%%1N|y+C?4Sc1{vGWZ3?btYQ1}9lB2vk@0KZKKm;cyog|9068 z%H_9<0^P&PlAK$+I>KLjZ@U{^{%9O&40oiAB>%5NI>j>qqc0q(o#J-yj~-`sWTXJu zX;@GRSIcu=@QHc>eyvgo+KztRt}9aB&obfWBwNKX>a7~s zvNbQ$TrShaGO*Up@e5Z2bM$!`=U0`Sgn}y9^Q69bmX5*8U4uVQ5{e>?X7%wH53YHn z&c%KP602`DN$sZan_4|KhI$OCL))HAR}e@taCwpf`j2nnEZylCF_BFPcwUhX2i^1b zBx$lKnqn~-W32o+u)_UV|1maKgqOSiZEfd(WJj-Nb0+gg@5r0+Z?)Et&K>X&Bfma; z*MW-3jzl6Wpz6`dmJ`4U{R4U^PFbr!_)CMF)38z;f{rty`~glbHp`H;GyuI_C1dnC zrej0I;euy6@6u82zHs!Y=s1EYW9Wk$G_qGDRPCerD&^$(2NvD_oxp9R;Zxyc#bob- zNJYx>uaA$-tK@C?oUx0o5(blGamkEEz&68?5l0-7^zUD197e&Uz9%_3PV)6?Yc%Th zFw2Ri`S*40;M{TK(~|8gN{kkOX-&w15QTGyfDFkhMwYP;U=LXv^+A)U55Vy zp0_8{-?p^q!`cEpuxUS7zCPmv&Aq~%RaWb^eIG}jGYw5|H0Y9xZxJ+}4iz1muZ16r zJ1$Sy3G&`glmcV(yB^57l#Q2(M#e{IREXNbBxs-7d^@nf3?~aQ)N~(VRgUbpbp_5m zs1-RroFY~)X$PN0a>Y*l!AMnY_dPyVDQ2#fx1<%K73A&KwjN8-1ZP zaQ@r%BJa(`V}q~w?1@?_5wPpXNN0gh-^TE`5t0h5mb^MYcL%G5rYp6EJI&Ze+p2qi z5S?f?2tG`Iz_7QOeZ~^fojHBRR%a!W4BEb>sL2>`cp0VcWy)t&YWhx_-p^!YO{bp~ z@@WLG5wrx5|A2I73)?}4(Nh3EIaoBv_d-%6OtDNou3GDF_ry4YJ<})v>jeeJ{14q( z`iyg5y;$gMoTxEPsGTW#t#UlNwFdp-aQgxw8R;T$vXQ@4So5oj+e1))yISk~natXp z`CS?3_M&O=ht&s_g^TvASg^;}{~trEi`xH6fdYQuAD=hmYyZTIfB&fmn|qDh)AA#| z#O1S!o4hI`6!icyAJ#B12?6QeU&p?t3`zUM`@S^Luvwn`;kfJ%9_W_FNN6{vc-Vgv zNrWAZSL*&=dEhB|US7+u>HDEC%uA6aJgQ&-SOtU_E-NJmDIe~m^l(k&sL0P>cC4b( zOFW2@3^I2}0mUYRGc5aguexVTrfZv?m>r#ehqZrceEw}WI|))BkD4h~-bt^>gb1Ad zDOTYmpwg!VrI5GYZq!1((l7AgR=49b zPEKRX@|q1Olil`PRNO^~D$=4G{8ZSjeG-Z*Y5b6=55Mu`S&D^%mU33X;vv5TbB81m zpC~ZA?rd(i7AJLCWUj?+1uceIPh`FR)KDcl2_65^XHYPo#egP4GN!G|`j0-aBZ45$ zPkC~u5%xo3%9w(Y7@9weyg8Rgc?eX;Aa zR5W9uuLM*!g`v3wn=U`y8K}r5cU+%SK;Cv@*s1k1Ocn0&=N8Za1T;^KQPRme_(Da1 zl(;L!*e@xsh#0K~Xc6Sm_8Li1ehGM(?4aiK_gN!yT# zvHh%*12+^UAYFwjNb?>FAFN2F(E5T6P{}#bP&4C7J~Du%tNj|4N$TlbdV4B+T-MpL$Ar|7#7VGX$z2IoSW41u{5`GyGa*IpqIe3V3B6~Zx2ha; zm`sfT4wh-35OlH$_c!Hd@vX8A8@kD!jh$)zN>N)5+kp_C(X)rsOh)jVvhVu=dUyW1Da_0`1xJg8paj_K4`XD*v9sr#(0wy!;OFGlR^m_UfgC$Zp3|&B%#8;ytsLf2|G%E zB3G%Ow!l*4N+FxG=UAG}Pzmn*#U-VVBAX9;ic~EP{@aPc_M-Tm2iie|okj;bB2@A( z0%gZ=*PkP!F{gzo+S>wnPq+m95iVq_qAlQE4jJ||hO0DiJ`3jl{j;8KwSB)$63j%f zy*QOm6Ga{v&7)nkJcIC)H1HV{09~%m`QQLF7LuqHGpvS_8%E0cGzXia4n9HeX>h!k z|L7RLu*uz+87E61TFV=FjtK?NYkHYd8(xv>S<=uE#h3b;hI+MyBKy|4Ob8yqR18NX z?_N`ws6JyO+ym~1le}boI7)toCVs@O5OQ8zM&hj--d0W@+CNhyrq!{A!UN1jUrVxS zDX~lSTL+Zlf@U7#(4zO=I)KjB*GAYe4I{z*cNlRpK(mo zlB*n6P84*LNz}-q$hC}kcVvt$2K&NuCqFP;fj5WlOAwFf&@LY`i|Y#w%m-eT1Vw}I zuC-?5rPNmL*EKLRT0D_hq;$=n2uuG}2rl^W$p~wEN#J-md$5Im%`*^R0xwXUYkO81Q(Th#DP&qsz0onxHxegpt{nen_ZjtB>QCzJk|uYlyQ{1VdDt-_-p$U z969%1QSL(_uj!WeBg(wz{VA$*v2tqs+Yxb4+v6>COkbBs`16qvmcv>f5FC}PH`=DS z;|$$CO0azU(LCdRQsZ#g-ss%3QGknj*6i!`n>F`>s^22k46{*-aAVW|0Guise4!l5 zrQq;1$Oh|^O2pfq=v_-zmgB$EMP>ceJ^mTz)wVU)%v24#G;mf;w!f}B=WH?lOnzNM z@r5Wf3Isd4-*NrgKW7oY-^9?BP{3w+kZ03qn~e|K!m_A7pLbCs_G0>u2Klf#8Jh5j z_74$IMHc9FA0w9TN*{+{HFB_A^wnn$x?e*1Op&=6v+!Hn#}Q z-gROue>P1!C9N6bgiNa48l-M)Cxb2fWn7iQ4=3>C>r>ZdBI@Up#_{{hN(7jY1rXh^ za`QWxvPC4r?5*7xEFo}48^@85aWsrSDOInT>g5Z$2AK^sLa%=)pY!U1bC0=3w-@U5yF2xh;PE)UEa6#Y z2d@3$7ziG?7Pa`eb!t^o%*MB|*S(3U+vPE=}G`^;!_ z3xaQ~$fIu3w;&Dnxo>FOio-DhDWySz8h8A^U)kd9&?P6HzhtRBGF|;8R!Z}E;laWV zXpkR~xb#h{S$cJSP?f6rH>W@mw*gzNAQKw9p;{l@H zUNZ3ue#ib$b$0=|qvsCE+Q~dD{jP@v>4XsadqJGjY1*|Z-OzRpgwXj>><#VrgAfxt zX$RA`%&0nzG+EQq$CE4Wz}da$i#Nu{i~J2L2#pP}GQZ)MSP{Oc>j%ywqtU!q_^gun zntSsJ<5FCyr>7eERd6V?#LpQTU~o!{l86M0k~Yle;yfIbQ`d5P&)|0t^Mm*I_NQ{t zy2q7}Eym6rUeC82R2C(oxO!t^5y<)q2f|u!X|eeD`SWNn1}XkrglClPUJdEv9j#^u zZIZL>3Xi}Z8tA8HoD%M*u{i3I{1`Ey-?0xknEVAFsO?}kfon2jONzlA{Hu>l3+l;Jx)I*R2#!EaOtAb+$4u`1G`39^BOhwXA$ z&^+(+IT$aAU*V#-<^-GbPOQj0rLd(HwlDOd$$gR~_X`@Ppi;lP>#fYSy-L~B&q2L3 zzK7#4)&apcX*bA}t}7#4W;zj^RPY~AY1r!&8KsFEHYTl)_Y{?%<3K&0Zps67*L|^i*CgsA8KaL~(?7Rs0*m)Q?OM{~$QjC>Jla}44GS^+{^s>iaIij}U!(crrY1JUl|J^= zYwt8Z_vt$&gU$}A;-fQ$s3s}UeZZM$M;tkk?VHilhcghCpoQR%C4!S(@M}`tBU!aa zg9v!3$^jFIy8N4D1Gz8gT7wj`riuw2XKJb;d@0HD%zy@VI+R^WEjM^a0yBvK>BnLYEq0KFgAjWKoLf>uIz(EFSKF-Um^L~Z(oh-k7AfqrL759REPM9>Md zPU7LPyg?^^d3B=Yp$FgMHct|a1~RFTQ5dBpS+>8Aw`M-2DPPW45_>La-y`7yH<0m= zeNbKcAK=(N>#_c(x8<$iIUC`##Y6UQ{q8*vE+qeF19l!vR(ZPHWc0Wm6(WH z^28rpuE(>15nVG9B13D+y%4T{>9?fE^#2G(*4hLG>pkKFj+?r^&27!p)aC)SmAkQ-}^CK;|~{aN$W2O01`-~DiAugo_Ebvy|1!fDPFgi z7i*x}O!V#^9|897{M`jeVnRi9wn*D#u6oR9{4BvgX1GlU3&8P6ZQ=_Q%B>qmuScv?e*0P~7C_)OY54R!{CAOuCiC%84*uBX~?g{oqw^~itrcCYlEN(-X*vNQfN&<6Y zNBYs^YSDtlasg-vrPd)Xj0hMVP8M$3u;NhV>$undgKq^XxQjsKO?L$K>riiGLA1G;*KhIaL znsE!J)@wv^Jp)7eZ5ujNFEuv&#PeQ%e~Ql9fSVQ#+t~5tRT@NzG$Lv@d^`3OnJ<&d zxdG_rwm9iB@gFDjx!ARh&Ic&ckK+@Z)kQ#4ejUNbZt#ffeAT4MTm(PyUi(}B(!lZ?_zo-QBbz4=*p#owd=Wnr7YryQwUVx*6o# z5WI;HWhGZJ>?kK(X_<-c6$VoDk^;J!f}_|-!s5VDe(N{JfzgRUaNheXH7k<^74p}` z)(3#W;86XB9Sr0nazh{1^D-X(&F?_teC4Dlq+6?K)yuGojr;G{?Cu{b%|HUz&1`?suu&e#*f?G zo}=3t`?X@4pfZUzc=&4i#7@U(LR00A?L-xw0OlGg`Lr%`#Bei9?>)N`&eU8GC2L$E zv|R*tx4LYwX+;O&rU>cf=fC6xP4lAPc&ty7v$PZpj$3z^XDd6 z=~3b+!ZHeu@)ck5a725q1vr5-VOCWVB@DR5bx1sO$6YID6Kgcxn}3rj2ugG&FK7X0dw)j2beLH{_Nia~=KeqF^Qlz|pfgr@Q}VH#;$eiX28W?f<+3O^8JBc5N?a ztADIz#E4TXjEshr1z~v5Adog8dQdiXJZV5Qa$<6VC9-c^zV3s*&z~{eI2-(x>4e+w zUIyFHDnc+MMoEp3DCzqQpb1(21Kyt%k|%jD1}Ez*ouZlx z1yjiFrxC0KP)YP)&Pnoowx>qNPEZj$PDpMSg7qt%HTI$qGX!yegD%GBj3O)|)7n7V zpQ9lk8gV?mw4PEZ6miqb=C--0iD)o_)1c`8^@ock=h&Ss=dv|fkMo_3g`6l70HfZd zkAN`VA)GSK<^!DoSmda>mm)#n>M^(~l6p1WAJh7IE9X_!>r_V3YbykDs^KN^TuEE?suT?GiArwj023; zSlzK{tt2L?yAhnODANXS|K>AUT%u-#`#i({blh&;B1s{!X*KWBspD6h|hg>fZnC74Qg8)^m!*{6EqwO8U zP#w{54fCK%_{DciX*RQ(5Tlt)A^Fc2a@J!>x(6rFT>oNqt!J3Dz2DE8RgM09{j^vq z>K7tBJ@`=^lf!cdV{5Vka5%bM;Q{@f@^}quKWiGpMpCaC7a9kZPd}%zfsL=)?YWDt z;8a${7BBSqFMwWOge=j_8twU~7d*$6uRNkfC7IEZhr%}90(1r&Ut9~|soK&B2~9F{ zpgbYlu&`RYa#lJoSD`$!Mw;V>j>T4~2GBEYCb97{u*4dC?4iIHY>lXo2S&eMKP&2| z7cP_Us$RH;sx-nEsx-DEd!PIhfGBBGM&~e9E%P;h@JvLKLBt@HE^8xni~+>H%<52v zio6s4=uLxDY`gXhpWlH>pxbE(RJ*BtaucZf4?u$%@G^;DV-1Z2(L|5YGR!(L!4LDx z^SxfXey4K1$T#wBuEX+llU3$)u{G+rAbs2MgiFc4tD=9o)Trk)wShgn-hW|jtJ3o+ zvp*vizkXky+LfGc>uojItL&qsWq~H@P(-k~UTq>Z0VI-KgwKf)lxPw_{tXr3wcS@e4$&`Ptac2_ZXh2v- z+{{Czf4x3t!sC%Ot!ce~_Z6faN!^EtuE@p%RX>Qw^F0UMO5^}qS2?nw#h0%$BmWo~ zUVQhE!~jfQt?Vy9a>_<4LahqD*6dAieS07Lpm^{W2n%y%bPUq3;bgO{zIR68Jd?YH z5UB5#w2wq>kAIdB&fsrn({+`Mesnkp`qSbQ-bNXnMyXc`Jhz+ z>7U64P*UlgL<}MEp-2nmI1 zxsmnUOijJ{x2w1w|cB?$bxAd^$o*@w4+UZ-S>mCu!%AB2}icY^)@EULTlhk}@@z zX){^+5P)arHDVq+l<<)p(?^IV+;BoZ7oK1zdXjEM1xX1k&dN$EOOa_Tl3yOzpJRd9 zJpjTYTic@j1J6tTc=5R#O1Uc)23lloBq#4`)&2(%f$Pke;%a1L8Fs!Z^j8nAVs6Kz zzn4bAqnT343a@{=eW&tQ09e;uH})2 zLN{1MyRs|y*4(%vuGB48#^vb(EA+WF>MXLhOVV`0!E4Mv!cVskuQ`S!KXwTQh(!L- zoHM6BU$FV`IeY~4ONS~Db(e$+|3VlbZ1oZn|3xdZ#eC=4zc}GEWVZ~oJUPWzUTC~F z(<%AaAHgUtKGGN|4#PZm?Y}WQj4kQ*c#{DTD?nW+4;YxmcKQ@f=G*AwLZx6giR7~- zw;690ihytymx!822Y8`#jn@HXXa51ZiT`Mu@{V=c<|X-t+et4tlaa(`*z@Z7>+_Mv zk1i}jiT~{@Mrb7|0jtV+S0KH*2ZVU8=Cs#&CwvVRpX`%n`>Jql!k>2yw%!sue>pl{ zF~X%zdChjme??ol8qtQsRv!Oq)_g$d(m+T~3CRT9G0rI1Cni{`(6%457BI3c*M(C4 zF_S9|AGM|WVi6svdtpqb+2CrM^+?3(C7>+tseE|dN4sXlD=Je&6TQ=?V;QYVI% z=DWZNqEA+&I{0tiN#Y%q#HG*lx(~YkqA=m==}-*Wk9RieSiNfwdtFvr;_K;QBukl$ zq~skZntbT?y(acq5xyn^urc0Gwf3Yooioa3`p3@6f508(Pi$4pxMu$Duip?&VE!F5 zdqf9bU}hp{FHlI7$9d?N_+~ywS;RQ6Rx^5rC;bvlj?=8VsCBjj!!NT|xyR|6m~%IG zQMG4%ZMNQqztJ0!zxYIP(;+7MW=1Zk@ae02R&V_yQ-{_OLL~CaNxz(2{$wZHadM$r z5mT<0zx(K3pW!V`Qt>~;_GCK0R=H9d`di27`w1TMNurQMjreMCe}8E-Ri@kxepQ6Q z_4)pW;7^~iLo|8*(cQBmlIE<3k_)-7_^|8TnGoV_>|*wxp3HQzNcm*T(tauK5+nnyAF$+2=9H-c6moJL&tTz!7lH1xoc+W?7rt zZfwE8)%$7`CFLe_ZtmY#)P~nfTrKg-6vDGJ$y{dMQI__9CL6LzH-}4J$xth@v|aTP zH*?Kr!dUx0*PpDs^>b05lkL*e<;|tIHh5ejEp{S|sSio)CPy?xrnpoZqX_X7ZYCjJ z*Akt%k51qNOuTQyKfT(Ch*J34{_gI1#H*4y7jKO0A+5c}PpUBf=4<=oYF!C^3(MK4 z{Z6CJqgk_ki92fkOUC1s?nk&*p@t`Y(IhuT=SuteO))~TWJ>p+1)q1~BV?T}X+aG} z*yWPWbXoj*&ixV#`8Q~tntClUQl4p-V&@0(@yI8nz8a+^v#*(*LTd*} z_L7OQemNR41{u#l5Iy+(|3C79;3H;+kJ7c*@$4^E%rDG-$wqx}zoOe$(^ORxD2TQl z?eE1vtpnA21G41~YSrQc^h=@$xO{BEF5OQJ`7VO78_F8R$ilbX_tKD*wlQEQwgqO6 z3A=jLZ}rzlW8C4r_LO5tg$O+-$*5P7Tq*Qy%UL!>olR-EY`|VoahtpDf>@L~Em_0u zKY;e7ZjtSF9~j;WdE>4KWBrjf@R>Oh1VWBC3ARYWa;OdJ_LH~W@dG*A0I5lbMsN=Q zHL6Egp;91K%Zfq%b1Lhr15S5!TP+||u;w&umr2>7U*Gu&-yae$tu5J4%{N3q?Bbth z=m}?$I%AN-|2+Mv3XcI99bRN~Rwfuq64F4^@+sX+2nfv#^?-GL&AQ&0gG4PIh4+6e zz`J2cD#Ph+f|T%fgIc1(2UOj)k4DjG8dYI7bdV!2G7NrlcyY`06HNf!d2 zK4A+F?1a{93Pep2)j(@Y_ZQWq>>H~{Rs1BwI-36j_Qs%&8B!D?shz)FooUKF2Bi*+ zIen>KyZ=>n!THrgu(MnT5mR~`>jMf`g#|2~Z<;PH%ZGY3-Nxw+SEGD(vw^RUq}&XE zaIgHc7!R9I{Y7R%ard6-dJWLLmr@h92T)mP!d%1tdjTZgs?781W^BAN}ba_4VzZb)%0~h{?a@+9>|sP&m>GL zsnoR-`ajCvJE+O93;TRR3r!FR2oj1CrK)rZH7H%_RX~a$O*(>rlmLQ)A#_9t5Tr}* zpj0UVsnWajNR!^dcc1s0E#J30JG1-8Gf8H`B!N5J_c`afe%Ep@PfSy%3bUcohbQ)- z^iFZ=uX}9vk2?X;=Y1vI$nH+bIYhKpAJ{>$huZgc$t-1ut|?nrk%0|b>tw|WwKG*A z|KSuh3nbfGYJ3s0jZKy)OYQlywSpA64NBKLDmo}#)z-3JCglh++0r%F$VN9w$<$xu z#q(teR#2E69pkAzX3wOI?tG99Th}xDYwsNUhLb*5D7Nc>*((DnRmdaq^{+n0A6y|L zIJGUc<3bkEiugF<#5C?DRW)bUCn~pXbc@2Oz@=sO4AziFAoT zT&WhDpPQ-C(}b`il0461!wVaThuWgyvt?4Uz+aO?m&vOmRQ{1DtO(#PZL5Z_%Ks z!h{{-siG%z=v_5M{?d7UuajVK4dZYSQq7ZDL&JwXVy}thyp)npcPypwNQkb+OzGUH z0i=2wqLz7Jwva>x3rB2QiWS3O{^DmTVF_Rd=DXa0n5L*Gr;4UXnycTr)$k1|g85Mo z9_l89yo6*$>Q=|ajZ)hMnPZVzQ=atuJ1Dw&Rtznd|D#1S*zhUn#D6-XZp2ZKr=qd7 z<#fF1wnJ^r@wqB)NY9nbo|gk`wxtb-#r#M$D^|pLkj;qSRwkQ^*(o?=|%20^K2SNh}LW9Gkr%Bz2TSl!D)+ z*@cJ$Ut2lpNn*QAR^DX$KuID5C=@po1OS~58>!s;4V$T$hkIP@u-s;s);+Kp#|Z$C zam?{G%rFJ_YQtdeEi17>tx;fMCPwNQpWevnn2$ZwAxZyUQ6Dm^R|FXidi`!?W$!VC zY$34*;3Lv%%O`%XU!TC|bU{5b4!=kK@z)^{CRF6b|9*{$DUqdJ$yiEY_|&RU0^B0Y zNZ}oh7;v9Y%!i^?00_^ma;QG4OObaz+@d|hQ4QDyr0^6~B1o>toLNGY ze)WF<7VY6reDow}m@5Z#S!KbOr^VD0Fw4E`ImvPLO^1Xdn>s&4BTX9^CL@h^mveN_ z0^bDyw>`-P!sW{SZAu_!7|5C4t|ur7+|(g)73z>wz8@4oi}BE!&T{u3wj%maEvEwD zCx1U4zVf%VOA40utSWph_lcuOy^{Yi48ml)>;_!um2(F)tdHkwO0S-(v0jiDF*w}B z<DG%+ex$E7%ELwm5 z@c31@PfoX3hN9{E>)BwwE(FR!#AG(tj~&{nTWZ@kKtstXQTvp)%-m(pc{anh^rOlZuEs3;V#W@j*Er9c z`Qa}YPxeH7lfZ1pA^LMHG74x|4?%G~ocz~k%-H>~)dQOoe6*Q81Wu3mc-(#~QOWI% z9F@I(hcahI1^TTUeYP=gNd|a8r+NJ3zkzAFxHCMNO*#0hA8)Gr@qqr>LST{>RMt2k zm+UiXsGLCVp#~RuCDq_lkf=JR&^pgm_2{EhHfK^6U3mV?U7K3c41v{RMf0Bx7x_qz z4V4e?Xp5zg+(YCh&f8&$5r9We_qzVQYTXDyI{Nagn1RRF8j#(89AC!m>hta%;;Hw4 zykoJ+km@u{8mg6T^qMXKeL?~4`4T!9r1J_xKcFZos2*WCkg_DM6L@a0->2(U&48`{ z+V{hF#bzBv*&((HN@67F@TTlG!nz~FB?LwrKRw`R$M6V3_1>}j2rR8)M~~RwzoEjB zPFK=6i8k?!=rN?4aVfvu>vb~lL|KZ8|=kBXRoEnp*F)bM?y&9`Th zQK`bTwm_^AyOpwSNtj39qxnq9UJk(ZGj{!~78TdS48J5g3w}rVh{ww+!9zucF2Eo# zFLot0^X1UI?C^kL?Wc##rji2R+dby<)y;A57lz1lKdAhC?ir|zh>veru_*%;kIx>e zV*N)&VJO?V15R`*5XYK4Z%kS@UL23WNXOFq6c5&@nGr96BFPc4=yz83VJJo@txu_^ zf~i|dMbF9GH@V(%##DE;^`mUQB~ABtZ-8RRYXUd+KL-ANqxaq+MXd>H>0go_-t4OI zE=2zsF0``&gxfRu#oV&9iGAyDz-rA++dz0epM>CZ6^&YWgP<-S-@47l#*0-3j6^s( zm(3p(${Gkg#T3x9EsPEqnZ2Zxy%<%hht%#}7Lb@!G=8}+Djk&~Yx_c(`~1acTHfCI zVwGS{e$@R(wZ3cv4iIZv6N*1_Z^u484OQ$WI2D92|BP4r$CPp89TG3(38NoC3s$QA z>!&UuGNNXM!Tco{K^jat!bsJ&oPdm-SpgQBlSTm3BQSvR&Kk9gMb$7^WhUKWFj zDx8!5qUu)L$}tSs4|!HD7B`%_z_eexN&ur#tlzM{FwUUL!s~Pzz{`m+AWjXvPuR=< z92pD2oG`-dL3)!3QXlU%;6P$>y(;!A-CNGC9ER_AJI?LWUJ6kquhh#4sM}2! z?_o&%z(M7N(a$ZN>+%+whRG8MXYS=PW{=691O5$U-YtV!$(6S{WK=E*Yml%Z()m2> z?7P|C18kC9J>>;gzVm3@XEB_;tPZL3!nKo`GARj>7$gG@@MSA9GL;x>Cxtm{y9zd) zzP*qQP&!R7AlNJh)6UJwWF|faC({OCTqSDcI-Azp6~p@1j_I`oXZN=uL&md~lnM)2 z1-8qlJei$w%DF1-yxR_K6=%l7nb%qtuw0av4;`Qwi8n2u;Ai)0f(`NX-OKq;oas)} zGE$hC%E(Ah-d;>>1QT{ndH#mWM@weye%%p6*yg5%_7SmC7By%6dkPE0$YzeysO9$Q zuFnXuw!7mhkLWj1@F&eSq zrjnwSdW22B#6{T!xx=|++y%d{qWD|en7)yZ+BK*91R3;vdbD(?O zdnt}rF=O%quj*)x`+_?r4w)_tg4@c2p|U~rh_4tLRijeyO9sLpDzx~ znBB2Xf&_vP>yH|E*ji3aT{ISEb=>LA$+^2fTi{7Gs2BxgXZcE-jT=t8Yik_FkX;Ii zrc5o6`P>1yL7@RWH|r0s?}hpE?|x2sTJ4fZvbnrzxl zWsQCzgxd#Et%eG8zOVbbZ-;+u_(LAZb0H445}D=iZ^VMjPGO;UYDwtfz&-OXS6Wiw z*}?^shY+tmyEXF%*bR4;xcrMI_1ogSZ5Zl>u{t;28q3YC39o!MHIt*Ol4XMxr~WDj zz^QjLCr6G^)mNF~4o5C_N(qL(wK4pa1(e)jNl=L$13*_9_P<=lgIv3M3R4PdSNTD} zhEc4Eig&aqw7x3M?pc!VemWIV;!qCpAwCPMOj|76ilxNUui7lzqrD%HoK~K+pNvPd zx5=pd>(9hr3NGq2}fVlI|rAhs`7KcUHk z?46S5%?C;dQpjx->mVd{JHUIzE;|{aC+VqJbVHPTL1eIy*)YdGfl(N&NyYI%dW-pp zHch;*+*e199A9PbWnPJAmxSlpF*Yb_b+;stRl9E!Bg>_QEC|s($>ca6hHil-7QpC} zFF#s=Ivz>QO)fpg@5Kz?c;HWoHcZ*Z=96qyoQtADVC&& z4Y|L%<1g<@F6?ciICA4z!j0WrHJ@(13Fz%!SI_?@u4ouRz06x!$l<;k%25xdw3OPo zQW2a-`r=(?GUx+_Sx}SU-bd{-F5+U{59l|3o}zu6FuRoSB(d}Eu-72Za9-*iFctfx zpyYZQuF@j|42X!;in&gky}oH!I@Tj)Ap&`4L(l9pqQ_8v z#iwA6VV^;Luu1-g$b;lY68|C69^YOu`^gLa4ArM%{e#s|B1gYiZx3+?te{sv z_wu7!AL^zy!3kRzU0&FfugSksW~<^_*Nu44lzT0%e?!r1vcKChnpFK?3-8=Apri2E zH2iBLQ~T8li_w%G-cSmR2aG}S0CGB$j|`iAZXoab2!CHr!0*=6mop*Vq)|me%CHzQ zGENi>l1)?e_$MRk=#LYxBW@LbGirWu@Mn+?Y6V;UwPNQ-G(k?(6Qo4$_=dFUUp|Wc ziXmxvkmp#$PoB+N(2CsDyE`RWjuf0mvq)eiu4azl9>chwRI_;6H+R$AyClw35$%>SO1!wJ9I zc{7rjsuS*O;1Z_OS1N*qOX(HE^nQHJL3f$I-A22w9i-Ilt-hLR) z(=lL`+THJbREXXEmV<~irr`1#pwMSEQ`IGvp?5$Qg+uvw)lC!?(RN>fT3ck0cJ^X81%1&$uO~Cy7~o1+MO`}(>yp;H zfjDeE%-tVdxj4$PU7kz@XmeHbw8eA3V}`@^>N~~rgS*fqXO<~f{MimJ*-cWkFQbO7 z?76+SQIsY`#6BM#$;v{ihvBv+P5nL}(9_+?{lY8CgUs5*JBOw&A8hYMXW$RBuZs23 ze@=E%hZSzGqo@w-^DVqIo>hcfTsgGP;f4#iS7LskZ?=6SrlPckw1;t1v?w^WE-Ozx zm`bN^J)qqLFYi_`ABh4{C(PGzJ<06=$ zIyfE6ywlbRzpj1+TG*>t{z?zAY1_o9Az4`o7W_I)-R4)|Hm1#X9;NqF1p+(WzJF(t zNA|+-yBodJL(J))R*%DZzH9TLbGQr-c0f0H$d9 zfRE~pi7wc=L4`Rmx|wX#xR^}RZR8?9_55Kw7g;s(zHGySgLcJcHH_k!q8u`7ZfAFdou2LGrPY6dnB7E^x_nn(UIAE$q6e?U9azCXz=MVN(I zoa!r8)rsVOv%2mJqR}2GU!@+ge`bDJ$NeAR`+tD(l8XmZpT8iJX%~(<1FzTCCT}S5 zedd)SC>oYxY~!PZ+ey%}uby6IRL}T{h`+-4kkoE9Q~dGC>A6!`C!aL;MJ?Z#LtDa$ zk2N|U`!*F=eO(ql&sAf4d+0TBwKQ8}H}n0r4O{JF&o- ziJ#FJ-kOv(+7NzAjXfWyB2|k6)V7dCE;O-{aBEL5U6|dAFw%_dvmpxA*nr{Z?&@b+ zPAd!%=A3gP%AMHu@1sZkEa5n!BkSL5fT^J%g_fs4dbi`V`fi@AWo8#M%#(Pp9%xkP z0oDB@MYJ@i#U1ommHg3=H&7{LABQCj=lXu~IfkF>J&|=v@gZAgB|!^53t3~R&OjoI zf?hrPXW?}^W^z|;W!8Ww>!tlF3Gt22fn-G^JWOgM=#PZ9?z_fQ0bmd|K1yX?&`OH@ zx^{+05L(V?*g-Lw3i7?=J$3xso$V)xTNrb6#W*l)DK3Yoji?HoX=DmtbfGys5XxGp z0sqmriTu;;oHewqJIe^p>Xq;@XwL-x7*Ao2Zl%09Wc|9sL}!WdUMi{ldi`xk_uZnW zTSWG9dM6;?eVC=gieV@!(k50)Bx`fsDE{8?4yDvdp)DC7xyR`cxd%MAQf;}!aEzz3 zFtCB=poDMv09MqY4lQ5M^|rcy+o~w^2IvNNFh)i{hV*P^B#oHPstj$hhtVsJH@ubc zuC<#97YG!5r5%?lyn@5#q3^eg+?Q(oqgXT^1!v3&AB5XTBoUEmtL#mY;0n(5N{Qsj zOhrpL|I(h9A`~uM38**rEmo3X=dKx6$Kmh62k5;il1e27Z@F~XB%qjncG*;iWPIk$ zHT=xxXD;Ti$JVvWdXNFg>Zb)=RxW_C7dNwhg)xBf;9hD_1XI5hH<_9*sjMEeURDYT z)Om-ju_@a(Y7j8TZcU!d z-RoDp^W3;L#kMz7<8V*25?@9uGs3N~asWsNP+q(LW`)GJEjOv14>F*wkFB}6V?eIX z4Ikn(mYK9=BESG~Tlt~6w}wTY8(Hi%C@p#+cg-iHYQuiPeBEHo(09b0A-`a(05VIc zWEe_#WVUN_I;>B@}=^FQP zn!gjRGo&cin7VJU?|-1F1MNe@Pr&XtHwmB5yMaLdH8R)hmmRMqV0x@+y#w@Kn|i9; z@v^aApc;+>s0R+^D2qgLhLxBVS=R}suSF=oFiH&~mrK-2(`ZrJf$93JtL%9A5 z?z<~l2sT{|#Zr zLJDk8R2%KpPik`?glN3}EtVoSk$|nK$Ue2#8Ox(`bQ<_O2{Bk}PP$5KSxB|KDKD1d zMi+7~H$nLB#u|$Ob>JR~>;9y##rZ!)n7i0Rc*uCu;BoL(sJ!T9)S?yy1h?I7rVWt5%Bd2bTonbRNJY22Ar!n^YtG*N{Z975A`SCMfCzrtwMYXn&~M*>*h_*cNXhfW5P4R=+u$M8;gQZ z-0=`Wvn;R{YOP4!{DUXW*Z6OJy|3`mvf^Q@8)hB>#t;;BHgnwGTJDoixrh(fO(1?_>gDhs-ac z0KPB(|1JT+UO~-Ab0rT-Y*KkyeOFOG+h=bkM*(ML$Do!kR4<6oQo{_!2JI#XNY#v# zX9`W2<+o}b=pNxh z`CoeryMle7&$0@rPzc%C%87WCGw8fQzee$@^Y7vJkGxYtPwO}1hFdCIrr#bvIAyvp zK2>p}xzyTq$r9fmLL|Vx@Lh>kzDzPY*$AfGqv8H zn;9XA51fF@ccD<-6D_Yz;}Rof1yS&ewcc_a^m+Y`{0~6qhN#%1fA^pybXG(sExsIFR?Ihv|`%9_mkob5O?J<}xuXW4sa z$l0m`?Xs-0yksa^gtqf-9|cFAL>D_T?El;&uGp_C4i&}4{-|bIM zBf(H^Z6}LN$c4Ys{h#8l|JVDRY+yVP^eU}-a9Z{F&Df>fy~?KT@aj*J2t49j)|pqR zUm1~SxuyN>e*nno@WrF%YF~@_#kizTWL9xkg6D!Tm@ zsOW@!$Bw1`N}g+Il}~pdLFU}gdjAVuz*gB&yz9D-!!lYvD+l9gUNrA$^La+~9R94!SY>Deu8+%^r4X4KW|7MRRMv-i zlrujMpmGi3JubgKu($G7;AxC1sbYntNOMgMXGM()T7S%}$gX%ZyAChfVxY1|WH$jy zE6Tai!%l%h?raiu*!PeZGX9yS=5(M_urY2L&0a->(64F>i$*{Tk!xv;l@%RfWJmek z9i_uLu~K;Iz6SYc<~CV{Ht+c9W|#1O&$xs{^xGoX>`u6c$fDS-U%E>#=(RTnEW`wR zJiWocni%5--4l;?`(9$%1bWl(B`VR_Eb4~cQ zRQJq?+{Rei!}yB00spY^?3!u|noK>a!@`fZY2zWhs{|+DnGT5x2-dHFbxnN(1|wMSOL!$;lZXJi`B8{$)uV^}3LyoyCR3!Yg9S%9@z=ML_0<2}c6u2}hU#laE>HuS zU-2RwU`0jpQpR_)6}J6F)CBW(DNChqCaGeBk7U}k673O_RY*4^$q-{2;@aCx&&{Qg zA{FQRM|%^+kjy}0LLB~FU(qTBV*idcFZmH+-SUY&*&>X6NI7zV-{)R6X5o;xMEd%# z<~Ot%z@U@!UD>}cSIXo^2`|dNiDYU3-`9k)86mi%f?Voow5PVz?JrT!o*ZBj=8F-U z4@A8|zw82&2ZJljdnt9~*3K~gbFx_IM&Nphbj&j7fS6yfj}?hh^auq=3VXb-6N5K( zC3cq`m&eiKw3iG+`Ztxi8Gnb{*X$zDS8`60qn=Wr5YVyus}>zUSyc9&Z$<`nr@Dj8 z>>Ff^YzI-m6jQ$4C4Y;<2U{coS!~x5=MN`UKOQ%S6L;~~k{dn*E(y#1c~#JQF-tf0 z!LtQ17cS&JWjOT?fZWzVQH8o(&`_CO{p7PcK!OC3C+ z-|Fl@gc$SmrtB0j1F8Vr*iRv|rm;?vyHJzxH8mH5hLFGpy_)87Yw4HS73-K`Zztw_l?A$6GRK`G*^p1x!k2PpP1gF5I= zAfJogEL_kC;waX(GyLi8QO_~>Lxt_3P_`^@KE=gwE5CTAlbB@i1vy7m;C!z&*fOS>Xmi&f;-jr=^?q|S$+ zkKDL<*xwU1sybkot!oXd8RoVXxlejj^n)!9Aw$)1>fO#(x))zWa4|ZsG9QjG)vNg) z7c!m)#1^|F*HP?KF}%=%rO*$jchKi_H8Ef^PRWN5NlSeuUM*&#rE`aLy`}aVmsl5t^u+U=0FEIcYmgJ30j4$drMmr?bKQ%$XU5TOy75{e zN zRszFzxNVJt#($Uu{6TXE`xK?ic3l>ND}yC-G5T)n*N+BpD|F58)0^$u(_dsv&eoGk zRjw=^GAu?&Gt7T;gE&=io6I1gA?qlP^v>`Gy-a%@!WE8st>(fznwrF2FsrfYMV1OZ zn^0G|#O)Cl;}67&EeBHE2wT=@BrDI*Yl%Pe3}`i_6a^{JnMN$fzc&DCf2ZM$-z+v6 zX7fQ1w6tL;j<ttPA2G>bqoK+M~ij4zXts4~nr5GsL<^P;5+9 z#eF%nVBW|#HdyUY!ygf2*S=@#tqSSJZ|jGJnMJjAK);s%#AC}-%u_%Q7=nzn;G3+wcwi!iskLP+= zw)frCzczt|>)=cz^{3uo7@-U_4BspI7AKVX=5O3nn-!cZo19Yzy5N>}uOY89j=X0* z0mWj&w`lC@wXWBDb8AtJfRr#L=L?UzY;RJ#&o&w%_lKmZi!F3n);3N@44uLgHw2D0 zC~UyMC!I#?HY<+}KFHUVmHQNdg*;K}>5u;b!+vJQLTXES)eg0n1D^g|iYUfTs>jus zU;!`D%Eic@ZESTkA6Zxr*X#2r6+Hv_MU1=u5?a)b%%aj|XRyg}{iiKB5QlWPGOO&v zZctwy3^EtxZaZIxf{i_r;EIsjjgdma0J= z3MAVBeoKG6?-|jyBDex`42-p^CWBPkkV?J%z*i-q1UN+w3{y;H;h0@XVv|wyEFJ5$ z{E-r^GSMz$t0S^hAmf=Y!{G}@=4a)lQ$(BrWVHV$!_K(60`=(1K?`O@V7)ueS65@K?<2@cJilR2lJD{g(VkFGVob zWla)|x55mO>oPwb-2;Z)V1&W~WRuE7EvjyLB>s-tE?WHCb|Z9Kr6Hz&)m zv*%F|27nVN$fn$Syuvwql#^KPQ4Wuv>ORC%JgFE=_O(9KfeT35ux+X16IP>p2L2xL zhv2AKSHiks0OGwBZwOYZ;5n}TC97D38-L1TNyjBiZH+( zc9*_MqayE#ny@x0Y_aOiCq7=DC;$^9D*WhR1h#2J=Sz>T?DCOyiaoZ+~r>JZjZ;wlP&W$6y6>yxn*7Ju`_52Gzr~fPcr01 z_^cZ_7jvxq$m;b%dl@Y4k%z(~XthzA{+1xDV^?)afxyM2_{Ep0{l>%ipObf4p8yIF z6nr3QvFJ+6`jw08lME^Im5GK+s;dxr@k^WU@76h)zq9nU2ae2?D-U{l3^(sy#VRZ$ zbJCv%TDvT@eB8aamLt4wC%^HgJ;LJE);;$2^BeD7SO|*4_llPcfjiaIVWi+uX*Fib z>>ri=E@5FycQg1p{=M;NBI!+9*4UG7uuo7l^14J!rN-=@pmxMGOov74HYLFMqxgTV zpvYnW`(t0#?R#J`MR`hd@i2EFtz@(J?bk>6l9KG4D5|#h>&tMifqJe}0s8IjR~JIQ z*Bb9Ex}cPouBnK99y@OO8c@up=Db3LM_t0Na)MtqJ?@yEo6jnIRcSsblWgbbslGGd zKzdXLdho+SUw`nf9odrSa2%w&Di{<>i;*A1CLJ1Yt%EQB=u~$POPRH&Tz72P_m|9# zje=pKNX%opCFQgk`J2P~zUGLPyq}Gw$-n;K8jh?H>#9sWk#0)von_ghHMBzRjLeLj z%G3k#i~9WVEU{(Ox3RtK|s#+JB1qh!;mQ;UxInGmEAJ@z7)Aj>{ z157Xze>SAmLe*wP%e$>SDe>fAqWFOSuUB3#%u8jcpA{@6jo8Ta3-I)Or#%-;|N1TA zhdp3Q5&TkUILFWH+lHX{GexgxAlNIbh;Q`{tR^WwnKTEFlLP|~A6GQPcA< z8rXGiLuC$tG}q++Qn>#=bQ1rEhT?4JAGPs?^s}I$%qpXbypPIn=OpL;mT2|izGg@> zSw1o_uJt(&$JIXc5bP9xiBMr9V+iFVJ$rQ8zerO?d0Kj)-iXO=cmHV^ACF{KXxyGgvXar+HXvcTe5rcOYpj9o_!+#bIK;+wNp8iTkWesvx|Hy{l;%(+5 zX)J76Q#=%pVqv6Ac*8+e$a@WaeP67tAc@U$!BaYH7=8QOXA_p#m{aDv=&YUA0Sdo@ zzso#V9sube^Q(4YyNf<z+iA6lkZi{m*Q&xF0mOxq~wrV_Y!j$@Y#2Lz+d>74jyK^-r|FKFMg{*kOL~5${n^gw=)WC&(xfcHDx%h&3M{zSREhWe3%>ldD33?Um`GG4N`c0!{Qx{Chj1;fLHt&mokb2n%)v7mKJstPDLV|3P&qu>&fI<#Gf8^w%MK`S7?)PVxceGC9kh> z|1Md;r9T7e`YboKF_LCzxkPk&?8TkQSoN-Jnu1^BQD+{l&=N_$kx)wq=q8E%`NZD%;R-`%pA&JQ3sLAWY2T1_i_DGpZg^dsS>Ie7_H!;d zZ{ls$7(GouO^2M^m>aXFRy5&xw5?BI``|9M{#5tk2ep+=DadxUNxFgdg)cWfK0wYA zIFp=ICokGs2^!XXo-0@!nvX@Oj)#xGBCB1CADb`7hQR|JQ)Q?f`8s_*jZ)gu%0+9kqFYLt?Yuoy__5KB{e%CL4=fK3j|zM^=A z>RO0Zm8*2byx(B}cVMvr+~+g1)EAR{G9WbA|ChJ&alcX@e&ujG1O-d|DIrUzsWM){ zmBvBu|NXA^ouDKp5ch5agP3h?1Z_lJtM76b(`T6$mQxUjoDKE#0IAr0QitnNw69{; zwGpCW)2SwOO%4!d=(?r=sci{uE5~GOj%Wm{MW6@@q6BsCa%9biVu)dyFJ^oyh~uB@ ziJ723zD<;hC!;=ZRdEjIg`w8+IfCO}#B$&aSzNtQc1L{&MCz3i7hMl`y2|CRc!fr&2-5Ks>ZmEX9`ILs=Wxkk@pQ z?%#I^9=EN;yKZXg7UrF}R5Wja;%9{jN9J=DN3S zsdxJJ*kt5Or0r*8xi+pV|7~&0kRbRl{&{VbSrZVD2FmC{=5LLer5O=M{sWXf&xpPd zaS{bw?{!})oF5%gWG-s5KM63Mx`o^zfBs1`R3V)klu@8%AO8rhx|>d^`aN1p=Ee7I znuSmAg*0}mpN0^ar*aD>A6;+iG^w@wU=#K?(19d5b0LtrYeHnYs~-Lrc34sUaW#sZ z)m2#V(UQ*Iq6f}@O!y_E)!nxst^v;MZY*oVDp#QP#r)cD(euNCzcdf}6ni%0)|1}| z{QY@`puGtsUnY~Ibv#BU<||$6L?uNs%b2q~S8(;D9Q3(%=7aEfF$m^$CtxycJsZtt z(+XQ3dyy$1O{XO&Pt%jES%IYWUn^0odYWO45aaY)7@|-q@{Hj@U-{pxS(sVo*o{`} z^6NJky*1sj#lasSU*zJ?7P11SPUn)8jFql+-wKo-qd9%?A)cM5!p&5uEZtg{Q_H|x z!c6at2um!n1qK;#%I_I9C_~h$GY|c#YVLgLNe_)$^?nll>4TbV#x?I$o=46T?lPf) zizs#)uNseAw3G{muX;4f<0$5(h$T-*AAI_xrM4_#aajGn7qIfVix%jAZNIp(d{IMM z-TX{vHc&b$XqFa|;R~CRH*5oEmCSc$<82w+YfNfsgsh(Ez z@vafW&S9bJR{2)9NcCafEprw-4qq6AY&YzF_rQYc?QD=q_3iaZk;k^97$$i~ZISIW zI{@P1b=5z4v=Lcbi{jKGZ-5{@CyMYFGRM(5d#M2)XB!@)Z;$ch8F!Q3ynX$(3Z-}3 z=AIAMY2q|>BD3RC84@YD>!qeRTV|8s|wRv53RR3p# zltp&DKygJwoT6Mk_kq3=cIyQKOlkohl64{F!zeOo_XUy`Fkrv)PK^lWFO&ykAQDMq zbvS4~M4l-$Fk>qlzNxwYd}4J#Ou6danHq9X{>X#-0Fp=>T!n&7&;5i9KE;h$4HTog zOET|EaJ~v$?sCdG?u~u={1l0&v@(u+%;+(AH=W3;#_oG~R3y?B`kO@7XQ}9k>%|!o za0kspwK)dDuAg1qod!O;XIlYb84Vi(O{>}rUr?#hTPZ!4wHlFW+Hh0d=fO4s_-L|J@^OJ()XMv zPuee%<0?YINtoZ!jHa!}a<7c2mo`nHN}JfT&si|#K4Wm&|Rt2p^-Z0m zTapG%+_1b3PHz0fuUr>OMtvrAZ?)Ss-#p!0n(}_t8;(n6AMAUz?H1DlRMWq=VD~#@ z?;d90q>M&yTLJ+uMu%Peid}Gw@Ca@Y)?_ztaGeB3loQdwC(ehFd5g#8#{=%3P*`QT zJuQA29_Rom-Klr$aa&ik6KwEpTU5T)I+w&NM=s6%$GsSdhu)H@6%SPLKPu$8b;E-c zR90h3>64-TR~tz-^D~}eG2g&{Q)+Q9*_>H+>YB8n>5Qb`cMBMp(|X-LakTB|qg0l% zu4Q3pjbBvN)|EkChyKOD}4b^4I}qT{Xz4sKX&UA5-CoUr8piR9r)0v5bGHQ)&$ z$muWmdDQ^}u z)`>Dt@nXsh5(8u$#y@YTq)=CdqP6d$g|6Rt2ey7;nf9}Ee!RG-+`CQrX7Tp*D6a_# zi{P7%!nX|TEwn_h0ZwPOe0pLrO9UsAxDfIW^0?Qf`g*5H`O}ztKlTRHcTB!zb_uE_ zYShuh`nBsobKGKjZ{+~Vt;?yl6AV8V*lvUj+-$_2ESKP3g*UMAj+c8Y#KaXb95)_J zcmr>9zU8JCdfeWdOwA8ml9Ln`k%G3!2@+@i15871#Q9-;*^B56PLGEpUVhu~2j|Mz zZ+l&zp?wMWQGdrWz4o3wsl)ucv@i9teBjgq-!V^5NWelR1~(K~y`RlQ_JHkp`SP@7 ztu$)p8|n!gbDLs1r$=ruE1Ed$snePC<`QQGaxlYhy{7;gdDPnyS2{^7cLL7e>R#cu zp8)s&+5B-7SHMWuwge^n8-Esx7dBK{Nw84gWm@3vbc@LlsoH%Xa;e}K?CmF-yRm$ifZf_Y+_s%b5q^t%A0E&ia*DP1Qt#)dE(&}r8M*`0pu_!d$2dU%lE zxnfY_n0U!@qxBmxJlJ7}QTZ)xSl}g=hD4MK8Z*!g`~I%;7RP%FK1lMx)4>My%U9n| z9hds`HJU#tdbVe%XnL7Srt-3b)KlisQ=4{un(8EDHlAD{u=j%f^!u|>@3(^a^|2|r zMyxgy5?9y$4F=t5+6!)TqdQH|P3e&v&$wx1({t;?zoh>mFxcA_KQGxXknF6}ilUe$ zrv3|QhMu~*QC{->l10iYbB>R^;%DVq;{~S$#>y}q$p5&QIp*eSqQB404S;sqwH>#j+udI=8o*WB9#_}za0{3ROWkt1B(EL7_x+LA+4#Sh z(sfSmiWt3LHLR}INsoEjxvf+eE&Gk5TAVXEUm16;J@;RolvMPK{8zJ?Sv7dcqIw*0 z%FO6EZravZX%W=#xq{Jw9#Sa>$vax^dJsCsl+0S*o9f3>sNWmheE#X3!ou>)^f6h( z-Hbl_P^-@baP=z~IF!Br2Lty5Z*a&T%$8WU7d5xe_#M#bY*O(U@cQRrsTII?RU{7y za2!d{-M!HfEx91o9buM;)%yKI3)H(EYVb1*E7M`v)VjG>7@qvU4#5A<_Ras%#`(YB zlA%SlfDMN-P&eT=IFrA4vX!}8r5AV9jo2eQ#@0&4b+g5Nka_{>#?$v$o<4wf1PXR# zRv+iu=d-?_9D39x3B99Ew$>t3#?xLUywe7s$on^x$?9G9F+*Xr(XwQ=G2!`aWAOk1 zSD`T8IRA`ArTxDOS0i#CmyN(qnUzS<>;#Ry0+*hVX?%uGy?!U4<;u`(B>Sedpd%~t zY*!&&$#Qk7^%&L>H~`VkfSMYrV`a^U_mv zt+-3I;Yr2ec!xag#GdW10||F2F5%RF#MZjH+(La>La3s0@gty^hn!g$9Ivx>siYluY7*Lc8kbK8_npD{E)EPcKv-6_s5$O_7R5H<8cZTBxcWE9Mn z<8tpIJl3wO=ixI}7#bPBZM@;jSzR%mh_o`W!JXjAQk5rdcCa}H_WtFT&bX-h%=MtY$-*kU zj(I>^aXg7ZtU+-p{)rELv&w=OZWw_}CS?Vg7)(MhKU_5Riw~}8P;=7T=&5s_ehkTw zp$>l$FFBW?JHQV0k7gjA~oTao`Lj#7cEZ>p-wRF5SE_ zPOJrF`1TWu^qW}70Ms;~{6UIvqcEsoE4g+5>|V%#@)Nk(gkXl>a+9c;xBY-RX?cee!fV3)@pPzT@H{D z*Z%-U9uuLC5tL_bE7;~lm(MdeS{$8MztE%}a>WNv*} zCjmS#D7g68WBsvTJm(GgYu*w`i5T(}tjq{axl95GUWjT@f7!+_w08o=oFAN77EU9Um&J-vD|9C6k_-$nV%e;K6ki;3~G zanu+5ezj82CB2r@ZC&pvCvd|mC*A>4tR_oeqO_8s@sIgdJ3nGnYYIL@%DTMD!O!l& z;hXD2W*x|1^qorrkVpd#;-2bBhjj`HgZtQ0s%Lu)5k=L4;9pCsUo;7lTL;PAL5Yk~ z%eWy@4ICz;$-z3VMwK|980shYjT%MY>;R#BxkcZS%P$i#1Rc+f`swJ-A{tEH@^X>G z=rDx22o5qUdUdGU1{@efKqK6&LomhBwoVa^>iN?5GTNZtZ_QcUVrIgFT70A(Un&~X z-i61=d6=5M36n^>EM~!ajjWaxUh-ccraRE{W+c#ggz*>OH^&~kf73~-lbtB#!IX%B zkX@OM)SM6GY5Q-ZKxXZ~p7YwQ+w33hfTLxw1h>>TIc0h@l1o8@fcP#LYv(&28~rL$ zifmnhVEIVF6Fu!e0*j7HjJGTO$;aUH&AMML_QA9cN-{HLq?pp+5`Uc6Rm$}eOnS%C z*WYtglnnKVi`RHM&%woi?_Yd8e)7_s7Wcpuw;reTSV#akE(!6hxC;!zQ%f&w$&z?v zhsY&AxELC8XRM{IO4Q$egj`_WHoZpCom5UqP@FCtyp9N)sR4u^v4(NYZ^rU{i%?`I zw^HX!VwZW`0g4(+M!x_#d?7#RvSfOlTKqG%3@Jaj z^uU-_9}>ty?0N~8F@5JOGCz)?v4MPEI9cIH{lNGS zf3Phcr{;@!dt1oxg!%C_Y2ak56>X~hox4zlg9(5coGti?^?b8bI`*ll8CDIOU_7&(u-5n*5uKZqfZ03Q zs8m?;-GU~6p(WeaUc8}B&Xc7XV9}e8lkS%W=HA#%k#>1FjLQ!Xsiw&1+FQFq;roTn zVfJPrQ*R{kn$xr;-0AQ;?DX1X&3#y?*|kusb)aAf1wX+cB>Y|u3>PW9%+#{GJ-{e# zSSMdobrZpMjWsYBJ?{&POQo_E0Z5zOC0`V3v7HPbYNYVAz8kV76CW&Tdg}(kb4|Yf zs!z-lQ!7l2BCUVX63&>rQ_*N+$=P#CZ8xxOekZ94rSmF`=ISG4JG_mz1IigT@XY@N z*;R3>VtGh`{=StLQWm0?RJn!oMj10a9hUAfG$|-)ARMQ&JuafS!D*pDN2%tlqg z;URFjYs^Mz{DO8|Yuu~mshX<=bSi#FT0hny^>*7|{RtF5)s3mf;tUqKP-CjGa+F4< zCr+xKHkJ}Dk?IfMGDNhw2=ajxK)`BpP6vR5B}kRWGZ5;B;<*Ht`}VpfV7@=pSrM?r zQ`ovC23{ywu0%`0$jcn(oL9ysMdk>ulJ|o=->Wp5wJRm*A#6}482FNmL!s(+N^Use zFI%m)cFLwaoj%qjp9>HyI&!Vr*TSfk)G@v}>0XI!xyG0mDx}_7(IsYEkVHQ5%)VDQ zl)AsrdD+EqSa)hc2U$Rf^istlTGxapRA{gr-MIZ?7SVk#tW~9&Pw0JiG3sAE@fk>V zU)%^ChAkk(Y^_3wQRs$TY+C02ypMmz8zw`P(04?2HvKGk2i9SX8P^wEnd%Q7n z4&^WU)Mp2jl|{vT*M%~L-N%VF$EJKo-IRL?Pp5l%1(il;F>N2Cnyf7*efUwX z#m)vC1vjM8%Aw~8_IdMNeEJ;EUuv6OO&Q)No$VCYxTao_?a>t1S0gPd*5a6*;s{!Ri z+S53{`3X_QmhKEGr|>8^07hy3@wj)Q9MfM)@)-#HuLKy}7em#NZjY^SXXp3ZrnqY| zg)$73kGlF~Z?Fk5l+af&yAaz7yMO%ug2Std^yUPVBB?EwFo&VG zXj|tT|5P5cBtE?Q*j=CAhl3x!i4`E=Y-MYU9aW;Qt>p3``SK4iB7|gx3`%U}1)nQS zEic}Hu)1%*pQxMX;VQq%+817am0MY(l1oK*ku&^P{{J$tt#;pW`T`ciefx{O{~DH! zv!9*>>Ed#D-cb{yj0bSmU*zU&Us&y`$Zr_KsEk`3|M2?lxB0Q=qeioWWIJ#O`^p+g z6lQ!^XYp$2?2|aHL6(s85%-?Gnw ztqpV2OYC(C4-K1Ayai{Am-90r95n^dssO168?ZRU@3x*=5iYvG52<`V-DDeb^+IU= zz55^@uyt+&xz9Y0Rzm-0u->Ch+JmOo;v=^`adQ3G=%pL}@uR~^r~ThI{SxOOH*9cB z#Y3s^=%4X)6ff=60qyNXpy>lU_~$V@c+M~Pr?l_dtK{4k)*f@`BESG1#&|G8^cG2o zbHhIGY1B?ja+j`{#`SXgK1uZD>+h6Kyxc+WO)JU^wAo_-Zgfi@${rJvJNNB7(E0w1 zfl^dn4~L4Cm_}h_XyN<+9FK!+#TDpH+@0rxsE>3ovCpc0w4nS*^rp|+0a%O`x9>b7 z?Gtgx`rcXg#@?AQ>2iur9XhwTzlbE>e8OJe?u4kd-Pxaien*JQYiulyY(1Q#Nxj@e z5|ch*KVDGoI+b~DJ7d^6TNH8-%jYM=#QWV*_6KpyT|W$U&Al>_^I}YM02{HU{WY;B z92fg#%w?r^n%x=wIg@IJJ9~5c8KkL`M#XA|Q)!3MTXjP44_Qfqo7_VAI3IT1l6Dhp z2S3=%mC+GQXc6x1`iQp{647Aiep*1h8Y;z1VP*VKDN`o@{Czx2m;uN%^iRO^0n^_( zXykW6j%kI8;UT4mdn(;I-@D+DCw`x^-t@#H6Y2}5`O3P)x~~~EAjB{m5I2VgSLui9 z8enQ=}(4LOX!dx5LFvqWQ{Fbk{V+B`A#KU*H2Dc>biittD2R z730*f??yLf)i39!-Ure}g;BW_#ZQb31Pk2U#!_ItCRinzzEj)Li|T;+Q$K}QO*u0< zrur1JOM%zTzuZutm*zyP%1JQ%)Sn^H3*vvs7mw)@TlEr+dcEzR9r^lc*z$B{Eq*-a zUP>>Shy>}}%KezSpB+BH~OHCG%6Mh!@!n?q)oNjHvV8R3ew@cQJno;uz_S; z_1kz1_gZX7f}F|q!vE3c`Je5c|F2gVZz<D!e0Q}Q-(0UDO4sEle`W9yB}>voJ!pYn=G(pVg>d(x0J_=b10HUp`;^cU zC>jteWD9cyeq5O@Ch6Ao0wR;Y!~gANgiR`&3cq;ef)C$%=%5jn(g>j0UGav z-avQL!JqlSuX3)u`n3?a1Gtp;ry`XTj8l?$jW&y{q9|nVeNVC%gDKu}z?uwy~jvQpl}Z?Fyu!J1^4VRT{b z)8YNyZ$96$gJga^D<$F17Qr%<`|w! z)FefAGNS*>{MjN-HPTSWAEd-UH~ya7XkOkvn8i3Lf0i%LkiS3vnXNst{5vs z)|DY?yaOdSReC#O3lmgJPPZk=GPxdR&x>Xxi$+a?Cg&H9&&ebK&jTnJgB(g~$2}-K zzK8 zz(31ongWJLQQH}xMYbJKUq})tzywJYhKdw32?9z=L1QI_JcYCrO^AF20YS4Din05N zB*7XR_D5H6n#)MQ$2!FY-qKEJ)p};JQx#M+Hc8EPS0uA4H}tdwBJ6m8ei|0A?TYX~_0xMvFw*xRkK z3+2odJfn>)+tYTz6NWBUfw?#0`g8~2mLa0YN|4GIvbpe87q5^YR6#<~voG(}2ay;- z6*+QBRV+r=mTAZZg?kHu)`@1p8z0h@XHyJF#=BZOy6UmA>#ZxD`tyil8c(ye2SYdNoOyLW-x$8$m8LcDtwSMOLt-jv0 zoQ}i!XyL?VV39EY#YNEZO=Ar#tIDC?P3s9=4Nn{SjVvEOa*tAOZG`2jyy}VvS|hYm zv)+!uPJDfkRmQJsG_LL%4ODQH-W&KrpbKSdEE6rw!WDWz!Cv;myuk z=%pPg8{Glyyn>J*l$_^8U1E0iI_<$Y zb`7-aE3HV5-|^T%?^0cKdk#5z2#luCf`e~spOXk^OOC;(6(GnjEihqT=vnDZ;WJLDLwdaQv)CKX?W@v zWBQAGXp*Z*`1a;8x6gsA4dR8F=BBpTRi+>9_}PE3vX zDJv%9A;O$!O-X#2j&ov|{(LAVSN@vX_WS#%pT9sbH7bIu^2H&UHZ{~Rs#siKTH&DS z9k)V)Hp&olLCbf#C|>LXu(WnOscpt#U=tQATX2=v=A|Ej<9gm!aTsa0%Hn-n@|#ZE zAs;R4fzg>G=tHHwIlsZ+2X*Con1cZ*A=!v$wqpQ6a<=<`mScoUk?<7ALoH$y#RJXL z6ak72Y%%y5+0nH>?|1FXfF?l>^LiqJheESyhzT1k9sS-A^M^VejYQDjjc^dyl{(JF-K;)TNAs)K(d_vu3&&HEU>p(223IK9GFDAi9li zL~~cZXr@StCp9uc9Obnm78Y`>Y@05`5dvmPzkYAtfv(j}Ghaton0BNrx$P@l*}6`l zSyY#cZnH!^eF7v)l2d#IRwaj+Yu7_fAQT5&i=Cbn^Iv>rBKNZPe<7H9?p=s)^6^%G zToO^7xyg$7VgJ_T)^nQn*}_-c4`8CxHcdDeS=6!_?HS3&wQwOu8S_b6-cC&^fC?Y$ z!l`<()(0sI%HU=f4QY{tJjdDrd>p^dU&w<};q?Cj=1UJ+^0Cc{aI;G-^4g>QejMSPXk;}}q$J-)3+85)43nP9 zX7A2|axSOHkxZy~W4!_VZnb9$xGl($8*BW#hj$GpO=Nf&-BsPp`{EN8b664b{pszV*X;IhKW9ywhyrtvo*pgf-zztS#O!iw)JB zyHmo@v4fSn5{vHYOw;&>meACkI;7A`BgF}Mp{~F;&RwtdtL0v>ZqQFh`QsPiN&ji| zc8|oV;Whu+t526bJs@r+2}{p9y#-J^P~a8GDLi0I3S>q3vjayi_3n}w`u0cF3JMRS zerrwBnm`x?)mRuRb2$beo>irMYFp&4-E7Ar4J;*NfEd%#?j^qUyBDpXEQ z5s>{5N#f=rvS2^;eeYbj3ai?i6_+Qh=en{=)|L8a;yH#W1+X$($b`ywI$^@-v@&Cf zGAXCHn>?s1h>zI)b)2ko7R0WPP|NzZh=C9d7U713mc*ba-8{H0eb8}mbD!y`(Y))$ zm2mUy`OT-F{vUwceDWY~pPG9P<;3k+cbd9>l*~FYtHyih*{dj6rqrLp#gFfh_SsI( zjd>OZq}}9BQ~~MG+`lMii@5@``S03qwyxJV8ft=IhZn^Q8K7_JV0AOPc@eD?ymE9^ zrsA%JztC7%l!Da8;5l)2DTkf`k=>uMR_~DJ$_FRhO4GkaA-&W2ZjQ=uD;?9>~j8%2c}oJ$whI~k}V@h34P389X@jC8IT7fNlV>15Add8!ge$%*AR z3U$-VFNuu%gV$FD=p~)0r~Eo#S;?Z$lKC|y7Imx}kcuryHBKz8K=GT0(9fM%Q|a)7Wk z1}W2kCr#rETwkPoaos()KZuhd*RJ0BCfu`Ap_nlljNOpjOx>=n$tuB~oxqBkou9ao zRcCoA@^3y7g+;7krU@>#9V=(j9X&ewv(T3eU0c%))WIcwohnmJtCgPYN1(|AZ+}9pF6oCrCKx zrwIRw_s5exh5W`eK?Ubw_El|Og2u3snvHG%DRJ)IhmXDD!_kvV`+e49l}wkz-$-AF zL`M>Wz)%HE9^-dB=W5&CJ+!C>NYOjf?Jw{6R2!nyxjL|8*??!K+PHNCo+jUwZtcOv%SkEDCds-oG{?i;r-g16AQy%qq1 zwtt$&HcRf$ z?0NKA|1-a`(lyx;3opzpCh*!k5b(*~L_vGyYZW4lm>w@P&P_*?cDq&HjO zCk#QpeJt!Sa20!MmRN=)QkiSTcvUOibUc;?7+h!#EP5LjH*-cPC^!tOx|@pHQ5+2` zb$mRSo5m=5Dz#3nwsh>jWvTkGw%M1>w+mABS57xxsI@QDpI-NIW?KB^NBKEXE{pf0 zFKm&2^W-B?8a&!6H_znWI>pk&_n>M_vys7%vH*$~zFD}M$VuASyxMhA3W>{Je9>0f z6FKq^JD1uqHDZ5o^Nl2R+q!JN@29Z4xzFyDs7E6BqphrP`8oesV4k*Sf{rD@e|4L~svPi)s*Q1y4j8?Qq86WS@ zK}-SqcSRmtj;9}*8dE?0gLC!#E%k^G5m~>Cx)$0qU#oN76!Xo;&I2zGJN&38(H4Jv z+%e`aPE&|lo)Hr{(;{~hygRX-cyc@02P5B-SIqmqSYpRZ9bD()gA3aBW1c^nS-||T zqg?WH&(zecs-~~`&qBgM0X2>HmKwrOFvt0q$uf-OAmnd#*XnjeR0%^yBWML7SZV(v z_HtvH8%BPnB~a8}J^LJ43dyWJcdS@-P_i5<(1`zKBK)BBG}`tmu7k-_peht6k%$C4 z6B>46Dl$-wHenh0A#3es`oz`@?N95D-#n z@Y&ap4tbFE*bJVZo~OyQg`a9WU$`W0y(u$VjISnw_>pqw{{e2CYWSH1PZF-dHa9a) zr7xZJoEGn?Vq){57H{!-rN~8AY_qJYo)80qnC|ToKz78ZLNA5Z?y<{Xkb&q2)J%(D zVJ#?=qUz{w8x93^J#ZAoUGH&Bz;h=%GT_e%PHyg8y-_V4x!W>0aK}zZ{}?c`ir{eX zDM+_57rWA5EN}Nmg;v`;_bSx7@eZvZL>by^wb{t_C?d46u}ih`q_o&iKDmAn-lNif zxrIv)Lc88p)WXEo&S#zI#toc=ODfG+t(?Df3LgF_TjLc4>0H*@QC@qfJ-aMfv*&*p z-$Gaz&+RGh$3LQqBXrL`S?GMH+@F;A2r_m=`eR!WlOkD@UCS*egZOl8y8_<=BsI|j z>t>ri)EA%egrO{P0S2?*42U@K3npy1(ub8DRQ=wU7bkUn5d1Fde=Sg)$UQRnGaF?F z!8!(LGwaY{94m(yax0hta9X=&mlg~z1j3h5$Fq^JP8}b@jNmdV)^jl%`|YneLgh$9 zyl0)jRtazU0g#Gui_B__j3(dx-A6D-5FR%5-uqW6F>18!W#854FP1e$ZKU(WL@}C(-pZ=*+RN;g%jGu#sQIJ$$)Ob3ijeZ5O}q`C$0R^g(q7lk^zU=%bF&|gtvA| z8eb8JdPP93`DWU6f_L9jc!@9ZP=&`ioe4o5E7Wf=>eveb85Pn!3GO}c2ki^_)g?e& zV~F_Icl}+En_PgJ#{I$=l?Q>9k9kuW+tj5ge7KTEX3^^%?*d(HQu(#|Eebj=XX2;* zS_`-Ft%Vq9PRHUb0E?L1%o7#=Mlo^)>VNJkZ|?)@ec16$Y^|c1lp}yRJUM0ri4!CF zl6T@2P)KKox;$`Au&~OFn+gORpCCPlq~1ZqKVX zmM4tc(Ds<+hl(_9mhtp02|%aD0q5T7*1T{p1bSXETehAcdRuzyVra^bQO`{9g_5vej0XIUJgtqvck!|zqS9LIp zJH6Vw;4PBJqq4NQm|J$=M~)`&KJaIGZ@BvA8)HmpXD7HpOpa|$m;~^9RZ9H_uv~nz z9Uta5`F*tbXY280-g!-VqXfc_k>{(5U2D&X71@){f=w_EKQ-$IQT<*h6^bM+|DFAf zb(`C>i2|e^m_}{#d0TBcUQMNjt6I$k?9x`5tlQ=vR?tPtc7urq3*nVsH^)t6cpz9# zC>RHc`SS$RfHML28k?iE{?4}GP?H?itkoFop(p1+E*;Le+r;_X!29ehv=JqujVU(c z-W-=NfyWS)@-2c*20)27G=?P<^8)ZIg&Uha$4j$c-~plX>odqekE3H0VZl;!WmV|k z*PQ@|kRH?mCDswq_P;mznD5^qPez6y3t6-BG2}27Do25@Togieq{dqz>Z4K3j8^|# zeDbkJut(pd-PiL5vR%CW>LBX$XU(H1hU}m9>17~0PQ@qu)HgBiVBADy9lfN+$kWLi zeh2p{>K&`fNwaI+Dg(p0!H&eGSR-CKD1<5b$>z zcI(UE`ZtYEIgjop>e`|s@n=7sE5@R%!hNy>@ySLkP({I>p`JZ|@KiV-`8Zmuc^^Oi9BESe`UjduS1_i_Z5siA!ZE2p-j*wObKFWf<4 zg=hbCQ*JKW0!n_tgo#m-L9HsI{)n;nnY!V~HRAAiB*_~_a5aHW zzA3Vb1X^AUx|n~~MV4#BKU_QclILg-37n z!j0Qo2%XS{PPCoKN&u#0u9AFRBda-Y#+0%DLqlCWgiPc!n5ZVn+d8d z_K=-6keu$62pXeHd}Yt79P(j=LR|NcXI3VIRm{jONP?>o1@GX((Zrk^Iv`gLcNNlc5`rmX(uwr}J2blPYv`T`Bq-%|9ku=*ZK0@SfoHN%PlKkW(E)_x%9RDYbT&@L{6PdXa%rDK5`Ul0kH}P7kP))NncG)?-2Qobto%d4W&A7RZ)? z%e$9X#1QUK3oQYz^RW~($gLc$+#XV@cp)OE(^86NGm1ZDcZ*@1k@CwThLZzQE?A@ezBit#DZ@i6Q4O zTTB^bu_)%QUcsmG(Fs(|*5e5C5<+LbMNRIr50RI={DG(D@(S!7T7+7<}V6Qj?~JZAX7W$b}!9BT#Gb}3ehv#V+A_TQp=1t3Hk?RLw-OLfAm<+ zs;UqPX~y1``;?aY=P+JqGQtn=(;QL znbn$iSWe@16aCPlbVhLeW%=EbHMs8YDta~62S4c0{0H1(4`^WLw$ZXy@d%$CgivM^ zwPt`*PTP$DIca>-EbU}t$!t-xTU^Gf29D>mY|kSw)zxrxmvZT#hX3nWuBy-9iU@)D zkSYEy!}3$-9|-oq7#gX;XQF>v;3ZD%Kk83<$^Oj{7IpGW0DL1o!nCn;A7fbe@QRB# zxp|?b-?C}CAcChILS8}wZ27r}v0}eI z1q~tREk~kz(`bQ01N6G$bGPpbKb|Pn#Zi9e^~uMaC$q#;LD4T;lfX_MVG%mA({LsS zvcX^?66u6OlnELQ6G>$G%nzVw$1yh2AZYWQKNIS8w>HFYSjc4BDB zvFr%38J8E251yCfAfW_yE3_|7=oyUyh>Al9vF_x#a!^{&6o~}>=`ZhJyQxuVzHBKX(xS)CBm##c4W{_jsC&o6c4KoZ`G)!{ZitN^LaUA9CPKUB zKj4hSZhZBClkMc|W#hqxy@uKVUihf7j9{{^BId`4o=G7Bs8Q8htZoc4L zFm0qgAm4`19XIbi|+!SlO^i!;3(q};B5cLNW-nL@@( zF&@x_+t3g^^oDDX2G0r)Gc@BvgvQ%4^i}7pr%?}#o0Qwdy`y9-Sk{LX2y~z@d zBvQJJ!?l)JXyg=l_(J|>b#k=-z(pt@|ERg=KL8ODazU&7S@+yDy0Qt=N^;cklq8a7 zi(;c@zxl@Lv8(HK&{S3jX%N|k)l5&Ngv%^-VIarfFE`fUx!JQdVUFGy+aYO#7osO; zQ-NDVP@0CZT(8;+bh~*d2e8jYTV%+yp>aS*ct|Lo{GZi2O7aAC2N!&jL_^_&1xTEy z5AL;*a5xO`zmWY8AUS=ltglamE1%@r1LTeC9hIE?2e=sB+*13qS#=lt64hi1n);!& zmoWj0R?_~y;_(~OzuaePAl)!_er$M(;|1dZV-~OlE(%)#oQRCEmh8Rc3HR52*;7}L zp2G>!+V%E^m`gwN@(J`G$aZ0BS4k|!*jM9IQ&rr>vn_;r8yVi8`slZ=OQPb}g$KcB zzP1A%RAh4)pKMHS_9_||Lr$86*oEyVkdqKaKUd|+UutWhT`?Wex7SP1Flt2~_ z=`QlK?v;p2-ymJ!I;*NS6sAj5R;IHv-;Fq#nOj!*MRY;zLYL|I{s}IDuRe+feg*KISM+t!e)RRSp)xzLfiDb9eX62i zAdq!EG}K-;9gEEqLm2?vD~fRpZtl&t{vz$YRb%8F0J15G{L0LiwS&;(8tl_Fq!J-Id5FJN-btL?3TRGx_16B(Wz3b`Kzl zvq*y619~p1-xZfQ5vDH@R}h6T%AG5&^X6htD2Xf7s{hI%>m* z0Z;K%T{D&47oLgt)|~mE zq{&v!#w)_u1px6Lb;YAz*F%PWtFi4pJvV1seNCjIvfI-XvgzaR+U1~eKM<_%n6Wgm z7%xub&qK)Bg|DwG>U)?qm#ApwiReZQ0Px?HxcQPNSM1Q5 zgNjK_JRdaZO1X?};%rp)vRXl$$sU%<gOver?J~$e-jAfMZfB;m{mbHau@_O(+cS$sF!i1k3Zuo|YmhYBct+pPkGqNrx($<*R zzI7PZc;p!X43skNC-L)(M_dzAdIofD4D=CeafsV8Sg3TSQ!5y4Xe}DXeK;G}1a})^ zl&OoExBhH_swTdlN0F56J|&co1>*2z+DjMx) zn?(RGi>D*f{kQE*eXB)SlK)NV{4WJT;uWz#yEj)a=aUmbs3H}1DK41fwm1FDE5YEC z=YX^mIi|&Ii&#)&`6%VHM$2hP)z8fO!tCn_{e%JtRi0w`ha?tsHLY0zPWDS8_F6I! zypmoQ67x%nrimE+%bsiRZ+Bg$G`1XzY#Q4aj8a|Pm{ZE?&>@~>75a4wqA6va&%qdW z>Gh~|4xW=7%N}{5vKul)GP!bOU|yY`?^h(-EFlTTItFR-f1d&aep#G5>&yjNeRmUi zoP8$|(FLrnnHd|N2#fuPFaQ^=h9fw2^}~Wy0>$^p^F#p8btk&l#PWnMKjFdJ+QXC4W$8AD8?5r^8;q z*AYOwPGYyQvP?BZrB8ORx)GG>q(2@ld5~K;_r^Pyn=hm{AF70F`yYVQPfO<~%*rgV z{HEXL4S!%ObE)w+(uV_EF#X{<^`P4m52B3w>NRB0*O zL$uQP5?7Or2~Vz|ax8K$Er30&y#R!Fa`8Iz;?mRQVlkw-GmQ4xQ^oOY#8N=0EMLk` z`PDJCrZnL3icF)u;A?2nc_O;f{Wg}$)(&&Vs7rjBa48pJyyP)F(y+i&bw3g!Mp4{h z(@{bby8T;J%f^n<67Y@eP)qr^!5$S<=&`eMtv&V&i}6SjuD{Kd3T$1SyROWfYd~oS zXx4PA#$RKq(hHppfdSYn9oX`{BYQM+D6*rAuMLtD)W}F`xXK~`qJ2oUpKf4_{%Mf$ zcQwUM7lR)3B>;pb@_J%iQ77y=2~SuG#BjKnxpW{0U{eI zFQ3D5fK<`n8Yv?&?$eW$V3;q1YQ`LYlL<8k-N6}xD%>WCBy6Zj5;-V z?*KHJR=CHZ!R_`kwibf6p4>^U>aC`|J0N7ej`pmDUMw z1>?Zo1;bu`0&9&YZcmTEKh{5xx zsAppGqWRXTG5d{+BAje^WXi4+mr-zb(mxTb?qf4Aw?CkrjkrMs#U&c8 z_i=Oyhj1Vgk~dkoHnATN6?4Esf>!>OPS(w+*$${-jDhXtthNpnNx?a#9EZ@ZPIQ?Q zU4NYpU6)$7F!NEe9xj4*Kh5!r;x~CIoc>6dEjt9gD=@7dR= zXna^e5ee^l$`2|kO*xTJrMk0_+-no_5>b>XRT+Uo^KiBI;P#PqO{YmdECz*VMYADi zsMrR%70NZwTFl5B!lrM^zA~?KAJlY$&5L~jbj*?4@*gf?9s%Z={P{We!b2Jwr1#!{ z?;jh~Iqv{Mk>s`6@R7*V)y3M%0hgpxr=W=HRi_r?uwg3ePC!5F5V69GC1%%=4F6bw z9FTt>Lz~kOZ)nTbV52bsNRPLNhK&eO%_s^Y2l%EARg*{JLoxihPgHgLe8cN`B%hD9 zN-gEb<@iNMCA6P{O$W$Kal2c-eD_Nqp})oVi6`R5*%lZGj(p327z;RF6HgjfuJOmf zXM8AlZ!Bivv+uquG(*6y1t|xQjykZXIZC0`L0d(iQMYu#Fs@bS58J9VrSALgX`-t7dSkfKgLEX;_2RC z&0ZXN)IU>VDuB;abO#Sp1F_|A-Z_FQ#g{1E;v1Gsg)35VED*(Gu@IUE1eb9CGy*GF7j zi>C&yZXZk}lab%#B=gilB%m&&2&uES$Nwm%xI@vdS>SQr~f1>Uw+dlWKf37Tv z@I#TLamb}T(SQOhb8`w=&MjWJTQk=U1IEq>a#B z6MF}o2ouY&`_0aIR`PHv6xvjSOgc*;j6UWI+}I(%eU9w<4F#e@BG08p_dF}=LpNE~ z<*EcMY>nwnkhoyD%45=oAbzd26Hjyw*DQTBzSe*+=NO^zRFQGS50(7ycycWKD7fm3 z(c~7?JfZAbCoQ zr*5osp8c9i88H9s7GW+a#%DU+{b%_>1S#>D(e+{}fcGxAn32b*KjQSj4BuUFntTbt zm+cCAF(eQH&$c%sy6|R^_}faDCzbrG+Mye)->?NsAwmG|h0*^bKH$`*CKb#KD9Srm zcYYQ$3`Q0l{Dg}II=k-#O0UmspfCqbVka;PiAhnjLZ-ksmTsPFt3Ypj&rde{)FKSC z-H)&6<92*N{$jj~6g0taamRGP^z#P$UFHr)H{snE-L(CkqYvImAP<#=|35%X9w}Vy zLT%u-i~Ztd1=qyHuRaz2BtdT;#;h%;8ZB3IfLaC+vETRR;IQ5lz!@Wx5a)@zP7bb? zF5e@_zA|XIi!A5~`Ucv|FuJ3}kMUCRZwi&@V^{MG4`>Yo3(q8^)Q#=xLs|rV^6~N> z3}9qeLd7E$-&oiBYK#{dJdGmYM2cClv&m#+!+XyNJ4C^ zgnae0qZbjF-!?kp?(=aXWIvVNmdN=X?Pb%5&RZsCUQUc0%5HUdirGLkUKK83oPNvo z(@jg?5k2AEcH%rW6r`TJt#-6x@3S|9=rXh$Tlj$8n;HoV+STJ7i5@lbWqS&}$RblN zL>j}rp6XWoV7CW2Zkt+Z?~!OS?fVi;dS`gU*r7jX_k!}t#`s{dbXU0M*MsU@?#k{| zsC2uF6v_1&lBnWl@51`e$%V*}cJo}}i^|@YRb$9{dbHc7OQ8N??r?DZ}k;g4^39jTcHtx_+&`}Z&8PH4*x&!58@Lsv62C#|kA&47foc)&}KUq1K=`if@-F990RK}?I`^`?d zmm$ugt~B6s+-tOAp+oqaXWqEs!Moh&qEBBUUp+S`@be%mC-SjcB;*hF?y`Yo2`1J5 zB7*W0C+a2s)06jztw>q>Miuj+;p`7GKcI0^Xdl75yo5`%@ikX)YIt4bk$pVm`Bv#} z+27KvmlB-=~8J;kXa5ILSOuV;E|DcVsL^1z8Tj&RvpZ4lYf|N4u4MTCLW@U%>2zj}Uepq|R zQgj;XcC#Z(%u80t@BaWxyF<-EL>EuV)dt4AV~$=i+%B@1HNRK4<)R$}tj~94E|>~K z(hgL@Gs2KY7{P{5AWPKh_kPz!U{fS5PpXRq#Zz?m`?JQHKdbpN-fZ6T(Mf?AtdND@ zU{VXmuJaw&;?RWAR{Wn>SI2K__iELn3zMTujulNUHTCvaHBWf#=MfdvK@%(Dbsxrm z8m=odstb{0jpXAW#P8(AT*p7Rza`aNZ%<1}Qt|{NoK}}kNwTEX7TRKiMqqPAa^#K& z0-3%g(jU18MRyQleK#hLMM$Od!9%kM^PkP=N`dyLd5GX<@2FD&CE1y3rZ|s80|T;a zlKZeNe-{70v8qyV0@JS&=c*FRH>NZ`HEIecx9KikiITLf!F30NReHO@y$=!u_UDe> z;i&JLZ|bk{%74!!yt%iL44DpjQ;+6SYD5A(f?=xp`miy zgLlR|R*7EL4)3k8SXoM!DO_uB>WX9Roi6S>-B*M@UPl8v=vE)&j zVw4eMX*^>piBDV;EU@-ZTR?Cl;#+Z!bm6vF@Q z=i&BFV)(#ktEnPKPtZ_6TfU{KQLCtX%=LtqIBFYVR5isvNZhYN zNwUT_U;#8emhzcw>!$J{oT(mIkIUF;5?~7edxN#qT2Rd^vVI0W_~R3ORDhMOxpxG zHCIYSKw+p1Abt_{a^Jxs6r~)Mb@?eEUin{etj+p!RYC7P^D;c^UKckPz7+&NXUf~> z;m(qBe$#}NfiMX*!vYJ~sXB2g&6;-o+K$6>o;Xm(C+tp7CoT^WfM%B#D1Q>(!?tVS zBSpI&5h`Ou7_;(}!d)bvJb=4Xcb3ssNEOrQANr^vIJPteqjoRg@0njWlK5ZCIm%oE z0z-6f_9a?~R~?I(e3|f@wS&zno}8RW7s;V@W(2)eR0jJk6-76(Pcw=(p(u7~B061( z*0G^rVrcJp2VOo+BMRCKA_NmBx5sSW;B}WCIV2=Z@0Dd_gj)$Dyr;bRrG~sDAfD6J z2&`%^<+reix$36T5tBk`tMtC7y2;8)?TQ_FW$;=E3!h0oi`EZWIZjRzE=$wMeu?2D zV7S4bbhd9sDiKu$A*M0WM#<&NO+nFFd`TYRTk#?h1mnkmL1XlnZW{G!#?v$5bT9T| zTx?K9qdvM(SyyAQJ!k<9RJ+8SinGspXzq);o;B=A14n+?K%55)cD{9-46jfI^(EDV zmO-Ie86{*${F>i?UNYh7T`3Bq*(hv@Z=-yCR9}#rG-f{2Z6q9BL5SwsM7lp^FsSo4 zirxW(0_Ko%u%TPRx4j-}SF#Yl@sL5$ogD@e<5)gNY zV@2K4W&vnK%q}!Aaz$%n#C>K)Op( zTDp<$4gpD}k?Y;pdhh#P&-;9swfN)=vS;t}{GY$yaTwQ*!j8O$UNtCC2Yp^H%p~0{ zp{}Bo;{L9<^!7)kSg&xlZKhGW6R?MU$$RHm!XcV~V{{aX6oggmg(9&wcltQAkx^~u z#VB4cOgDe}BySax1|dT?9|1m$Uo1Q+T4w^^WSUVXiaC3#w2vqWUrQPKMBT?_=T_^^ z+wpuMh;RcXnzdKTRZDsqRTS09?5e4lgU2T-DdM9ufti?g$9)a*s-WhwHW?Qmo|kClq*CQ_B<#y>fDRrk3Wn^ z5SxA*IgbgJA#*7pnd=0kcbMKk+Eo-NnhJ@f&JQqIRxPUqj{sM;zn*3ij|u$TNGB;; zn~c%QTp!)8vG2*>LiUQT=#sou&bfa9;xc?*Hjvab!1lG(Az1cjc7l6aHnj3EX=}!h zNW9Y5O#*WV_!z|7#!*6o&9BiPHDs6sr^*bYk5DhNVLcCW8+7|paaC06Xw9VH3oVyNjBi6d$~b3 z1l-{)g`4s@?`RrxU*@K=y7d-&7_rHTN4-%k_0qnd%~1}Ppb86(e8XfHd~_f3Gt2na zlG2|@asS(#W3(?F`Fi+DuWE?C9@saJRuT_WCCq;2PFHHY(xKAdMh{pz&&Me!IL ziY~faMy}A;BS|L%S2O6RndcDAZ%Q}O?1eLsQoqV9D@$Yho#iPsYm3uriv}f# zPdub*nLTrE-m-A*m$_=x#DvV*kgVUykVb)hiO6w+}xuWUQwIUn${-lZpjCIq;sQGx7 z%N@;=ls@zRXAN=q`uK!@y^aA_FcY6D3L`3Y*Vm9s!i9H>Q=Sg)#jv>`Ibz#}0Cfw6 zCN>=>g4eZBk4?mX0M+3N#?@`CxK&CG#NBBqFc=Mv(jKV~20YR!T+t;?Y)Y;mQa>a;}31{!+V^ONh|za_M*|@BRsQWV1D7O*k--w=Nn(ziX?z>c>?Q|Pb1KB z)jE5D`2x8nY`muNWr$MnUPOX0uX>U?6aNyLSJ}`YDU>LEE7KHd9*Q{Kinr2a(Z1Ai zIpiJ&M8Pe9iYfyY`YA3y5wq&WyGUqDvMu3}b>xF_&m$o%upn}l0(Dm@ijVq3oFvk_ zi|O4T)*LBmMkFYqaLmLbl7I76P!^_-!GSPPW@+joI-r@fu8Ow$y&QVbGb%IlNCfn&4A+3cdG%ZtCV{* zn9~uT^!u+H4T2Z$DK7MCRNNHceSd~kaZS_dUo}u-_B&QTsS@kUNB-zhqSU=5{P;~XvlS2+^s{H2rJ&-Ovbiyj9)P}D>S za;`F{$#IX%IPd9JbNF|u0gpNBGD;GgAoF!0vzT%-V5$InU!y?&fXaUEY;1UU!s zYd1ZRfvCMHm*Q>+Y3rm_CPd#)Mk-wL5iU%M$ya~)#67zKj&@j=F3vb=gtL@3(gk~_ z(1Ke85kV@$;@a7f;N4ataIS0w294KTD&~E^MZMr4#R*{H^m%IDy_qs&{0m-iNz!x? zNNo@!6yuRc7i4e*o@6UNgFh1eCHpsz_wB8Q*Di5>Uzl;=#8E)0I059WKuSCXFv!Nf zz*Aq81kIi*2x3tU@jvNV!S})z8-v@<@=+gPhnJ0{0C?HP;(P2bl^ext*4dskzn3x+ zCFk>#Db^4OOe5dMqyVF662<|{ipLF4%LV+%sOvufV+-p}3&BwW?&0MAzkYdqr>|zu z`G7P(pJ~R`hm?QbOnx0NWw%POB8>=c5G`L|xj?Gl(8Wxzd)=mAoDm{{U@eb$ttQ74;ygf1f zQ|SLn%!s@)3wn@ZgU62dDrp6>r&dk^&WJ+&N5N6ixAWiEg}c$Ox!>$kH`io74kANZ z+{QsRS!$PW7_wJ;+K7c8lU}gvv`p@=d)@3W^SWR#K~$pUT`Y6&&k~MDddiuXE;_pA z7N)h0UyOWLA?a2T{b!rl;}~(TF0x6vQnJQxC2dhJo@B7k>ie0o{Xr2Q*P98y3=KQ9VHAsMpur(oL_Ik~- z_~^Rlo_}5L8zDi%1zy~DglX`bvAe%*j!$~dFc$=0Z{)H27EKBBmYLZ_sw9Yi&MCmD zs$B`~1M^vxeC<#7qJd4sZc&%aOaGpv!6J>Y$L9oe~^N8p=uwz=u_ z52WAJ-I8h(N3Cx)liLI{U1R)(PbSA9iKK#Q8L~3;Cj6V5+JHM=Qtg%+%)R(o5W1jO zDwGPQCqRgV;$)~htTV|^nfh|l@u|`_EOW6hacA3^BZiSJ$3NE7tpRWuyO=nZqt*0{ zGQU)ijdBy=ah|L6jKDQE1#tUWtSWU)YEk*s1UM&5dk3kPoUo7C;O_;OgabBEWu0{p z&nuyQbZoImO>uH|TB$25l;RnC zBs6n~56e zd;g{7y>|?+6+q%XC1!NDes#RyILjBwKGGW;?2HSi3?K#0BmNtb0Tc8WoJzlcJ+*P1 zEjB(9F1p+N-1T9EhZVl_CFwaS_;)4zmvu|!m9ZMtNg>}cw-k?}lXdFv}G@{ zZ$a}NkzVufaX`CbzzX&a#eabJmWe&gKy~f7q}5ROQoz^#sQAap!fy17pD|BP_}^3p94U=_taB_kdQUe)8?BI5 zrxw=o{=Z_^6|fk<=(0_ujlT{J%WET(LhAsheo2;wK7k6r>}7qvgmsh2@V2k(>4G zB60h$^#sv>1WrrvWBS82&IeZZUyl~iU49J5jO|lPe4{4)%I(hmbF2zQ&lN? z4QK)QvAAms&Clj7F#xy#)3eT`3JqBK`X2yzC>+V`XUiz_dg6f12cf^7u}^a}_L@kq zKC0J_C*8R#;8{j>K#2Y6A>kV%6>68!1Y@iVP~Po0ufOV+Fqga7R!9DXmL4?2ZV!JW zise_-K1mnd(YcT5mB*7#kDt9*?$|f?*iuIKi81u5v&^>Z_JA<9Fqn=7C*V5ukufev z>^wg^t!$IIJJ;fM^9O%72w28_b05^dM;uC0;0a^T#8#YmJ~iSx;!ToI%huc46{0=y zeVd7FftltIAuqf2TJDgan@UoGhELS)JZ_G1o+^T~58suD()yr5pr`=xO#dRofWpa9 zi~l+K`!_d5q?ZUEGR?r$(O}HlEsm3cCvvvhk~ds061ZLQ(L8&Ca8B7a4e4{ET#5u| z)Wzzxc)+TcCN`rKQ1Tt#?w<`(R4H=yJ6wL`e+wGr!a~!iOoLVU0smBX06*m`W%#e^w!Of-mUfegM2Uw=y)1jz-G^&Auu0Srw3S{ui%qg%bOP=Q~NU$xmQGXycKoK~( z)*-gg!g7i$ha6tNxY%kW2Dq7p9$*;X<` zW%>q^LpwI&`&s_r2IxIZ=hPFiq^QI4aYCYJ{>9hP_1L;PL{}j8H>hlJ2W!#z4j*)) zFJF)*4%4FHB!SZo3rr2jh4CyMiW+^U9)?#v@sB3)oiS^rhWt@suEA62`ziNX9gHgv zvGFVkrhY*(t`qjf55FsPf$Q|CtP`M(HSJvL7o^-4mXo~U!mXTzb=7Y4+OR;l^2SCA_`^id&}Nqu^GwKadiz?HV<5(iLokfg8h1RBRXmanG{zQ#i`( z3jh{@w=rv=CtPHHgN5&UCX;kH%QuVzNyMXa7Il9D+_&V&Rdml{e3w0?Y=x2$Oa+Ws z<$Vw*(!h0+o^vEPRbZCeY5dMfz(<#{^Km1&`amyYlwkkfP032X zi`5vMw=oBOw--lwRjClsL)1K@-wE)KQro^3hH*i+ znEHetc2z{(9~JRGAW{t?86!DEyEHM2j}kPz#qhJK9W?Y9mb%lSc6I(N)M@KaDJ1a5 zM&{SqjNp|kgB6$7 zayI>FkgAk{&wYMAXv+t5E9h2Vvb@zpVK#Ilm6N5N8L18tlcJw_(S?#A{&)gncFRYU z#1zhSrOOz*&GrmAqr3NM!^<}t^TbhB=RDJI77CseM0wIz^nGKE&^2X;$41F;`^l0u z*e_nK6*nm;$`WA!PCSVyo&kxBSe;UfSs!T!bwKAFf4|p6L5taHF1TsWPl_~r+949C$%+Js?g3c-LC{^@xpIYFrORHy`VR-+@83VU10 zApeX$n^bEeC-JVDm+;huHJwA_j0H9+lj3<}GC>2Rt#{A(ET4q?5v7Zo0FTF>1YfU{ z5*YAJzVk59IXw>et`pKJ8x2NDN?$yB>Pv3b8elj)_6`>|4bU78y)pazXCDkH-c=Z$ zyqtzhMu2zCjTw?*iSvTV*IC1|58KajWFIeUUX9{wC(ztv=Tsp`6L5T3;zSexyec|0Q22<2>RI~|gH zJ$=FFJW}!XKJAzAPBd66dN-IyE%#Ur%&>Y2#QxbP%70oaEhkUU18Qv!pVMm!ad?Sk zl6)oOw*QOJd2Ci?spaI{E>!p=L3x-^LMKnp9h5bKw=_=Wd2uZLDFb44c?&jwsQ-vn zQLA4`s_0305mP@5EI~(8@g7mC=NeEo;E@Lhk0lVRkvBT;b+NG-WHU>FsPFqOMSa6R z=Y{EG;X0d2M9oqYY(LVI?|+zh+!TvUqxCUEjlwO-o8|H5)&%jqSi+}ek()s+l6pqo5}S#0_yG3c}-=ggI}N_#RUeQ zDno7#f6CvJS;%@n6(;(3#L!H>MXrs-crv`g$Q8{ezJ{hrBHUFu;O0U&uwwJ`Y;81O zq}D-u7+#-O4vV{G5*FX&qKyA^@n=C)5OibdZ%|gyI@Q;^U!Ol_T?yWiVR-P-W;+mD zBV0w;JxDjR7C(9ae$v06ZKs8$KLSrU5kBCh)9s1%aqkkPSawTu7iLosGjo>;iGjY`oUP6M^Cd7rx_ukIvk#f|Kx$9*ao&9CX51QnQrS+ z-UT59Mqb8*(oGW;`3X&?X-6cP(1CYifZHxNU#|)@ct(54>?1iu3W850t;I*#kx=N;T0uZe|1XbSeh+%mqGgFfiaOL(5wtW&wjjBYd5E_t0uS7%h3b zVG+ULorq>f+a0Q2*>$)OL_@9w>}zL)*=}Of&SB654pIX3_hvDimZZc|Q49x9D+7M_ ztWnK9U8jr!w=?pUmUo|MmUa%n*+mC{K_@BztnOsr5|@I#fvxWstLsU(d^d7q{a&sL z@fM0PPcJUNs0w7_n_{dUwA%gV<^9_Tb6b>NGz%i`bm|O-=#T?Ek^j=A2`-+Vd0gn` z`U)JmM<_8w=GaK~qlHcgfJXC%E>C(uQ{n&r(%*PTgAW=st_x1U`*R_2i z_R$s#mm|&oAR1Tew)<%KYw^MSnGx5!VIO%ZSXRe19icuK`_KPGpEN| ztLU2YaNhv8^P77^L~CHewK*h8vE+bPa(k=N?WgzXI|X( zU50ml7yofi2Tcs3>uMw;xuTuuo6^G+SH;Ze91E=;67!%L@PWh5w~ZA2<*NB2Mhu`O zIpFT@ZSP)k?#scjw=8Xgr0XGjPN>(;o(dC=pYPqUN_+7hO?14SDP?kgXJx@0NQG*N zgUE4u@aePSi52F2w%vw7FN##Mc@oUXpgqkpR-SKoZ;?`*5L)_Z3n$khyde+Mb$1R#Je_Ck-a7Az*b7`B)W$K3_@DhMG{Q7 zmLze@F21P%|63i;_wP!ci|4n$RQ13;&NTYWH|7)xbD3dYYlZKl+!c8VPHW3LubdSu-moWhs! zMMmO%bptS>=$C+oppgA|;dMj7oK^>ZaJ|ppLR$VUQ?!l;y^3XP0Dgcf7^Ex$wA+XZ z5D`v^Ft$&pYb6v6UzZB(O!7r*l5Xz+GDJ2p+cu7dBJv#;D}a_Cv%#6Ch5ssrSr*K z<@FTzW=!A{!oI~`_8e~~63t#INIqG@e6vBpuyPlmLQ(zUIe$A*jJS?gmEX_Ux z22wuG3APJ|`Ou^of>)*JIt(kU`74{g`u`e@{%C9jss&ew*(1xL75RQ_9+CiIEbJ+S0VLb;BD&OL`s zS-uWT!p`gM;1@xo)JjO4$p`V0#G-$}RuO+k2<9^?vmXKMXrTu(vI~^N8xiFw9!83f zNQSRc-?%u$9_m;sXxD^+p21-MZbtv)f_x3aEuwr;;kT*CO(6Zch)9bBQ?QQvWet_O zKkHG{iAi_ed94^Xrb4($1Urz>7e!*0A5Hc3N?z%|G8~y5Yr}C{X^1BP`0ySK2|tiHR6I7l_>eA3$X2s^)^kslsKMV%0Qx28+HDSPJUMA z2VMy{3Gl053%w(LH%tgZS-zUr=;}Z-QX~8siAHs@7R{KPvB^1D-S)^T6)DgH7w+ke z?;;}bVFEW_5EoewjS-wG@ry?daJDm7kL7Lv`|AZ9DL^vv$HDwOmb0Ee>4cMOi%Z z5;WM!2V$|Zd9$IBa{WX@=b_KtGPhw6C0Hi$YJ&@XRq$^DwUbLz<#2Teo9}MY26Kw* zDKTrTgT0v$EQt_=#zm<&SnM~qeq^$1)anNGr5@%Pgq5b-H3Iueq=Mku<4}f{Q&Ic6 ziCK)ktR2ZoeLR{HM#A*27s1@5lT%0#owgorjYmki?TlEjAtx2-cJAGmAC$l8m@&&v z;>r8{PtiLQVrnjO`XX>*{6v;0znp$XwQxYC-6T%3-?DdSf^q_aim0l$23w5QYkZ&t zhi_PbPhva5E>;X$FNx5AZpFFvz;-lwjgOXA)^oY>`f5g`2*lRi0f)ZBKpBd6F|YWB z(tIenUf8LyQrY^x{}wZA>XrAck)J#Bzv0&ob|&9Q+W4@2M9wSA=p#?#!NIy{ zo=nk5Q;QTBP6J}L7QlC|PFLW2aEMdnlfc@b>bbj~Q&Y)&7zbq6-d!k$8gq!<-Jfxte=^ht+Bj1m(FD4fs=dRRO?GggvoWKrpG8OFEB z&7)_jL549dm$@6G!X#PC3bGmc>@pMli8nF~4Va$2Gx$d#wH2Aw4ZcsQ z2%G&yZ;!gFg3Lk{1~)$z_bz$%3QJU-ZR>fTRLfD zLbEsbvxtw|kXXcbG$sEuJw$J5lOwH%-hz1>w2$uUJF*!;PqG+I6A7XzebzpwT6sVn zIY5tZZhX2H(k^i7i(N(FAC<_SI#o>Dv9j|-8jETSthVs}hf{E6UW50BQ*jvj9^B@_)*o+rYqbuR_ROWnj}hzT&6dl?T&d10bZIFK5Z%a+kSKMZd`}q8-%M;h0;qKKA}5^>a{-GK{ljXE z@LgMp*FP)eM{=d#zdUSEF)n9E3vxV41*?SZ=fx=sE4uuRv|Zj^@>1Uq<^%)xG~2_= zUYVf?x6ne5l9W9G;vUqQ@E2$6F6?ISfo*4u3Y=2R41`VxdFN2RN(=%M3Ps`e`4Y}) zM-po##^D&&_451bw%KkY^y!w%9YU*;RX=oABmT0ZxfX<5r8SWgbUGZV<{?C+OX-sy z@AU)^XQN+Q+0uL;guvh{_kb4Mr!4YT@5ZYSI`&qHl-q$5W-)^z?QCW;zqp2wO6bmO zQed!|0>&B~q(-2Fg~MyPL{S!#dohFXTqbqARQr4T9Djr$a%&?4pQ?g`FEV_F*+ma@ zs;!vw>NrS5k)A{8QhVID%jOR4M43Z?`y6{oZLhhO7p%wU^Q-Fb-0eWyMq!~OlS|Mn zLzvgzp`m!mJAHp5L#?~;aJ}H+CiQMS1dSaBe7?LB34}0d01Dj$aMy@1RJA?*Kq8-ADw#g zUINj?&%nLg2$OS#gj3Z%76-Zx%n+67(>d*Hc_ zPo?h;)>|OQg*LU?ByD90(MYEd(@KC+O=8k0h>jrfko;Khz8<+w+Mfw+Lurp{Z z`uzwQP@h`A_fjQ=B_2(&3~Eu?ahN*T{*DTJ_fQ&hvrVy3@;qAIJOan?4m9|9Y@zR& zYq`vrsXI*Um{Q#toqao_z2Uy9+qRA6igK=CmX#9V1eEdNAi8KJ!Y)*oulTgRV9Lrl z#Ifx>-*lfXYS0>wjz`dMfigK4htuX>R3}V<%W}ig#kKF>Ph|Bc0~~KkJb!cI znR?G;qXh(PelD3W(X~j^(bCAySQ3H1a~Nn6uv2plZXE0KT5O+~*YGioHPaD1RoY zJ|D%FCfgj*3%8;ZMK8`~C9oPbkuk8K+x>L5AT((S!eYXShp`<*i!(RxjM%r5=L8YS zj+IGO<@W|U`CJ7*M=0xTih%>vQ38uvZYcjclge7s&qpK*JJS*08ZRivm*H!;rsgD* z{P8g~*JsN(G<~$1s}}KF-5w{g1#X#Kqx09_ue6>F?ixUF-AX}wd zU=)Mz_2%!t1MFd->`T`_pxztan@QBYYz2SDu{Ty~)GtDQ;JqH&#qQfTUQ&;30|ytG$o zvTh@$Ou2kyDsCHNa!WALPKL*SG)@*M=6GX$p6UtO7Tmkjo#Ix zSlbFC!_G=sT5^01J|L4!=zmJ_|1HM<@5`yRdgN2~QB<4yo%b=1p7}8KLKnJ!w5DXt zX&Z`1VaoGg3ASv`Y`3DO|Gv8RT@bGOUA|Vx5dI(FlW%a;`MuUu7Hnb^N5nz@iSN|P z6}TN5(XIE+Wz#{#DCpFVn`n_mC8hl_j5c6QCgUU8-Z9j>a^runZ5-{Ch2}P}A+9Wp zcOH@9{uKcetaiTnm3VGWswP2ddGokmQDO^?N8eZHLF8!Y8*=#pibteo+hA#hO0(a> zZCHs?qyRp>kQqY%>a9ykLUG@Yv22V#$5eun9?Idr{btGz56@^Sg&g_xCbJ~{0E!8% zP%|>tUt;vY$!=t*nfJOdS3K!~N%J4w1)&fG^@s5+?Q?lV3ZUfF1M!v;)ZlxU=n8xY z)JvGzb}Uzwj9jDx@qgvikDdq|`9xF{E`O=tjxZ?I_b0{a(Ned?cm#nfU>;dI$q;%d z5ppTj)j>B5_Q=OoU)M}K)Hrr@+`*JUh7%x48zp#8X<@dp|66KrF~IEeY>D(kn>sQ+ zZKgTC^`#~WbqfKSShN$NsPONMsxbRoE(2w!)>f021`sS!*M9Z!tUR>(pZu-QoMO-I zB}1-pRNMRU0$^hH5D=sj(ywl1GsOUTWz9%Hy2br z-?34ikjSs~oGzTu{%9q}IFjYq9fiRnq=hEf(vGET1Vw&RnKlA4sCPb~-Aqpby2T+K z*IjRL4t-3Nt8jm|Ppb)I_BFn#bHTZNM+QF;Q(n`s-^IRoxFrB`ql$+IjYSq*=g|B2 zaCO1ULJ-Rj6;6;V(%8YrFix)_jnBN-GCMo^V?-q0BW+KoF>Hg9{`WJmty@i^e#IBM=Km0Qg$&ZZF+X*07hSa zjmM*5{Iz}>p7QBheX)(+kMl#8<{h(Ntd4oP~JSBZih2xzr)EbTgK?qpgpy2rw0BeAI3)4_$P&=L>@L-f>u-||> z%Xt4L&~AvvRgRY<=g{1<_SarweH>}iuN;0DJoOL^9Q|9SI25!CBjw+FeLu1@=9$bo z_^em*A6%%|&XeM1k|ucNR2;(?&8_m;;ScJUx=+}Y7RMhQTripwn)OZZq$A8!9icrK zL)_HS4xUg_h$mH-(#8(Ssh)BIW~qpF$Xr8@%hO!oiEqRzrHlhu z%@KF)53%P*L_4|SUfAF^B;x+`Kyy_+*crG5vH7LIv#LUne0#>Kq0_|-YP-eYLyExy zm~Q7$E6l{VZu(Ut$rC{t;^A@RGexm=qFjAlNX1W!Kcm`Jyrh*B>aIG*CFsz zeexU5PDwFxtpGMGPPlSU9%xSqUZJ6Nf26G&@6%8 zM%uzZ803zM9+jd@(=SdlNrRo_GHGR2Qtaej&u{FH>U}&=4Y2^2^NNRPvsai&Ky(8o zqcSBU{%M!uNz=O=HP<%!NV1TAT7l(<0@@YSL-YSVMS1V+EQog(DtW9TQRQID-(&1# z9n9EbK6)Z<9^uwG5JqDTmi}k@hiU@n&s$n1#RbB+JD`_Z-EC-n*a5$0y{>)90)Hln z`~$uYN%y>xh;>^JNmDJ@v|~~UB_Rd%rU7xcw;0HFK%iycMwN0oGeYZ0Rlr|#fmu-V z@-usZ6wwi_-MWVSmK6#8yhLw(E z{H?J${nz2urfsMwvedBlL`?_nIt_k3UYaA`w-S8%MIbKm6h+(62L^|)6`*-KZclxR zBtwiTvaz!C5W1#>bAW9fP9*F{Y(Z(>ck527$W#}~Dm%?Q8VF6quK;6<=Cf?#t6uAM`|7}Fd zAxlT^`a@kkt{8I`7|NnDH$HcM9GXug1Y{`(CoBffJjvC!8Fc6}pjMJs{YgTiXYxgv z$;M=nk(5Y&co!(;Ju!VN)4rX~BeI{ztATBzOPP*VqFm`0H(ek5wuvDzaux+k)f!Z+ z+>HrRpgxvKT8z)&OiDqnHr;u-G0G>VTNaVy0Lo$aWf=Lp?~U`SQ5EdHilVPvaPpGk zH`G{A{#h{JRy6IcFTe=`QwSP4;u8s3XLn!9x`i`+THI^PHZI*$29hHUB=zO6%irmSAu(IU#_`H$PhRNu-j7gz!q6?sUa-vb z(Q=r|REiTSu&dxf{Lw*tyXMvS*H74cFShHMq>804791s4uwsXLLfh_8vA^I~q((Rp z$y)?92P?z`8@*#fIaUZr%HsF%=Wx`z)X>{yBLYIrQMWZTlNGY7$VOk z{sD?!5wX)_--JDTXo8%Vs!@b|U0%2Ds#hW?ewZlu%hjyxSX%3o%0go!W+xw^4DbLd z1nyNjnZb|nf$c`i+EeAMlR8CdlWw#a+3ccVgOj?b)Jy9N!|h?G(z@8O;@#T37yD{{ zT~9hJ<`$CTjx*wdWti+LO1uX1S(*8lDo-Cas>G#XYift@*HP8GUH|yz_%P78{$c%z zHI$O4AmQliI=<^tU1>bIiJ7wOeo99}Wuz5(feMpyX{y(xsn)BOLs%xsYqD+{XWVE+ zU~eQbD~quFI{L3G`VYYjr{f|K`#Pu5Or;8W6M63naFq-ixt#vii_y1X9C+8;4Wg^Zl99&y>q7EEaMlV1!)i-Muo)K^v|AHZjbC`cAo5l_%^~7CBC^Q^DEqHXyxOcFv9E4PTVlN=3 zch(XbYtfy@yj9Q+O;;Su$bDf2P=mYD|H`J8n~)BW^FxrI7x!@mn-yJR=dxh&_v;pb zp-N>U{x9rONy7B_VggrGnE-O&{&vt6tH+o*D!Uy(|K$c3-%wT*fC_Tr-y1dWIWl4 zShwts3_Op0DCsDlJ_!})em_yHJ&JS_T&X z0UGs@pKary`MI*rj0KKy>j+CUw*X!n*kehN=aj9n7y*sNk-lv%B58l~hHP`aOq9gv zA@s3gV)Mh|q_ztxo0sMde|NN!CdxTtr-dd%X`-3|A(cN4`iKB=*Qz+G7%+|y1{l;T zl}Zv2%fi<)RDtkfi;7=Lgg7lNK4s}l-FRJ|n0&yAKq;s^VV$GS7{uY)Z}w`!FH>?O zpm_W5#J~}9WCL4bV8)xNoMa?Pi*_1_&LIBj|8~M%TX7PG^FjtI^((GOY>VY+px6dZ zd?En1Lb_*=m9xVxK72~NJXxX|vBsF$9$7U7(=fj5gKdr)KoLA)UvZ-HDZQ~(5gidL zevu4QgpD{|rGBpNJHF2%i#I~bpvEHta5pw|YiK2CWhX{4XeyU>G+ zpiMHJK;)U@B9zOjNmw44)&)Dvvg_*9hE~r_> ziq|xGrr`MP-+9QMfNhgzKQa}B4gGt1TfBlcz>U88f1&{bYg=<; zNU6ym&w`74S7mNq0@4w^PpKtIA4&K7n&){3R({+6xh*C2UUlkh`0A-h{{dIx^-pD( zzZv@e|7<;=eE|+HrC%zYy*akfs!_PFpr8Q=G# z`kns)h;N>MI_)N~0sQK2IH18JAwJWW z^S3{$?_0T=tWj_&p``T6?}IHcT8n}bp65{Z4Fu&!p$bK%K}y#dofG?!%Ken*&fSJ= zJzp~klf1;>BfdHbQ>%9e1IBWl!8=xjazBqfukzn6Ksf@v@nlC+nMM}2zBBd7(x6>e z6#s9|M=Lp5j%dL#G;>6e{I{bIG-GL9^pL=5RxK`_UI+Cut}!-CVu1y#6d)8nnG_1; zfbFZt+NeKtA%^EwFcTk{)iybyfuJHGqk83I1- zELA+f`YlpyIfm$s>iN@|0l8THi;Vn2Ev57?L?+hIE9Ad4)|BOyk004G4$IOT))%H7 z4KgVH{vB%~$+bDg@aic8-4c3>06rmsx*X5(e}G#u?`s$fsaM_YosVJF?f)_gH^ZYY zEPfpHjue*9ke(dQt)F>~x7s`o@mwOP*SX6ZTC&)q)O(1-#zAhtt5WAoyV{ja3!_L} zq&0WAZUe0)@Kd@ryY0@PzJ+*IZOwPKu%y63KK3VC^{-F(oR+86kOh3ZBca^hO`J*o z$}Wxik~M98Ddd||qcJ(nQkklZb2FcF_lF4w#RY*|)=>h>Dn(yNRCl^Pk_;`zT%D&u zxgqDQ_WJOT@_ztyCSix!XFhjUe+IiOwizGX^wl_nOw{3rm58?u617y#yAm4s*dHPb z*}y5Xnb3KFP&#-=*9w>P`(c~p=zV?+R?+J$lT3vbSDVf!I^wJ)7{y8Jl zn*eqZNvr6?pf;?CjWiADJwnUbyXT_~&PkoR(Elb~P8?tl$m0@bgE9^tEx;O!vf-^X%kR^e`6HukdAD+BX%r2!nEZZ(zJ-?)rg+yrq_L&pDQ*xvk2)cl?twnIe} zWGg7hwYbeJ9xTIRy9g#=-UQe*7T){N`pMHGM)Wcuvs9fbpdEY?+fqDQHF^9=|GuJ^ zoAy7RRel%Uy5a-q#6+Px=j$a)2}*0|DbecT&E4{|kg?b1(>09ta=cLq$~5X*cUqD! zctG&W=7sl~ez4j_=ql81Kk)vR5h1wR~bwkpJty-b-ySBBwRXuKdSQVmD zAV8xPKfpE$v_n-BR6Xfvy({nT^z-n8G4-#fG$xU6hOK_HUAx*Ye_QSvlIXfuI#FsJ z6Z%CyUE{QT=|8~i;aS?n%WGw?MW8q&t`NC@%ERyO^LxdW?Xt8|Ht&5#;m4QFK7hwGl zy4n-AP2vZyk0jPz99?T=f4cH@x%NDw>7}1*zQLZ0y@x4Y-#?z_f7MTI9_sJcRdy77 z4>BNFe3RZvccbgM_RsctYQt<*4}RJxQS!xJ=hak=v+(4$nTotus5`?azhuF-ofw%^{XxhI;wWRE3Q(Dshxr`yx;q4J55sS z%Is93mXK)A^3i1?d8+Ux7K-_<=JZF_P!O3NVM1>&eS8#*f3|P(sz{;M!`L~U@ck~; z9JIaE;bf4lTb7lXXDfqdR_Lys6QMeo34`9Df9S`^*EVAKH-l1k%a9Yk>QydQYcO}k zAKT$-lDzumvt^zD1X>8XdM*2Fhk|i469kQ>F1ABgoAMikJ-L=ImW1 zZJK>WcU4o#9vizOa}C4v-to#JYi(<@ALx4{^Y}RN;v?XX$0>Tso89$}li2VxIpCrU zL%*DhZ6TkeTx82i1}kOJ+4*9bG~LXNl)Izh+``J{o11_4KKaE~D_e6jLw@Ms0dFs;Au zK@RkkaVx)C=BDzuZL<3`jqkIThHVdr?{!ld0#$4l_G<#lV)W^HXOb4_;6JzDVb}K% zV};s?C}0ZdjBNkxj)z7?+y;TDNZJvR>`dXVQS^2^whfnHmJA3p}6frt8# z{JKwi6d(*HbF;svYARJbs)>#xG>&Vi29rkgaF?H#mth=DV zvM2P#BlTpE^@**XeVfP{ z5PYueku-1S)nr{jSfl_Eui|BTpq|14RIxrOpMSq+|9_Zz%dn{4H*9we0}S0LG31~~ zx6%wK-Q6J|C5?0qAR!Jzhd2T%-5nMnF@%89(v5(0OZ?vT-|w-Hy}!a7>jSK{=6UYt zy3VtiZl$p0)khA7d{DfMXzN7Gjr-wR_ISRZ^q9G<61i&%u}dM>=#I+$&s2?mZYs zW@&xzfR0I+7rFF~cBJ@D7Z9|zwc00sgy_&symgf=o{LNf`&}+_$Mu{LZ~%^SWlXCID{tqYmB zygEyRHlji9J<4Ja0DeMm?E~`%M^lTG0{T0-zdlJ9f4l*kOV!%o)3N7On+KPIB!9gMB4ya`ZU`3 zE&7LfSjSKvP_9lYJ3tBtlim-j?gzXU?BWJ_r}q=Whi;^?hD*wc)8z5qQhodC-s`Wq z99czLe?pfyB{g<;lfPq2yNI!9zg^?yXzkgIO(@FkJ6}6vZ}=a)#)Gvp{NvF|%NdwV zp$^`WpT^z?#m`(ZD7A{zdQHMr*46YrP`8`=>WLl-9L-!;NR77-4D}-z=*!A_iSDos_^>CFeu;FpwQJbV zgCv$ywHb$)>UkqaR(l+@eq=xC^(}gCaHh|>bP#Gc8J6{T?3s$sxC0&vF285xzvg&a zp8d@F(URi}h6=6v_@gL>UR8x6Q5Oz;yA+~LFx>3iS;IF+&_Cj5t$n0*cICik!B{l;6jm!yL}ccdi}#$D<8!^Jum}y#TJqfd3b@1z7O8sne*7MT#ZolB61#lM z5P+L}%O~!lgege`%s-&hK#c;0+v^@Gf{sne9xF6?;UkO0r!;K*b$R zoe1u%bkyjrnSW#uHAHpZudIAa(eYJO3`tWnH&c@QRA1Yzev=O~!6n)(N(_*w@1;^| zdG3IBO3OogaU5676usK_zw1AoV@4!CiuW1>%b)a`QtwZLbm4&Q)M}Eoaj`wY1%{NIEjD(cKg~ig(*{0eeVuO8xVwttZ~1gU5o%P3Tv18oV#6eX?MmsPR`>QVfmS z?zS7g>4NC%&h3(~t_;NX$rmYZlDk=AZHBD>%X`^1nwrR)!(=y#EuXC6MoP;#xif7) zFVYp&N-^|qQHiZDm(^Bj`~PbEhVl^ zr}Z{8*+RRDG+XB-9B-?`(I_v~8jd9_IS0E!pKZ*RuRJ?EeEhE_=#7=)d&8GsYj9cFc@&p`*H<>#wwZM3IVbz#_P%WSVKv|_>E_MkH>lFd1o8ow2NrNZc>gpQ!+|0 z3y$J1N_>A=m#!n&6J5XN(Pd}2@DQWjmAa!r%bux!G6ELcxjbTO@nA^T``UH;zI6Xc zK9e_mi2ij7Bo}ctLpoEZ*t&H?fDf_ezJ+Lr4lTb=hTqhCL`joOe+p%*ijEo-ZJ_Ob zRFf57A`Y=qKTbtoLB4ZpdFEc@s@-N4 ziF7kRVc|@VY2NpFBLB$zB!D%>LQY0tEL-_bT6T5vt4-D!?>lf|D{nYs8HhU-x{&mv zGqQX0<4pJ@DxzX7Z58%Zts`vulWzoCovw2Fhh6aAs+13q0wEj4PY7OhES=&A)Bmou zlD(6eNLZFs;8{U26LnA&IKEgZ-ayvXUDjbK#@oJo7_WsISIPIUrJ9wl1+e^qhAuD0 z?1$;r%=|eMZcLlgsw;qUrFrxHBLc@njuAha^BV&H&KLh4B1uv;e@M1tDWeyNKOeTBB?#h3U&vd~{z#5CMxG<8A|Bt)MIM-Xy~^VoZ(?EV zia?}mjm{XZ%_s^X#W0afCp8xWs=L*@_`Vy|iqUUa#F4_)1ud?j5 zRO*u5uMICk0ZK4?C1k=i+}saANZaKTU6txGZAS-cQ5 zs=jK)$iG)~3HM1I@k_jpZ5{XWy0^%+c8rrKTdtwmktSHN-fHopt$=2_0k_SOj*Bxp zootQZmv8U;B3(MBLcZHfdp0>>P^h%O#!eGC*2u#M~ODBDBV+uQ?q09=h zc=%5k@o#EL_nMx0St}2Aak(O+$UyQbV~7!Vu?dXX+|IlxdlI)W!g&g*g9JN9hzw*h{-~Npd9}#*AiDHmz+rU=E#QgMML2)?d z)cT+)ZX2sL!rp&6rI&on3mJ#%T#2RxZOXae)z7J|4%+@0PeGLLadVwZa9XMiHAJ13 zg*7Qop^uUDHjh$oZF8Kfc^q2EzAO1mqj=Z65oD#kGDg0_6oixmL39Af&G&%l4k1yk zByBre>d^9}tK%)4Mz-JT`dSExlk-9KmaO+Kqn(N|69!u8TZ#6=j7sfC`-WV71&;YX zm_~^B!^HihFKB=u0tN2w?}F$~*9eg?eO;>URB6|Lp~Qk*M#GZ!A4~W6mi`0Cw~pMT z(IzP|U#A@q)z8ldZ;2KU$gbILas<9S4)&zk>BiSs{no=z2+Cio+2dq_42a_B=?GZA zzx%(HD#-d`Q~ckqrJ9-7%i)XBVfqe?t<>ob0fqvkr>m(`fawz3ZvGYL#p>CMi}=vx z`B3GcNh$SL9hc^z@RNPpQIDYZ-I%L8VPZE`vWyRtSDw?o)>lhtY&RO@IoSsHl$Y;5 zHMn#I$84*Wiyo|rT&nfelq+}$O;fJe{vBIo{)({p`Rqy|M@x)%okfO9QQ}yzq|gTW zH%+kx>-du}gtu0P3ve!_e;`ns8R3Vc=L!ij1|WSPd9OrMuRKslCaAN3qw6kK4!Xnxy!H@q6cs& z+pT}1=xUO%do>=5U_lnehw#{I_70-QYb%@uOI+B5=pgiSyZGuP>-8b_6_zez+f&gD zD+q3esvDs$kdyPBk|&3@6I%Ryi|se;?A~EZ?|%TxOi-lKFAGC{RAY6k5k5v;7J{UW z=*X{AeI4=W;s~em>qSo z-v#4d=+vVtwupXK;+xEGY+djF1eE^EI1oCEU9!3(iC<$NOjKi6fQNbKn*HeES&GEa z_#oUxba)p<5at1neEyfu`WS>b3p$t|d3npSt#A80t=G6H3Bw_e!)F3c6=u25{#{62 zAug0cZz3(@HccEAo{g>C!-QLU`q;j*ZHWZm6sv5z>MM*-+a?QJMpF}K&7b@Sa0=ZV z@eM}EUI!oU<0$W12POA>>Yfs{(inQf0C&702$pXu`5`c)tTcBDiU3rtLfd|{(0KCu zrT1zZF=g0ppNIOGOLq+s3s56US$pesY7d1;vEb7(ITR43Nho`=kv>dR^cot4`|6jv zBXFOwo#~x_tWaAKYzFlxFtdxD0U`d|`Y0m2Fo3h6^7Ki1nj+5L?IM3fi)VEUdB-m2 zQ?%($ZfzQN*JNwgXj1o$B0D^isKN(-_Si9R91=3Qn^_ME>8C1hMc2C|S zE__zrzGZx$@(__84YQ}TIJ_w2$Pl_;^_YEa2?|!&T5W4hukTWJD$p-A9&qEn<_46i zshvu2RsIM98v`Zx+Z9hJXzk^X20@r_U_w$ z%mJ=D7djmdw4CMf^)f7+)ovTzuw=zDYO#1d7gUl%JJV+{9fbqTviq* z9hi!ujPwwqwCSptzkDN^+7M&Q?&hu5;>)N5c)qC_Yo9GyiXBRt7;kxq60ui@Rz=BADjHNNLi<%XIi>%tWf(b@0b_sTw48F`)6UYXJ7x;3`$xzrgq*c z=-=>yY}zO~h3{18?8UF1&3L;ptw_<*;m|`{yxT!GlH&0&libR)%?JMh9MI{hKl^{L zKH6+eE{#BdsQ3a($(zz^7+t`|Q<5b-qM8Kxds|Aw|CEUvxK8N*nO{8#vUB_7*rHc` zO5~S1`i<~nb@^36`@3r_Jb!un0knJ9KzTfy%OQ~Pt5DYxsopA-p++H^5@DpbD(U&s zwBQel*_)08X!7F-b)BcWPY##4z+c zv%Zv+>#+_HIu_}NJIIwct;GyXmw1XHsa#U`zBrN1HcYWp6e@9{F5~h2=dJc)9$fkK z_n%c=y}|o_7f6ALL#$U`WweGR&5Idq)j_dQ{nu`>-Nm3rYKb-`x9)xRnfuVVB=tWBysV9fdUR`mq9U6`79g!U)8UQSrNv{s>7}G;dHZ$O2gW@P=nh zRAP$501$)0{-hD^X*ocO=h;IBoi|p+fi!w$f{buC9!-LQgAj;8-4c{7!Z*~Avkldz zHX?rl)DD<=xUVIe`mhqYJ5T17F&N_5H#rL&MIWw6a?=6xv)GiI?QZ`1-p3k2`&)V$ zT}wi3^!#C-Gl~T;wbC!#I&Bixdml{sRiUS4W_8v@DEvd?A}#FhOzY0}1IU(ly-cm0 zw6`*^8sorc2WV+|@o&F`{xv_GMH+!|s%3z>EZI+jHv+me(7rXMr)u+>>{280r!rz< zVrpt6gpge=Q36J17O54K%xhJQ=vy_;!Z+h7RBLhN2HI@dtrX@G?U_rlq_M6eFE_)Mvy@NeTyZz}Z$_6IH?w zDWxsSwUqsC8526-Er^{_AKfIpe=xRmsx6K?c)-G|co&oz%H%jYx_N`FNw+Qhxx z{M^|j_9u7?Nn=H`d&CMWLe`cKINGU?um=`J8;p8{MdfF+Y+VREJaNDjql7H^HSs?9 zhK!r~d}!V+fc_*&<11`TAka?})>h;yx(#4N)HDIk3$(2tniWs~@-myv!|6T!CaZMu z1~xHYc?3QXt<__&OaQi9lD|Z9X~K2)^*2LC#0F!9;SdA50939}WSR`Gz9^C$@d^Q6 zvAe|SMXNHMA3Q(wv1c~|+a<19Uq zZMP(JA6t-b@M`XuSUIIIt`D9F3{SYf^jX91vM4(#O4ec@E>NypNN1k-Ziw|E5`UPX zy9QFQ(cV6zDDh_#2HOO7lCXlxinlrXGf(pNB7julU*={Y1)=Rcy!dgiuus6(VC)V^2n}m z75~^GFeTIX^Ea!twbODhry5BghRgQfpjK7j8YgdOm2UzcwfV?E9F|5YYrGTWfZ=2j zhRsVD8anYba>J&;*~Li~o7c85^I`S5&bx^3ELRjFHlfex`XeeuMdzl13n`@+fwjOM z;Bon>Bj2-ZFNA?b|127~*@OdiYMib1rcub)`Za zipM?8K^VEV>_4)5~)1pT&Vnhmw^ zFWX4B^sJ{Tzm@ErcJ3hQ1U{~kNmhtF$$t^kx5VUYp+eP6Ia;I{NK%PIaH0@LVRfI= zF)v9fx1nBA@U@L5$1Y*L){f5dY<*$|0ALYA(trEGgV|Du*KA1U#zC=VD)i zQzE6u-q*q3bV2qFi421T0jbTIG<6aklR17Xpt z!KZIVI6uBqlHy-0`(Mz3l2ono3rN52r}%jn-?_@t43|L!r2mYxc=cYX2YcNa?gB~0 zMSacYqDXWdxuX-93Wl@C>w15bw<0jg>h#sN{BJIU{)el?(MmtFI@yFZsm!htz^pc- zEJVsx3Pma2iRfFA<6?1gKmmz<`+)2Zj33rVhZZ4dcDe*N+@z+kCLU65@Iw_qrdLo1 zeg5P~}XgJnK_aTPXb(;VXeb8O+uAt{;uE*s-nj%+rFq6T?EgMKL zf_^z|3L696ZHcuRJlw3s)!nff_lGGDnNq8aZG&fY?cAOjlRb`rHUY{kEzBwuguzvj zWUe*gku2pL{M~?vkqI4tkt%mpXyjkT1B0toQ=A-Wr%Chdlskew*~BeL`hJ=o6q zHTCA1U(1EamAJ)4`B~q+|A2(%xvU2e>P!aKrqdzEAlP>%FH{&~@x>#xScjIe%2A>T zRR;aUssDTC{#ICkv{dq*4pE6dlI^AKf#pVP?ZxJb$M&M!7&wavt%^_&ic=Sq2o7wH z@XLFCPI*hZbHHZZa@hUtQDdER%LIq3W(`6n$8T%2oi^;*^6Pm%E37s(n-sWO7Q{Ew z3z9Y3l2#p_3jiYwK{n4%DNJR3qD&E*E;g!_$d|Cw;7MhVOd6lI76%%_bV67-| zBNas3r5E(5GuJlO14Udit&F#NlL`H&N7(c~&P33oYdW#Bu$GJC1DHW$bEE0F__WQ+ z^lBCfT4UhMz;rdK=Yf)%$ zeR)W;D+%|fOG4Ce#q{2t$upyl#$oa`5=~9RJ1CKqZa|83dZUn6j)8Pt0*`Iq7(%h1 z%x^K*8kcF0WFY_~!*}0feELf73$lfXAX>{NEIq;TSGa32r%&q(Mo!cn{DH9k^j=sI z*)khSal~)3C|Z~{(CSdf#l)03J6hTvg&=3=D&3m>YE>`qKx5=JEXs@DM16?y8`gFY zGJO(mYLGZNulczZ0A*pjSA=1}q`dU?vtM6$oZW_5w*u3?5Ww?)nx5z{c@ewX5FB9g zmj!6%?VIbG%|0qKz$tV$ZArip8f~P5R0Km1{q3WR>K=n*eeGQP)ML);&Ya`ka1q-A zI>40iaC0>~I?}l&?i@4{fAJ5gvoKe(Qc))~OnDd$!RcGSi{J$>)bStCvU5?<1K!jf zOc!s}M+u#S2p2`2p72ws=n&zGfEN)8|A7nnFYfu&xnrFRj1BP`7(4k9!6|3`sSTdg zg?41*)5wbl$=|(ZZM&4TNz6`m1GwgW3dM{1;b{Z2NJ(h!tx5H@V%SXbOiOd1WAyX+ z$Y)+N?YMUQYX^swWTKr03u_AvR_>&K4t4*F+n9`-_T(Svf}B~t#qXde{kdx0L45b@ zAMs>5ccWm^h`po7c}BdbcX4vhccp>Vh=*ZB7ygIG-+hBLSMJ2p&uJAt=8O5n8H%R1 z%}{7@zNU`pwWaj(yf!~*o@kQedG+Fm%1iN&sgJ}JhuWWd4pqI!WKV zcCH#JaUiq{qOI{^7x5)?R@-dE63pQy1cRJeX4vx%6F1Y zgdat`?8}M2-~3wm6no*iQaU@Bt)0y`9_*ah0Q;_RcW&SVxoF@foMRse$C6bXz5K@` z$LkTN_p32zhLCvUD*}vi*0*=>Q_Tr9zg>RahD~kc;+ELY$8TRsS!^unVNS4^?WFBu zrYFBQ#&3rga^3BNWaIel8u&=`W!(IlBmjH`Lp|BwJwmPXBnjVf;3sEr^h^93yOIQN zB?4Kog2s^S-bgCEKaWT?jVOdWGRW*d<8pvEKf(Wo@B7TXkp%zG zMbV?9v|L9m%6d`~zU}g0@GY`=q6PIuc#+_mqr!e=S*%o(dfk`k_b5s>|CR(~010#6|s=A8+2|BAfGoc7P$i1!j*E)n-kzN;-!g-#h3yM6G=X!aXx z0-ksJ_i_1QMBUZ`HRwQaQchJ?zf}km_MtZb2D?5mhk_DLiKeUH>hQxlvJ&3M#(cp! zEXgqjcMPBe1j$}*zzse4+!)+W-m)|uN|Z!jJJ;Q#s32QE&_(i{@pUc;yPmXqo(wKa zeCGW23+({?CdYRfeDEmA-xhk2H`UE#J*F)2C2`wm^?l8>!UcEBH66`ZFDrS|sH}2` zY~QM}$9|d)&;vwdy55S7?#)?_uwx8=1eWu@*@dw>J}kYt%7YyEefk z*D8tXuUw%BI6KR8FOA9T-BC^Mfy-HNj5?}a%0Vy-U0=<`eM^~B$Ztg@VJS{6^(NR` z8bTBL>^{nYvunz3$@{JX)vYkT&H_q?o7M=nt-Sj`*$i3|WMm!d@Y?T#r)Z0i!KbAo z@PN5Esg9ayTlBDm0;!b+a=|H(N~Es_biIdx=O!;pOxl!RW(#^h1PRUZ4FzsgQcf-G zc%i0@D{_LWzO164Y++w6^h|f0RQ>LmAIm%}+lum4q&+2-uJ;IQ#;P1)*Z5CZ?A;Rzp zndVKbxc1%e&Gl}dypa_tXl%1$0eE?5%ISR5TG9uj4D9T6zh`s*;g)MU-tbq-53#)F zE4}*6x6@7$Ms%P2vV44 zU7$x}rU$DQJIhM&y*<9Nv0Z%cvR<)ql8K9V%h{u0`kbOzn1m9~mjrp^zFtufPY~Ki z*Bs!J=O%epHtb7xz~kxc?qxXQ8DcE{=1p^h12;DziYw6iV(W8mNoik^Su~-lu0`$N zhuP>OUB-PQAySchwZbI@1+btO1g&D!U`6&>VYW{KJZ=Z4(RXm|W*d@@b--&Gm94>E zQ)-=vLsa&DTL?PxikUV_>KpOaaa~QY7`T(+Be1N}6G?PKEnyC^r#na%yy!w==5;tk zE92EG05USzqx6j9aoyUBA(>%c`F*dI0(_$vTw;zP>4x7e0y^Q4UNBj5AFqX#)7gCSRb@r*eE)WT3`i_Xt~J8{Ou)QLmH-+vjI zKRl5zIo)`SL9#n0Hd^u>ox<{5)1%U!*=8Ij?;xqWwFZxbbZt(>eJUSwZKBh6jAK5b zKUAwCWsFi6$-h~0M$N5$1>~0=j#4@A=y_T}`{a7meS8zY`hxvXdf1EuKO8*ctuJ~M z$F;hU@nndD3+oV*Yd6cgzt#An80Sm(_Zj!>D2iWYhlC#T7MAFe`zYOwRd?a6wB*YZ zE83|N*>Qd81~i;Tst0hzA%x+Z7^2hS^!4_AUGD3Zw_dVp0Y2xUV>a4HVVgBF>IHa8 z7$WwlnDO)SN<lbXUzhO?$nyqKT|vvfpBW~6oGK7%$z!D@h1JPP9h8w4-s$@yAanZ8BZ>kA z#QPo%JnDpYn+g0UyrPh(ai$=F77jIV86%Np#5{*iPc(Z&vQ)QOLdUm%Ny73~sz`4)X^;0ycidNNq|CI5y$nbg;^D2=2oh-8RDAT0k`OTXFgo8p|qKYB8*| zYKPA=JkvPZpfIq6KHE3wNVKAdnB|FqCEFI4$)8>*7_LaAZ6IeiKg^WLU65eF&gBy8QlpdkB=T)DY+zqSSGwuqBnn@qHyj7V^{!&r| zs0`aOWBz)pgQP#E!Kjw^YfMk#?hVvJr%AG?QiLH^Z7!Rl+t=X@M&o2Xf4}gk)DhW1 z(#+X>bcRaG+D!y=n64p$bfH-_aBAVIQ}vDFWD`r;f_jA z%nQ^>>KIPXt4LpB)?-vuSwI0-H&I%=Y+BH+MT$l>-CgGL$}@KIVA>weGgKLBsn=)LIu<%xvJ+(T2n#JJ*zn1p%{g=B z={&btrxQdVN-X-mr9WTC#^kx+eGx>wUGHE$El%e8kyvf$y@Do%C3@CXXP^(2jcsZXYTGMm_!I7czjIk%b37v$I7; z)B~4-A2HKw6Gu-HkZ@M4pI*Ob>Us`#6#?R*cF{6QJkWOfd+$w??bt#q*mktXSICH! zbbzH?%X@qj=29J(en`6g-;b&9`!YjWfWj85WMK-K#I$WuN3PzG;~`GYUWH&RbstM9 zL}g0S*2ZV%{nut^gPjpNzL#7oYX3qE`hBObzQT$ChlE_2#?+h`>ydbiI}IJHh}0b` z?TbipY0805HKYwqxiP8R;SZoHXERa`+eG_2W=xezci6cNarEQ5?xj(qve8nN);8or znX>sHeD4oA55Rd{a1=V(b(zFA-;WzDb?FsPw^Jy3u6gGVAsmhIK{A9yF{@jp&lxef zy-!I$|72gYu=O7xwj6Xia=&7BhAw5-<{eQ1@thDl&0Tta{rzNbS%_X8Z@cIw>!~kU z0)Q(9rITKSR%!^=n7orq1nE^bGbr_I-iD+q$~qqwho3#jS&!HW0pZxQr8z&$gZmk{ zN5L_?6*)%K^u2th$8Hp3P=tZxzp<*S8J>qcaI~EszEDYHSjwZ&z~X50?{<#<^eyz2 zPQd+?XP;LpB+^8tIrzhe0KGJ#**!tZ$NFD55M1r-FK`y^{7U@Yre0N)UUcQ85S&hk z9-+aLKUjER>A1$TS?7cfR>U!KiK`L&$q8-yj*%)Eyi7B;twBr)yOJE5X zkx{QH>jp}saIW5~^P1dD>2rUd)Rt)tf9k^zQP@Cwf~o?pJ(ep>2GIAOoI%tsMmKNK z{*ICv>-Q>BwQ-_V8%n>Kl#d_R4}x%XkUW9MSbRQAlk3wbXgpn(e-nMXxEuf>cO;{Tb*$0vD?j&1xgbTU;N=3t!3lP=wd%d$u3ek2no+)yiP$roOf>DV zyqj{I`n{tGWG5IsXIK}lf9ivgEL%xRSx3PA<;rI|I1^Nh|J6rBaW<_;8yia9!Y&pwbcKzSumLjOfY zDb#_iajGe4Z3fW+PX{0Gm%{aEUTXBxMwX?qJ1urqa>%8U8b_h8h_gzJaS(s2Dz%0u zhNR1zd@`UiugbW)t9ix~5IaK(Irf>X5rv{&_p@fK>BALs#nOTcNa|)~&AzAUI{Y+j zmTnDZh?=E;`YTSj8*sItZoK1;4gqtRN`$gfh?%tK-W|;=VpE*hw|X=bbcruU(Rd6g zDn3Yh#~9xjoYjlMP&=bo-5fHfO2T_}>qnG?F|1ppfetgEsJMxub+)5q2(PyzelT!I ztDvg`5p(Y9NYwr97YL{&`ps!P8%^nFJP;fHL;a)-|79KWlHtb1O!3}Z_McEPx1~n~ zBjSHPrY_umZ_$U!$?a^5FZO$p z>Ez&$8u%yw|LgovKD;UU4{)l%za6tB-@B$=sdz#wu6-u+71ihw6E$M5D{&!l6$tL3 zdB5>ovma)?r#`40vrrWaHVrtuqrwO>K}=7q&2PC5YT{*Wi@&9=gfo%Oy2@WaB2ICE zURoR^|NXs6DxfSt5i50hpqMb#8YTp8$b!POF6ycjOSZnze)9f%_eQa!AD%v26>&{D zy?Extlsb{UOp(FOE%VYb(qcDE1Z?PZ+K?s>9Mr^BxtlU{Q?H=pjls(}fj<`y6S=x~ zVb6BwqIiI(>2ihD!j9UrkY`x&>NouvJ)Iup|3%YcBgWYp7USAo+GD3~NhVi}u^mIt zq_i?q_&iubXr3QDIvc*p2{SyZ?1+JBdDSbWMu09!Bv!wUb)oL6wnLPXoKI`V)UhK9g=XsCzt^g0uzDq zuqn_OIg^_ri&1mOzCaY26Cvd-md*h~)xngCm^_^a5d3G}7#w0Wi{W+Jk8bL*#GK-v zT=wcXH?;(|hkJqE4%}0sH3xtkAX(LB!6LOq8aB)0O-2W6$kF0k|{+4 zr)3`NB!I8fjs_joy^aoevW0*^UT9LC3V1$!FL9!}sQd9gYtD`>7=r5LQLwA>I!n4J zbFB=D`)+o^%y>uhw}wAd63XR|pzj4gA+NBM*G?7bHUhV_oZULI-13qBI`Q}QQTh3{ z%JcKUvyhwoFxZu3m~7(#Eb7HtqND@fig&AP{%2Ng!2cW5!AA130LfHWE!E#gAIDVLs| zO#0!t6C@-p1f=hHovQL>BVe+unb&jI9)}w(hpIj2-?%3BEL=US8Rw^u(`^kSJ9R*T z)PDf&?Sw6}Ke^lXW$vhy>{~TGpo|Ii5r9lngiZ~fu~Ox(zy5Tj8Zi#pc(lNl0_7}| z`Sg%i`#$5z){#{i4(?}DoZF5=AXY-xzH6TiHYDHx%v75%R$>}Zod<^SeuSMIji|W@T*4r z>}IBgJ5D|`U`+2*i$AA{i51vqzpc0>3VU(kccpm2x`=Bh_y1EduRKb%!DVs{Gi(g6>eXi0$6F!i=3rgZEiYzy^>Y2;-Rry^!#xj;u=fU6meUtW`0 zS(XiUcPsa^w|?<#r{wjvq{pae(Av2;gj8ugx{O1$pd@Ac54NWzsf5mZ^5r;qizR-ZKStje04p{0=BOd0PjC9gPGi9T$^~oy(xs>@( z@}BV$YdJK>RGpw_u<66RW{F$MeDAD=8aWWr7RGeZ6uP3#%8<9|CrXCitO{l8YNvdj zZIRkm+mwnfi#GDH`QHG%??CdR&Ea{esF&Gpr(b?iM9wweg-oH#Oi++Vbc#qTI(=*b zC9A7=u=oDCpir9e17ERTzQWH_fB(9p9rkT3LWE4clK??!mJMA zpYGR5yy`RN@|y;oTvG|R{7K@XmJd(md_yK5#a`QbRV=(s8tj}?2{Fxhe#`N>HS-;X z!VIiRclpL?RY%W2i8OrU?4*G5d3)BPX+tC@yDugFNljh^hilq}UyqO!>Vb3r$YYza zE{ttRgq-FAb;;=M|Dh{|eS=4s1!+q=azg{lN|o$pjcc9FzOHNRUr zEJ%xnzNIt1fTPK1cWm01BPpt05}%nFJLt#igO(dt?*e5i?5aY%#kP3!EKzbxNr?r} zw5EL1sW(z=q4id_RzA}{5!h^sBv(Or)J2PQp4Mdk2Y9eWHA^qXJ55&o?LCSQWZC)a z8s{LfvB>a6g!S`#YYTOv%T+EikgcNtM7k!&)4JI3<_uEMsfC74VQgplX*>j?DcLlx zR?l`WknaAoC74-=y416tFo9JM`RAl9s#;Vo(EQILS<|nu6n^Gw><(yj-lKFGfZ?f{@G?AVT%wW9hFu3K9bI>NT$BfzjMgy*YpxTzTYsP;97;q z{1j-VojAB2s5mCOQ5A<&{#p{WvdgzfoxdY&TPsgVpS;4(eQIiGEX-dRU zsqLU1UJdgFGFr6X4iX520dc4D8RzJF;`?0aKsgtlgnme9_)MZDTE+J&96Xo|!NGAM zr9c4g{)e=g#}7A2|2D}L{wXD;9)rql%aqAZ!MyP!8X@$582}nWnUHb4@0gG7p=w+E zhEmS%&1R7eGx=npm;*ux4%~;TIm}W}N;1f2nkn^vdW;f_78|loRZQm9@i`B7`{JGD z3uFJ63%s-dX#_2@erk_7X6lwOl(l68;vVY-2yh|abT?Z}l5thxk(_)ZL{j~U+qT&B zD7&BFQHYRK8P#7yiaq2AqKZ$jZ$vA7j1EE_px=sK%N1m$dNZHAr9bz^DA@YdAD&;T z%xG417NP=tgXA{UEo&2L-$Al~r4%c6{K`OL`i<;bjJ~E9S3_))H=*=T=pE!A(md6s z2i|H1(<9761qf38&b^GA`;~*I$miVP}_MF6)(`=F_^xbW`%d;P8-t zMz&5fzK4#itwn0TBLfDf_BK!)xsOv|T>eGsALnCwRp-md$k|4)OMX$4A6@jvX}lHp z9zb?Uhf@Q^c4Vb;?-!jko*^l3` zFBd!=YTV=Sg#{Za4b;6D`A$77omk?Fu2|1n%PW|8{U%pZv+X-(qrv9yz&64j76ME* zV#Juqm(@>7nS^}@LFTX=k2~Q(Fy9FGWFeN{_oN05K<6Qx!G_z=3dYhT$qVxf98^m=^@3cjw zy7%<~9%bWYJ#`+|aom)2V>y_+wM@Vs6aJ$Mql>6gl?}Dlpv4sdN=a+Y088-wYD=A= zW9mjI#;rYlle+apHpbuqmEdaca{qmlkg9h*neb)!h=p@T<@)<%;4m%3I8s!d3e3BC z`xp}2tAXWFwkp6<SHkD5NB0n1ApvMMAKJ%?G`_7xxPwkIZki^)iJCt(eB>)vCj>N z`@15WigPyKw#WHhR66Llk1fO)P*=|IKNzYwO8*0-X! zTk5N6l=Swlj1W}=bt%Sj-%oEy(m>uXIcKmWWB(o{{X20tHIosW;;QmJrH`Iqe4!|O zgD<5Z`Rp?j5OnlA!32KNUq+OaLh}yBEs;-}w!DT91yjyCvjfyGQ_{C}FMi_d)U*(& zPF0!as2q6+G&;0sG}?PC3F@eChfIWi4y4|6A_Q}LO1$XqIf{b7Vy)QW^|jJ19kjn5 zg&d6G{ndYrE;@~`+p)Q6kGiEJElrUr|eX`}6xiRKTba*5a zuqAlkI7!cc-)tsL1#ARuO0w`pJa^?n_thr*ZJ8ZU%kbUtS^+n5bd48ZUZ*f%bgf=g zsZiLiGZL0{GVyoUcHr=usI8QQOC(oN59X1}b*-$t_Zo?L{MR7oVhc5cK>8*KoTe;N z6#Bi)?y&8GmyTo0F&<$Y(Wvu8Rj;p6w9=(1wl=)L_x91%bfTuR+QsRd0H3zgCWcRp#!)-*YzQ{4`nLK_6Hx*UjB#Kr-plr~*A?18$9o6Q0HD z{-nq(obm1UZe>u&e9~MO&u`DAhtC7JgLkR)O2S|3TjSxs{t|rJYqbQ5&=^DR+)6HP z5>?Ox{o21oqZ0Bz1idDp$a)_?wO83i)9dSbny6}#;R{G&`I>WS0im{g+R&F2fCX&W zGaJo+HKU$0h@I|1$@%;jeYgXVa?*LDRB@DRIW}or;qQu+3gFcJbTvS!+- zSrg39UyP9zCOnL9R5f+bbQS>A_HPGX{_3T_LZhxoW$<+tvyv+ z1Th3jrkjqtoj7o!R_NdHCwK@D7gKpe$R@eQwxyG(!b?9){1@hyi0sHrjh98U0)@yG z{aVz+QxHV-M8$T~eeDGc0WXf2*}l&`e0j2UnaNI=&~JNZ-gNlBDis@`ec) zJUJvR%0l?}(_SAPJLGVPPr81eI{6gq2{4_&j@J#oi41v*9f;ff`owGh4_kj3(B%7o zf5RK2I~9;p5Rj1W(bC-@2na|wNDBi*!ZA9<0n!o!=>~}r3P?&1MoLJB#P_~__kBPA z=f(59+S~2A&Yf|b$8mhv!U)I2kNk8WZ2Jt2=~+$Sk}!;62)^Z-AH=6|_{)CX5RXX% zsz{#M#l6^&-bexVthlrN0zdExv>DAYcfaif)f5w2OrJ_73((Q^#=)rC_3>QZJId+( zkdI5KJU>5rm$|PTfn56K}5l(lLOJ*yvco1bn@xN2XCO_a*g5i3O&Ri zgV|_zL?90g=oBF2$At?D61+A&V0)h@uczr?Kq;IUjhNwYctPjL#c@$UVRx4(M=LQv zf#_mAYO`c8^iX}w6M6f1FhcYG{q57WJptk%$G*N0|4_DXjq3I`3Pp6+|06MpT^RvM zQ#G^;)TZ3Lvae*m{n?wHCEK}uy#G_F{{N{~|Nr+Hc6sA?-^&Ulz+CRgw+*xis~dYs zg3TVw&o=)EcSml_VFeD{ZV0X}F-h@WqMeos8H@}JCNsV@V0Jb{QNn#}CE}{@h-(dv zW+rRUW7!dU6~13(R4Y?7BrB*^1ITM(v$qnV#Um3|i_(I!nzP2W(v;$UtFn9Nix+@- zBuZ>AMEha*((>&o)O`>(B7FVK478Z@mCn%^-K&=+_oP-9aW*eTXeu zfkn8#K#IW2PS&Nx7xDl%ys<1|Em3y_gZ6PAg>R%7C+4My2;pLGTMBS!nq-H1NH1yU zpICE}3?J+neheV#AZ-eNy{q{+V{YRk6v%f@g>1z3uoQJl=^w~>_i!b&dzG}q-N*Ex zCYA4~Er{;sdjaD#2a(0)6MIOb4q2tT^0nGq|2BcXyFiQ2uj{8clDk1Xr#8y>Kf8~# zQAznMZ?%HLWYjm$!;tCf(AY?}lK{cg%yyUKa#Qli+Vxbsz=vupD%u^W@fN^nnzc3MXznErB;?r@N*fAfU< zxBsx|b>+b;3GJz~Q0}wk=VOv=@d0RBE!Y>Blvh+YB%Jvc_sF9=>YmwI$ih;Yo?6s) zOGzd#?Ntn*HrjlWKe9qCD&BH^8Mu+Vk_$HcV{$6?44W2J^;OB9;nvTlxJunntt9+G z_+mH3?VDqYi?mtKx6UQm!y&yy3>a^DP0-aAy7zMB+04p``tSO#aMyD^f?IHVdknRu z;?UT7r`t|aw0zxz`pQ=dbJC%B@*=67m3yqX;e93hsYXtW-1-m0IaC%n~zoZXcn6G$&zV->R*$R z!wW^#Vf;6iVW0`o(3{9IOP=?`5N2)&M$65j+R>W0*7fcsVCDJ_-K5OP- z^MLi~pZx!1U2Emzy^Ec@TzSWv*r_hATeYT!F8ErN33D;)QX^q=VYk69FRF^Gb1fD$l@-n)3x zL5^c9G(qM`Uc`Pz777q41H0{CF_TykQ=+%;L(TCP{uwV3lAnp5%lkq|MD=ElD)LgaG6qL)w zzO;`Mlf>NNj-gaDM4n%#gv$2!G^7dfBf(YthN^}JW1!2w3an;9?f1l^H#%2SFYhP1 zuRfQvKO8KL*q|o^M%^ z=d5>Ay3Yo-68snoaqL?3=^n{t;Qi<_Uv9{E zb!~q@J(wr3vRw_*7K7oTIhRv&nl@DzI`6@*0W-i`;j2!2s&GbJ#)>hv!4HkL)3HdZ!Q<`v5C)-WnZ16 z%!E)&uLlJS%${O(I3(>EFNSeo&=J{RhX%a>3Sy~dLe2`gG;?4e_mdsZXbz@gZ1KRP z7XobiKl@Q}ZT>R?fKzc(WiMO#URz53k$jR}>rK8|4RW~(KVDDfV&`m6e7>PUZ|kkT zYaQys9i=j;2c3IUU{xF^9DG(lju6VvKBwdJeGb9JGHpx?R%%fCEFyXIV;@aH9GG30{Zt-gs8lVg zTcQa4nrUED-Spts!U6|y=q-}BG6SxDZYiVJ8_OcQoj)|qpx&EKDUlqy<0wBvEggsq zE^wB3F#iZ-tAf$-rV_I6Dv%y8s^Q1*kHW+&MrjsZP#?MkTq~=BqAvc~Z*k@J>S1kk z?tlFUdRR1ZE6@44#Hv!~F%JzhKH>0sm+Y}z(_4~ZvO(Gpqj-nT5S~RHx23@&5z^ZN zlRZ5$J<;|TFFanuc;1n(aml@8E+CiPLmiF0jJLNqhM%TQ!eoGHft5V>Pp{{58dq|1 zHO@A#xO{T|n{JY&URw4;2d2P(rb&IWe!7g(miPv>*eA{BmF=pv$r@}6BMLY$IqF%v zv|c1n@)N2i<&^f4khxy3c*GnPq30k~D`^l)jG#N#Bd)kKgNB4P(6F^?h_~Cs{%uy$rISqMX8t^OJ)?T_+wSRd;@!7-G=5jY z(S6fX?TR7bg!U4&>-=?nqruwAM)O@m;S^q*KUXJ6Yql=T=rz+39DZBY=wU1|QB})? z@PRo)F!ER2T)pL}ea@MKD&ttAmdJ^@4K!Mhu|vt@~$ZCtA3kW&}?w085>f2nd6)#<|_ZwAX>`?^Z)<<8Weay@QA8 ztZJ0@!vdr#AE_q^YwCiBeu6}Jeutsh?oF8cc}6G&!WFlQpDF;7`9&G-xD3&_b%;K$ zARg5|SIXY*i*~(7=}r@86~)HvqbBSOySpa&Ld<XzlBH95IP>C3z^i$=E(^LWhCxFl`UBpcE(MTee z^xvaU#bVE|LRuvB*;?%dQa6-Z{-|)^q*?b!y!f`_t^8^(t2RXk%iV)BT z;Xl_5ETzS{Cl(CKt!$(Y2_M!*Un>wGKzkaL!Qnm`Ab(M?gZ797np2&gHzD51H2FlX zVCsv~h&da_Y42YH@x9=TG0@?67^j^PRVLb7q1=<&Lhv(eywgJC1hzj$!GUmY(b>>U z5LA;p1Cv$76^*9Up{-2P`ve(qu?b_XnPT)R8|Pc44cQp=zH%vG7IGyxSp!vUm*W?R zcX`rNWJz6$*~yl&DG~%R@21oxZ9sr-cm>EeH6k{c;_k|q-~tDMcCz1Tx+!6k{T18Y zB~DiC6%HmlLF1xevA(K(b4f0i?5dBW4{hlMt!N_m%q$77xXS5BCkN4FEf^m_>>`VT zs+a|6$nF(QMH4pjGJ(hIsw}0b>S098;Jue29ve~Ost^>eJ_Pk#JXM*wul%dQ>gOIx zh2^w8BWrckBXNAcK|IsuM2G91vDMC9g@+C)hsL)Z+&3#3N^8X5>LsOQMa)CRD+Jp;cvxW{#h=zTT00bTgJ0)B>Xyh*@DT1i)cOb9c{jf zEFeX{$5Lg2C_Z(*Y~~c>5LY?^|J81tr_a zn+ij594_abS?S}y8Ym=Xoos;0%Di0qposP{_(@IoUGQ;INI-hk^Ntt>f=7v<0Kw(P zeoI9*`@bPGS~CuYi}AR}XwB5``11`&<73n32aB&`%!Op}K=#xo%_8TL=xUb%Zx%6I z`U9qNCgKmW(9}2HAFD%%fI*a?|7>|;{f1D|?cm@ar7X`QnK%P&*4V>jbGfQA>gaHU4V&c(9}6 zKA~P4W{cl#0<7vP%>+9fk*Ef6iYPVvGxkOLiY_O(huzDvyoXAy1W29+KkBMF6p+N! zhZtzpnhvq&IexwnY)Nz4HS9-lj&k9W`WTJUIB*1WBxTWpb7vhMB-cog`k8Dtq&{x- zcJp;JF(;NhNJGqg3KCDOqZ;o7iO(P=o=Qp{n4tO^;4g{@5RGCj$#|rSQf$+Kb=UJJ z)ppEDyll1rObRGpx?7-sqB(kNr*dFMPwce?aRACL2m7Zx-==dfA z$ukM=(f(^#jKt^0L4IfNFF-*Z{7dUA3_*DHy)Sd$=0w_6>7Q}HT^>iw3hKc$xZqz)+*v)e->MJIYt5cVMg!ID*R*Kmfr)ol)x$dN8Oy>oA z`Wix`cihK}NR1ShDl(nxUZ<)+ET{(%Y{rA;KW%9{oU=FTxHz$w>-WGnXpBl~?KF~| z*f+(b`%~yJ6qku0HCkbcrIBca4qxqi`^eQOJj(>p*BvS2iu%hEhhuV9A#X)NqC!w- zJ?JTNupo8yvSfP0DQ`OS?*~&)Y~EB4pKnnVKoENIk=}Nvvu!H(MKY+sbKI3hwxD3- z6ivreZoFxe=LG1n%Fm=8HDTezuYNwlCrggVP;+|J^{RfHGjB~}h=W2Cq_Mm#{BV=` zSX;jb$7d2bN$HKs^9KJ_H(4YYWtU3_xf>F(dq|ez)Jgr+BCDi_aWr99s`x)bPHP@E zg2W}KzpH!wFjDXpFK75`N)&JRTURi6sFX*wC_wt&4rp(1_*@f&maGg>&6^r4FRL_i zuUfF$ALoLpgh=!NJ8C57RT}o4Okb|tC%$i1%Y*qmEMQx1$hqY`VaCy`4w@tJzv!%{ zlBY9{IQXw;KwDiaHS8C@SN0UWz_IWj0gOGyU|;l1BMN~+xHbQuj_ChyU-X-S{s+mj zKYx6UOR&g6fN;8;?#jC{<*Yc}PKy?2cQS@L_D1Tz>Dhd7^@gqiFUxL@;|Dwe(XTMl z)Sn5bt8v|pUOfUa9(>kfSBds+dy&snsHS?IJ?x3W6}AHSIB@*MsuE=flqTb(o=On;frC)!1taC|ItN>H1`)0uiUHy zr@&u#i=jA=1#X$ZYlIGOCgdLBv|ck>u0*hAb~B-FUsWt=T3deDI0NkYti~O0?l$03 znC%k4aG>`ehyZMJU1EDg2RwbhiHKFPi7UN(5}*ij_z>6n>6Hh)p-;A#Zm8d-+i~TM z(suazhJ&w0iHG%;oJue5Teiyriq-BIn`S$e(Mff>YDsri(!Zp{dKR{`S(aEl= zqx_FR<#ZzcYJb{@GW^{BPWnW1z zEstop?etPRY)@cL{H#BzfB@0Z8+gEUS6)^vp{pOdIL)3DQ7*rzh|<8ybODOS0PEG0 zBs7Y!q24m+?eij2Dd(rEhwmQc-nD;$$s<3pUU8bCU)jI9|6X_W=6BZ5K`4>{Yu&qM zbM;u@fU8QOUhj({{^pXYRyO+nr%jXof~CR%hv3)xyn66(1vljQvM>KgK_GGJTZH?c zkT62M@lWqLD0(aB<>&!j2HZhozxneRf@Uhhv2Sc7%Xj~a`UPa5x4ohxj5kSejMYC_Y$D%J*yulYtVt7;Hoe< z+QWEZGeGhC`23XO?4!Pa=z(RHm19;ng;S>JUEtn&N7UpM>&wY7U^(XB?@9y<_Qes5D7%LvjEXf0Akb|#nVLb zLsD#uI(!OM?y4x-ZkA7KOlNc77=ro`fyqNM@MR%IkKg{>fNiP&Feeob8j8?1tGQyo zaJ&-3&?h@vlSjVM-f|4&I6Xw~DzHL#<*A@<)y~4^y=!hT4x>#eJ*$6nKUo_j_VIks3h!Sf#sl@p!wg z!?fELv7ol#$>l#}U5xeSO1KNTA~=%&&RRd$Co8j-AN~42kXr3~_Ax~=5x-MP4YYN} zJd8jAkM@7i67Z4Q?ZdRee@U@j5DRBC}txh=ARjd|`jfRj-4njlhjy$6G zRkstF6Bga$7hJd~TJNIJs)AjI`W%v_ose$(tXDigIKskbSsd9V$c^&-Y?zjG>%vC&U^*Z& z%0c4GJtZZok4%w>?P`gGgxynl#a(T;ELCzJ_&HF>{Pg5kAhob`v_2WU9ScDjx;}f( zkd2UVk~%MK_#s$Tge(G1Ls~TV2SMx$iOc3^%%HF3%FLU`gOap6hXI(!9BJ1RkQz=N zH70Dqfkp0SOGnc}K`4{SbtKtVM|dl%=KIgC=EYQ7Y0avMpvH(hbN$v5CAt=ATbb z0r}oV@bP$jIP0x){q(Jr@3Gbv_fx$Uh7Gg5x&6AE7hyWHw{#x%J{;|6$x z%n^o`yhO1bzb#Agp8UX5cpdf@RdFw9zTm=0j&4@)*|iZ0IuD;AO*!CE{@ekS19ozm zoiMy|kRoU<@oy9F%Wm6b8>g50t&n*J_c4a zYToZ)uPm0vowo2!Xl{toiI>;9`&`z}?4Gl!gB2-RB@%f)YwqerD&s_`D-BU#al0{g zE-bnU(kVfc@@_8P1-z0syqofL$K=h;*)Z58y*k<->-n4?h{!lb!4EhZrZ?jihy9X( zS!}!)^)YL~vECDJ6lDGYbZk>#LkM+w7!Q^ADp%p=C?E%qL+3V8eW!2fHhjr(knb;1 zEfEe$Oh9XIne`a0a9BP7wb`qbT3Kg;%$14m)ZsYGS$PKe|?){*)NhOlO4FsXZTke)3kA@m*6m1u8yF!l$Cor8R?If);$Ga?IK{ zwezokXh&_#$0{GW%Q?|=fcgT!cR$qcEX)kK3FZW_&5dUT$i4WR0ovXKf*hOKr^wD& zdyC5#;>rk$PMf?o2ab1s*Rvkic7kX`@j6VrL$q@9sE=)%p|b7$8^qNTc?j{?(J4he zWV}lzp|!j|>pOYPNq-vhcom`P|I^ooy4C>ewru6V`igPh;z+g z$84`h#+L-;UzW|O=ZF6g0Zo%N>>gi-Xd`z7T^=}D6)Q*I9j4Fvj(o*zce|!wRpP!K zsckufO%^@PW7z>)PCOHcz+_wMpD}k>Ro}-pRd?A&qbSdC><&wdy^lWPn1A< z3S=PlQI_L8d!~@Bq8zFdLMi6mV_Yc?dv=6#AXWc7{qW#R7|&1Ej2vM-ZSV`vpTqJQ za?f70UWeMV`RLfQ9KaPAu(V)XbtdrUJsocHH8pAUhw|;5*HRF!I(%em2liyKMH1+i)?2%~x;JltH`)-v?PdV+kWU+yL5qfq zrOA5m9FHW(zYLAk;9~RU#tHn4HK37TPUJ9Rr$G|!{nZ~KEm!tIM8&PAW5neeKwr#+ zg&>g&#m(s()QedaI3+xvye-08b`2P4IfteWF9tx;>w02G>LkCXl*w9q2c<7cQ>)(7 zTu&-=3Nl5~3AN4;DZYQiDDTps?L2=5Y>N zh~Yb=6dPVGAya~j(m~?9^~wxCI)mvkb1Uy0EjV*$oIO}MIhgY^lW!G_CQ1!DeQ)LV z9iDgoQ>bt>%aj1>E3J>SRLMh{w_Qd%I3 z2vcG+Z8GkerpsBwF|yu72f8NltZwo~DY>9TkBj6TZvuUpDQmWoQ1Ww8!~mj46M~eP zRAEx6Gt>h}eAbRib=WR~mzFuC-k%R(1h~e35~@2XMiCFibWgbKG=^B->*I%t$Q&rB zG3=W8pSj?4{2qda{_-lr<#F&PVsh#2Nd&qRKuzPdZAQAnxSc%h<>FUV0;BcpDYzfHo-DitSpTCDZMT>;Ls}yi7ft0pU%;Z;3mv0Ii z(F;W`*g#U7#NP!Z)XHoh^SqbrJ5?t|s2$*f?4?o_;j=MHH9~n1^)C{RcIxAh1W>#c zqz7bwnDSFXKM`8ULtO@e8ZQcZe@xZmQ`6Mrj-%J&!qvyunaRp-ae|VZveIU zK|OoqP2#l}lyL8XA_r1fMTG`U+m3UI<}5i?P@vq1a>gMk_UL!N_8Ffo`bhQVTNBYm znNYBez!Ws^qSzliBQn`(Z z8eQfHs(~xsT>qvTM*lp}ZQ-*}mxLs^>(^t3I{X38A>DJe^iR`F0U#sMk9mK z+jK>NcCVOtZGB)WjxQJQ5NFVwF~6y5P+;!c<{VEJ&JpBxqj?Zc4a8x)y!dERO{~RM zu&PCFrkW+6x<0J8?l-AE{^RB#M1U>OE3fYGEVGBr{z;7un#sagzbEjgsY=RfXeoia zKCZ-t>#swuW&`tT$fM6)Hp*zaiRA%q#g@QBHx~O%O_MQ^Ia<(7zcIA?u9 z>YEk_Zn7k2Q$Z91-|!n;EVFC*)Px9>M*|=kv5oc@z*B|sU4K@+7Z}4Qa5omOY)!zN zL3WLTfJKWF1DW-ox>1_pkAS zss$lI-r2#+hg3qg%WYtjnrZ~;C-rld22gxBm2h<)!c|KK)u3+jL7mQ2{Nrmp-}wVG zeh%ZX45lLmT5y11Dd2s!r#~?GQEtyu78R1WDl4l3kwMB1lITE zY+Y03<{9FM%c{+JFq!O3GZwgsBA)at>0r-i_6}h4lpPu4jaot~4g2XN%`#jS{UIjs zyvy;5AWum=+O&Y^IcM_ohio^OUxjJkEc{W}SF3*c`4%HVlQ&HbqK#D&8X77fESjer z!zLZ3nJnl(U2VWj|DYwU!|s|mEWIIt;{;(7K*7nGGTuUqb*0%e*m1m0S>Pg;2WG|v zMNV&+M{mZlGo1pd-r@uzD<|h|NUptRdve%P-s^Eq!8}G6c7pMgQSZHFnyF>ha$p1F)=QnhWTEd>Rr|6hZj-YKNv zYOR;$>sdd26@m0WSfq!Y#ZNqxQr4A71DA3saNIT1$vK_De%OAz(JWVGg}6&mmK&VN zX+t~;lf10J{gjNOv5hJbR!SOTBMlHup)(X8PFvE)D?c<9Tj;?e70XwtH@lg(3R*LY z;xa(z*a;&K-1_ntY-!W_xJO=g>I?+c7ELZp>AmOZYS$~vUZD3rPJq2`^6c8di46}S z?DpsHe9=9T#&H^!Y@n&A+(p=YUcJx1UR43TslfVd=bm=91F&nJ-HE$6ghv89A+y&m zH+*4ly57H9ykfkYsPVfn-9AGt$j>_g41gmej2yB#{P8dTa}RCs%{-R0@(fj2c;$t8 z5tV(1asDc4Fw-(gS z=|FdV_jf(|1r3+4SI>Lm!NU(mbFXb3&05E1a+{M;(@{?)z)OX zW#STGp@@tSR+6P6AV1-h+;29^0=>&bb+87Cbsi#yj_V$2t9EQ#UxoUW9x9dyG7l>& zuqfR#rOpaS6@mm07QSk@+8f5^p1FiESFdV%RQp%tAwlNDHO*_Nec5BwdQ%y5Q{ozL zA?OCrNZ6&J`v>8DOBh}V>-X+?%k}Po(BB8QLTg&>i5q02L_MfU)_Fi# zY+hR?st!{=4%l_%Dg4tf?nT z8gsic4c?46GNrhB_M(gAAuFLA!`>4CK4F`s7po$ILp_ohvyHMOIliFi!CZLOLS`Xv zeXEosM;`Jl|Dhb`RrI=3d`*W+^{VL9lKP}nz&OWNE4{4~D>oO1?G}txtUpUzc|?PM zIzibD2^#w~!P4l#77rp7LCe2Xb6$@V7N`c9+>mn+D-u9$r`D%x7nkeCjTR!sDY9?z zH>zblA%lZYLY%5WYGMtczj?O_&dZU%3A_A|@1z-RTQiMLRee{^P9HOg*hT{Mu8x#v zn>kHLJ)5hzMGh@MU=XX*1^QWiXawjd|EZ9i?(%AT1UJiGAoK6B5{!*>W1Rm^0& zUH$IS&2vCK)9RAFA7}hrH+gI6^E6Mzc%hxFM3ta$pLd&xA6^tfVMnISM_t%Qk?s%Z zi~t?zP4^XlU>_=O!K5?4U+c|>ZM%5R#4%-`X^*Y0*(;A@%O0Bt4fMAv7(%vC-U<&7hP9AHx{=5WQ>Kb8zHMIneO`1#m@R+&nP**aoRx0=Kolf zs{^ZX|Mb3l#Y%VglR0WDms)7Z35MH!RcC?#oY6^B`8YYYE3WS;qATpjVkNl+qYNd3 zyg=}G6ZpeTgil6L-3CY4uO-n9m+bmz|5~t|k5Qtef!FG5T%uB-Ha8Ao{>Ke93*-IF zni%;N3V)!UY|>^x{_2_8e#Ft2S&PP`j|(3CDUeU0j=uef)qpOUyD#z>EGh;`_rZ-d z`ko^7@a>T0r<`7^e;Bk)oY{)hv3MQ(qXSJB64K3L&U#PWDbmr$d}`WTFu5OhU*$2) z-Hj4xtoUcHkCr;$vLZcfKeDK~XXv|abgEszjxUO;9^L$EzZs$p-79;f7 z-lA4)h^{J?j=N($phj!eiqET1uPxYep=*&0e{F^+q8md$l4Kw1XZW*iFy7q*w+rv& zUGu5J9IhD3!}yO){sZL;e7F$%^zHWEGObr~8`#sZei8j2CdQULD&c>B*Uhk3K%t`q zY(prh8=d)pkAPP+mK}b950n1NyDiTQ3`2wNH>|i`Hdi_iu7A~zdREEj&VBwPe`Gm6 zpE_bs`%-12MRMu6(tjY)0*VH16#NVrh0Xh&<=Rh>gNLN&j(L>wPf@y8K0s=d|1PcT z$w2}|T(bEOG>%Mh#MT3t?7xJuqq&b^VpwLVYuCfsg05!C{#rRTu_6UhB%xaD#}fV<0FY`$fWpiZP6s0>s_g4$Ed3gYyV=jVGCdnF#DIgm3zp*d-vJwP z=u3YuYG+|3`-qH$qrPdza}?n5t6zHfgfmT#6bBJq9iDgl>WTrdV|`@wiM5zYDYMGn z?B%17m7>E+NA!qay{;0Do2l;4HtiW=IK!PFNZehmH%)q5gyT*tXoY8d(}-DZNa|T6 zVLh57KMjI`TTuSPR`sM%`*->HpQ<@oW$1;E2s~BqlSpO5I-9xUE?i zJ&d{Mbz$rvRc!8xzrq#)k>OZT3+MsMq|IMT)d(@Vr~iU84F?H~pR|rgOaHt2wAPeX z^>}2|o(M2YyU(^+Mz#@Hy)^;~P4kb;eu8#aS;WMj#V*i@x#$m4fwM_?LQ z@XhbpU;P=SVtLJ{yK+0X)l}wQ>AhY0zt~*zx7U|xEy(-y3jp8SC!1*D=G_0@U9JJ0 zASz`|VHY}q%U3l-5BE!|7B)#{1BkgZ?vH<0B!%gZe8S1>wGL+H#`*f<>gjOLHvVT0 z()S%6EjQ%pC%PJ|b6qP93D-cIC)$1z_7E3V%>v#y%|&SG)0cyg!mch1IU@8dtpld% z-(WtG2*m=@acY-c{>oZhxS#c_buD(fK1#V3lwF&TkLS>Flu#eU+5`KMD?yD1h5)kF z8+K{9VFl4wCO!C5wf2bCs@W9#EFk7M(*P^|0XXw<{Mj53JlnA|sfyA028ax6g-3^{ zk&`HA!Ky4N1ppupp4(Zwt%~eD7prrlOe3pLe&_n(BMncDx6sSFXYt>+fg{PZdPzs) z9(=1RnD93oMhN&T40^t+KBjb_cv(voiDwiA(5*u*_jL-HwXm6~IB+#zxZXPNY!jTqgmfO6k`UEYH2RjPUYB@D}-%}YA8@oy5HPW21TuVQS>L$<4Dq}&hEju zal95p`UCnj&Dq{K;eH_Yvyu5DME0U1i#UjxEF^#6S!vr$wrVV?FYO%i4-bFFcBtPF zTLK8X*2EjMW*N|Ta@*_R79t@UtP5E%tqeV*wr(g%))o`Sq;s<{^UgHZBx@bb&6 zC^q;Olx~N@rrP3Hhw8Y5u){gqY3`=ohux3K{i#wcjdCA7e4nbqDIsBK=mderI?2FH zLwmLzh=xUZp6*$aTS;MirCVEx3G+GM#d;aGzB0Rp07Ty%Jdelqgn2_L%VZ2+hB_ zDHft*Qa=mWAz>KZHV~iv!(D7jUYJ!_Qh-0qI1)qet>V2(8%E|;LwS=anmJVc6vNgux~Hif;JRD540lvs{2J+GA%FesJ z)(^cbAmV2yJB>jXR^M^rpU_d(4*zkZ&`v37-V}-i2qMhlZy)@@R|IYWxH3`_1j^`` z)=CIAcK=P)IA{>EVG``s#cvPbk#K#8KB4{SgK_tZ(oydcZ!qgJ+D})_Noikh2lH>5 zs?}*x#1;sOuMy?pCp$z?NR~f!iX_q(L2jW$AiV*kY;-pq-NOa42S;@DWDTKlnjELjZn2D?t z9X3@!twCilL=bK8t;3aZyfcDw&bQkHx(QNi0IM~lULu( zcD#dkO%K6AQCJpaqeZ+b$Oj1ma;k(vwKA=TezW-aYW9<%&&u(F0gcVTow$bx|MLC`_H8G(Dwpv2@V}mQb_JNiet-i?MyFVn8)^BXXfq>&8&-eC(n~kaFhAMM5rW1_=g$G(?nfQb~ zV|vv}b7OQ_5Sds59cs;yA)!b{B@f^35_Vc-;)W5LV>RKh#K>=Ew66w>c$%nk!147 zumGW2-NXlvx42{j{uu}Q)h4^sGxru~+uhSlRlnG@p=go#Ii>^BbK@3D#3IjXQg!i( zwrk$;h%LMq@=DKRGVZdk_~ELE1|lAY8Z2CZk=I}Hj)zEG{YF(}8e&v0@-T4`mqnGQ z`UeTqdmOd!1`x`%T>^)k0;e#5#du{CF^q86n4`sfsj_<+YBKu$ zTk3BqhTg9<3Y&r36?=ab9u~B&uS0p4Uzd!!KnuYC`*LplmdGfz_83 zj7dr|2_RI+OXC&Q@N}1Z1297z+Xi`qwh85RxdH^r(x|T&kDHJ!-v`J(MZRB;KcfT4 z-8j$bmZZ^n0Gs8N+9Ty*q%WDWk4q}EC3`vG88rKVdGCC&0k_95ZHgUF*7i%&7Nq|1 zu;x%`SGTz}h-oMoZ9)r{S*&smz)**~PguR@{z@*}HZ|+x^N=KZdMn%hdAoxlp%fsc z85Fy}ryrLDnrAn8$Qw5EWcabio zOFmf)XXPJt9<80G06;4$_xVrW^uuF5Mry>oLR``CfC`S52wpyXSs#7%Re>M#XT5*8 zLBa})Slf4rd=K@%91^O_MJH5I){C7O08afOIH^Wvk|5BikLhCIiPjT&K0v9o zGZEs%agrT(E%K9TSV`4L>DqJy+){jbmPifpM%+N6I7q& zXSuwFQ%jciKGIbnB_yZ`y)h~DV#H*OH=h>}TF)xAQXY;U15E{U&M({xvnh2oc3=9A z)3xI+1ssg|P1buZ{is@tAJ+y%`yVfoI^+s|d2Bt&U~@vK?;3WvO3G^7Iw!fL@lTxp z1U=pO@i5sEChS_K93cc^0bA3pv2`Il~rnLBHTJC6wgKY#4==#%z4X`n@3wwGc z<>FPo_YeB8`4=p(4F~*>%ErKjku$4cfgh1(&qT%Dqn-=~y2Ae-F{@M$*NlqZQDH=l zZEB~0oU4De{<4qt!I-BQifmEyM=(F-R;!2K1=|%tO~peNs%9ls;pBw#f7}o>^w|yR zE%@kjPy4r{#Ew)*-YB8i?gB*=ly@!Ll$qj1a}%-rW~xW^%l}{1?EhBLQgRHm+CiX= z+-t3iGvKSI1o2*YPSgO}Ug+ z>U!D{nE|cOua6=e3%;&A8V8g?3YuHvW0URp4y}q|AF&@lITG0&Qgwr?Q43ty)sJ%G zL0gvt;ZJ5bke2Z|2<#MR$I0^3lt2l;L1!F!b|0A!he7BP?Yg+0lL?Sa2xCLt6O~Kf z(Dgz=2Dvv-NM6VUuCI`kR4nlmcV&OW6!iWCi+Au!R=*^&M<_D4=o7{T}(_mQGgROcpc#Ij%mUujLZ@a+4&T( z32reXACPx39_FIoaD?$JTSPJtD_ox_oR>7^hH7LKVIoug z7OItwPlykDHl_slubrYoT6Nz!-7x@>Fl(vL`SC*it&7Xo5@!NHpZK z#CtmZYH#LBrk?Y!w?!V5=?p)~css5Sq>h#EiticSSctCTE1cUtrzadOw>2I13(;*Q zei?81oEL)3_%{U%mD;;_ikN#Y4Z!fwX3t+*(Pkki453C(&uw?2dOJQ#_(08448~xewzZyvF^VgT%xe}KA`xYDb+)t$o#CAy6wW-PolE8LNd*Fg0d?(|($nBt9L zn9H{*L>_=_448};ctZ>#mT^egwVBuk*buSd%vVMj9hn~M2epWWQQc%Kp7_escZmm)U?O5lj`a{?K^PUAr5?-e?BgEHzZn4pa0T!Xc8?Qe7(sc3GE8(( zAO5fy_ygcGbwBtI+RpG{2Sj}g=3Smxh$5)Eh#0w<~c;19q0k+n!0tZ`R87o z0gl@!keQ4`OtH5R!=NvrtTRNbpS6K2;r!WhNoRVdY~Y-%-*H4g?j|bFZ~Uj>t01ZF z7(to!x^oIbO$aVL&wmRh(0iO^6-RS1xN*k+O7DHQ3k8*ngwRNC`d38^0g9*l=qCCe|0YqE`$)@$XtlswTI~(t(w>8 z>&|SLs50nZ0jc0S?q4=f?+0y;3@Px#>?f-IlODRdFk=*;7aVEl7_;dGwRnI2;6N9~ zVx!|cc741*Mb$f*Z3C?chilliu3mSi^%od)(R>OK?R~8I$&BOK_J5jqmCSM=C=|g~ngrZr;`Mhx6~gY@Gcl20s}@1Pn!Q z4yxZeLpJ1-81D*a9Ru)Y>f_sX3szY`iwTlD@K=A*$jbAgKp;H(q9#fISldk81J~ojd@tH&5+*P4 z9|%(`O>pt~wwafH2%a1YjC+aoPr=oVQvBaDz=*$N-A>(@ViwBQW4gRK9(+=#U-)}1IOjRDmBo2QLBS%|L@swz!Udi)$+HEPXHNZ!* zvtZXA1Oi}a!aE~qyQD1E&)laRi7?OT>c`5wZw3Vcciu;WkzOdvmrUxE+mcvo*{^S5 zRs|2-0AYR4Vpo+51XQTtl~FkA4?6fxJi;Y1&gi}Ln?R3U%R_3kaY`IYfA)i2JY`wmYGp zRFjVH3TxL=jNn|z?75`}57HVNW++q1Pra=v0IE1neP_377{*HvRAub8FPTh<6s9PW zql*C5yLE@H0h0US~CPQ}~$MvUOFhiUB~)c29WzEpDXt$Y08u zc%E!!SR`D<*-Xk;CXdchu>ZAujY%uT-L}jzf0Kv zjsS5goA+5ti+atnJ~Oq%SBIvFx%KuR78`m>alH9Kr>2Slw*T@P;-QK>*lDRd3{U+z z_Fe4~XXC%Ag<5S%R|c&G@7)1gG0%Y%-jW0e*^ueUDkrA}!g}B__?Oa0YE-Q&g3_l=PRqIb?5#Tx>>HJ(%B0 z!$m$1H;|Ux3@dJFvdQsy$xM0M60ad~V?LE$&37+r8NVgWVuuQrhlcG|`#z)VQOg_i zBDDFooa2j%UPzy^uJv;zYO`zQ8FA!=;jYo_N7hdyri4h{c(KUke=hS5{r^2TT4g zBkk5MAe;5Od?=*gLF^%C+?Fw)1NZ(aYjIIMYRkxK2x*;Tx^RtCVdkNWNPOY=jivYX z7B|lf5X=}XlisgeZlO-iz6`&-Kwg23Pof#jn9vy>)QOjJZBE?yrwU?Ry!upR&+&LP z4E3ez*tU`f(cq*oy$gx))!ok?#t{iP%m=atDEAI(*-1Ww2P_|O;IF|jOjN57&1-Z~ z=E)j@jas?=QLe;%>)}*X&-@^ne&;Vh#7tlDcy$?1g^8QToknv$D-IEUZ?l4LXG>TX zg${HLfNFnFHf}7HQ0>QVa_fDfpUj?wnj!X@4_Mx^fmTAoMnQtb=sQLi!7P}{#ddDO zSuuCU>s#6G3S&V3@IX)tutZUcl+8yAw*J_^GEDkPTo7FcY1K}f_o)s;OO{+uFOns^anPN~7Y{>} zM`s-qlORe^6yO$if|KNQY%wTh1q&}N2vK5%+*JL_eUoWYQ8NPDwY>f)5?X({FM<5o zn%a^3Ie|AJ>#Bx6e;-6yGw#}OFAid!I~pR98XxVL0a8qUcHg>zK&L^nlsiz*8( z>N5l+=J+A6@iWSP8shOxdA>;`FiO{A%z^QO%aCU%kKF@3SmFJoibsMF2DE}4$)QT3 z1oweMb>o5GT6ku?Dy64{!2W6h&pA@FPWtnQ7#w- z3TMp@2I`)30|V)(%cD^!=H8*U#bt5w_6r$-@d}%H87biWW2Wx_ac@Gbk0}ZDJo**n z$%_$?oCVPIMXN}g9MnUsfgBNa4+0{83_NVUJx@O)zh_PlkdXPu8@!ECckObzHXL!; zsLA2v^v%QkgEqM(aGaIqr4=V54?xn{KJo9q<_gKNWzYtDHTS#OfMbU&P*L#BIu6hi z3m8G6;^DE4Rp8`sh8J6h5|Mmkx@jV=Fk&2sD!8msj-7|O@QEZ12wLvO5?F?V1;>;;W8P*m{k z{)EazggFU7fcv@VXe$pPC1}Pfg4C^G-J_d?RiRAY;v#1^$s6`%s|Vaa3jlDLK4WB> z;cM!=PIg)0@#+KE+|7E?G8XZB3hx@3Bz=Jv5B;we=`JGF?VdkIC3j_l1nKWW%9E9j zssD8dVdYtH{E%M)KxA-Kqu ztjbO!i2-!xj@tBA5H=*nc5Cvb}jO*2E) z6}AOv0l0qVFGnMbYyj?8$w5Z-MGkakH?yo9zj7`5kEP&`i}nCL)O8h(&1m~}xtSIL z^(G!(G7>ayldZH(oBTnPf{LGVb6a|{%yS~x4V{2ER?@T9If2N=D-`Nd97lZ0g!`8T zDOJRruFYoxcIUTB0a1@JNnLp3)tyf-XGh=qNIz~DiStq8*}K*LLTMIhnjvmEUQoZT z)TKo+Ir01utD{ehz~O96WxhqV8}W6?Or&C|8OBx?C_92ht!5A)Mw}1?{OFUT{j{%> zXqkgsO1A1-;>12AX51%R><21}%j}ymlMR?zSAx@R)T#a8YQyac^#f~`yd!s!V_ky+ z$D2iU?kN#cT4tyl$dtCPYlnV_m8U9W=B@$t7du75$th|yHX=7B_+(wE2KK0sHu5gH zbf*(J(&D3N((CV`c=cfOuILSp5w3abFT8(@g3BQ;g1hCJO2uYofR^qyaFYaSV^LKT zoSy@f-;x9&*~xQ=X~{QCl6w}MIT z3^gZEX=D~Rw^LkDf;-YGcpnb=-1zx1ZX2r z-wRw7v*Boa!(GSG;EXk9&1^z=m{euuu9;pVQtxJs7*xZCS6+sS4B(J0tpB&J`l0Tyj?^^V{u&KFJ3%G#wG;W}lMhp))AECaE0VzWuSd#Nid{BAjKN z;ZA0rLALut_}(_j@4+30Er1O-gr3>1Dq*#endP*cYCrX}J|!J}@AFq#VxQ^+dF5r?3QJz^Ja# zC%NWx#;UM6YGFd`*>zLY`-zgnn~4!&4rlH`Eqspy$qtGAT9Ks(Hv^5yp;Q!Rl_9gK z!TH1HkA~3qtotzXOWQw{{Jn5hM!w_V>fmGcO`3)Lt=XupxOZwk-(nwlTjLC0%QfKw z`s%rfI(O!lRdC84WuQQrPTZS_p~06srh@3eSX_!9waPOId`^st=Z#TrZyKhL%$sAn z=%ZlsdxwT3=jcx__io~YKbzL2bmH+Trl&pjxNRsl3&10^X}$(_!l=0(odU2YgZQ3a zw@;oNhb>E!`^fJl6t8yjwlhD{2KP$47cKAKTe^wuxtiAab+j7qyDtfCi%84yUFLi{ zn^O$yn@b=|6B#ge`ycNn;N!a^ui27#lB^vxeFe`SKmr)~>D{-p9q6E3_U2j~^O$KNcDtRLl{m79F27Y0mGW4AwFw4V3J zvA1*O8^ly{oS@po3MZSw0B4(Mdy*;+n;TD#{U1OZNC>VoePRb1P*IObdk?9|A89zfX44C>{0gXCyj$~QnPyYAwQnr2;1kGwR)AfN5KHj)^o?B zzZ|Rlh79gAcY9=e6+zITS>T255JB8Nm6tlx*YXU6L-NCFXz9nrkM2H)TT!u2d+7$L z-+l3iD2r9lNiG_T-8sIw{@j%Oojgq4kRQl9N9g?Z*?fUfu*@E8E0wJ%`?`x|^? z46r0x#lQ&NkG{O3?CuvueGrTC~0>(Sg=PaRXrE! zu@eVIjpUmeG5dhJZD5zGosqNb4udx4uMZR{&)$js_NbKoErxA#A(F>6u-n0&-9v}t z-aS59V#n&}759oVdW#pl@zD7BO>$D{T1h!I(YZen<|e*-%I^o>r0=oz=}_Op?5ElZw%Yzu2x{zypyC!xpkHM^;y^FC41GYqkYwy8akIaEu6)lR2Qi_Rs@ zUu)FuR3G>4jboL!9&=*3sa_dT1~;egnuiIPw|)P8cQ|C@vE&r*~Ob`gEw_ zC^V-OK3HRpc^gfgnp<&qum)>M^<>0|_2$4}$U0L+nl`LNW)k1bHkDG~cBfFoMnQh* z(a)^?&Ve_S@+ilm56Oqd;^FOz&K0)%^egYOWJiE*==k2;#@)|oji^~=XY-Dui*5gb zB7z(HK9?GOaJWvTJ%>NVf*zc23h#nn#kO-^NZqz~W>^ST4XG~nZ$KY{N&hFCJ+B0Er6w=Tf#PQJv3;>V=CLsyijE=V`QWNFaOfIQ@i=A8iuk%7mb*qw*b z^VBOZ%IP=bN^h1h-*2atO}a<~54r)!P8Z?{znQ!KqMO*hPP9r?1Y(fn&OQm7YD2YP7VT{dQKPt@4;yZar0RfqvS)#<4fn4xZb(g4h_<5~riy zG%p=F_h>(5Z#D~RF+9F>&ouxoOwAo@RE})5@GaQrd{c8$T6Z0Fr+(G2JWQuKt{Hp6 z+e{w=A?V)E0(Dp;UY1JC?d;b7V6Vn5qmHVo(2St;+RVJAuW;B;7?9I8x&sQgK#{a*EOt^_boDr{%)Fr_*&fHk)@r@ zpC)fN#9e}hYjqboiXxu1j(Exk_6~{uEgV#!dpR-|zZpjrN=;~p*>IC_PoYG`kDJS+ z5tvTD%5}19#i%O<{Lb+=iY%(18amx(IsHwM+Z;>JuDf? z+6FjW+i>5$K*|$~3GD$wlJuSA*y5ZL%0{;*C`lEaIOp{_f3CC5PJx=jI?i0Yohgk2 zZ<_?Mt{Ex$l-p$GZspd{H!W(*4MiLELHew=l#c!N}nHt_O>oZet7m{*KzOl zXZ4c~bj^p`=BQ_8?&!OQ7!admf+E|x-xi)ks}sKYq`I}guK@W(MTilMmKfj9(SD7J z5ItN8!VY*jiS~{7{p`@U=#^%?e`QD1u`^qR%&}SRs>T5F&GIF^8IElS97oa1 ztnx?Loen;^52;~OBi=z&QaivtImh1g4q=#ZeiQSNIZ}|UigU(7??m|ea9MX=yg@wV z+hhY}9<2zW$}5tKcQIRXd~cO=`}=vp<=>QsaUAQj&y<~hpU4oKK?X@OH|$aQV^5wp z8w|N*2)UAg!OX7Tp(IAim$QFn)Ps@*rMNIO-}C1 z-i41Jx~!G=7=fqosos}}0U3#7tt2aX{Pa+XZ9na;7)?tvxGFi2FP|YTIl@Oni8?D-xEK zsAFY)UlSJ53zFyLvLJWjL}Q-7_#T}ufS&7DdFz&k&25=D%I%veGh=k#$At2SX}Ck{ z%+I@Iq}PJ&Kn5>xKT%=F+bR;D{;V){i}|7vSXZ2iyVa~>98q@YUN+URUL-G1tDLyO zw~%;t{3&tYRD;}Mq#JH3N1?Di;>*?#WDwfRt1?#B7)3@U%LlDr=dwdWk7}r6W$`Ic z>h0?iV?@E*pcG{{enO*9Pa8=5`v`*E(lodi=tA8QCMf}7B z+A9%JLmB&0J@E7?kB{iRfCJo5qmG}Sw2y@}**>}()%z{{4H|c`z2$ocZQF$Q)iCN* zri4(e^PH5e*X!A8XxgKx_pSQog_+2)9#Q5K9j$xJ@qlTf(QU>dH;ntJLeMMqmxb!`1J`9( zsBC1FAfVXvom{+I_D!E}S;CkJEJS`x=q3-B(y&*v#ZWANLVK*ib;Iksw&~3Tc}2_N%sX03)-JzQug?n(wnDAjnk6kqm9k zVJ}G9n2RSin8P01uZlam)uiC=Ykashm-@|O(_kJWtLi+0Lu4w|$e;Bx z#_5MCOXP?9ly&NY>pTz~%|+rsXaaTCB_^G&W!zoUDCk&927~rorB;u`jTnK4`{wti zRD<9(FIag`kj?$>VM^ckK8pR>UB2D7vJ!oW8SGG>^b*f!ybxsA5S>R337OW~+m5UK z=dZ138}N%kbE*i}$i)(f_5n__-ra=gZm7rLv1VH@1xrbHzp6pVbUC~WBxiQKP2BQ|EAE}BAvQdO_EibDng_S z#3L+U+JK{O!$$CgviCZqQ3r3nrHnhLcPPbh9Mwi>E=_*((IFqkLC}~?gUg8@r(9^? zR|=veZGb4Z91>i!J<4>-{{C*u&G;m0=ezph^BYx00h(E$wvnYS;CHC1szIGstunQ_ zboYABW=V|KXym})*g<~EdtcRp$2_|1C;2aO2s9k8@(hjoFts zL`o61x#w`=x(1PFZY2)~KypM6>#JMYU&@#~siFP{vS3quU%a7xA|{iva*dmN$vw~-|jrj>{91dJk0eik~j4eL;S7V%-bQerQ|!b zC@}OKSp~UWf0uy#LFnZi&^1%3WFu0qAE~Xxvn7s*vRc zg>{~6(NerI$CE)X{?Zb|5ZS9P76B)$C!z72YAR#Is>rCC zugw-UG~jUWCAi0*<>Bl#MMCQYA-U<3X#$(`Kj;VP=}8LT<|NV6A&~9^B|)PoBr%1w zThRDPIFl+qy^SFIz|D8QL=^~#Ynq}(0CH=SPfrWhzHxl9jllm>2-5u;9_*!wu#AO& zfRYOIK+7rWgcrrOfdCn{9!GWq0Is z4}Hshyw|K}xo8 zm?S*Y$3QoLj=n=)l4$7afRiIP3i8gabN>Cf79mc|d-~E)Y2drnTG$EeE&h!JFiwug zJd-qdPD7NcE7w&SLrme=oRQjJgU%d~_9v%zZ{v>{UBB6>*?PBzU{a%z1IVHU#Xt>A zHBP7HDeLJ8!m^da@H25Fd%JppRG0;475DxkyOFH2h(QOZZS!g~R)>uTgat}2-x8GH z9T=u?!%7B*jPU@Z=eG`gviX0lvn2IB!~eEOuQw|U6^0a9T>x_5B61%Ecl$BR{@`UL zfA&A=PrMh^lm!CBNpe6bkuPvNx5bqtn!e1+w2qr|Ya&Tve?xC$`m1sYRs*VqLOt@Z zebK*tFGsW41?7DIF#%3s%0pb26g6LDpa@;@g4s#1Mnh$e9yg0n2@(N(6<`+Pceqy$ z3#(tBDr>CrrHagDABh610Tu_)QyrjH&fEJrrTR>iN40$o_L1M#-QNAiqg>jKxHDhY zT?szZ8~?1hx%Try}*LIe-f<&+HO8eCz0!dM{t{OD+he~UTUUFvzI8!9a7C0?sU?uMpk_RptknZ)dXN)^>o_fq1K_wMIb7Y+Fp zKB4|{z090?%tGA+8d_(5ZrG|o&0W~psr)%RqI-6;kDmd0S>wJ47xKHnhZ;!XBS>Wu z-A-ibm*=Xu77J@k`JZQU*gMY(5)Zx9tu_)8;7Au`koWD>l5}x;60F%o{z12Ytr0)& z$5mB*nQ}8HEsh0=X@dlz!miMgK;9yv55FrzE50Rs$XPD!$I z34`<>wJdWb6is9w?Vqgc?%2=hb>^%R*yi|;aa-09T)@0@4}95QIR7iJ5~F>RX*tVD zEg`ZhA|kd)LMe;_3KIc0+If|=?HkI>C8T}z-R;(Wfc9qFsN^TMixERtvFp8er2`jM zoXvZv*LkQ(pamy4G*v#+F&%5|F;(*G(l@E0brD_bL|U<7w<>~y#9$`Gz8|;P~r;xP|4k!=^iBSPl11zR~gH zZ*L$-8=&T-@k^xx{x_%|Y;d3AWS*%xS%Q&WBjUPmaLa`*5iusiwXen=jrviL>T(s% zw5%UkNtk?ruEH93?i~44J-V~S$oCf)|J;L5%BaS0Scj0NZ3?*8^*Yn>r!zQi&G9vC z`0s029f0VGeZDAvXf@B@9aqw>!u&hVQ*ObK`wK4muG`@1W=dvL2l{YZRTFGZvxu*E z7rbSN`Q!R6#wF9o&gs~@Vd=>ex;XuO+OVmIx#B0bIS!8soyAT59_iQF05wMZdu|BO zW4m$g9qw?g=ky`R61x+5M?LfBF6)M|(Z9$k)-Y$8DC_Ri4Paz@ql&(0Xk@|~&n_j? zUyRamx;frA57g~N>Ap`Re7=!WH9Ut0b4KUVZOBcQAgG`smJ4RkX;KzQ9#7#B&zto&~A{I(>#`72VzWzDBNM-N0vUOU$k)n2;?EK{UH5f36l6$=4{t#D~>e_u8d+&b}{x8MgK+u`}DnF8u z3=lSkRumOlLyc=u!l@(6C7@;A^#6fK0TJS_Gs3j4;yK>qkuAf~;z{(duVEa+u9a== zQw|yyzFG%>X)X|!*)F!UM+1|WhI+!9=F?y0jkw_6IkvB~V37fTCREA#D zRgruYjSyrUxI;wWgLdr(#9v{}sQ7kc#Us z1nErhHX0Y;EuR}}7iO2g1j`MQl^eW|q`>{IR}R!Ku=0(ex>$ZfsG+H(7x7MVY%|2S zbD4ZStJ+Xri*CU95AI@E`dTWvZR|djXduK`h?aa`E-O9(JBz6ub&) zu?(04OUPdxD3k#l6B%UtFyc3AarGRcfxSAN(kYWCo zzJ%6;?``=;xs9X2?puvOtm`~HZPMyW8)=GzW6+?E7+jrq2kREZ&O7fTg zlF7Om9leBfewc!jt zO6>fDCaWS)nX7Ua=d9t&ja<}CZ#-Agm)f3$E=7j zZUH4Z30%^B*h_O^r8-hcykVl{9}2?7s4{%MgE|rA$NLl3o!H&R!}(0o9rzZJ7^ONB*%Wo zEt`3gK=n3ly+oQ zQq~Xf`t}fJ6reh1oDWZVNT2@8Vj)fq?awb=;|(H(!wBI*li0<}V`}R+q9x!@c)z*O zS&^<9u#ZavJ?~+*k(LQSspFWf1p(7)Z&Z*CN>{j9bJw_uU3POf%R+yH;!T8^%(_4q z31t#7eS+&8qyYp=gd6&Q;+=SHbefDfHMlZMbiaiBmG(Q;-&II5XvY5r<12Y5F%p8)022kNS#_qn+T z3&g*jOe1)}Z15I?B#OR6PYxtty(nuJE1eKf*m9ePCR<+$Aj-&#hHXPG@dA~VqS2)A zyxm^B8Dw}WJ`*iLDflDQe+ihe_;A|f2dQx7LJExDo4_?^CphnAxF)hdW67%F%j7Ab zy-I;%Y{_5`Lo#T#c8mqx*fNb~EFzLN!ofZ46h=@G`JMpoI>qO}TM=nZ_E(_n*^rZM zG*?~YBGDNKzZzitcoP`+{V7YQ-C`u(7D-1JYmi`k3D-kxkrVGuH!(-j1Fa}Op>mkq z_<6+)=f6>#Ai6j^NQOONgz1@1wXWu(fQETJ;P*e<34RPhesWdl%piYji8e!6 z4iornsSzinUnxYX`I9BXwaE+vwvdd`nVi7Du{I*NVn5q|A^G3f< zMQCcxp4l8@uhN8a8CyJuZ@PV5XR{VNJ^@a92$OuK_h0}$ptzY9}YMh z=ZZd2<$lY7X23fSP1S|r4Yya=s2GXF%jK|n>+gwL{P<)Czj9Np7iqH9UR3cBa-w+c z<+!VnGd%u5;`^B^Xr+5Wy-0{3!eg63&@1vh%-FQyZOa_FQ#GSH9$)>N*Pne0#aS&O z^H~06B5k??N3Outcy&%}%1Ryfy8gQ|Q2tpAoi*rYNOsiubzQ-fc!M#p6h8|m^!b*m zJqWr*op!F@k#g~ys-op;tsO-8X~N!8{m#za0Mx*y#*zWla>T!x{s#VEfAU=uw2(5= zs;s1Dm~8G>-wD;b22k;2O_)%8mqrn7Tw>cZAIaj~IYp2e`uQ zwaHfqrB~&xPqQXlmAfK84(;u1+5Q+bd&fbudr~|L=W{fVIPTJfi{|3eqE{EWPO8L{;D9;VgY8RS`I``7b@DIA+zIoEZNT%uKLi=Qe4 zDe`g_d`Va*2)X{TR7yzr!EvaGFK9p4`d6{*-rJg!S$WJof$b0&p@a)1xMi=>X4>jC z_iq|E<}{buydEdo2Q7o_NhO7N2MUl=Jddmo*ge!w*Rx1~06nPPMcH>XcTXY!>r7&B zuyRVV`O6TR^f*)vU5a=gQ&{d$UUX5&9g+N?qjl>5GfK<>Yz4=!j~!Rn6hK**fT%36 z8J;Dp99^(=>Z(2@Z#7>GkcDTKypT+v5k$byjjo;fbl#w{x;0yBQhQ9PE4XDV%BrYy zACurBf4o>S7OK~c<3r^-3x8e5GDhzJ>KH7KbK*~DWE4afwX000s4ujl7p-Mgo?V$1 zG|_SogOLy}ES#xe3ZhlKNP@}?a4k5}zW;^k3K4{XPMVPp{nzY>uL z@1<(R$aQV~N|@P8q<^ArQCvO(zHX5tt?sXJabm{lO9ptB?ceKbF_~uUC2NjEq{z1A z?Q4I#{0K1*3za9aD!vqO2t#tg2uQ5l)VVG$bFSHQ29{jOoRwS^#>&2YL7&HRke&x6 zo-YF*v{AjvybP*`K(V1Q@v^!v1VSGhX)PBbL+9pqTNdx)ZAFP}MuYPerop11$p=0p zGP}-VlKOJ=iSeci0h+?_rCP4VOkqacrUbwLS=x^OdVF7AVrC0ROvEo}dklxRel3;Jrat>YjS*J*67(%Z2O4tfo8GN3+f>|aC>N6!{MS`ReIGJ5Xg zXdn+xO$KVLo5I|V_Y+an*8UXxk0XQ2B9e)QpmZPXUaq?@3dkD{uzDf@8EyCJ0ng=? zIAQprAQFCluZoc5KN{6)yU@Oz_uPcj>m*WQt@uwTaXfKsaxD?3xttEJBrl0ZDD%E0 z3mENB-iN*HVUBA&5l=U$ZK9KzT=ARnjeSYfa;T;>6bA^z6fVXQ0n|nHyuXpQG0tBO z_4w!5igCEbKOY(x1org}(PY7eKwt-C$}s#3|5mYG1!-X`C$UxZ_O#ntq!G_{;<6fq z;Z%A{$=E)p{uyT1;DWikFE6}%pe5h-rYh}Kb34q&s`x}3 z$%o^D-|^~IDY-a5z{qCs1-a3ugdsCZayHUY-_e(d9tc!gq@*2=Lx}tS-HyDn1vapt z2I%gGP^TCcWBY+;}#iFXnI}&?kXY^{B*c)J7oo zQ>bW&< zUYLJDd03iDJk{z8z5@SjXZe#(yLN!wM%Lt`P~c`u*WX|R`vSEZtD&4cERX{~2DCPZ z>yo*cueL0GDQ+uoH%<6!*y&COkCZW{IhWJUxH^nr;HS}zsEr1ylOl@Ty0$B?JriZjiS4;cC8m*O?j)SU zC+I@a*aW*lGh^q4>crgfyC)*Xn*{&y$Qx?PnVlE;Atcb|4HtoZ)6WzR_HVzDFU!&+ zJgfc$&l_A^%1#_r<_EWzX9p33A39#evYoPBMBxlyTm!@jAKhc|jr4PV#39tOnjv|A zwx%M8+t_x|<{ft^QRrHak!-BEtzo8xzi`Zl&&?+*FdE(fl{<>2^vT?6F0-I}vfbtt z@f-E$#pxNVI`jlRKtDa4`y{2fKDalBt|{!{+!UH>toqDLfE0SN8Sgl>h+T0IqF z_B{IJCar5JZdz-sWgD-ERIkKLg<;mSz zPG)3Qmk8m-ceR*QcGJI9xo)Y8MTI7nd0jy;^{|N>UeIgA+_By{mBL-}79B z>hzN`?R)f+vMHsm#A$+QuRJiFmNgwxexsCO5pPTmx_vIW%%t4=aJ|Jx_51u}m8)$+ z4JGk1jcgnmG8?)R5{|XB>;5d8SoCZZs!06r#&w*;x1lr z%b&c=rg4&0?aL$U>$gDujs;mP^N3+vT7)te`UL3Jou}={YY-_zoS^KSR0(~~O_Eq%TsjI(Q zDiQ*9dL7bp1F`c8V}?p_@bFj`s<%SRo-=l+uu8C8$5;R zGx82D7|qw*Mx3Od`QEHmZ)L_i4ers6;@=~?1=##`7uFgI3(^-WhM2mnoj?zB!`?wJ zvkZGu2HBB-!61eLnl5P8JZ_=6c;{v5P)6PEY7$@IgQXjdUjNs%wIQm9dB>Dr*h|I#Ftg)`Q=bR`T=n|I`|clI8u{%WcjrrKgDB{!bwUAbd9_)W@bfehr)KYcNq^-JO+ z`wRxu@Rpd?${yRkm|R*iHF4_hU+WY5{&V5%6!FBqHA+R-t`&HWkWUb(>JE-HedRfh zWf#NO(EY-67j$NSvbLam(~_)t!QMb65uy$G$P2!f?aN(o1~mKnMPxEcYm$nK-`qeh zkkqp>%y^R`TSN#JN$uymec$sRD7Ji4nOmTegFDF+(&6DA@P0zXmQ~_SYc*@6j?yzA zOZJOHpU37NjK2p}7sc0vuUsx{EUTPDe?L+*=hooWmhxlD<%i$MU}aK-IG~He)gw z%Q=J7x*7JlwQuXJ$NJ?QzttqvgD<7}9{Edz1?85`2FirWmP> zUQ!aEs+pcE@*%nro36sbbTC9keumMo*@$DjtK8{dAP*53BsuB?WIn4nU6W=+oG5@y z(d4_K`DHq9w4zL$yuYDkAsCadpUycY-zbFA_w@l-|B*b>Ee@cv7xRosoOH*+5QI`SE#;M!ronV&!bjHaX@uWi9<9kHon5-8XvGGfpJ6NyV;M zdD&F1>-~M7#~?gWWt)uUXC$0AK-ihrEJnr8Y^#BqUd`j4M6=4&)qpgu5A|Xsb8z5? zD!JXclx0_3JG3MZU*Md=U|0}bJ3l~Psi|I@Y)dEu9!DoHe<&)wiIW&nfHCfnA8S@* zbeQwhlRWi;+~3;kys=sdXyNFk6sj zP9PIxQiS}QY{?=+1tAHUsC|(bRb%W*F~R~0jolC--;|xIkU}>i8FdiFx+=UhQO z+dwfEH!yqP#K(GbQWmAY5u`^)T$%`1peCymsc?7KwNcr(pF91Sn+s28q<8nv+VUKh zFMRO_tlBWMKsJ_FwMQn?tH^uRc3`U1vu(d$vy2b1J;W@)P8EoX+*~e8ARNT+ZCs~WeKgi6& zOvRpOI`QO^{4<# zp)R;??{#rTo5&$0c~}=+LtQ8xzD3GJBM)YM5A)xR zyF<214wVy8?Q_CC#ygafA#}pE9m@RctdLARfi57#8B4aE=!OQ{qfYq?*D=XMu50v- zLZut`_LZ|7aE`jEr;atnHUH2w{Gih4_oY=JL88nMhT z*8`VtNxnHy4zY8HFOVOrk2*JKC19K$tIE%$e>CFY#3u$rhcIm>z{_x!j@GwF=?r_j z-TOM*X2o_mgxq#CbneNl3+`A|)v&8RaC z2H=KBWe_E)dRD3<=)5wMfv1||R4>@unGUonx&5ajIb-qFpZg6iu$w~?bFNjHD2+6=ZrH%=ifHz-lW_EjF*FT-FJP(L5nkW1Vpb-^?zsr!_p zA{~pE$v<}(!H-Ywkq(J!M&;<}2%@>kAHzbG{LpR7Y3ffI{jJHPAO;&Oj-H7NW$uH+ z;d@F1HR!sOdc&NIMQHtT#@32RY)7!Wj~}QuUpV4t`XD&8oxGT@s1@~f!QtG1U?Ax? zg_z8r>#{=V8WzSvmK^Gy!1B?fte+utg_{X% z$uhs_;@+pKfMBh=ccPr%iq$cz1+8yi_6oka7^(z9(!O~wkmMteT9yQe&B`Uiq;JdX zk@q1YG=9jr!A0v!DBj(nMtdv>V@q&MNDVU5P3Zu?>L1oR`9F@%vLTB8ZNsxHu#_}N z=OU@n(kvjI(%ndR_tJ>4bcm#MOQ#CbjkJJBH%Nyd_cQi?tKSO^d-%#F7M-M z0buR%1hA9hk6r)nOxrJE@bD9t_jm~WtipA833zUt#omY^@{>^nt8{4)F`SQr1qXpX zr7PBQyYw&3MP>zO{GE|yz*%;RQOce+Bu|bHK{*ZODt20HRq?9&T>d6u5rif7krIz) zu>Qeus;&Q=C=Ay1jN_T&(|ZOav^0j+~>3)b9HXkZ)?o}q_d;49-3pTX)?QMYV@2ny^YImCzmOV{AoEznN z;rmBR%AP(;zc>CY8>pd?Wi}Opfj-{vQP@`CEVSZ90a5LDxv8H!Rg)aC^_>)ZY-p4v zoNgXDw)Ojlf_fwS&66WA%Ie`Cw&u*}?iZe`HH*^qNI1pKA%dU_V`9TkT)dK6QKuLu zUTTuE!nG9d7dJ47R%H-7hRjKx!1{y0mAI3fOHEjW9M&jIV_9jh*)+IKc~#>#EzJBJ zDUFJ$0W3#4eMgEYoS@m>xf65Gq}{&e9t8fXE+La2`_-w#7GGU0)}77o$-YSRj8)tezuTWr7loZ|As3=3EPDJfJXP@ z69emEhG6;gs>1OeqH~^qOT(E#d`_AG>mQ=&+9l(W5`|q5yxs)y$8%+!pt#W8v^gJT zepoX{1G~GqA17Rd*61$Z^Z!uLuRXd3JKt*P$m+PxPNEeZuQ>VCtN{WI2RmC{3`T9F z2;H10Cpwo;yf*_ljs9--{Bg&iebC{9wW1)5;Z?!@o4yL9u7sSQxczw_j!lRhG#j90 zev;JomqyFNAKm(xbw*s4m(>!&oV=pl4yN&v6(67R163p{Z65fNhN`jMwR6<|B^QfQ zQDUDDweu8Zc3vRFA`ln@qaM<>;`aFtR>J_EH*JF8RW2b1vFA;r22)oKQfc=Kph|X8 zx=jOus0~}4-M*U6T4Mgr+9_XJ#+K5^8t_ck_2GE&tH9bFwS%Pem;5jyB(#ZH#nC}W zO7mG*{9i>Tnn_>%KmcSZlHm#JD3}5qh!whWl-s;Pi3HB-@ullfGP~_m4Z7#N*0+B7 z;WwlXTZ`xhH3TA}mDjTN*g$SZ0m`o$#NOK@iw8zibA!+~cBb&Tn7HkLS)&W%^*q z!#%Z}lJlgHCifon@_ScI9Ut5C@>;M85nTKU+ifnpe$3WT$Fmn<9q(RjmW{`_v}+ zRit>;wd8GtcY)ve6Jc9XDyh%5h2tSV9>+pnw9I#rIMEJfB`5Ux)^)4LtTJ|-4!%3~ z{%FvWRRR;fshj_{$a?*Lrnv@ZVE*6_{$Am*m;eyG?I;r4zO@-w=J7MBgn#R$0L;UkS*-7G!^GRxz$9upxq%^A~5*=p8ddN`O~!V4hr0@(LBu za6)G?QIO*~uAMDCZ7a!Ef$M5H;xF0fz!?KKmlHZ12N*kaGTrt9=M$p#CXR1e3;HcZ z2|ZDw1WNVxKCvEk0|8+BM>?eu?FSwX>fqK5d(FFgzuElVcH!N(T+Qqa4_}$tJXi_f z^zrgFaiiyI>EnU{^V)XcnZ6yJqO?L+-q*Q${0z&+m-9#p0fA&ee5tEr!vKrKG4xjq zgmRqN$10AyG2;H4C3g1s#~0+Ax9T;3<0zKggv8kdhxi^!`rqbKE=%7#I{oX-xI$m| zt#bGkO*YWrs^Z~q;|rPH`M|QI%m}$<4T~FWYhUuE{|_)>Y2LHs_5eE_8Zh}1qmh(G zq5EH<9Osft%isAN>7ZYuh0euVtOh)IOhG(fs$msF_n^|iZF=d?gAVk0U%%e(y{!C@ zhr^JSJSu0t0X-$H;+n%l(^Yme8e^-W{19s+E?gJy zRi44#3VksB!Up|xo?8e>q}xdyxgg=B>~{GSnVvyNfrfpk%c%2?*X(}-Uo0i1%Hm{H zx(K4W^8>f%^d~(FMs46MMV-tATSqSt61G6Q2T5?D#y}pb$FW7D$G~XW;pvo~t#$|g zZzV{*K;yKY{$^SwBp+e_PJW_!a!qd&A zgZw)qwyzRbsRmn>NLvdUfS2!wWhW$S-#M)0DNF_c4fFxTgW$?P;3H>-shSch_n=Cl zRJAbhVJz5w$Slz55=6^jwrP@9Ttn$OgAHHcA|kU=C1i4)okq5wY>EM}s(PJY+}uq|TOA;oq6(pHc)F zwaw2Bt4C=Re%hUjhNh!C7T)mp#Wd9sLrcSxJdx*y*nOzC4}POFKE1F_7qAT!`E_fnATnLuf-?Uzy< zbnCFZ^o!6wvxE+xOn10z=&%)1)%9_Xo=EbuS38;s-ayU;$o6|R_;QKlP3yNd{aO%& z-JcEot-Zfa{oK;|{h-j}Cqv#SEKwZlRYU*e z@rTF*3EQj5up#Pl=v8C4B%S$}Hbsf~cDQZ!bs}z%*;A}~uH}!yb;EUFX054ze5W8u z)%_xahWyaXDv0{FLBN%LHF&}e3p|%xhb}P>sQcSAmQJA8-!J`E%MncS~hOam= zuXSK&m72Y~E>_)>A#7-DyDUMUJ2T5EcRsk&>5YQYQouofjp)^gA8n;S^Wsm2;8lWo zB!>*dobnxo0B-j=JLRrKZslJNzH;1%z160Di&zDv+%ZwF0vsL$vq{OjNhhzuDHwW% zt8sSANELm?W*ve+M#nl`W_z>O3tX>TXXLYgzd9U$ts`+bn4D|O&iEUvdq zc1a&AL9_ZYvP3s(7E6((^K7~^fAPwYMnUFBMJVL*4cRLH_}p1QFr5{;WalKoZumsldj60A6sOCk1p{NVu-@ z>oZ4@;4ej=l&Wz+1pHm+2Hv!ZsREP6aund-lD0 zBpzJ#;q+U?OM%YQdc#I?uoQ6h>Ztdg+o5Bi0^?}@c@#rD3lQvo&o1z5JF3eUz1{{O zr#(EPj}D>eNYvmkhmeuIx2o~q1^-4YS5!6JG4?uk&d;2ebAOp0-*8{op|T*}3b2x_ z0km41kw`k8d=;;cjjoAi{mdBQnF!fM>vHX*Kh-dy zR=1~nqJsb+8Cwg&fna!-=7&pfaGAc`COUZm!JE*Zl07%C@XW)-d^FpJY7&^Q#ZSL~ z_q2=3veCFCTNklCzFTi;7i|_eoCyvfi2UX%iDf4Ayz0}s8#uH^ii;}#O9>Knrm!gM zs}9&CoAdKrBZ%RD2YoM#p)kQS?*2&hukL}pT7<*ljq`qZZ}#Ok+y|4>g;*?Z<7evh zfnNaEy%6FVelJ{%hP6;~ZbxG-_dcIGfhSRyuZHhGK%qnZrh=OAz*QzaS9KW#KU_#~w*n0y40!bBpE} zXp|eDOwQqV$n>Jf*BcI7K^d&-mFXGhBjx&fpl*0;5SZzO+SJV*uN zuGC97o^{qe`$}~7tn{X}LAfiZersXgtTiEF>Gsp<5Y|{i>TUMze}HCu@kzD1X&Qt| zlpH3hv>)^|G}tB}WqC-3eUof#N$z}z5Y2xx?kY5b9=F+*{2*!B$dJ#)4Icvt)a#Lq zUFC=w4QJmnU&Hx(c&&ey`Hrj0+3A_Re75`(y--jo|7OJP`8vR0rxMjZC;5aM%B33V7!aBjl20L0)0}MVX6&Y%v+2#!PChY z^Hv*6GCzEt>?=pVnYUno|1b`y@V-U{Elzn|)rsGxR++qi8)fk;CtPaZG}W)1nT?kk z25oj*<@%AZZtZv0>>+qlK)~GG#&e)>14_~bMdqjG7z2w@s{%Mhe@K?fZ%a1hIbEXA z1YcP;GJo+ivC*55*9e%xm?XnUjvwZ>N}atV8+JscI`a(4KrXTmj+=I8KLu7u*gTR6 z#B4l~_+@3TVJqH=1N1h{)mr_+5xNVw7`He0txBkCkI%Cpko~zAuXofeEr$f9s>t`S~`(@eR`}YVP2EOBqj)Ee7J2VGavTAMo?YVujID zSCPX1^wjUA1-pG)@n9|-t=GJ&4)sT3H1)MvhJ!mXuT5!)DQ+r$%e5(t-bv}aV}+(7 zXpHRMS^k{3VkUdCrW3UeJc$tVCHuLuhv`wzVZP->qwOn!{Z=oTkZ`mWEV%US5h`9^ z+v@g+;l~JgZY+Gi*!Yb*9P<1fJ2?TZP;KSpcj;f}XSEx`4u@X-23|%9f;(jAt6b)B zz(d8qq7X{iQnLxh*o5LMvWxjLJFZ%lm)%-7RhPKey{FG>zFZ!oQ)0X~ujO3-MrY5n zeDEU5t+O1O-0{8kc<}k54wWJ%4xvYg(@hO-te)=(H_SM$hMx!fwR2v8C6bdoSqeRh zx$vr#W%Gqj+Ezf~wt56P9zrOc;V(Vv2d?)hlri`v%3-oQOe*=mJ;n zaOo3R1%IEtwPzCmYT>c_CW_b~z(wAi%lscK?Qg7w<8M-lN*Ca})76FpDBhyZl2X=taH_;s2_betl@y z{GZ6**>Ll3e1#k$8%Qp$DI{gj&{Zk_=Zs(%fn76;iywIZYk<)P-pz zX-p8ZSLje^ix8#v=W6F(P>Y&(`e^3hW}COn}{O>B6D4)ah((Rc78xSeTY9x;>73dq?Qg8eWR- z)KR-zR)!5ERTU$n6_Dt9_@;|b6uE**FC?qHE0kiyI(VWVH%~gTIp8<6n+=pbDQe@) z{S|#OM>b2$2@aoV6)0-3LnbNz1LRYagvT{IUvdV;a|eT|Aj_kOy!XX z7pzJi@zm&3Xpk@ju2Mt0!+H1G<0DR*{rk(Q+e-NpcuE*()(Pe3S6MIzw-m zVz+E(vQggt1Sb=G!y8D(WX)fnYx$OHmhwed7;NeNY{}4nxZLs0Jo7E?%s?KJNmkN&*R^AN;23ygnJTLkyH;fMGr zG846CLJGU+!neiT$~%a|pB)o2q+! z3Ds3_5L*uui#We?0o&D=)C>74p&aw4hf0-^pNGX0l}2ViSV^)ni*w3LeRSZoIxoPl zUGmHIkq91FgL4)BeFFM2E6OZ2aS0(5zE!j>H+eidKe0{f>4Kj~IA-_@lCAI!tcDl86jT-iFB!VL{<4KjZbc1` zqA$i~=@UU|4gY8{YY%qwTw1Ip98gG$?h(y8W)5;=nY#p^vVJj9XJcUDJ7C{n%lh9a z;l0u=R=cL3n0N8hJmV@7^1}&H?FHx$VlDkPkgT2d)Xy7Hy|dalL>Y{gJ6TIWrHFJf~F&EA&cn z+UfFRLX)5eB=+T-9*y4|G*+ZPPZp@(`be7 zCaB9w^zvSh5_fHufvzH>u%F4}Odo6*|NR3s3dwkoHrnF&M5U%^7R~m-5k&uMz;8fa zxSv_RXK64GeB`v@2!3zh&8FTl8GB{zRX*a+@F^U-%&>7S+@BPv=S1=fZh1{Ad5}X> zFZo6I2>GTSy{_eOAOow#AUuKeL-J{NfUN-O8BZc^crVJq77I31M(devhp8#YEw#0S zVff0b}~lH!j(Iz zb{7X6b%pGOOypBBp2_8sXJ2?pect&J$5{h%iH4Y)gQ)MRZs&Fdoi50Ab%uUTf8CmX z`yU_`r|kx15Yxac=^tsbj^8@oVMB2#T+)^G_99`HE81n>}O(MHZHpD6F2hAu(4L zmdh#a0!w&A_&eOcnXw~F`qy=%HdN!tI=i!$pmU%!O0bVdTBNuDM&A^~-$w)9?a ztM%d%D5Oc+E2Vc!qIpq_lExqBT>&SUMRU*w|36S}!$%>)pkYOdhU61Pipth>H=deKV`s+{MkZU96+Och=BKAZx{GbcJ%>umi!Lu0TG;pB zF0PQUwwCb&KRCJJb*7OyJB96uLZHCBa^w4uQX2)WoL?y=Gd<&*L38jE;D4V-N*8!l zl@Z%bxQ3J;!7eS2N9%eirk%_!yV?i9b`iw>yrrNi5G2ZEWB$sNxb0V@ITt>X3&lw` zU#g)QO;ShKK)0u%TqWIdQwy9X!!+i6Xx~UN+3S&)nn09qYfxqpYX4gUnGUBzJsw+m zZbF}S$I>x@=Q%0zhVLjdxD8Na+tSy?juD-dL(H`x)i;_eCWz*;g3KC=fQv7`qC8<% zO>G4_!&EKh8+*D&5>FEcC>mo!`F2^8mC3%|A$Q#;e#}};7j))6bAktj#qWZa?5B$D zbKb8b(e(Hse#iT6W_G8QfoZ4KYHKLN7Su1&cOGW6%uvUX!OQ^H%`W+%1m1& zE9h#x%JHsKKKs*0@$hn8*vgi^OKapxOanF<+Dd>bZcEvj7v_dIIj{NFO_;sU?ld`= z9^A1_P0jx6d;RG)-M!Lu1srMA>H|iHW(9Z{{W7GZf;rc3G^ zdrZ3rs*b}J@Tnxy937HUmB!ODXbs@~jlkQn=B07?24!qtgiu{8C@Tqls&?#xG2l_K z>m9_oeq~pJGARILgH`WEZ^KMQ%^L{2!w~cyykFbb`)!OL^77^`{sRV7(R9+6jDnEr z6mACw%w#B=#FN%yI$X4so& zk=q4Vi{g@(|rDf3!lD zG?ozhniXlE4+VhgBAT5-ug_9&KGK_sbLua$Swx;qj>m(D@NJeBb7)SS74s+sUKgtU z4}!3%j9SWKpBy z`%>k=kcSrl9EcX}SHWs3Uz4v;9rLMew6Y@+rSoz*mn79a z?zQ?UUdPUtC;j6UJOd-k4Vc1Uz3$T^-h+7a>23_yktRUKthu?$)!Y?Iz{) z3j+0<>@G>!(==(>x9@y?VDWm3X06|PMHA@zXB^y?iBoKl6LP$cJ5_?saZi)q>evV~ zOkoNPsXkkYVJ&>}DA0F1If!lV@~Co0v(fa(~x+XwdT?T>@`gPW6l3E5n-QUWLeYRM<35*HGzM(Ae=RinBq} z5?@buu{&;OP4nvvc*YYG)L-p^5#x z-XV=c42xL~>h6D>L+b0fGrji$oFBzSbuz7ZdNINOx}U#P^oT>??kUipkWo(k!h`HF z{cN(2V5zrnsirSV;3>24z{5h)?fZeHfp(u6Q?;Y95OY;)lHJsd33-|+n0jrH{~7H{ z+1M;xqJYHs>QDc_;4Ds4iGYYsvX6mQ)DjvOsODVnGMWsYEpU0bs-6(S)GB-*gbWP~ zaa30RSKRf+@^JfL1`ydkoUG+P1M@!Px+xRV3V??&6H+4Xl=Zk|qlRi7Yc6LkF+C5| zw18g`4C1+(t?2p3hn5XYWxbu)7Q10PGj!h?b%NVTlPOz+;}^!x7GXig-FNtOSj*~n)S;eUS+9VqYa&J=fhdd4Kp$=Uu&m+HO-7G#;@9&(CP@S!(HjYoG zrU4WNmHvG>bxn9+KZ8og^yT3%Jio%_j3l7Bp2h?rAJa(s@>`$jV`b?uBTDG(qjyBP z-Hc&s7f5|y)YkKH`_*Ta&Nm2~nu3utGy1vw2W)}3RB&5{{~xfV}*#fogrNd>v253zb7-O1&&{v_SZwP+=)@WRKX=}tfam|c7 zWxcR#h7yBS><7fh&R25}Hiv3_YXMW}k24!G#Zv$_*+^P3UT!amL z#hcGO4x!58c=d*!>?-D{XYGl6w;my%y$3TVKBX!Uk`pqP2b|W0h0q%Yk&m{SJoefzX>p4VdtM0M=FU z6k5{5nisT$@lCP_2dKW{2j`ifkVGf>-=(iW-R!u4L%(QIK7ykj@TRNf6 zTPPe^y7B0}-Yx!b?dk2= zqJ+dD5UZ8_uzS0?URpl~sthT_^bXYrRH;S|dorDQ*Y0dFK674hUZ*yOKL?@dD=rLH zV8UB`g`1%&-rNhbLc#j&Y9!GVjaQB6p_YtO z)J>+u-7$jl23F2c*NCT+MNd=(xT8L$>@7bXFzNK#SC11+5d6%Eib^B}8Y0sL^V9>P z*;<0fa$3|d6u@U|KK!qi!SG6@&t^C*0QhXniG}#09;%d3Y&Z2;2P%fAMFOvCWe6oG zC{<>vrwp=f3C#ug8%cKP%gC6Y?e(OV2Kp2yM9`;ahG~lT8AFjgpu2wc7^_c=&~ z{rxx;1Ep|?Xkq}6ZV_$K!BR}&LEtQEoPG>b>NxK0svphOWLYyH%z*gzigj^X zklFQv&sI=Dz)YAo8)XN+`)YccFg%ZdR?-lt)qe+3!!mWys7bMUAF)7DPz;7oZ@6i+ z(yFb-xI%3H*+JXm*2I)TED_z~64-D>&lGKZJ^p?<4Q>#x$c{^~3ec}^AfG9R*OKvE z(D6;_e7cQ_NK*LcQ0x;ol}XSFjlL=yNW~ivhJrIQeo+eE6zl_n0PPq`p)GuN7u!_Z ziK6Yxa`NpP7n5$QFa&fUzSr$fJXPROtdTh!1u35!`z?qqJjhI1P;3ou-L>B>xnQa{ z8%1TYP6*RA4I9Y7q!E8K`#Pr@TY`lOAaZ&TsoiYmH*DvVTmdt9MxM+=YLKDI`5o;f z!dqy;IAG^*YOs=gS&}WFbD^+>N=q{Kk8q5q*R*G~7uLAljfewK20GC_0|B#AHqw|! zyCqydREFE5e{?p(QQNbx#=e9-dO>&_{40x{1?+@+@VR+~Xbr818?{h-O$42Deq9i0&2?dK2iz`?@8wB+&k6Y(X4qr9s`bIQAHengEEKO zwYAoI17l}XIhq5?{om||#p2{zW5;(yQq#AnfakwXFlo$#IeKKM)bU?rIN2kK2tb1 z;#IP?(k0LUuS&g{0r~9lj7cd3k%7gOoWAoOH~X;*Ed?5Zm2%mqGB{zSA8D(N^T3+> zQQ#DYA0yi!fC_2mdcU2Yt+I6rRKEAQkLFhM+pRIw;(Ym$HDnf|`ImQsFFYVlnQ%Lc z;@;eLx{O=cLt*Xjb$R5fNe_;D>IDwaRjvau4J3LqGHqVjGWTm-rEUk4D1U5LFUkK6 z@N>&L4u~25$&}#|^G9p9Q;hQ!u(s29VspMlIZQXltTLA0wTqes6vpl&U8gQVONeuW zReZ*z#O%C(ijGbY2}pXrx1bss{|ru8@2ou&5@r$>%PG2oUTV!(kD*4Y2pAI8u1qed zK#9}`Xh0XJ3LD+-nnJy$C*aOu!JNEdK1C^=EH zr$-{MeorJKKr zP43oeO;njL;={_^?S^YWyQ<5wNK@3uv#Z3Lm{e~=+ClPU$zYbk1$V=vGvs<&UTd7W)Q2x*p*hSOe_F<%quiRt6iIXQR|9Azz{fV1bB~{E*T3^ebR}jt z7MR`HH^OP=T0XKd=|KPg)VDHpR06(a$YaR03AEE3UW z>*KF!zp+nj*>I7EFr71H!DV+VqSz$ka<6cIS+UCxVRjNWNA9jxjXG`Lbi~_6NGqB&L$lk70}3+bEYu7%;moSyQRC#^WYDpW~G}mT`##nB&eGblrX6gsd=XO^F!EL zi5^c+MdE#nvtDJkogF+;SYWflQW!yrSH_=@zff?pK0{#b#qhqO5bvB8doOZlAgL5k z`B}$mX5kBay=6&S64p4N707Q&Btk=#A?kIGxq;8qFH9`wTo$Y?gvmcI2I-q&44l)(zf)I7Eu zs9D;F3$VWr-b71&k4b-n#=TP|yAw5hxbikd{gwNY$Cn!o=ytY%xn46fnN^AhUyhdc zz|qtAup!Ktcm_Ob;R38}<9060X+QMKit24gqsVrxXk7~MC-06s*ufg5x5ZXK&>3ps z`W}Q5#ciB|f+zguzb2=313ZV>q@rO$Qp4h&X0g8;>iVb?@o$s4=rk)QKo8_U?SJWA zzAs9OWQd217~FHFU^Cn%j4FTb}$5me_NGGkon?$F(BJZs3wI|4{#-deo%=*F7k+Ilxc+RxTQYkL`I@?Ow z&4?hkAn#W>@FPeE|HFnQYuZseGj#fknRI7s9uLP_G$l>;U1MM4C=TvNdkEG~m{|6u zYovr^rru{1Zo~zoDd(~u2$(3U7$B`!!%xriX6WV0nsk~aR%#f`npBIfP^9T>b(PFi z0_LNSV2tuw<4*g&Sf7su{I){8#|<)u-rlK)Tvb`tki^HMff?rX)8{_-3zT9Ps?(9G zFH>9d9xf|8u6{Om@LHj}w+fia&ol5w%iQ;XKrefDdWa<6RprGN?}*iU=WdDM$zOI# zrTBnvHS%2FbtfjvKw-(=vsSM6Ie`oL53)16?JbU3{@BB2hL>!$P?_d7p<37eWch31 zfs2tm`2gT-PatsaZKM)n5_oR-P0{-!_Vc$+NjY@w8|9{}y|%$@7d~sbd$OWRXQXc? zTUa$Bi3w_epl|nY9+;ovK3`gn=gmn-Keg@ujiy|BKwKU{!3yB~bGofB`gxnG_}1u6 zr|T+f+^y^N`&%72pK%AGD#afcK~J(`_@(o6vRiLKWmxXc(o^VyxMTBKeq?R+3p4L_ z3YYKTAw;!0Ud7z{lnqk4ZMB4OJ~(-}Xh>ZB&c_xCy5 z(AkA41_H9(ThiO@{$2uS2>htg7KLGG3&%*uAi2EI0iT9cmV$1AocwsAQVxS%OLed$ zKDd&>9%7SX{+C_L%!+9huJ3i?FpBk~hlma)w6Dw*1&|I+Y^EZf=-K|8npB~=e3oWt zg(gQSuKjoBQ#uxq*yT4aV*i1=ZumF?8D#i}O+?`0` zQfQO&a|6zWjuH5+^#*6uL>U8^A`49*vfsgwW$xs;hm3WOSM95H+wd1%vQ^zXi`9WK zV{#sxN58|(unMz#xcb|%ii8LJ`vJ|u0m*AF|HpOX2PVm_oIj1K$WPXkw1m1LHMd6GZj|4&7O?%&jE>W!?V) zgo-7LR{4){s(}N3{oS9R~b`X5nP*zGG?{(jde(`Ix;_U`c^|u zb3AKL1bqrPb|>gg&{E2HYs8D?lp@DtChpKdJCW}W*Ftk!WCjNs>mk#U_0gFdUw9qA z&<%sGcpjwWz&CzLJFxuuQS(%=#;r^Zq}8*COu@!AmM}&#H@|L|Kg3Rs<~`u)=5^Zm zmrP6vF-mQ1G+O$T%P>$1{h6A=NDng~iwjficFKlpQ!BU+cW)FrMzo4zLI2?G6gl23 zD#EWo{yEoo2C-H|i0g+|O%cWzh9ptEopSNN;U$4r8zq5#=i$8JJm=tMxgDFtzY<^j zp&74Lehinro4KvRHg!DSKY0uCeW#LxAr+?#{@4UDH}(%!+knAobaJ1~2diCinI}GH z_HfVR=prXxX-%dvTFJq=c18ZiV*S>R`n&%W9?mPG0sHhgk&mldtub-^FU)c@UT3m9ZB;Gc+Ql4YwH0lpKJZ8rUgJPHN@eGvw8-YDX@&v&U`3;)aiQp{eFYQBhJIA>thoi;FC3xAHZUd($lwtfw{<$nP7SIpbd4c55lM;1S}IpIaZrs?-qoAkG= z>fiH84qgTeCIK!zdKCWwU#lF~2ajH!&a7`AnC=Hqxk%$=KocJVkYcRYH2-3`#K?-4 z4m##@!i~|0(ySkwum8jZy|VqZ^huTwL)#fD7SeP~(CcH!&yg(0`vq%g@KEiH^_^E8 zu6>F_cJs6>6}zx!9Pm+hp8p^5_@67z^f-P^gRF(`{{gM752T5*x1P41pKb$naJ0#A z5>f^iN<2ePHNM@lU6sY~SB*n^Zz>D5KYbEZrUx$&(b>mMSnOBU!wUzhn$52_EIJ>< z5VU&7MEAzG3!C^A{Fzjd;jEtLE9AZ(%#I8odlbt4#O!Q$F>G5jISM z(S0y=Uq!LvvkNAbh#ndYgnlIjSI)c^0@Lcu^F?;?_U-Nw3#&+uw2apmXn6!Byjqcr z?ZU$w)r96j_>q_6i0QH{9YZ9Cx}A-%HVw*sy3*9XY?P&F3Fskfgvy2JxP)i;6{Y)J zIaz^x!SS+BwMXWgg#sqdKcp^1tSD}3jtxhIv_xb7&cmnC;hg8H0C_9#;s`t{F5O%P zIvyNxj~3da|0w)86!7coN6arTiq_AiSN8QZgFgCgxw#==WM{+Pd+MeRMn2xD?#5`K zpNM{z;K&S|h7#N|-do;E|JFR6Z+}u+x1HExpDHo0+kM}DAY4}f!Q*`r%Jv@se6tIU zrH2OD*l+wsKlC&hcNY05xZSbNm@`}>{?920uL-ajxpmiXPJdsFO?8`s&P8Z6>qYaW9)JI^3?d^oOj9uvX;>! z1HgTy82GSm@I_v+{d}sBK%jw!^L_f8l^OQWp~mNFq3lC9}Zs32+4NmH=+6;B_eU3zmxOQCkhr^R@r9v^Y@63_%P+ON>za3b>TGC+ssTM0AvG z;{AYD8xn@q?R>0V+#+wmZoEdv@vzqzUokmfV2xK~-*Z`j*SY-cgPVuA|Dlc^BIzde<<}ex4d{0M` zdX9o5d{2F<++yw_rTjGftbc6Karo)4+k}#Yk8WaU90MNwJ4ohf{=w!i>;X^hOd(_yRc8CT^KtFa#E*38JErj4 zz6`w*%MXfLvp2Q$1HYRfnp+bRCw?xnK;VnQ&0O9e28Bt);M-5Ljmd-BjKvV|GZSvW z#nbG?;Wyfoot)xVT*|gd4hd!b)ORez#>OpZTf}zIBXtbF4CS2*oh0|<2$L=<-|K2L z1I5vJ+ON$Qp-2DDm=+9d40h>aSWANW)&r{?J4yX)P35F8kqqy9-Ir>a5|rzH!F_6d z`+YD+v=}vbg~c6Pzs^=WGr#1j>@rVr9C>^mq;)zGLo%`yp4o%$LJCpa*gaY=iG-$3 z<X=XPqPnTy{*H$O~2RQqv91cGJAnwI8OQMeA|BS=pTQGU)=4PPzNT; zJ07QhH#59h`&vH!?;a7Dp z<^%$BrI!4&{+;+0;OOZ!jJt=c!xJ5H*!0g0e*x-=sTxUFNG}G}ntm0( z;^Dr$tWv6=LL!8mjvv??72cm$(glETs%QnzDLFr%fpl;^wQAA<_eoX(`$rp&UKkBH zNOT(v%ej7r#DXNh$Frh!?^jT%FJCGCyOD3z!fmC2_BZcJwAk7?=$|Zrz}LbEX)9BB zK*J2i6wyp3Cg2pyE1Qp?SQVPU1PZW9vvuiTid~Y?Da7U$(S1#~-O`W~zAVl>`t-u6 ze3ukr43on-@D~fvnvxrIhpqg$9(qqEb{3!Q!Amx9s$O4!M(y`QnNDgyUy0nV$f60q zh^f%mT2$=2`)bk3@kn&K+ zln@`62{#K!ZvDz`!_sasgW}-fC}b-F#SWv!?C1(=!IPw=mY7#yo9c z#N@n&6q@^E;aN=EqC_3Zw;keE@z-V+F3?s ziT+_WJOBj_jq^Aom+Q>{uZqo=R2h~8w5n2MUzv$Hw%_gVzfNQtIm<)rJpnk$a$89* zNw33r+KpZ4(oHb$LjI^bq}ZczqlYcx0O?GxV>6EUddg|77ER<0a~ddS(^lGc58qU~ z9B8{ABgm{*dSf#DNsAVGt7-7(d-QZhZkA_Wu2L>YQlpP zG&01s&@pGIpInL`RHTn(y@{gbTSdada5mJrNOH8|wUl}~AX8Kdzcg|S2v>6}r|h;O zk+mgl# z_c1>pgH!iS3_|+40Jcow`=qjn6-KIDk|xidXTXpCIfu#(K2$ye1x7P% zAQv?6JM%MX`838tqh+FL(atWb@N^|?EQS6zyj0A0&8E)dK@b~t09MHeC-18&Gp?i~ zOW2M3d_#|r7>#YM!>{T+WA;oT+9!ax^O%Y+I|Fzofftu=p$Gt+7Ns<5p71XmsWC~% z@#Y#BAGO3%&?2u$QwK(>;S~J0R_9iDBD?&VbQayoA>l~kd0kmtB;ruf>s%P4d(hlI zdK>a@X_vp&IthvjfFcNssnxSar{aixH`^8;j_*I4nWKhEnZ46+?4@R-OuozJ0Tn$2-^^`MG9TK~Q znaU{q{sRK(@bT@SyncAKNs5{TxbRqX%3Ry%C=3fjOBL{j-z4C1YRFi z9AGNedCm08;Uvv&3ZSwaf-%biU*U;Ag%leVVs(q*H{I!vM1}PX!hhhospW+GffK+N zCt^b=zM)}Dj+SKJL60|$c?ENw#oF;vLlnCLAB#I^jYhfrH(5&n?~f`sXg7p-6M`D`AKR?|B!i>Vi+ zYxo0=D#v`JZ-UMW_%Rv0k_812s{aXLv0`hs^6|k z*R9ejRwZ>O3_riBt}+N}*#du7r|Ve$1Cj&>ld$hT`;kHluXFqG(A0s=5}l3@rm7>o z3^`#sc^guh6bz@B0Xp7o-bt+)3gU7i8tCU3*7mS7e0d9<-4L}3h z4U7l^vCE-~GI!4K;?rPu_!CCzzh0E!?10)cljAs1-63s^T#9m+IYPxtVWlG{JKRA3 zh0i$w#W8|p$juF3E^rz*hk!lABK~bvaa0<~0!{p^gWH|({jYK~w>sujP?Tl;gNvuH z$W=5yd0&%Vy5ILSRO|H=em=5$twuZ{y~Hs;1#^Oserfoq*}-9(2grS ze`rSk3U(stF1_)dCM^PSENwn?Mr_n_2+~&Q=zAO)--!Sn{SuB%DBdqm1kU6zL}5~n zwi44`##yV^L)Elb;r}Q)%eW@rK8kM)7zk2=fQ%5Pbb~ZZkW{3kyQI5&G$NgX2q@j% zEioFTyJ6B@694CZUhsN+cJI3G>pH)4z9*Xr<};=E;^z?O$8XtB_NtAzY<-tmJn?~a z=9zbvLXh7ah@ee8nes;j^9ws8FQII_XTRSY4_p=IH!KGYMG;KDs*M80)k_0E9G*)m zxx;+~nLb7NVGiTZ;y$6TYamB&^)#(5iY1?Nt9Y4iCh+wL2w~h!B*;EMr+S~4>?m9J zVf>~3PkBK!zxER6@I34UFmC>lq4kc6I#*hXFQPjXlTp+Zkb*vO_W2x~AaFDwYJz+t zN>yH;xPfO=n^dF?wxy~2r+Y`{s}rTAJ=l;PUHs;#VrcGVJk{{WwvxSyIYZQ}fKHUK z*ul1MJ~S9O{Op_Fl%sV1sM=yLlVj3^Rgy4&&KlMnWbTK1&q|!+KaQzS{;UmFboTRQoyhwL1rq^1F$5rdo$Ul8vR6s2;Ai=;1it(Q1ef6+VrA((zo7*teI=#vuCt`g(u=Vu)d=6&wz(_=E9XA*^?pn&q@YiPPC zZtF3-Um8#3O}o|z4(&TxJty^WpV7l+Bo+@S9j<6*{h@9;-ZQl6!r*XUv)> zHnkT8^=7Rnb2_Ot#WThss$7JFjg0Nq4<+*PbhcaG8n*am&gwVRtWrv9E~pih!4!DJ z7m@UqHtk1~z0mGNlRiU_%Hk?klJQ4p@UcERy0*rppg)@6tpUMN-Nr(GKHpP2Bj0uT zyVXquP4PmmYR}K_R>s{v(?fWDAY3Z=8G-O@Cg;~OZTgJmaK%QjQ`beAO#qFyl>HMy zTQ|zx8)c}ygL>j9-fX)~`f2Q!?1qL^Z&oAUd23Yr&G&*%jGQBepBLrOo)w{nsr<&Q z!wkAtaUR+D0i@O`3HtKPf~regXj&cgGxf%X@7$2+<+qQ?ni^A@Y9>Z;KQGv4s*dVJ zYIr*JUK8L#;Nwus^o`X8Dk}>?m~r!qv#cn8Xw7tXd`<|LP~V@ZS#7(bkT1r1_D`?p zF8NYVUiGNvoeVZC(^-&$Pi6sXRKl0ftTsWooe&|iH5%5FAJZYnlp#TcA2fFfdk8~L z_NoTpPSF0%iS~e-f)nCAD{3~R;3F+CfPe8O%dvVZ18ZMXwZ9b+28n5`kUB;EzFX#y zb$D4{gx>CTYDi(X?0wqQ2_U2g-t>38{BYW5&DdaJmrWemY$6+1Y0~(YSB3W%>}VID zZ5q{odYA($AF}Gy-LY6vo9f5Cmg`p4*b2a^xILzQaq4cvr*1?Ut$EM%D{TK4}`TNl) z7SO^zo7@wJkYoPEe&q#`r`<>qbtSwT)lIdQcUtnV!eq<*+<>lv(QeI_`nIVu8T@OPWiyVJ+-yiCbSQ2~T!*@QgP{^V5e+|Gi{9JyCo z&wE#&T4V~Wes{!L&0mcaE>37sA(5nM0M6g$)q;@Emf3cf|1QmrRXC-(2# zD@pj!=6SuT`1RhD7dw_h)JXHM#Ub&DBqx3+dJrp3p3YmdFN@Tdf$Yap1*sX4TrbGd zf3V}3?(a;#+PX}%tpgWk;zWlpFpDAX-5?Be7tlb#3*lQXT@`47-|hl4E3X=S+{{h6 z`k-wAk`gEH?RZs#*X&cpa}{dieu65hvI$EnT=8`G9oXZ{0{0*J&sPt{?x=2jHZl_( z2TZ=Y?w)0UcyDJXBDu1CluvWN*7Zq){D~i@0BQ>3mv&lfO^H*+xOe4_T{hdR&u+*y z{~T%4V1s?)4gdTH>UBVhKfU>$H)LL77}1SMW^2JuA16pBu5dv@tbpnrw#I&YFEM7e zi@wYNI6ivn#Y+82^uy$@2rcYQ?6zl}v^bxe8s+mE#A=d(8mEpY;^cVy5#8UN z2*D5npk_oey>Ahq*dv^1|MHO1VftX&`=ZvL{WPyhSKVm5XKv`?FuvD2_2BZ3%u1YE zs}5*5DQwINf6_^&hRV^Lcwvxgku#r{9QBeI1j65pEd!~apu$Q;dGk@mrbO!RK;TXo zc#?6V_RABzXPvNdIS6B&C;4H?ow29xmHUbMRKoJl)-%|zl)nh$DB^$P&_d7aO^fb| zaH6zUm5ui{CK6#5EIxNWn(XUii=1nkkq)Cj@;oPcx1gAmV|xFAS`5cx|Noq@Uf+B_ z)$Aj;$-9YJr#q)$$+^pfQnR8v@E&JY$wVbe*&jM0?I#fH)o@@Fd#tN9d~PXD7onJE zjmyPI84I_Fxw$T5c?g^8yNZ-L^4w*leWOXQ{z~i#5OZDu!;O>H{2P)4awf`1!T9q zz(0u#JckhRZybE=gr6|DlT@Pt;2(el42t%jx>^CBY@@;s9IiT2d`HS+cMZRE(6n>z ztq7eeP7fLIMNZHV=38Q<_Hlk~KJL+X-c*_9TtFPjE!m85n61oFG8FFQr<<|@CV4?J zOs5hKm|21+wIWE<#AQ3VQ{rb4y*tU%{U{IY1b-@48mI9|%HT@6Kmbl!|Cz=}c?sb9 z=JMpwkyPlNs@u(1Q!0Jf&*R z8$2g&2VR<>ikrtn;xtpb;D4Hg=0&5NPsrECp)UAEENIZ(bVP*5LQfR_j7+S1HGK&e zD!@g@F?Ea?RqmsVHAltT-wDmL_f+c@_(#1kV#lpm)<Xe?^T;(6#h8P%WsxFyEKDa(4ii^*Aj!6f*{WbbiPH=2&I2In{`_?6I zPo>Z_`ko{}=K=bF{10TgU&iq`E7#g)PpR&_{Qs^y8{O?px>Iovre3MSL0uN!4A)-g z031<6yNy_aE)V>`#UZNOWBq~J^Bhb7d?kwRsh_P+m2sdu+#4nkELng?m?o#pYi+`! zF8C`p7AYPFhhB=FkP@(lkMG2+s@j2AWPXF&o8UC})BwywW>n;a*HPZdj2r-8u5J*0mh()AXROQ5(WhCI=isqv@+d zm}cmO1fhB+TlBsL$A&tMZH$bVhz3nnneO~=y-GbZtZZC23F5aV6pauERiM(6`6k&M z(}6f%iX}1mSg)d|BH~nwwKWxC=4u*jfP0F!8S}%Yox3P1R5Uf4Q2NxcPpeFSSW`^C z({!RW2PHur+L+XK0u_^T1th%hcXB#9vfM9zCAMrUFWda~b-MfDmq)|bHma3LgA`Ai z5f@dINc-A3ZyKbeuw!;wp0}Z!#WBC!?Z&`={wDtPz4ELZi2dmMj>EU3jrR11tY1NP zOxBvCrIJViz)57Ip#|Q5)xWnRX^lPUAs(q zYmTnI@Ml`YYm!d>&9b$|>SqaQyK%Xb8d{@vMZKCMIvT)g+&4I0k6oPT{#b+G+z;Yh zJ{Np+yG`8yNU-GCn#4L&T&v0FLryqhLt94N71-;l~CfJ9WlceG|U#^AsKs&(Isge!5qd2`9Hogj}ZBq-j- zGMLTnW$hi~vhppms$9U#O$caxu?~L9sGgGt)Q1r-LepIQ5#`sdLlTccb$!uthYVw$+zu-l)N}jk9en{ zOxb_+Ge2H0lpztoFUVm!S7}H#iGC6w%C*IaGF?qnV(0E71!S)O8wN*bY<&%0%ye zyoH&m_uEk_17t-4FR~ZHq!jyqS$sZ66)E3R?(ZV-o_zWBFk#-ZwMnKY^A6>)d8{VS znS>kd)ObGjR{dyxla*1zPzO|5S!1HEvUQw&me6r$KEYAvnif+MNYL9JcJQfXWPd3b1^<1aVHUA^j7 z-z^3j5|`AlZZ+m6@MAKkz&^h6G+NuKXZg9Mf4Q(Bu#Brh_PqC~;SeKNj4x!<5%2yz z0adXT#;@ULIAUq?9Gh;JOSHOZuoF3TOaf1?1QQfT`u{=-vd=M^w-hIcA@5I01p^Eu z*a%p9dwe)mCIbrbRIJAbSCTi%?ifMpkHU!^jLS?LYkL=uqT2q*B|O~(?N`Vko|@KR zgcqY3i%7vHLNDa1!ztD{%M^-2=7xe-8Pdy48A#rRIL)bNi9~k;rpN!0*l_jHUfzf>L20p)N$tVJhGNM zl*;cKxVXy3QxO)WaGA*v{WWKC*e5cr?a`NJfCFRBt4xteOd3GZ>VT@4)T!!?T>nk$ z)+uw9y2l{IiU$bklPCb9=|%B12-B9v!zmGgXMGxaxjB(9ZPem2n`vG5^)}ojy7f#^ z>pbN(9e3v%fcBFLfQZntwR88AQKx;P#K9dCbt~HXmZl47IQ{heXpCc~^O_U{xGd!h3vYT38%Kn_+!ueBB7JhfRMk#WI%|mfX*j&6v;lnfO>Llw%?zZzD;%&3aM9=X3I4W zb{5{6GO$)~k3YMF1N-XLwV=yO>dIVoMb!->-``8>Nm{5uC5nygRvZE@ZnRW2t z^R@woz+LT`?VkZj7*3-$A5TM^$il>(y2SSB$&EQiWt3hc`F@(2Zf~9MtHz}*cwh+H zPB}^9k%T7*i4}e2m>K(?;gX1W{`Dn(;m7rHu$pA-OG?3~_gY)(cwn{~Q#fSmP9q8r z4i9xmdRV&3#+~=A=?LU27t#(_DJN))f|Btj_w!Y&v=yU;igmLq062O<5OIi?}m|C zjv^C%TfC5$lz^s3*la02c|`{P(t`}6 z7*!OON>l&Si3XVo+H3W$`t{VrYqWB4d`_e$ge$B3&kN zbxCF*<7RgloV8wLARmdP(z(A7!d}C`@Q|U5p(A~EH0S4{+MHz9-vd5YjLsm!h!J_= z8&!TIg9(WFs$OXM2!@v}*ZJQBqK|mwZoNwE2yP+OnLaz;MQsc5?Gh10sL$#$<2>FO z6Fd}J=Qr^mNg7j0OrhmWNxW49YXsZ~0$MtJ+zXoIzd%GTJl6O`DSE?ZhLv;++tCYJ z=he!?_knE6C`PD2)`vZM$%8wAl8ONvDWMl&5&LCE;Ds+c)_`RQj@_z3-rQinTDr3*yGq6(E?-#1; zIzae`_i)nfjt5B-hd8BfG(9${KeCGt4JYEoDO~Vxh{I18maPd%ZK6ZY0ArEvGwr(B zG*;slGe>FlsZ;hlW@j~6xwj@PlfB8&+$U}jTis6@cVhtV_$uzOUkD|Ip!s@o*TXrj($gyU1=m&G8^;^Mx+k2TI0I{S*-e1W+J zxdgS~WzWcYvnnhZPxN_3M*Ev?jx;X@oWac>oo*F*;_rV5B~sNyxgQ(Q-o2aSwL+Uz zFeJzV3BX>H)6z2py>?Y_l!WZ2FfeJJjjUkLPgwf672hvbg3;YuE$e%_TEFEluC~(P`#!H!Q@Q~2a)7bSQK!fK zk2Qy}J6=Wn z$r{04kLac@0EnU(R9o^v!|Pq5EK%w$Bj)Tssg^)W%EFr9UpGIFG6cWTY-w~&Z6!QS z02ONjZ?5J?y3n$Sq$rCxB?+DWsRKR-VoBqLQmsuf)~qQ`^X(7IP$zXZx7&lQPJ7%D zkdg1Z8``HA_9oR(cbAn`$cDwirIQuIl5Xc9ci%I*+4%+NmohiG6ufU;BA$?fv;6%I z!iyi)EAmxTXimS z*1|ID2)x8IOj?W|V6N#-}JHeKSo7;0rY;f6LeWD4PmQ-*?RlOJBaT4eDKFtUNS`UIT1_EW=1aha3c~>C?`9AO}17p9NAs}kWzkW^7%Oz z^Eb0VT|Zcd(o8Y;b<>Pf>o=v>K_=py~g# zJ?u}+x%E2Y$g>yZ5B6Wuq0S86{94FfHU(xdg;G?c+aGnlG!fi7qMMywZ7>An%7}Ac zxha0CHWKGd8#}u;o2?%K-OZy}j(?VP`hx|#B)JjfwUk(w8;dgDnVQr#e>;L`t7pH8 z`e8a-HM1pzL!b^irycW#>-hzz3>)p=*S~r?ziKk%BA(K`z`A?&IFLzrW4Gq>{DrTf z)txXUoO>%cCO92*e|lng|14m`whBIZ<1-{F!;{0Xntsh07I31NMbf=pUw9(ZII!(< zzki{+*xjsN>#wsIuzC2%Z%w5|hf1d5KC*;tkA>5oC;|4&zZ0@>J;oKm}#rtVw8t#J@YrIr8-6UpPF0gZZm?J3gf?b{q1arw<| zg6_RnE}#XH`p>PNXc0nuMJCHHXv01B#Rg=Q_>7QVFmp@DUx|hDtI?Z)J7G`pBcBlk zW=_lxB{=>rL0p~{UB`>ZS4XEnyF8_SUi(k_g)}WtMVDTtu+MbBg3DFG&6m^vKw6D$ zQJsl!?aRDbWRa#*>l>$unTg?dwcWemO79Pce4@Bo?V2zFqD3r*$r>iQ6$ zfGcAH9&ld|nYzew2CjIjswx;5}RT_~-F8&8ySs;X@7& z1utj?{|-Hw>;h>#V1xYh{%j2&_HT02<+*mC;9n;V5~l7g&W|~Ki75K0;2+CvOc*V{ zU)kob`J|g7x{zxb=s;E0c9(|usqyViI(!T$!h0NIszwWXE*|!sdBrJcUX;WuyTrHk z$76dkMRK*Ao@o)lY&${fMbXsJrZFF*W_~3A=cY_ZFS24HCP*>}B-!4j&$210 zn2YmXjCmL%MwVfs(1zSVz2-S1+}kyqfB_}I)zVItxX|d_WzSRUOcfvb*H_)sKz86* zZ|}${!%c_}Jo#7CtWZ3|pMOGU42^|}hCs0!%Sg6RbeNm`GrNgUWhnyhct8*0H)6s4 zyt^7%N7?yAB4q1yrFii_Q1KJ+78)QX0YwIcAN`ZSeE8#o)vO*PJ_4Pzk(xg<_dX38>-DE;2tQm)2_edBK4IPe zZWUi9WsgZb(?KJ#_HFe=xykc-TB}#_$S(eWBWoi%V!H1dTD0YsDd0XENcJ0`E}GKa zB8GLS4%3q#;$kW1=B#z6S-M9w;D$>n!PUpDXEzq|#GvC_fek*sGIngp!Up;yiQG<`(8l#g3)%6M&G}A5i>yKJD(8hhlv&HVFdLrxqoywtl9+z_g@0jQB z{7PM78!G@Wn>~%?ZJM-f>4eiNgZPe`B z+{b4v3#~O*!w;p0_q;AnR_4CouXOkq6=NL$TDtz~X8>R2SmBTC3@rOv@I}QT?w#&} z!e`g1E;^zo4GK4t8|Xs|4|KCGaQ%QJHn%!#XdXgKZ_?%chg|n??wTs#v#nAAegfY` zb2HaofGz?kAIH7>N{_NE*>bPEw+}_F0*dwQQ`T>V`fS3zhB6Xd(icy5Rrhxq#5}VJ z^=|?;(n@pjDFBy;!RcDS0#x~AIbrc3JEA@a0OcEUTY2YdsC*$px?hy(bM^(;wrJ`2 zf}^6wq2n|{54jF??>yOGEod1f_?7gv>TW(*sH83Eh6!!LGn26nd+gEz;hBy$S<{@< zxke*_nMq(N)ftXgX{`fa&~2)0XN>7CvmM?ES~J=LFmR%hdc3fynUJ}5)AvlUr7zd_?;Se09N@QE{>Vx&Kf(`mDJi6Vsw>VEx^YUDX->cX2+ z#y0C;3&ZcKS#rxCKCW>PO>gj_O^s>wo+Me`)=LJII6xl!H8~iL`9==SPvk3+c9!5* zJTlC~=4FyY{n7eY4P|9`_VEgm?aWIh5HJ(-$TCxff%jw;>UKDO=LlgJ4LbX~Ab|qT zc)iDy(%1wE7I;#%S-qTi9R?!{4lt7-V~hWgu$F+J24&+8|3t{f?vCkbeQQOM(wP}O zF@z7i=>I6VD_7V%#YFk=f&~s*qj6b5 z5*f4z(2woryTtYIg@B(u!iajd@?wVuvGN7Bq%pPnTG^uD1t zhh^h2Q@3W$IAWeazbl|4&~u?|uZkO-u~_deX(vq^79;)>eBU-j>7AE;r3(Ml z(z*2b9Qws;0gdIA{!z_AMPx@-uQ&J83zmpsW4d!q-b zER8%%tDn`dzRd8|mMXUD7NedM0*`3^^`E$=JwK~4kUM(@Xj$>;iv#6BFSO9Hq|Aix zFFk@CBz+cp%G(S#e*Is#Df3e_1!Mt(Q9qZKE*QkDg-kT`<2R|icaXeWMuSh>#`GrF zW&5#|hJ_&Mt||LXIcTw)qURJduONvBmS7xpf?q)2kBnL2)pf7`yM9KFWN7}A+fl{wXMPJz1<n&5J&z+OV929KVWJ4}9$SDhcPQeK4u9f-h6UjHHk-(9UEZwOLr^Kqq{_KW#) z9(=i*E{FQ|R@HNVj1;u-zOj>$w#RzPfu!6pY)oaPM7Ns3)B}FjW^GIq@IC4Qh@RwW zMY7O|0=N;M={HIY+znXaRLzmKrtXL%#M$E&%Z~|#wFJOogSnuJg7=y`cL?Ck)N#_E z87~od9&5R~i1HlDETE=7S3py?4wEBLVoadW370ypjE2`~BBdN3SO|;6tjv}eUUPuN zWW9qN&29U0AydH!jDs|(y_p$g6{IFfUOh`5QHlxkk7HX#J2^>yzGg}3Dshrev-uLuE0F8 z)N<|&9{3AXR9HMb8V{!1dK^p~T8PvHYdkHsT^*I{Do&W^Qzai&s>lNwMk*I2o5;h| z(v5BfA^Fl8$Wl`{Ny(y^RjL4895D_+fh7q?=rUr`rjijitG!;%g*i*hq`unRCh&$` z6=YK@K;paTkrWEK$R0Up5kHUMd?;P~zzBb2A6Rf;4+z6*ONnEQV?A(79`PhbIf_|N zAJ6x^ROwq2g3o+vj!i)r{w|a8pQS`N`&nWz5IJJVkGmD73#ZjCtou-E^{py$fMhM&$eOk)?Y+8+7E1Z8S z+ffm+43o?d0C0$hy#u%EauO@l(VsZ_dt_uGg(cWz%#AYGgx(dRR?kS3oxK(;!B?F0 zP3-$KWz{LMp^W19>a6mJBszH3w&qs{EJs-w@dA=nxNyJ|DL(akbo8UYK{imH@RhCU zoHy{=3Or9q@`f7_y5Hx7-YUfTU$MT~vLK);vy=;xO0tbI%eX4`aO#PA61%Yuv|jV` z*?8%IdN3q|a`?-vcy*bU25}|0Pzs~tF9g1*H}<0=XM8LpFu0sDoq+fGLmr&!iz?2R zNrDhYQQwj~N+DVm@$J)bAj;a7doVVI(cTjS$(DOd2TRP@`Cd4<2vP^I7WVSrP1yVJseCis44s`tHqb1nOwk9 zkMiiuNE1})@8vfeE~Y>>UhJ{dHG+OTeHy92fjvU&poPDLsZsyZ-FgPlBt!%N;}&~aajX3AU4U?q&~WZ; z?ph3U;s>qm0o+6B9PGGE!~w9PGG6w`GB`L*WILaACCH6Bf(~_5I>Y8FRpMMm)ElF# z&SD5p{wZVWa>ZwTj}oBdH<3pSCbVABBn1uaU{=10g{kSxrQvl9%R(`bv>+p;0KKWd z-=~glWjsmau)ZKzGv{*Cw+2IGgq>ycKyTy)=QOvwB%(FFW*i{}O3hXqn!97e1?j~@ zjNiLP#hAda!0n$I#dq?QtC?_kQLn=y`4oFHGUp0I9Ecs*)&g`uakp}d6kCxRae(@5 zBuhG%t+6J+IFqtX!#_XJxiyXf&vgG}nmG36kBbkn=LJA(+Zu%3E}6@_?_Q3|N`#6b=`f%M z!EJQ1(Q;ZbD>rt?7_%p+P%QWyIP(DsxGzk2jPcQady1r*Id_ve!)nWtUUj>o~GK5 zgEK~LB(%wA)7M!CKTheEbaYBR7MjfG4}IA~Vg= zW{Kg{@?s@mzO05}%2y^XgYljGMftT?uO?K2pfF`4(1DHV!V%vxm<=dNKlj8;I18 za<<=ti=L;3#Mtb_O1P1-uD>J%OunB$mk^~?HX`z)VSIB_kIfm=IU)IRbl(8{D(XTawr?{ zo%Odmkdmt@jMJGA4g~@y>GYd$gT@GnM5p*k*yUq#kF`HMQzVS1Upri{s?VnRl;c~% z(Gt?kP3Jt?|IeWVg_m^GrkEw9?#8d2tvWYBp^;$+rE?*WNnS%h1-*GIG~yW^>NarU zlN?ts6{movsF1Bb)v;Cq70ZC0j)1I|KA0zxu&mK^mq`oEZE7sEG_Do)zJ;YeTVngn z^Cx(8p`jQ~totKA$x-+PD8IRSj^h&Qxwm#2nO_eA47{mNtS+EP@Ui@v<3mUo}utjC9Wm|kQP;x#>Fu+L9P zoA74Ju&gBB@#rk;7q|U7St6;sFq&i=Ht%izvHWqhwSh@Yq&@A=a<*4^V!i5h6gMGIfbUKd#PO_+gA?TzM%fOccGzOrsaD&+uc zCMw_hxVPh(fiLr)ch_*g2{7E{-#CVzr$gr>ZXG8d@oO+$V&qv?L`Us$h$ve%ocvFY zY#cW9{GtN-kRxHc|J8G=CRq99i9B#r_tif&yo#H-mvv(;`$P4eVijoG8QVBMoTSvw zscr^g3!3|{Dk(a; z3<4CO*VYJMSXY{HQ#%`|z(v}Jf6f%miY zNbO1)6nocg6|kZPQCC^h+h!z7)VD*_%lnllvxk9&yY>Q0P0Bt4NY?F;))dCUATey~ zxsIgQXlEq{;Nh>Xr{0qi94ll#*MA!?6`TCM%s=w+ch-x8NB$d=O)c^Pw)h4XLe`0n zEX%s@e|4=t4#glw{Fv{a0Qu8*zIJ!7J=^R#D330RB6Po-+zf76RPllDj{a6N%ThuM z%YAxQpSB8Z2xjPO9P4e5gHBVOjN*AEikOxBn2kgt~4znzbRlVCuOG|7o#A6NYYaB8Gz( zAC!S1aM9S`>A!r+m>MY>S1J)@laM`Y9j0uINZ{`~n>-K27A5u%X^@vdFYP?-dTbBc zi@ywm+yYjO3SOKp*&&QFJdy1PTVdvTpC=j53ya=s`VTZ-atx%w&sVP`0Gp74WfrzL zI{;X-Dy&t-GyO(tw6!U*QZdeoCwOu9uJ-Fuc4rY1lmIoTRR&9wDuWI9@AUj9bPPMQ zAWM556g(jg%<_BP;=kHrOf<-iyqPOT9d1~AA6xvas6$K3O)N*%JpoVWI#A6t`S^tR z)L~;a!oG~1U)!`{MO}jdpiLNZS(DrZ_oSA2mFe|w&m|1cS6EivaC77^E*LO0o_V+x zS=_M0ZSfGeVz?B1;H?GCa8<3)MhJYfz&q10tlE&5<>zA5)+-;zaDS|oJF;$)5$aV@Ygf$4a3cka=%2^rh`r5A*g6u4 z@w~`qDTW=;{Qfp`;8YdM7>K~p);a>fAbIo116)WPw?fJ*2@1#bQaCgJ3 z>UqahaSGF_7ky&nF7wm+_3Yrmvuz-@an^cMQS{GJPI5)+x~4DRf3y*LFKEZ5@Zi(* z0q|$qy}8foPPfWX@CL5${36f8=0r`RWfwm9f}bPL2|YRo+bKcvo)ZEScMk3T=Ubq8 z{#naJY-KqLiV-K`{vy|G?mq8X<80xNee5slnX;)ivqPfTNG^zZH=8^J zvU14)c&Qb96Wn$vnvD{@MY%0;-oV@G@43X4Pv$q%eSLI@1dKM@K<0S7Em+=Hy*l+N z@98KAmQ3;!;Gmf0{zGNG>Qa-JlfdoGr-FE?r-K2u8EFXJo7L2rBT;Z9kQ-|=T@f@+ zwokU`8a17U6mHRkckqD^QmR{1n0W<7jkadg?__u4>9bI6?@fKh2P+Tn2BGWfmqN%} zIp|$e_7k34IVl!&I=z1Pw%9GrRD6#ls!O%stCCK>Wh%G;%d{JJ}##qsqw2hqR&L|MBAR2Nzj!EuJN$x7N<`S>I&cj>O zN5GxHd}dFjccP?{?#g~{=LVr3^9H%*N;*d3iuvtjZk2JUt(R0vUYpT9oBTKZUT(==+Jr|!IHRBb!*fv%-eUwIfr;aj7#Yx^ zT#jun2t@08HzBi1mpCNY_qMQibY~$K-EN7oIjSxxpSYSQ*(t8Y+-Fs#&-eY8>zYTe zkcC?EW`Qw+M4EWPqugbGp=9YD?2sDzQFtolkil^T)h6s0Vh0?);mVj?zxO;u{GfSa z#?M%v-**+MP=G}Ksr5MFR~ykDjbnL)ZYsC=CmWcX|85czT~ojO^aSqS4~2aqVSUb) z6FfJL<>-+u;(ftSp~>EAWLi-sw-v?!BbfSI>C$QnP!ry|H$Cb1KI2yWI&uJ}JpB00 zA$5pxn;N&^U1V!M!AI|LjAJ&@>h9n%GWwU%Ul#kES)^kG5W~VAxtPpLt@s!8NGcI- z#XB!(qGFGNls%fXdK8l4AL4pZyyDD#>kI-$Us$M2fmk{V%dVZDpWiVMfEmv6ajvqG z&olj#=|bxhd+mOJi>0b%IeG7Z0}ZIHoa$(5p&WzMU9(H80=OuIs!X?Fd=_ z+CG<^r)}XM#-YDtz9)M`{X13t%0>VBHF|gAtHnYfB+jYdd{>PD1K)CsAo7!2Hg=k5 z=pvq3;P|vL?|Y_Uqs^ic4-KEg6j@uEkN}+mhk9nDTHlc+#?>Utb5K|xwybx7C_X7k z8jBB2oy({O%g;`X1nEQ@`IhXvju|AKG!K>r)koej0N7vNz1@uqrDR}?%z4tZw1}YG z0`}0PQ6d-t_ZiX>%$X03%f%2*FJ$b0*(LZFYR&ONo3uhtjoohh^Y1Mn%uh-5ux7ys z+De~{)VjikLZ+sz*eN3xoMNWw`}==Mu#IC3>nJ5t32jDNH6$LxqFl+?K2-f^af<2C z`NouV4SHB(0;jYrUhB$H-WPF{)jy02m^KyBJ;9Ytj5_h#Q;zeWmJsOll=&z2k}fe9J2=5E_*j2g7+n|= z6TrKXpxRf132>UJ0q!7o5)i=jdq-;o5hb3Qz|~*;e1LC3QwtV-b5;cr)POn7F68;( zDA=3Rp(k?cn$79t1ZiE>zkltI68S`sagLy@k%?E39JqNxPvvEV0+@CVFF(_Ad=wfh zdkT*J^ek{G9aR3ngU-AqBTeAp;tuj!x9;YFRsI!85B;IyTu3MgB?al(;kC&v$6We+ zNF+Qb!4^L$&gVD&y_I;~q7jwH>1)_u)I_IK^$=$P+1|4kO0&I%{bfXM11|Ja& zaR9RGr|0;OD6S3XnVeA|D0qLk!RaRbNtSsMEplEh0e$HhepdD2fA| zGS&H5r!~_I_tO3~bx?4S(7vWE+Q_#RpSaIk8N%`1=jmPeojRs6y&OEWkGFq}pa0%m z3x=MB^5du^17Y_1^V@N(;S)S==6mfzPKvA_Nk(@rku~rNTxuLTm&h=~mDqN%ny&08 zGsv`tLiFXmjR}QTxgPp<<{eyjsGWyU?5WLL_loEGm44g^Vm)ER2kRVaXPY;BQlzbo zeMhp&*2{MT3`WHDC5j{iL@aH$BOqyb3lR$wd`bXcU&5P+c-E>YjY?u~Dzd;0mc<)* zh~O>lP6ivfa+a;uA(Ho3Jl3Zd$d%*O1ek_RV2T%ff` z6S*eLgijt~)(mcJ-xSl7g*P(Q-*|N*eL$8N>di)YFU5TRxVesC%YkCjj@8$bh7Z0$ zGMVi+oqu{HA}IgxP|k6)5v~Z99)9FX#fs=>?-DDKbuR5)g+M7rG^TW!8~bpeZ6LKs z>BS7#W+54uZ>Y2{%;hpSkRG?GY02@Uuv%|3iMkTtEr}QZ%y7&FOH_TgH)(68mNk)$ z^QY*Y!?$a`eZOBWnex<@5J^EZ%x&bRAT>+$q=@6;IYC-UXCd%D>c20}jTE?z@;A%_ zu@|Q-l;#F6xfSgYM-hoTcn6x9+lDht?y4cmSc1?_V<2TL6XI24Uy|w9-B1Lyfb3;p zNa&nVCSe;7dds%T{@VtUf!vwF?haKUR`mOz62GK#&nG>quhd^=e=4(%^x#k63mV>j zdL%oF2mPuI1)GXHPGzL^DS7b|BARf-J^(viDEAtv!3z#V5H#YFc7swNW$)n9Fis%e z_{BZ;C7ZlpXQ4gBDd5 z#902#5GRD`tVkCl@ODRB4juC=7h$g7TZwbPoT?=B2{!3KM~o%n4BjY3^hd#9vev+e7;)2^$z;>$_aN`f5e)=c zfcsmTi)bd#b1G*-QZW20Y%JmnN-h4K`<=LBNXCRTGsLzda7^d4mMB5|RKFu0f-St1& z%u#>)GIrYlT`sH)xgV#6fMT|0$0e#gdQvN!VkW%KRNA~X$G)W6{wNC^zbY?Tf8Hh# zey@Z-^rqLnO9%8Ieq*yKFk?p=j%mAQ-zT}l7Z>E^<88>1v0qqLscWsr8@ zAn<=1HA_~Zvpl+?djD+H67sXPqjAc9axgB5ai(m{)V+RihVBT;*Wr)1G-XS{b+*I#3_3#qQ^y(0b2j3Np(yte&Pclj8wtLsAffwS zMdN%q-mErF2R3--K-?v59>~|?PDblZtPlU6K$$CeQw3%7sasxMaQ~}?WsurTd)h;p zD9`5!o%OYTW~9q%^@xgdNYU*OdL7R5DDAbX=a|HC_kIIibfXR?t{$71DrzPXasOO&>|HO(s zZ;j-qt*x~>Gs}Z2&p@o-zAep}D;MD8LQk2a8CZlThzrx1d4(cAVQYa%Grr|@3$@9L z`tp|ftk9CrKTYCd0}6g*75#ldaXptMWXe~9l-4{(^OK1n1+|T?)&zV0MEgpkDl&l; zuT!VhLqn3a5CMoiE6J0dVSOs=0}CrsmG8VH6hJoxS6w%8u7F^H!d!gkrALr_J9%2L zah2m!GGK*|eig%IvwyspvUj$!bA&kH(lXLSXMHK~i6s#klz%v0kEx&YcNRoy(!SL$<#?2^}sJy&#|C1N137 z$B~gIhpa8&g3*a`HvJh=ze)<=rj^t>5rB~s_TVE9>P7}9}P zHbL<}j?TibssHW68#THlC1ps1j1Z6-(%p@Kf~0gKjr16efRsujAPpiNqZ?_Yk!~3I zea`Rs5BA#5&N-j^e!s8lsB)b!Y4ym(ocPsts}4sp%^!}>_}}pb$F(qIunc}y{Kl&% zb1nbJy_1LL@QL-5CJ1=m)IM#k|M~5iva`&BCSM&_MVdZ5ucMC6-=SNMuM$jHOZ6R6Jd0Z<`JPsoN-`ozlhJHIPw}JH}j)* z9@>5>b}hWsxGUx8#$vjX(|wCa z(~M~81o-Pm5_s%5S$h1ro{kJ5aNF8cEQ%6_$ zd$Ot^Vti9Tgn4#4uO{lAQhI~EBVJ`ubyh+~@+$oYrXn{EC|kMP1^N;@pIMz`3ew_%z9Rl z7{C1b!<>h-WJr7m^XztZjEP!$wfJwXW>?&eP=!^WLE8tXNSJ1x+NB9P_>sU0XyXF4 zc&fP-^ouV4?$__ISz+|fA2{}~gTMiAAIgK+?iEfM`ie`@$kix!xPWIq$$r!t^*zPn z)q8Y(36Y2#I^4#_DngkJ^*Cf9^KW70OVvE@<7fApo(-;{Y_doBU@{BhV0)%mMvOme zGZ!ROZ#sE2@KZliJ^*?4PH^yQ+0z}=A-2?$d$}2j5rs)+W*_FyYb`*z{Ec0KqA|rQ z`tb3|@&8Q%F_c;+K2MWb03^pw<$Fw*5J~~OMQAR6VDbmuJHKknD|X;@Nu@KzvS~OFZY9yO+eor{m!sjB^-wBpdmPhFBw_D) zm1RAGn}oEo@IT9W(PJ(+^SpcU80!VV9G@kA6_LfJztjPEtj`%JMHH&m+iqOzm@vqO30^>$wBuVrXQ zH$s6%x!-@F@Vb9rdcEx?PWVU}CHHRusY;mt>t_#nLi`j~2T+LAkVU9D{S+e;rST`Y z>6i}elJf564r5`-!%G)8e9e^>pUG$CdR18Jy|MLVTUN`!JqFZfjXW3e%Tn!~9MCL*r!5 z45j<4A1GU!B?NpIDD0W=gZ_^Cm8wNkz@$B`ty*>EY=LzJl1O1nB^%QJPadRnU1Z2d z>~AH^s=*-YtQnM1Vif@k@zqY|SP*dnZ3RCC{k-N*l=a-h7T#Pv{IFB04!=56@=kWu ztayVp;Q z%v}C+*Y6V6Gp0&s`QSyS2mgus#zcDOEd_ay>{CDWl%zvVdBco=-#ZewddH5UktDqiCaBz7WHr=IUWy?=jk`2A8_qK>ceyS>8aGV33T)^l3 z1UEQi9tAlMa75`_sQ5^Hae&)TE9^w@kmDVJ4M#~<>+PgCl0EB0y#-8!i~O&f_WKmo z^gdJ#0{y&Lzh5$E;j`Jcu?mTY0FaFEN1-y%ok)q0(mC?9 zoEdueKY*&Qi2LeWGja&l)WzltfrteSKS);O0iSn-X!%ouZ%dp3Aa#&emQ{gkUjYa% zCc0k7cy5P3NDS_vRG7nq^3i+%d=1v1mqv$&*_RYxA>AVnAkU;0>-}$gAk|4~#)OlS z^|_2$N~BQ9!KZ4_DH13S1kPl?dv;C?vDnpT*f_`O9{o7ENBx6^>9@4nj4y+cb5c`2 zLHOIQ!vRUZ5;n5B0Uo=n zK)3)HF+Nnv)bi>=XvkAQ1G5rWV!d*S)orK=mGaL%NwGnFzs@HgkLo$xhZA4k@Z59+ zR<`LaEZj5kxg+3oOc=jNfV_`15lrye z#M}-8<`yGSn=5JmEGN6RpCgz4C+MeC7s zO~ZofUrD%wGU!oGAWpvH_fLBG_g(2_eNl^9i0-bjy>_0 zsq*t~M?8V~Qgr|IB9AOtcAlmRDCxUiT$pm72A4KP%~~1>lwuwV#skXwUoKueH$?3bpB|?`q2o;xWD=ovdj>@(+;6 zhG9-ofVuj>FslANuf0$T{}z?kN~Zm%d*K=f`Y!Nk~r;=Px1 z@hqSQ5)hA!q)%gt@{is2{_ws=lB=iuNgqyNOj*P`1CBY~+-cAxqUXhO|NX9&zCH__ zcq7jeu&WOV)CP38a@O=dED;Mf{t1EJsqEPJGPag$bQv*_y>xBW@cWS(L#r_FF~(B& zgGz|bKqhG}3pDdS-Vz+lHzR*M!{_~E;IgzJyUtw4nNOPQ>r*^FkxW-b8X%1!J8BPg z77Xnd*4Tcp3^p2F7iG37Lb?`1vgx11RzP7XqV(h(7}of6=Q1dR>+7;tVSUeeF|8T1 zr%%cc#cag(@DBBz^FMnZ^F-)&_JUZ-e!RW*V&I(kME059O)W+x0oE7juvK8s@r~)#9J3-|DT>hj76nnP8(N zlmY@M@Nzf$eeEw1+)*FMeJM`gZxhoYAM27kDXa)V+~aqE;U(`CzutqJ)=C+Q3>z%A zs+TlSBTyvUb*nGF540VZvw`!vY*GK)*3nmu%(I5YbuM+_Zej(oNIa>A4y#SX|HpRy=pqRXKn8SpZ_QdE3J&VPu;b-sg|B2a*L!V?UD8Y=WSLL)#@f7+qJ4_WeFs?_R0FjV{ij*N#x(DL_gFRM}n-vXmb<47@ z<%fTbLDhqdlLPzZ60+U&0Et%zJs_ZlIX8{P^cr&uulD@xPn z@YRLq(EI^R$qC<$pke5RnpV52Y(OzWSdr2qJ0Egd8#X9~e**^FL`^#PVrJyhjIWQ( zUBjs9v4`wHbwfF!4`w|mQ2I_7y?9vuVV9GYl#U@jFl9}gF2_POl3RSTa$qJR$o+BH zTp~gCl){_Z?<@{sxZ8Mu`nYC6wVQqtY*+lHk&p)1|0|q8VomIw&F7jGu$~}OhjKs? zYAK6vLk4bVr~LD}T3_-CN#^w9v1|_PISvG|`M%p%V|-J`{7jS(2n20=>&lZ_@afah zfjz>Aycuch@_G!(j2E8`{aiJ8lhC!_QmXUlmq{&&yP9=np_`fp5 z3flN&r0!0R8dlynh^NCnfB)h;uBB1febdI}b=j?R8f6`KhZckecp^1c-Pibr}74pJF#4 zK@!A$9=`r3)iaNLB+ z^=bs;i*x>MBq0UNk5)>lu3OsS!*+ZGANNq_DC}1@tjK!hFKFl-Jm%}0~D)O z?tpm~@HuhClA-TaMF~2{(QM?Q}d{~1s0(lIq>yw=A)^+PYe9vsimGG0fuU}j- zq8&Z3<13b;^>NMIfLUKyu;uaG@^9&n?;<-9#=0#|LA3!-P9Eb|B?Tt?bdsFneaM4y zN-*c@T5vBGS?gu4^_-=O@&RpxP%z%V*{4^{zKN!$a@J{c7a;2g$5eFaolJl@I?!(R zRa;HCLpl^v7~~3^!+{jrYSGAg4x>v{5UB0UsethLdv{erQjesS5YfMAt{3+dU-Z$< zm1g&XCw$-DPB<0XUG?o;7ra-cN3OR^U8**}DE8ZQ8bz`0WKY$PxI3AjneJ8+h&PL& zJdDX#`sqKox{3kiGFn%C!=fcu*oas(KLu~|9f?Ybjiqe(qL|RWSeDPIa;GTfpAg3A zL6tgVtP_9zIM>k@z18bmJxwl`vpLsR5A~0qwCkHj`Ry=#EUC9J!D#8pggONyfv+^H zmXAdx%G|Ud-402~J$*wau@ANgMu3+@OF1_{M~@U#NfshzfbV?0C|+C;Cqy{2B-^o~ zlC4%5HG!pY2ovR?*x-E+(-#Rnon%=h`)V03Yq@S@J~DOntNV}81P?f=@{?EYG=$zl zNo)fk`qP!-q(8!<`m9LNk}Q2^lT<(7qCmVvrT{xUoO!fV0N z3$_VD1c90wO~%k1fkI8q$@UCMCcWPiUK~|UHk_=^v__1Vw?L^BE8?Mgs@DW72k(|y+uWhNl>|N<(Ts%b|FUx3iYXfQ z7z51YW!cu2v%ThEH1&GChj#436z~l51}k*`X?F}>{Um*&vFy{;2CYMvuaEGqS&NVV z`p5`ab&enrdHLA;k>*1dah5(|k|mC&(o( z@#AJ6Z>!1~*Rinb!jW~o?R5c^sUC19+P%CJ)!@k4`4}gRuyzhEvFm-a7f9*V-NM*a$kDJ=cL(zhnvK>EgP}{S(u5R1{TkbquT0zF+DgRKGm8RCEvSYYzOl`l36StbcOPoW9Q6 zx$x@%pqT_fZ)`!m(&Uev_nJSc{jsV|Q10=9{TUz(Nyn?}HAoomJ?8315)#vV{l-Q) zkUzG?NvQYKdKBr%p^ycSA%J{9G2R5zq zC#%zZ{9gS?YUIb6P%ITy7?V%Qu~s#Czmk^Bzj_IdZvrx6+G9X+kHN}mP!Ku2^_G+1 zr>*2Jv0n1(#|iog+wJ{D3J`)eoZ+`^hy&+y1iS}fRiW-`{Ed~++LJP_YLDq{HT&>_ z$~c7jl*EXKHI}^t5_=x=JXtwTNpMWKeuKek_?M+=*vCISx)^ipV#jdu%-1FJyGrf+ zxEg+izSpFrZpixQKh#(|E{_44Gj>e6mp(0R<+b9}vK2msC3vdUeTAaN-iV)OU?=v1 z;pr?H046iP0Q1Hpw*j`Z7v;Bf$3*ycQGJB5EP~Lp+*Ou|7YR#&Q!q~3IuO>Iom?f} zMpn@iP(P1iDe$FCZK7e|u0%_&p^xi(lTvevp|PM_!7JE_S&Hw%1Y1Icm#FZa^qsg7 z0Ta$#7qnvzc4N5t_h8u(kPq*~9XR*EF;*#sZwKzA_bePw(!QWN<^-hiL6`qbhvL0c z64t+MI993vs`S!^&UBW$P@2u{7%*)>b|42P)%g~k(Glt-_i|@N`ULT7IHZ@93&)Rg zS8$=!+lC$ycr=q#YK#?Muz-sKWr1!|u2N1(PYk=ar>uY|z!F~70Lj8#U#U-tnZl^T znUOz@@-y(^rP6T0UGRwy8u5v7?DFohnT97p6ISF!AMp0T| zeuXCeNjs|{ADONEsHX{I=8*i~J~!iL$O@7@^|D0t9W0j!I{JDuSwWJsLf{uezE>|u zxCj7OT20S5B4AK&kAB)x=VysYY51^(uTGV?&Sj#&nPsfi6L%ntgw>$2J7aw1vyN#l zDrvIDi)Lsm24ybq6d({CwhtPV{kO%qtfK$e#J z1TFfDO}5PA*mOQmxN&GYI)ueh(MUaV2J&s zi&jJ>#FD$8<*7b!kqeF$68+?yn{&P&$2Q%;W7|#&8I!mwUtwxgE}*4hJ_{`8JG>vt z<`c4#oD)sLjz*cN*mBrNPxR0{mzbsGg zL+WjU|0$XTw*HFXZdQU+=i`^vxXe$@m$35bij@|BBF7(y#QAb%@J#{ARw#b}TJL?1>@Fhf!h<5&Vp`aYpU-UX4b zSv$0Q)p?6dT_s|}`|aL$Dd#N9P=Hy6W-{n6q*6-=GZ(t;5A2J*UzTEBbRMc@s?gV3 zHWoX8as(w)@~alx72bsy|0bOk$1W*u8en^9jCr`4NCGzA0lOsUb`e z`VnS)s_wyQlG$CKdTy9hKmxsOZ>K7xL;rCIW?bV)?*0Bc69zykMQbh7#3Tob)VW`k;a=V5nc#=`SX1s_ z6ytp2BVoPD$F1Iq?;-Tz9kpi|=!|v(?I14&dzdn*b2kbV;t~r=7C12E`KqaGM%R)h zIg=ujuKIfeMaR}&6J^q_<`R*sk@Hk6808CeB`{bn0KOjaeb^E}NWED3pDgICYHO zx5p(rdlOmrQ-!V3ka>eKhfAraT53z}gkQ1*!-)5H5pS;MNvx+^iy#hILHZSP&+nTV z3RSWn8(4YW={>3lX<~vFo2?BUvUI?jK zW+pAp+P<=uD`GKWG8@}xOi*FgA12bgb5*rkSZ}Rzd_a&&hnDzEt>9<6Jzq=-r7(jsDN-7-Tq1>iC! z4BNH6D>(1fBuhfAF5)+S>bNPw6h|b%!+;$)A)z{9hDq$_z(@FjKi9Ob5zWD@HKYzq(RTIsM zt$)wpc=s|A+QxZxcB9&59j+xgVQa%m$oNnKE<_MrM`}tSQ%4@1Equ&B>6l4vuOR4v z@@pfp0wqmVqXWoKlUL$V2{W5yN7>ekfFTyWQ{^9fQ^bGcmMb2v{qIDsk*W2a%!X7d zc*10WDJ78@J{std)7RTXOjo+)(7*W9GCM?cMDLf=VY?lK9vI$)MR&s4fqY!6jGN~! z+jy)}@uGPi2adU+q(jb4viIN#i5X*22=DH!%+fP0h*)8JnrevIp=3x|gU$e`QyY1& zmvWrWuOtZoJJ?~>Oq?BipyKD%6!UPHkg z2EpXR`y<@ZqB6XnI(Lf+wn;!xDrLpYHOJF^ITBL!N`q38qgs|5cr z_?oKK>4+h<4)-VXoPXejiVn+jI@^Sx&k;66R0b6~yC)VA-f~J}7(K?uRJew?pNY9vmFdhKs!Jmpy zW4}J^pxIXwpv4if_0e%?88rID+i|Q-mqv~~O5L1~#|NFu7q}iXi4{|=oEAlyuq9c* z9@eIWpGs5*{CI$1PKMyw#KL8zXgo{WCKw;1BuB-k1*;)G; z4$Lh|dXJcX^2h(-E@9JQt&+H<8<~Y_zc#_Ml3cW`dS+JHkFUQY?G~eB=+BSg)ZY@F znCZPS(*6iz2)iBk>XNsu8}Um<`cFr?iej?*IaMPQi0qw~Qj4BpN`6YHYVx{akVCNCyj5PmK&L`k@ z#A8!PXjJnoVQY+eK4g^}mhNW_$2if{RTKD$T|*NJ-~r&;L8}Yhh^Mw0P|JVCnCL(U zka4Hthw%Pw1eO^k=)ofk#P)?xL@^YRr59g7yL{XfD|0sywx%EovMGpVOAy@<#nQsr z=~n(T*2@ojWW%gdxof|&J>{Gl=K4(MPq^I%nc(|AbxBhRf%vj#-JV~$oC>$6x$sOn zFNXl=tzAgiZ!hefaI2c+^BsLAL1O!?m8`7cq`GRJensK}!_0f3c6C`9EGeTR9HUvo zwKrZ{(l%K(!|LZ&P5H!s<1d<}6-7`_J(HuBX{=XqJw$Hd7iD z=m5E8YoB_oYviml5StD-OL@N5v!wvfpm)}*qV7qGB(F++W1|JHtMew?tkEdoO_ud! zCz6kGN~tNq;dV7|%YyE4@$ZQi!+RHJp>l>dpK0H;oIh}{^O|m~v}~xuzwhyF&80++ za$sJnx3B)teLklf5bDtZ^1LsfYkLBWS~Tv-*5zV(->oz6&{}pdZCS)TaWtuD91$ME zftG&IbGx@XC5bwgdue#w>`!_DexNdaoVFkiF#aylkae%7via<7%B|rD6RpJCZ|DvE zoV1PS#y=s#H=j>}uYR9K<_Wo)JGf)fKwgY;FYo}}MDbRYb@7tQIi3(_R=^T=?I+Y? z>_OgFK&}j_w_dRanjS~`LoYt811&o20F6L%;V=ar&49=Hx!phQE?*9@L&w~KvY@AgNiy#ptaf$JZK~+NrCVvyd-snI0MKiN9U35I47;%-4BfmDsS7Zy? zio%>MOp$A-ZLrG>YuYPrbucOzzhA}pxT)u#{Nqy_KM4Z|W?nMpy~nA@RbgVi?D^sSe*eYa z`M)}+chpbS5Jt8~n@oMJ+~(u#vl5Dw2!xR`zZS*SNKkT6|KA#mPo4=;CSDJZ2^8nb z&I~L1qjj(?u&ouDELo9!O0Kdm029Pa-EJ=C}HsPpzN z#3j@E_#DC+VRx#JbGh7q_==}K8zhFNiG4V|F&va)JAMB*`o+rnp3YWA%C9Ql^Bw`m zSHn|E8pgFvjV3!L?0dw43cyWF2O!R&Xfapv^$10FlDofF(D0I3Jx>ht2vxJAG<*yG zUzWzeb(5Z(6v8en`J3?bro0tsSsx_^L z#7&I9d;;#TvTEM1G`;WhqY+|_rTD4ctbluUnU8B#JLl0Tsi3M~VjTkqg`=3(w3N@| z4-@hwrW6H;P)Sn>K<$mLFjB#u-in@7Pryr~LOP4H}Ev~FE8v0f3ezk}tX)ciR_0d8_HolzB#KqX3!a4fK1It^R z0_4hTjjhc)E$qO!Eu#F;Jx%{ud-{znQNZ2UH9PobIRBRZqU3#JQi?m`yw47k?~0|} z%in9D%J3mUO2p!x1>IP*cXf?SqD`{~x9$&Dz0-@^!n(~iaH^R86?ov|+Qz`dB@YT# zYp*5gZDEQD!mOTgvNb$^W+4dq+9{Q`mv&PQjJ(_*@@-C~!`_}8UjEs&QnSoH16NI& z(k0ZJ{6P18)Pg)Y4PFh7c;vP_+x6f6Lchy#SJ}MaOG_&?bNZrB6U}nn^_R|J%yZ!b z*N@&dYjgAlQ1zXFGvxyR(BRb=3+&%`<+5cKyGd%NQr@_;kg7ZVD^xdAcpC-U_Iq!E z-77PLQ#t<9ryH~5ce8KhK@>WI*mN1I_-E}vTdiAtIdw?CJe; zYm0aJX^)*LDSWKVEl%mKT7f?HqsZgL?CMf@VzTwlRAG=?&^<|VJ-KsP9}fZ>-^}I0Z~Du3w<>a z?W+yHVvnEdk*#_!h(2(ibL*eJtS`|R6P`-e9QHBr>Z$E7P=(q828i~{7ieD1o|sC! z#%5;c0|-;0p(dJ_y62?RY)?Y7u7u9189|`Gpr9VBih<2B#{1geK^t0sJr+KR- zD~7%kS~};G?0#HhKlD5KxPA{4i3(76+E(rAd%u}0-PfwX3C$8tXCwR}P~by(-wB9% zOWU3Yu>JWqT^H}ahNXjn(eDdP_V*3vyay&;#TfP_}7kYfv2$n=~rWni!yaZ^XDdoeDDS`+K4v9A(lT7l8MWPavWFS}%Wh zvTdM}ePgzJQ93%0UQaH;BbU6IjOmSBT-N%PK>fU zge1TCS4fj5v>8ZRl|rWV|9yX^YR%-IFo00P$Zh3%&k<_q{qYIVqhw{YBIDDP zN{w+$)~(*{Rhl9-VOAa!Lj7W;!gpJw0Q2^|qYV%YQf^0p_cN`uRecg5`G z-@XtQB_lTf*xI+Y+baCcJ6XZ=qX*8r|F|t)Pi3A$WwW!jZ~!!6-6oQ>RjJqO4=iIM z5T&UyFmZ^%aRcjEj-6{HH2SdH2Sg{H8Vvf_N{UKcmeY0Rl;AEZ_li8STUpooJDa9XN2u8GzG# ziv3UznCffvNU1_zX?|)a@`|f?J!n*6!LfgC^|fk>Y5w^2uL(c|?cz!Ui+9(YY-$hx z4^(rM^3^W=?C%`L{mYjZ58NyFl577Cn3W8K@nb<4AulUf^c&8MtgU{2Jt8XguPmr`~p~1 zA}d4z$}YMAWI;#;F`GhQui?#|hZ;Wc!d8EL#Z;DKEGq^Ma4mds-Hd4Ukh8jH({vHSGfA*ADQ3XPci4q1mEGLTCOl+cSpyy`Ex#; ziEC5#SkQ%SVjUMgIp~0!?|hWU8)21OU+BXXZN;2~3~^hi-N|`ltRVn-?U#>lV~@Yu zhJT4QP2!4w-;vE|e{}q8KQ#Bjo-M((Pnuo}TdbI8OJ5A7rst8VTiTD3(M_Z3IYwy^ z`<1xxLFdmNb4oB0NrYG78ve;%eS@T<2b_( z0rl8^3@BN(WZ}4-#1{}+1_vj^Pxqj&@p7*H+Fx?#0p;oI5%Q6_Fj3l~p;skcmF{A! zx=YMj?xMRWw(^?VCn2~O`Jftsx4(9fcClLG526Je0xz@a&qtKf_giS#CI4YSywC5u zx*ns>h}@UIf6$Bg#hn&y^ur%`Q;vrBz@z2Ks46 z_4e5SLj-T@FrvkphM`t}OFZOlv%9a*Kh}2|blk|Ol6(SQ5m89)MUN(|TOjH&qwuXo%X|NGe zjai|W&Xkc#!_d0-FXtslNy7VBTm7@yMj9}E;KuDL8)(NuVzUk&e7F4P$5@B#7+zGI zq9EZXpWi^%fg-8#LW<|6*6XE|be0%1gy}|j{M_9oVLA&eb{LuuCDMKE_sPeAUdX9u|aE68n(1iF3dP0q8# z6vTA=u1XHqksSKp=s$W3ztv}r&r}fHdo_;HKUC|c;W1F^6!Tmk)(9Z1s-QK*J^t_V zTqI%_i6>Ih@(E^DYb5tNY}>>QJ|y3Sgsg7d%$$mR0V}+NL)a<5i0XR-GUp5-uy8@s z-J-v%I=O<#QN|{aybe=Gy1IoLR9G8l3yMJE3&z1uf2f%bcRbchh}rhUVrZ+@NBk>UDdvm1N_a&v(6Y**7AIVIDZs3G1O{Jk~90gWy zh7yeAL2@l0#^1cEJm2J5rNk}^e-Y5RF|LcTQ>yGKzqWxTWY~mIDDyb`uO(RNK2_lX7YBKM?bck6TtNrVQ7SD4}MR z3P`v4eV?Ayv{ylv439X&&v|Ab*Hcpk5s!4s0xQ#aVq%40gJ8S^48SWjC*|lp43nNu ze0ri~6+!p}q4y+GVU8a*wgD$+P2oyPCMh}8YPM#kBs98o$el5V)AMQiCtv-wnWVsY z1#th_ydw>?#BFlFTfRt?O!X-_-)bYZ%v0fGi_qdoDcuCaNktFtYR5*@>sgJca|ZI-p??CWf+i}o8EYpi zZ0PtU)lm8fn_<*ME~hM!=^iG2btBz$#Re%Dhy+-h6zZv^MhyR_mcG9?> zj*uf~vh3_i2)nT&UFc4`hxTyGtaywhvG{a;z*n@yCB1E@V(atSaxNv**K`q5pSN#(^BS9Au$N8MGe zSe#&d5FeYhdW3)WRKUM^d~$bt7b)ML)D19wwfL=zj>~*37v93IoB~Ey|0$d2ktdpJ znA)GU78A6m{q_D4R33Q#gLUQ;mN#wQDQsaOfWq!-Ns(XX?C!5t9h?xYEUpzw` zVmm~a`NV_spg241C`ct|EsvU}Xy;DWr#Ck*_sE*1d$s&3SR~E=O}0&ihT!e1 z;YZA;q^u+rylH|I%jg!?X?*R;_UX?jJd~$QY}PQ0pHW!|<~7drHA{5VxaHr2i_(bU z)aWxR!kFna;T#z8J(-E6Gy}&PkuDjW<}mdZg_x_Plw8e1WxLMK_-a&u7S{M1B~pg@ z&W)8Ha*vMNEbf8gGrsFaXT3ELHT~!eW}b2c5R1M);5?VP@f*>}I+NiP$K^fLY2k)# zB8b!I3-~CFN-)`hduqJU+>$j!f^1jLor#|efeflA7$tC$LrHpQ#xyn=Ti7uG34C&8 zsCcq;RK3DkE&|~DK@E@!@5L;tR2;Wzc4z=^2+PAA;gzJiX+wm9)H_9uG@>R~1T9$H zx3nS~#YVG{zaGMt3?tPkW-N-{9HO>i&vjGgj%1DKK*@|h{dA<8x~Dk;yh{pARZC=B z0)%8(k&gr!Vn=F*w1YP3S8i06JS(|G+jn5Q0fRVuob8B?NWNE6N<5(p*T+p2H8WrM#=0^F&Vf{dbgdNx9UoEz;& zhbr7eB;wVi2^(ri1oLZwy;g(j36T^wg3)5@5RSb_cqZ1T*ed&kx*M|*(&(RM_f+eH7Ct)^5hx}ui*0|?T)nq`~`}GOmVejqP@~L)RZw;0&!xu?A z@Vd>NOnk`3MX8+9#5zwXVrQ~kZ865HpV>p#IC&^O6R;E}E@q^ul6++^Ow!MbcDmy#$dBsQ+K*q#v1j??~9+Jz}*A+oGdc61{V0=Nq3 zuA;2)GG#Ivf^+&EVU%wy-6DhGaH{S0;X+GQ#Oy1tKdD96AhJ%$2-|zp>M5QA zqN1D*#1V=DOdWnnyNRE_;kLVke;JI0&J9lfqf8TVmp>ckD{V@;^1)sclFL04fEmc} zr`o0F_3!}*AQlB`pD5~noF@|rA<_C6d&}M3;66Xk`I;t?fOMI=R|*^b(swO(=b(oZ zR8D3-Uu?8T1-2%BS-lBVN6a6&g6SdVX0kO)(49}Yoj(&o^0 z)KE6lT5q)%2AKxUwn+x69Bnn`WyS}E2hE=Uo%eM-NUG+5vfEb;NiP^0G&TLPR(M!QH7}2`?mtjSJ5ya1g=1_` zj}4xy%qHjYvBd;?XK?fi9Xe-K^~Dpkl`e8`VV(KkX@f7I05|;~`AuoKq;NR|5t40b!E|P2WI5fj_i+y;|A9V8 zQwFHbI#a0|ypEKeR2h0G{SV~mLVmA%iaqUE))Y}7DqhwtDi@S+H!fC%%u)itLrWX)e3b8t6Rp~2Ab-ULD+ znAnIA(18P9jt~7MB-GHV))=}xiVN_0E50f#T)l|s!b{eGDI)`};5{2o3#d)1^7Wr*E;^aEFBVeyIs89 z>KM%%6(I#h+f0tFWAwey;~IMwz!;u&_hrqeuL^u`Itz*6GcFgi^`xy@^2eXvm(Bew?S-1LQn)`)QIVCNU*_~D z?PAX@67o*8j_2tNPLTC}r6%@0EY;7#Tmj9s|1Tk5c8RO9^Uqv82o5o}x_iySH@iN^ z6xFHBNyffecCpFu<5&=a9QmDgBi5J!Bc$TMx74cEo_Y&XOthr*|%Isbw;lgWe6L&AR` zYjMq}Uy==9%NN4M`Xe9kGYu2dfq?xjyqDj_4qayD}2-o&py8cx0RPMkNb_{~AV zff))XHU9UfA$=c1f&cqtq3^daeoDUsH{BW4T>>`!=w5(_v!+FlEM_Sm@HAzo#VoR~ zVl&+`C#g`tgn~Ahy+%NinLmd$VEYyfz&1`ExV7Zlk^hScp!{Sk>RcRq`yD04QGZey z?oqa)LJ5t|8U8rCX?suMv4OfO`s!OAnBBa14t%Fl%nwCv%&O}oWJ?OQ$v(+`Rb=VG z7m=VuaeA+cDh9{ey{E%dHxZ%iSzXbYe%6xmAStoG-c#fLo<&OS>=_!0g(}r=V`w&h zezVpCIne+S425^SDn}BzK=6*de-1pGG^ZbBw4gweGG?ZO4NG)OLoomaLIM6#lCBicI_Tc^`_JF*C?wmGf8-{zKBAob zZV&{Ul1gh`<+zp;WP~jNs{19gH<=R#06=ma6&Z-4*iIA;IY<-XRn*14+mGfhs(InJ`Y z+ysF_at+^NRbIu_cG83m5r}Hik`jLhdazUaNTXaZ>=z=xNSS`+(Ixj>MXByHIt*i2 z9@fr}9?Z~~gL#EGC(^R&^{2P)g{J|7ukwS-5fKD`PDCrjtW!bcjWX%bG0cnKxxkC;mMP7m znwFWUFdUp`aZP0|qPj8Tn)H)g1cx(O$p@PP;sQMbc(BG8`*rGR5Ra8*6)6?yrEQj; zSiL5Xo+aihIFLuj059n3ufdrLcDhYA>I^}g^4%sZLR*O6 zl8=d8%bBYuMfM9WoP%t^T>>=675NPiGG+9Xyd?h=b+so-Q%_oC;BlnbUfwDJ=fQf< zskZe$gf2;489X#kH+gLmDOr6RTpL+>O&u>SOF8lKpdeu~JMQN=tF1Wt3 zPpNIIi7Fgz^UewdPRaVmi5c?=YBpMXCqw8!{USc9Y=Itl`O9eTNZC;=EmA<=!L}F6 zJup`-iTGP$UQ+gjW-IE$`u3e(4|{6VANbMBV#n5Gt=8^opESn|a>mW%8e2bfyi5+sRO#`7H+CFVZD@&B{K?jHX zY`wx%;>wppuV19SkpASfP3{cXs9^juhPLLCN}eexkOIq#*}^=o!cX z&=#c%cn{#dYDO!`efTd&$hkgOjMLEPu7hFbPXq1i$E@v?Q%HKxXi?ap>}Fmw2bRjy zU&2$BD>RO^+aCJ{5di`IpP>_=%h#?t(zZW+K-jR_brwIPl6(w9Gj9w{4EL0z#b(^& z5>S!=XHAp1m+6SSQtq54XWA&JD+`0iQazq^A~qAbS}VtEnznbKZR~{GenXWV9^&-W z>^<-Z-k>eWQJ1lO8v>NMY@O#*CdHR9O6gz`WUK6G1$MtTDDB$C*YC%PZKXbNkGm}dDf%i*VZk}P0&nU*k`L_nEE zPn9H@Je9lInGHIWF;mMxl2zM|r2l)gkH8W7=y?BC>BMGCF+egAMG~=CcCM5g)V7zT zGi;jO00HG}MS26^R`Ry2Ug@MY+k5*5|7Qjl;0(i9-mYdSe*8B<4am&m`1rOf1SYYl zgQU+H_!?*3oeo?KR`Dlef3WR_8~EmtzEz(?(0*cx>qs$cYUh3DF-V(c$C}84lOusS z(r)vMi5?eTZUU&)iiTkk>FZlf&yy$61Xrc&i>$cXjD%%^Xmciy5zX{0C@$s>K`1}B^?$E}?3{5JodTY5K%JS-~sF{c3c!;7-YqDI% zYAM#ps-o168R>Lf_%`;F`#oSw6vx?`?q|rly#P`CZ>zy zxhcTs04&pVYEge$y3)3Vni}7rc%!7UjcxkpF_QrTm%|2_`B5;&&X7Y6OyVStRy~vJ zW-6{EE;CG1#k?7Z)h~UM81Y&#Od>$?>Or@{9U-5%^difoy@pN{1@_k0CAOYzHABCP~|Cm^LtVs+mtd8n~c^uk{_$4gcC(};)- zHws%v<&`Lw+#onU8>CS#0xPhocXp;^a@hE6Wv}X->RK7Ht(#CDw~}ufw@SdV>YY>? ziO1wtr|^5?jP{w*m~p!L0-5VEDNVHSlkDjGUyxG@h)!P0&$Z9~^&&{z9;Vc7Lw0{1 zXf~O%UsyN~2?YKM$r`pKZkVM%E|~D@-EY%{JR*}*uen$=XXNU{NXl9ThSQu5!ogGk zUi3yBTeNi$N#OLGL<-tylglwNC3}~1s>hNg|Jl6hBvZi$pUfl!Kv`QqE8LQw=`s4_ z;Hz|1j9%SV2}@Sk6DNxiJ+oIO!<~^$rtRzzQ^)Np5U3x?q<`$uvmY^s zq-2+iA4?2O(nFN65>XIt7Wn4^+#Ehkja#fbluCj>L4ZX%&mzWqXk04fAaVJfj@0&F z1EXm&af-FgqGXd5Tc1IE@Hfr=Us1O}@K67{S?}3m^n*AOmA}1JB%~TW+SlG`EHfkh z2IUr7=)jZ;xtjQ0az^YHMdL z4C$8#1`hC2_thbnHDId0dCZTc%uBElzz9^^*U+;iTtm z(=ysuXmOD{D~Z=v_elFDcb(CpM@Q)lfMU^k^@ot&u>_01C-oPTa6Lk6sO7@n-h14L zyHqTVc+jw_^$Na(fqoK_a+o>Erzn^!}|6OhyZ=VdBB{bb+Iqi_(ZOvTg zk%K9vjm+5$$^qDW78v!DmWFW~+#c<*e&?hEb*2O(nn}x+>%j=x9AFs_L=D#9dY?eBXdLJF#6C89Y^(M4%dt?-8*AF2cF%y(h?dUK z-S<8GBD3{3>W&kS{+p~;3W*0o+TOCOW3^ww-%BOuqmNhQnM3iXz@o*le3`<{~G{2TbF>w07^CUaR!?mcq|@utqgBtnzVQn8(@umvP>Gb)@cE z;x;S*Z0n5bkS>Dup~6Dsx48)mtOebjjm{1?iw?w z{{1)qu4^V91_^)hYU_&Lz9q#&uhmufbqXiSo~>s;m-)+bxZo(sJr^V{?6%@<+>uwVhbthjkcw zX{37qf&-a za5LXuFiEZe$EXI@6sr)YRc1Xo3(2U@dF4&E~v!R%)d@>y#aTBu>2qmTj) zFfVNUu*iI>H9_Go_UGVQbINR(BV$;(XAtae4sHA)Uv4VVGq`8yRz3S^Tk;aGU7J3b zbG`%aId`$BQrR|qBvH+7TGuvhW#1Zulmbfz1%nkT&GwtMdTN7E^NBaTeRzL&y1a%q zziBf#x6D(CI7VV;6KxKB3<>ds4!8$B0mdFZcxApQ(xh!~IC^;xR2^Cpj@*0HF{>?4 zbx^YQ#w6@4Aq5)WlMnGl+x-o*(2CzU{T?6~v2T{89cA5uBjj6U;;o1vs)6o<$mo)V z0NvXl<+@r40T3fr9GN;A_$;^Q($P6A=`CsuH;eg7VdJCbLubpvP3TqN{q$ z20PB|k+{OQP7e~JMRs__WEbN-?Tk-525d30_!6__0_fj7J^k-JwSV~XL{wZrujf|t z+dq#V2ro|gv`&v>-OBpyknHBkAlP>7XWh@=hNaHp&DVZeZ*)wxHkbjBkCt{%dt>o9 z%$rA~!frW=9xVYf z`tRk(>jbS-$hu{VTmRnaU_{}M-^aQp`4<4#r^|Py{HNvSQ$Wp4_$F6Ic3t<=%bJ!K z>tC50MOyr>yR^QVs=@;PT7MUO;JnFf>eMsM(fd6f2%d)qUkAAEEQG6$Ar9g;5O7Zc zUVF|$j5`ezq9`RHQ(1QmU>kdaB5|k@eSPeZ=*GY-_p&|!ZSqX8n^+e^%#fQJHVI}| zbTDHVW!N)*WtPKq9_=f7P=#tg0G>c|6lVh~fr5>PRsS`B{G@x#UJf&i>0&<>pzvVIS@8ojH^E*~zIVGpnUdGw%wE7bo#)j(@(W7`e z!ZTrUz)H4=25=zBRlXvTNUH=S$jw##6sH%vVxWM9p;$%)0kmWuL19=d4rTT>()p3n z)AYlos+VSt`aKhPu{c2=1qQbev?O{d?a;v{gH|pfRXS^FG^tY^6s9DB;VNBO9^x_~ z@mSHpbrEvh%I+H#Mu)e5CsDGG!Q2`8FL=BTZGO=W*kwbXtz;lIGC(O(N> zp=qz)Ml(Xe5y88x;e#&fPm$XfASS-8FyjMKaNMJ(^wX%}+GFhh-(gR@BU)z)DgRtN zrOI$Q*lFf8qS#a`+oY%6O30CYiVLtKR$R=#bmDS&h(y}18=QhQ3#6^A0b~4fCdbeT zPDQ{dTP5<@TIaqI>v`94&`dG)^@y#Y$QBmNPBITbGIOA;3k7#V%}L1IVO*RNFlbJA zVa$NRIw&jRIu-e(ka*q9W?(ba{lZmv+7J+i!P$H9>bqkptGy3C1Hgk7mma^ks`@mW z!MaeWpme2|#Up38q=Qn*%47R3l&KUDp3hGJ(;;b@y`_5%AX|3QqRcuc3s$WV#*97|{XO>=;-f(bwc0sp6nwY$t;Y5FiLA&DODX-Esr?s(J?wy>AtQiG5?#s z+~;6~HED-G%HS_itlBYb;ptECToL2N=Q_dh{uLbsiw~4;9PEJ*iqfI1!osYm`G1hbLd~?QKvTArS$J2~>#U3I?0yC4M`xec)zo zWjxc($Y!Ca5U1p?RGeO(UpemI_VV&Ejsc(_}V zyTsOvp>$!8!?^70MN#`T2UBrz)&!0pr9wNVivmhYQj@qUTk!=#f?!wgWj>bz>jcvv z(&>$1S`7JoezC>iPVn&}#Jyk+`Bd4RjPe6}abTGCT~NJ?E=Fdz!DSDQdA{tiN9#(> zfMk^bYd1_Ch@l~ar^n88_?a+*aWB;R^tK`8k(E{;WGQdO;~Xvbn+I!kK0AE@r-6Dr zh^Wl%q2t4PSTA)?*+e{gmR$a9)paqFAuxy!*8aunNq)c zh+sQkU+z|n@R9I(f`BmCm@s4Em*rNL**iKqPdiE3t6Xegz~Tn*gv0#plsA|cvVHQ1 zsU@A%c`=NNLWCyG7B>?j=bu@B=6wH8YF1mMGExj*hC~N8a)x_Y%K?S{r$MUx8zHCVR zHak7Sp<`$AwHFgPgJ|1^X6IDdo>1K|4C1D6ckgOn+2=ziYSsblGUc%uZsDYhT zI>9+UM~@(8j|PG}TRQOtjsAc3h# z^mnX?nNG-bSii%*5FaqUlB@QeBQk;tG6op5SSQ^~NQg0#? zFFCD|y~;k9ib!MsIaO1JD`|}<*{{>aZ_+Bmtc!T$Qk<-t{!8jfX8yBqF|D*$|9QbS zCXo^qN9Oj1(6o2I|C-%pyReN@6K zh*hcXz2e-Iwh;qU6Ve7vhNaI;k|wYd_Kno~euS4Lulko8dDSJ_`7_E@jOqY>6sqfF zmk??g%hF2NTz-e5<2a4r0~oXywwv+ZPSKGWwxz7}-$e4h>NC8iQ2j;f{PMy1;ezG4 zgs5hC#R=8+UTwa8ZjHf&qzL3){qe9zuAH7Cr60*&i&_ms>5l*u*xE$1A%sg=tTM>p zEdqg$h6`ZvNL-fYf7!XUvo3%`HVaZaK3=@3TNY9FGzk8ftUQLG-Y~fz%)a_ltexx` zk1@yA&CI}%yaPb5Do1ifTB0BZCrY*v!f>p^c%Ob*%GN4K<(n9^n=5jxx>S(9x34qQ zmi?tLo2n7=JR7BYLFTnog*c;lJaWw~GYh3GM2+fmGZ1-W>1-sa((S0`5xOqi_A5|d zco(X8g!gTuAbO1LF+T@w_O)VqpM(#}oFejw&>sR~QzYU0%QUj9ZGe@R5m7}QhgHt) zS3@2kgCw^-4#@Xr6ldGRpVWV9{m!A-d315bBrI$yriZYV1gy3td$i7t&GgV%O&e+` zd6cAR@FF>2$oY1`C7xLNC3(%lJB`_aFn=hJ((? z%DP(4)}HI)@UL62ybv(J)j0h%xEqxln))9lkP6C&Y*`1#+h;wut()0->6~E$N?={B z1ce-sCOJWq%&sC{?6H<@6SDFw0K|V9TwpzVM?DR?#@Q19*VOxe-HcB4!Yahi5GPrB z;;NrmHgk>|V@8pCplGvn$FH{$D0aU{iD)-=9%U}ji)ZPFvt!Xk)`W89}QY);zo z*S^zl9l!5$70hRPZ97UHD?G>^`9kTkQ(1e~`^}zEvyPQRl{*t(%k*~iiCRY(5k`QR zDYLRBI#f8EqIevU4)!MFQ_rI{u z)|l~~#f;^q=wz=oj06pJG?>IKEzK!(Mw2c5Qvh8Ww$u5qmevl^v4i6XtvmVr z)}P-~A58RqixmH4#MADsAm#J#?GbtOPqNBj=8~eKrf*?k$uItSLw@)xAQ~orr?1Vi zl*U1@_l>UpNl70`&dyNu;yh`=8;no?8I}abVyn}47n9lB>I;^TvI_r-f^i+099mHL zILVJX0OhBJWe^OJ_RRds{{Z?9Ig#fr%MT>iY787lZMuYPXB%W=X-=kc_gOX6TCoBh*As#QKy^BH&#|xWrQPEA?$~k z_UqoM%7NbqX(4T0{Q$vOLPh+BprDypm)Z>z%9(0O8VIC0u|EnYc#)QV8M;s{iOsQD z(|1q`k}~z9r9o>DnN7L|fV&8MD3JT$I{6Kw)faV;eH+K=h>v!Q7Re=vJbU z6`Tyi(xFZRRXafRIgJ?B7FaCL7+DhZT{g{PG#EE=JKM8K#%O#$Tm|rSgw$*4{)e4} zRxK^C&r-5hr;vKm&Y10rxAi{&i@j4!+B<#-9x?{#eOG?8>buT_@4Q!IejCN$eashR z(GjCuYxM`OZGSXnq>;Jvze#+B)APQSx6QiiV)j6&&s_nixE!`Qv&~Dy$NKK|!p?%iUwK2b5*0>>1a_W=E9sqdTdj})r?Ys|kz+^H6l?0G#tvDAC``Qj00-Sl3IdOZOSF6s5# z^Se#UkGY1k_Q}dC>gQevXx7!$T9yC2I7-WmFU8a|D(3Ny;-%!EjDe=l z_v?%anhlZ+I$c!Y4+cu=rWE1>aG_(}ZN(%#E|fd$#Z%lzZ`qxV^;eoDW#=w|skiv*P6+$mA3^%5cfxj3(okj>)_BrpFue<3sbnG>+O;<>>d=BO5Y~lrjMQf`+;Bz@S#=^bm`oG zlVs!L!x2c-Q1LSOzq>#~73GX>mx&@E1ail6|K|IR+g1fLh3Oh}iT9H`DGD`zX?XYK z-m>YY<FWlrPo-tbED@HCxu-8JmqInoq2&3`6z(fPX#{x#3CZz>stsR)3X)RG%xMVgQN)`~KeT6yFVFPzD5xSqvsihR~P zZO(3AppMc~*5X^wO?Yvt&HVVr-ZWndr{CZY>ddm^yoctn*|C>g!F)dUf%@h}zktY- z;slcXXtH1ZzfUvy zuQ4vo?99LC_qF4|@N8BnUtMawBgtCsx5K~2jFq5AN>=8LRrHJBgn~KY!h`!DZeL*| z0Ovz62id(}h3-v2s{!in%+lUGwEIDTOm5N~G$i#t&<4E(|J&F9;O{!0BNeV|MhqCs z1cKkZT@Sj;6eCc@*`|=1x7c_Q{;jKyEw>i4Fo0F_>TYji@1AO_?=haF+vSH|uk_cs zMIpSWA07zXH@@JqrWn`D_u?WGI4=L>k&nB9;mJC;*n9n;CxeA5*j9TZl9Km)$J&d% z4}^=4J~KT2dxcb}(_)l7I%4CDIt%jrx1$tY$)R8Wv{{(dNZ{dBjiS~8v> zSd+%!(CZfQmpjt?rc&gPCf){xr*FU8KdC zHzQjKAypZrd9(r#6V(cS%^nzlGn1#I=44KM;Cz+kf>OYUoDI%Irg*r2Gid2p-b>cW!>50 z6TFa~a%0%yt&(S;b>#}?$IHjqDMO6qqNH2`6+>HWNItD{<6R8!hxQ4JwO?~cPleY2 zQSu6fl%aKbD^Xt3f({Oq3eIO0&OmCFQ7%1f2Yd!1RsCc?NKW_%fxb}PZg8p7q8olU zd4YzA&fdt6HkGn?T~+HwTh`#yF8gZ+S0K7U$q6rVvVK@j9_r0KRbdhJ6kT}5RXTmB!iP9>XZ}enNttAtWk*77DTKR4Dv?7Em7YT6Am*DxNa}-++iRFa3Y8TqJn*kk zY}iW$jx9Gi-J({Tb0l0CLBpY!oGzD?^KW1M8?XuoD(t6+tQD{X2b`r#0Ubvy=q~xA z-ky`JWFaO5yG)2{io8|vxlm$SR;n7IgHF2T%UEH22}Vyyh{rA6!Hg!xLB?aIJkRt z>{U9xz8SX>P?>+uqZoYtRWdI_2UxGiFK`87$}L!Z-nNc*X7xyg*g}tzG}8^bp;!A$ zU+wM8({P>utvz4e^+x;7dPE?W zL%!0z6dpNguDFQA1W~ALtIP717Dt+xfftJpjTS2E?h^PY@4tq0Lrw|} zF0$dsr>}5>H@flHzC6txr-#GKJ3I0{*`X}g6@326BcKg~yAwd*yxXzc5!6G-S1@LS zP2XZQ(sYIh{L%?E<(4c_w~gg#Coq*3u=a+y9m-fvpCL2P%)@aSQbuJMr&Edi=iG-- z>A3+w?DX6ZmH2Q^aT}(ld}nqdzihxCD{m!SKBjejI{QdRfx=@6Np)^W=c5CMy%1Bi zCjQRid!&m&t@!*7C|#(9P+aaGA*eGMNJ<$cu(EdkJGQyd--yE6)e`(WH728m6C^pH z3CMX4$d*VlLW&1DVuxH>uTHdENs&K5Cl>R6Up1$nr*?w|k4fz6&lCC=WZ9c#j52K( zWU@^GF3Y&so`FQRm><@{1Ckt101GLAgW$u?pl-jDP^GgU1aoM5Ca@w?H!hu%_AVQ# z?#&nvaGe$eK+qmH`Yn$wMh=Gx&kcuQo?boIUwJgNcN(a)6%dq(D|vJi9%}_*rrRti z$Wo=ol+uHV)~ceSEB?|8U%?!cEFkzy2(^duEl>HDXzos4T9Ja6B=HWc$;~@B6kG}P z19QOjz;A4KDX=ET)|MlaP-6W_nd=4@41b=j(tNbG?3ovO20&wsgD3=~h@w|;r5nOf zsALz3(~yip+iDcj+!xSNeK_-y(Q^x@@QkyrL4j^LMwlGizx`#au>03<2lm3I#S z)~$fSwvNN$^mP)jtZj4lrCrNIlbrnRq7?$Wq{<@QWxaT<<7(e<)#`4s*S9B+)CH!z zRKnV}e`uC|1gj$u&-M)A%lc8szh+`haB^tz^lK|(jLZKJM3hkn@ZSrFl92@2uA+RP zMQy3kLi`amYL4yJ%PK=QQ%Kq(Yw?SS86)^u@6+xVd>+?|Z-?mYgoK&!e9?SQ{=gf= zlwGB*k;MCQ4T7~R$_o3Yr*#(y_URPk?U#>=*xfRGI4(@B^>=sL26Yki&GoFr>3ee} zI`+)(ziW6`R+#1jx54CrQ!QSPAlu-UOzLHiK!F5kaQ#A_p$+}bJLK8vXA832l8vl< zYZ$@i0fG(Bm6BI>qt0cuRAg}2=(GN~WP(9w93e>9bcxI)Ua%VnKQ`)L2y90A+9eI3 z927Y$rKR95J6g&g`3g(=%>yCElK< zc?1Q`>2Jc786r;hwFQTmo+z>8NHW64O5^E$*9b7OsUvNRv4+3BF#8A!f-Mq5vjc(w zO(BDX_-@;rff6L0iO5LOG*c7psB`5gV!0h40$7uAP+w1#B`4H;cLed{vB}LZMJ+x# zGnOU1N}la=q)lB%XXfFJP7Rp;WN|<{bEoaFPNtcAPrM2_94N&*R^2x6XjchqPE>w3 ziPK!)YJM_gGvGYhAZXc+xhi*JtJpEPTHj17PMgRBjp@}~{H<`vZCi1#gg$Bu-aO3+ z#Tq7lucm+#72LfNafqN!VNHzO`V}}ege;7huYvQHPQBwx$QzRs$N1*_iwEQ*ZK=70 zkFuK1kLV#1j2?4YY=XdV1l?uPw1|cgy=`3n%8w;c#ysX_j@Hcf_W}ke|H0UGFK7po!I3`2zpoAqM!k9ht_l7 ztEK)|G$YA!XGkAZlxXF{T~qX$%2j%6i%}Jfc$&&HV5CF6=XI zXWd6Z{Vd=%W*sYaYqM>l)%C>CZbl>$y9~S|HK}^aZ4qX?mG*JbFG~B`cr-=VO66#|h z0nDm`I2&u7)0bI73HEmOEgyxBzm|O%=PQE$pf^Kh+jmvpglrPjY*2NqFnvTY{SUYk z^G_F<(O2z?)lNpRjtfcFls8(CE6#wSE-_-0MHPDVTGOdt)K%MME`{08fkM`lw@jHe zO%M2oPpkbsnb#ts7_5<^)ep2cuJ=c|8uH|?r9ztuz6L*^{H^n}I`aux2l+#%w>krF zG+J};my**bsbSMT-NNqIprPVW2iNEae`O-U7VrmPdhyB;kB!v%25@7OwVmNM6- z>EP0wzsv7%Vk2EQ<^xW3&)8-~Rr1nKu`juhQUq1U>yfZ%DC5BUCoRR4PvQ?C_~}^R z66!kUqp1lf(E@zpCbi*nHcjr3q2D0h_J^&wC&5lgx2H)?Q$eYGF=L(!c7acKwVPIF zI`^}@BOQQcuJTptJO@Vx-!CO$1l_BsXs(M*ZpH;)X0`T0br?`d@A$wL_(1DA)f>{Q zQbL3e#I=y6b~$9W)B7`o8~~#?VH>4aCpatrshvh1<4Zzo#>khpx+#`luhv>Dn`~jz z)y%S%e5g-;6l)fk*!^d-i}PR815}-MbtP#j_h~F&)D{io_H&u!^hwT|VvoMMTg7dJ z1C)EG|J}Xisa=0`1#c_?tPd@1{6)E9%z-ERT{RiO7~oqa)=ygNkk?bpIgPpVTB~oY z@_8md$P3sIzw&^&+M|+^5=ua=1nq`$+O@-($X$gmT4*RIplr%<>kSJ) zIiZy^vuHPbY(L@2gVot)=a&7aq&~UwrPbcgCJA*{bI8nfKfE|<@Yp!*ZU$nc@@HrS zkoGcKPsQP8FJUW79w$K;;GB)A()>t+eH@pb#A$gEs#)pvM5@~3@BE?JzK6d;HyZ(<%K)|{boqfY zfXh8e#D86nHH|K`mUiUy4yUU^NY5@nCRe0ikGQc}EiD+Sp&SE3?cVnw9#~giI~xl; zcIm;e1RD1)p@c2hgm;>g{Y5WZjxsmDA8AvqL_86tVu>a7wYu&_9I0}AY%O@^p~|kr>>G%h(Hjf*EtVJ(fkO+0(tKK<*(Na{6*xV$m^n;2SW^TT`3!I8arhO+Z!HX=Y*O~K>NpE1j9>f< zj8+dp2>_c&*otb~*^~2-5MGwJcRTE^${e$?n*br5SN9OjcI(FxGG-{)0gQO6bze7F z&8vwDb;}sb3dq3VO=o9Cj`qY!Wgj0Qs46Lyd5l=XC1|ycZ1052p9ut12&=^p@9|9< zGHTw>TH^@`2_qP^+8>`lzh3V)Q1gW9c*HHv$(owD03mOAN}&s@;HR&0@4R|Skpl=| z>jEnp!nN*=zn!`byroxeqwMukg(aN=vzi{=la3k7sXHI+WP|aVo#& z!TxJ|%2c2AGrFoqx1oz=@$YW)+ld$URS0Kh5|PCSThXtS5mz+|d025gd06@B|Bb)9 zO+QdQR@77k9JDt=n7018WIHV6m49L;4}R|H#g$3aNi|klo?OuicNxA_$3URo%-r^BZS_& z$6Y{DvRrDe=xxbD)5;XjOPpp+bvTCjf`n}Qss{UCjjZfG6L1{|erIJc!Vu6y$8wQ0Rq#bfYi@uHyoVD6D|WhE zJz>PDApessENpVN{>)`*V!GM6VuX%mJLpaahbXy$YPf)rfM&?xDhacP4m7yy7|lM* z0YG}Yyw*lGS`a}@m18b+*1h}LqjRQ|kz6Ec2)Sq#;-Rayhx@63#1+3ZkK}On0?Nzs z=9^#jMUNJk5zOpa5_%ia25Vrk$E@&82D9VnnUtZt8lM1jU1-9EoANV_$`jc;CCz#ZXbN2sX%N zDd0lzi6lVKJ7M3lvFpQ^vUvB}+LW17QiSTxsXv_8#wYWSio^sKk}Jo58G0;i=*nqG zuYRr-n#TXjAU+OYj47pp*W;xegXo*AH3t?PN#dD5#pZ%SgxC%YGjTR7x3*q0WLG4k zz7*f%0rnLJ(4F*?vD|Y*fAqiuW#2G@<&mTOn)jF1S!?!tT0rf!ws0E5m1w@b4Iy}} z#kJ!o7~Pw%sj{HzKMxPQ+(mM?y5BCfVanYIJUabZJiD$$r@ue>%Z@>o~SR zx(-K+JAv=Gr`%;RXV(sCM+9np=G=lsV%#0X#)=VoX7EHVV8BKvZosl)m200S_%fSKL(m0gp>M0}2%G>SN5g%92Q z0iyOsD3J2^8oyJH57YW)K$#24N+~7j>8UL$rJ1@G5=gn05k(7Bj@_v>z$r=$R36EEmCP;B- zn6-5iCjl9U5Kl=3>~V3jG&;la(-pF|(h;C2YyeNLFh(ZIHg%ii48fFCY!=|bUy0|D z6+C@B^fO$_%H3J|ZNw7-OgDSjp{g(}n}>M|L9RYo3gHmnH?&*jFIMz4c!E~$%k=Gr zUuZfFUyy6IvLQK~Y9l?e|G-Hl)SqE}bARzsl(ua#lLMQ(v|pVcS-txX%fBB`yCy`z ze1}TY-3y{I+(lAcaW)M%$|ZrE&4^`ocD^+vwEUREJ)&kLCC+4dZ$~|Jpi7!FaVG{JpCtuBNRckrw6e~m zD0IN7okqhXoRzvOD~4if*EIgt#`@P*u$u-*B-DP1IXTkKRAB7hCYya)04swFA0BE8 zJX{ct2Z%sqb1*amRpXL4Qx=leSlfX~sx)t(e8Snj!b&P+jjPWFb7cVPze42R)11_k zoE6AP_ZUA5b~-$OX=ZuR21A$}Xr%-B^VPCgV#HypNOiL0ctRgjUdy!=Yg`Qs7OB>< zay~|a9T6qyE+;(-9l&tO$2y7Gw~> z1Bi{+tQw2zT$MFPSWn~eRG18{X z5o^6gsDCe%PE?=OmbW21aAx3KDQ2KD#2NRCX){w-Ca7ot@?h zIF|=6%Jo#aGaI?-_B`^i2n`E4qY)BJyI%q;xbRli&%Jcy-0OyF*B@x#DcRyF;#A9S z$)s!ca(IP}0m?Gc?!&OEA1ioL=-y7t z)bjqi1c`ESfq-ON$_Z!S0|%FC&xC?@mYp3*?<5i0q$6FYQc_|!KgSjaxxMZMo>;=| z=&z~#tf&GFNcr&lBKUdh%t;bHCxc2=(c&%zH9G_48n{vzE_ZL^xJa2QH<#uJGZi3b z*{#I1f0kB)9~7MfpFfhdf$Bg@@zC~41@~C4+Wt{>S}Kb z)Q|#v={kW%c1IXJ$hfxo6Tn+2ahYJ9si}-+Ba!(z41V~CHYvvc2EVOJB6k=iQiDQ4 z5RW#!xp!Y9%F<~1FPNHg|Ag6sBfsYTAGnyFgI3V@|$HOq@n&AsC|c0)9J_Bt6@CkxOeWhI_3h45~*Y z=^{YGb5O37S0xf~z}XJ&p818rbI04bo$=%$j4xoXaR$8g68)5v8Ohywr)l)m!F2~R zpnQbI5Jre|>1-o|YKL&_RR`+e6x*4{%s_IK0`F#w$=mr_IIg)nmFisK0oP?&fUGGn z@beX*Q?nD5h<3W+Juk+?=kQY9#nr59hpLn-1o}O2MLD+eHcs-_ZTnivMC!cU z_<#;>x_3;eFZ~A@4_$5d`i;c(8tFO}!d!Mb*Z;mSX09n937BC?2$BmZR?)wUY<=JR z^;(QfGt8mchmIeQ{LNItn%n;XBM2Lko`j88t$?be)!bmvxmxV`fw;oj~1{CnIEqpYGrs{bSDtOJ_*|F?ZcjYbfV!RXP5 zw2T}m-JQ}%2@=vZQb9TeVGgBJ8l(kD3F($b8l(mN{Lc4z{@DNHY@EGcuXEqm6@YF8 zaQ&>lb_g`F`?H)MTK>3|4OVxB5xhsBU-XfH>B!4A%9}2MKP{M4R@y_MzW8$#ALLxe@QX8--lbP{Ykxs~64b$YwwNl(fZ_a@At#lw*uY z*B${kuDZ^3!+QI3-{y|#B^-akY1!!0N4EGt;^wh zn3Pr2jbb+cHxfp_c1o)7b=&6*g6q6*rSAXyuR!JRrL@VPm7y>0SWh*NBZJ*sC9>@G zRB+=jsyjPi*Ksm->M=)LYg0bp{d#FnywsD3)OAFbZTHaAMq0|xUH^B=p=EIoardcG z_~pQYqEs!?BJAQ9?ixibhCWMs*0eAxiXSZI%b7*?q%~&vkxh|P_7QdMTB!zWTt9KE zGFP){)V%egX?NXubpKZ%DENBf;B{akbYtp-J1fn%e&b$=-@7hu3yg(T@x0`6E_Q~6 zp6+P|%tqcRKFYzS zQ_c+TOgA>Ki<2XC=Q;pcuJn4bCY$KHk4`t$zbW%7{ui3$!*tEPF~f)6c$<(4Uf>E8GTUnV*(9*6SIP3IU$o_Nzx(^m!4{c*(fGu76X)99_X8 z7%a}O)=K7+1*uoyIJ5{P!VPXeagF?2cf?V19ro%CNdAyRS7Ymk z3G*Xag)ko~ga6)o_C~I4O;sj`gsrln*20Apc5uA2ifA#4w-<|3j@$!r4sKG;vL0HE|y+NBCJ{ktPNP{I?dKNq$%zw6+n+e$sCzaajmi;URnJ>@VFV_*erB4d zcYpJj*0~>zcXn64*y(V?ne=VpS#x~yEH42FI|u_)Lp95TAJ#b27n{Y02q+lI0x$fp z4$NQt2xgdkeA)D@W&h6bKonfF7)^`0$tl$bEi3J^B|PBBLvNg7N$@k2Owcl#dhMqI zuZwHU+tsMqYcj(6z-4Yr*lL9=;WeL|_or(+F_ z7|M~JpSi3o6S^(N> za^a-0uvrm}My7w*xB3`X>vuoIOOEJ zm1=&IBH!f+`Y`=jW44gc{Qti=`rq>Cf3I*95^kXXCf8;ZwSTN{#1${CYO}U1ZoW95 z$)Py-Tmnljwc*$MOr(p6uB9{Qn*GgaceDNM=7+<BiT-~tK(~K z=0l$sSC7qnFjyQs2SekHo7t_$eMxU0{NtS|BJ=-7as__mTX#Y0u1Sx^sArcmB&}^1xJX$S~`C zOrJMeQ<<$+2=baep4dOS34L8$&&T%yD(xKyRAK8C{TltecXd7^4#~ZcEQT`?qVULb z8a+E=6^r|WFc1#H*GQm5AybMF;yth)*~Lt)!FknFwE}~tpG#RupN)aYvxW(ZdUntx ziD~#1N|xJiUDjq#dTQz8$p%ZWuHx%F!TdTfeBz;OgQ7QkD=mCJApMt5)*LO;A~Yty zQngZtl;Aq8xU!y?IR&}es>AH~zm&HOx3UeWbLkT$s1UXfwiyYWVR2MaN$uxY0#h3Gn%1H)$wSfdUUS`=fy=5# z+D)7X4`gm%eQh7DRWE<4}(K7K!=f0;fzQADqx zB%B_|G-8$R9lY@`fva5GqS46mhiT;9vkeA*zpp5p@A+e)-NHBFH5uPD92y)P!6seB zslb*^6VtmQhS$*wb$0O?SdzYVNILHJ{x|vi*z|#sanR5%Ai!9&mDn~}`E1lra5F6j z=oH<12bF0SGkZSvod|w@mH+n0h@65skG(dfUw3~WMPk?7GB8k1Mw}K2gY6q)y{gnO zk%&Lj-*VUrM}ut9Z1?&qYt}Cj^l>Ht$0vAX*N7H}YLgHQ8t2xn6X}vH1ol0(Oz7@C zxz~ICO_Tn$C%grZ99iO++vjg2vHwjLh67ZDUR44nU*Zo)vt{4O@Yd_5stNsxTqsJ^ zPbiEi_*&9PFQ_7@>sdx8={mARRo>~=<&Iy z!)xyL28`h8EE{NT7YvQ6xhvQH(|k63libKbHZ+T)#Ns5=Ik?;D6<40}DVb~Nonyxy z@TyFeIS6_VbYXGy=`?%q*ZY+8lt&AF1}+Bwx|k9=u(luqr`_J0`oXD|op9DFLa8^xGxF)#11SJRshQeZ<3{g%9#hMdsw|Hjwo3ya@6zj0juJS> zk=oPZR%@Gi*zWjg`Qt?Ci?|u~HvnSqGPxz06jjgIA|nXocxjgn+$HG#I;CX8fp+ch z+_*nj89o}}k$tLs@Ls454!5?R^6jl)!ukMH=EJSlAwN*0+!KIj*Ja7uC=S&-m$7$x zGKDS2hQ)7GZg96o0NEMM@1tJIEE8(Ilnu2q6n5%(FR~3+eW?#Cj+6MA&LJEh8~q?R zhRGta@K<|IO$Mlv*Wr57ji>o417l}c;s>=DaBffGu@cv9K^G|UV1Hr-qp3M>{c>S%2EH@H8}fPZFJ zjfY2q6E+q0`4WM%y;DuQax<1NA7xUs#H{Di>(qOwVeeNqEaa??zq?XsYLS$@Aw7;C zQCTN-vgEn1W1%uAmsuvyUMf20K4^^?LsDl6zq~C^*49UnC(Kd2yE;@k5!t%3zu3-P zpn_^)8XUgs_FuhbPeI-5eY>Ru_q_&d6E{PT?6w5n!`WtMEX|)afhpJZ!PUyBcv^RQZkU z8k12pJ+sKS>4L(?@zZ#}G0=L(Tom=yNQR7hgMGyT`<9m}Zygi0)iUP`n&K7t92vC> z0rh};-ScxEpv&_~2Y($rWv2KwB0>_=k-lpws+;mTZMFf>&6zj!{mgg1UD&8XgL5HK zWHI{K!NlioxAEJex5OB@?Jq!ZhoV~K{F%-N>JVf@jJz+X(xsE4goz5gY3!kbr zUSUbH?nfK-SG$yPB+%88|4op7l>OkiK>9bTY~pjmWpuxs0CEIySzP*h;%B4V2TzThSNuN(kpC-Z8JUo%a6TD;QyLu-Ic0JA)vTAj&7}C6+=DG; zPg$b%PH2aSLLPScZi@ka-TQ_)MoRqObvyHr^Xcep5HKOGXiDT2NbZj%qEei19`K%( zI5ZS^X~aXA1pn}!GXtZbBE3DXAip3Ysek-^`GCrkE8m@lSeJLh;5&Kk2 zf+=tJtGNGLK7fJ?zK-Ur2xH~V?&?0w$$jd}le~jF@t%A)@vAWO^m+EH^%X1b#s`dG z?xE>kX3_{0Xwop`E6L@~7z2Hxb9uyhsUM1X+bVtw5|cx^M*zcGzX*@5aEq(MXH0oq z3yo#>h>ml*QfEX%R_%9kjmBQ1S<-hHL41mrlmSr;-NuK&oT*&vZ&!huyB{DEFRkr!#dPqTscc0pyNdfni!$c3l9q`KA z7NE7B2$A+rRyyuUtESGw2Fiz7gX-!MmLR&83l6cK^OIcX;Ld00fLAOtl~YMVNIb}eAHX$}xnoHAIe7Cv_=DknZ#fkQ zjV!_W@_BBKZUed!%W-x;)Qf0!qIX+Cn^6$z0yF_6kd9{p?cotJX=NyEj9upRDSw)Z5$*nz4j#G! zUEjHUs52r$B)+-h4*6zEDaxx>J+)pg*=L$PND8J*&vL6rJwaJdqS6hTZl}XZF#lP5 z*XnluFwtWwuMkDxnW}W-oH1ztUXJVc-|q47jRrAFGwIT?VpyR`6iKdq3V0C!#e{ys z7QEl8yL!SmHg+}(xy+k*37_ahdo%1go}uZ$rKzHb8#|0Cd(*&cQLSf;wN^`LSNrLP zhkFRLP;D}kK^_WXLqy&yS&44y~+f($RIdbex zQ1kx*vt=DtIr2IoT2hlowhln6hXle~x4Yxfa&0n2JD|B0^$ZK&!7}oWCRJKE<)FVb zdWe6PfIr8^J_{GPe%LSC7uDC@bc#_n1O7y=KKgbVY@OgPZ->^GAq!DolX1L#K8@Qc z?WN^<_HwO1t}0k)T?Hd-^w{(68Q)=bxTTc&vLv;sNE>8u7sb@)W}6UY153YfIMkA~ z4ark4l9vH?m>M`fHEa?g>^x=qaVpyj%H(ZZ#`x8qUZnw?jO$|+@u1+7NCgP=IYk_#WJ4J^NCwnrMV7s>GLG0!usYvg=* z{pm;5(OdNgP?`Onsyi+}BHnu$dlY7q*FxocR^)g77&}|oJ8LFx+~W|czmFcGL5YL$ zn}Khhp@gS|olS|`tl?}C0spgrJx^rBO+1H$uZJ)_e(jglUlsVT;jHtJadp_QQ8HeT zY-#7`X?3w!b5y1VxKMYwIlhdWTIpM+m2a^)Ap~*DFUN~P4FFgCz!OJ0g7!z<9sK42 zc*Yv4y9v`f9jue~t;u^iFZn6>a;^32HO&qf>ma}5DO*8AdZ*KKM$H+O9ipS4S-l*7 zLYe|YUH~~}_FL|Cs6gFA`2A#9AfGJXc)@8dry#q8P@+cwmhA02w}&ak2D%uW`ztLn z-iDYNJNjP1kue!E&46`^L&B!2-#wV1nUKE)vw{`Tb7^--Fwyr!X3-)U+qjV`Us)+U z>dE?CJBtohwjiFj&F{iVRF|q!HT-k}`x_UEUpD~W&ZS%XEJ?m(uB$9Sx)8KSWd0O= zo%09#Kian{lbxB7I&HIy^gA)Bf4B#lNVUD3Gp$I^vpI}0QzDLBER-nbL^=8}`=9ro zAnM2-c6TF5tOSCUuN6z3vb6DMFvBrO4$qOWr~kzMW=lUU4Sn@PA5Y&cM?YHR`D|D$jcs{V8 zBoF^b^L1BvWnOOnXpkZB@p;vIl_{7tK4(88A(jlLaNMgKj|tcioqd@rD`}hm7{xVq zEhNKDA7vlGjNM_c1XM=&D^ur~GVUKLEf`QC|4f?w6YRGmy&TbPnL?1;Z*Za?)vwDp z`Rh=y7>KBERc#EOkLcVw`w|!DZbtC@ZX06~l*dh!9LIH-(mG=b*f;F>!B@_fn|X1l z*JFc7%Cu+-CZ7D!#^+P|o!w+HRnQX!`|>==r(}r`8`ZHfsu+TQD-k-nkQ6JXf(W90 z?o0Reyqp=*>G<~NJvI?k9kRLv?kqSV6aqOU)BH9Rj&L{gcaZx8koUX1$aK){s8Fz&SQjw?Srbs!&+O zbMij&uO|OnE4rAVzP6nYcOo(v7})PxZy)wMCX|khI}2N2R&X=#nr)2sG9!@C-)%(8 z5rw$~i8q|W5B9$fCNF9pXbNiq>0TdDqAz|f~o_BMrM7f6d?jC|X%Ypn4vJObEP z(7f7S&)y7Z zD>jlVM+5aO0}yTrQ|F=(yqZ#N9%a0%61(rlP+mgZ+^Jb|qnG?}(#;%nT`S}>9FvX3 z|I#Uiw!E{}uY4H?mxEuFrGDc)NV&7PHPE|B&g+W&1#&D7yLs&yTc5Wa-&+YNj{pV+ z`(5flH4RH294GM1L^2bbN@aKka>wZp84ILO=k#e=zIVKon<&n(_udAr5Dc6hm#dX~?a*=k`cp3i*=#9fNmDf6miCR*MQeLE?)LFNqT7=Nx1e=_ z+(Y;N;S?6lX_gswzBHb1Z)RQY<9t_Tj&A z$->w3pOW-^c$JlpZ)U&dyh!BG>1dm63?^;uY-mlGG13u=zmH<>_;8|SwHW&EN~iW@ zyRJg$Ynjc@V{)1Oi^p9Z9B+FiEsS;5DpHkTS_glO&wOqlT#p%lKCQ|SH5Q0>kk8$a zj{AG}H?_faM1Sqydr#^3t;+NoFYgbTXc^4^GFAWY#RJQru7g9Sa)7u$zez}*w_p?v zb#rUJ1xwuqht6hV7#mu~E5!H-yMc<_$NQG8w~qfN8pFtg#XO5mTy!gnM4F+Sp-P=} zpuC`SLD}FmwAGvbCz5p2!Q}MMIF#g8_0DHn+OAwnc0RZ6m2Ft1KW(9O7L|0xR;?G2 z^h{<`h_|1}k~)i9e<`x!6Mf{FIN@r%4!)mnf|_0U;Y2zCSz97OV2&vrl*Kz-J6_?3 zo2_x;-(NU&39H%nJ6$RtCTGMh&sOoeerk#yqh1Vn{OG%&)J8jCoTNoL0Fp6KA-t-@ z)x-1@mr0c-El=6GdjT2H%*J|_0tU0mgw<45ng>@WW8{|#&Qu8bB6>V7i=h_yc&|1g zD`=J+jmIdLj7j@c^p04eDEGj#T9NT2vqB%p*vST?A|TIn{KblWa(vqK`}_BPFQ%Kj zq3lI23>jc2s}gXCm7DnC8Q$6+XchD6_xYwy+baE8ScVU^0>NWa<6{3;#dEs)AkYtZ zby^3meFk?8HWQu}7yXzbZVz6f9b<2)xELfgeGN_~hIUU^-d>D6;jxR-ot-JR_?S$@ z4xhR&ZI7b`(!t0Q;exi_IWevlo25v`J;jtEH%s8E2r>D9rzr>p ziN=w{?ife|@qIgzlr$v1c!SgD&mP3Z^M$y zren?K?NstJfo<=fDXN~{_sJ5GHn}?ZKE!i6fuSD@niQCw`nk}7aX3X!@HTym7CRiC z4|MH-=~&YgYEnMCmtsWmslL@LJJn{dQnTDzn^}Cz#(4QMU@%5aK$Co%L*4sOf0gb; zb#TvH7uA)pr>vGe)z7pZcnNOhu{fVmcm||mJ59uV-lfqzvfXUtBC6cAoCe6k;l0?PPlkG9Rxgxlmf_S z`7!tNU#Yru*3CC{Ga&oPl;Cjnv`ci~pVp#E&~sl;8BjD#_HN=#)l13y@mMO57=+OM zAZZyGqcK{GP5aJ{J8ppSHGYNtW8hWRvOokRY66OQ*p{Jl2{ATS;RozVS{Y)Qn8>Sw zRKhzD^gXm_%%F;e4)VMbVv<-3alZ6$i$CrQfs}mL`es7D6t1PR0FcgiGh65YmuF!W zMsSS8uI@lZLPqG%N^QiPw7{lJU7`!ohO-h0c{VNx9U(kwt&5=0b8&Shgkt77KN1f_ zD_3*oRBXEKM8*>XFGkm&G&G*A6xF3Du{&!)Rx#(D4pcnCauQ>*^*zK&c=?hZPB?cW z(n-HJY&Ht{Bx~l%2;n=7yd>OD(ct7gNWD(Q<=wmk&Z5e~ncri>7e0Q$aLBR6r*x00 zMduYuK#O&AD*4^m9i8xeLBxq~N<>tro=C1fhw8J&r=E#11x-eLuWbb-1NBW(&Uol> z;o~@FJ-nN8FqvC}iMvTWJ&y;eJb2-D9NuF_Vn(V@2*_CRFhZyYBubwMd+~Q90-nw5?g&=fH6oFZT{8-6N%r=@NpwL!4vU`=@?R%<_(C}!8rdiBA_R(dm&qbNB zzq2^5zHKXx%~{CN+uh?QimXzo&5IIJe)lHYL1+@V$MNP3TGid21vMEGyy zj^jT69cS;+dybQD9+@kkwIX>@&LnSs>yJL9n8Q6>A{_fS#d+l+HNH+^s|WDSd!Js}`*jw}6>g#XE@?A4c)V@Fl9fA? ze@~k%E&dLhWQj~Ak`XfO5v_o5C~HYg)f6boYD6D{KUWDeBJ_fL3=QIY_iX0SJaR$p zmYE2ZGlt;)$%%5RR;`V(B1sU16;-fDgX?`w>~PJ)AX1{gNA7L3;}Ew`Y7AR7)buro zdDI&56)j@^9qJMhuo+}HED_}uOC#k)v~T!u=sQ+8=LaZdF-TMfnRc~lwY}_?6&~IT zZ){imnoclEPD$JlvhIC(UdYeHHew*Swx3NnR+$}_t!^hyWiB2BatAd3-5HV$Bj-tj zF=?SL|96`;B|-Mf{4soU(()oaNnTeGrf93P)$U?)FvpVao!Bu2+z6x>iNnE1@s$R7 zn_i~I*6vW)VCiO}a<}gIj%@l=3@4scDV+M%bBj$ELxMOwH|;hw@yB*x`w3f=F`#J*4A z>?|7nAW>88UIqaZMKL&PBoeu`u$(5Ye{>dac6eDbqRQj*CT;lsK-my>O94Fp`!2|H zN;h7WR;5ZzN_ou*g5wF=^kDlp(>SlHxBa6~4i5 zKXe(S^rmt@x5P{Vzbs;)TOcWdJW#Lc-M5si_&@r33*2w|$!3{8R$s8=})i8qSZ@T}%13xwp7pDI?-PfyC>UGom@Db|Cfeua( zo5+BnFPrqu@ed$rsS?{Ii_2`Kp#&76+ZX}qul9_diDbb2(bZ_iAb^*L)3eKcSwv@9 z@WwPf7ZXq<mfB(+nSOTX5^vlSgZ-rIE2N zcw%xf^}w$Cb0xfcf)cXzZxN|2KzO1S&)XM9dIu8y)PFGs(dZp!p?(51hwbUd<_$Vt z?_;p=@clo4l9^KRVV|iWAs5ZrT*mU~x@T8a(pvvptDaC+Bh}i(E^sAL2wv5T0iTDw z64N)lQH; z&SWos8901u97X^2>@d?)C_Xop?^kCm6VW7|W+}ql9wvp}<9nT?P}iBzTeGGzy3UQ; z<94B*Cw}4JoQ;wh@x#!ZdbSy!6|DY4R(yE#k5p4YxxF#o?cXn&(d(BMk`CkH?~!}W z;A(KJNF(cQ3J=gk%$Hvy{$t@rAU{^x{>(xy^1|tY1O;JeW!i4dqtFgec_&CJdjg)5 z&)?G>S$z*ncE3@QoV6=3;U~tDwFUPxYU+=lD>SEE`y#s;6<^U_me=$8kb#x#kM%m} z$Hh1euiiT){;2moHe`vOqp|skEN`@4Oksf^G5*5EHYMmi%=a{C_(19$IHgH5MeIjP zr4$nKckf%nxgPILLX0&)S1t-U8|$~4bM5*-b>O&col zTmGVbLuqMsxjN9na>k{R&yguzOjDh9t(L^hL+y=Mmky^)IlZbyokQ9q^{1wjcciDp ztYkJU)+rfnZL6*@bI0e7mR5u%d? zn;@13JYG-sOthg1hjAn>D_vibT0CF?tr;nCS1*Y}hdOvWGYnsqBHddhjm!MGF3C>? z3ZB;OdI{G64&1m~FG=piJExAI8BX6-Z}VM$QH1}j)oNcSvcb6VBQmIR&eWtp^HDUZ*9>p-JJN33dTKE!;Cxz(8*$H!$! zblv+&=H#36u)^2q2VTMh2x`~p@D+o(7>)!W(?xy5p+a5a0?agI7#aypU6fxQwnQBL znIWqjDkm#OoL9Q4>Z!_xf>YHcv7-~*h$87###FuO2C?9e4CsE`N>nBT8VHk&)Qi$~ z{}GLc`44!5rRYz(=638Mss}e{O({R-zzz0^Z@H6od*)IRi~(=E(*{KEd}1cVPMzQQ znEMYpvq^Pm+gPQ^(TMV#%lP_B*Fx;30(GEpUE2?7xfE)dG%AzQLj5$*cT^h4)yPz` z$D^r&gkH)nfB<|mLelrpFrnL4-HzEzeK?DwmO`%3ka9p!8xL%Rk1dS1fS!97eJ>ax z;5{n_GzGl-j0c&-EiG0q8g3#d0!Jep^H|-lXyS0K`D|I*y%F^xa=?6yw%tOVPZ0%CeU131U%|19m$ztt)u!dJRHUF zleCTZ&+!}EgnP9yj8L_|rr^5i*&Rf1PscxXLu){R@VVBU*s0Y)$O-+Gc}HWaIxVNM z1&w9Ht@OfnspZCt~I@1DlUHwxt(QIrVqZ9#hwB9%r zcDk?8GA&E*;(IwNFPLE zgJuEcLg&4()jF#h&7I5b{L0-0Q|?8K@SA{9nG)O+67%{@z9u96tL8G##XD!9)k{`kM3(%AhX`fl%u^$lny7V`BeX&AK2}i0M>X{prAE^+M--QjfmB zUss?{d|_?oer~+4+3ycT|3>L4PY0&gC%^Vkqw|Fl!7|kOhbU2}^HzMtB=>OuFNi!> zhu|BvE()Jo-yuhWU3h5CfHYN$8}e*MRA2}2;cRof%mM8LQYTrcJbm4G3x3Ch4fcz& z5B0N$Hfv$gp$skRA!?k>gec;Tq|k;N*sasQMf%tA)m4W!(~M1Z)ekiuceB_$v=G*+dy$|Wzffmk7{H;&Gd&B zHj>L5oCst74(i=!fneHsQwKITn$F6z@~y7a+Af$HEX+o$b7?`Hkrs9{mq{`%1~pL5 zxqT<}%`B5B!!K%ok&#!t(LTOTz=IoC)+c0s86%QA@wGKnf80C8XocEKo%DnUX8V>H zYfY{Q7{}K+MC?G@H7;Fw0YcbLob&BshAPt(46Wngd4VN#XH)UlAy;+@FT_o5mgwU( zFV7-rwk;RQ!gW3bqm-}e1`#NNZn)=4ev35=;t|VPPGBc4lx|Cy) zF}05d8a$xFU!_uIl;I6vgAAelS1I>(REjY>RUmiJiRqshR8DY|Z$gwSfq&}Jm14kj zI;26A;}89Lf-uWNozgy#9<^WltgTjF%vAU3>l)navTwuedDlBMrl#phBBi6=C@Oc} z$8KYCc?PX|W6_o(-Q^0xc0iSvcaDv1S88#!9ybp9eT1op(5QEBuc z7{>|$y%(Y_Fg(8lXTbvx3Z{+o4>$i4KwMf(?tdA#ih(E(aY z0W@CEqqDru2FlJ*mw@wy)MT^^EU{D;DW0FD3A zIOI2Z%kFvq= zP#Wu=t;WsWsYwAkwfEkbpm98-Sz#)LM|5k^CaD&^j}x668#hrVk72uU5&laZvvka6 zKn=V`>Bh6)gZnW;Ts`gYPnWp)AANoCF&Fze96C`0uhD`^+&G($%UOEzn)g(T8pdr2 zcbjM|2WpI-WlP)Vy!uU>EHDnN+F`*thd5frRPs+w#gmF}hW`P)4$Hl9w|XLJ3C$&+ z@-$+UEa29+^gul<{lSqoyXg3BE)Qc1-n28~`2ZcuzgP0C4`VEaK-Djz8Yb-#v{8ww zD{Hx_HSs&t4vjX*l$j}alTMZZSFNUxQt6rpBqR#QSd%yXV7rE>pY_!M+%W%M9F=4) zSi9orNqRJF$cTg;>nikiO!BP$7JB-`D`PqFKVVIpyZkDK4y-HFFO7b;qk|y_OC~0d z?NZ5waxzWnB^nRAj*ktWP7r);f=SZ@Ugl{6-tqCIdc%0(Un4&}(Rv_}G<;A zElW-=JWj$_(Nq2oDamf6Q_A6T9oU^yp z5@!mLz)~pbjXAMrjKOg=Og_)?onIFB4PEZj{iE^-`DN^uD^7SA2RJ2UXiY$8D$E50 z*SyE+D|b{M4UwzthtCwnm>R5+*psH9?n_TbetryKBF~FGSr$;ZEn|U(I{RP5?_6LW z)eR4zMIsYu)(n^h2-Xsr`P7nWGG+6}m&VoQ7)K+Xyg^&HDS%V2^k>cLIDRW%A?2HQ zhf<)vZ1bdD(py*l{!!o}eDErhmO1&Sk>>nLOq=`$Tz!cY$Xp zvF&{CHW4#*>rB@yEHF+%2L|Tt6rx1m&PI;NdvnL>_0Vy#OtxK3nU(ej~r5fryVO_|N4htWIyuet>n{X^d7$Y(+M?D%ZJ}nt zc*wa8<~6NbNt#EySK;M4=6w|J7$k7O_dPyIo7Y|NQwT31Q@ zYNj!g#hy73h(TCK39nv?UXb@@-`{2=chN>ZAgw&RA0af6!`UOaK(0k01Lj?QYtZaa zMiG@d(Zr!#J|-=m>X)n*DM<>>!8KDG;TI!-3R|M0Q(H}v#)r|erFjt*JTD-GM?k>g z^|25xOh~x^z`A;j>A+!izWXIHIK9H z7vhAAVPb60q^g#z?@!KPGv_VkB{$(aDX0gBOsecl8}Z&>%B@@|?#(j^B~A<1n0!^5 z$1_x|%!@T*JOj&m)T8#xb@AT)YPHdiU*g@yl?>TPDWpU$otGXKCX9}IfyT8)qr5jx zZ+0T%GEGv{?+NN8I@=iv*~)s3E+ov|+e$OER>t6^3ta$BE0wJ zUaOeMtxpdT?{m?rYuc4cWhK{8+$u7SVXD%s(nAy}M%0jdFh+XQK&`OFpquQB^i}cO z7-T{}?$PZ8|G~V`0KY$$Aah<;24y@M7X6pi;(ryNh6S$qH6uc%>8I|0i$;S?Uc6d%F zJDm~o#gwE-e7o{j&rr5SqnC$2mb{jSasxnXV?}R$U^c(Vf8-Rqvc%IsBLYUumos?M zhJJfapb0YUZNqD!bkG!yJQW=V7?ho{0G`r8bEDm@IXP5R5Mn`u+pHKlIWuFZI(DE*i&c669z%!&9B1Ax&6p@K0; zVIp@5M#%}8zCjw3%|r=Cp3{h*9*(nI4SWj~Nw>X&W4gO23aTuHA>lwKm)@ttjVxZC zQR?o=6F|)E;EryrN$lbUmk2ge!djJ@FoQ5LP z9~}3I9HXdUxE@46{OXnHracnn`+41khEbFbp&(qh!ohVxP2bVwBf@S+F?jl9L#Y!A}Y#D75>4B+)tayPyOZlB7EGgP;P7=0M>~h5)X5%w|q) z6Pq|Oa_~SX?z>?M@sUQ8#da0{sK;(uW8eHNDucCk@*Q2e1oVShDd}d5vu8B;xS;Q8LGELXDosH7vhmR%@ygeN zvnM60I+00cpskT?aEkn6G3vGR7)$U+G^>i%Z-u7j5w(i%1iy!`_4A&oKIIn<^3JhC zyt8S0q$PsF<&(l!-XH&97N|^jW56UCsaqb!WCAUgHmHf{0SP^ccRDy3Bzecl#fjXF z=@oWP#~A$=J_Qxj?;dZ>TWd1*j37&9r&PIt|xxliXZX*6thI1 zN0YWqc1;g(Ca1+nefIL~r=EJ3n#O|E&nUk`HQ29@g8$19 zm?x&`#!ba{b$%-SK9&wjHfC1nzmE71Fg)YAQ3{;$^_y^K=`&u+0mf$?k`$*ZFBZiq zZ`_I4Cpu!TJ=f11?}rt{S;Dw%>S8|5m$V{b60jTU6#QL1t|m@!47y$mwhY+n{fCB z%~n&S(L{CV0LxN%3$og^W8(YkS0#ip3EpNi;YEt<+CezNS0jM`Rc!r@59h0#dme3m z+ik9WITl~Y%WBzbKRwnHinKyqM_jHjDsI%E@wp-wX?84yPvS9r9c(nCR#v)?v%QCirp4yAfJ2PgLNPc_>fhCf}&f z=6dQ5SUHn>1(E9DrfjL=vTPvtjafUJmuT!aChDxW&f-r;%n3`-iNzoU^_iQJkJT56 zV@v~S+VCsi$3B}((~uXzrPpzkXPhP&0&W~k@!ETaUpdHpqvctT5l_%!N3_Nm0(<`B z<7Vo2YFx|2@Z6B@J#rV7jWY-yK6|SCUvAu;XLgqlPc*lBv>ILRb*Oah?wa_?ef|*f z+!^6&{~zGENpm5**tJ=@k)-x!K|Zyj1-6Mf2g7r6pD7~aF|LbG3B0f5M_lJZdqN57 zlbLIZJj0{m#*-AT5P%H_x~u8xPw7<#5+OD^V4&xW49o9Eo1Un=!v87fkiP@wB!2J4 zH|K>4Fp3kmm;7-Hg)4hLn}U*fu?miPB3eJ(9-`hTQTqZ$AHU)0y3G-Qx|y4E~lIEe@~w^ z=2e(kKs;%>tR=mz!kO-aD~~44VppgCfJFqpyK;6P-{FUO^MAx2@~`X77k}=h48Tbv zxzvEa;_7QP&+PZ-=JxI+(<(WvVW(StnZc|%gFjoXW^6Fhs+m6eqYLdZ-W#FB zhSTE1rd!c(l^lJQZZDfv3U(Zy!~u7XGxenhN2F4Oi@7-?7`_y)%;J5^jnmFG#+?|k zSUQ*2R+O8Flwxaf|eLy^4u`BKJ zQ6mdFn*$s@G$OQxWGgee@V(!ch-Ju1+-?Is$Lrj0xl?x%`wQ)s?i5l{Pc-@`&@yaS zy_YlP@3wIFT-nb0eNVl&N#n1okyFyoyruogRb>V%T>rWsdDx$6TQGs_Hs^JUxUV?f z_B&!D&+asHcAMX0mS$n)ZL?JF!a~eul|=LCjbtymuV~4)Kku(BrydIR$+&WE|8air zX&bP^RcM^3l=asv2x2Dr{H@Gn@J@9gQ10mXaH(Ubw5q!2k03F`f?0p1@JAc+bBsN# z>aF&K5du!G4W$Ndr5qB)G(RQ&yQp!7NN`=0otl##Se(OX0twsNnBBP{x`ft5eX_gX z{665zQmL440fHN)M;{O}EobgR|$?`?U0>hwBg727-(8S+pLMmjh>}~yHMkE+?*!c$!mYZz5 zzcx@&QK^7%&HQ?GSN>J*1;v7~{;Fp{8x^8U@_I{bq_}$mEO$xEjzD|{})jYXIj-UNu z1m??@OG4?`Q7bM9X>uprgOzsIfiM?}`MRDkhC3m#=zs6wslto}MV^Nf?JhG882k*? z?u$}FQo%0DUrx9uotM?%KZ6EX-hJcPK7MYOu$jyb`UK>w8Bekf4A-?uUDz0Yk_>d4 z!vrb+^8LAYYSqI`;@`-rsjihU9Qg6{k1>8#=#V9T%aZL6+nZa2^?$%YJ>;hJ7J0|} zzQ_0;>I-%3BL?xO%KLG*J*&P68&a)=ww-5sbmRC+`f1NrUf&8`tE=#^IsJ$zU}EnE zrGT#EZ8EFNaw@U35(-hcB=up@fX>NrjD57h4a$pxZ?d?-M^K6NjWQ-OM-|anAKyxi zf=;yTSHl*cxj?lWLgsJGUxHl|MewhPTY;azNf#2*DwMRA)|CfGWgFJ4>ih4g^;O4TNxf&LaN&c^$tSDEpDyOywM}(` z7+G4g#lP_`NoYY8@3DPLbMTENtsqXFxvzdxTdVT#lwv82|Cas-xG_^+k8TG!`MkD0 z@CyF^VaJO5`a^F{VvE<6aat>_^kz<$(G=&GjGX5`#~$X+yr|r6{(2IE4;T}U7Hm>f zn^9^JfR9B*7Ao5iURZe2yFdfhkC3|X#3=~Oo_U`-1ZqZ7^dw}QLfb5)*QO(6h(K~$ zBRHzueT*^849NKIztGRVlHcq$UZQk`lqntA=1ndTg2S&$gg}h73@sYQ4*X=@=m?s^ z5&Zo!rCIcb%^q?8!%H zqx=zQhy9UdA;jfp7VCzQj`uw;pC}_(ps<=q?^CcbfRlQIYbi`hl&sxDRW?2)IH^4o zzVLGr*4Wp;j%X^9&Pq z_kSFnhd-77`^WEN9V;>;$2=!H+0HQ!+4I;!*%{fJsDr3<94j+3WMyX)%1lP~j?S?| zcA`GN`}_M3JdShT_x--E*X#Lw4_culvHp=BkFW9ohC_B7EgGUjnOp~)TXUGVJBfzcW4_n^^*`^ju4hyX3yh@pA?ZA_l=gzsDBUG#skrq zcpXVrfxK&ofM-44M*26!z837851@`G_eZJUj&K|rGH+!)XKf_@Eg0zK2+oxP}1S^yJ`&4yg&-w*PTwhu&)heDkTADLsowYx535a*2Fm4GI}L)X?ClO1q%9riK0v$Q7mB}=j%RvBzCVZ?=6GU3lus z+YYO5LwAxFvw^Z?jT>LZ>7HPO#B##2OjEanbEmJ2^_t-^d0;3qe*`k+J+!-xW)kK7 zvGf_vEu>Tdy+^udK6o%DvQCg7KU0}$y1dFvAno-CRQQE$&@gxO&uW?{ zKmX;ru_|%dE1h;E=X2)Y>6XOnS`N4XG;8LbzBT~?ikwRM201+BtUvGt8;lbCU?lQp zmehW&&yk?9=6#nqiTP?Ee@QI6X`mLq+sv;vc)fkPFP`-U>re3x42imIHI=Pg#2>S_ zvXr-$kIpNijrOBrl{>eOmn2lVf@8)XVp)Hz6H%PZr+jZ6@fYq=VAk@6!5e4zWOhwJ zI-(aGacl6YE4!+^R1&IJEHsCkK#k+G+1Sd5Q1DLVV$z$l~%m2y+`Eo1Ruar zunCg-d}3I|UNYoNxrLQ-`M)dQRK zBG`n0MX6L%?N`j1ZmnC;aL>Xww+E4%AoJo=hY7tjm=A<1J*AEhafyJ@g)@892$(Ffn7((v6&9X%(j@7bU?Tr$$<%8#`% zc|*4!IpXXd;x?X`f#5<_u?Ef2Q3=3ECz&Dgv9^2m^Wfnv{9dA~jObLQnMfmRb$Pn2 zJ1ac$AqR`<-bFJX-2XQb46^xbr)?Vk#oH)`J63;3_>ssSY1ygXtAE=e8kT5VWhF(R6pbatjV*dWVUz;89x0I%)rkCVtZ0%PUk z!ySXA>qjMy~#N+Iw>?=N|2ao3P{${VNh29gu^$=nRC9dnC%bvnRH(gc^K)m zykA2UlY3P&%9e5Qm11yDF<*HSe%>L@P@ zE9AC{aqMFHc!B|05QAb^37c>U-S;!mjfF@gd}d=)x`uujl<8%%*hX*tfn8lSgIx*S z$x2j|-Md~6%?mK4N`ns?C-07ENr*18qfZCI(~*mg?X;&b3<;v%YsrZxbyE5wq89Yb zPK6t@{xkn*Jcpkey6!xXnCXWmsjPHv5#W@V$-@rn&?Fu_o=P8Q^;B`_vyGmo#tjW^ zx)o5TXjAW-?@eUaiQn%%C-Bu6CV#YC9~Gw)u4Cvg79s{SLpa3f#W& z5)thbsvo16=wi!n`3*OEwL+p-9^*W_6^R=k0|rBn!lST$_XR%PVbWRq&eX?l4-bZ= zqPfdeXgVxr!y{B&^HaLS$2?9f+S;?FjRkI>`-ZX{`}{m0%pWyzki~)XC!MJj zOODqnFfU}mH7RfB#zh{oO5g5dbCY>yxeWekhi|Qw{!0j|Hsm0*b))D}TF(22OV>K~ z`z75-9_fV*3tmejy_Uae@S!WUXGQe+y(ULY%P~bLe4<1(a3b@ET}E}l_#e~8PUKFu z4hC>};0xBUBdOLBSr$F6e-2_UqQm}Zn+tjo4WvYdZre$O>J3ztx_{P9SuIYcD^-yR zti8JbvGJL91|0Cm1!MzfRRI>wZg`Gnvf1q4oBbQpTodqPE_x-60KG#y>zSVDWu!w7 zX^D!?xY(73KV7M>jo+7~t`fjyp-;Kh*J7RnvAX)O-Htj!2J_ZtZtx+oZr6s3`BzC( zN_z@9Y3+c_)Pg#h);birjb=Xapj3YrAo$G(hr!fN?gXVLn-n|giHFJTTB zjYSA7&Y3*3@LPaU! z_8~nXueEA6|-5| zm-+c0&@i^=@PnIT_j-|s5f_{N0kS3sa_cwgabVdZe%1P^*7eV^-FrKljv%iedvu(-RHO%(yRN(0|14D;5^>?Pv8U}+1syI6tI9TI z8(jrp0xqLJEW&+FK~Jld_8r63{fh$nItR-wiA3+ymxM&}d!dy&>7##^o#`ZEtQVa3 zM3o_dJ=!A2Ah)cb)$DPSVA>NK;>@s{-QV&nhC--8Wep8eKWDl#lA5SnquB7Z)a^|9 zbZ&TcmdN&e<)l<=wZw!*fQ%4@hQY0t3@_EVBh1cLIC7Urig7`GA+OeGLfO2G3j1td zeg4%;;|0r$#v=dT`GmJ6c^);?7uaSI#aV$JkHQl=Jr><}s?uTMkfF-$(p0d>^0O5r ze^7dv`_|#OR!=MIY@(IbLJ1_rHuucyUnPT&r)pvp%XG|aL!&B)P}>64nD-!E_N$gfm-5)6{lGJXEet4v_! z?dG1I={;rjn3>dZ+)F3VP5mE^El-(ZE|m0c^s?7LRxQ*%=VW`L<>@^1%xB^wM`$p+ zOC3oFMmuQxkLBb|nG{v;mKVI7vfyDK*vA^jHXZ!OY2~B#-{z;Tiw7Lr$1C&JoL}>i zRO73UE$3RPk$c-#9|e9*H`PAtFm5{d2&3f!)w?Q?k9Yp{aVfVRDlGPu>VNyt;RuiV zW4XnB#dv-eaH#T`o8Bg}0-6A4x9`S>oz+wZanCpOoHxhqM6${TJ8D{%{!_TW8U2yl z{Rw-Mw&z}vxoSeYraVL5Ye-kgr(g3G4X%lH0T%8o=9<$0y{aCV@B&j_F27Uz+AQO| zM*6OH3W5+ga}~DVGh?4;e!exAWQYZhvk#44X3xI3(xbWkH5Pu^Edq-|-}uNA5!^OY zWAOZWwVY67;kOpz-$y<@HxttHUAd}$C~VCb$D|Naf6tEodHzy5pEN9ER?hzVyc3*u zqob4n-D`Gzx1D0s^ImX)x=f4f3e49Qba~n>2z=668#>8v>Pt$9TSBfTT3_M*R{RrO zcqC8UcJN1-5WQ*XtK9#6d)m0t_~Y`;E1UbOb1>ZVF~!T-k%jLsYJzNHZcp`Py~zP{ zRW?-))%+44aQ-^PN&YT$YzR49g{d;)A`C?oEQ_z(p*Kx(Bhj%%4x;{?yn_ytFiiD)mHSQ%;KC0)e_b&YeV-zVMDZ9q0Tj|8_BB- ze@$)GL5kQ$lfoWC3ui@dJ8}U_%$Z_{a|e_lYtO?0gE|o35qDthG@P0|ZJ40WrFTHxI3D{e9RRO#^~nMjfmQrdv$6;@6*tWR3|$a$}TO2C{db5y~x zY}nU{1AT_96zkQB$}h3Vg`OK)oflAEt=hQ3oJy1}%#0+c$TO1l$nJ(dwEL7F01Ja6 zyZir_a&zS!SU2Bb@)Q|ZA2;8=r+O=cO=*W+AYOH_fcBVfEhTfH^tjBMPs8>|%cE&M z?U)U*$>~wDv8vOr1loePw7D&)X1ipz{siia{_{MkLH%lRow20pR&Ly`{kQYYj7}Hi zcnht8+!Ho-ipsk}?5f|(Wju~F*(v?{OmfmLnomJq4AACl$^Iw1_%k#Fdrs8a{X_HnL?w1-+#84!xM2rxf z-1aOAvpA82$?WJY)B?%bMIFXFTR?Ok%(WN=NhP5nwH}n-CX&mlqkbm6EJY9P4WYVD z-PL4KlAySc=GqVG9IT;|gvou|ix*Csw&WWXb;8=_9GyGt2(e(^a~=%&q6^hHDTtYW zh-;l+&k5(Yj@9F%V$KO+k<^|$rW8;N+D0?Tyy^GX;!NxU`{hctQTV&Ah-35pJ8vMc zB<6pCuVjC=H3js`W61h>ApUdk9CN)gReJ(_ai-*PLb0GdYD{Sd<&wzL&XCu_3~aqM zhon)VMunVTQJVL#bLVQFXWDB0rq>Nk`Vw-my#uzt`Ia$hbW5~*{Q1%lI3WfvbfkzR z6ByYu?s)Hlp@0e~zXqDduYa^RQF=_A#-?Z&UpJ)RG-%2#eDQfI2&f6KJ1e$;6bu%0Yaaem}+F6gwVAFBzl_b6ho-rfim=}M~&xoqRxLmU`Rm@Fxl3!;c|=5_6*~Q6*)&Fr^Q2|=fWW0 zkww#&0_t~wW@XfH>frjGTo^y7hn19{4)GC<>mfzrv5As6CPXP5&KY2k1%OYnT(F}(9s52* zSNHhC@ql&Ybek4CV-m+imAmPy`^bU^MY9DJmcKL3vHN5o3juwc+!YcL*eCENumK>f zk8%BY-{Vc4dr>Z+u>>rp{lIdw%rT@t5W<^xKimXS%cAxPG5e>|N$M2?xWglmW&Ob2 z;%JcaZp>ufsrQ%RK{VtRnn=H?$4>blfaHnl*HA(vL6-1uvA32&7z>hfZn6_ni9-1g z!cDEsB~r|2VNTMEA?8ju%a+3aU`TS~l~sFGayW4hCBf1}_wGTt6C}L87F_gh zDw>x0^fA*F!I>WzHrE42PLS@1VXC}#3j{8@ct^)Se|RG3VD)3{{e0;3RatS%n*wJ z-XsxM?=WP!@|WuNxnElPCQF%3Vc1nr6?mm;` zS%oS4Jfw_LRxiS5Ng|r6fO7v6>-wL(YwGdO>XVa{%8x13T{QZF{pq5k~LXkxsj89eG9PAQM8Z2E} z)Z$sG8u!=G@=3FhRF*vfFl3L|aI8Z^-h!c1LiVWToIlh73f>$XD9!=hgfvN2b|+BI z2^c-%-)hcS$5ZmXid~U>cG$mwU*KPi%E4bl7298OAmO0XXNoz;A<@IrErE_1H~l8F z`SXikkqskv-Pz#RM#B@sfq|*jMQ~MjYO+w$F8mXPs+Rs{(}2vpS+Yh(^#FmOnN=s z&uX?(&=L0JH6%5Bf_tG@w{md_aqG*4qs_b24L*U3Xa;$$@||QQox8zl4I*R9YLi!;z+yu53Du891Qn*&)!P$ zaZzBm02z3OsQUI$s)e4F6XJC&-Fk*L<7=4PpJ>3j{_a?`J|ukv!51+@Bt^f8NO3_3 z+uFqXbefZLr>ByN+J1>Mh4}$Zb3H^tJYdh;6ObbBhe?O@MnLen0Tyqc#qu0MF&dVS z!REKVL#G?ba(zWb+|`S1lly`gBU^A$Uz*|vcczbUEMaW;p$4#>g2Tyb2lr5`!P9qI z?(k~e)x@*5>3VHP8pxP!(7V_d&OAg=V_HrXrsJJ&-NgHf%$d-_pXEbJ+WOiFNm43I zlL1cyQ5mdXFf6uF2d0_{>ldgCqky?d$A>)_i7}K?MUVQ?)s+6>;2219bxw#0b7>3W znxOhG_y3)PMN8gMkY4) zGAG(2Z?dieI9mY?ldU+!y#7gUMe#&N>acyl&NUtWRo`SHcnsV~6)6|aiHiGy6^MEo zh)~Qq5h$^Gc}pZ|@dc3@KdxP7jD^CSL&`Oo=o8DpEUs(1%;lWZ_ldX1Y_hWXXD@c# z1umWhBn-|$sg@EvhylLl!E(PY0>&Y%QBE1mOU{_dH=2F^@085m3-0T7~)m0(6HCLEK*z1 z6jlx!9;Z&gwCmU2hlXTqN~HW$a2|`5v+xdE$cTIG_mG#jzSIqlc{J1V-OE@X8l~cT z4Y*~~Vj$GoMT)C*Y2SaV7&55SzB<}m_q0%cRnjLr^fu;}A)xrMZCOsDp9RB6fgaNZ zrYF~Y=SIVJEeVSpDFZ2?EGB(3Xx~B`#YEkDV1-@&uN#SJTI81^GW%mwH3p|4+v}my zgQ;H?vb0FarurgU{-N0jT`&w;L4$ov4qfqNjCRadrQd8y74JOmxg!;brYSP$3Jp97+OPUF=R9QsACFna_JGFS!Q*ID~+>l zlN`?+T)3=`(|_jc*9WLdw+e(zYpACpBlgeu-ULXHzwi&Aw(v*WON{__t|rQ+ryFlJ z?*tLeZyy0xf}~Sijgpem0BnC$XTSqU-Uk#24`TAGqz!+@{s+98NRe?}2Ovg@r^U&X z%C0qFZd+L)B_8n*H7cQxT+vHC4w4?SYW`xl^h?6{{m(FWx*H{c=(^4)32LPZDoQAi zGd>NGDvD>W(&E*0grI)X>jH=Li}LPkzeFo(>^)Hf)>ndHY9xWbRJktj%RMZD*7D$d zPh>UZ&?ica??uAaGs2W(7td4AuK5K*Z%BrSm-7gp6a}Ugbl!`Uu*&_D^T%!f4I#w0VmSOaQX10#x0=%D!?a%B!^olW0Z}VG~7tx)$oRljk`*-u2+)o?7we6x02I5&z6Q+_U=})@t z$i=Q`TxdqTHK&(z{8q5aqvNmGSnjVrP5}4fSVx!i1 zkXuF)#&gUZt@CH*#>)r}hl*~;mS(zQ&SBiluT0UfCA!G%8oA8kvYvl|kYoA*?z!X7 zPvn~OfBx~Ou-Cp2`Qd}NtK}~(GLWuy`}sxE%(G@@u}YpMD!PJd7e77nJ7#Sov3dYu zdFIZe=wAT(iGeG|-!CtPJ*+(^{sRi+k3uE#LtC6>g;yHz61uRpgvQPBlb*a4rFx7@xeY4;Kzeou02;Ax>o zd**gR11$D7I1$ll#tQTQpb{>8O)Xjg2WwmHE{Z?A-n68W(C)b2-NCumi zeS|+s-u5=$6t>|F;c8s9WBe!O_K&qq1Z4sry(?#WF%Gq<37t^*>+aKtdKxGhoO;ZZ zuY3GG;VE~A%G-NGv;prOoD?f@c?z>5T_3pjVpy`$PDa!}4JA=VJcZlwT;2Oy6QS{g z^mgf4DiU?^>{;Hw6Uc7dwJ*%JVnpB$w2M4R_6Ug<57Zz zg~@Xcj=U@-_e6fn6eK@Zgd;Gj<1?3LI3c@YWJ4c=r}yZT$}qqZ65GwzUp?fERKSqZ z)~Sa$b=_5+f(u(n`cDld7xTo-mX)#cufm8hP>NdI^Ut=X)Ee*FLkR%_rQh8i`LX*;E!_w4(Fo_H_L?VC!0p&$DC{kt&5hM)suF_tHqY|4%NZ*OY!qsG?F3nL;D zW5A}7;z4F~0q(TS`yL%cAU^HeeMu-u#j?J6=mV|0Xh!s+S(7}MU~8aH2K$eq#;{ue zBb3v9gVl9VsTJJfnYCNmGOLJ%ReZ%pPK3f{Vk%JcIKt#i_OEMLz92AZlXae1@vtC| zj}v4A_&>5hMsEsAEpm>y?nwL`J>|Ix7*Th3Exc(smDy&kM_6<#fP3=zV zyij?Z2wEn{4M%$cc(6PUQwjOrD&xUw>eG<#F_JXI{M_#%pc@3-@bf`IgLb=d z+YS92Jp=k?Qrh(caSj7$atRl}ORIZ8O%T#RZlc@DbHYO5bib#6JZ#{Ba2O|x+4G@& zzbNysFL}LIYfu6+*xT=g4~t*nbL<0IMAyh$j>f2;I31Wr>^;-$obuaIa{m{O@Ps;D zjFZVFTz2r1MdkdN@)J$bRP66Z0^yUl+7&*%qoAV$!CUfsm1-43A}l3tjue<>FSXS`_)&l+v*S`Ao-{=HLwoZt zHo~Md1ae#2xgr@~Djn;La8Lk)A=x@C9Nywkw8E6}m!9TR;7E{U`HPje*1T5sa(X>{t*rcHVjr|B^u! zNxU2Jv| z`~5-6Q$mTkSBWGg5=__@vpDhg$S^Ijq&mX5BqdBFkF;%Z&bV(rWd4%JL%Z2PP(zuw z+3L~!TOCHZ3;Kv?4WUHmSoy^D17lm^hN%1u5Ul)AGlS#h=0x$*&o|LT(g7Ls>2x*p zDi=^G{$)4rc9MKNV6}17Z&TwC@A=WGQilUFMv`s`(PLp#5|)q~#>#^}OJdRotT?x= zS(zFr4g5nLf(Dc8bdq5vakRk0-Qn2SeRI zACE&~H5Ndy%X9OfRJ|5z9sV1Hexg8SS62xloc^1?t; z%mUvTNf)-R8HLw*uP*X%O8}sWw5zjmluD_Lq*tne2el zEO$PNv&CA`wSX8e|J`l^Cz|DY7$tcIZju&s+F~io?X?C+she%b$#YAbOtCs!kW$*D zTQ2PTN)-@Zt>yMPzlpqhucw)L9oaxgk~5Fj>hZ)o8>^{kBVf{=R>vg#WGr0lmv}K( z`2X)t@$0$OWcEjzQrmhj9eH(~@!dhC3pkyY>U|_xfQ}yx%Gat!5iAtOc7^#y(wo04 z+DoN=PWmxShHnw~^Ufgb@*AJ1i_-0~67EIIOmcb;M7;ShZ%QEl6GeVbhQ#a&_ue z+^0=n7@GH<=p{k8cpi*hjQBE2BsH0g`lLM;QqYyj?KvgD<>( ze)v=Bm%iP!_JWjaSoNgpB?fWZK#3L!|VA^)l*8{Md6`DuvW zc1lJbJvpSHSP{;B-~I7E)li?2Vmx%ehm;LWZ49o5=oZ@tQ4}!7^w{EiZ)V>U_e+k0 zJuGbA@On;0cLJd(+ThE7(`fubGj#)6<7XXS>|7{JuOu9cwcoh?yvD?h)KV)6FVRh4 ztGW~k{$V2V`?UJ8eikc%lfE-B*t8&l#n2GM0q00uyKLBkR#`6clBh{U#YA;iKAzog z8L)*-g&2M--G9Lajx`XN0lrusd-{y*k?Hq(bx58wuEy{wlw-T0f{CrXpa?wZARZvx zsef-VbEFvpgQu9=I(Hw${Zx?&udG0Kku)P7!3hCq- zMY_LrrfLN_3@J}_fkqc0dybGV^a>T4LM=o1xJoEPG*cFf)_8ra{pg*Uf*^u^@tPfiP< zoed3MlYcCUo8DGzSZGb@=oy&xPI~-7FaQz+%>)1DE^8S&1rC5m`8ZHdpqXObY)P& z+r_A8lr%*D`qyBwYsiH?cK@&~zlnD(@yLJ9J)6<=)-}wNAKGmI*H~$Y2M_N;)!_Ds z-Vuo%P#uaY!(K>QZuyyL)MYq$rpW)ma&8nmALcH{svY;%d;n9Zb)W#lq&QBXhOJ`k z{7;fZ9{4HB4}KRWp@(PN3OB8a(|c4x_Xl0}QGceRLO@C5G8DCkriNSiukLg9l;Ji| zij7d8@Q8p`@Ejg+Fdm{x5AvVmnu74@v$3+X$-rg}M3PFALiyf{O4f>I4wR^$8LzhS zjs=4d!cYJFOg0l8W=a`#cqLY&u9VZr7{ncWNubL-!IccDe6fD1v%okh)98@p6D`vv z(^Z9H+U}g-KAqP%Z$}g~+tbt~n#)(-wFJ-~w5lPyj(T^y&0Clos%WAm!h2CSG}KeN zXBey#1s+%0;}y9DE{T3CSv*#6yqBVt+!48$=ZL(n1P#QlsH<;Jzcv`d3uL_UI_F5< zwNbyiH>o@MN^7Q~xJcnkPPl8MVRBe9X`U3CtiH&VG;i9}|D|r5OX5@A2BHg|1NS8G zcCG7|LU5I}8=56I&uLFK-F?OjGao46jbTv#B3gj-upWj#B+i-DKW4J(M z1KXaQ4?Kru@16|E6#vp%f1hx@Uo)WR{e5Y6#CM!iDN9LE2ro|E{3UlE{sV;9tR?9q zO5j+guEtM8Ut-voVkd0gXBDaV+XYMVuWEb~G?pY{CWe*vR8@hW0p5hR@zbHP)L z{<@)fypnR;P|oMJZQ$Ov9m|y=c;SwxkY9G8$o*GbHwlBmBG(!=Ow8`@O2w+ zffds9d->*ol`x{G)}J8wzWi;NoIN6`L{q!STd z54~#EX#KF-+i33mn;Ac|ibLZDJ$$zhldihH$j_#QUY_y(>MxN}I!m}I>x*Mb?C(;) z^Y5D7??-{w`VY1JQd-88r~5*i*Zu<*es@j=*D8Ub0&ouV{U_BLjZIodTV0}?x2me0 zW`xS$Y(=Iu8yP)LS;?Qu_sj3+mPYO0p1Vtw%ou`lK5GBf_3R<54nx%ZYXWi)&87_b zP4)IO`}F1{;j?eo9n*g@2i&wBGVVoI2-&ks5*$Cqn8l>-8sL`zr|A?=M1a7pcy09WiII+1jCpyuOGAbqJ*DZ8d*3@0 zQqsH0Iqt6_eB2puX7>AOSlOGV35@rsrG5WX;qzM}gVglHplHDSab>70ZbKTXgg!uX z(bNCTUDbQs6DZ0=`qq>4sqnTm_xwS3aC5%LzfaFT%1hEh_WHsVo9cSI!#pAnjh?C3 zZ@PNYQUfIg5y)SEQ-qr9UdrMCxG_F&dctZ;KByz~Qr@XWSmLUJMo10L|C6gAf88`e zHJI(35e-V<(?_SBL}11^+7lKvJ*(d5MAN)X7Ktub4)cKabrkb#QpMkHdV4Kvz*#)H zyY7K}%*q>)BH3Pti(`|)!B?Gg0h7ZrCOX$!eV;v!>Mo#CpTEoXGmn_3A*lls7-`A7 z*fkbW){oLwIuhC&#{LXF$Wyrqgxj+4+(2=~<$2G#C9OVfovBnP^M-O)X`MgMIHp$v zdB72Zu$eRipYf6!u8y=c+m2lF~aoM_c%w%l^wq#d!i4>W4mZLi~ZXgxO|i5)irL6IW?ug zQ@a@~n7#A-zF;x@IX%&*#IAa){(f>Rbh7G+|5f1M4>H$uH-1pGqu6`s0BshQC~|&b*=W;FBsBj)%d9u&W@gGJ2%p)GczjrDdFc5yP z!=zE$BqPNm15^R%`m*huDO(QVip*zBJXGcmg*(l z^SM>CSnE%_9PM^ChsjI0lw7Lo}e z0^m~I#O7hp5(U+H*@N5pZQysOoJAURp7b`8Vud-f^sYv=kvrh82fP?f^8OyvH}m&m zps?2&BfA-RB)e4Ue3)I~jX!$Ru#IM2?IBTaJ=nc}BhK+y`5x9`H@>?u*_c$)7izsU z?xTI-ml6s3kDokNH(SCpL#E>UKQ^?wiY6p2x6izJpnbTPZ2c1AH)qJ^B)XERK2_@p_?>hr( z9r3NArEX-KKAavMReZI`9%xM?pmnerRK^Pf5JMe;DZ?r2zlju$c8xniwZ6RGkU%`n6ZJR^N)C`4%->!=iGtBCv4B-eaF9vDOr<{ibuUHN z(h~9eNhL1^_wsdLzOz_ON1PYX@EbP_lew}ZOmm8jD}|4=tjqe&5=9TM%D06Hcdi6} z70^iNZK6oKj6B@q<&vU1jf^o=9j)i3`kOVTrd0zYG2MzlXBi19&FmC*7^5G0cD?)} ze6lzZlF!chvWzT&`@q?0$q|bPp(_@@(DLx;Z=WxM10nB*B*UBu2oN1M0W30s{7JA* zQdeeA3K_6YFg{y#P9D!YbqpQP{Zho$NC)FwZwnj&ba@;LbIy1s)NldE5k)1+3#N*p zj>?#)H-m}KSZI=#eu4MJr%Ncf4?RFQaic2c!jR>4BB!a&|M}=vna3i>S z2O05iiW=S1d1=U2x}@T`(9nhDHs<4hfC>-OSa^Eh*!+wPbRUJvA1Mgohj1(T%TM_^k8FszLYcRjXyIY)&JW*EsjpVAL+c8t?%Wkc#Bs~%Pf4g# z#~q7np-xLWUMny|vC3QT)DgB4Fj{Z`f@N8IF|?bE(Id@L>|ec!v2bj!*D8~)XYJ9q z2a_ZQ{kOd3z?7f6|9^n;YGkbXr1oMGFPzievwo!68w`vKwLWCCm&g;A%XynNsyQKV zHp@_K5=?YuG5;>`m~NTg1F(sxMPMI8jDqf5e>lb|>F)JFa?W9>|C&xHgQ_zbq1pfd ztCq5xYg*h1(na3(95H)(tQ&}C&D~Vf!47h>!2y0O51yi1p)<5xbo@Qm==(blpDZ(b z+C1#!yqrs$-?@=p6(IT|*1t4uZx@rFOQS0rH8_G=hO_Y`d2}??m!p@Mra+p{o=D;w zI6DjZXGW503c?tt`+2|S9sM-Q_%FI&pHQIP|Z z`C6JK!FLEE{`3Lgi+>NoVW*Y!Vk|LoUp++3R3*gb|93FU6CU>$J|_!#zkI;i{fVJv zrexemG$kNvK<159T$av7=X22D_iq0&)-U?;M%!Z!=R{Hm1f5~{EZn1CB$s%dYRe#S z!MjK_NvxMh{{<_Pw;=W0bW}xHv(cD6E#p=jZu+k8hEnVcfz&+<`0K{fuR5YA0L(l} z79>)B{GMRk5@=5Y3pan(%tLH8T`B6o!x@q(l#n1tA!nxPLljGGSKqxuG95XA2hYs^ zda(MnDQ-?QIBKftT?d0=o^x8TF9=^>g^iMQwxk;gwc#<@r4If>TE%kFU?}nC_lWC8;OlGlj=)xdfRNgTZ)hz-SVYL zA+LBT;<2fIq1~6@ElK1qnn^D}whvO@9@clOj8U0;KXufAhwtg@+U*f#_+UPAiR_HM;+L6xV0G@lC=Vn+$Z$p10hdRT38@p&3G0E>+>UTHdbM zb3Y~rPLUfaYps{X(I}Ri)hA?h;W-!zto|v<5rbpsIelll&P>6> zwSnclliU&(s$85+GsJcu3t1`GCSGS~<8mLY|2Qe}Kb`#a*eFH+7%X2G4}5Jgp6p~) z$)MshRB6+YzkZ*h8(BaFr=eW>3T7Wns^5va#{XHa{r1tH-nvp=&KpJGEU)s|%RkNr z{(L_(`dyrHw5YY2GN=hsN6#}p+w4aA7^2_PtwIDkpJ+yqA2yCXQ^X_>OIR%rplZH# z%@_UXY#gcTph59si8p~ivP$wInhB)7%YQ|5Cv`6G3OWxePuu9UG*7SLtv){NSFO%R ze@Kqk@QvA2lmNTFfqOT89#Rq1==GWI8zwS{KU)A`gq2*Ml1u_aeH?JkBA1ekqR!f^ z4#$v>Y`R;Z{dPR28(Unp9L8!oF&a|-^Q(U>s^0KuD9B>{aO31H-<)`okAq8G8Jaf! zkD~K%g!=#E_~#r>c18|oE3>lqILZ!Z&t#9wzRCz4G7`tx$vD|$Mu?1zLsoW1_DaZ3 z{18;p0EBY>P75tfwjsQo`!d z*P~WTrDnJp+Lp-uhV*NJjz_&%&X+ZvJ|Po$UEGrRvVq~Usap=;i#reEpUCZ4adIDg z%vjE})+_=9+$I~#MKY+!qR_k(^D@=I<^J>d3)iq^@FW3RV{>2 ztRB%-EV6cY7IsA`iQyYzV(ahKhB$*3%tbDGRWujLALE7o$&~<<4r+B>`tXd%^+#|o z&+)^Y$Miq}{;=Kp^5Re8g*}KH>FN1=kxbn8spdXV?Y?_`=ZNJ~OVYj)mIx=%Ra}X_ z=u~@}qZ>q4{C=52F``lTcRSP7WSh_dQx$Jp3UyEy=i@%_wn_hhbcG$wpNbV#3UpbJPrxmvh#BvOq55w@x&sD&LuNtuaVTF{ z2$)J~0=ZSyb5#$;x#L#N+%xUzhaTC7i2rLm9@3QK%`nrNCm`B&FVQuv$v?zzey9-{ z-T3q$a4p2)AS3#YvCZ={7bsjbkO^{;x9l@Z)n&b9`QxwH(D-9F>3I)@)0}eNuU@`f zDmfw`Qt9q4zHEDl0d0YchtpcORs6Yo;ceMhTd@-fB&N1o0~do5O#Iy3&q@@1dM7uV zpm7K7(5s1D_!M`7w>RH8cD}P^x;QX^7);(kpFD6XnYX-vWZTX5hE*FH>9JL*t3VLR z^)ueLH~y_G1)JaKxy`6C6gDT;CS|3H#C+$!(Io{@8zK&?#r;v1yADBGceKc)dKl zrIC;<20+)P6W*hvhaaw(Q!0Q#?Tr@#kDm_vKaT_R?AwBe2Wha4uTKe7r(u$DK{a%J z3W>oBH4|5(q_L|To2=D$Ynu~p1s2V#cw$RFKg+$5R#Z<~Hcv|{zk*fB+z-h9;IB-h z$Fvq-28K}b7`z}zt^~_O|LhOG3V=Jw*zf@59t>86(an&v1)8{uOg&@>%5)*9a(L)o z>k=o}FaD!O@gA)K*kl#=r%aUcw}RVem&-r>!1Z1lInfSiJJ%j~$++IWU+1eWP<~<3 z^G$qLQS*huV1y1+lo>zg`vtUp9pZAc8Z-SLP>p2l=Z(+l&h3(V#rxr|r~i)zs+w8Z ziU>MV+IswlXnAcNQZ5h?)W^Zs5yB+lH*Nh%xc2>ei?6W>? zWi{y=l-k-Mo25hYc>n-8=>c?0VC>O(0aWE-O6M9v#9p_UyEKT`g$)t<5`FF5wW*@F5v#}h1Sz7a{~4d zHWK&eY&CCpr|hSzbELUbQ|=9LTN+Y!z_QEOYd;br2==LHmuhF$2L?CX_ z${~A|!I|w`am8(yZsifu*UItb%rM(o<$axr13>GhX)}(*HWK@M0`qYHtDEB6b_f08CFYm| z=d5Zu=a5?zw?|(n0Cm@GmzfZUk`H_}nE-OMjR4Ox#M7mf_f#$~G8rSm7aC3jxsx%> z)alFEFQY}4*X$$>qA3PD$~ZtWoowIRuUmdNeJbkq=Yeqe>||LGn@tX(Yy@3^ z5srp)gNx+Y-rCDw^2$Gz0io})2eTh$no?8nx%Ci-(+FR+h3yB74$Nk? zxT}Wi*@6qLZgXRq8H#N#_rPqgZ9#M_w24 zLcL^+{)INaVEQN_er{%#)=6!_EkpO&?nfod&^Gwg;>JC(zehvB1-;KPzv;CH<7}wC zS@rvw@1&ktgQdMIKE?n<6IMr#h8DidjghZfXRyFJ$2-+*+XXB?3>!C``0kqOB)w%G z+?ykH?`tZ(Cb+9GU(UJZ*C>)`Ysz>TBiNlCJQYc#E)hC{4(ppY$M9#SD8B*??rxbg zNsb7}^pCQ4HO-0>vTfql0gQ7PO*#~ByvX(;T?Lp**h_haVOzl<> zw9<3?Z%AxQfj4BMCPcNY^BHMPU!g23^Yqql(KnhL;I5EA+)lgMv++#3wAxWzc43xc zJFcya=2Mz5T-Fwxy!zjNuQ?)c`!|E>is%d;Ee^2F>{^8Ck3+f;GrZ`XB73}wUGTV_ zq;EhpwcoHJiVP`B4MJ!8NLNzs*oZcxnm~@V^jk>HZ@+BLi7h@A`&Xm%EQv*cNt#s# zwRlRhxjg;vswDuwGCTu1Pj8;7L<>Hn_2|W`{Y=m#5TbY(6n{yw- ze+l7*f@Hl<`w3Kp0!_XLC#8ib+WDpMsT98inKUJ?F9d3S#{o>r(I|;7itf=tabM&B zDeZz_#sCFX8(ljZ1KMT~kw35^5kCXU>BW16Z@G%(wBi~9c;&Did~N9Z_FEgnY9QC* zow$_Mk|`Z^?bm29ro3ZrFVeav4{K0aHpTv75APoW%z2oRb}=<2W#*BO57mZekwx<@ z^lHlD`Wa^!W~3N+ABKKsDs{|uJ1B7DMC~7Y>!5LkmIGZuL8)q@suF7ySDQn!OCTLbp$a!sP*iZ-~3sApPkG_ z{3vNnbSg8xwh=!pEVO}>`?Gdd^zi-LSKRo>U8ApVyvZ1>0=VX#8~oPWnP@UTmOCBj zVk*av*mz5F=a;O>wA5L=^B$D10kD`K5fkF+Q`Rs$V0u4Gvz4IT^ZxUT1!+vb=yD8b z7_WYHrbbwd0{#Qu=|#r>2S5mPsPTOB28$<4SP9{v>r5-6he17Nb#Fa&SUqVaO|+Es zcre*ut)r~dD+(g;f?3>==gOhiS6K7yuxB`a7u9#}$+%bx5(#3PMb{v?lDakGFjD57 zece6E;^o8))-uRHVxPYTAfxE%&vLM`pQG(*gws?aKdKuTdQ-f+6+FN{R3-2T@*B*mh6 zIN+x2H=DOXk(6(gw+~hxI;5ijQn#$u>m0rm!wL{nz8nlzUbWIXPMx>!f%6g@;5E#n z+F~z9yp_)&3GI5aw2}Ym<~ke<*Ot^eugR(A0Ma()l5R@Q6PS+frya0rbb1hJ9Yb~a zzflE~$b2NLp^_t3=q>kt5^=}me$s5dIfzL=&vf?WP_^cd*YipLsjz{)A#WnU7p;sQ zYLki51QA-pTBfmg6x~wHMejh!bh8;j)!RCdL8*p2`?#D@L3ADNBv6I^*RMSx$$U?J+lAV!H~54u(H zP>Wx`IkrOKi5d%VG(!nw1=ttv4&YYG_=1vswr5ug)l?aWuHx0zcrSE2ZG{kqN26Ln($t(Lo}#!zsF~>KbEplptj2T zbiDwdr^E;@kKY<>As5Ie>drK#1d2kS69EJYYcgQH z4l<&fIM@$q?qB67U+jZHIf5sx2*Ow1-y%WunR>VlyUvKZBAX7k6OS@cUM1~j-THm| zRROsXYka|@6$C!I2T;eyJF!BKrEfRkWClHHF?p5B4qCB-2xwmK8*$6usHF`oyvOLU z3IskBvZ){8Fu!S0rHq^%R8+B?nF!_oaa^t#bK?gtLdd;kPV5#zuY zz`8~|$;&Vn!6dtE=wV7yP=b!Vs}Z-p7*C#-9Fl)E&ZWfaMa zGqk?%wI;C|c|J<^4qrNuvSnV}D2U%BMLdP~SfmvMre!*xmcATmYISRWFiJMvLY-?K zmd4S#&m&Bf+kWs;3g_PpJSn^Htj&70CkHw;&7IW^IY%tJU$ck0s{`@19D!2ux#tk zHobLr&1QwNFA4V9@uw9U!wWA1F1PXVkEvj!fPQ-d)unE6v}XJ?Uw$UG0i`Z-EV_U7+N#5W;w27ubI9FluOS z+0vV5D3tkk$`vKUw^SDEd;{!y#nR4AhGIBmq*|9_kC6AYwZ}IQgoICz#N;)m=lI7R zp?`L{%e#?(j_F)%NQ}BvqxbOULp-6CukKc*3AuNm`PyIUv#xraJXupU@^{JZ!{mOw zJqh@Jo>%ldqwDV6nA}SIP{p2V&l?3w;2%q9GJ_6v3_)4=nx~`dEIwhOPGp^n_G;k< zZRsI8_S-3^>*LCAFT8zdM31zj)0$5aY9ZEaz!NyPzT# zJVLkz#-RhkT^?(|Xk!HSvN3f{W-YS=m6+m=AYIERV0g@_6S7NuUE@x`+;zIUSFklk|&}1I%>UR@~Sz0S)032%k1Rt1ucoJdzXpTQjlGJQTG>9*>2NW2`3`%eRusB z{*p`{#w5J(xy{>auJ=$^yq>FRrL~~D{Wr?R;@NA3Ft48w0W6gEUmv(`Z>LI$=N54@V2F|?7Mz2Yptsh06PsjgRJe@nh z6*^yk)Z$b?E~i=vgysG@I^FsG@fDSZ&$9@lY=_RPhNX5Uuu-w_cbA8V)z21f__ z&ZF!w-hTuouj+v@nS9}Nr9G!1jCD-BbixC!`XAz_qM+`x|N2E^bjym)hPJdUM!D^E(DjCwtN6qiePr8-Wz%! z(rQ5oB<~`6bja4Y&p^fJVJXgx*04w_h)}CUy_!{j+sr`s*^c(1x@mqN(HFGP$g{qZ z^900nlw4m2A~cn{;v3~TN>lt&0GdMQ@E^sm-u9Deg&hNxK9t0I>dS?nbRX3HnHc*w zM<=Q}Qd-i8AajRKIw@Ubya@{(oI#`5*F60 z)rQn==y}8BmPVl_XkSeV<)81j*}nFZGR{_42x>a!*UnFRe1o%a1do#WIeD8ZIy2@r zAbdq_ov^`dSuTQ27XAB1yMs0pOE|(PbjorX@^^KL(DWvg`QD#VR_v_BPL`*ioU45a zzb_5gkYd(xen_W;I>;Q|UHcCRE`HkOEe}J4>ml5?^mO{brfoYL#odsQ1zN%MDN~e_ zJbUd}Rq6e8%O^cDGDppQFlDe!QN_m9OqsbQ`>cG3&EJ_crN0Ngpn327GYeOxagLKx z?W|w2ACh^gA=;=pb}kq8S;2i03aC5^_DB|IB?|{LJtZmyb;k53ODM9hj!a&5FOT*O z+Q)6o>XYTjSxr}!cf=kJ`ty1QAK8SlG`n)A&nu3?GJk|fA5i_&415!jzMb`BtW{)1 zQBWuOARLMdtX7|3lYaQEJX#6AZPgeM8w;Wc;Qa*Z3aXt7)9;Ge$KH<(*v|rIAdwS^ zx`Vme11bErr{Gtq-MtV=5`IMY$q)??4{qd?Ybsp?z2Yk+Y5lrl_dz*k&s#t-cInD& zC+mF=YGAi<`;q+Bs0y!5jt0SEyMr67&ybj2t&R?K+LthzTX0yFq5rQ|`a(Xy zb9LtUpGa5Hn{;?&!wTnM;S8TG&V{{J zVQK5ggLv1Ba1j4AAvH3K=}o_*^!+vVIrz|h@>gp&rgFBMH;eBCbnaQV@&g6cZ}zF*(3|JnZ{k#>K=@hfK-y1{29k7i)5V8V%b@ultdf56MvmJC6!OSQ!p zpX$-YU+U2fWMzZPpD?V-_@@Jzn0nc{)h$d0bL5NFU4@}RlrFp9&*C=Jqu5*_3*)D( zzKS_@%8DH=P`)e01BG=Pfz3&{zT*=Tp|qWrU}_2C@XtWVc;21Fpm z{$$AA@Z$a-x94Q7wv0PSjzcZpTZe=^^%vHxY#Min{IoeyepwbopKCw$YxfIG689S^^C*EJLc{UHgi0uR6`73&nuuMm{zbM$W;Ss2&9dg zrt=_zXlWu@)Dv>;TXRY8^@${a=!CNUP-VEV$;t$ADYoL}68IP@G^$(PX2}OD4bIP!c@G&pzRnUquw^DgiDC?9Mefh2Hz#eFRVPAi&1G{v-M629{>x66cDAP zs(iKit9NhheqY5Fr>bZR763=aA4l^^LvU))IKb>a#0tATtpDKc%(BJ4uY7p|d;j%k zj^cgHuEU#XhrhUJEKlB0oZ;=-@cB67`}ov*BaOjU#4OxEkbtsB`d$%52Z1!!o=c2V zSbOv13`RgXN(1qp^<@c&ktZfZWLO>%mywJ;Jox4$8HJTs>-HC&Py|-Pyk3XLc(`Qo zuW7PFp5G=onf81p4p?d|G9BY|RGz`Pip+GnpVzeOCR453iZDR71WCq&G+1@dI(jTD zJ3w3lt~kpZs)PNrN|3766`u9Wxj3|<$%mh?&$~Vqg>)v!C;!0#z3X=>#L)dLTc4)Vz z77A_dSwPbTmbmH52hO9YPfCk*Zu;Z%VagaJN$UN(*_eK&k$O!ve(IE7^u22lx9Eno zxX()Y>u*MMOX86<9t^ho-Z=?|j(Or=Carksq4kK|<_ekQAb()DSB^l%usd&4sv2DJ zNcVO0E5kPQ*X+CZB7)64cmuw=@i75b1#MR0e9DqKnE2nmTEO#f9=;!U*FS0@T;E6~ zh@^>h$dhAPl{=_e;#ZU1Bls{pz+vc50W;59Th2*zXKQU!^&lN|6a`%~VWa4mgJx$H zNDxJ$X+fuf+3PZjH?P?1f;NlHa?%W#Ka6mrpc4uoztF;V%&M()e|JT08=ub@GaZJa zE7w+}W^zDenfu-pdlY=w(AL7F@S*585-zM^`kvd2#{FF?>w1qqv{sY<_@_I`m*Mx? z@rW~`ZrpYvB{{&l@s=Nlf2joR=lgu`*6BHP?I{z`lgUC+kiR)Cji$)*{9w<_L6j@+ zH33>R^0e>%N4|KZpYNi>~gA~dvEhrJ#~rqxPU?SQvzu?3V0a>@8~O=c_(OO zCM(gT1Cdu1BFSmU3_D60JwP%jRknEQ_bQs)6!j;Lvnp@jC#UFodfFp_>d|)8QkDb< z{%?JYt!7Kl&^PG+7)=Cho8Ml61aYTx(5U`ehxO$cRst5evf`2TwDKK8GIFn}&owYV zgDN_aBr39-{J~~Aau`Mu%tQ(js!_+iMZqCvX#K=DW`uOjIl^P*L7A~X%SWMuR&R&^ z_fZcZ#tm>kEGhn(MUkQ^XY5C0rWy?S!mPmATo`SB6aX6m0|#|=1nwxR#LwY|S%Sjl(07!uI5k%WDS+$=DYSCPJ~AvRrQ)0O7BE{#tV99*)WS%T)IG zqwBi&wA&n(oN7wHh^MyED%y{dML(P~VqM?XTcOZHWI^@#Fclb`n`pbq$AHVQc z7ra6|8jl1)A*L(`G5T?z{}AYE{{x&xaK0X=H@=2GgI2+;|3Usp9@KSpo6~oURasEN z*)C20U{-1Lx~vmZIJ(F<0O^yFU+otU9`=-W7SG!<^Tdb-kHUWTz6xMI4s$eshtF33 zD{@HXUlcqMD61Cu!?#*`vLm>6W82abekQ%un4-M7{|?U6Gz56t{H&=K)}%NoXAIQz5{8Q9m4$JZk>Mj> zcPyMddCvPfz+DCzzHs;(SgeGuYN4!3lO%!62A+1lJF=@CbM&aH`X(kB?P-w`;`XmF zM1FbUPT*~y)W-BKU*!WN*UhWhFuu0h*3a5^GJzpnSi^5EoRWs0N)b=iR$_Oc^uIzlB!J8Zcb{y^KdubO*%7ArcZ{Tluh>SK>qY>tqb^bfo& zGruYBnOJ_zT0Siz%*dP5anet?mcB&M`eifsUwLa?zbyH^yiG&xfSwu>a)oD7$d}3C zFy$lg2$#Mqj5sHfJ|VBKPrUxqI?$)?VW09D8{xE0w>goUPS@WicJ*+Awl#YcrsZ|u z*7K33j>GKAWTJM>JfWSK$2LpWTOgx0BI+*^EA#al-5uJ?lQqgG59(AVH01X{^K0-_ z)P-?irlVp@nGQe_z$x;6wEgjdai^JcYYOyV`S~GyAlXTdXs?VGDGu!IhsPf!DU8CV z6byGWLl$;lBqHrTjnG`piEs?~Oq?#^LI(c47<4f+OIo893;u^z-4)s5S9JAN4tPqS z8>gcRTXg&$S5-gLHybi?^*P{1-fvX?DQf3^wD(Jv&GYH?+a+-guR|OUK0R}?;5nFT zuUSQ^-UcM~{_X2GNqk$fV?GU9>d5CgtPI#;oBshj)9cirtjcZx zf7AynbsDmL#1$B!#JezH7*b21n|z-5N6@SA;Fp&fEll&p)n{kh7oGR=6Gl=hv64x$ zYoMO9!F|y9stCnDQN*7sQ@c8wpV5=GCVKCugv|2|tm*^sS46zlrPBLXuSOJjX1F|L z@*fbBI#iOEVYS4V(#}7<5xV&LB#mdULltslE_u|G5 zl1n!*@pR?jR)L6=#aIBh5BNqgSB6b;incRc58e#gLi`6L1io+lg+yT@f;c>CN96lp zew;CtKtR@FZ#5J8?$JUY^y&GKE|5XD2rjkv$C4+gWn>)uU(lbee@$cKj#4tr1w1QD&$w2w}f3k zvbV00Qil{wy`P&y%He}KVU-G3QhaERCIWRoj|cn~JbF{EgbK61F4-er6quNvsglN; zSw|{rdLji8tB)$^CvwPdO0#@lvZB@Eo6AxQ4Cyh#HWy|shx7uph92JTpjIz4uiFHd$=a?$=9 zP|>C}()bKxG!W~|{sG+my)DFg#V4X@kVbD7ec-*{c6KbH`M5=c8u=|$qYqL zmwhYGg5yuhUH>q2W&oUR6M!xke;sq*+Fui+0>d}B&~lNAF{6*aC413HSspODVR`sA zl4Z~5o#vql911>!lhM55hX_n(`95NBjWJ0JFpc=0^Gu8tstj_Qs-#&d_q@aG8Z34t z^ioCe#^*Y%*b*RMSDPU0-_-vl4-Hh_ETz!qc3zt>@>tFY;;TXreoMb;2u1u8n!2)e zqVz`+s4w1{hd1IAZ7195=F9ot+9s>&dJ`Ue#rN%poBk@gxZQPYJjPBDMgHMuf72I# zWl5tE{}h_Jut!EeN{2iYo0FJu-_=Rq?Io$Mt_*p5z-X@#Ln zw)|Ty#|L|LFsC{iS}oGK<-Ijk$@6cZwkUO z%@7s``0~kdkO||rQ)W;Ed``Qr@2W7kPAw1O9-qAT6pZkXN`SjvB{AqvcZg0WRlLdM zz2_##Ro?6ZDCuu^NFYoRvtwXO8xxNzfU=I1N|noxRHK3PYviGc=r{dx1Cyqts>c;P znN^ZVYJXy+wyAHoNuq6%;H>!cXFw7Tm!jTXJJR)67!xPz0-9YU%8CRjzVvi1V3C#qGZHXc0PD20D-F4N(|6>RG}g(p2fBao-1+D8QD7dFBEIUxdu z1m*eDR}$Y?U_t=`h281lwGW72bQc0ehIDZaGqCheFF{c#WYQ)Ih+O1A17eqXm4N45 z;7<2c4E;|DY#=ccz1!Zyb;AZ*QPz)J4XW~_jsS>Evg(4+4>7Ag@eYywEJH+f%cH-O zUmwlFdS$x3n->y|U-Y*A2k=v`#{U+gg9#iG=&U~eE0NyHr{Yci(Y`i$ad)=bREKHk z+T2y>PEWr;^|l%fNCS-i4~Q&+qaI^kYuo!zLAUpdq1(h!+VVznmS#Q_jbA zI@iDjQE@$}oCS0-#_Mt0hOW$jg5~(w3wJ~EMV;CPQdVUux`XPJ?}bL4m*wIZKQ1AW z$X~%I*!P+c*WX@UUJniK1V?g%Khwg}{pi|21tPf6N_7|X5Gnk5r|e{6_{N8y^u5jgTC?l4mp_7_P)i zBd&$X;+_8hW%f(7mCCKa+RC*EeFJq|l=htgY~xS`Sa>vP#}y>$_u#AFb{ z2>+(kNb9eO**6UQa@l%)t0XJSCiz7G?o~E!(%K4?XRFM6SW#S7&WsOpC!I>6JbRBl?=4 zrA+v~^?TQegyQlh^#Xn{%~c{Ouwm;&7_kO!Sh#WLgO1AZy1Tc@f8o-o{S+fwe07Em zjm*a=3hV;r>Uh(PHe;HOLvk21lZjO3osLjE!n7WHw&6*Ie!#@jRA-khSd&(i+fNw>w7598n;Sr49Jy z9N#NocFY~zuE&4m+XMIIEC$Yirlz5inLEGbIn@M)oBr=3RyiIaLJQ9=J@%!X;y}DPk!Ug z&8}1uF~3}Y5ALL|N8oed@E-`IppTga&6{P_!eujbaw}=CwIyOmPhfHS6->yFRKd9u zz$EpaWs{wRq`s@s5vycm_D1?mvRWc%TYdjK|JnKH7PG*~ ze7qjLmVAGO1oQQf{ggQ-NY1khXSx0n%xrpRrfND7F5h2P947|XzNTDu+ujojmc;{Y z<@qw=BV*-uhHJ?`&sU3VDM|L6vJXt}a>&+61NYE3n^Wn@g@*>!c;^%PN-J$1(+Mu& zhpd~_?vRV)hX7ZRk9zH_a@%?wUn^1*v=v*%tDJ;bsgcSFH{9RrrYZfV0VH&~k}Q|j z4$L;pgQ)Ik8uC{Du#VL{wOyKY=IQsKySr5r0)rtYzq*=v3gd~^ z6=g8zFF3_fa<7~&U9f2^Ykt&DE5s>(qpp%c#C|AAhl8Thkai(RmNbfHyb^eVpVRFi zDe+c_i_^A=q6pf1Zq`(-)Z!=3h1Adx?IZ6cU3)^H;9Eg)e0o}O*N-b*scki78&y}p z39Lq7^tI=kAv%2VP~`RcLb^1_h>0yR*7|-L?gz}^aba^u5-}O(V7nOGDEV)X3@{si z*gAY|XUK~`o|mkXq*iK^;-1jHO;Su?my~maJQ$DELL_jrvR*yqQ{%p=1)VTfEU)qR z!==eJX|l#LXoH2AWG_TFOe=GP2y!?kp5;Wnh zA?MYJL=sr4)c^mKvT>|fK}x)1CPAL!+B~gCskPcLV# zK5{*-v*`;FZ%$Owo_ez_Jc~>;2u6_%9P*_Z^&=*z-!BRw0y;Ochxmu9`a;{#Mr=H! zw{+H$+(~$ZDNf6J4M5rUgQ?rB^Y9B@^ZRC$wDLdEk4-hsW8m^5V4-evl!HB+*u59m zrABUEGc()5#GAcNy$OxyGRne9`Q7@JT!=w3L|FPOoE9_L&zZpv%hD}Pz4)QI;>INz zA2twRU8oS1IiA9ve7yfwewI8vMWmB5UD3m4h(twl3En7AIxS4U73@r`Og2k#-tADL zY?|pE6_cDIWNE=g;&B`AHMsE*7vi^;QPLf8vrYu6$<+~}49t~Dr zPRoqmzbjEFDDT~H>Kfz6e43dYbNetd`lNawaVBQvi&(_e#um9PbSNw-MBw0G)NmAQ zbDJ5vc#L;FWcyjV`84`w7Ck&y>!d6R}*)a5oLmnlNO2;@ZfWn zmG<3N?;jg~(khj7&Xql|V_o55-?3iH^*l4S|I5~$b2H_(^e?gKa$-+QW*!+aulQ(kwxWemk zZNtsHa#yGlzNxYgf@x{dV*bV8)&I4MRh#u3eUdJdWb1~Qq$pg7rpDyi3A;PHCjB3I zQGdwq@8IvREcDKvzYqF%%$5d^eW4IRhyN;h*?o`&G-B?~-u|tS(ns7eCDk1PL$D?2 zTr1}XwH%-DW|Q|^l6IAY_K_^SNrE#-lp^FuLC};=+y|$b(_+!egtrpfo1FEx>-2fZ z4z)LLVXu3WkH2A&2lqKvx%z`8iQdP=4@k-~Rt}7bjZGD~4Hi`SM>R-8 zc?DXKO)P_0I3!CEPWs~)!AEvMrPhIe+>j*k_??sD&l6rOeDXUfQ&|ro9i0p3*OByg z?+2m6^!|R0pGj`MGP~a-ko=-Zx$ua@OHo^Z-;@sVf$;+Y^m|GLlo!4ap?_{X?Bs{l z)Iyw;Z?is=*R(zHd4XYR4a(pYJNbMJ6;2J(WR*5GIQGUZfd6e)pE%PaB-#BX2+^_5R4UylLibU%e- z*~+F^;<>4${(6n2+D&cJfFVH7H@3gU=PN#&+Vrs$B_#v=MZj#4c40cXgrtAq?q5?b zhYl6v6NgzWUmh)-_r*zhe4DGf*a*UWsPOuEk<~Ola$934=Oaae8i7^AOdavg6rRth;@PU34O;eJ1c=jq2K&*>RysgC%`%c94jxmx2;l?49 z>pU0!!xX0>JpZm%f>Q_VX9cX%l5frya;fDu7zvzTeiu_XDVZNGBsbfMPnj*(ULTG9 ztz`^)4Xu0}HTV(Pm(9}bi&DuD-jv*H90^(;P8dlaernFuNW-Q&u|DQGu7$r@KqcQV z{{Xs7XU3UvmqF0pv9#pG?0x&Ti+~@QMR-;g6@~hZ5rcY&=Ijq`9Odc+{yv^OWgnzb zn0;gOx&JRIrs1TAXb&1o6;nOtY|7cC6G0ZuV_F68h4C}@CJ;`I4N_JrzBc4oq4`>dyt`P#N5R-W%VjNY%#b_Wf{g$CL$4vaYL_M} z%_wFq8!RguySBa_DhDqvs!%T~`nf0Z(I(i*K zdkr~+)188*?z0jNL}a`So=4VbYZ@9_vlt(a_L_2qpvW%%X=`HIVbJ&~{e_8mx)H2_ zhRpNyHy{P?WGAc20sl&LH5V*^zqy1&>EU-9LQo83jEL=pfI#LB-#_Myu-r%Z}nKJjyh*Chr0s~l>+jy z9GIViA|vGZkDGa88KQK&SdRTTl){ldHQkFZ+48HZQGnu2LzUE0HK~^;K-iOYN|K47Bl`Mp;^&a zA$XL^jcOK)P&wca6`rvD0_jDU_G;4U<}P%Q`GLo5YFbSEn2g$L96p+5o!Foip~dmp z9m1-ul%)xBUw^H6-A?(DMMrua34yXo#jL{#wa|062h{!(KxXGLQCHnizBg2;quOss z3QG%)i4@Q(`TS_)JdKb;u6*I0nKd_o&w%--{wvNC2qoOCqGy1?aNP|4#1o|6b8{zV zRFaa&@8s4C0sbETe#3OjNSay6Y-2Ch{*w|0%=Bj%So+8(65gMW6-m2HP_7GAE~Dt% z%>rE6S<&+Qx`05ns;;p@=wn@H5+R8iBnNrR;hCF7vI6;1?>}$J z3FN9$0uq5r80}vw_Mw8TFjz?gUrv4^hamKXWPtt~^?jWYhn`2*HTeOYa*yfw>wEO1 zdmM7ot{c7%;O$M5!yWP=mboTA%wghLu_*WDa18uhr~KO+*|0-{5**s2io~9e!I$n9 z7BR+qYbYlC^5IX0<<$%DR20zIAmgDjinQq1@(muNsl7$XI4p^z$Pkr$DX_@YM-_AQ z|4g#D@%~F+Fm0-m8W*AU6=}(8hvIX+n(ib5hu?fN zIkU%z^eNOf`NJ#?qH($rt+^c&w@+iwNcnOJxyKN1*~5PL$an*T;l=!BiEVC!=8rw_ zPmMqB91;cNr`yvNjQM?DWeHZp2DyKw)FtMsk4ZhzCVF=8-708h*`-%%LcO8T!% z-$y)tqm*S{WfCebo}0ysx}iOP@U-8WHlsl9vh}Y|X(maETt#Xd+We3v=xh$+o192Z z*?ydp4qbMDq7yl_2Kv3e1iYR}+j_@N|GtgrN?FAtjnObD`s1M>d@`L=z_X4+Ix}o!# z7lh}gCS2fD4gwIbv+A}5A^gIPHQ6xr408Qaqs*hc+4#iP<; z`fLFooX1dUX)+Bb(K7Fpohy!-SJ<6xg^X@s?|8_Ps*Gx{j+IRC9hrS65B&Lj^0uHz zjfd8ygqWA7J* z;b&s};j`tH1x%u#lyRr$NpkgYH-j>|a;JbR74di6!Ge|?#N+>uqI2aoPjq%L_1Vpl6{$!GsaMitKWCHLV2MeA97U1T@vI0 z0*ebjamY_qOkns_A~|8=bNyuVBl?u5WdlPh+|)eHUt##4mKg7T5!;ksez)^oijK2y z@b^BWy_t`7@5LhHGGmwm&}7pwc! zOGEvK&>1lEhSN>=;O#3(Jb-wD$bE3O*65Iso(VVXuDm3q^}dua8uYy^TZjSK10h0^ zosRr*d5nLvYsV%jkK+5y?EZYZ5RFUeX|aw)th>(U@j%XuvH_7FC-t=N+|C(aKO9jM z;ndf4(bY@v4An-~-BQWBSd3vD0JiL;ha-FEVd-Ufl!s@dz%A^C88uXaH$FoER=i#S zkXF1~7|4S@Yz%+K43y?zo{L!t-y#{kRm)s36@nnnspn${d>n>EG(XUo70pH+ce}I6 zOwx16%`;lCdfn4N+S#|;in#9Ovfbm!232dq2AfnaJ>(}Gf%QT))Qm1;(n;G2VrF^E6dM7eVME%mS7vT>!bJHI5=&Wx}93P9iM&`2Txr)n}i;X z8}M`-H`iQ>(svOyya3I)N?GD+2;Q!G5iWcFe$k0DXUyN1DI2bDSO*S1$lHZk2iNs( z-c_YPX>jnEKcafoTY#Ayt1~B$VBm7BH!{VjhL7hBeFk>BsZRaz1wdTR zX<^TYpNED@qfML!SpQ615a?i?qrscCKHDw0QfVNDfKqPU{}yJMY+qJl3b&Csz*eoA zEq|pf@me}yvby!>8$)oP(IUlXu3;q9ig2eg048YN}^x`d?xb02Te+@URY+s%QbDtvxKhK}O z>G$cCq1xc}{K&4gSHCWq{QR=^Xh+LFs4i+(1%Au`on5CVuAMrpbx%n3HdS=b+sg_$ zC9${hu~NWZCc@RH*;shn%=(@v8{kn8t@7ODJI5b~t9i9hMYst(!Cs-Z=J2;D4mEWO z341s9CA|#5fVD+sh!6M13tn(~cX)_u10UVHFRpO99hSc zFj2Or-uzXsPFL83hM5=x7DD%j9(J`x1UcJ51GJexgt@~z_`AAx)@?}rK{Ld^4WAZ? z0)IAbvhC(}PS;#R4~17=;J(AR<>FzpyC*68%rd%s?t)N+A9!aW;CTPaVeQbG@h62v zYE1N+^$rF#!mW@*fj7#Gt?GJvRX?Q&82D>*o%X(`W(w*Xv+lU?3yC?y54i9)W@*~2p!!lntKZF)_ciL3HY0z3A*CFKZ5&~($3#U z{gNRnD3Vl9VL_Kw=Ev_AkznNw?c|7ZsA{O3a?g&#>)}N=k(hwug%Lm@n0uGScW4_X zRjWqq$RqMvQmpKBoO-l#wYp(Nb?lArxiV3q|4D(_2aCI^1_zdj-{e`< z3bnxNbJP>}Ef3LtR@NP64!j>myEuFA7Xj=9%~DDu&)Jv}jOK z7*kbNsWMXOKCBd-#cKLSsDbq_-&}_%oZY}ggDT6-mZ2jPITrb6m$h`WZxJknduuzU zh$>?mqEkFctJ)4^{>)$x-MCBeX@DQRFV{tnAwq5uctzx z4VBx{BrSLql@0-Ivt%;+as;8k+1@q9^A}81j%YITopX(LC#J3P_#2Dhi2xt1JDt|9 zP5|bIskYGEBZnq=ZP_xDFm5+7f74FDM)W(HBiqZ1@yF3cizPrwH%h;{ojManPA=@E zG>s$kl;-8Xu>qcx^^>SpB%(U>j?BNi!UKefbg4}_UAT?ihBc*+nUSVKUnZWGi6|8- zd~3K&OOFv-=%W3Xb6b~{#3yQ^=Adq?GA{%sZP31r~hslNu`M{o6yy8U5Nsv(l`v#}Mhg$sW zAY+h9auIR2KB{u=JAR#i5MuvMD!DnFccQGZz{s3lXq^pls>?CN4qcw9WD-Ny$x(=! zMjht08?vA3%-+h}y*~xo8vLM=yGaZ zZHTS(J{(=vUQfoIUUKhdUxJ{k4*LRvbqX#%rrwhkcOQEFDQD^^B7p28{8*-fK#;)A zAoq)ScrLiy5Xa1mudcgIe!m=e#MmO=F*j|0RTjFOcgpBRfR zVrRCa4vVvW#%&iyx06XYllRJEQ@}kvfK8Gcfw^ivb(oN zm1eUQ@K>pV9~1>k)D7X_S6E-mR~Vef#I6*YhZF$>kfmRt6L(c02lFHTu*!lB%|y!< zS8n>A5MaC9zP|Y6#u_834JJ^$hnKWAJ(hgWMPbLY7B9?A9z01vA z#(kg?T+tUovGy_L0|%Tg*j0gEuN!2g^K@fz)m2ng8=o?4RTs?3)P z(8=0W+xacTUZTE^Et}hk#2ncQYvg?Cw!28_uSm+1L-RO9!Fg2Q7sS3n?!?C#UI zD8k@~DTds*ibJ>csScZc{wb+rR2FzK>8K6->CR%H+GDLcCLrU?Mru^ z&?u$5-BF3qJ#7(4&4AezUfu_Wge+BS;hbO7HBi)35(;8EOFx~XP3rPK8MKMYf4K1G zY^&Zc@Iuy~mfR7eN20^5%FO10eie`k%9ZT@Rz%cvx3XZ-B5-Jr-4*0o>~NgeZJFLy z$fgdCq-tMoV}HiisHR9n{pu&|*bNGOb-;jH`aAZk%C=?$dd?lgLnkNNn8meDv~H;% z?7Z6IWuEk{GIS7zK2yZ*snAplRw|jt@#)>vvbo^2?d%{4V~t^X6p{CmpHf5*giO4= z%TPw|is6wY}X1n+6!P z6>)`aoFJPSZt7dPT4a1!B5PtRMQ<)zs~uMxuHKKn_fCuhw5vE=d$_4QUsdUIp+ovP z1e_mM6jdZgr&ok708U)JOfV{PRzbbNi>R!u=A?90rHY9}t<}S1&}}P=HJ1eb2WUog zfJse47SYfkJJVRw{_%5zreZg^jRC^}OzI1q+ArdMSLu_s3y+8!;ZuL7&2!iqw4cGXP9Z7-2$xe^=wHL#*xPTXt zQP0i|ebSaGcM2Rg_e@A!tWvDuCXq{54ytDHT+d*zW4&CpnhNUlaE_a#Z{U!q zNWp9p>&$>|JyV6Y@#hLb~VV4aDmSPABH%?32<& zk@5@oSBmI&ORW2G0xDa4Ic%-2suG>LQy(0&YBqbIKw%>^v{Zgshau zmEr7g4pVytIX)^zy;TyF+u0Cz!G;#)(RkFJgTP6vt`)Hyj;rl%kMx#Hxm|O3evh-h zHTHgE5VuaEEZdLV)8lgV=CEs}{MVG3TBtiNc+(j;lsc>0f7fIGY9cu%XkHGUK&Ew9gF?is^CUu04Akc+I_d zRL$}=c74MFX>3P?^G;MZGYDJrpT}@P7ZobJdZbu>U|viQ9wYD)J43CeuXOVXS`SY~EZx5oavHJ?~RtDb@s094!v_ z9p0C1cJx;@bEFQf%s3oBnzwN{c3ZcC4u|A`1sA}%Ea?sy=J}4ZqKD#pn0{jU++h7m zJcByo+C)+JKZ+dH*~7spi+H}ci(anhMHPn&&)|z)I^ROabRY~ zSX^_f1UqVMcmplKB0ooO`u*gSZu>s0*%;(+_Qr#?KWD3Emy&a8#2mudOjLePUvt_0 z0asR-5>#6=XxkV8Ox4ux)E&$7`}odp4F4K)zwz0+{_}umOyx>i=}oyqiE#+}{_Zg0 zWg*;Me=trz7%w4$zk#C2Q~S7*lZl{4EbQ1KLex1;&5HO6Hx#uxf#Cyq-`g}x=3(K8 zBwhf7g*<1UgQgesfOMqf1dh7d3TAP4)ne}TsGJPpZ1FBlXCQIoh0na=5 zZL;IW#P;zLMw~uLIu2hUpQPX1t224?2E+EZeT^s_aP}_GBt0mm?Pks&`#HCvGhy9m z;WHPWZ({X+_5nQM0{ZzF>S9SMd%@-SbaUy@NoJrYyu9AM>$MB5ZU^j%pq`O&c*feW zQxM@6M|mazHbczP4Yd{8$_Lb{ueMGlo4tmO`ZP05+J8(xX$XDF0Ht(H5IZE)!kmVrq*d5n2oO26yzK zs>Kl4 zvmD$IBxp?Kw3?L;|y>vU-N3 z$N;a$rTG^v5i-`X;9QOqDr?N^=}1!B%{s2Cx~?=*ADxa-RZm-1j|<36$oAzv z^+xF1bx{{zA95tsk;=&P%M)J6WU~^_Lm&C*?Sr^`JV7Gv1Otw(l(8B>VBq0$xk#=S z2x#N}4Oz+>_mLr;`X5QWr))5TvfU(+tc2Cu9mvAbg;v!D%7IDZ-4kfPwS>qq0 zS|XY6y3TY|);)NzTUx)+zCm@I^@}7!=+=QO9GfROKhNAOy& z1KKUy%khWDZ9Pxh$Vj4 zKe;a?$sCT!Gs!rSnD|YCyi$)?=|^ei{bYu*5@fy4pOt=;_Jk;URC>}DHhTrE!T}zg zntUfIk;%ziEdDD!MeGnb5j7Uvk})^8w1pJ=7tDFiSHa`XUYfnO9<$V1NGe z)(hp!99#)=F7{Q+uwMfZ(Y=}+ALMS zR}&MK;}xV_iSz>PzQMrz%w;3fWF6^2Jl0ysn zvX^bF;XxRRT=sKYn|Rqy=?5p5qShJ@ZUvq7R(;{+1151!Eo;^nL}w|jvt$~0x{Mh} zyh?b-%xGV2t6y2J=#`$%`|RA8~n8Hf7iRuSJ%7|+PICPyn+sgt=T0k8jX^@O4Jv$R=J`-kk46etE0Jw<< zWqMAcP&d#1$4heE3~ozDJaz^0B}W7b^q^Xws68rrjD5 zd(Ll?5kp%}6$AN6;P#xNHo#7gFo_7d58s7oNa$zZjsor_{+{rP5ncC)R>PAMaqKqk zmN9)wIM1~t?IPAun4Vpd4LZFJiab$ZNk2jqvB6LgRvPz2<#C8^y-Cj`wHBgO|COw+ z5--sz5lA=mXBBR62|PqOS|aHxb|Z+H_azU@YYl)d)Rcp=%JUQblgE|N{f{3_9bsPR z@u@xbthE*BV$nmxyK+pu$$Vn><>&)2t4eiu-kp*I!c9FV-y&Yf01}b5XnqxHTKA^> zYIyAz$ecHUH`Q~0>F@#9*k|Wmv7V5F%DQ^t!7J9-8vcv^;OLr!9o#Vg z*z&W%_p&kIy1+G%6wbk1tg<9YpG7YHozD9*O0KfS>v^YbWi=4W8I7^R7zlx><%VU9)`84eFb+m%MBvggN2In(fG=pH&4vy$J@U zwWKFkm#BNFsq4!5=EtRM)z8%Ol2XJ|Z2X$%pL=rOIaLQZ76e>)`+RJndT-IZBH|En z-n}D^s|6wZGeCRC=`>s3j^djO1L_dg$b4V!nlG6N&dp6{6fXx6I$EyDxn~o`E@Zh! zyGW+K_YwUDaWpA=@}%>-Jm%c4k_w#zRaob~+sPh#{2eiZ`KA^4K zVFv8B^=c-cfO(5PXUqJN2DI?d_BL@jcK^Z!8fU!e{xRho$ z@Uv|kUrI4l1o?*q8dy~7F_%%aBa*h|oXPPaVu`UoazW55#~($H-;@gNSJNX;4n z>|eR099AK=)$F>@409!aDNrgC5a1a2YB$@!n)G`G2Eu(kRjxmXCQviwg-Rse`G`g? z<{I5BVz)L?W^=KdzLdsfAu6d|9Lmt%8ga_LUq~>5h)2`Oz$|JxW7%$)4jHv^2a4mO zep0)SgIAxt%Zp)F? zh{2hGde}E!9DL!y!xe|;_5a%C*dPo9(=-Tg9BiaGE{hWD_5$DI9>Zk+w^%a*ia8|@94$* z*D%!ckz>Ib!-)Mq%fwUfz&>ZDUO+Rh>!{k3-g!@0C6CXcy+Sb~ui+I73@ZdE5^9S} zu`88N?Zs}UN~|Q)n^`B;j4#bAf0wV{Ir)i)I#~d`tZVX{0$w@V#B>|Vigs2vE}k6D z`ce?u*ztlu0hhrAPD&8gB%5_7H{ZP>e~AFv{{V&jo0IYA>qrUPUMu$mm%-1{&A3uL!>~Hae@tOEj5Jn&hJ5z)DKBSorw4eMYo8q zd_`F*fcBTbwzQ}3CJn!0nzrd`)_OCH6>(i*q&*#u80YV z5$aYs_vG`j9LrQIL7?kg7_enSS_L?iZ-MTh>VfTgP9`aLny!7QaKNlE2U^}UlJ0QF zl$-N6cJdNPlKzo7*o7gXcQg60ykpe9D99er+~b5Mf0C(i;V)chT?&3B(vlXvJ#?^c z%_*NZd`myB=)}fwnxSZ%Fea<_KD5Q~*SeiYqoSc-Xm9ko@nrwZE|IazS;U!<_TNRj zf%vO0r1MD!2F=pda@Vt{>7%tU<2z@G*aH+;xo1C$>uCSuU6CY{7}4u@PrIxjF!8*~ z;AU`XYv>v`3j~xVV|*PR<}Y#Y*_(WjnQ#5^$4U8nibX@WsG6A)YBlCz$d@7#}RC{oWHut>qsm|Y+CgscysT2ReH06(jD|6*Tt)* z|5k$2tuM-w;R`wrGlRsvHV`xJPtx$t?>8|N8fekIo7qD6f|^_j65lx(Kux+ki_0^Z zl|``L{2utdGV7MVhJJ>WV+Wz9!1e(2=}IT&Q^+?*Zod~FiPERwRl8Rce9BbycM1z> zd&!G6ddqG^=Of+ma~C7FaB<)s&q`H2gfm?hE8FZw3LQRmJ*3V_iwB*8-XZMQP%r9b z;xLqa@Vuw*DV@@0)?r3J56TwWSzdEXUM;NZTC1?E-erd{=?mXjUVZ4$=}&2(TbWVc z@#&7@PzeRCd6pg@;s(kb=@Bj>*ijC!YZnq;lH48~`}D2}aM^GP6izGnK?}jb*!Xmr zc!#7~;RPJewck%~3UAmCMAtrEb{=HHifh4cZy8~0HQLli0Sj~`h6Vy=K0iy1TNq@L z5*eoNmof;Hz+BD?TZ~&)hU%)SaY2QTTI&Gb6RP}e5xNCQj#O<`K9xcBxR}5tpVfcC z@14`MrAsB~19bo{lNHwvB8?x%_?vJT9Nx4IUFOzOBFx9ssPt2-x<)}?*mF~KRk*=7 zrl@?w?Df2kaFrazxZ-+unYRKZzn=%KMF>?gR+6Rw(Rs;{bmkrYbq77wQ%oUO>K;H9@? z&x6SDgpi@(U7fWum40Olrl?861jZhJu7H!VM^Bksy?xZ?=+KYyZ2-$3h`KpS8;b+UaLJpY2E9fb9=@i(W}&wbo)V!T0{E?e(|+ z78Pn+BXWDHka|lFnJ&9&vXI0<4cGbl&GVk%MTw^A*#d_Qjj3YY`w8) zsU6WZYRtVxH`nUzg(R%RH0L%FBY^n~BL|RxkJ(19s{Ef2EHy{E82M9?LmH0X0|JL{ zvCC7x3!3#?RY1$-ptdjF`7`kY686%YA^1l`-V1Jz)U42oMHz-nnMa3N^?0N{dmu~b z1;>YuMP45I3e-2MZFZj;gc{fVuMSBRniqVrbm~Tqc?UvvP?`PJ@48WIHPYmiNEyd~ zy1=>DoU9SCeFD$&y6-^?A59P?nkP#loQ9a4c$p`tkYWzcgo&<9bQ@W+nE7y?}a!x+z44)X$FBI*wzvQxa_r$GGG%QY(k|!z0uCi6?b!9j+<+kh$s< z?M*d*MCf|gD!M2M6%C0RRz0%Lbmm?G4R{+hfAcet}KYnQ9HryDGs<_f5yDiDeq)oeS1EIAHcqu=QUudTHWrn=0(_=0V zZPetpQc1s7hVHa{vxRHw^1=@+nEYI>c*MsuRwVTM$;!hA+E5hAS@;u4iky?aHgNM} z)PG7HH*1594%H!3^T8)SF1;|&-kE)Vz$-ZC@#1Ah+(tp~BZsz5@6#p{g`U1n@~p-M zc-NKRrk=L!PsYfy847R1)%pVFuPj{FT#<+BgQWwVmE@D??+PcUmz~aZ6c1RAvyxd2 z@8;_rpzB;-y@VYG#-fXa-aRP6{+rdjCI8%Y;SvvxoM6l9edFG$zS{i6t%ew(i$hzW z!%p^I`eK_m;i#aK{ZT+@Gl^#*1@JyP)hZjC4%PqOS84`%c;Iz6u~|;1m<*<;F`dfo2BI(y3(YOH=JWqouE_5^Ar&Tk0a*ura+fBRb`m755cVdLZ z%jcFu-L32o82%W4qU!aqvX1=H2x}`t^5Iys)he0c(83)6M%M1V!!Sr!FceedhJ9id zwQC?=ONuNAwiEjU%4)wI9b~XzM^l_FDtBYc&a(Sw>p>9*=xfYIowi(BB2O^roJBBb zR^qxfK!>eZ0r3SH;Uxv2H-7!kHozrLVMkzJ!MbCl`F zj=5X+=dwUk4A{{{Z-6}Rrs$i#WtA_P2tk^sx3V+ehw zJURKxk21_NIhZUh(yS}ATW_4De$-@zR2NaG9pd;mBF2Z5%G`d|S_WKHu3&X|B=JL@ zY<6{`aPV><#B6M_R4?3YIf?gwKy_Az8VTTd%P9P>Q;LFJw;(@3dC*G){pcjh;WVv+Y|8xA*zNoGK`OZ|!otIz&|Fyi#$&Ds5$<;U0oBJMiBhjeo z8oTM$z6)vgIJ`(qRMCkqFK2~K#hNdF5B!zAF!4nFozT?`u~@z7fG7E>ChU>v!9Zxo zD|xk!5h(4#ySSfSk>o>3)O|Vm%Ke~!rDFDj9T{7cL(#FJ8=Azq#ndzf-L+P(Z z#&D5#y}&{nlP(7dZO5Dhpi`4faQH$UmXUY{-echLP~%AjI_#4=L`ZNzP_PZGS)Ite zb~jq>y52tWsYmQAyfYrqaq?&L@jE-0h=UVhkHTewOd{X`MF-?m^&^~!YfbWHmfbvw(?RVp1eO|KG}blO@f9JoUM89Gz0b)D96oH zZaoCdcH_t_&%~Mr5xI~*@U1?nHdG{?Q4sbY-cQ=p6MV%olGGC0_(>tuBCj4+{`BB@ zb=SFFx(@%iLzug|)#nw1CJ5~Pi)|;wdY^lmyGrhPkOW~{X@VPE-2e6HUAlk5k3bgP zd^;_#RY;^inOEOeQ&ycEqE|@=JIey*Vcp%~VhSTw;=H!cX zL);0SBV2<6b$sn<(wb^F4uBjI*DBiV)G<{k7tm#ku=*bnZ{ULP?95(UxT9O%2>pM=Lr$yM&g~9m+%EeCYs1@}A z*Ru3Auz9RtRd1nAq6@ihUu<*kpH~Q3iOp2HI{(57LbTe#wI$P%xU^ryesr}FzZ4JO zmvH?Q?n51tou~+{YfC0t8^oXC6y2h|#mx0zre#(BmR-Gn*3REd;0FxbDF+UrGB zqfJOqF_QSX`EjVP>nDzIL!p1g=tZHQpM45rAvsMd2%6%%o4~ z(k4QrV?vRrVjp>+&T#d~ZY{U1GVj6~Jz}F; zC6PP0sQ}ykka+eB$U#i=15|!hSU~xclnoiSVN#0vy2nk=vk|q%IB@W!O~c zEBNJVBnPp!+TIF&G{;aAc7ehQ3WG8rtw}n`IPSd+Ep!2myIkjR#HB!;Vq3&;m@bTU zi6o0P0qd;_snD!1`U<-CA2MB^RJ^IvADw5v4U13UU|6DW83SnZM$NSluV_*E;#uQv zuq>zG?AlqP+2vAFvk-q?ml3aCx;x-k4=8w)M^hb4`5b#9N8^O3?%CO`hKscz1Ogms zRW`sN+YAh&K>H%5eU`ukOzb%(mNg8-BYtW zAc^CrZ;TDb2-4^rLhkJY!?B}S5XC!d$|*6JOrh_`J!SWPNRKeS7{+SPGs=mk*=F`g zA~uq#xD)C}_QI+*D6We$o2u3XTD*7J?sPHWbML#tiIg+%gFk;w9I(R)BDt^cY1$yf za#;Tdyg~;_zDQoTcAa$+IB&1R%QQ0Llzec5xkwZNbbs9)6TKIobJB%XFp+MkzE77k zvBP55vLek5u6FC$vI@+m-S*7XWkl7S4y~ShZo7aTR8Qt#lkO2vjtHXaqG|tl)giZ+ z-VVE^Mt)hW8toHeyYEZ4PH=1-tP=x96-p0TWR9{kY~q2dF}ar#@!AZ>adar_!6-*? z>X|;Z>nBDDT^lZ^&#OvY3_y;7?TpD$GG0P#|D8^m-!&ZkZfwKV2Kaz0oPsD#MQb5B zPjI1d1{3DM$`IRB=~MJNB2o*jI;;CuJ6H@NaO;$$%+IEe25jR=K#f4lKXTiEvt-A)h&@ zRBHOUl%>Q>Uhy0NFFKovgHftsGG%vPeFM@r?B-^|(t(y(hB(t<_TtY5ZnzFhAPd&y z)0Ibb+EnNbOvDzZafzs}Fz2rK-t(Dc+)9~as6q6j>lg~Yh-=d90+Y9C(iis)3Xh!m zc()+FL})e^RIigTp2b6BmNyQIxCkY_|7{d66}$+&`X=+9_F5srNybFt4;OuQ-A9qv zC=l}Nr<9VotSF??>Xp=`)d(Dul0EmJSm?-;4>(F;|HbZ{L$TgA20X9GfL`Ee;>}mo z#R4+pMaAX$=<4*UuB%5bdITrmkMQM&)-MQPoc--3Z^hA0k!N2WWnNR*6>F8}y{5!x zt;df)JbBlzJB{rdd3O?_w-0Jzm%azq+PO&E0MjR@7;y;xew~<_v%aP~T$zsCMEMQB zFlut^ntmWl;at5XH-9?Fp)YzE(2foYxx-g8*>gH$PKB<$?li9Rnx8F- z3lMdrammAv3^c5WEd-as@gE#xjVj{N*O$(?IRg~BH!Bh(=H5Ue>DP2PpV-Q4@AoM#uf8^l zKhRz#DmD+NDzuGa*J?EW21G|w@((nE_4R4~P8;iZrFn-YUA~7xKwVgM8EJ(zy22Q;h(S?)gAe?iCMWW6#3KoT zH2n2V4nmT0jo}mWDG$c_vsu4~P*iL>Go|#JeG2N`oQ89|zZ+x&3k+a@mA~Iu;)J$0 zg1f3G;g7?)XGnW}Y?oCGgG+sllNV+vZ54!HT zU9p^R;KQr8l;~((5t)$WnnXw}0M_f9AK0J3D{1c6-#+Z^!`zW$(yfEbCZF5a{vO(L zTr_)Py~^MQJJnV$x4+Cf@!{p3ZC1GLe}ALza63x5p323A$4_0aG?if(hk$}g=Ed+M z>dSZvkD! z5D#BT+Z)wdF`?=YbG65`&kqw%zYML8M2_kR+HY}iW> zXuo93fFP@=huQNgq_OrXiN$D5GeouO6{|DhHU_E1u20J54Keg4NU%p0SEgFl?BmW~ z>=D+y;KpvV=!KYRa1#EP{4DG;dm!YJYZ5!>7*?N6rNoxQA2D)4uaVJ6E)1^U9c>I9 z1(*fEt%)9ioXbT_jmHVf)CiFZ_uT)O{x?Uh=e)bEVBy{x)kgnn@6A7GsawFy{bMno7N11uWYe>!zOMiLn3p zaVMGtAHKcEdJa}-j*A;)*bCAlVvE@M*a_wUIJ9%DQG}L2PaKLA>nF;l0uhaO$fk~k z?E^nl6A~PWa4@%MayLNs$l(YEI?WH3qL}N}$bQase1@M()bln@nB2l#MvlZxS-~WGCnvRm>;UIj^WE%E z)La>R-P4UYQPYW%C&I;%o8UlB=S+iX@th(B?7zlIYPuxeLm zh!c$K&QPdlCuBL52k1Ttk6oI2fQUg#;x^eVG@jNbyoH-s!{u0-A_rlztr~h(QdM5; z9N!cg`3osAMMyUhb`Oa2-`K7E zJC$w_ml2`MML|Xn#%LO<1M843T#UH6t2xN4UMUaO@IM8u6n!3ik;SwN=`{nImH4%< zwgW@oL9i*thZ()n5?s2YsN|E538*t0-P?j|gIH79!Z7pXZcqv8MqoJ%MZfFLFzhOWM7+)|?w7T=y}KT;F`A@pV!&)^a$mgRy} zla)#aSIUe@hh60F=o)x0v97fobo##<#{Ziww5$X0tnHApka!^2qlsdc+FiKnWYT9F z>CE3tWrHDhz|m&~FQ_VDS|qA~e?kfkHw0-5n%+)-JFy#fA}P_IDJnxn?3iGL8H$b- zJMiWBb*8sOdqoyA!BQvI3oPyJPGwy<-A%-KX+!G(O?f|OKr?cPg_b2{)BId3KH|>l z`phB0tKb-wUZ?TEg3vC09kjYl#o0Y&_+0n=crDYPO*xJUCAIkEx zPS-SVU?6NNckFb3tYYNwVU^O!C3&vcO*7E2=NJC)xfkuYH{QN^)C7V(uF4dk^#1x) zxojv49;S@U|928&-#+TcR$V>}uCk+p9CSYp-S)vPyA__4ezhSX$n{a)TxuGtFWE^q z^SyQd6^DY1Goy%;XsE;_I>p&j1x5!U9Q7#=hwpcxQPkPmA!L>$ZfTE%6c+LR5fR6d ztH)h}1qZK+_y?$jw~1qQre3bcAAAftt3CGT>zb`OzbS}nn`CbnVOH8eiDbw zy33QxBMq!9xaE>4F}vA$c)n2XDS?n1I6M?(3q5=NB-S0B2^nB-Ia_ZbRjn=7-yYI< zS@9DJ;yc1tZ!+Td%lo$k8=w-2Za=Pc0OfVk<8t+kuo1x3)KU8G z!;E;S;{oya9)SJN2_rXQ&eiHLCUk{0YPdl$wg`U3qZME&}-lh$!FMqbbr@22u*C9Lg zwyqci9KRLcXpQ}GsOxFD6bI}YV}@peeLEQUP*85?!wx^h>r^B>qHUdRo z>2!wwy+6u%AR0VzaWvMUidyYC0gT+qlmQ%UoJ2~wwa84e;1UehEAGKGyi>q1{ zfnkY2mVzDAqd4?L1teW5&S0j@by;=$DkZ^T8-ts1+WAQ2@VX%zkxWn4mtWJIak_1< z6KS-4jyk4oFtzTeu$4{w1!{P#u_g z!i+s+OR8_rbAEsJN9uLXanAj@uj_hW);nZ6SZrU%a|ou;;2bUjaZSXR`g(2%|C7*WtkSRiDTTiQ7`xUPDUzo! zC-;@0*<0-eAmyUHgaV)nK*SN#6E5YCk8Wo102K&P_|Q`1x&~IjRQeUmlLUjSchq%X zYyXJ$Yc?TekkqoXZNhe1M@^rBN#5WOtE>l6qSZ=iCjUAQrqfgFlT)U~;9sP9zUb$U zfh{>FH7E}rbT@j#%7kCRYLR|e@!r$y4U&O#+7*5Hw`3DUjXvRmh+YH&`#Nsz*RzC1 z8GLr0e{Em^C1Iu0Uxl>PA^3E`vJVI@S+V`|7f; zD90K_)8a+J!{?~Bd~0~9?jHx4*9Ex!;!>_VTUbuivs8W(zPQW5i1ixvpk0EpN>Lu> zeBc>5KpoCT_eMdhXyBK+q(uR&CsCplbNkJ^=?ykz)3l=XKHJ*G|DHU5MJ@kaGE6^a zoFyj4jGl{sS{_-WevLnw$NIw6(Sm>*dcvK7moYSM37I!!@TNyAB^MYwbd9-tOfH1c z_!YajjGv@os+9G3nx=BDbsMZk4pdwW@(N3L zdul;;>+fZ8=bxmf1Kzig0c|cjJ0oEJ9mYdotf3KQ`#)bgaZc{S<85DuVKKacz*wi- zOHDRwh|z&@_(Lr{3$f&@Sd)MQC-Wp9)@cd(O^quz`B9My zxtoEBR>(kC9Wm;UKxnnXzyfwmI1m^Qm_U3>Oq@<9P0+a;5prerxegiASq8T|cWr5r zzPUK`s5Z!|x*``uobAVrMt|n~&_qmVP=HpkKBFvO8Mrn_>96Tf#-hkxpcVA|trp0G zdd-&_LNJ~G4NOXxPs`~g;ul_&y$Dn_918?$q_62M*)ATIH);F`Gp!4pvwl^7jnbp} zrEpL&MB4vzX^k|U>S>;u10D33=2Srh%ByOW zMMt^FR3=sWHYk2xk(EXS&zqQlB@P{i;s2S{OaufCseV&YYr0!$-)k)IoGD_;3A0w>iK}Nw{#G z1-q&T=s}t8kxA^bnfV`yQWtqSfS^nC6d-kx==`& zgoI!T`(KpNVxI-w6?sr6@k==S?tpvIp~F`~*S4I`c4#%7G`w~{Xa|jM+RLsk!A7B` z7q{$sD!$Ft52=bBb)L!(>}Z6JNe8U)e!zwamG7GEXcNwCKS?nw@4+HHv~B`9SRH(uh94ViRo{yVOJUhS~9; zNL0spaI0mo84>^zhx*6h4`_kudbpQ)+A!h2RyB78*B%v=JE+Bd9tMRAFM zPE#xGCri>~q(S%yV8H#bRcZ$_s_5kG@{sL~7s2MT*Ncx=g=b;x3l&+PtZ9+*(~=#^jHNeW1^!KnOcRB>(;_?CmZj&%+DuB765t znoofucn?~bnd8Uqsapq|kLt!0q;dUL5#LV7ny!=tbcbh!-5OFs1t42MvtiRRs`V?q za=D~%*{JitI9_c*GU%x4+|9mjI#^2_f)Y%(%pTO~(>Km73hS)^N7oC51VE>(Cpvt? zKFLHTFpBn$V{^bUQRodI{DZ2SBM0@2)c)Rk#Rl5N& zneF#h&yJjVe+A2GxCT$gt|qqE-B&~~Y@whOL;r<0y*|kW=DJSFQI<TP>W7 z+*p=3%CS)y(-It)A6t-j=@@QfnQ@1G^OWyub_IeG0lYfvy8rn@LS!Hp*Ioi=(iO}% z)iS5Z%yE9hovrXKU$h-TzX_t;(y~=b<3qkEH3=CC3E&L z_AJT+vG)YoN4F}@9(O7#Mdtf{E#0&0D6KnxN4!?grh{Aii^v4w+=o>JB7UD(yIVHQiofIYJizva0$p+^@WZp19d$ss2(*`Lx|-)Mtc*)N(+wD*;E#sS-V(&H-U-}VbG zW7j8vg`0rj05Uz@+2g&eNHd`+?E=9VGbDzc(A9FkNaaCaIM*tgrRDyKuqJ6jQ z#OcrvcbAKvJ#0a26*<(~xp;kpLr@3R9tMy;6kZ?v%y!~IT0g4l0Gdt48+Y`nSAXg1 z2NUKl!5E)=b339SaZBxvftjTTe%HZJDtPY0r*hscySX>J5)9BYb?syF2T~J5VfB`r z&J3hnaJog7-Kdb@caX_dgWLeZRCOm$9YehJ(A!6~2ygpxtC`#2>z)5$=wgQ->h4$| zWu`Rv@eh2zLUMO($e2E$AnP+{w%%z1_Ip1cYL&z?<3^mKRs^0tnOW=9^7ZXv@5c{r z*bs$6+S|cTZoYS6a6hoSb@BP^Q*weXeSz}5PUvHd*IwmXW=x2wJ`Y&3ad+kQ&w;@* zjZ)fKIU)8I^D>wBp%)%%$$j}LFoy$I*x3m?*Gsf8jYiZ)m2cK3)m6fOUWD;l$2h%i zO7k3uOC*4^RHj3M`65TNXB9^>EccrbEboL1=J54J3j1l{+f*v&t306bohSrE;q-dy zhahfP9~rs*SM&Y{m5i+cht)j;vKP>8Xgv>AYNZRB21IFhlCqJTy{4rK>+1x;`WxkPt393GG;HmQGkXx$rP?ImA7||g6)h$FQ&dH{+%f$ zau&$N!OD#93l{zz*UpLTu6&lCAIbwRCD4~hH^p}QDGf-_JS>}x6l4_MsMsoI~!HskYI#rOpY`E9IqTw zSJ+K2@c--<{uzY*PSsqs9$g`fqG@I3Q4&GY^~g{h_Vn`{=EnPEzh*l>&skzcW^@n_ z?+yt6GvBrS&@E|rn^p!`Dfg9pFbk_00Pz=&8ttzjzwsj&=H4KAo$r%$@1cv^TN_yZ z+Cf*=1@o<-`}dM9bLge^IM5aRpQ8EAd^3qf zaf?$pVfGdAyuIuz!o%4fdgK4#Mto~0>nw<1 zC5eiP``?pmJqJ|ITr0Q--w=LUHWhUxBVM|KwVLLmJmZSs-C1oq`yGC+z)kM9Cd7Gh z*oNyxx(4s}Jwb1bG1Zvg=dO|q)xSe!XSCebSi9Mx&*gxW(qOr{$*QEg)~gtwbm{3M z;%AWz-*sBn{Qab8Th^1w;Ai&igHYBQn`OQGZ$Q4DhWp>fw1!=^wOZ_i2_Yx?IAjvi zcyC$Q=l=j_9+7fPVDi6bcccYw3yK8aw`8mk4YzmiF1#iKT5+Dfl% z^%E$-BgfM2gg_tNrZ^i z3n>wNyKD-4uDPc;abY27z+uD^-Vc4P4l@c6E+J|F5F`XViL1IK!2)_zLZdyan|G%A zJ`ik>JkKi^Hv1*wLTrCxs^dE;>r20shA689ZR?U-BJ7DdrY(WB_iIchQn+(sAg@er=pZeph59etKK!4mWMoD{n?IZodXsy5s zO%7SFA!a}09cqV-If9|0F%yGK9{EA|ebVDfL=O-0ybgF6S@2EG`uHO{JxO!){{W32 zy12{uy9jr`vol_`m*jG9?vJmvX+jiUn_6lh@7yd(TS~oI+z%7MS=*@ns3MX|9j+k; zpkxp%{vvI_sY_JNNhPBHi@NvEniP@bFs9JxPo%usLbM`kcf#@q2mPbPUr_SM5 z6<@2L)@r;PhCTZ(t0R5?MmptedcfC-Q=<#)R34jtF^MN`@1lG>qqbb0OSVYYf!FBH z&TJ-r9a_2>7NKHYZxyy-3W_}LzfNw`2rWffpze6OvJdj zCM8zk|K!n7U)?hrne8Kh<{B#dmxIfW1n4L%4a%nIXilwVnSg@1dW6E!h-QvSj6(`8 z_t!Gvi+em4K9?MZh`W<^RAGJI3{=xEf-H0%{dAs~iChZK91A6D1It-BN8vUu?O2s3CM zF*aaUF-2VbTYatlZNBJ~!RX1qrGJi)-$ynyKX4wlt`1B?ma8NHru+xBIz;ss2|@2x^G@n+i#B19n2oSlT)tf z)Mghtx#UilO)H&ie}ve^atZ@Jx#;zKffMGdScqL~cs1Xk+T3Nb*n{93P5j#ntsla` zjF8?_wMX6$GRyqlE~zI;5Eq?GENTqk(9O2hYMa|{Lx);1(c?@4LJ2!-zdsiu^14DX z$rl-_Cq-(cwlQ>#+NER@H)et(IATh(7%G1O4mA@#$ql>eQu3AhnKEh*AOmo8ugl<{ zHk#!bfZrV*LJjZJ-Y$N0Y}Iez&XF$i82(30@%;n#KU4tx25_XSw?EDPruob3+6fOZ zrazf$oH}@eCd6fLLVd*yK2gTd;w}d7)r%3RAWv_^_j{X?xRnI{OiQ{D{E_m4%8RmPR_{N9jReaBbLOO;7L)KJ zni&}%!lJqC^E@uD$zj%+rq=v_z`ZbmP4%aSg8+I)dG5Agjb8|MlSTb<4mBBysbo^h zQypnG-&n!NMj=Z4QsR23Ck-|H(rhhUlt#o^7w59Ebn*wW^dfjo3(BsJpCe-3I+ZWg}z@ z7pJa~S5st7cupgBtaLbr;K3p`Mpn9-!AoXvKy%pOS}*YjM$!MYB3AP9o!LvF&sap@ z>k=*v&*IlQ0mBPB@aOw6oeL~yYb#rE&iQtRNhEtk;OFtxb}W|hJPV_AUZvfvmDISwuH zO=d%*b(kI1-G~1VP?bzW5`R{FKoh-*dy}6aq)P|cFpM@S4;YwJ^&-G79@g+ls3jD~ z50Q@CrHJJSad({k*}-Na0|`mMVfo$NLarlJOf5=8v^p1!eHceV{&NZ}C8z{z4M#Q9 zBkbC*_A|g%u++Ig=<6Mw8_^~A*c{p%L!-o+BP`sj2{SbAHyPFoYLeb`{c)IHrOGw) z^;;Ls{uleDfexxD-7}R_Zjpkm!-n= zxp?xuXHCSta3m@RkOOIk74+=wI_|=DyOBJ_nCjW6TYOF)JW2*T8^>7$KD}jvNSlMQ(ZdV2bVMTz?>!iqI>xEDq8s6+0{NG;aLf!!UJHnIqx}r(Om;Ngf_#(gy z%h;LkDnH>a{_wRH(~d|gL|2n`S7Xy7cd=Y#+4=9htj|eX$JG3j7@otE9P_cf5>hi) zxQxsw_?PREr8`+-iDf#znI5P(;c`Ww)poHw}$=y^C$@8;m& z{b>b3CT6LdU-FLD#PV;d?-2(Kk{s>ZG7`4uI@eRS2m0R|4!{9YreOTLUF6-WGiD{% zl1~o%OuQlt{5(~4DrcI)lF<5ikTZWNb$gXXVn^TerLjOMv*rnEk;_TRTlvpJKc&gf zAF#G9g*`f(CTduYGx8(|Dl6)^a{jYpmNlM|uUVO+VmP?<>yst+=6uZE>xaNBKJ^1} zIZ09+C%jyAEXmjJc(kr(Z}J`DMfU3iuDWv8eMYa6nIpfnXHUl4^}(L}St3Hgiji{# zWreMai(n8>tu<%P_W?e;pdY4FDOWfd)5Kfm&pY` zA3G@nH^EI$#j~@$puOw_Tr${fO?B4UYk1N>`jAx7!qv7z|9r=PVNw(~Swb%^QVt=- z^6EMe-m0>sd>w3Vq`1ZRGBj^K&uB zm}{oju~c@kOIa*=9*}-aU}@H)*z!@L!8+r47Kf)+ttu!oJZzkNcX7poA-0buu(ywidr_<57N{$7HUh)?~lBP3|2$ zYba9%vORe8lgi}Z4M^;E(`*8Z&`gAd+Km39lE^M;nP}cMXZ2HBX*38}l%{USo2S+V zmK4jpW_rY+XRj-s9ZJ#=h#ElDaNdbmt-z3CIDoRy$4}HU^Nzti5q}}uD~R)-`4NL< zO@%g_*v!DouAX+CgjUMeZrM<2c)ULtSC5I!9q7 z;78xvB-yTAJS!Zou64)Hnr-0WC8RM)HXlCOO` zM=)YDX7WW&hhBO%Nj2d0R2&}pI#eyepGnJ=@81?eyzEATQGJM~DohUEM|fYl2%U2b z>Fyplv9ZH);+XOLD`5YRB1`@2E3LLs2)E}ejS64{Md6H@B1 z7vg^jcs}0;mo~$y_@fFVR|FsVKY56yy~#U8vfw1h0LZ$m*jqi^iI%Ra67tTEl9NlM zS=@3HMj=_~wE*h&I}XR(qNo(~T-s^s;_r{5Z~Agxj??9)9;P`U!h0eHsH`Jt&qY{m zt}9H%f78n}oT6S%wj?r+%C$Bx8T`b&v1RG@N77$y2Fmgo%KrDPzMsYZiL+v9jaZCt zL&fKv2%j?MQ-4Y(2uwTx>J9Q21$Yka)D_`x>IyPl?X^E+O^M7`}4*5f! zgY7j=^?I1r+ETWMVrl4&5x?5G1_2u==Fdda8dn&P+W(wk`vPrBw5u=g#@2{UB7gQ_ zuSTWL@+0&QK*-v3Zv7?{e?(=CIu=YQS)r$AFpuTb=k)9XQMEO}Y^Ho%QQKo$x->uk z4@f&k_A~}$qquIIKjz|;;G~4zvWnFb80H*F21{=BBSv{f3PB|7eaZx`brHlVj(z_l zj{uLMdGThuaG!+tt%vZF5b1BnDfbjJKEJPv^SGx&Wq;)85!;AxAgOI!YBc$#nQn^2 zxymw3%6h!lT5j5nRO%_%TdRTk; zTcUsVp{%%);3z*ZA(Z>o*XYukSgB`Of`dTbJVkezAbTe#HXq6JKntnuA+CWrAWz=+ z_h7SJ!&r%VnYBZMMc0{JQCJYFvet6FY5L8nkGYc(UC-f=g#5WcmmptdbE3yjFq!_? zr_+9~9s@Gl*ev`4zgQH#(%Nwp`CNPlielwnI$t>A-62-IuS^Dlol45DC() z_ecL(SeYEH`TiLWQ>y({wM^^mi180WP%#=ub?gjZoo-FwaS$Co9+Pe1^5232Bt&EU zE|nSBd;0$6(Cp#i#y-P|^+I1}nR}B#NU;&!;9y6mwq;quwnyq11t20?4gceY4}5PsnA08h?5JlMbTOdY@GM@+@#Dz(looM-UZc-cwxfTO<=mA7!uOy^INM>dUadL0ht zz9}=BC1^1EhN)6F+`_^{!SYhxXP7ps2c?M^dapel;1qA)*t+Q9m5!D}|J~rVRRs&x zbTAhr&8M5?!Jm|b#{$e0MLmjS?&Pz7PI4H-$~v7COH%gJ6|8v4DZ>fL-%c~D*@E9N z7)7CnK?uaLmZuumt9$>V{os((g|=(c&DzES+Pz%^tL3)>_^SR1L>`x06HUh3t--H1 zq05$dUbIi$#r_hLZ~_{_FOC@6R4 zlTOMECvvv=&bvN%-1<*3Jn>SS; zvtzKSs=iR>(zmKtz(icoynw12(c=ujnd;8KQ>@fi=C2GZO*|2)P~2@7#Z)!Usc372 zas$d1-@Cxn^F;Y+o~{=bX0)p>e1Ma}QQdorE<2Cy9!HLq0V=}+FEl7O;5pdTcM8m2 zWhM=1=4U6-4xZrwv28qIao7C;qW1R8Af_sAIC_9pBTKPIGE*)b!&cclM8|uR7t;YV zCIvln1S7_A&oW0=S~`~){W-wbfA0ImMB*ps6<`1c(EkS|6G7Wkv-Hl?s`W4r!pb!D z8?}GHrZH9PFWlr1yI29Xj}DZ3Ab?aYjSc*>jeXCG-LFXvLye5?ezsKtYLj}9`xjI7 zD(lA0u7STBvxS%HOX7siNFG302Ei{rBu++rf24~R=;~u4vFO1Sruc|_^Zw&_)S>2= zI+^*b{{!STfuBzKGbC=a`h9rzB%abV8)b9Fuq{(~*TyX=)Rq8Js`II-vW|DI-&2Hy zR=0IIITpY{6uiwtW^sGscU!v+*7biy+}UFOCZ-~68=)@ z+f+?t;I?eD@PMsi-$4fnH_jsu75go&g)oUg;z^V9+*fr}@jEzYRN6-bebd;~CoH=j z0j#kSw6}M<+|R+9U1bAcqh^QbYUc#m+iE;!-=nJPLVTQrw?}bUNNZ2fSuzK)usn=E z3f(1LrmjaEfU1~Z$iJG-_T_Jv+P6Azq2i*eK$Ie878WfY&EDkxKj5+C;2b{vkh2k) zIyy4A?Jl0SKb_R@DQ;+B!AIF(hCCDnp{!uC-IR7{z0mAgU>a-LpeT~L!i=7 z{KALij-#mcxi|>?O@DB(<;4Boq)RE(7$ZX@r!Wq|rakut^%ipoEy!Ad6{R`0gny^gmgY-br9H@uqw3fh^ z!X9iAuui&fO<|&Kl}`b0!S^xMNB@ z^f%~r}<{? z#pwAdIfU>)_4}3hUT;dwG5kcO*pshKBK#QSc~LFv?=twazbh&%M#+h}@nH|QZCZT& zfACfHM^D(aVe=XCGaHn0f^3S~8E+=u5PY8v@>$C2g`SP6YU8keRo5`kxw%}`5(CWv z-Aa~n{sWSx*VUsxx2ZsE@j0gG7oUlWkFP}NgWRm1))hql{LDBsL}WNiB2ywq_ftMU zc=+T=`ZV$76Ao2BKcKlGjXj_Hsm>oFk=Gvz;zKaiM$r0iIeIaZG4zK#9l4{xwnLpy zQ0C4d6G6I2CKOl{r@_tAD&v6kzg{=WM) zpEY_6Q7N%c7ncBUkA;-j4ZPQ2i8mdTaXwBsph}zn+@75!p zJOJzEEPS1m!KO7{`1;Ds(#234E!HKa_;>Lq4)f5r=e@zag=+`@3!nVV8x|$2x~-Bf z2NYwlgP6dB;WkHPqE zW3hN!lcBQwA9Kf4_5$bmzgYf^rWfC3OxD&F1vQDYUI;oN@Ydbj=vHuWVA$tF%o!AJ zbFBfh$&j_F8ajUQH6$dVRzzwO*%DV=3DulyY7}zZ=&rJRDw)q}th+3(Xp|1S&f94) zA@u?x3ck45v-&sQ`KlURS9I0>TY-Vaedg|oy4CD*Y790}64Mv?Q&q2#Xv;j!ujXEJ z&br1nUc%NJPrzj_l)4rEOhe=*GkCx~b0ypK2cM;<7m7h1wRBUQt#o4ds3I2?by^2w zrR8_PP|JR58D8eHvf!xlT`b9#<%zj!^202(uW8riO&pJq#7V9*;!6glf>vqv8}Ca^bg20xXY{e;b${h#vTv+So?Y=>aG_pRISL(RWWUNdCIJz5HlTz>XPquqNT@}FXU zv9OUvDZP@)u{j*!En2(n9OQ(1aJzk6{OZe9ZkjJvbYuNRqYu;%={?TU;&iUHfIi9K zNXL#%Bk1Yg=6W8|cNoOUy;&6tVU5;1Ac+4K2kX~R>!{VTtVNa?><0Oh)PKXj!tHIW z1Bd^a*?Rd(w}NZu>h8BjwgRl`+?L~PzrqJatK!{NoYHuwXD71e&|k}3(>B$x0w)|- zZc!J#wfM7wof3&VE}`a1B2>eDwT zAWhU?byx3!SQ}XO!Am5C@|BL~kTooVjCd`nY*;7Y9Dm9*lB@U72`V2dxgdgm)6&S#I!A0@J(C!e+VnDf#A@Am z8~CZJ6EF|$8w1($Tbm=oy|-ItH5&qR)ENe_GP_$|$89GztXWxR%B3D2U@PQEOju^~ zlW^1MTMe(k!d*GknT&=P;y1y!7oq|#pd;ZWUIu8#w3b{;PdvNuSVV)U@H=~M!W?P0 zqtY|Yn!1yxB0&cc4$KdOHqYz+WK8f0SaLx~PpZm~X5f!>*2I>n{?`V4eaz4y+Pn zyG%0if}?uQheev%=#%a-nAFqY0A}ukeh|aRsfK(GPYvXbgXw z*(Eie23@Fp`}{_}9OXHIfhm^Um#jv^I6H%2=@axGfqz&Qg%){+@{}fO9H!c0#?r z$1bEjFfAQneW-4-_ji?`_)M?2@V9SCjycyHrL)@e$)H*|2$VLKevADNJUiPDP`$a| ze%UgcC3++dR-u}+Oe|B`MCH?1KXyh!%K)GG4-#SRphQf;*SY_&y4EoxA`dy%aw_G~ zK92;eraqy?74TaVRW^5of3TWF4%R&SNEEI8^_equLOEX)`~`+s|670It-9Q5lX_h% z6WbJ-#^Xb*!zfkniIv@|xQdzkE@VXZKGIsez!z((^0M0ewfzu+paEV-ZoI8-#@5{Z zs0{nrQM^O2G9Ije2^Rfih?UWs^u2 z35q4|Tt7~nH+R^fYq$wwQ>bA?-QvliYCfK5 z|6n$&xYb)d}>-5b;66IJf9 zJy`*!mJsq!Dikdj|Lap$HBrEzt+X3`cHAB^KSf|N9~;R&D(jk^rv6>uZL0js0?j)M z?gDN9wwr3^+*^bnRtOS!(7Rh^RP^EjmN%_SqJGgSE!1T3vlCd5yHwOramNtQB0u2q@qOq!d)N&;OP++PbL*tS+jM4Zu}6ODg83>E`1`4JPsKPQL~#v8p^%l|Lrg!@waLA z<*(zcS8E?Yyuk$%gNbc~ttp1L`C5Idrq869slF4sL>apGDZj>InDAU%?Nbqur#i>! z9Y66z|CI*FoIdEg9P(W4&&Q&dc&^)_V*-oe!c_L)gqlZkE%z-%#c>>l&iYI`eWw~s z1bvO3MrV}*Ay70zf1Kr}c)_e)n2l(_Rm}$lLe%BngfTI+|xZO z`(kpc?_E)RP9S@5i^0Enyt5RcBV?X!om;Kri)xKH3~VX8QiN08{~VsZP@r=L9sByv zyl^A7{tmv?V=b4GFaPiZ8b=1lY0!Q!&^{YK=UK1-ynLtcRjX}oudJTYc35fu!}}5b zAJ_za)n=p61&44-UJ-^?=p0q@fF;0m z#B$vTlcrt?@<_|J1l9xH?gP~QNb_-?03$QnO{qD*MSxqN8@X5`!T3Ex!8a~I41hHtYkO@cwt{j{9V-+}{; zCrtX47c5dA7&9MkgBh0OoZv-|rxWGQHgZA5Y7-UO>+sW1^p@qRt(LH(F-@S?S5cUk zbK6|Gl(>zMmL?sctX7^G4u}p^4qLl%#T;t_S>Md1Qd{`P>>Mt=RPrelk3Fp3e{pk< zuNz!r+awbun31Gqf=XE%(hJN$XA8wXhlm{^1;`1#415FB4*Er&uB_9l14bG1H3AqhryS)8NrUy_t+nKX> z(g<|9`s$3f2sP|I#rHR#L)c}`!)Hz z>Ibh}l2YN1zbmO1iQz&YpZi__pP+wtAg1;b3DVb1E22jm1UmbtM6H6ZUrk+792v(Y zx~jd));1H3q;ij(H4^_>5i1523Qk1{cE0Z#^An@DEFM0l%k> zl$Td? z)X~rK1q*S`7HP3!d8W!YS?`8SK24{Si{EJ=6DPsRTVjO`6M0x;VwMnfPhEr31cW$S zb$I_iDkaG=o3Y~i?cyh&GC)`a=V&+C_tE!72J2YMvnpE?uOTtB zo#;;@{2=L0kBJ*FM+R_R0(g<+Ps>h?VcNW*DT;H6lgZU*sP9`aFDBC8ce$3#6hj!BYdWsRy{%9mXldV0M% zYyngHw|B+H0!V$2vdPAgD)c8`Jyi(b-sn21dLhhduwxT+M{|9d8TjkHM#5vcvR&u$ z*WOtqH6@WN2gHlrXR=ogdLl%t8&8551t0w0MFV%qw>ns1qW^6isGk&G{FV*U+dT$H zS<%u$Vn0bngW}vD+s7dwE&?$bcjrXZUUElAi0fr%1alYb(~y+AQXW`g8XTC2yI23x zZlYMi3nAg*MUI{XDR4+HaOKNCvQmY{fGM1epBd@=B#n`)ug&2pN?Ev~VlQK$k~w?C z=C+ujI}eYlJcRlFo%3?~5a)tf1@ht@oh?gdr5#TI$y=*8=0TL7g!I5lyPXwofLO$*HcPd5yt z%9ErCISy9T0BI|yK7Kz^qDkdD%crQS^E#Mgh6D1syLS{%w`O<^M|MkVLVQJ%<`V#p z`3HfqEj7~BiAnli3k_=>@)yEsIRTzg-~7ezwryZfuNLy5jCgoJd8`F(TiJ=rB^_Ps z{kY^PT6#b^@`Rf$aS}mZ&=ywcYe0AoZJKyk=H8HuHI&xTLS1)|6fwm7+OSudIKREy z-ERz>nhMUSo_l)H&OM;dJ)~Q%vW8>ElZl_87C%)g1WsAB4cGY36OT? z#*!Uxwy(D%sub^Q!wYF%2%K+m|?7>5)r&qw}!wj4a&SVykyiYAx11e{FK5$(6v(j zgNV|W`hw+oH(#~mG!VLVQ#q%KP5{X*$~@A(877GEZAZGf@PO|qn%SvMM$+g#8}q-W zUd6>lk2Qik(>YnAxce*iX7#g!O~|!Z@RNvcNC-Q6+s>$kr{8&FcY%QVS~a23-igXl z9g?*+iF)qjaLg-lN3@FKp3$|v=@0oRRX;ms%@ggAM0{Cajyzm`Zf^0ci$NCLa2hTo z*W_4`!9}by{~21_Obp|=@^2*r^&RxW;%bb8IC9vbqS4MlZ_m0I5--5YfIBIdWA1p4 zB-Bn8)!=JqE5D9WB3Ij#G6hE@LreETzOciY{G&l6-(^1#({*GOhc4_0ib4{P>!R<4 zTp_<1FqcMum$%YgT?yMg5W_jRZDd!o+ zxvU{>J1%IgRw|HPm_I>{6h-COTQ`I20824N1$u7&UJC@jw}F=*9-94(pRL3wzIasl z@Yq`*n&8iLr;slkPYcYx%g!CA@1pa>rtYzySHYL82zwmIXTN zrp*`69>(NVbql40tlXbZp>Iv3`9*$`vLt{8V&{84ZY#_oqTJ58jz#7?j(6y+4O7lu zZS8yH$@I~ki>AZ~u#L|*YJX_%?&{;fC2WH8W|Y|Bs{O|mhnFJwiN{D21=B(kd_M@C z;ENqu*MU8&sL?Q3)jxl=QS)3{rC1x@hc?Xf57AZ1Wlgx-3OU9DQYhPNtUPP9NQWImTC>g|%rEDQ%k|M7yLiHWr zfAc%P=bUq0_jTXr%=4V(?tkpRDkGtFWjgMdS5JPJw^u`bc#mjcjTvuhDzE>`rCZK7 zoJkmyfrtC8P>c|}Qi1oko21Lme(b56X@6S%w0rTSlCP6xnV+hcV} zRW|gPZ|^IRF1lq-x=f`~4qai?-jw&xo)HVuRLU|`f;?xs-`p;Au+YF05t-vVTp}e6 zi#cq;HF{!(^pr#|FiEvk&yWV%{4d9ji`18SsR-VlA%TlL_N5frLw#kn<5SzP> zac;`f$>AVhIR09k2DI7u`RRQAw#Bk3*M=KOfmZw!r1A4_@YX$olFa*EDlOmkiWnh{ z?bPACtAs)sqhf%-8jEdotQNTA-MsSBIafBBm9FH zg*;oawX}2KpJYV;IgY1sME^Ecz*re{M|X)scZEnGn}m@`0&9pondvXtGm>d<;K*4-41QNloFOojY5ej;bnl! zN_XcS(!;e==Q!{bQbkRtrE}|7XrQ<1Mfa{NM)u0X$%n@<`<3zgGr{P*7daNZ1`s{>+e|T;PCw&EJQ>AGV%r1R(L_!yI zFiYDGjPI-yG;}jx|HsE%8UIA7+01?ip*)VWRfi>MeNQk!6oz_*Nsx`f6bQeKHI!rD z!8ErTh1e0Sr+&;I9Y%u7A8=!1NO1PKt=qoAw;pO@+$Vai{3)62_GhE&HGelwe=XO0k?^{?kj^gvwPq23FmCQ~=}P<*dk z?m5V)k~9ucj*W-BSHqkjgp~M@2#06EXN2aj>9V zv?D7ph5H=kAbiV4G0>`jUt(z;F_L{-o7ruxUVwbvv9OS)*N1Ay)k>D@eFHUnaqZfo zp9cF>Dazl*)3-{{>4iUU|A!!!kJBiZ8N|afVcx&M@xzXuEy_+y!=TPXTpxN9|d zV0}LvL}dz|xI~DngN;xWgQYfQH10vdKCZt2kW}2&zHK++!OYQfJ{KnVAA~?XD#MhS zl-?hnbJxXsP251L@f{V?Wl)B9$Jh^c#H88>s27M;sdb=lKdL(9YTFw$#$D)k1HkVk zn~D4r+zL+5wv@LE%IUSn>V+(o1fRpGBw9?j_3b%ZrL1mI(1FY`vX*(?&+^RCovTK2 zq!~b{O}R~*|L9RbH6p7k0kH^-eX^=UM>7raksE&Ay|7M#g7=kUJ5od{c2DXe$X>Um zyEGQ3p%5U!iC5r=SBBWs z#81k2F5*<5=ya|9r@bnGb5Tm)@w6;?U5ZmxsqLaZTG7W6K{<$=Hk-<}QJ3dc7aRFb zMX!_J;Ys^>p9-dk-@t5f~miaSxbJ{dSE3bo6yOgy-3U{d@jVh5YSQPWPJq!%D zo4OR17t%^SY2o^J$G$cr`W#R)jWWVpA&WD4x;K#IP@pXgmCSglfgye+u*<6Bl81Qq zfW3?xZ?~puuq6gZa3p0%K5I38gK`i$<<@488;On5q@2`}mM&G>iV?zPXdCzzjk<|p zGUjtHbpd6vTnT#3@Ur5h+|4A|w-rEG<>Ubs1d06lTKYo!&+Dcjj1X@hzdE^nV*o;j zoePZB0Wk1KV@UGFGFGxMVFRYJz9U7tI>UG7L+x3+4IMGr^&eXR8etSo^v|fTow`)4 zGJ}B#8g-;X2QTVwxS0$>{hwCNs_pC@^Iie&WkQ(9uIYU9F+U%&T>Kv3iR>pxq1G1uf@;YLe7ZSH%D!vxH?Y7?w&qiD(if0HQ}INa zlIQpNtuSyGi}z$*j#w_Qe$si;eJTuE{hj4VLDnCYjA6+t)&)wpTx$FOAh9pb1{0}) z502<#*g!1$2V>AX_T9$=;;><K7nUgj3$EcEnS4Ny||$kf_Mtf%lHLUCeAH#McX&E`E#+;n@PU zNIoxLrlnQBbsn+EZk>@bldnWM!27IfV?o|%ba%0h#14yKh<|Sx$QW@NedqwcueUH| zd92f?LeHKeClj!HS4*mMBh;{rSZTI37&t=)Tr= zh?cZ8R^AwE_7W!v`ex!oy5KnRNdTXRj!0kWGft8 z7%%7~XvyV!)o9IN)K$O-DHCSJusp-w`{^+%GwD-VAxq{|TaJP7BEqc#yJQ`IXemDn zSXiuNXZg-r)EaIeIvgyQUjKT|%?l3sW2Re^ z5p2yp4I*Lblp_aD#STlf3hXO$lTi@@K~QcU+)96Lh=>TI;g48Jy+&3O5~ z{Gm;51aLQF+G}4dc%O;AvI!d9o<(nTLY{R`9s<5$M(|}MMMd-kq4|KikUmdpmMGO28M%)i@rUyJ9&qB}6u{sip{fuTsn^PHxS{hadO zT6Jt&KWlAe!U=4})+8g9G4Am+&Qi~exod(b=U29Dx@RcB>EN@Eoz`ZpHYtF?0dhp? zOfXM--y;RZIz_x_ow+_qt=oR%E3lBn!jFHMf1p6;iTYT>y;agnzZL)quTvGYj&Av1 zKM1DJ+@R>*osUjWf`=vF)I{?qO^oJI+h2w*&32vwH|D+0X`-XxKC+)&AE%qS=~<)ANt0jmok5^gNMb{YK?vD zawA{m26?uMyow$_40;oJ!@(FL|3FdVCIf-viy!rV{|D@7@-BdAr~yh7P5J^3xm#}i z0*cNVaJc#MAY;dFgO4UXtmqf&g)HfhZr_{h%>O`e)Hr*1`tL0624DegxR%WX{~P^6 Z{<`4h? literal 0 HcmV?d00001 diff --git a/exercises/6.1/src/myworkcell_core/src/test/utest.cpp b/exercises/6.1/src/myworkcell_core/src/test/utest.cpp index 0e8cbed62..193469459 100644 --- a/exercises/6.1/src/myworkcell_core/src/test/utest.cpp +++ b/exercises/6.1/src/myworkcell_core/src/test/utest.cpp @@ -4,8 +4,9 @@ fake_ar_publisher::ARMarkerConstPtr test_msg_; -TEST(TestSuite, myworkcell_core_framework){ - ASSERT_TRUE(true); +TEST(TestSuite, myworkcell_core_framework) +{ + ASSERT_TRUE(true); } void testCallback(const fake_ar_publisher::ARMarkerConstPtr &msg) @@ -13,7 +14,8 @@ void testCallback(const fake_ar_publisher::ARMarkerConstPtr &msg) test_msg_ = msg; } -TEST(TestSuite, myworkcell_core_fake_ar_pub_ref_frame){ +TEST(TestSuite, myworkcell_core_fake_ar_pub_ref_frame) +{ ros::NodeHandle nh; ros::Subscriber sub = nh.subscribe("/ar_pose_marker", 1, &testCallback); @@ -22,14 +24,15 @@ TEST(TestSuite, myworkcell_core_fake_ar_pub_ref_frame){ EXPECT_EQ(test_msg_->header.frame_id, "camera_frame"); } -int main(int argc, char **argv){ - testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "MyWorkcellCoreTest"); +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "MyWorkcellCoreTest"); - ros::AsyncSpinner spinner(1); - spinner.start(); - int ret = RUN_ALL_TESTS(); - spinner.stop(); - ros::shutdown(); - return ret; + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; } diff --git a/gh_pages/_source/session5/Advanced-Descartes-Path-Planning.md b/gh_pages/_source/session5/Advanced-Descartes-Path-Planning.md index 3a94bd304..98c006841 100644 --- a/gh_pages/_source/session5/Advanced-Descartes-Path-Planning.md +++ b/gh_pages/_source/session5/Advanced-Descartes-Path-Planning.md @@ -27,18 +27,18 @@ In this exercise, you will add two new nodes, two xacro, and config file to your ## Scan-N-Plan Application: Guidance In the interest of time, we've included several files: 1. The first is a template node `adv_descartes_node.cpp` where most of the exercise is spent creating the complicated trajectory for deburring a complicated part. - 1. The second node `adv_myworkcell_node.cpp` which is a duplicate of the `myworkcell_node.cpp` where it calls a service within the `adv_descartes_node.cpp`. + 1. The second node, `adv_myworkcell_node.cpp`, is a duplicate of the `myworkcell_node.cpp` that has been updated to call the `adv_plan_path` service provided by `adv_descartes_node.cpp`. 1. The config file `puzzle_bent.csv` which contains the path relative to the part coordinate system. 1. The two xacro files `puzzle_mount.xacro` and `grinder.xacro` which are used to update the urdf/xacro `workcell.xacro` file. Left to you are the details of: 1. Updating the workcell.xacro file to include the two new xacro files. - 1. Define a new move group in your moveit_config package called "puzzle". + 1. Updating the moveit_config package to define a new Planning Group for this exercise, including the new end-effector links. 1. Defining a series of Cartesian poses that comprise a robot “path”. 1. Translating those paths into something Descartes can understand. ### Setup workspace - 1. If have not went through sessions 1-4, copy the src directory from exercise 4.1. Otherwise move to the next step. + 1. This exercise uses the same workspace from the Basic Training course. If you don't have this workspace (completed through Exercise 4.1), copy the completed reference code and pull in other required dependencies as shown below. Otherwise move to the next step. ```bash mkdir ~/catkin_ws @@ -68,7 +68,7 @@ Left to you are the details of: 1. Copy over the `adv_myworkcell_node.cpp` into your core package's src/ folder. ```bash - cp ~/industrial_training/exercises/5.0/src/myworkcell_core/src/adv_myworkcell_node.cpp myworkcell_core/src/adv_myworkcell_node.cpp + cp ~/industrial_training/exercises/5.0/src/myworkcell_core/src/adv_myworkcell_node.cpp myworkcell_core/src/ ``` 1. Create rules in the `myworkcell_core` package's `CMakeLists.txt` to build a new node called `adv_myworkcell_node`. As in previous exercises, add these lines near similar lines in the template file (not as a block as shown below). @@ -82,41 +82,55 @@ Left to you are the details of: 1. Copy over the necessesary config file: ``` bash mkdir ~/catkin_ws/src/myworkcell_core/config - cp ~/industrial_training/exercises/5.0/src/myworkcell_core/config/puzzle_bent.csv myworkcell_core/config/puzzle_bent.csv - cp ~/industrial_training/exercises/5.0/src/myworkcell_support/urdf/grinder.xacro myworkcell_support/urdf/grinder.xacro - cp ~/industrial_training/exercises/5.0/src/myworkcell_support/urdf/puzzle_mount.xacro myworkcell_support/urdf/puzzle_mount.xacro + cp ~/industrial_training/exercises/5.0/src/myworkcell_core/config/puzzle_bent.csv myworkcell_core/config/ + cp ~/industrial_training/exercises/5.0/src/myworkcell_support/urdf/grinder.xacro myworkcell_support/urdf/ + cp ~/industrial_training/exercises/5.0/src/myworkcell_support/urdf/puzzle_mount.xacro myworkcell_support/urdf/ mkdir ~/catkin_ws/src/myworkcell_support/meshes cp ~/industrial_training/exercises/5.0/src/myworkcell_support/meshes/* myworkcell_support/meshes/ ``` + 1. Add new package dependencies: + * Add `tf_conversions` to `CMakeLists.txt` (2 places) and `package.xml` (1 place) + ### Update your workcell.xacro file. - 1. Add two include tags for grinder.xacro and puzzle_mount.xacro. - 1. Attach grinder to the **world** link with the origin: + 1. Add two `` tags for the new `grinder.xacro` and `puzzle_mount.xacro` files. + 1. Attach the grinder to the **world** link with the following offset: ``` xml ``` - 1. Attach the puzzle mount the robot link **tool0** with the origin: + * Look in the `grinder.xacro` file to locate the appropriate `` name. + * Copy one of the other `` tag definitions and modify as appropriate. + 1. Attach the puzzle mount to the robot's **tool0** frame with the following offset: ``` xml ``` - 1. Launch the demo.launch file within your moveit_config package to verify the workcell. There should be a grinder sticking out of the table and a puzzle piece shaped part attached to the robot. + * Look in the `puzzle_mount.xacro` file to locate the appropriate `` name. You may need to study its various `` and `` definitions to find the root link of this part. + * The `tool0` frame is standardized across most ROS-I URDFs to be the robot's end-effector mounting flange. + + 1. Launch the demo.launch file within your moveit_config package to verify the workcell. There should be a grinder sticking out of the table and a puzzle-shaped part attached to the robot. ``` bash roslaunch myworkcell_moveit_config demo.launch ``` -### Add new move group to your moveit_config package. - 1. Run moveit setup assistant and add a new move group with the kinematic chain **base_link -> part**. Note: Since you added geometry you should also regenerate the allowed collision matrix. +### Add new planning group to your moveit_config package. + 1. Re-run the MoveIt! Setup Assistant and create a new Planning Group named **puzzle**. Define the kinematic chain to extend from the **base_link** to the new **part** link. ``` bash - roslaunch moveit_setup_assistant setup_assistant.launch + roslaunch myworkcell_moveit_config setup_assistant.launch ``` + * _Note: Since you added geometry, you should also regenerate the allowed collision matrix._ ### Complete Advanced Descartes Node - 1. First, the function `EigenSTL::vector_Affine3d makePuzzleToolPoses()` needs to be completed. The file path for **puzzle_bent.csv** is need. Don't not provide the full path, please use the ros tool `ros::package::getPath()` for getting the path of a package. - 1. Next, the function `std::vector - makeDescartesTrajectory(const EigenSTL::vector_Affine3d& path)` needs to be completed. The transform between **world** and **grinder_frame** needs to be found. Also Each point needs to have a tolerance set for the z-axis to +/- PI; + 1. First, the function `makePuzzleToolPoses()` needs to be completed. The file path for **puzzle_bent.csv** is needed. For portability, don't hardcode the full path. Please use the ROS tool `ros::package::getPath()` to retrieve the root path of the relevant package. + * reference [getPath()](http://docs.ros.org/kinetic/api/roslib/html/c++/namespaceros_1_1package.html#ae9470dd201aa4e66abb833e710d812a4) API + 1. Next, the function `makeDescartesTrajectory()` needs to be completed. The transform between **world** and **grinder_frame** needs to be found. Also Each point needs to have the orientation tolerance set for the z-axis to +/- PI; + * reference [lookupTransform()](http://docs.ros.org/kinetic/api/tf/html/c++/classtf_1_1Transformer.html#ac01a9f8709a828c427f1a5faa0ced42b) API + * reference [tf::conversions](http://docs.ros.org/kinetic/api/tf_conversions/html/c++/tf__eigen_8h.html) namespace + * reference [TolerancedFrame](https://github.com/ros-industrial-consortium/descartes/blob/kinetic-devel/descartes_trajectory/include/descartes_trajectory/cart_trajectory_pt.h#L156) definition + * reference [OrientationTolerance](https://github.com/ros-industrial-consortium/descartes/blob/kinetic-devel/descartes_trajectory/include/descartes_trajectory/cart_trajectory_pt.h#L139) definition ### Update the setup.launch file. - 1. Update the file to take an argument **adv** so that either the basic or advanced descartes node can be launched. + 1. Update the file to take a boolean argument named **adv** so that either the basic or advanced descartes node can be launched. Use `` and `` modifiers to control which node is launched. + * reference [roslaunch XML](http://wiki.ros.org/roslaunch/XML) wiki ### Test Full Application @@ -127,53 +141,7 @@ Left to you are the details of: rosrun myworkcell_core adv_myworkcell_node ``` - It's difficult to see what's happening with the rviz planning-loop always running. Disable this loop animation in rviz (Displays -> Planned Path -> Loop Animation), then rerun `adv_myworkcell_node`. - -### Solutions - * 5.2 Update your workcell.xacro file. - ``` xml - - - - - - - - + * Descartes can take **several minutes** to plan this complex path, so be patient. + * It's difficult to see what's happening with the rviz planning-loop animation always running. Disable this loop animation in rviz (Displays -> Planned Path -> Loop Animation) before running `adv_myworkcell_node`. + - - - - - - ``` - * 5.4 Complete Advanced Descartes Node - - **Step 1:** - ``` c++ - std::string filename = ros::package::getPath("myworkcell_core") + "/config/puzzle_bent.csv"; - ``` - - **Step 2:** - ``` c++ - listener_.lookupTransform("world", "grinder_frame", ros::Time(0), grinder_frame); - tf::transformTFToEigen(grinder_frame, gf); - ``` - - **Step 3:** - ``` c++ - tool_pt.orientation_tolerance.z_lower -= M_PI; - tool_pt.orientation_tolerance.z_upper += M_PI; - ``` - - * 5.5 Update the setup.launch file. - ``` xml - - - - - - - - - ``` diff --git a/gh_pages/_source/session5/Building-a-Perception-Pipeline.rst b/gh_pages/_source/session5/Building-a-Perception-Pipeline.rst index 0c33bbedc..1e761094a 100644 --- a/gh_pages/_source/session5/Building-a-Perception-Pipeline.rst +++ b/gh_pages/_source/session5/Building-a-Perception-Pipeline.rst @@ -4,7 +4,7 @@ In this exercise, we will fill in the appropriate pieces of code to build a perc Prepare New Workspace: ---------------------- -We will create a new catkin workspace, since this exercise does not overlap with the previous PlanNScan exercises. +We will create a new catkin workspace, since this exercise does not overlap with the previous exercises. #. Disable automatic sourcing of your previous catkin workspace: @@ -25,7 +25,7 @@ We will create a new catkin workspace, since this exercise does not overlap with .. code-block:: bash - cp -r ~/industrial_training/exercises/perception_ws ~ + cp -r ~/industrial_training/exercises/5.1/template_ws ~/perception_ws cd ~/perception_ws/ #. Initialize and Build this new workspace @@ -41,14 +41,15 @@ We will create a new catkin workspace, since this exercise does not overlap with source ~/perception_ws/devel/setup.bash -#. Download the :download:`PointCloud file ` and place the file in your home directory (~). - +#. Copy the PointCloud file from prior Exercise 4.2 to your home directory (~): + .. code-block:: bash + cp ~/industrial_training/exercises/4.2/table.pcd ~ #. Import the new workspace into your QTCreator IDE: - * In QTCreator: File -> New Project -> Import -> Import ROS Workspace -> ~/perception_ws + * In QTCreator: `File -> New File or Project -> Other Project -> ROS Workspace -> ~/perception_ws` Intro (Review Existing Code) ---------------------------- @@ -96,6 +97,8 @@ The task of filling in the middle section containing the perception algorithms i Implement Voxel Filter ^^^^^^^^^^^^^^^^^^^^^^ +#. Uncomment the `voxel_grid` include header, near the top of the file. + #. Change code: The first step in most point cloud processing pipelines is the voxel filter. This filter not only helps to downsample your points, but also eliminates any NAN values so that any further filtering or processing is done on real values. See `PCL Voxel Filter Tutorial `_ for hints, otherwise you can copy the below code snippet. @@ -173,6 +176,8 @@ Viewing Results Implement Pass-through Filters ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +#. As before, uncomment the PassThrough filter include-header near the top of the file. + #. Change code: The next set of useful filtering to get the region of interest, is a series of pass-through filters. These filters crop your point cloud down to a volume of space (if you use x y and z filter). At this point you should apply a series of pass-through filters, one for each the x, y, and z directions. See `PCL Pass-Through Filter Tutorial `_ for hints, or use code below. @@ -297,6 +302,7 @@ Plane Segmentation #. Find the ``pcl::toROSMsg`` call where the ``pc2_cloud`` is populated. This is the point cloud that is published to RViz display. Replace the current cloud (``zf_cloud``) with the plane-fit outliers result (``*cloud_f``). #. Compile and run, as in previous steps. + Did you forget to uncomment the new headers used in this step? #. Evaluate Results @@ -389,7 +395,7 @@ Create a CropBox Filter * The user should choose one or the other method * ========================================*/ - This CropBox filter should replace your passthrough filters, you may delete or comment the passthrough filters. There is not PCL tutorial to guide you, only the PCL documentation at the link above. The general setup will be the same (set the output, declare instance of filter, set input, set parameters, and filter). + This CropBox filter should replace your passthrough filters, you may delete or comment the passthrough filters. There is no PCL tutorial to guide you, only the PCL documentation at the link above. The general setup will be the same (set the output, declare instance of filter, set input, set parameters, and filter). Set the output cloud: @@ -413,8 +419,8 @@ Create a CropBox Filter .. code-block:: c++ - Eigen::Vector4f min_point = Eigen::Vector4f(x_filter_min, y_filter_min, z_filter_min, 0); - Eigen::Vector4f max_point = Eigen::Vector4f(x_filter_max, y_filter_max, z_filter_max, 0); + Eigen::Vector4f min_point = Eigen::Vector4f(-1.0, -1.0, -1.0, 0); + Eigen::Vector4f max_point = Eigen::Vector4f(1.0, 1.0, 1.0, 0); crop.setMin(min_point); crop.setMax(max_point); @@ -431,77 +437,11 @@ Create a CropBox Filter pcl::PointCloud::Ptr cropped_cloud(new pcl::PointCloud(xyz_filtered_cloud)); -#. Update Publisher within perception_node.cpp, find section - - .. code-block:: c++ - - /* ======================================== - * CONVERT POINTCLOUD PCL->ROS - * PUBLISH CLOUD - * Fill Code: UPDATE AS NECESSARY - * ========================================*/ - - Change the "toROSMsg" line to convert from your newly processed cloud into a ROS sensor_msgs::PointCloud2. - - Change: - - .. code-block:: c++ +#. Find the ``pcl::toROSMsg`` call where the ``pc2_cloud`` is populated. This is the point cloud that is published to RViz display. Replace the current cloud with the new filtered results (``xyz_filtered_cloud``). - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(zf_cloud, *pc2_cloud); - - to: - - .. code-block:: c++ +#. Compile and run, as in previous steps - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(xyz_filtered_cloud, *pc2_cloud); - -#. Compile - - .. code-block:: bash - - catkin build - - - .. Note:: If you have the time/patience, I would suggest creating a ros publisher for each type of filter. It is often useful to view the results of multiple filters at once in Rviz and just toggle different clouds. - -Viewing Result -"""""""""""""" -#. Open multiple terminals - - Either open three more tabs within your terminal *CTRL-SHIFT-T* or open three more windows *CTRL-SHIFT-N*. These terminals will run a roscore, the pcl_ros, and Rviz. Below, Terminal 1 corresponds to the terminal you have been working out of. - - In terminal 4: - - .. code-block:: bash - - roscore - - In terminal 3: - - .. code-block:: bash - - cd ~ - rosrun pcl_ros pcd_to_pointcloud table.pcd 0.1 _frame_id:=kinect_link cloud_pcd:=kinect/depth_registered/points - - In terminal 2: - - .. code-block:: bash - - rosrun rviz rviz - - In terminal 1: - - .. code-block:: bash - - rosrun lesson_perception perception_node - -#. View results - - Within Rviz, add a *PointCloud2* and subscribe to the topic "object_cluster". What you see will be the results of the voxel filter overlaid on the original point cloud. - - The following image of the CropBox filter in use will closely resemble the Plane Segmentation filter image. + The following image of the CropBox filter in use will closely resemble the Plane Segmentation filter image. .. image:: /_static/xyz_filtered_cloud.png @@ -542,7 +482,7 @@ Create a Statistical Outlier Removal sor.setInputCloud (cluster_cloud_ptr); - Set parameters - looking at documentation, CropBox takes an Eigen Vector4f as inputs for max and min values: + Set parameters - looking at documentation, S.O.R. uses the number of neighbors to inspect and the standard-deviation threshold to use for outlier rejection: .. code-block:: c++ @@ -555,75 +495,9 @@ Create a Statistical Outlier Removal sor.filter (*sor_cloud_filtered); -#. Update Publisher within perception_node.cpp, find section - - .. code-block:: c++ - - /* ======================================== - * CONVERT POINTCLOUD PCL->ROS - * PUBLISH CLOUD - * Fill Code: UPDATE AS NECESSARY - * ========================================*/ - - Change the "toROSMsg" line to convert from your newly processed cloud into a ROS sensor_msgs::PointCloud2. - - Change: - - .. code-block:: c++ - - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(*cloud_f, *pc2_cloud); - - to: - - .. code-block:: c++ +#. Find the ``pcl::toROSMsg`` call where the ``pc2_cloud`` is populated. Replace the current cloud with the new filtered results (``*sor_cloud_filtered``). - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(*sor_cloud_filtered, *pc2_cloud); - -#. Compile - - .. code-block:: bash - - catkin build - - - .. Note:: If you have the time/patience, I would suggest creating a ros publisher for each type of filter. It is often useful to view the results of multiple filters at once in Rviz and just toggle different clouds. - -Viewing Result -"""""""""""""" -#. Open multiple terminals - - Either open three more tabs within your terminal *CTRL-SHIFT-T* or open three more windows *CTRL-SHIFT-N*. These terminals will run a roscore, the pcl_ros, and Rviz. Below, Terminal 1 corresponds to the terminal you have been working out of. - - In terminal 4: - - .. code-block:: bash - - roscore - - In terminal 3: - - .. code-block:: bash - - cd ~ - rosrun pcl_ros pcd_to_pointcloud table.pcd 0.1 _frame_id:=kinect_link cloud_pcd:=kinect/depth_registered/points - - In terminal 2: - - .. code-block:: bash - - rosrun rviz rviz - - In terminal 1: - - .. code-block:: bash - - rosrun lesson_perception perception_node - -#. View results - - Within Rviz, add a *PointCloud2* and subscribe to the topic "object_cluster". What you see will be the results of the voxel filter overlaid on the original point cloud. +#. Compile and run, as in previous steps .. image:: /_static/sor_cloud_filtered.png @@ -631,12 +505,10 @@ Viewing Result Create a Broadcast Transform ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -While this is not a filter method, it is directly related to the final project (the capstone project during the training class), so if you have the time, you should implement this to get a better understanding of how the demo works. +While this is not a filter method, it demonstrates how to publish the results of a processing pipeline for other nodes to use. Often, the goal of a processing pipeline is to generate a measurement, location, or some other message for other nodes to use. This sub-task broadcasts a TF transform to define the location of the largest box on the table. This transform could be used by other nodes to identify the position/orientation of the box for grasping. #. Change/Insert code - Transforms are used to convey relations between two frames of reference or coordinate systems. In our demo, the AR tag detection software pipeline broadcasts a transform based on the position and orientation of the AR tag. A separate node then listens for that transform in order to identify the position/orientation of the box for grasping. - Within perception_node.cpp, find section .. code-block:: c++ @@ -664,55 +536,16 @@ While this is not a filter method, it is directly related to the final project ( br.sendTransform(tf::StampedTransform(part_transform, ros::Time::now(), world_frame, "part")); -#. Compile - - .. code-block:: bash - - catkin build - -Viewing Result -"""""""""""""" - -#. Open multiple terminals - - Either open three more tabs within your terminal *CTRL-SHIFT-T* or open three more windows *CTRL-SHIFT-N*. These terminals will run a roscore, the pcl_ros, and Rviz. Below, Terminal 1 corresponds to the terminal you have been working out of. - - In terminal 4: - - .. code-block:: bash - - roscore - - In terminal 3: - .. code-block:: bash - - cd ~ - rosrun pcl_ros pcd_to_pointcloud table.pcd 0.1 _frame_id:=kinect_link cloud_pcd:=kinect/depth_registered/points - - In terminal 2: - - .. code-block:: bash - - rosrun rviz rviz - - In terminal 1: - - .. code-block:: bash - - rosrun lesson_perception perception_node - - 2. View results - - Within Rviz, add a *PointCloud2* and subscribe to the topic "object_cluster". What you see will be the results of the voxel filter overlaid on the original point cloud. There is no difference in the point cloud from the last image given in the statistical outlier removal. +#. Compile and Run as usual. In this case, add a TF display to Rviz and observe the new "part" transform located at the top of the box. Create a Polygonal Segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -This method was included primarily to have something that ties in directly to the demo that you will be programming in session 5. This demo uses AR tag perception, but also collision avoidance. The collision avoidance uses a pointcloud to actively determine where the obstacles are. However, becuase the part itself is within the scene, we must subtract the points that comprise the part in order to remove these points from becoming a collision object (which will then make a grasp impossible due to the object colliding with itself). +When using sensor data for collision detection, it is sometimes necessary to exclude "known" objects from the scene to avoid interference from these objects. MoveIt! contains methods for masking out a robot's own geometry as a "Self Collision" filtering feature. This example shows how to do something similar using PCL's Polygonal Segmentation filtering. #. Change code - This method is similar to the plane segmentation from Sub-Task 3, but instead of segmenting out a plane, you can segment and remove a prism. Documentation on the PCL Polygonal Segmentation can be found `here `__ and `here `__. The goal in using this filter for this demo is to remove the points that correspond to the object of interest (because the collision/path planning requires it). So this particular filter is applied to the entire point cloud, but only after we know the position/orientation of the box. + This method is similar to the plane segmentation from Sub-Task 3, but instead of segmenting out a plane, you can segment and remove a prism. Documentation on the PCL Polygonal Segmentation can be found `here `__ and `here `__. The goal in this sub-task is to remove the points that correspond to a known object (e.g. the box we detected earlier). This particular filter is applied to the entire point cloud (original sensor data), but only after we've already completed the processing steps to identify the position/orientation of the box. Within perception_node.cpp, add ``#include `` and find section @@ -749,7 +582,7 @@ This method was included primarily to have something that ties in directly to th prism.setInputCloud(sensor_cloud_ptr); pcl::PointIndices::Ptr pt_inliers (new pcl::PointIndices()); - Set parameters - looking at documentation, ExtractPolygonalPrismData takes a polygon pointcloud as input. + Set parameters - looking at documentation, ExtractPolygonalPrismData uses a pointcloud defining the polygon vertices as its input. .. code-block:: c++ @@ -802,7 +635,7 @@ This method was included primarily to have something that ties in directly to th extract_ind.setInputCloud(sensor_cloud_ptr); extract_ind.setIndices(pt_inliers); - Set parameters - looking at documentation, ExtractPolygonalPrismData takes a polygon pointcloud as input: + This time, we invert the index extraction, so that we remove points inside the filter and keep points outside the filter. .. code-block:: c++ @@ -814,88 +647,19 @@ This method was included primarily to have something that ties in directly to th extract_ind.filter(*prism_filtered_cloud); -#. Update Publisher within perception_node.cpp, find section - - .. code-block:: c++ - - /* ======================================== - * CONVERT POINTCLOUD PCL->ROS - * PUBLISH CLOUD - * Fill Code: UPDATE AS NECESSARY - * ========================================*/ - - Change the "toROSMsg" line to convert from your newly processed cloud into a ROS sensor_msgs::PointCloud2. Hint: If following the PCL tutorial, you will have a vector of sensor_msgs::PointCloud2; you can just publish the first one. - - Change: - - .. code-block:: c++ - - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(*sor_cloud_filtered, *pc2_cloud); - - to: - - .. code-block:: c++ - - sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); - pcl::toROSMsg(*prism_filtered_cloud, *pc2_cloud); - - - .. Note:: *If you did not create your own publisher* to use for the Polygonal Segmentation filter, it will be necessary to move ``CONVERT POINTCLOUD PCL->ROS`` below ``extract_ind.filter(*prism_filtered_cloud);``. - -#. Compile - - .. code-block:: bash - - catkin build - - - .. Note:: If you have the time/patience, I would suggest creating a ros publisher for each type of filter. It is often useful to view the results of multiple filters at once in Rviz and just toggle different clouds. - -Viewing Result -"""""""""""""" - -#. Open multiple terminals - - Either open three more tabs within your terminal *CTRL-SHIFT-T* or open three more windows *CTRL-SHIFT-N*. These terminals will run a roscore, the pcl_ros, and Rviz. Below, Terminal 1 corresponds to the terminal you have been working out of. - - In terminal 4: - - .. code-block:: bash - - roscore - - In terminal 3: - - .. code-block:: bash - - cd ~ - rosrun pcl_ros pcd_to_pointcloud table.pcd 0.1 _frame_id:=kinect_link cloud_pcd:=kinect/depth_registered/points +#. Find the ``pcl::toROSMsg`` call where the ``pc2_cloud`` is populated. This is the point cloud that is published to RViz display. Replace the current cloud with the new filtered results (``*prism_filtered_cloud``). - In terminal 2: - - .. code-block:: bash - - rosrun rviz rviz - - In terminal 1: - - .. code-block:: bash - - rosrun lesson_perception perception_node - - 2. View results - - Within Rviz, add a *PointCloud2* and subscribe to the topic "object_cluster". What you see will be the results of the voxel filter overlaid on the original point cloud. +#. Compile and run as before. .. image:: /_static/prism_filtered_cloud.png - .. Note:: Notice the pointer is pointing to empty area of the table. That is the goal of using the filter this way. + .. Note:: Notice that the target box has been removed from the point cloud display. Write a launch file ^^^^^^^^^^^^^^^^^^^ -While this is not a filter method, it is useful when using PCL or other perception methods because of the number of parameters used in the different methods. +While this is not a filter method, it is useful when using PCL or other perception methods because of the number of parameters used in the different methods. + #. Change/Insert code If you are really awesome and read the Task 1 write-up thoroughly, you will note that it was suggested that you put your parameters in one place. @@ -912,10 +676,10 @@ While this is not a filter method, it is useful when using PCL or other percepti .. code-block:: yaml - world_frame="camera_depth_optical_frame"; + world_frame="kinect_link"; camera_frame="kinect_link"; - cloud_topic="camera/depth_registered/points"; - voxel_leaf_size=0.001f; + cloud_topic="kinect/depth_registered/points"; + voxel_leaf_size=0.002f; x_filter_min=-2.5; x_filter_max=2.5; y_filter_min=-2.5; @@ -929,37 +693,29 @@ While this is not a filter method, it is useful when using PCL or other percepti cluster_max_size=50000; - If you took this step, you will be in great shape to convert what you have into something that can be input from a launch file, or yaml file. You will want to use the "getParam" method as described in this `tutorial `_. Get params from ros parameter server/launch file: + If you took this step, you will be in great shape to convert what you have into something that can be input from a launch file, or yaml file. You could use the "getParam" method as described in this `tutorial `_. But a better choice might be to use the `param `_ method, which returns a default value if the parameter is not found on the parameter server. Get params from ros parameter server/launch file, replacing your previous hardcoded values (but leave the variable declarations!) .. code-block:: c++ - priv_nh_.getParam("cloud_topic", cloud_topic); - priv_nh_.getParam("world_frame", world_frame); - priv_nh_.getParam("camera_frame", camera_frame); - priv_nh_.getParam("voxel_leaf_size", voxel_leaf_size); - priv_nh_.getParam("x_filter_min", x_filter_min); - priv_nh_.getParam("x_filter_max", x_filter_max); - priv_nh_.getParam("y_filter_min", y_filter_min); - priv_nh_.getParam("y_filter_max", y_filter_max); - priv_nh_.getParam("z_filter_min", z_filter_min); - priv_nh_.getParam("z_filter_max", z_filter_max); - priv_nh_.getParamCached("plane_max_iterations", plane_max_iter); - priv_nh_.getParamCached("plane_distance_threshold", plane_dist_thresh); - priv_nh_.getParam("cluster_tolerance", cluster_tol); - priv_nh_.getParam("cluster_min_size", cluster_min_size); - priv_nh_.getParam("cluster_max_size", cluster_max_size); - - Once you've done this, you can either delete or comment out your hard-coded values, but leave the declaration of those variables! - -#. Compile - - .. code-block:: c++ - - catkin build + cloud_topic = priv_nh_.param("cloud_topic", "kinect/depth_registered/points"); + world_frame = priv_nh_.param("world_frame", "kinect_link"); + camera_frame = priv_nh_.param("camera_frame", "kinect_link"); + voxel_leaf_size = param("voxel_leaf_size", 0.002); + x_filter_min = priv_nh_.param("x_filter_min", -2.5); + x_filter_max = priv_nh_.param("x_filter_max", 2.5); + y_filter_min = priv_nh_.param("y_filter_min", -2.5); + y_filter_max = priv_nh_.param("y_filter_max", 2.5); + z_filter_min = priv_nh_.param("z_filter_min", -2.5); + z_filter_max = priv_nh_.param("z_filter_max", 2.5); + plane_max_iter = priv_nh_.param("plane_max_iterations", 50); + plane_dist_thresh = priv_nh_.param("plane_distance_threshold", 0.05); + cluster_tol = priv_nh_.param("cluster_tolerance", 0.01); + cluster_min_size = priv_nh_.param("cluster_min_size", 100); + cluster_max_size = priv_nh_.param("cluster_max_size", 50000); #. Write launch file. - Using gedit or some other text editor, make a new file (processing_node.launch) and put the following in it. + Using gedit or some other text editor, make a new file (''lesson_perception/launch/processing_node.launch'') and put the following in it. .. code-block:: xml @@ -985,37 +741,12 @@ While this is not a filter method, it is useful when using PCL or other percepti -Viewing Results -""""""""""""""" - -#. Open multiple terminals - - Either open three more tabs within your terminal *CTRL-SHIFT-T* or open three more windows *CTRL-SHIFT-N*. These terminals will run a roscore, the pcl_ros, and Rviz. Below, Terminal 1 corresponds to the terminal you have been working out of. - - In terminal 4: - - .. code-block:: bash - - roscore - - In terminal 3: +#. Compile as usual... - .. code-block:: bash - - cd ~ - rosrun pcl_ros pcd_to_pointcloud table.pcd 0.1 _frame_id:=kinect_link cloud_pcd:=kinect/depth_registered/points +But this time, run the new launch file that was created instead of using rosrun to start the processing node. - In terminal 2: - - .. code-block:: bash - - rosrun rviz rviz -d `rospack find lesson_perception`/launch/lesson_perception.rviz - - In terminal 1: - - .. code-block:: bash +The results should look similar to previous runs. However, now you can edit these configuration parameters much easier! No recompile step is required; just edit the launch-file values and relaunch the node. In a real application, you could take this approach one step further and implement dynamic_reconfigure support in your node. That would allow you to see the results of parameter changes in RViz in real-time! - roslaunch lesson_perception processing_node.launch When you are satisfied with the results, go to each terminal and *CTRL-C*. diff --git a/gh_pages/_source/session5/OpenCV-in-Python.md b/gh_pages/_source/session5/OpenCV-in-Python.md new file mode 100644 index 000000000..8088165b5 --- /dev/null +++ b/gh_pages/_source/session5/OpenCV-in-Python.md @@ -0,0 +1,516 @@ +# OpenCV Image Processing (Python) +In this exercise, we will gain familiarity with both OpenCV and Python, through a simple 2D image-processing application. + +## Motivation +OpenCV is a mature, stable library for 2D image processing, used in a wide variety of applications. Much of ROS makes use of 3D sensors and point-cloud data, but there are still many applications that use traditional 2D cameras and image processing. + +This tutorial uses python to build the image-processing pipeline. Python is a good choice for this application, due to its ease of rapid prototyping and existing bindings to the OpenCV library. + +## Further Information and Resources +* [OpenCV Website](https://opencv.org/) +* [OpenCV API](https://docs.opencv.org/3.0-beta/modules/refman.html) +* [OpenCV Python Tutorials](https://docs.opencv.org/3.4.2/d6/d00/tutorial_py_root.html) +* [ROS cv_bridge package (Python)](http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython) +* [Writing a Publisher and Subscriber (Python)](http://wiki.ros.org/rospy_tutorials/Tutorials/WritingPublisherSubscriber) +* [sensor_msgs/Image](http://docs.ros.org/kinetic/api/sensor_msgs/html/msg/Image.html) + + +## Problem Statement +In this exercise, you will create a new node to determine the angular pose of a pump housing using the OpenCV image processing library. The pump's orientation is computed using a series of processing steps to extract and compare geometry features: + + 1. Resize the image (to speed up processing) + 1. Threshold the image (convert to black & white) + 1. Locate the pump's outer housing (circle-finding) + 1. Locate the piston sleeve locations (blob detection) + 1. Estimate primary axis using bounding box + 1. Determine orientation using piston sleeve locations + 1. Calculate the axis orientation relative to a reference (horizontal) axis + +![pump images](https://aeswiki.datasys.swri.edu/rositraining/indigo/Exercises/2A.2?action=AttachFile&do=get&target=pump_images.png +) + +## Implementation + +### Create package +This exercise uses a single package that can be placed in any catkin workspace. The examples below will use the `~/catkin_ws` workspace from earlier exercises. + + 1. Create a new `detect_pump` package to contain the new python nodes we'll be making: + + ```bash + cd ~/catkin_ws/src + catkin create pkg detect_pump --catkin-deps rospy cv_bridge + ``` + * all ROS packages depend on `rospy` + * we'll use `cv_bridge` to convert between ROS's standard Image message and OpenCV's Image object + * `cv_bridge` also automatically brings in dependencies on the relevant OpenCV modules + + 1. Create a python module for this package: + + ```bash + cd detect_pump + mkdir nodes + ``` + + * For a simple package such as this, the [Python Style Guide](http://docs.ros.org/kinetic/api/catkin/html/howto/format2/installing_python.html) recommends this simplified package structure. + * More complex packages (e.g. with exportable modules, msg/srv defintions, etc.) should us a more complex package structure, with an `__init__.py` and `setup.py`. + * reference [Installing Python Scripts](http://docs.ros.org/kinetic/api/catkin/html/howto/format2/installing_python.html) + * reference [Handling setup.py](http://docs.ros.org/api/catkin/html/user_guide/setup_dot_py.html) + +### Create an Image Publisher +The first node will read in an image from a file and publish it as a ROS [Image](http://docs.ros.org/kinetic/api/sensor_msgs/html/msg/Image.html) message on the `image` topic. + + * Note: ROS already contains an `image_publisher` package/node that performs this function, but we will duplicate it here to learn about ROS Publishers in Python. + + 1. Create a new python script for our image-publisher node (`nodes/image_pub.py`). Fill in the following template for a skeleton ROS python node: + + ```python + #!/usr/bin/env python + import rospy + + def start_node(): + rospy.init_node('image_pub') + rospy.loginfo('image_pub node started') + + if __name__ == '__main__': + try: + start_node() + except rospy.ROSInterruptException: + pass + ``` + + 1. Allow execution of the new script file: + + ```bash + chmod u+x nodes/image_pub.py + ``` + + 1. Test run the image publisher: + + ```bash + roscore + rosrun detect_pump image_pump.py + ``` + + * You should see the "node started" message + + 1. Read the image file to publish, using the filename provided on the command line + + 1. Import the `sys` and `cv2` (OpenCV) modules: + + ```python + import sys + import cv2 + ``` + + 1. Pass the command-line argument into the `start_node` function: + + ```python + def start_node(filename): + ... + start_node( rospy.myargv(argv=sys.argv)[1] ) + ``` + * Note the use of `rospy.myargv()` to strip out any ROS-specific command-line arguments. + + 1. In the `start_node` function, call the OpenCV [imread](https://docs.opencv.org/3.0-beta/modules/imgcodecs/doc/reading_and_writing_images.html#imread) function to read the image. Then use [imshow](https://docs.opencv.org/3.0-beta/modules/highgui/doc/user_interface.html#imshow) to display it: + + ```python + img = cv2.imread(filename) + cv2.imshow("image", img) + cv2.waitKey(2000) + ``` + + 1. Run the node, with the specified image file: + + ```bash + rosrun detect_pump image_pub.py ~/industrial_training/exercises/5.4/pump.jpg + ``` + * You should see the image displayed + * Comment out the `imshow`/`waitKey` lines, as we won't need those any more + * Note that you don't need to run `catkin build` after editing the python file, since no compile step is needed. + + 1. Convert the image from OpenCV Image object to ROS Image message: + + 1. Import the `CvBridge` and `Image` (ROS message) modules: + + ```python + from cv_bridge import CvBridge + from sensor_msgs.msg import Image + ``` + + 1. Add a call to the CvBridge [cv2_to_imgmsg](https://docs.ros.org/api/cv_bridge/html/python/) method: + + ```python + bridge = CvBridge() + imgMsg = bridge.cv2_to_imgmsg(img, "bgr8") + ``` + +1. Create a ROS publisher to continually publish the Image message on the `image` topic. Use a loop with a 1 Hz throttle to publish the message. + + ```python + pub = rospy.Publisher('image', Image, queue_size=10) + while not rospy.is_shutdown(): + pub.publish(imgMsg) + rospy.Rate(1.0).sleep() # 1 Hz + ``` + +1. Run the node and inspect the newly-published image message + 1. Run the node (as before): + + ```bash + rosrun detect_pump image_pub.py ~/industrial_training/exercises/5.4/pump.jpg + ``` + + 1. Inspect the message topic using command-line tools: + + ```bash + rostopic list + rostopic hz /image + rosnode info /image_pub + ``` + + 1. Inspect the published image using the standalone [image_view](http://wiki.ros.org/image_view#image_view.2BAC8-diamondback.image_view) node + + ```bash + rosrun image_view image_view + ``` + +### Create the Detect_Pump Image-Processing Node +The next node will subscribe to the `image` topic and execute a series of processing steps to identify the pump's orientation relative to the horizontal image axis. + + 1. As before, create a basic ROS python node (`detect_pump.py`) and set its executable permissions: + + ```python + #!/usr/bin/env python + import rospy + + # known pump geometry + # - units are pixels (of half-size image) + PUMP_DIAMETER = 360 + PISTON_DIAMETER = 90 + PISTON_COUNT = 7 + + def start_node(): + rospy.init_node('detect_pump') + rospy.loginfo('detect_pump node started') + + if __name__ == '__main__': + try: + start_node() + except rospy.ROSInterruptException: + pass + ``` + + ```bash + chmod u+x nodes/detect_pump.py + ``` + + * Note that we don't have to edit `CMakeLists` to create new build rules for each script, since python does not need to be compiled. + + 1. Add a ROS subscriber to the `image` topic, to provide the source for images to process. + + 1. Import the `Image` message header + + ```python + from sensor_msgs.msg import Image + ``` + + 1. Above the `start_node` function, create an empty callback (`process_image`) that will be called when a new Image message is received: + + ```python + def process_image(msg): + try: + pass + except Exception as err: + print err + ``` + * The try/except error handling will allow our code to continue running, even if there are errors during the processing pipeline. + + 1. In the `start_node` function, create a ROS Subscriber object: + * subscribe to the `image` topic, monitoring messages of type `Image` + * register the callback function we defined above + + ```python + rospy.Subscriber("image", Image, process_image) + rospy.spin() + ``` + + * reference: [rospy.Subscriber](http://docs.ros.org/kinetic/api/rospy/html/rospy.topics.Subscriber-class.html) + * reference: [rospy.spin](http://docs.ros.org/kinetic/api/rospy/html/rospy-module.html#spin) + + 1. Run the new node and verify that it is subscribing to the topic as expected: + + ```bash + rosrun detect_pump detect_pump.py + rosnode info /detect_pump + rqt_graph + ``` + + 1. Convert the incoming `Image` message to an OpenCV `Image` object and display it + As before, we'll use the `CvBridge` module to do the conversion. + + 1. Import the `CvBridge` modules: + + ```python + from cv_bridge import CvBridge + ``` + + 1. In the `process_image` callback, add a call to the CvBridge [imgmsg_to_cv2](https://docs.ros.org/api/cv_bridge/html/python/) method: + + ```python + # convert sensor_msgs/Image to OpenCV Image + bridge = CvBridge() + orig = bridge.imgmsg_to_cv2(msg, "bgr8") + ``` + * This code (and all other image-processing code) should go inside the `try` block, to ensure that processing errors don't crash the node. + * This should replace the placeholder `pass` command placed in the `try` block earlier + + 1. Use the OpenCV `imshow` method to display the images received. We'll create a pattern that can be re-used to show the result of each image-processing step. + + 1. Import the OpenCV `cv2` module: + + ```python + import cv2 + ``` + + 1. Add a display helper function above the `process_image` callback: + + ```python + def showImage(img): + cv2.imshow('image', img) + cv2.waitKey(1) + ``` + + 1. Copy the received image to a new "drawImg" variable: + + ```python + drawImg = orig + ``` + + 1. **Below** the `except` block (outside its scope; at `process_image` scope, display the `drawImg` variable: + + ```python + # show results + showImage(drawImg) + ``` + + 1. Run the node and see the received image displayed. + + 1. The first step in the image-processing pipeline is to resize the image, to speed up future processing steps. Add the following code inside the `try` block, then rerun the node. + + ```python + # resize image (half-size) for easier processing + resized = cv2.resize(orig, None, fx=0.5, fy=0.5) + drawImg = resized + ``` + * you should see a smaller image being displayed + * reference: [resize()](https://docs.opencv.org/3.0-beta/modules/imgproc/doc/geometric_transformations.html#resize) + + 1. Next, convert the image from color to grayscale. Run the node to check for errors, but the image will still look the same as previously. + + ```python + # convert to single-channel image + gray = cv2.cvtColor(resized, cv2.COLOR_BGR2GRAY) + drawImg = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR) + ``` + * Even though the original image looks gray, the JPG file, Image message, and `orig` OpenCV image are all 3-channel color images. + * Many OpenCV functions operate on individual image channels. Converting an image that appears gray to a "true" 1-channel grayscale image can help avoid confusion further on. + * We convert back to a color image for `drawImg` so that we can draw colored overlays on top of the image to display the results of later processing steps. + * reference: [cvtColor()](https://docs.opencv.org/3.0-beta/modules/imgproc/doc/miscellaneous_transformations.html#cvtcolor) + + 1. Apply a thresholding operation to turn the grayscale image into a binary image. Run the node and see the thresholded image. + + ```python + # threshold grayscale to binary (black & white) image + threshVal = 75 + ret,thresh = cv2.threshold(gray, threshVal, 255, cv2.THRESH_BINARY) + drawImg = cv2.cvtColor(thresh, cv2.COLOR_GRAY2BGR) + ``` + + You should experiment with the `threshVal` paramter to find a value that works best for this image. Valid values for this parameter lie between [0-255], to match the grayscale pixel intensity range. Find a value that clearly highlights the pump face geometry. I found that a value of `150` seemed good to me. + + * reference [threshold](https://docs.opencv.org/3.0-beta/modules/imgproc/doc/miscellaneous_transformations.html#threshold) + + 1. Detect the outer pump-housing circle. + + This is not actually used to detect the pump angle, but serves as a good example of feature detection. In a more complex scene, you could use OpenCV's Region Of Interest (ROI) feature to limit further processing to only features inside this pump housing circle. + + 1. Use the `HoughCircles` method to detect a pump housing of known size: + + ```python + # detect outer pump circle + pumpRadiusRange = ( PUMP_DIAMETER/2-2, PUMP_DIAMETER/2+2) + pumpCircles = cv2.HoughCircles(thresh, cv2.HOUGH_GRADIENT, 1, PUMP_DIAMETER, param2=2, minRadius=pumpRadiusRange[0], maxRadius=pumpRadiusRange[1]) + ``` + + * reference: [HoughCircles](https://docs.opencv.org/3.0-beta/modules/imgproc/doc/feature_detection.html#houghcircles) + + 1. Add a function to display all detected circles (above the `process_image` callback): + + ```python + def plotCircles(img, circles, color): + if circles is None: return + + for (x,y,r) in circles[0]: + cv2.circle(img, (int(x),int(y)), int(r), color, 2) + ``` + + 1. Below the circle-detect, call the display function and check for the expected # of circles (1) + + ```python + plotCircles(drawImg, pumpCircles, (255,0,0)) + if (pumpCircles is None): + raise Exception("No pump circles found!") + elif len(pumpCircles[0])<>1: + raise Exception("Wrong # of pump circles: found {} expected {}".format(len(pumpCircles[0]),1)) + else: + pumpCircle = pumpCircles[0][0] + ``` + + 1. Run the node and see the detected circles. + + * Experiment with adjusting the `param2` input to `HoughCircles` to find a value that seems to work well. This parameter represents the sensitivity of the detector; lower values detect more circles, but also will return more false-positives. + * Tru removing the `min/maxRadius` parameters or reducing the minimum distance between circles (4th parameter) to see what other circles are detected. + * I found that a value of `param2=7` seemed to work well + + 1. Detect the piston sleeves, using blob detection. + + Blob detection analyses the image to identify connected regions (blobs) of similar color. Filtering of the resulting blob features on size, shape, or other characteristics can help identify features of interest. We will be using OpenCV's [SimpleBlobDetector](https://docs.opencv.org/3.2.0/d0/d7a/classcv_1_1SimpleBlobDetector.html). + + 1. Add the following code to run blob detection on the binary image: + + ```python + # detect blobs inside pump body + pistonArea = 3.14159 * PISTON_DIAMETER**2 / 4 + blobParams = cv2.SimpleBlobDetector_Params() + blobParams.filterByArea = True; + blobParams.minArea = 0.80 * pistonArea; + blobParams.maxArea = 1.20 * pistonArea; + blobDetector = cv2.SimpleBlobDetector_create(blobParams) + blobs = blobDetector.detect(thresh) + ``` + * Note the use of an Area filter to select blobs within 20% of the expected piston-sleeve area. + * By default, the blob detector is configured to detect black blobs on a white background. so no additional color filtering is required. + + 1. Below the blob detection, call the OpenCV blob display function and check for the expected # of piston sleeves (7): + + ```python + drawImg = cv2.drawKeypoints(drawImg, blobs, (), (0,255,0), cv2.DRAW_MATCHES_FLAGS_DRAW_RICH_KEYPOINTS) + if len(blobs) <> PISTON_COUNT: + raise Exception("Wring # of pistons: found {} expected {}".format(len(blobs), PISTON_COUNT)) + pistonCenters = [(int(b.pt[0]),int(b.pt[1])) for b in blobs] + ``` + + 1. Run the node and see if all piston sleeves were properly identified + + 1. Detect the primary axis of the pump body. + + This axis is used to identify the key piston sleeve feature. We'll reduce the image to contours (outlines), then find the largest one, fit a rectangular box (rotated for best-fit), and identify the major axis of that box. + + 1. Calculate image contours and select the one with the largest area: + + ```python + # determine primary axis, using largest contour + im2, contours, h = cv2.findContours(thresh, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE) + maxC = max(contours, key=lambda c: cv2.contourArea(c)) + ``` + + 1. Fit a bounding box to the largest contour: + + ```python + boundRect = cv2.minAreaRect(maxC) + ``` + + 1. Copy these 3 helper functions to calculate the endpoints of the rectangle's major axis (above the `process_image` callback): + + ```python + import math + ... + + def ptDist(p1, p2): + dx=p2[0]-p1[0]; dy=p2[1]-p1[1] + return math.sqrt( dx*dx + dy*dy ) + + def ptMean(p1, p2): + return ((int(p1[0]+p2[0])/2, int(p1[1]+p2[1])/2)) + + def rect2centerline(rect): + p0=rect[0]; p1=rect[1]; p2=rect[2]; p3=rect[3]; + width=ptDist(p0,p1); height=ptDist(p1,p2); + + # centerline lies along longest median + if (height > width): + cl = ( ptMean(p0,p1), ptMean(p2,p3) ) + else: + cl = ( ptMean(p1,p2), ptMean(p3,p0) ) + + return cl + ``` + + 1. Call the `rect2centerline` function from above, with the bounding rectangle calculated earlier. Draw the centerline on top of our display image. + + ```python + centerline = rect2centerline(cv2.boxPoints(boundRect)) + cv2.line(drawImg, centerline[0], centerline[1], (0,0,255)) + ``` + + 1. The final step is to identify the key piston sleeve (closest to centerline) and use position to calculate the pump angle. + + 1. Add a helper function to calculate the distance between a point and the centerline: + + ```python + def ptLineDist(pt, line): + x0=pt[0]; x1=line[0][0]; x2=line[1][0]; + y0=pt[1]; y1=line[0][1]; y2=line[1][1]; + return abs((x2-x1)*(y1-y0)-(x1-x0)*(y2-y1))/(math.sqrt((x2-x1)*(x2-x1)+(y2-y1)*(y2-y1))) + ``` + + 1. Call the `ptLineDist` function to find which piston blob is closest to the centerline. Update the drawImg to show which blob was identified. + + ```python + # find closest piston to primary axis + closestPiston = min( pistonCenters, key=lambda ctr: ptLineDist(ctr, centerline)) + cv2.circle(drawImg, closestPiston, 5, (255,255,0), -1) + ``` + + 1. Calculate the angle between the 3 key points: piston sleeve centerpoint, pump center, and an arbitrary point along the horizontal axis (our reference "zero" position). + + 1. Add a helper function `findAngle` to calculate the angle between 3 points: + + ```python + import numpy as np + + def findAngle(p1, p2, p3): + p1=np.array(p1); p2=np.array(p2); p3=np.array(p3); + v1=p1-p2; v2=p3-p2; + return math.atan2(-v1[0]*v2[1]+v1[1]*v2[0],v1[0]*v2[0]+v1[1]*v2[1]) * 180/3.14159 + ``` + + 1. Call the `findAngle` function with the appropriate 3 keypoints: + + ```python + # calculate pump angle + p1 = (orig.shape[1], pumpCircle[1]) + p2 = (pumpCircle[0], pumpCircle[1]) + p3 = (closestPiston[0], closestPiston[1]) + angle = findAngle(p1, p2, p3) + print "Found pump angle: {}".format(angle) + ``` + + 1. You're done! Run the node as before. The reported pump angle should be near 24 degrees. + +### Challenge Exercises +For a greater challenge, try the following suggestions to modify the operation of this image-processing example: + + 1. Modify the `image_pub` node to rotate the image by 10 degrees between each publishing step. The following code can be used to rotate an image: + + ```python + def rotateImg(img, angle): + rows,cols,ch = img.shape + M = cv2.getRotationMatrix2D((cols/2,rows/2),angle,1) + return cv2.warpAffine(img,M,(cols,rows)) + ``` + + 1. Change the `detect_pump` node to provide a **service** that performs the image detection. Define a custom service type that takes an input image and outputs the pump angle. Create a new application node that subscribes to the `image` topic and calls the `detect_pump` service. + + 1. Try using `HoughCircles` instead of `BlobDetector` to locate the piston sleeves. + diff --git a/gh_pages/_source/session6/Unit-Testing.rst b/gh_pages/_source/session6/Unit-Testing.rst index d4ab9b266..57850ebd6 100644 --- a/gh_pages/_source/session6/Unit-Testing.rst +++ b/gh_pages/_source/session6/Unit-Testing.rst @@ -11,7 +11,7 @@ The ROS Scan-N-Plan application is complete and documented. Now we want to test Information and Resources ------------------------- -`Google Test `__: C++ XUnit test framework +`Google Test `__: C++ XUnit test framework `rostest `__: ROS wrapper for XUnit test framework @@ -73,11 +73,11 @@ Create the unit test frame work .. code-block:: cmake - if(CATKIN_ENABLE_TESTING) - find_package(rostest REQUIRED) - add_rostest_gtest(utest_node test/utest_launch.test src/test/utest.cpp) - target_link_libraries(utest_node ${catkin_LIBRARIES}) - endif() + if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + add_rostest_gtest(utest_node test/utest_launch.test src/test/utest.cpp) + target_link_libraries(utest_node ${catkin_LIBRARIES}) + endif() #. Create a test folder under myworkcell_core @@ -101,14 +101,13 @@ Create the unit test frame work -#. Test the framework +#. Build and test the framework .. code-block:: bash - catkin build - catkin run_tests + catkin run_tests myworkcell_core - The console output should show: + The console output should show (buried in the midst of many build messages): .. code-block:: bash @@ -124,6 +123,8 @@ Create the unit test frame work This means our framework is functional and now we can add usefull unit tests. + .. Note:: You can also run tests directly from the command line, using the launch file we made above: `rostest myworkcell_core utest_launch.test`. Note that test files are not built using the regular `catkin build` command, so use `catkin run_tests myworkcell_core` instead. + Add stock publisher tests ^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -149,7 +150,7 @@ Add stock publisher tests .. code-block:: xml - rostest myworkcell_core utest_launch.test + catkin run_tests myworkcell_core You should see: @@ -193,12 +194,28 @@ Write specific unit tests EXPECT_EQ(test_msg_->header.frame_id, "camera_frame"); } +#. Add some node-initialization boilerplate to the main() function, since our unit tests interact with a running ROS system. Replace the current main() function with the new code below: + + .. code-block:: c++ + + int main(int argc, char **argv) + { + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "MyWorkcellCoreTest"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; + } + #. Run the test: .. code-block:: bash - catkin build - rostest myworkcell_core utest_launch.test + catkin run_tests myworkcell_core #. view the results of the test: diff --git a/gh_pages/index.rst b/gh_pages/index.rst index 30e16829c..e41a996a1 100644 --- a/gh_pages/index.rst +++ b/gh_pages/index.rst @@ -121,6 +121,7 @@ Session 5 - Path Planning and Building a Perception Pipeline Exercise 5.1 - Building a Perception Pipeline <_source/session5/Building-a-Perception-Pipeline.md> Exercise 5.2 - Introduction to STOMP <_source/session5/Introduction-to-STOMP.md> Exercise 5.3 - Simple PCL Interface for Python <_source/session5/Simple-PCL-Interface-for-Python.rst> + Exercise 5.4 - OpenCV Image Processing (Python) <_source/session5/OpenCV-in-Python.md> Session 6 - Documentation, Unit Tests, ROS Utilities and Debugging ROS ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~