From ff71224b2d61af4d0797f755c4509f671c2ddf10 Mon Sep 17 00:00:00 2001 From: Anna Mannucci <19239559+annamannucci@users.noreply.github.com> Date: Thu, 7 Sep 2023 18:54:42 +0200 Subject: [PATCH 01/31] Fixing typo in compute path through poses error codes (#3799) Signed-off-by: Mannucci, Anna (Bosch (CR)) Co-authored-by: Mannucci, Anna (Bosch (CR)) --- nav2_msgs/action/ComputePathThroughPoses.action | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_msgs/action/ComputePathThroughPoses.action b/nav2_msgs/action/ComputePathThroughPoses.action index 1dc0cbd2c1..8a81f6f954 100644 --- a/nav2_msgs/action/ComputePathThroughPoses.action +++ b/nav2_msgs/action/ComputePathThroughPoses.action @@ -11,12 +11,12 @@ bool use_start # If false, use current robot pose as path start, if true, use st uint16 NONE=0 uint16 UNKNOWN=300 uint16 INVALID_PLANNER=301 -uint16 TF_ERROR=3002 +uint16 TF_ERROR=302 uint16 START_OUTSIDE_MAP=303 uint16 GOAL_OUTSIDE_MAP=304 uint16 START_OCCUPIED=305 uint16 GOAL_OCCUPIED=306 -uint16 TIMEOUT=3007 +uint16 TIMEOUT=307 uint16 NO_VALID_PATH=308 uint16 NO_VIAPOINTS_GIVEN=309 From f3a041a7d7081ab35d6c4fcd208d0949829a77e1 Mon Sep 17 00:00:00 2001 From: Alexey Merzlyakov <60094858+AlexeyMerzlyakov@users.noreply.github.com> Date: Thu, 7 Sep 2023 20:41:35 +0300 Subject: [PATCH 02/31] Fixes for flaky WPF test (#3785) * Fixes for flaky WPF test: * New RewrittenYaml ability to add non-existing parameters * Prune distance fix for WPF test * Treat UNKNOWN status as error in WPF * Clear error codes after BT run * Remove unnecessary setInitialPose() from WPF test * Update nav2_waypoint_follower/src/waypoint_follower.cpp Co-authored-by: Steve Macenski * Clean error code in any situation * Fix UNKNOWN WPF status handling --------- Co-authored-by: Steve Macenski --- .../include/nav2_behavior_tree/bt_action_server.hpp | 5 +++++ .../nav2_behavior_tree/bt_action_server_impl.hpp | 11 +++++++++++ nav2_common/nav2_common/launch/rewritten_yaml.py | 10 ++++++++++ .../src/waypoint_follower/test_case_py.launch | 5 ++++- nav2_system_tests/src/waypoint_follower/tester.py | 2 -- nav2_waypoint_follower/src/waypoint_follower.cpp | 10 ++++++---- 6 files changed, 36 insertions(+), 7 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp index 79b1df5bb4..2dcb21e42b 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp @@ -196,6 +196,11 @@ class BtActionServer */ void populateErrorCode(typename std::shared_ptr result); + /** + * @brief Setting BT error codes to success. Used to clean blackboard between different BT runs + */ + void cleanErrorCodes(); + // Action name std::string action_name_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 9a8ddc613c..7276429179 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -236,6 +236,7 @@ void BtActionServer::executeCallback() { if (!on_goal_received_callback_(action_server_->get_current_goal())) { action_server_->terminate_current(); + cleanErrorCodes(); return; } @@ -290,6 +291,8 @@ void BtActionServer::executeCallback() action_server_->terminate_all(result); break; } + + cleanErrorCodes(); } template @@ -316,6 +319,14 @@ void BtActionServer::populateErrorCode( } } +template +void BtActionServer::cleanErrorCodes() +{ + for (const auto & error_code : error_code_names_) { + blackboard_->set(error_code, 0); //NOLINT + } +} + } // namespace nav2_behavior_tree #endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_ diff --git a/nav2_common/nav2_common/launch/rewritten_yaml.py b/nav2_common/nav2_common/launch/rewritten_yaml.py index 2887fa5503..071c884864 100644 --- a/nav2_common/nav2_common/launch/rewritten_yaml.py +++ b/nav2_common/nav2_common/launch/rewritten_yaml.py @@ -87,6 +87,7 @@ def perform(self, context: launch.LaunchContext) -> Text: param_rewrites, keys_rewrites = self.resolve_rewrites(context) data = yaml.safe_load(open(yaml_filename, 'r')) self.substitute_params(data, param_rewrites) + self.add_params(data, param_rewrites) self.substitute_keys(data, keys_rewrites) if self.__root_key is not None: root_key = launch.utilities.perform_substitutions(context, self.__root_key) @@ -121,6 +122,15 @@ def substitute_params(self, yaml, param_rewrites): yaml_keys = path.split('.') yaml = self.updateYamlPathVals(yaml, yaml_keys, rewrite_val) + def add_params(self, yaml, param_rewrites): + # add new total path parameters + yaml_paths = self.pathify(yaml) + for path in param_rewrites: + if not path in yaml_paths: + new_val = self.convert(param_rewrites[path]) + yaml_keys = path.split('.') + if 'ros__parameters' in yaml_keys: + yaml = self.updateYamlPathVals(yaml, yaml_keys, new_val) def updateYamlPathVals(self, yaml, yaml_key_list, rewrite_val): for key in yaml_key_list: diff --git a/nav2_system_tests/src/waypoint_follower/test_case_py.launch b/nav2_system_tests/src/waypoint_follower/test_case_py.launch index adeb839c48..51ccbb451e 100755 --- a/nav2_system_tests/src/waypoint_follower/test_case_py.launch +++ b/nav2_system_tests/src/waypoint_follower/test_case_py.launch @@ -41,10 +41,13 @@ def generate_launch_description(): params_file = os.path.join(bringup_dir, 'params/nav2_params.yaml') # Replace the `use_astar` setting on the params file + param_substitutions = { + 'controller_server.ros__parameters.FollowPath.prune_distance': '1.0', + 'controller_server.ros__parameters.FollowPath.forward_prune_distance': '1.0'} configured_params = RewrittenYaml( source_file=params_file, root_key='', - param_rewrites='', + param_rewrites=param_substitutions, convert_types=True) context = LaunchContext() diff --git a/nav2_system_tests/src/waypoint_follower/tester.py b/nav2_system_tests/src/waypoint_follower/tester.py index d2083fbb4f..30dfff574b 100755 --- a/nav2_system_tests/src/waypoint_follower/tester.py +++ b/nav2_system_tests/src/waypoint_follower/tester.py @@ -236,9 +236,7 @@ def main(argv=sys.argv[1:]): # stop on failure test with bogous waypoint test.setStopFailureParam(True) bwps = [[-0.52, -0.54], [100.0, 100.0], [0.58, 0.52]] - starting_pose = [-2.0, -0.5] test.setWaypoints(bwps) - test.setInitialPose(starting_pose) result = test.run(True, False) assert not result result = not result diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index fb214bd41c..21dbf3caae 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -217,7 +217,10 @@ WaypointFollower::followWaypoints() feedback->current_waypoint = goal_index; action_server_->publish_feedback(feedback); - if (current_goal_status_.status == ActionStatus::FAILED) { + if ( + current_goal_status_.status == ActionStatus::FAILED || + current_goal_status_.status == ActionStatus::UNKNOWN) + { nav2_msgs::msg::MissedWaypoint missedWaypoint; missedWaypoint.index = goal_index; missedWaypoint.goal = goal->poses[goal_index]; @@ -272,9 +275,7 @@ WaypointFollower::followWaypoints() } } - if (current_goal_status_.status != ActionStatus::PROCESSING && - current_goal_status_.status != ActionStatus::UNKNOWN) - { + if (current_goal_status_.status != ActionStatus::PROCESSING) { // Update server state goal_index++; new_goal = true; @@ -324,6 +325,7 @@ WaypointFollower::resultCallback( current_goal_status_.status = ActionStatus::FAILED; return; default: + RCLCPP_ERROR(get_logger(), "Received an UNKNOWN result code from navigation action!"); current_goal_status_.status = ActionStatus::UNKNOWN; return; } From bd47a9415537c273be75c5fe7b105e59c354c429 Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Fri, 8 Sep 2023 02:35:17 +0200 Subject: [PATCH 03/31] Fix `min_points` comparison check (#3795) * Fix min_points checking --- nav2_collision_monitor/src/collision_detector_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index e12d9795db..98433ead04 100644 --- a/nav2_collision_monitor/src/collision_detector_node.cpp +++ b/nav2_collision_monitor/src/collision_detector_node.cpp @@ -314,7 +314,7 @@ void CollisionDetector::process() state_msg->polygons.push_back(polygon->getName()); state_msg->detections.push_back( polygon->getPointsInside( - collision_points) > polygon->getMinPoints()); + collision_points) >= polygon->getMinPoints()); } state_pub_->publish(std::move(state_msg)); From 0976e6319bff688fe6375044ada16d64a1f365ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pedro=20Alejandro=20Gonz=C3=A1lez?= <71234974+pepisg@users.noreply.github.com> Date: Sat, 9 Sep 2023 12:27:30 -0500 Subject: [PATCH 04/31] Expose action server result timeout as a parameter in bt navigator servers (#3787) * Expose action server default timeout in bt navigator servers * typo * duplicated comment * Expose result timeout in other actions * Proper timeout in bt node * Change default timeouts and remove comments * Remove comment in params file * uncrustify controller server --- .../bt_action_server_impl.hpp | 23 ++++++++++++++----- .../include/nav2_behaviors/timed_behavior.hpp | 12 +++++++++- .../params/nav2_multirobot_params_1.yaml | 2 ++ .../params/nav2_multirobot_params_2.yaml | 2 ++ .../params/nav2_multirobot_params_all.yaml | 2 ++ nav2_bringup/params/nav2_params.yaml | 2 ++ nav2_controller/src/controller_server.cpp | 9 +++++++- nav2_planner/src/planner_server.cpp | 11 +++++++-- nav2_smoother/src/nav2_smoother.cpp | 9 +++++++- .../src/waypoint_follower.cpp | 13 ++++++++++- 10 files changed, 73 insertions(+), 12 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 7276429179..76986ec54f 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -61,6 +61,9 @@ BtActionServer::BtActionServer( if (!node->has_parameter("default_server_timeout")) { node->declare_parameter("default_server_timeout", 20); } + if (!node->has_parameter("action_server_result_timeout")) { + node->declare_parameter("action_server_result_timeout", 900.0); + } std::vector error_code_names = { "follow_path_error_code", @@ -134,19 +137,27 @@ bool BtActionServer::on_configure() client_node_->declare_parameter( "global_frame", node->get_parameter("global_frame").as_string()); + // set the timeout in seconds for the action server to discard goal handles if not finished + double action_server_result_timeout; + node->get_parameter("action_server_result_timeout", action_server_result_timeout); + rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); + server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); + action_server_ = std::make_shared( node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(), node->get_node_waitables_interface(), - action_name_, std::bind(&BtActionServer::executeCallback, this)); + action_name_, std::bind(&BtActionServer::executeCallback, this), + nullptr, std::chrono::milliseconds(500), false, server_options); // Get parameters for BT timeouts - int timeout; - node->get_parameter("bt_loop_duration", timeout); - bt_loop_duration_ = std::chrono::milliseconds(timeout); - node->get_parameter("default_server_timeout", timeout); - default_server_timeout_ = std::chrono::milliseconds(timeout); + int bt_loop_duration; + node->get_parameter("bt_loop_duration", bt_loop_duration); + bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration); + int default_server_timeout; + node->get_parameter("default_server_timeout", default_server_timeout); + default_server_timeout_ = std::chrono::milliseconds(default_server_timeout); // Get error code id names to grab off of the blackboard error_code_names_ = node->get_parameter("error_code_names").as_string_array(); diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 821818dd2f..6af6490b61 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -133,9 +133,19 @@ class TimedBehavior : public nav2_core::Behavior node->get_parameter("robot_base_frame", robot_base_frame_); node->get_parameter("transform_tolerance", transform_tolerance_); + if (!node->has_parameter("action_server_result_timeout")) { + node->declare_parameter("action_server_result_timeout", 10.0); + } + + double action_server_result_timeout; + node->get_parameter("action_server_result_timeout", action_server_result_timeout); + rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); + server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); + action_server_ = std::make_shared( node, behavior_name_, - std::bind(&TimedBehavior::execute, this)); + std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds( + 500), false, server_options); local_collision_checker_ = local_collision_checker; global_collision_checker_ = global_collision_checker; diff --git a/nav2_bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/params/nav2_multirobot_params_1.yaml index c2b2dda69a..692ca6ec80 100644 --- a/nav2_bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_1.yaml @@ -45,6 +45,7 @@ bt_navigator: odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 + action_server_result_timeout: 900.0 navigators: ["navigate_to_pose", "navigate_through_poses"] navigate_to_pose: plugin: "nav2_bt_navigator/NavigateToPoseNavigator" @@ -277,6 +278,7 @@ waypoint_follower: ros__parameters: loop_rate: 20 stop_on_failure: false + action_server_result_timeout: 900.0 waypoint_task_executor_plugin: "wait_at_waypoint" wait_at_waypoint: plugin: "nav2_waypoint_follower::WaitAtWaypoint" diff --git a/nav2_bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/params/nav2_multirobot_params_2.yaml index 54704a2e7a..2d57aef383 100644 --- a/nav2_bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_2.yaml @@ -45,6 +45,7 @@ bt_navigator: odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 + action_server_result_timeout: 900.0 navigators: ["navigate_to_pose", "navigate_through_poses"] navigate_to_pose: plugin: "nav2_bt_navigator/NavigateToPoseNavigator" @@ -276,6 +277,7 @@ waypoint_follower: ros__parameters: loop_rate: 20 stop_on_failure: false + action_server_result_timeout: 900.0 waypoint_task_executor_plugin: "wait_at_waypoint" wait_at_waypoint: plugin: "nav2_waypoint_follower::WaitAtWaypoint" diff --git a/nav2_bringup/params/nav2_multirobot_params_all.yaml b/nav2_bringup/params/nav2_multirobot_params_all.yaml index 372dcdd3f6..6f7e66cd61 100644 --- a/nav2_bringup/params/nav2_multirobot_params_all.yaml +++ b/nav2_bringup/params/nav2_multirobot_params_all.yaml @@ -45,6 +45,7 @@ bt_navigator: odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 + action_server_result_timeout: 900.0 navigators: ["navigate_to_pose", "navigate_through_poses"] navigate_to_pose: plugin: "nav2_bt_navigator/NavigateToPoseNavigator" @@ -324,6 +325,7 @@ waypoint_follower: ros__parameters: loop_rate: 20 stop_on_failure: false + action_server_result_timeout: 900.0 waypoint_task_executor_plugin: "wait_at_waypoint" wait_at_waypoint: plugin: "nav2_waypoint_follower::WaitAtWaypoint" diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index cf26d389db..112a1de98b 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -45,6 +45,7 @@ bt_navigator: odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 + action_server_result_timeout: 900.0 navigators: ["navigate_to_pose", "navigate_through_poses"] navigate_to_pose: plugin: "nav2_bt_navigator/NavigateToPoseNavigator" @@ -320,6 +321,7 @@ waypoint_follower: ros__parameters: loop_rate: 20 stop_on_failure: false + action_server_result_timeout: 900.0 waypoint_task_executor_plugin: "wait_at_waypoint" wait_at_waypoint: plugin: "nav2_waypoint_follower::WaitAtWaypoint" diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index c76f9f86cc..241ccebc24 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -50,6 +50,8 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) declare_parameter("controller_frequency", 20.0); + declare_parameter("action_server_result_timeout", 10.0); + declare_parameter("progress_checker_plugins", default_progress_checker_ids_); declare_parameter("goal_checker_plugins", default_goal_checker_ids_); declare_parameter("controller_plugins", default_ids_); @@ -227,6 +229,11 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) odom_sub_ = std::make_unique(node); vel_publisher_ = create_publisher("cmd_vel", 1); + double action_server_result_timeout; + get_parameter("action_server_result_timeout", action_server_result_timeout); + rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); + server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); + // Create the action server that we implement with our followPath method action_server_ = std::make_unique( shared_from_this(), @@ -234,7 +241,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) std::bind(&ControllerServer::computeControl, this), nullptr, std::chrono::milliseconds(500), - true); + true, server_options); // Set subscribtion to the speed limiting topic speed_limit_sub_ = create_subscription( diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index f1e3cd9c5d..2add3d91fd 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -53,6 +53,8 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) declare_parameter("planner_plugins", default_ids_); declare_parameter("expected_planner_frequency", 1.0); + declare_parameter("action_server_result_timeout", 10.0); + get_parameter("planner_plugins", planner_ids_); if (planner_ids_ == default_ids_) { for (size_t i = 0; i < default_ids_.size(); ++i) { @@ -139,6 +141,11 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) // Initialize pubs & subs plan_publisher_ = create_publisher("plan", 1); + double action_server_result_timeout; + get_parameter("action_server_result_timeout", action_server_result_timeout); + rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); + server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); + // Create the action servers for path planning to a pose and through poses action_server_pose_ = std::make_unique( shared_from_this(), @@ -146,7 +153,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) std::bind(&PlannerServer::computePlan, this), nullptr, std::chrono::milliseconds(500), - true); + true, server_options); action_server_poses_ = std::make_unique( shared_from_this(), @@ -154,7 +161,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) std::bind(&PlannerServer::computePlanThroughPoses, this), nullptr, std::chrono::milliseconds(500), - true); + true, server_options); return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_smoother/src/nav2_smoother.cpp b/nav2_smoother/src/nav2_smoother.cpp index 522d361830..6545d3e724 100644 --- a/nav2_smoother/src/nav2_smoother.cpp +++ b/nav2_smoother/src/nav2_smoother.cpp @@ -53,6 +53,8 @@ SmootherServer::SmootherServer(const rclcpp::NodeOptions & options) rclcpp::ParameterValue(std::string("base_link"))); declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1)); declare_parameter("smoother_plugins", default_ids_); + + declare_parameter("action_server_result_timeout", 10.0); } SmootherServer::~SmootherServer() @@ -104,6 +106,11 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State &) // Initialize pubs & subs plan_publisher_ = create_publisher("plan_smoothed", 1); + double action_server_result_timeout; + get_parameter("action_server_result_timeout", action_server_result_timeout); + rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); + server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); + // Create the action server that we implement with our smoothPath method action_server_ = std::make_unique( shared_from_this(), @@ -111,7 +118,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State &) std::bind(&SmootherServer::smoothPlan, this), nullptr, std::chrono::milliseconds(500), - true); + true, server_options); return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index 21dbf3caae..42342638f0 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -36,6 +36,9 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options) declare_parameter("stop_on_failure", true); declare_parameter("loop_rate", 20); + + declare_parameter("action_server_result_timeout", 900.0); + nav2_util::declare_parameter_if_not_declared( this, std::string("waypoint_task_executor_plugin"), rclcpp::ParameterValue(std::string("wait_at_waypoint"))); @@ -71,12 +74,20 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/) get_node_waitables_interface(), "navigate_to_pose", callback_group_); + double action_server_result_timeout; + get_parameter("action_server_result_timeout", action_server_result_timeout); + rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); + server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); + action_server_ = std::make_unique( get_node_base_interface(), get_node_clock_interface(), get_node_logging_interface(), get_node_waitables_interface(), - "follow_waypoints", std::bind(&WaypointFollower::followWaypoints, this)); + "follow_waypoints", std::bind( + &WaypointFollower::followWaypoints, + this), nullptr, std::chrono::milliseconds( + 500), false, server_options); try { waypoint_task_executor_type_ = nav2_util::get_plugin_type_param( From 427427a5778eade756117d4391e321b5f443b784 Mon Sep 17 00:00:00 2001 From: nakai-omer <108797279+nakai-omer@users.noreply.github.com> Date: Mon, 11 Sep 2023 04:48:33 +0300 Subject: [PATCH 05/31] Fix 3744 (#3745) * Update collision_monitor_params.yaml * Update collision_monitor_node.cpp * Update default topics in collision_monitor_node.cpp * Update default topics in collision_monitor_params.yaml * Update collision_monitor_params.yaml * Update collision_monitor_node.cpp * Update default topics in collision_monitor_node.cpp * Update default topics in collision_monitor_params.yaml --- nav2_collision_monitor/params/collision_monitor_params.yaml | 2 +- nav2_collision_monitor/src/collision_monitor_node.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_collision_monitor/params/collision_monitor_params.yaml b/nav2_collision_monitor/params/collision_monitor_params.yaml index 239960e593..e518ef680e 100644 --- a/nav2_collision_monitor/params/collision_monitor_params.yaml +++ b/nav2_collision_monitor/params/collision_monitor_params.yaml @@ -2,7 +2,7 @@ collision_monitor: ros__parameters: base_frame_id: "base_footprint" odom_frame_id: "odom" - cmd_vel_in_topic: "cmd_vel_raw" + cmd_vel_in_topic: "cmd_vel_smoothed" cmd_vel_out_topic: "cmd_vel" state_topic: "collision_monitor_state" transform_tolerance: 0.5 diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 6b678c9c76..8b7984a9c7 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -205,7 +205,7 @@ bool CollisionMonitor::getParameters( auto node = shared_from_this(); nav2_util::declare_parameter_if_not_declared( - node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_raw")); + node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_smoothed")); cmd_vel_in_topic = get_parameter("cmd_vel_in_topic").as_string(); nav2_util::declare_parameter_if_not_declared( node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel")); From 28b7c133f0c815b5e6abcf82e269cfe07d048e2a Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Mon, 11 Sep 2023 12:46:02 -0700 Subject: [PATCH 06/31] Using Simple Commander API for multi robot systems (#3803) * support multirobot namespaces * add docs --- nav2_simple_commander/README.md | 2 ++ .../nav2_simple_commander/robot_navigator.py | 14 +++++++------- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/nav2_simple_commander/README.md b/nav2_simple_commander/README.md index a43fab366e..339d986ed4 100644 --- a/nav2_simple_commander/README.md +++ b/nav2_simple_commander/README.md @@ -14,6 +14,8 @@ See its [API Guide Page](https://navigation.ros.org/commander_api/index.html) fo The methods provided by the basic navigator are shown below, with inputs and expected returns. If a server fails, it may throw an exception or return a `None` object, so please be sure to properly wrap your navigation calls in try/catch and check results for `None` type. +New as of September 2023: the simple navigator constructor will accept a `namespace` field to support multi-robot applications or namespaced Nav2 launches. + | Robot Navigator Method | Description | | --------------------------------- | -------------------------------------------------------------------------- | | setInitialPose(initial_pose) | Sets the initial pose (`PoseStamped`) of the robot to localization. | diff --git a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py index d5daa3cb09..f5abfc582f 100644 --- a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py +++ b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py @@ -46,8 +46,8 @@ class TaskResult(Enum): class BasicNavigator(Node): - def __init__(self, node_name='basic_navigator'): - super().__init__(node_name=node_name) + def __init__(self, node_name='basic_navigator', namespace=''): + super().__init__(node_name=node_name, namespace=namespace) self.initial_pose = PoseStamped() self.initial_pose.header.frame_id = 'map' self.goal_handle = None @@ -83,13 +83,13 @@ def __init__(self, node_name='basic_navigator'): self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped, 'initialpose', 10) - self.change_maps_srv = self.create_client(LoadMap, '/map_server/load_map') + self.change_maps_srv = self.create_client(LoadMap, 'map_server/load_map') self.clear_costmap_global_srv = self.create_client( - ClearEntireCostmap, '/global_costmap/clear_entirely_global_costmap') + ClearEntireCostmap, 'global_costmap/clear_entirely_global_costmap') self.clear_costmap_local_srv = self.create_client( - ClearEntireCostmap, '/local_costmap/clear_entirely_local_costmap') - self.get_costmap_global_srv = self.create_client(GetCostmap, '/global_costmap/get_costmap') - self.get_costmap_local_srv = self.create_client(GetCostmap, '/local_costmap/get_costmap') + ClearEntireCostmap, 'local_costmap/clear_entirely_local_costmap') + self.get_costmap_global_srv = self.create_client(GetCostmap, 'global_costmap/get_costmap') + self.get_costmap_local_srv = self.create_client(GetCostmap, 'local_costmap/get_costmap') def destroyNode(self): self.destroy_node() From 809c3cd6fd0de233d711b1d1c91531305d5f4719 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Sep 2023 17:18:36 -0700 Subject: [PATCH 07/31] =?UTF-8?q?=F0=9F=9B=A0=EF=B8=8F=20Bump=20docker/bui?= =?UTF-8?q?ld-push-action=20from=204=20to=205=20(#3810)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumps [docker/build-push-action](https://github.com/docker/build-push-action) from 4 to 5. - [Release notes](https://github.com/docker/build-push-action/releases) - [Commits](https://github.com/docker/build-push-action/compare/v4...v5) --- updated-dependencies: - dependency-name: docker/build-push-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/update_ci_image.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update_ci_image.yaml b/.github/workflows/update_ci_image.yaml index 5f72cfd363..f3c85ae737 100644 --- a/.github/workflows/update_ci_image.yaml +++ b/.github/workflows/update_ci_image.yaml @@ -99,7 +99,7 @@ jobs: - name: Build and push ${{ github.ref_name }} if: steps.config.outputs.trigger == 'true' id: docker_build - uses: docker/build-push-action@v4 + uses: docker/build-push-action@v5 with: context: . pull: true From cf8b0055a7a879e516c9cede7de4277fc208a515 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Sep 2023 17:18:43 -0700 Subject: [PATCH 08/31] =?UTF-8?q?=F0=9F=9B=A0=EF=B8=8F=20Bump=20docker/log?= =?UTF-8?q?in-action=20from=202=20to=203=20(#3808)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumps [docker/login-action](https://github.com/docker/login-action) from 2 to 3. - [Release notes](https://github.com/docker/login-action/releases) - [Commits](https://github.com/docker/login-action/compare/v2...v3) --- updated-dependencies: - dependency-name: docker/login-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/update_ci_image.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update_ci_image.yaml b/.github/workflows/update_ci_image.yaml index f3c85ae737..01bcd7f0ae 100644 --- a/.github/workflows/update_ci_image.yaml +++ b/.github/workflows/update_ci_image.yaml @@ -67,7 +67,7 @@ jobs: - name: Set up Docker Buildx uses: docker/setup-buildx-action@v2 - name: Login to Docker Hub - uses: docker/login-action@v2 + uses: docker/login-action@v3 with: registry: ghcr.io username: ${{ github.repository_owner }} From 5a1df920fe45859d931bb05909861f80d27160c9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Sep 2023 17:18:57 -0700 Subject: [PATCH 09/31] =?UTF-8?q?=F0=9F=9B=A0=EF=B8=8F=20Bump=20docker/set?= =?UTF-8?q?up-buildx-action=20from=202=20to=203=20(#3809)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumps [docker/setup-buildx-action](https://github.com/docker/setup-buildx-action) from 2 to 3. - [Release notes](https://github.com/docker/setup-buildx-action/releases) - [Commits](https://github.com/docker/setup-buildx-action/compare/v2...v3) --- updated-dependencies: - dependency-name: docker/setup-buildx-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/update_ci_image.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/update_ci_image.yaml b/.github/workflows/update_ci_image.yaml index 01bcd7f0ae..ce987eb118 100644 --- a/.github/workflows/update_ci_image.yaml +++ b/.github/workflows/update_ci_image.yaml @@ -65,7 +65,7 @@ jobs: steps: - uses: actions/checkout@v4 - name: Set up Docker Buildx - uses: docker/setup-buildx-action@v2 + uses: docker/setup-buildx-action@v3 - name: Login to Docker Hub uses: docker/login-action@v3 with: From 8d0de61c2883ae6fd208bb30ab5ef6b42ee5dd07 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 13 Sep 2023 16:52:23 -0700 Subject: [PATCH 10/31] adding copy all params primitive for BT navigator (to ingest into rclcpp) (#3804) * adding copy all params primitive * fix linting * lint * I swear to god, this better be the last linting issue * allowing params to be declared from yaml * Update bt_navigator.cpp --- .../bt_action_server_impl.hpp | 12 +++---- .../nav2_bt_navigator/bt_navigator.hpp | 2 +- nav2_bt_navigator/src/bt_navigator.cpp | 20 ++++++++---- nav2_util/CMakeLists.txt | 1 + nav2_util/include/nav2_util/node_utils.hpp | 21 ++++++++++++ nav2_util/package.xml | 1 + nav2_util/test/test_node_utils.cpp | 32 +++++++++++++++++++ 7 files changed, 75 insertions(+), 14 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 76986ec54f..3e2ee0aee8 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -126,16 +126,16 @@ bool BtActionServer::on_configure() // Support for handling the topic-based goal pose from rviz client_node_ = std::make_shared("_", options); - // Declare parameters for client node to share with BT nodes - // Declare if not declared in case being used an external application + // Declare parameters for common client node applications to share with BT nodes + // Declare if not declared in case being used an external application, then copying + // all of the main node's parameters to the client for BT nodes to obtain nav2_util::declare_parameter_if_not_declared( node, "global_frame", rclcpp::ParameterValue(std::string("map"))); nav2_util::declare_parameter_if_not_declared( node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link"))); - client_node_->declare_parameter( - "robot_base_frame", node->get_parameter("robot_base_frame").as_string()); - client_node_->declare_parameter( - "global_frame", node->get_parameter("global_frame").as_string()); + nav2_util::declare_parameter_if_not_declared( + node, "transform_tolerance", rclcpp::ParameterValue(0.1)); + nav2_util::copy_all_parameters(node, client_node_); // set the timeout in seconds for the action server to discard goal handles if not finished double action_server_result_timeout; diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp index bc9c8049ce..2b552e1b02 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp @@ -44,7 +44,7 @@ class BtNavigator : public nav2_util::LifecycleNode * @brief A constructor for nav2_bt_navigator::BtNavigator class * @param options Additional options to control creation of the node. */ - explicit BtNavigator(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + explicit BtNavigator(rclcpp::NodeOptions options = rclcpp::NodeOptions()); /** * @brief A destructor for nav2_bt_navigator::BtNavigator class */ diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 401a5b0eb5..c83ccd8b23 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -29,8 +29,9 @@ using nav2_util::declare_parameter_if_not_declared; namespace nav2_bt_navigator { -BtNavigator::BtNavigator(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("bt_navigator", "", options), +BtNavigator::BtNavigator(rclcpp::NodeOptions options) +: nav2_util::LifecycleNode("bt_navigator", "", + options.automatically_declare_parameters_from_overrides(true)), class_loader_("nav2_core", "nav2_core::NavigatorBase") { RCLCPP_INFO(get_logger(), "Creating"); @@ -89,11 +90,16 @@ BtNavigator::BtNavigator(const rclcpp::NodeOptions & options) "nav2_is_battery_charging_condition_bt_node" }; - declare_parameter("plugin_lib_names", plugin_libs); - declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1)); - declare_parameter("global_frame", std::string("map")); - declare_parameter("robot_base_frame", std::string("base_link")); - declare_parameter("odom_topic", std::string("odom")); + declare_parameter_if_not_declared( + this, "plugin_lib_names", rclcpp::ParameterValue(plugin_libs)); + declare_parameter_if_not_declared( + this, "transform_tolerance", rclcpp::ParameterValue(0.1)); + declare_parameter_if_not_declared( + this, "global_frame", rclcpp::ParameterValue(std::string("map"))); + declare_parameter_if_not_declared( + this, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link"))); + declare_parameter_if_not_declared( + this, "odom_topic", rclcpp::ParameterValue(std::string("odom"))); } BtNavigator::~BtNavigator() diff --git a/nav2_util/CMakeLists.txt b/nav2_util/CMakeLists.txt index 86fa5fdaee..4635bab0b0 100644 --- a/nav2_util/CMakeLists.txt +++ b/nav2_util/CMakeLists.txt @@ -32,6 +32,7 @@ set(dependencies bondcpp bond action_msgs + rcl_interfaces ) nav2_package() diff --git a/nav2_util/include/nav2_util/node_utils.hpp b/nav2_util/include/nav2_util/node_utils.hpp index d1a39d4a5b..62201624a6 100644 --- a/nav2_util/include/nav2_util/node_utils.hpp +++ b/nav2_util/include/nav2_util/node_utils.hpp @@ -15,8 +15,10 @@ #ifndef NAV2_UTIL__NODE_UTILS_HPP_ #define NAV2_UTIL__NODE_UTILS_HPP_ +#include #include #include "rclcpp/rclcpp.hpp" +#include "rcl_interfaces/srv/list_parameters.hpp" namespace nav2_util { @@ -150,6 +152,25 @@ std::string get_plugin_type_param( return plugin_type; } +/** + * @brief A method to copy all parameters from one node (parent) to another (child). + * May throw parameter exceptions in error conditions + * @param parent Node to copy parameters from + * @param child Node to copy parameters to + */ +template +void copy_all_parameters(const NodeT1 & parent, const NodeT2 & child) +{ + using Parameters = std::vector; + std::vector param_names = parent->list_parameters({}, 0).names; + Parameters params = parent->get_parameters(param_names); + for (Parameters::const_iterator iter = params.begin(); iter != params.end(); ++iter) { + if (!child->has_parameter(iter->get_name())) { + child->declare_parameter(iter->get_name(), iter->get_parameter_value()); + } + } +} + } // namespace nav2_util #endif // NAV2_UTIL__NODE_UTILS_HPP_ diff --git a/nav2_util/package.xml b/nav2_util/package.xml index 4f2a5b3588..9de53f5fd5 100644 --- a/nav2_util/package.xml +++ b/nav2_util/package.xml @@ -28,6 +28,7 @@ launch launch_testing_ament_cmake action_msgs + rcl_interfaces libboost-program-options diff --git a/nav2_util/test/test_node_utils.cpp b/nav2_util/test/test_node_utils.cpp index 7c43927161..9d6d6ba133 100644 --- a/nav2_util/test/test_node_utils.cpp +++ b/nav2_util/test/test_node_utils.cpp @@ -94,3 +94,35 @@ TEST(GetPluginTypeParam, GetPluginTypeParam) ASSERT_EQ(get_plugin_type_param(node, "Foo"), "bar"); ASSERT_EXIT(get_plugin_type_param(node, "Waldo"), ::testing::ExitedWithCode(255), ".*"); } + +TEST(TestParamCopying, TestParamCopying) +{ + auto node1 = std::make_shared("test_node1"); + auto node2 = std::make_shared("test_node2"); + + // Tests for (1) multiple types, (2) recursion, (3) overriding values + node1->declare_parameter("Foo1", rclcpp::ParameterValue(std::string(("bar1")))); + node1->declare_parameter("Foo2", rclcpp::ParameterValue(0.123)); + node1->declare_parameter("Foo", rclcpp::ParameterValue(std::string(("bar")))); + node1->declare_parameter("Foo.bar", rclcpp::ParameterValue(std::string(("steve")))); + node2->declare_parameter("Foo", rclcpp::ParameterValue(std::string(("barz2")))); + + // Show Node2 is empty of Node1's parameters, but contains its own + EXPECT_FALSE(node2->has_parameter("Foo1")); + EXPECT_FALSE(node2->has_parameter("Foo2")); + EXPECT_FALSE(node2->has_parameter("Foo.bar")); + EXPECT_TRUE(node2->has_parameter("Foo")); + EXPECT_EQ(node2->get_parameter("Foo").as_string(), std::string("barz2")); + + nav2_util::copy_all_parameters(node1, node2); + + // Test new parameters exist, of expected value, and original param is not overridden + EXPECT_TRUE(node2->has_parameter("Foo1")); + EXPECT_EQ(node2->get_parameter("Foo1").as_string(), std::string("bar1")); + EXPECT_TRUE(node2->has_parameter("Foo2")); + EXPECT_EQ(node2->get_parameter("Foo2").as_double(), 0.123); + EXPECT_TRUE(node2->has_parameter("Foo.bar")); + EXPECT_EQ(node2->get_parameter("Foo.bar").as_string(), std::string("steve")); + EXPECT_TRUE(node2->has_parameter("Foo")); + EXPECT_EQ(node2->get_parameter("Foo").as_string(), std::string("barz2")); +} From 61d70bc86bfe9edfd58b809f62edabb47bd07839 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 13 Sep 2023 17:34:13 -0700 Subject: [PATCH 11/31] removing deprecated progress single checker param (#3815) --- nav2_controller/src/controller_server.cpp | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 241ccebc24..69b06e3128 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -86,20 +86,6 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) RCLCPP_INFO(get_logger(), "getting progress checker plugins.."); get_parameter("progress_checker_plugins", progress_checker_ids_); - try { - nav2_util::declare_parameter_if_not_declared( - node, "progress_checker_plugin", rclcpp::PARAMETER_STRING); - std::string progress_checker_plugin; - progress_checker_plugin = node->get_parameter("progress_checker_plugin").as_string(); - progress_checker_ids_.clear(); - progress_checker_ids_.push_back(progress_checker_plugin); - RCLCPP_WARN( - get_logger(), - "\"progress_checker_plugin\" parameter was deprecated and will be removed soon. Use " - "\"progress_checker_plugins\" instead to specify a list of plugins"); - } catch (const std::exception &) { - // This is normal situation: progress_checker_plugin parameter should not being declared - } if (progress_checker_ids_ == default_progress_checker_ids_) { for (size_t i = 0; i < default_progress_checker_ids_.size(); ++i) { nav2_util::declare_parameter_if_not_declared( From 6b250a7c57536ee43a402c9820ac2a2acdb8bc13 Mon Sep 17 00:00:00 2001 From: Chuanhong Guo Date: Thu, 14 Sep 2023 22:19:55 +0800 Subject: [PATCH 12/31] mppi: return NO_INFORMATION when the checked point is outside the costmap (#3816) otherwise the controller crashes at ObstaclesCritic::costAtPose because x_i and y_i isn't initialized. --- nav2_mppi_controller/src/critics/obstacles_critic.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/nav2_mppi_controller/src/critics/obstacles_critic.cpp b/nav2_mppi_controller/src/critics/obstacles_critic.cpp index dcdb08f614..60383d00a0 100644 --- a/nav2_mppi_controller/src/critics/obstacles_critic.cpp +++ b/nav2_mppi_controller/src/critics/obstacles_critic.cpp @@ -191,7 +191,10 @@ CollisionCost ObstaclesCritic::costAtPose(float x, float y, float theta) float & cost = collision_cost.cost; collision_cost.using_footprint = false; unsigned int x_i, y_i; - collision_checker_.worldToMap(x, y, x_i, y_i); + if (!collision_checker_.worldToMap(x, y, x_i, y_i)) { + cost = nav2_costmap_2d::NO_INFORMATION; + return collision_cost; + } cost = collision_checker_.pointCost(x_i, y_i); if (consider_footprint_ && (cost >= possibly_inscribed_cost_ || possibly_inscribed_cost_ < 1)) { From 69c7bd6a1ff5c0a1cb7473fc163f5a0b9e67e66c Mon Sep 17 00:00:00 2001 From: Alexey Merzlyakov <60094858+AlexeyMerzlyakov@users.noreply.github.com> Date: Mon, 18 Sep 2023 19:52:05 +0300 Subject: [PATCH 13/31] Fix CD configuration link reference (#3811) * Fix CD configuration page reference * Add CM work on 6th ROS Developers Day reference --- nav2_collision_monitor/README.md | 6 +++++- nav2_collision_monitor/doc/cm_ros_devday.png | Bin 0 -> 437610 bytes 2 files changed, 5 insertions(+), 1 deletion(-) create mode 100644 nav2_collision_monitor/doc/cm_ros_devday.png diff --git a/nav2_collision_monitor/README.md b/nav2_collision_monitor/README.md index 864b28bbe4..1c5b32dc7d 100644 --- a/nav2_collision_monitor/README.md +++ b/nav2_collision_monitor/README.md @@ -14,6 +14,10 @@ The costmaps / trajectory planners will handle most situations, but this is to h ![polygons.png](doc/polygons.png) +Demonstration of Collision Monitor abilities presented at 6th ROS Developers Day 2023, could be found below: + +[![cm-ros-devday.png](doc/cm_ros_devday.png)](https://www.youtube.com/watch?v=bWliK0PC5Ms) + ### Features The Collision Monitor uses polygons relative the robot's base frame origin to define "zones". @@ -83,4 +87,4 @@ The zones around the robot and the data sources are the same as for the Collisio ### Configuration -Detailed configuration parameters, their description and how to setup a Collision Detector could be found at its [Configuration Guide](https://navigation.ros.org/configuration/packages/configuring-collision-detector.html). \ No newline at end of file +Detailed configuration parameters, their description and how to setup a Collision Detector could be found at its [Configuration Guide](https://navigation.ros.org/configuration/packages/collision_monitor/configuring-collision-detector-node.html). diff --git a/nav2_collision_monitor/doc/cm_ros_devday.png b/nav2_collision_monitor/doc/cm_ros_devday.png new file mode 100644 index 0000000000000000000000000000000000000000..63cc8fdea43caa2def3ba2c92980be5ccc0e2c3e GIT binary patch literal 437610 zcmeFYWpEr#vMxMgW=4;gnMcgb%rs(VW|l0rz+z^LY%w!hWJwk?S!^*`x_aN;bIxvj z_s@y=?!TRmiRiA%d@}RNtcvQ0>=+d#X%s|4L;wJQA}b@I1^_?-0RV`8c*ysWObAdu z0Kh=xtD)nrX6glWc6G9}v9|!a`#4(wExc_k0RZon(j47%Vm?>Nw+2Kei0gXd0rv#Y zg8dUA306(;f^ySnE!Yzr&QHwh7uJ__{xTh8d~f_h@LfAY{={Sc_%T(QboQa_dHRE& zaoF_5$um}$@}_o>-};w_KU#0cO!+O3M#68A#&to$mnWMh{@Smuh27o4nLTeNdl&Fe zAMj%HgHohQF7EHecKr&mg@xfak(Le{{7Jh0++rL&zC8bVu_An!{w06jgZAw7*2Cu4 z;hc}XD@*3nU3NnvG8Z&PwVU1dGYRDM;(wujXs6UenuhRL?(_7>fj_&TaxL8bt3~ti z@jP*XaPvdEur|Y+-q6hm<5?{RN_g`{eJ|r3dO^oF9G-<+#!YHTotC4@8dkHG7sM=6X)cZn47V2p7!*EcfS& zZP%!sT(Hcz52HP=C$DF4=bH541#QInZDs~+wv7alT1v(~M0V)sUTPEBTgE|eFU1~; zH72u+43e-|{K6TTR4*SeOIl`PcyM3;?3q|U`$3dN>*K*BNl;`>VYHHbdKH}by3AQBg_%=I&Z@KoP zweh#jE{Y|`6z4Ug+cW&NhEu#qrcJy$?DWFtiFUbfn2xa_ zroAj|ryI&AxHa>z?6^t!IXx8ZsZI(l_({ZeOQ}v@T=K_O7wg4s?@Re)OV3%K>7T9x zXxt!IK6Tr-c|`>mMS()rQ@NYC;KQ(}9_?hOkZ#4AV zVaIb>8Pb<+oiK%_9&#f8lpA23t2dorJL2Y3N-bp^Po zbJuj3m74h_PTC5i$Rc{u4nMnTDIxnqPn?D0+FWkarFZu&8-;e_GCY<{3nnR56YGU3 zcE@$^*8@ktgJj^R-K{APaZ|_7GaB%%>qHDmC*K{uxYaCt{n1LRKiq-( z;nx)@X4OI>2CayIg+tF=P(hmYq{MGy*njEFjmHTxYpg8O8IDMRr-;hdKAGW%`< zZ9(1^?CBj^ARunOefb`L|ChqkdU=6xV`LJ|AF#U~W>1o9;p??DR=w=mCF^<65E+|V zAZv{h1_FJpP+}@V-A^k31Hu`O@0v5!ETqhru_~F_v={oyZRL%@E28c#47{cwH(knC zt_{sDU@RYX)$f3fC-R=t#~yX6h-WG^ioZE@#xcsA1&18c#|$=-QyvhEDKz76V{ zs78q6-f!K{`q#DyK)DN-5iIS4JiB_6?{%W&(7~{Ru=D6@^+Sx=tZrM(H-hS21<+er zgL{v8Uv+J%!>boG`_!;?&g->|CfVm^nDI!W@W$kv5{48eM&^{;!!WStmoL38*mZ|J z^;XDkrp!>F)bJ?sZkf@8lGiCY%v%iWpt@4XA#xz*ykOmb0WMcs3|}G~sDDm;IWeT(!+TR}lZ^A;O2IXfzwM9hcNUX_9p(#TMhsNae+#oWx^*c?R7l)BqIz!2z)VUoVjt_jsx3N|G64sp7&GdB@} zn})Jjq|v%Y!Ro6u7Eq%qgvFtag2_KAfgDh;g^5aRF0_Rq=Hwl56`4`1YlHyiH9j{2 zVfZa>**1Q;wi?&ZOiu9KB#Y^%G}&TQP@|7!b|lwu48aGj;rP?WqrBv~7A*CQxE zHu~AZjnn5s6n{dR$tI?w%?jb${1_0$COVsg;{)`$k&TkCVF8E%W}V??9-=%0JU_Ya zqESdVV)Dm0a$!8;`z|RF+-68 zgScriVB20v$w|DTI&C~4jJqKiA<8TemzhxHQz-i>U}#GEwT{a?$)h&}5`&pMnZIkBrLTNXG(?>DoZ?=J~lY3J3TX2tyevq}v^xP))uGa-iz;oGy zWQeF_S%gCRU<~H^AMH9w;mB`=dKjf1Ww9EdY7L*9bq-{D%1_>rGQ4|W@Y>>Ke?!RgH)8|?y*7&h&`XiJZRb`}=89{mu8 z8)Q0WG(RL}53FER3$0&z2lq!6Jg@tAeb@N8S znwd1&nEKplK!?r(7k`MhSP6}ef$G}ANvR3*QCX7VDSkNVH#rsL5J>01G$?QQHuv{Xhw5u&OF?}E6Y2>Ee|bSzREZUPEGq0DvO(Kiq)1X%=^ zY0PXy>uwTIr!{r{6DH!-XC0hxOvqUohp<~CM|>N}k~|wQ-q>kYkT8Q=B8IYkdtuSH z+MdwAVkD%QorJ1ExL-qG_0lsrQIfFlW02T@Wh8ZnalD$4b5I@qG9|h-Cen)0 z_KdNzl{_?_fN(Y;d?4-bf@VL-tzvl&Ss7O|Q(JL{Tng-qL#0SG_*DKHp5hdnP~gxn zA2QG^p5exFk@W`$Xxq(Uw@Wh-r48Noikuz^UrA4~Hli~7XbMP8VSu!AZ;?K4nlB}<%y%?cPo@QeEX0wgP0a89h@*Ig*ZM7~dy?=A`g;7u_}Fr)WgeV85U zx0B!`OYWg=RKNNv7QQDddB(KQ@|5BnL9^{`biYKuIO_E{$e$a6h`z@_Tn`;hf`e-M zdA$TKd9^@g_%p%LGYtbAWFP$on;Vh|lTqG7&IRi2|CvP=u zP%40eo&i51GNV<2N5=@sY2Cr!oI4(&U7&nOJ1H17P9Toim*E}lUj~_@`Ix9NzGrK$ z)n%Vf&#_Tk0)_!()(^;o2IHfZ9w*%^OqmbrMOvxCgoxl9*Cx6>#h34)hHzaW%S5qI zPg|a_5C}Aob`RDiaKj!;IP3;M#Pn2KaC$@ytxXJ=tXVYu_9X%N%B2{D8RJ*6 zCC$g_AIjLslzm%$Co*?=NPb(hy@e*@O+VVyBhk4Ku43_uBfalnMnWoVW-_ZhTUX-I zrHxQBL&D=86qa7d zx93J8GSxe3FBGF!9z_3wGZttP%q!lAqsY01jfh$KTN)hM>;yMr6=4kt6CyK?GeS{}xUH$s=id4QV} z=|9&SKuU#t)8A)z<_pvCWGD_y`NncFcm|LZ=sF}6wGJ$q(KVxu9|D`g$gPD@ep-gW zKnYm<)|aA-ltL_Ft*9k;v=E$SKJ74gD?y<)qheZKZJQ7;oki@=ffcDt`JuxcW#o{e zpj!@Zk3U_bKD50rQ!Ev@8JIv@CS}PctvwpwLv~pplecK1C;3#%i}Zy+)uUQYeEK?s z7AFXb>e`eO4^7@5$Dr#N!h1I)!NNhRGJ(bjIZ2w?ADfW+t#AR5C~NtIfdP>A^$q9Q zABuxk0m<%EN>6iq#5c6uij1{k|Ip_5jmw(>rszp|Jn6a?(Zxg>gwP|lft*7whTqjc z$_nen2T@30DZpAr+SOl-SIX8+U*s`cLr2kgqYL)##SRs&N6_97Iw#Ddn_}iD4MC6` zHc2Te$RQH_>gfZUX-R@K&aEGvl9JAin>9~Aa8kusXK*1$(is#kQlXtJYvzBqm;;uKWmU@`(}M3QVBehCnajO$6SwRWp}FsLX!+fTWZqFESj#Mgnw|S!9l6n)-f7SO$t2{*C5sTz$4?4(UF+O~-f03kvFwB9t4BUu?~YA93;jso_0^lb0?8urlU0xqpHIz_a)MHSs_m8J-2 z^Q1uWrC|PXj)<&+fJOEX>~Lt50UraXj_y3w{fbtQDRIA%iS{2>sEG)4WBGQXeDS0% z1`flpJ4eKF&p`G@j;yB7&L-RpYEcA`OEamMX7l;tYpnpNteTx zFXa%)NfTlA6wp_%M4yeUAYxg3N3Wx>ddB9_9NL|b1&kC`cubhg5CBJGFu zb*#(B-M^nrJ6wFw-1@Devr9OyywlYy+^SF3!hSdLN++s}C^eke!}jByPRv4-7}ig@+t zN2tDEkqbLoenhj-Xh#I(jY!@@C{Oma`b~`AtoMr5H^g3Csup0|A%*r)?VVdx63dax zx?@#V7Iz;&TiPw$5h$SPi^;+>4oy?JNLK-Svsb8* zI;tC27KphmvXic77Wdyc-fVB61mrK_=+HlZ?5$~h!64Ov(vP51|Khp3I)hmb?*@^9 zj0{h|DE-X65tSo1gICR>t?R3_VG2SoWCVW{f4;K1M#Nk5BKjTfj&ikrZE}%G4B@0# z6o=gJ(8-d-A7I(2*pA6Od!B@{aHB>{dGyt6rbJF&^nk*y-2@CEg@!#G)wQhg1rx62 zYnV}PH>|U5?U*klRE~!WPE|}rv0>b(e?e{uIhD<}7r@w|k-__z+F&Hbe%pP;n+EO$-d&;aKiBw(x;8SOOKRw%=dU)JSPkKhs#2AwGBhO|ct zTi<^RpYBc>MbkX(-(58gfZL*&jzARGu^XWrRq?|qP5(SlY~;Xa#3gwnqlfN~-b%=D zp^+~)>)0fRO$iz}U%5M@ul2~e;w5BiJ_kD!$ar zeh^KTY)y>aRKb$NdZp&c3zjS;f7u>GW@i)a54=r(pj9A6`mL@Uf}rYI<$&FUDG_8= z#V5b)*8;@g)E)k2n*qDOt?4T1S($?4LYGI z5IMdxc?uO!wf@Ll_&T?mOT5LmOm@w%D$R?NCaq$xHm%#yHYG4mC0UupZd{^RRUtp4 ze9A86QoE-Ac@m$ZZN&;Q|J&O~FLg#0j2@X+It<@M(~MDsA0 z`f0ISiF!{57tp1xRm2;=e3^t{+H>*&Yoy-YK)ksb<)V$aYP4nW(mkM-+~=0aP*lo3 z)Qrf_RB=0g4xu1%6Tlx@Lvh7m!0ojNWIV)EXvFH(j=(q)A=MUwcZBt4anWPAOVf8L zF4n@t&x#OjpgJ3ex~)fsFN@SQslmQg1yoJ2(NUHVrsGm(ZZAYO_X*sf)BE4jpVxpe zzG_~Cm0}O5U_f@u%$RA(2$qvdoH=jR842RK^^^{{>h5M?5TE|PkQHP)ef5y%6hcGvM#T7D{mJL7~`mkui zUXGxf)|IS(hqe&DmLiq$wtaS)&`I;w#FHVwyDCV2qzqIb5#OpM#K0(*-I#_`ZfsR@ zCQkc?OeD&ff&!B53x5iC6hTYXDHkv)*AuiMoa4MT&kQRgK6Ny1Qc zqmNQDL#|Gm8*no-WiTiiqP{2mnsuX=n+5n)qVwxqi#gtV7PkD7Fw%OZJd`sAgLT_T zf^i9h2v63!V{Rd^eKaKe2bR78{!$DShGgEPbgvyn?5J)9-=%X1qP)H(B>_Tw%H*Ey zXHxXN*b~iJ{4mki+RE!b8HoB~vtk)$Qf?28c0x2@Am!?qtp1E5P!J$LHYK2mE4~^^ zLS}RnJ-SaM62S+()}jr0?VwJl4=g)hE>t}KXfR?_Q#0F8q-BG)$+S)=Na$0^@b zsS=hDtP!H$%7}8i0jm~EeC{MtBRE5{sYEj%$y(JIJ?yen7;R)!SYa`tK~Mo7hUEj* ztJlO9*Pu^Kb21LyFWElh;If? z7rmU@@djR3M&ZfolLryA(Z}W3l?_#zF|9;p9;n5IYpcxLVmbc1hpNO1k6+d~mEq$O z@o2Y4hG+L!Ptm<%0;Fxh+N?kd?72z!$3$ia+t8$|51PMJ2PHnYLT9IEJwN?Y%1xyA zHN=H-R}AI{DOyJnN+wkfo1&0nmCAZjJ9;kYKw^`o%ft(!hyTzb8>ES)9V&*+98BQM zDj^|8^i$Ft`1a`1WQC@M#}&QQrK36XG|HL3#q8*_z3yU*6H;-;=>MvjnlAta0R;_g z(yNMMB-{Ue9fHm(D5vUYu;^H?zp{nt>rmQ;ND9W8`aPebp$G7#X4f)B;$GS@@3^e>^=n&J6|U>EYq1eNs*-|5tS?xr_0;6-bwBY|xU@RnXk>#PJZf^Q zSH$G1GbfxRHB1968p%7-&#)8HBHAuSQVZA@Dp^%g`PNH%%q8qBCeVO~U17N7pkQd> zUzn1LAZ(M4JGcd=~$)S3p((7s0bqQ+3KjonaOXc+?*T1NtG!#93?vdBq_!9ZOB9}cKJ8-&w zeU>gC=`>^q)Lbw{fQ%MWfh%GRzk9zsT-^KOWS(rY6|bflaGm`$G>L{;o=qk_BaPiKjfKQ;C=7ij%`b|UKfL6TH77zPv+n|13HF+p3!PYyiLpzrA zkt6{P8&D;Ienfy;T8mjTVSUN2IS3<|kpK9yaXWbD!QM=~dBse%ycvs9YPMg2b{KkQ zbWbwrEuZ#wgpvL#oTHSbMR=L12}SdB#-TL`^-HBG?j$cCdrGAz=cEu?yqIR!a5YXj zU|_`}BYK#}C`0*>-Wvj3;TQq=;rMGRf|@eJ1B_n?xJ=5)gI4b1Gpaj#hV0#U^be7S zR?YRT`E(p<9Nh3~5vceGe4Y*<_c>?al6y&ryvUn$ZVh^;bkv#m zSecsL5VA(C*QYMKjA}JL=k-W}41iwrSlBSTqd&Ld(RG+&g0MRh`Vme(@jd%kNH-Tx zvlLSHs+3d`%&enIA}A2Z zgd9+B+})nD4S|3L&Q-5vf zH~3^L?%YH*OGn z&7E%IE}E4)sA=Wl*dH=B=V*tQt@D2fVg(A zJ!EAI*`vAgrsRMdlPx$5cGI|5>OYx$uBtc`z4Y$LaTPfp^)K(+v3u%0%D*i%om*wX z6BuT;^4=hgE=-q&R)9Gz)s=NB%xxBEjZjXkmkCX##1QkQRga&squw zB|?;x@XYuyF5AG`LpIHwPh;j<2D9AcrnJ7(Fg~R0!y0h81s1tu092?= z=#e&kCkvGeW;zon9V8AB6HvWU?U*BR1eKNcN1{~*mu_%lXM7a?{b`nFknT>4X3Tva zjvyh-P5x7{@9B4lgYy+;4ZPMVZ4D1!b6ibvA-oZd_+(soM>S5_@|ZPZT07TaWV3!uNOosz1EK5lU8 zMxPbH>&JCaWr(&dQG1*R;Co0p2sWOxiZq225*X=6IXIXoM=7x#$SOjwG^#%%U1bld z*cINk@jz+rf5;eAa5(a-hOo}Owq=-5tCx(bf;=$#BT?Y3bLmF_>YuDS03X*+(9hb@ zyU%EFsmvjJsZ*oQos14Se4I3qp$3d=l#}+QYn=NzgvsCW9Tq7fGImZJMI@ z6JvKB=@n%0QolyG?&`}LSaYW2$*VcCLWwpkJT||MtKy*n{sDhMS3VU|n zPSmT_u71kBnZd53nk*`b2_|>~lzBf61!7FBTyD$~vI`^11;Dp8*LO*oWKZd&Ac0V{ zTSiTh2=QjI*}AZ}N`>ep_6c z&@SPxXoqiBdrMMP$5jYd5o~eiL~mZ5kQpBfwJFeKmg09(;~FdIFUIh?TYP_NLZ%&k zS)rYsw}JCVU>>pwJ88ZOlos(jM7`lBYv9j=kRhFS$z~wTMsW*bAkQ*ydF$$o>^bgr*q(5@Hd(cyV^FcAWQf-;>NnWlCDkD(o10LfA z0&+%;b=|Zznxd%Kbw;0qApjW`* zN}vM)QxiLiNW{KPS%P?X7+2$r8IGi%RRx;;tg%GVer|!fpR?g*#}#220V*M)a|ynE zV*1c7WS%bI^S2W2DDp3kPy1vKa&;tl7C8y=t#QVmHLV_ZR<}>9tjbzDlA=EbbZ~&^ z(9;7gP#7YG2?`XXUh>i1C0M$Oecp-1>kY~VN)qKpSxfI#h(lx-5z=rXS6ZB@S6e6t z@EjR_s$T(0bdK1J;Lyaut7Y`k!ohhc7~@wS{jfcO=n_M) zP`a9;E~?ODLRpm)q-lYb*R@H(4*no_wh|M;cjx?uG*=K&R3BzH_TDoaZX+(PA}cQb zUv0AQ&9ONF$$~NiBE&<+`c0bjp`Pe2qbj+K(XqU?II${Z^N3$SnFdcVii9cHc+!1M zTU#S$3w=Yn+Hl&U=q~^l4;MA}WX!h=Y`sBm=e0zyds43pKv37D##eJ<6|M;xsvR-v z4ti+g+4w+rGH6k=G9j8+S?`28zlR53yj|Um!&l-ixhZh4GBD4g-4w$KUD-(wbQrJ$ z&mf2Ro9}m~C>~|tUi;}4(P8L7U>*V6T&2$re1nR$d0V{htV&FIba8BzYPaxiW4}+_ zSH0TC1Hnh60X_$d&nKKw$-U(1K(XMD^m4QVVjs2Qv9ah@68#>ch*?gfd~ataw0Un^)=^XdnL9Z!n}VIpESS9=oZs7;0RRDE zZ)a0;I}3N9nT3^&qagW3M-MsB1}sRf&85hy=qzqwZ6o9BYN76{q+#xBXU+#E7ZySk z@CLmDI9Rxw0=*sV9o<0Qg5-bWg5K}{8fGB}{w?BeCrGZNr~(vsalBg`2snjkCLrlOymiOj9!_4|hRw^7nb*fBEO&tf=_k@Q!Z( zWZ|6;7H?B$7B*&976%8Gf7Nhvm-KuG`KLqwR}D9f_wH{NH48T<4_9*wNlyz$cZz?7 z0Gt1}zO#p`{omn$%~>q$EgarO-QKOT{hLW?Sw)rq*7%D8D;o#rzqQ`U{x?Z?8_WM8 z>)(9)Yv%88{?(Cp_5a5GH|hV1{cquSDMdw)gp;|)U+&3D2$KJ09|U$Xw*iCxzU8vy zW;L_0G-I;hwKQeow6p*-newn&FqxWzSvhzt*f{xkIQ|7n*3r$~)Y07HFQ|8LW}9~$ zK2~!xumul069<@!n~BqmosG$q&6JPH+?hFoa2nUI($O@9PGqe8Bh>E?byXCurAi08#qlfqZOla6RSg5<3{>3I6Hy;-( z8xIFNHxC;JCnwkc2x(cky1iH8UzlvH%pCu~{VOe?_h8F4wk{ zvIO^>M*V4eHr18_OG%Z~{W`ZP;D=uJgyfYVw_D8kkdoP#zymsV%%j&BBDc5_S@~3Aeys> zCS$??+tp{Uh}*9tFefuaaL7bVcPm};+Jx)_Hb7*z6rNnLv+1XH&}yA)2J>_0~|_joqSpzc&{^(rzI3BNWzcnmk8T^pZ>a@NJ3%qcWX$IoX!Sv zjqlc5_d0wE|E$p-C(Ar}VI;nacI{A%jPEBpZ+1L{K|4M(XDRzn=IQ@Nb@rB`3Pn}` z0+WJ-AyF%2RiFVykE!&Z5yiZupkR?Ah_Eoe=hOM?jO5T2d|rhtQ2PBbM&hFaWkhhn zR&`#6o~rbcxbb=FtogNWFPy|^0=eGO1Z;(YuQUa8`ggbr- zRQ!?9$LYFFpTF|fC54$$cheK+eRAA!!*$>k^zAVP_^IRK<-U;m7Ri5x-)2JEXln~f zxvhc4KV~C&fQmr4MIq%x*|yyB?mDJB-?`QJ?tCTmwWDF*ENG|Wf(S0=%3WvKQ+qthYp7T~KA=3aTVz!U^2=!yqC0 zzTP=$pGideQt}%y*e%5<&8MMV?Cg8BZ||L(<_k4Yw-?J#jDm7wJ7;KN805G4OJePwZ@~sqv`T{y$)&qJ^ zss?JX3LK9a#)VSbVHl#8>@Ic^Qp}##QqS*`qRE6la349YpLdYthfZ(eg!|uaql(a} zNUBD39401h$d2Ju@oiSncfm41m3%CLMsx`-NIi8%m5gWDf)mwR;orvg(w0$C*%B+Q z4^vEuFo2A%lepQ@<1|%@fCuvN&=sLqxhJ9b{+QhQ@$<(|Dx{bFiAN`t-jvBS;n!pq zC>`VDs<(aBune;PCWRsHup!fR72}~!<@A+CH7EPB)CBnoOau2Xo)0mB=r^nr=s~Fi%)(AxQLbSs5=!<6L3Qb%=xij75B-l7- zLIzc9Ul&9Hv}Qso3HyIa?kb!uZu9vS#GZF>8Z|$Jm>8On#n9PlTX=g_Xy*fj26*H*xCv9#75nf=1>x z?U#X6IpbK%-{GlV&v_#gJ(oHFyX%1<6W7{lD%Ur1RgM{))wD)27>OfY*bflj^*oux zA)ua7VS3qDpC1u0U_!}7aurIf+_k!k=pXT9d?WP`0sC9xbMBfPw29b=GJG}lDtpR4 z)#Y`<^R2T36}d-p%~y#7qd9RBu=NLQ_>7+FX&pUH&7bTIAxS;jmW2O!R2#&K!%ldG zt6(foCKx6&taST5D-%A4J{3%vj3{n&7scPp-fZw^3(q90t!C^fnT&k>r8_CVZ(Pm$ z<~Jb|fErEJ2{|6r+4jOI`M`T`?5TXdV7!)C+`PHlyZZ~tEpWn7%Y9}&6?@$qy)szm zDxALSM05mi|84qn@2hdgBG2+wj382(1G23yj<~dX*kNk`D zQ9R@M^=6fQ)3W{!4&ZLv!Xj(kv}^1sl##3bEpTkDrD1K*L0o#@BSKeuQUkHRAz`4| zE#kS(>mKz@o-3?tjr;VTjug;Z6PtvtvVN~RqmMe&&v38;pm;wSDKhc%;RgQn(sf3sH>Bm(d4jjfMUa< z8WIRRDei^)u>+8u?R3(bw6q8*IS%Rew?BM5j^{BayJ(re&XBt6%}&(uN6>#o635lY z2(BgP1Hg*V(I16md*OY0V-eByG&zDT1US2l(bRi#ywG?2>bpGiKu#oWI%%#v?K}7Y z>3#GBYcMP>U|abtfVADL-C^R;m8>{@(3uKNO`m-?(96B8*Mb6kYX@A59H_qo@7&1;YU^j#Q9ueO(<-R z^s`Zx+iL<6k+<370CGHWo!OrT=^rB$Tkza1eyjx>cTwB)=1zcqakqx(J3c3_t=+Z+ zj5K)pV}yn55phUL`0?a@xnTs5c*fu}&Y*reCmJ##6zX)2FzX8HJ?=29fpkvOY3aH# zCP6sMnra0l1>A6NjrVRL3~cV^>1-?t#P&U*K#XsDKOrtpuuJkQw2`B9<%bLoheOpp zxVMT@-_u>P{F2LYB$vWS24aS5igF;w8d&1XOw3iI`dBJ45Dm6~cNbeJ`}x1M*;U;` zluhuRW5^e%SD6nK7ZNi}^tAG^CAp|y+{3IdVWu$8+nc?C35MkNkdz5(Siq@I*?-n^ z8>1kNnM;j4J*JkQi|u++GI~Vg$^teJI|2g?ttDOV4dnU3&1<NOu_v0bxDtZ18; zM`}KyWY~OKfJ{JTg083~Zao6)d2PCZe$FZglg;9d)udnDcFEAZuC<7sH!});JVZ2g zzRsr9!k6XdT5lWn@uOpCDJw2)M+Vk*BevJo6Uf8d)gJ1b{7y>$di%UsNp@s+k=}TI zPEm~n`6NUN1Xfj55iO4eCfP@BR`c}>r}X)L42>DtR}8{R-kx|~-weUtHaDxGNvSGC zQX+abXI1ZNmo*;+MYP=i0{v3U!S*G{~S`< z?);5|YAfDadb|9f>~(Re_2_K$%z-){1cqL`xB=PWey?Zw*(xK;vk#xeF994tFDHuX zA{2BQS=2t)gakCEyxjm8jB%lz&q4?8hRfCxYh;cf(yIE$HORSlQ$FC5BTz?gl_AvGe6_$kL?k?m@ zm(~FVc}uEpxl39;k?tZMXt+~()7s3QK|_8Y|B_pO;X)9_(kOI_6u-gnp=Pt~&pCzA zOQx4im!Q$X7=dP7A%GoYkW$I^IJEyYcB=d0DwrUuSc2dJb)~cgu{H$DuMU3^M(~FG2vy zs~aizG1g;LbZf~WR{a2z(B5ThQ>fmE7-kePQEC>$+Z(G7F;Sa&b$f66^^y0{Go zw`*n|=;UdAU}+vA?>l|*ByA9bf0De~UF@*kc>B#`4DBwY=xr_mo8}kx-1outH9Ba& z;C(7oksO~4s1sEg_?5E+4OdfSWNeV3_4z?PL@%aF{m&itUTs1&cNbvE~Dz#5pDcJXEx06pYziXhiZ*lT|k;48oCTZ(7PqwJUnL*YfO? zz<^%)Sy$h}j%P$6dq4=VCt-xq9i~9VnJ#~IB z-OTrXMU6{+Ht!$ehHF*B$$WtqtwzU2r^)@2-8LCN79R}7Tq_x|Xo?ga*UHyhVJhi4 z8-Ko2geg9wrWrb)g+rR4iwN`>rfD~lNm-KW_bD1wSSV?PdqSaIs2^Xeo$9k|arQ2ogiO$mtwhP5kT|&yE{bwc#;|FN{BT zfkWhgA5ybxeNjf2q}B=cqMVEiUdovDX9riC)MPU$9;<_fRQG-PjeR4tLkEYYRU&lRB7lw)c*n7UkqiO(EXd zs&Jfmj_zA#Fx`#248xtK!YBPqpHluzg&UjnttRO#^DDDFyyhN5tV&{OxIRuvRDIEl z#?V+o`zk*wkJ*C~TvMS=;AYmdOyv!%E*E3lgTG+gM6vrOuSvJ&pKcib;OULtt5J?+ z@rUgc{-h|`PR^;2=W4+};{rv-1lqS8sP6D)Dw_C1u+I_93g<&TflYfbQ6V_cyqJ0I z#2=;LG?CE@@rN|^WDvMZgZ9D-$jmwBhNv!N4a2E+j_#m5$s`F61^CGIle0=6 zzanZ@Frzm)W;+C&x>Mp|WyxR+dSQe94*-`yXutDN?t1iS_b{@+Tm>0jA-9Fj&3Q^o zLSQH*5D`HT2y(YUl~QBawcy#x(d6lr1H4i!-!H(u{JH>6(N4LU|0hrI2Ml8FIa``B zO-g2FS=XhiA%u*^hA$JEA(=PH+y!7D0m+<|ix|b+&0PrJWF=h&b;(qe8>|{sHD4*< zo{UBlOH9e~SO$c-D5%)$P(fAHbySfUwW_L+kJ7oat5Oy2(wm5CmtW{*D7`*?OQ^n+ z8A7*p>A%jceBxT7WmlSPHBNGsYhRi$IHdv2akX@0o&u^`b{gH9(j`pGeAYDvMK`=f z`l0(d7`6T@J00nINcvSUSm2HgVrG9=1G2k5lzuN%U=$QUYi27%FHguyZ0RSM4b3Bb zBz{;`2bE5u1QAO#x@D{*3{X{VDXBG=HmY13*EK>wo`=$y%#95-s!U_36-sKkqCj^5 zF$BpXiJ+~Z$gnzq<6DAxrKm7x*=l5Sc9QBaceEL4?X!@8km95Xj7S6^G&hMBI$ z<9na?G)QB%G-*B84>D0agD6NAQ(dv+6+~3L6bZ5?$a;>dt1iNz#;_={2woKmakcX; z8%hCe^>a^qn*N3oh)-G)zc&Hz+#%h)3hdkIPQF4jB7W&ftx0f1{Zh(mEB|;IgSE|s zt)CTrka`-X2)mMKn$gUXSxQaQre({faW`Ae7frKpXV0v3q9qq$sA4^;tE#H%I>s0( zg{mTI5EarbwQXurv-CyNCNp~9RiU?K8Db*`Y}}Y@ z1Hj#UgnRC`5$JKfs0O|$u;StQBrP(=XLqd1*Rsu&oQ zff>sfiXhF*-PyKjxmY%Bqn1P@R`qB!9*ssrjFsV7GM_J&i)G`+zUDhX0~CPMTT3Y= zX1C=Ig=U7H!w9F@{TVSjSe5&~i@4h`8dwHW{pqAv*XXME3fL^x(d)(C?t(Z~$Cs z4?JXi^0|38vh)9TckS+i_k|8yo+iWp{a8Ob93Fd9aG48m|4IN>UQkyRxWn>^UTDxw zE+B#;jH;thzPRj$$`$wk0rrjF&8IOsU9tiVx_h^`no3kL_<4Z74KA{ru&Vmwj?iVIW0 z$_hw;s7S@4aq2LH2SH@cor$QrP@R?LTpP?FCQX4GD?w%mn5f>+5TmG;eRj)CCIym2 z5lQYF@hE&g=wg)Cv2>*~Q7CXAK$K$QMo;dIbLlW?(zsb z&-kkDj*mRatwJ!lR9dk4;VrHGB|o%QpSW-7+6}NuLTg2V4T|PUaxf(~W80>bY}uys zhv&=r?DY8P)$e@g_RZ6SaTO8D-mbS7hLFBUX})Y8o}GPi_s&P3+&#N^7)DbWsT)+_ z&Ze>DvU&My&%bc{bOZ?^!lD!s=?tk@>UmO|QnIu8?1K+KdHdZD&+gr;Cr7c4093r07A&MZSWY*4SXWlFiNAX|&>Gy8lyy1Wg<_r6$pS-zPHkO*(H?RH4_rE!+iWkF< zW+?+}2`3#)l-GXx`s;6fD3b`vV!nLo*7HC5!MEy4Omj00ta5MNHj*MK*?gH6^Tn?| z{`lPwes%HiF73$N>(MyFKA`P^RM4(yeNc;vPR)NwY#CPCZosnb0lWc{b{)-2S~*{k z8?#hD>p6t(3_({u7W9zY==SI*Xc@kwxrs>7P>!6;-Bm-S3KhCTP{kln&kF!It@2nl z_85jiS?jC5quym-m(Ri7SSzxZCvWzQt(NFpHlyXYRiHqC1no^cm@838xX^@&6e$24 zSxKE)6^aUSsx@;pl*_D+(Aia~z(n$QnCT>efDkJV1>%+1f$DLkhn3clAPnM4$z95` z3^a?6Lcv!A5bLT|odk_6o(?(N9mQP)iU0`%6Rn)|bQVjhyqOWrMIsEsDrg<6gx0MwU6GoIgj_eMm`|XpESI5z8sLKB?d7SprfDu7p1=6q&0D9( zbwsF3h=1kf7vFvF{l#K|5ZyynAxOyB$c;_o%VoQmH=Zm6L=~Zj5H9A8>$0j?RW5?I zZBsLAW@pEf@xS@epWeQC0|5=?;jI1fKfV6;J0Ffl(?!!l!+5OY*hyQsnJ0;ZeWT?} z0mXA6LYrWzZCZtlM_L7GDPDSFKtw{#dda6Ihe+MSWy|=4#?^ix{v` zRJ_ijSAs|ZsE_~|MU4s<$(@5UC*vY*mTJR-lDlV#>W zVy()^EGY&pCJLohqOFHN@C!p2`+L_9rJ&f7FQ8BJt^r35Yh*UG4l*!eeiWj*EMJaY z^zWk+n0$PUweCBGp&9ymy!J=Pvmo-wDw%zh)vC&D`@7Ixee$}!{0auJ^H3TR^nK%$ zL0lXL!yyyAtD`e@u*UgnQ^Sr&TyKn%|1yeEl6!03n#~uB`F#HEufOu$Z@zLksd9}D zA@ilDWM+9pCu$&0^6`rxWi+UF%#nE#0C@N{o<2@_FiOr`b(b zAyJ7|ofW~&8`uBzhu>|}Ywv&hFw|oWA-Sj4-KZie2_lX8#mr+Bg(w=$K0PQ-(gZHr zw(b&>H^~tQ6#?DM+|1jwIG=g5{LZVdOhz$kFXfb5r-v^*|LmK;eA|ifG*UvO3zQId zh{F?8+aycwOrS9|&Si34YMU%3Q_+;#W;VNZa{Qxz@yEBHxsi#O`w!-S|BpX?|5u+9 zp|O;l=B~m3xJYZ9FB6OJLMN-}Y!vg~$!X%t)=8=*PtMdhlL?ienNiN>t%NFTe<7kM zoP8BT6#$oUrO)2HHu|$4{>|V0_|Ahfi6f0cLVz(qRI~Aod1(ZYD~_}qyt;A-EGBhzGCi!SuryDLc?FpsOvjVjU1swI&8Cyd z!DJlf`$26003ZNKL_t(3XH9Eua;9!l+eVbbz{5DX##7;C8W*q{TfArWGvLJ(jiMNFJPlgU9+oW`8Bh6xqL!;M!`gp?I` z6hc&}V_`;_ z&c81#pwI;FoE=Mc9IiRT7W1F4N<_46aXD~Hm^`UBy7IoBA6zWnc>R}NrtF2d;N_!|JP663SkNaP(qeU zK%okSXGJ%{WIVpOn2QD{+*Lq0-Q1F;Mbpe?&)vFp>-w=$KxvjqRY#SMqJHC*m*0K= zgT-+tgXtK;^NWk~^Yig|d@!BFfVNqjKX^Ea z@#OHZ3ZY5q{QR6|#|HQQ-)3E#g|O2T`ls zMQ&g;ILv(IRlJi$p*Rs>GaZ#P@3g)%*}xWNwU#hPE?}$O6djNlWGsvUwQ@w%im^%+ zI{(k&1?I&)BeQHGDpEm3BuV+_p<;y)Bbwv}I%!S{M1y5JJEM`oK#Gy(k}~*Sc{^_` z4Otz~nFtS=iB-BExZLFKa&)}=F>@EvTSMG~!s4RSSpWVo80=&PQmw-#e=EK6G zE$K4jO7?mn0u zA75`%3R(%!T3V(yS?ad|bl$mh=dE`?m>gb<;|W4ltd7lu7tLG0I{4Wy|NPJYw?-#~<7|*Q$zD2ogPngXz(@ z3IP;&U~wwV)tQ~$sf1F**NOa?>pE@GG|Q%?XPZ~=_U&s;nfgS2*QIB*Gw~siV^7lkv#i&d<&ki^a*w$#gOj;e2*6pIsat984z@KrSvW&d$!J)9G|NjWJl; zo;`dRfNMubRTYx?*~NKk+iS;1lkte;`NQ-1Vlh3KPN!o)=FRfq#o27JAZ0Y3OsA6= zbIB)rS@GK539F1ifA*Sr!?hH^UfyBl1>4yg<_G3Jj+e=40eSr9i@7FHX%h{HQ4WH* zOCwAqC{gHAY61&zC^m7L14s4%?{=C6UR=f6Dq8>qkxC>wBcv|Y1BrCN16Tu7#Wco~ zIvfR5LIvEV3uGHhbzkI~En~9wy%Ul3dCJbhj$3xI*hFi^|F`R1#he`iMa3f!14cnd zib&Q0l}IQoD=jy)%IK3Nx1}OMq|%U2DG5Pw%Fw?gkx5(y-ue9~BxeB{QXC1OyLEad zaTiemOOw%I!+LZY$^FF!Ph{G(^^7+-o;5&J6zm(CoqZ;gD@pFoY#7%v+h4F6sZ0v& zYY;*Ay&b_WaY-JWF}8AO^0pxkA$z9EAh zA|CIa5eG?Eu8W&iaLPBk9j`TpTS=@|s`EjTafPz7SrgY=x_Ie?Bc8b|S2voOSrXy( zYbRZcX8GX54}bc`yHX!(9J^+pq^>eXgLo9$Vqq8U{KI>1Rh3p%y;v-xd*vpoZCmVd z)*Fr@gc$3QRwKr`II9Gb?uO4UF8=PHe*WT%&z>HQgGg1y!-G`ffr*#@D1)(XU|gb2YxBGbDkPzxvjT!1uJ&n}_8WqvSk|ovZ{`rId`Qx8G|Lm<>Hx6@V`{d;KosaLC zSxOcaBqx)}@njSf0bUJqVZ9Gwp$fM4Jx(r~=HA1z`{y${sOsI`uv;OSETOZ?P}N*? z+3y^DT@HY(6*N1jM>npWOs8WJK79Cau~;4-AC1T3lx#Meou8i{92^`R90)m^&Cbrw zrsMJ9bQ)r8+V;V{`yqsDC&w|yWs@G9otfM9$HbbLIXPKnu|Dlqu7qSAo?2EOIL)F0oJ||N?GM8f}rsWOcD0R zrdh&mBd`V|h+Hn1+b0k~n0s1M+{`nxB5(zqUKa7bYOV0(zK(o0`^MzuGeRrK2&@BZ zcvOjm37rrLN}q;s65}Yy7>I%Z6^epJ_{tm|rDqmOg1XRultK09AWcxJ6^gJ+xl zi_5w`HHs9jef+p3TEQSKnRvu3BS@mcnF>m}ko+Ae0-D5uAH!EmRsb zx;lkol9oA`7?XiScc&b=_C--(L(wclD|fNzG{1A_;oZAuCkNvgM9ArMvRpQZHAH2Q zMI{*kWnx+yo1_rb8W01rou&c|!KD%%F}K>Hq?ADSwp}h3^VuvazW3d49Us=Y2iZFx z{`%MVW*6Z=R_VU-B``^EKH^j=wSk*wt9?xc$;bXtZTGK8sE~+ZH zx39c-<3If$|N8cgT&Vn$E7&j>|=N>tWC7STnGj6lzY@AP_gNV{~a_oqOB37n8?MeOWXqkyKJus5AwbH{wC-@#OAaV-}1Gf6c=3AjE({V){&F1sQl4pzs?e+~O0;9t`N8TJa z`XJV8umA#(?8gC4N8=mUt{;qQH+%T-;cPZPJv|+d$L@ar{)3B)i<6UUhlht0T+A*q zx;i;L4pmqzn+NwFgbO?EY3MI;F_PY$h;Ho4?&)fBaik$kmb5bOYt;3!}W){s$XykLX z4Z(m_K+GLbb0a}7yGqhrJST3^KhzE+ zmH#YSZi;7r7-kh^2yj)ioN-rrZ)q#4N?OUNQ@iACS4*(5#`f~2-ZR~EP|mq!*De>` zX-SFo5{EUW<#FIu?xD5OK(5PmW^W3~4IR6&w(2vRSDlsJ%i4cuWGNzyTB>`p@PA{O z#OiJg-OZVm`&Wb%yVUDz3#V%6-z`g-lrJFMP!Fd&8nX()|yDJ zU(3K`>Czk}0PhQ8_c&3l+AH*0*N!9_Y@pZL^sb%6)kv%kVCr7M_$8%G=yvhk><_q) zy<0a`@BcS?T5FI6+;0F;_VpN4Xszx>PBr%a>>EGbGwUofc|~TKnR$)~X4d2$Im^W| zwHyZ(_)9O|{?GsZM?ZVx?Y2$stn1O?;dDG6O(v77szL}sV?NGuPE0ztmxVW3QZQHi<#q9R!wcF2JcNeIf&zc|ql^>^ zFaGS-jYEhelV5#u|F8b~A3pi?ew<8n6amdGA1zzJnv3TlK^1xC#ZOJP8L^Hca64s>B`KN?q z#t;UWLpq;Th`2(g6 z!}G~_e0+2gLzvGNpMCaOjPcshaR_m_OrPHUtTj75y)_!wjq$R-95Zoycr_L75y@wAIS&gRw3IfGrfmX`&xyrN- zHgBNNy-T+h^IR7+$(K#~Vi+u48RrPyR2d>-h@CN}KqNxCK34*OW~y*eLdJlT)PYjL z#myH^cS+^g!?K<2rehLBA`rn!SgAyK1Oo-geeueTi6r1CR8zU@R-#yGH{93!NGE{G znk25(O7x+X*0(_~I`ak-S+)n2-(i zjQcR(7ed}lTS}G#W*%B8rJ>((=HapaGP80t)zZ~%0Ohbz7xV;qy_E=QgL1jreelj_ zU@IHDE=XD(SIq^mpbrBPM{L#nXdijM=M>0-E`1619{XhNAH&fe^)Sy)r>N;pB z7BoGD;q-eC&tCuKJFma-=K1Vgf+I#3r&*3gq+~BbFG>SU!et zS+s5DDW#sl%6B1vu=zJ$dHFy7#h*QM<1mVd`>%d|=fC~s|9bC(PY+K{Vl}45Oz43Q zI&zx~Nx4p$^cyFK|NdY733Iz2bZY3%1||j?w+!XYo8c#xR>-! z5&#GUNONmFHP?@)M+XzS#2`)L#q1)lM48lV+xE_#yB7~0s8UgygJevW+W}p>esXej z82bI$3Vd|@8Rc*~)^PLVyPuuUlS6yG8r>&#n2aZ(w4H|bT@tsN=VX9&crclcLxe4t zi>P*b>*lDg#c8Px!ds^&)9E-Uo2K!0aeO#AIy{OYw5=`Xv*~1faBvW#D!6PG(>mOk z9E?T?@HVAUu*uPQI;|k)&dQskS{dtD#lwSxs!|BWe9$a=sN&JyQNx|*^XC5fEKv>* z4i2UVK|{crG8g^sNPM6*?*PeQLOaBqv&PRKoIji`zCe*XK`KF!s9uNQrBzcN#Dqwc z(o7sG0m0m|DS~F9LJZn*LhjNgoTtUZk;**h|Qu5ZqNgg=uUW6 zlS!$3ak_~ndU>}yAFLi9FBRnAQhBvtHE)X5zN|LiYjUMB(^gmUXxZ{=YCm=+dP`Yc zaOnCCT%%i13PcA#h`k5@;-FuznpEV5aecZiGgYc;<~{bxaB9Q**vzzxkDVEB$QaAr zauc;);Z>IN&cG}aeEVl~2|3O^1qQ=p^J66kJ7UncJlZ()A?SM5bu8C*eZpn>aT%x@ zWtWM=W{DF8&`X@L_F*sY+Rb!cEkh(!(g#=ZXYYBb;VA7e7Pp(46_UTpQFZ{UkQr9o zZNy1|B2@3c|Ir(_-v92mU#==uR~24A87anHx1A*7c{AI0g;P}rPfw;l`m-P0x_$G% z|BwIq@M0MuMmICDw8Hge^GGwNv?A68NugVtT2J$DfB%oJT|dnDvu*9p-MgeKWUcay zRE1d1+H}0R`8I_S1ZP2+8Q%VyS&SJ4pjX+RUcgyM3ewhRry#3y*U;9u0;osiA zc?dE9^Je+lYp=cj#@pk=>juUv7pfDx2 zQ9|~e_sn1A{E$nsWlA#-v2B<;TSJt9yIEQsPU}DU!8cD1M~-W$ z@yT>_csMRDCbYWJx;p4hCKPgfG|l=V&4bK|PPE*sCx}505eNZmZN6OGJDZu{!hp%+Vyf`{4Y%af|UXk^APKTM~_pT18dK?HB?W zg-c6?P6lF8=4XEnhFl!0DqYnvASzb6CQ}Hp2qG*fOE)VSv|%X_9K*G=IEYi{kHJ6tiKuU3Lt?+(tD{%K{!yAN~Z(Gh+V_FXJCYIq^ua#b< z?0})u@}>(jIt2i9nAh9FSduMgx160f89S^$fn4Qmmg(Ic?uEVbWUwK8gw}qC`NDo) zYP%oKPy#=^#T$OjyWJL6(x`s_(wA&=!-;Y0GP{C?H4#08s~qW;2CG!L+iJ{6=YU1e zePJkWIY*@-*2`u3hkyFnGTAp@ed%aA(#Rx$XX_i1q8b5p_tp|!VvM=HI^9+ErI()n z!S}!aSAYAHwrvSXDT${t=QRr;n3`sBaUMbt)jqSNnhp;}uYT`aKm6f$$92fPaX$I< z(~o}jQP2>e4r!ebi2yg~p`sN3p-F>iVmdzxNG9xL(daHf zG6S-vBlejbGm5|k!lGqi@wv>Jp^_nM&AD)c;yGd0k%-yh-AZrYUQbfsWuVlGaX@Wo%>WIZ z^qPdbgDmY_idM#ptPc#Lc?2p1qz>Kj*A&57O|`L33{}RmrcQe6YPdb?|l7hFWkCyGgQh>&pw;YA3Qvp&zferTrL|k9vmFL@ceVH ze&hM0Q3xuk^2#eO{q*PWe)8G95QAq9K)PH2<>gmiy!Gr$8Qc%6qw7jfPY+M79aWWr zLc?;Ie)-mWvy1ttI-n>??QCTLHA}C*`Q~5!&Hr{(BHpTdmoZQvgxuXH28}>KC~Z7I zPi?!HpWnQ8_{~?I9R-0%)3iVP`7dS{vxB3NyNN3(56@QRuOA+R6` zF_x{b7k!ev|Eo{`pa1v2E?ajU8LHe!Bj!#;h3F5Cs&Rx0mTUm8iJXTeUw-Mu|NH;C z(P&i3et_9wQ9v1w$91Jah0c`Zv-{`&@Z+B*300_i5;S8FEj~z^b78rnCNHhY{Cu|f z^-ILHpRbAJdwHCpsm-JZ?+0Jcc#?z6<6#5EtRZ&HRXi%ZTjBuCeMH?rcMclcY zvp6~xxAv{>^2VoQN*to%qbQTs2~j8zvsa2cTd*;ADho1k(1VB~bfzTT26N>*Mfj>5 zpd=ThRO$r@T}pbTp~w~r`ER2egAu(bwHwpor7qIFLtf}IiYkQahP)?N1(qEfC=#Tn z*{IpR*D2yz(Jf9f!U&@$fssa-Akodyni;d(N}npp{w0H~8M+F_Zm-liMy;86cJ}o- zRfIuRXl~vb5z407p)3O&;+ynRKg5+Q?g-sjq==cxI)66Ah|CR3u(sjK8}`KB zBdwGBq3A4SRSV257L^-yHJ$Q)OB%nmU0@$TvYA4@pwhyHB_YdI;O;xGIahiB03ZNK zL_t&p3}sL2MB0v8!v0(~Y6*w77#L;=*L7wh;<-=WpsHen728nkt^G=Ng6#5qWie+~ z-KdurU62F@UAF$tho8Lt!KX1sNFXa9TZeYoEGHRhB;#v8`!9d-FaPb2z86FQOeb}$ zLP{25C4@3)cE%GAfq(Svua(LoSy`T-8(QuZV~lus(fs(Ie*XF!?^V^*HJYp1TO-tUn z`w*(9HxHo_qQ3gdbLlVs?SKCtf4#got48Fg4k6_F%j79}%KdK)E|kXb*@MPVOQ=Mr z8Z-p7^iaS?=~fFUoah905K+1cl_VHKxOwfk9qezR5+R{80&r)O{O-N8zx}({KKSUt z=-^1SqU2``IxN!|!n^>9kY+WbN^pe*1#!MuethR{dwg>J=%CWjkpU=j3eh}IBQUP? z*3DCj%;vM%#WI;KlDF=i5TLZTW4^6jXez8{j^1F~rsZ-et|9@@Q5@BEy|#iBQn`=} zt1_LwvPsC!6?RlrA;c~nnf`z3-t5_y<2v(OLuS>U&Ugm^7XSefAV|q1)w0A6E814r zZci_M@`EG%e>$S0qus4&wPcf&NRgl@Oaur51TKbq?-}+~mATgP!^*5(d!KVJAhslj z`M@B7bN1Q0c2(xewZ8B7b=?-gniyzM=y+x6NpST@UfHUyz{>>4%+pDG@9zD@tO*1v zx=rcH^?JGKJppmrgp;HBBnC;T$=&h!NjquQ+kUgzOsCVyr0KeTecjKGjwh42+4Sqp zW`4YgP26mgUajV*v+xgYANa7`%5asah`|WTa6TdhW)9>;Kpdym8MxIG33q0${rE8& z0!a~q!Gv%TLm*RR0M?Re1a4da#q4`EQUe+Z0}_Hb^ul(-y0K|)&`_A#Q}@KOrd4^W zuie#>J6=Y;&5w09OC$MP=^nV|o%d!nV-vnB!`u&0D!#%~E{Uh$agClT?P>)9%zz4{ zxHoMpSUdPCIwd|GZn^sf+@VeXp?8V>({_!-$5! z;SMkUN-zafyG8%xj@=TfbfZ^vt5WJlC+yaMom>2ahF=lkykBDP4K4>W>4AW3JXsz* z6JnONXuh+mX!f@$Wf2WIW6tEXCT3=ih!BEbEA9F%l5Mx!_uhTyUw;3Mb`m_wW(Z_c zRUVYrAO^}5tB14ZU+r!q$foP{_G-2MyI;Qdi?`kdjG+yKE{+hWUVIfbAVoH84TBL7 zGEzYDoMB43jX%DU;NvD_n$)3{7?V$pWVNI5&bkXQ(@qq$OUcErVy4AD4~ik<#HaykhyoG=A^Q6&WZjpDr0noPZ zzkK}IG@l=zgviD7wZBUs7$eTx=K1?~KKV3XZLds?j6NEo* zBo1zJ2LuWXk#>}+a>#cK8u~d?-~c*<)n;$T2myCTxIh^IA`#(uHL|U)co6UB9v}j}8ZoAF(`e-(rwecTTV2#(r`k3wDr>^5QL}ZRchD2Zi zF@S{~8_7y(gJY_4l~9g%XahiqrpJ-zkpvJ7vuQ7uRi(5gp%XyDNYnx}Xpx9O5Oy3v z+Y@#SbKs^BXn4jpGzmBEC0s;{?_ttKTnSw=P4iRfp0?f=ZGqamo zD!iu(T9u5LnV3056Uk~hXCh*bm4kymhY}H082aZhhHZLPKs4BG4n~;=?lwa-L_sRH zZ)UXGo+{8dqhUxe6qdEdN=YPVC8{#ATki+F$%ume)KQnws1+BQXpwqhfwy?O7DNp}5D&2uM@TsqdGo)h7=he)!QR%hd)jw39f71rBf_5_#sY9J&JWzb&9bVS zJgVY9iS)0(_Qv_yv2W^(`0dwT{r2mxdYezj=SBncuw(=Rc;UIb-+1}OpS|@#PrX;; zqwfpVK!HB^@RNW4=Rf-Nv+EG!zxluZ>VNp}|MaEjPZ(r23E%tPt4Y#d{rIQr^<}os zfRmN{u|ZX0fQqER223OAH;(dIv39FrI5UmU1AvD7#iNUNKlo^CO}V$hh~fNX@!B^Y zEGB^v4dCK>_3+Cl$0rYf8{|*|=1gZtAj=HlJxS;OCW;a<9Xss?IoJ2`-1iIB#9(kSj>x5uH#We`kyuzU#hEKN689s(mZO#p;mbldfp>+SV6yH&r9@$6_e zYeU|4>(%vaz6ecRu2<{rb~c-~ZL{61yUlhsn@%T_<$Ckv;^O@Le9|^u*KJno>7<=a z+w1GAuUlZzzHEDcrh;UMU~ER}w;6#NBL<>?z&`)k#l+!grUbid3VZTf7wbj9P-BzL zKnxSoRx~59f{*JID4?;MS=E3*t<04S_PEhnN|v46nf9G&BjJ)arBsU-0!pHz)qz93 z7L|?VlS;gqRy!~ms?)pFcdoQ_89P>ymmeYufvJ3C)7rHf-dN4GLIPxDU~{8190sL* z-J%)CO&SkXgntHDgZ|UCxbV!MFTT9Gx*CGjMqdl7!ka&T`$s?i<#e(DWB4eGR384x>Nf5wmD{)5YwyS6>NCsx>UkQ@YjL zV`?Qg8xY7m>;VY@+DZGZH@@}DU;QShKE&u_RtBIV38#mjU;Uf^@P9wL*kU^ufM0+7 z<)8n@AO7n<`@w^ICxM`C>3iROElK~Qzxip`t%zFyQs)jDkx$#vA^~VN7a@aSkp&6U z$ZbtT%tXW?5P_=`{bVcvV))sktAG0+f4I@c2I-O6`N`sc`(OXZS6?^}1RUb`zyF6H zefsFhMQW|s%T-J@JAWUMozG}MM5rn$Cn7vOS)8ArMZySP14`FzfBW#0k3ac@iSM1A zHGvM2yU?{500cOnMwm7RkOi^}lwB!|KH1p?s9A+Q!Z?Hm%kaq5h>!_=L!`an zhK|j2b=QuJI>61%HAf@;PuX8^Z-Ya?AuYy#Rt(f&*`?*WTX&Ly0H_UkvY5?hF>km1 zcC%Q_W7Aw+FE1`G?%cgQo6Xki^?J2FS}dm1$#%2dY}RLIr?Y9h*>0E1)nYOC{?^sy zW#DIWlLyZn?fhp4@`-{nVXy$egn_XM)cDGafTmytBv-MGBOy5`jL?YVq%s6A+I%DM z;XMf$q5)BlV1U_75Rz2`AEFl`4CwL92SY$lkE#lZBJUmgkmX=i?ByQUSH!=bjj(%b zJHmr0LJc8&x}@5Q1Z}sm?N||t;B)M{^_IAs!uwKi+=^#**C9xe_xc;aeNW8Sk`lv6 z_d7HV@c(-`_&-vCRm!Gap{1%^d{2iTQg38X+AV=Oc0hyrody0rPN*k#Ev|{;rg5Q+ z#u#IaM3l3rT1t|$h7gzo(ZFbMlRl8BnZ?*d4uLr5oK$ulA2;Y~IT~a!RAgo*Dp@S1 z=2J*j9VTu7K;-3J&N37LA`;qWGHJR#yTJk#nTx?>FD6h`-N`$uN)fSbC#IJAUPMuV z$i@L1v{*6~&eC^feUwQG&xs!b_zxwq@7nj$unH~7Yy}P2qo2?261{d0B zse~YK)5I8&fJ(zg$4v{jVQHZ*10fzQroZ>%J&Z?1tx;BBH51RPAR+}!qJ5wGJ_87W zeDl?p?%zK*vuq$aKe@UVL4<&y1Rzwnew9^*gfN}Pqs5dWzV!0FmtTJ2yvvX0W_oUR+!uO_?Kr5zapN&FBB&FMjmj{;NNE@Zc^H%qHOnfAsqV_Lo2UiAVwr z)v$n671Z;Vzxm*9R#G5?;Q9?$fRwe}>pjG6O4qB661i5;yJ&=92uVzg92rkkyz|RV z_p>+u{_fcij%E=9-o1DHgCG3SzyI?e=iCPksGw#!D{~fA@&Sw#YLk;S`jl3i&HZrq z{B+(FJS3PM^|}A(qmMrP_+wRj{@ywBfm41EpOmJQnmzpd%O}?>Fa1=_1kFkp(!ftL zMOcbsA%dBTJS~Dzr#7IfdYye02P$p zm=k_u9<|@~q>EMly8jOex!vxLqaJ*&Jwk;9GNGWCCM4gTpLWnW?QPo9PBDP*{o2L9q2n<=1 zfkzWJ~J z>|Z{Af6fH+N%$Av|IRk0zxv@%joK233R=HZd+GT*|HuFSzledAaI+#g8bu9yI zpcACNU!MtH1Z+fAPh| z&wu%=AQ6eZ#IT*a6&I<1EOER-;%A$P|>&1Gd<#H`vWFa+86C*bb3>Z{1kgVBc(oSJV3MC}> zT9)=cp-ecO9?cii&}~+i7f;SlPbZVfa=l(|)_3mTn=R(+^=7l)%xAO7WU}6DHk-|4 zF^_Hg#iPf|lz=i`4eP0G=07`&?FaR-V zK;-KCED~csT8>ViW8At6AK( zn`xrDVi_>2ibC=;oZonk^(P=8I}ADu<+t)b<06*CXECWnajeJ>(S(=<)nG))M>E2^BctE{}tvYZ|2V`kg!R#n@! z@$MHAWyvXvs#plb9H{B~UZixC!7?)i4la$-L9M(02IHg^)6Hh1)iNR?tMz)ZIG)ev z%jGhqRBA+K3kqBgh=|y$`6MtBFkuD9A#sRENW5CD`@U1nF`5@iT2yqyLo)JtX&q43 z5+sCBOalfgnx#NMtDpc)OPje?+qvdy~2a@j_vuP3=E}kXOJi~P1vdA zvG7+_A=WOJD^Od6SsO?t5`O!QZ{4|j#*AqE#pT7%-+KSiGEv)5D3@uMGv>vC(Bntf zKY8<=7hisG=k5tJy!6uZFTV8r+i!hHA(~OmLLpDjC9sB(*nkKy7)IdcgHIm)liAX+ zHE0b`fxS#4Dx@I;3xt6%FcA^3sn}0`_U66&_s-6a31B{r-~HYjpFMi~N3*zDua*}V$486l zY_?pjmaEm>^YckNxp;E1yk6eFf4^y(&1SRRZ07U%bUInBH`f=J$H&Jj94BB8+htySOU42EFc8L2t@>e`*LH&ajM}cd~!6-fzfJW zWw?O{`|nVrs99F)#j=qaDS(Ot+0=Uif)L;~&BjeP{>~JtV2Y+?Bw1TlhWq1Es5N^T z;Z>U1SJWdz93%|E8#Tgp$PX&ES0C!T!&Ga`s%Q3Pz-*cnazU*c=m0wUdUm#(ezB1_ z?jZ8u|Ho6pk^0BLZk0|w19tk)TtXsIh|xo6LkI?tQcCM}$}*WunK=|&ps8xt_gTaX zFEh+p3_w-an{CQ@(l%||1`b4wm{Xt36;I5}K~W_8uuoAkQEp>&M4lRKF#hhiU3`+=2xk3Ab;j ztc^{d0FbkaK>`Rs1p5{;XW}4$7Uq-hgsOl*DsptZc>VP^+BTY5Z}6+%JpAnOnwoiN zXB65p5w5H zT-qvt5Gite?>CXmvZN8_7Q~E zosSV1(6uzC;@TMlQnS7{4p2V@`W^1wSz<&Z2>jU>kAL#FZ~xhU{U;5ABAgu0{^XDU z#b5lVANif7sv@Nh7b)R}!&4w42_b}Vae4Xn+iQCL)d%K z;^??#%vrn5-P7awV$t<|x89r`9Z%b~?>pIU@1CAcLNFD`>3BY$OeU%C`}OMno%7@4 zV^ir?t3}%$9UYnJ`tmY7JC)aGc2v#cyu(l0z%XzzQ(&*akat3*r*1NbZqPb8AITJ+ z+7j@$(QpVRr0Rdu+52M98wK=)4hevc-MEoSy!ZEs3ig!{tx_DMswH-Ctoos~9@cCC z$d;h{!*XzB(kn6ssHvHLa@~>Ppg@KYh)brn5r9&elPaJVcoQlTG7egmuZszIrow%X zgEdqh|Jj->{AZEMKTU=O0|NmHx8vq`@gJ+ediM3d;eg)z#bJwTCzF&?N{K^2qOR-u zl(J|Dp=p}fG$F>m@3TmsQWgmzFgG!9my?=`igaC0DWyD_%$g=P0SQPX_mb1LH^jDW z6`@N>oR5=DG&5-kLFsRtP&bO&dbUSwwQ*_sE8b>-D;6n#FvvTCKXxhC%=( zP(?KejG#scNM^dpq6PtXlLHUUB@Wa1Ou^Rc&9?8UwDW2uwtr!B&T2r+F|v&;=tCg8 z$LbMaos;OnK(}U_>=iR()#3=x3;TL@xphRiCv3O9QVVWtO5HFRmN@x?5#e5qH5lIP z=FhmJ08|W+LOY8Xue<(dZ~gk`Z+|eGOwLbE@0^~T9v?3jv$l;Km{`p^yhAAS7!mya(LRK(tU_ag|CwwXYP z1>}iP(3-_Nf<%m=u?%ni;)B&npveNVT5eqPf=nNN^5tLr=$*xc!07R#E990#G-L%I zXd@yTk`cfA{wIh(eeuC_Ih!F7#a=YVs4Aa7dh-AL`0YSikKst}k~b2wnk?%pj|S9; z7?8faxJqf-hPe`h^^c!i{ru-|L+;Js@_J3gPyu8_!4Dmv)J%@we)~6pW@l%o1||r- z$Yi?cy5u>-A~m(GxZn*y9edIDO32w%1(vJL-~atPD6hTr+V|4-SY2J4lEW7pVb;-p}YCz*5JSdI~o3)A~=ZU%*qRx(Q(XNqK z`L}7XZd6DE`E2*fR0Vw1vG%MMG(EMZG<=G3>+2V?&sJzv`kLh|UDt^SGXr4XC-2$B z7~8f*#J=yh+ill%0MNFx7~8CpQc9^e6VJ+xp_$ERlSx~2^M5f~001BWNkl&+%-^*+;NGHIJ;d40WJuN479 zFlLMqnURY|$J9tQ5XKM~iF~SH1>Bi)UaeNk<R_44KyArrbp}-`a=*J4hSc!;s$6rh>f}+_BAWRAYK0n0ws8I(R2ViKSjDYEfhC z6<9T7IcG5x12GU05ltz1mvXyWx3MjO&BPuXAewVd4&82=##@qD!E62$`SA@k>-LJ> zq={tITAU$5+lJ8!4Fie{OZJ70YfceO$+y=mA}%v7tqn&MiFf!6frtXRFU=I0IEKx3 zL&O}&Gf^C%6T*ZjVhABdqOfbH)gm}&Njak#Xbu2fx9w!9m=Oa&GnpQ7h^nH}M-o#C z9Kk5G6F~M{S4C6=HHF-1>OoUr%t^%!j0RbZ8AAvrT2;IVz~Y!_<1(FaRS^P$GMX1y z#_@WaPfkyj@^-tKwjrc-?zSPsB)Ul&+Bt_1Lhwi4Z(hl{TW=UK#)yOph{$o$5^>Jm zX0t|wlhf1LYyn`5rATB(Gh46MAp~Y#Z3-`bKop0a0cejb`RmV2+yLm@vOgym&JxZ^zU5X!MAMbFuA(t6J{kOJHv-I<*?z%rk z8bU?%jZTS-NP#T4)6-Dv=QIRCAFJ=;m}`k_LF?YXGcPz)S8*@WW@pL9L1KVr2w6oC z6iCell?Be{ILHh#nEA10Inw~23)}Rg2_}KtQVm+uA>KtSLfCODQM) z{WQe`G2LO&Ji4#Eb{UJVXe@HS$p|}?92Vy{j6UyPVf6IwRq;OBFiI%xWVxl3DdmSg z)jfa*X?qnY=67jPWcYvUp#lBSE2hsXgPyIhdujpZ5(PR;LBxY$W-&e^#>hl%*L8iL ziMVaslv2*cgWa~1rkRA$Ag(ShFSqGxKA*R3+fYb3sW`yUa^G#zb~c?YrV9*=z>|gp zhc5M9w?Sq?FhWs>k66muXKh1>#6;*i5H%w=%mO3gcGItxoB4cxdUBp}Uaz<7^}6qu z)3!ZYoRHCz<+VtHplo0P*a(>s$xX)!xBCY5#w){^?mI59 z40r!lD@ArsD`9(P#j46wP-hI+O3N+BQ$0(~dwffEpk!j^?VxY^We2 z>V*+SM)Q~^-wAd{&C(eglGlJ^J8>R@BIhFH*hMfMEHZmdh!G6dXI?q$kds*+0|pDA zDTNT+4nc@n1WZHI5)*swTcBcD0wp9fQj=ha7z+Cu+=^YY_!zCreG>x_<&=PcVHyL4 z5D6o2Fk%pJSjcLsUDp{v2n~j!`7i{f0PfE- zC9uehJ{d%(xDy$K5Dbj-k{KF~+ya15oKM>YAyAghaw)2)nsaWN#?KfCKo}N_6OQCd zvljXZ09c(ATi>NgE5!v&1O_RInQl{-%|^{O>(y-1EKX0if`9+P$KMcp<-z@yF_<2= z%{O0sU>Sb-n~#=iG0apoWF-a62BOvT56I+BWMV+TO`qF_m)jK)bHd2nZ4>YW85N`) ze^f43OK&ISEHkxcaTG#O#B7j6RiFZx$p9Rbwe9+pl7YrRO%p>PGsuR0rDBQYM%abu?%zDO zDAV_=A{-bBwL-Q5!~ll&toliBq@|4CIMFkH`ztu_Uw5imaUqDw3LODTyeeU3OR7ZGU`x6k~&kOf+jJ zfw)g8sU_7co|j6d0%qFh%od7(ix9={UjSg_*=)AmZXZ8>+_dfD=;-+PD1`9j$&<^g zD-~&*b~c+ny1WDpY~WLHjz+Ojz>FpW00Kx%B%lOJwWCQy)9DlduCA_Dt96V%{bV9) z+t#~Wu+Nu2XbM(ioePhlURsHg58)3(|B|@Bo5Y9 zi^jvgTSE^I7#D?SJ)FM^HHJNjRm@C*NwiM-@o0J{RWCW_fN;+tdePKef9X?=R z&ajJd6D7c?80ry<5J1&~d&zc;qwxc-VV_Eb`C=WI<@+uY)O%wy7Cm3VJ`WN-6g}Dm#9YLyS$!Ap~w5ASgvG%xWe4EK4%U z+DjGzfMz=3Kn4zzDiRIX{(C?I0V;Zyk9(5JD8$|Aed<$6aW(}6kH#&^HNWKw08fcx zj8WBd!weY^gTdNVbIxvmaeuLc%9*G}1?=Xqh@Rb(Q%aM`L{*VUT&(GXIWR=*x{Qdk z`4JIdoFuTvt8VqH4-w#%2lppTh_;xu-+bjIQG0ZGt-=CY+y_?XR;63X$YJM zLYOp*zyt=X)k^XP;e-IQDlw>8%DL2x-kOdmgfyzM(Nr8-41QzRxN5y?q<$vJ0o z+**iD!$hQ@eO3d=3ILXn83|Nd;?+jhn`@Ko(keh8Bn~_a}1e=@cu;G;EY6nm8vI_r11ua$zR5J}kktiSs&+RnKB4PrDhNah4lR@1% zUbN0qIur z<}GxIG4q}1 z&1TH}_{o#idb3y@ou8k^c<-}^pFMeUaeQ>t%qC}NXHPCJlXTpa&W{;N2ukRoQeDnM z&@x7%pvG0m=^ya;_*g`*ua_~##bOa-)LJU-oOFBfj(f$Bh^pqH4jXC?@8sich|vQe z!mUHYlA?#ZwM$fPj35cd1(xl{bL|iJZYPq|XLG0m%Q}eQ0IC#$Jv$cM_Mu>hs-%q1aNUU-kiDX7@J+aY*?^u)wfmFuJWoj z{BIjfj^(_wyPQSCx|=PVXaRAlYL|P-*=OrS6qr?0&Kg5#+m?K|T%S@`{wP?^1$Tj9 zSrkYRF~%5T2u-61NlVD~@X!*GIQ$I30EEz(#mtZyi4hrI-+NVInx5#y@)F)zk?YDtcU-ReK-ez|PrUw}{A039(P| z@Zo3gyz?IDrc032vN>2-huC;OFAac|ax}`)_i4M?sshK*v@M4KmE$F%rdd^-Yc)6% z&8+YH&mTSMd%0dMV`vN@hTvnl0esN5ZR94W6k|h-V1xsf6RoOS3ckxg!Ri+790$#t z%_gOEd380LwP&a2%sjSnNY+n3yP6#zouAIt%FtU?LqOEQM~mZ%#~7g{YMEQYh{!e2 z!+^XmRtmtvy>Jy=!KsNC9iu&Mto^jAE;?vD98!kh)(+Ru8nLRH9agB~7PAWK-0jq6 zDkccx7xY%kJ&Y&7I}PU`7#Nm1t>cX%pF$-w0t*CFq6uQ-xHjV+u#=q4`kk>7odhuy zbbf@cAH-+42Zi3Qjw!7jGpZX6J+pO!hnMc)Lf)dm8tR*IM&0la%O7>2*uD&FTs9CO zKGm8EW1w~Q-QaGZwjb}lH`XjqHtlT|ws$H(Pc5=Rzi+jH1^Dzb%DzI5|CM5WyY&@D zchI<`$FKLwhKTd|v~8Qq%ggKQ>$YuXv)OvRy}G(eDa{u1>2z}M?%j)vi`8n?cd2Qb z*>pB(TPE6U*V}F@SpY1hezjW8X0zj?<7wNZuD`sv=yJx`fB^vumkmx$Eo-)3B|sA* z7k3mPsz}axHk-z_dGzSflP6!MzQ1?x&Wq1K|HWsYZI;)4PN8k?ou6M_UvIY^1@_^qf~jqqv(pm>ytufyN@+Tub6^?}T7%{Gb{(6gz9(W1 zJe-_Hf~GO^0qmf^RU{5NB)AR#7ly3aK`?6Wsk1SXpf0L5Oi>P6wyHag{jOxM5tAiO zrP`TyaX3Es8(9v`&{SL>QVFP7qoxN@d`%`3h3X95TLf&6Q-r&4oPFt-6%jfS4Oh}c ztm2M_hU=kJ6?fIv@VN&c6X2nZX-rSu?YR5#i$l*)uv|?<==;7;DW&9ZGKSE!ZD1zA zZrcriMMR-^4A~GR=ah0U*$ll`$^<4lw(p6GA`E74Pq{_}1r;^{%Su@VK?xay8}bk< z{y_;DEFh*)ChTyC9dbwqB5oMkyXnqF1@`Ji+4nW$$AsyZ+w<<$4R0eEG` z%)sPO?xeQfCJT)~=q!qcRqDiOd$sx5-@SvHzwzSplQsr~7-x zkTOulibX6%5F#?MOTLQ9F!!ZBgdxtRr_FS=T4ihvLyf&-15nnjaAS>yxr(TWfb=J^jPi znzkSqn?|IFB_2Twpw9NkTDz=!KxH#FWx%kTaPAMq_S0KxN@AsTRGI_<_z~9ShhT*S zHeozsYzac;eznLGf=*?rs!$L_m7-^2Xov+*@2ztK0CNvxsj$m97;VoJ;Imm61rY5| zB%Z>i*vDtok#2>O;67^t#|73{v*KRP(Hf0ooa@eyXwPWocz12c+ZuF;H~Tl+{r=q8cm0NCVWOnjv;}e$x{m4(HUuY+1>tRg|_}w zaTmrI&d<-9CSG1%=A38KS;x5Du5<1+FXr?4b9e7NX1chz=r##WXVb;BZ9+sq-EKC% zyQO~nc)hy5cru^OfT-WBRaH`tv5jrS7@c%vpr(Rm$ua?BY}`a6qD_cEuv#yhrn!Ib z>`B0ji;J8#FTL>K!3*~<9zA({eVtO*PNt_vM;Ch0bsNZJA!%mTHZ*NubO)`8B#|~m z4gu6t?|tNLlQvB5ozEum^Dn-*eDdYd@ln&Xo-9;+Ku_}!5SpfvP&i2DO7}xYDOaT% zU^nsscMX%Om>^~;BgD8z|)G{73H3fBQj1HYJ z^h9rG3>zAdWK#@oldY3OU!q(vd)SSu*VMmYs%@85?R28+0s!3LXl#&s~7=82gPnUA``q=%M zga|~wxutB`BL+& zfdRq8^7e+>)ibB)w^|6nuXEq`ecu6C6C;S`lwB6$+&d3_a>7dC5(n=f;_d_?3Zg1X z%+B(ybYf5>WKIB?2tq`q)p9K&A&{9h+$^{K&)@n$4PSZn#Wo-rG8$RkP7KB)Nw$47 z^==*k1`s22;NN@o8(G79AO3ceEu%*_0w8U+of>*H#l^){%}(VILeoT!5s<{dQpqUj zQ>rOjA%q=O*et1d;7_GTfOVVoQaQj2(ie$mL+N1-Dtkmm zY^(s;17bi3gBqV4WS}^ZzI6w<{9BN{KlSR7=8z=(x$icf<_;LYe~7`l44Gc}Yxcc4P^2#5hO5;B-~ zcZvxcO_+r7*i^7!RsF5HQoi(a>N;4+@r2+ZBBe4g158+!Ei~6w)M|EApCDNIcFa{D zI94ScOk&GHcGOMU_gC&(!ozX4G!Dm(qy0YF;KWA&wD2@tnC+D8cyk!&Wu@-wFx(px z+g=A~zf87b!vGtL%m@*z`iu_+T{~sX(2%>i&>Pq@MxJQ+jNTZQ)&uVM3~`XKc!0y$ z*uO6yHV=?LUd-mxHl+-Ji}}n#RY9rvCv*YKVyL-J_JC%|!cv;|Q zxGGoJs|Um^%e`T5ANluoEu|gSU-gzj;en>m#u2ryK*Vv*+UU_37O3HQ8NGhJoo*cn z!hW4%Frz2e`SND=AeY6rf69U zi8mq{h@zQV(=>6?0+5>aIk^T85xsChLLw4V5e2|33XnKP4oHAa6Nt$Hv{}?Qdy$lL zPB~fNIGJ!@GDb2)QltcuMH7+`3PZ1*ZTh(}vEP=)RNFZWq8X?(@feIu$-1r&a!rsA~z5iDuQ_s zjhfX!Oe6yLe~PrRxpV)yWu|xD|4>lO6?@1E*e7rCEk>na>wq)MC+Li-Vi|nawFLmrJ4ufSya1vjSkB?c!>UajB)6WNN0N zL6GuBO70>fPJkjKQ!%Qf7g=HR8fu8kYxc9dAITbX>S8Pmj^K#O#;?8cpYv|d? zQX8)E{v{iwZUWwV10s$QaY)P|vZu)sanl49LxY?%2cFNSZCkqALqA~mf@Y*+9%@;6NYo&ZKx4>7gdJ+#nEJy%<2Fpk!K+RcJvmT58h51HBiI^s8d zHV~k$Pw&6~>nE4X(%|v(tn|wat03y2#;Pm^+Z~+u+E+Tn5RFH5L-#A^JdX4j7pYo@ zvN~RYao6z>F;ycX_5@5U)nxfAh-wCes)aOxhy^)emL(ID?;tKp_Cc*=O{zY&b!QS1 z69zNNVqMB9X9Wzgi6MsAHnGW;Q|gBz+ed7YbE>McNt{sINDRI4teJqCnDtq+SXLDi z6#-R9A|TvM1A(V9lCM|3f~gl*)kanWWPRCI)zxaX-fRG1GMUU~vo;0>Fi`{)5g=5v zoU^wNVV4t6s+v-_S}wh#Go4ODY*N>)S1SSA_Q{x)7>I#c5weITNmB374?o$(@bL9a6!F*qk6Fp!*Z5w*SFKz=6bbU zueMzx=CkwrO%r1~GlVYnh-hfc#T`q4fYxUTq9KHwQ|A^%vk*et&X_5L;C;}ld_vou zq1;fw+3?BbbqJFXBNKC+#5OSTa<$#0K2GM|>Gc1EmQ;K`SZ}pJ)POlPv=BJQ@iI6x z9*hpAY-WcbN3$wu{Ko`N;triqI`5wKWhHr4hrN3w`l{l*gMYfuAjW4ESoIH?A%YWw z5CwOvrUUUGSwVxAYf-G5h{Z*y9xqr{1=z*jK^Y1RJ|sg0$mpTsRw?>W_C_2d^6iEI z$UNxamVSPjS->a-9mmxQ?al5+&H%e9Vk@zggHi?IsS~vtT4Fr>IU8z1y{*W=XH?`j z^dDLZ!J%ycK#KK~A_3kioT|8Y98BcH!N527-B9N#`geSWlXDzbHxk|(Akq#9a*LE6 z4MqZv(rHFuCI{|006itiA`}#n0#i0iDVfItRBZ&*eBeRG=vWG=aw1C_&_Icx?>hrP;*`bA5V&f54GEP%5rJ5}ucp=@ z1%JyWcvL~r^$@8`BGLp7OikcYIAU?N6wjS`_B9Qzs{u?eA}P!81r6xCof{eq0}>#39NAW-@B7sEh|!AU*h{co<##Y^+ljqKtFmUX-O*Twql&pl zQFJH86xA$(7(SU|Dev`dMkWa;O@ZWdL9@1P?#)K_r<1qKb)#D~giO8g~68D>JN+}>5&F9nU z)C)>>e7+e19+jfQ_K+v33 zl_(QQ%IV8TD`-zRnjtDck}Rqrgc9qdD5^QjX1iUjH%%i&VODW>P1}YLs-$hlw5z6L zFo2Zxi!UE-`y`^X+3f86h&iMro6V+eJ?Pb`nwnIcCFe>s%@SGL~4Yk<7r&z!M z_j?>>V_EayNwh=7`tMRs!M?3*m*HyG3-o~MG1_KHt;;fy3v3@Xv!h$?iUJ$T8nmyF zf0Cnqu(Y}&TtLGSPBYL?BCSyJgml7D%`F1Msz=?Eo--XMWx ze;~^DUF#X!E)>OGve?SPM5CW3k4BPr`9QaN8;$v>WNRO^^7I*X(!fb2e>iY78@&D-Yu{Pbu(6M@Ui<;7~rO}u~qE&y!1?e*2w#nr{x`Q2^Teg4H4F|-sIkT67w zjW$suQ4E5Rb0&e~c6t;d=L`m*0;*`HB4)B)u0HwX$QTH3)k1zZ@u-_YPBACd&kF%Klp<`m`ogfbD7JRBM+v~E!!ie%40|F&CN0+sIAZYmT&JSkgOe>0NIU5iJ9$0wZ zSp=7;iC_qA+fJbd^Qm#pN~Ebzo6UxZynKlv%%;*3zU$Ykjpj^5r>Ccr=@bBSF4{If zlmlYU8JUnMr4&LG$&zKW-E6m8XSmE}ix2_;Znudjk?MBa^?d@>ERs^*m~I42u?;i{ z4IyZsR5ka>L?%s>a`wtOWhqn;FJys`T4qd{y8oBG_j-~fNzOb~)y$kkM6%+fr#VFv z%mBCi_5^Z!|MK0Q$i3Vhu!jXO95d6LOjTDGuVfMKZe~jE!Q3Mvvq<;M?24=a$fxSA ztc(l~cQZBB@B4j;$4e9f5fzSxfJKu*#k-lHBgM>p>9i3c17)Za)ZVa+57hum+uKTv z6^kgd3_~p0K8Q936?s>lS!S8`n<+P7iYQgHED|%bj4@*5oEhZIF{biWY<=LJDGGy< z5wVzX&T$wPiv?m$8_)!8cLUBHf~P3C%|IZ8rt5oEEU6gT9J{LY)bcIjh=AX9Wm)>^(RDc?cpiKG4Y2#)LwP!QCLOwuw!GL5Q$ z*HNHRNDrx|Fpb}*1i3rwBL&3 zBmjq7NPXA>g8{CEO@H+Z5sn|j&rurn~&;KKy({Q#X9Y}C;)Y>8F@}u?YSYP4$zs=3mqHy!gk%$ z@c?D}+1Xh*?;byX;#{cfs_VM0>sDR2zkgw8XJ-%m!v_zSr(IPw6ub)|sU@>vqJ2v_ z!m1GwAPE4M(QV4uG{WrK)`yBkQ`Q(WtcJ=t&76GN_toKPcXV|4_{o#&*RNl^aG{>f zt?wT^e7x$0n>TNG-?TG5JU;&R+dCI8U7pW(9zA-JRRxIZ1=VT|YE4)Pcv1t-dKgc4 ze6=6EQ$saUK`n_XY)FgUy>D+F9UYzAynbz3VGsagp zR@k&E?JJxn_NA?@x(W70GhX8j&Z+tkkwwT%K?&Ssi9QQ}!*#Itm?ypNZkKk3h}iQB ztZ4?k&hXv*>{89Ik1ZSNg-B@`jz0PIhObIQMQb<(7$O3Y8k#XHd4NgdHDL$Q6FDMB z9?_8xHi0%0E3%sAu3M!v%w|npRaI3v@`TjupbBV|vn0ZplB$rR#zZ2Ob9GgCPK;+Hv=;&m%T+Zk7gM)*kqa)4?Ey`$@Dz!z4bAZy* z0-|9URH5&>RoB&Z-84<`z8nlv%p+n~IK?>hLlQN!?sSFVu&x^NGA*;f-husWdhgq|uBxhB-hx*UM{JlFxuEe4RWTv)_=qK^-ck?Oi`ocE<~ zs(?t8VkD&Cf&ws^p?L?WYvlo+iI@5wllr-5as#y*`v7H&LIWA$Pn-GK8ZP!iY0ZY; zhoh2d9MdR_XbAxjBo#_(X&eEWcf~4)g^xBK?!bdNKm*_n2aNNH`>jgO5(#!00=(q7Bm15lWk{$Zn-iE2+!aWHUc`t zjk)<*b;H_R{){LyTH{P{1IySRMbp`Lfv^SqSZC92-r=T-8+&rkYYy2o(b()6w%zDD zgN#3$W&RWm(+c|`=rY6$ARFT}efki`|EiXkZy8zMSUQOf`zC|M;*!JRl5?fGk& z6q;GiTzIhtgy_Kpi*~bghY_Vj<$z_CiN0a{by%7Pju}{yK&K|hI6R1)D;7`Ahmgch zPfv!fyRd&SYg+(PEuwoX5okql&1zsKV5v-I&5n;xo2EH9IN00WEn=*-DsC8tlo9}j z;G1>^5!b7h1Js6pQvZ%3unJQ{|)s z0q6)G4M5{UgJV@B20V7Bb&Zr#o20LJMlAb+w%jzZvT{z*5)**%JS4%Ea%N&KZi#Xn zf&(h3|4GZBn|a&V#M(Tr20#vtPz^;3<{8Qjt%icYTHdd1MwMeT{zX^*jIm&ACEgYx zoyCux)xka6Ctzh;cxH8uhzQT4bK%ooy|P2N=TbVKnc)0GObq9C9s7dfLADU^qhKUO;4h!8@RG!yvRxRfU7&;0}*Z*kHc9)31j6j~=du{`$46SFT?6Rdx5? zy+=j=?oiD%o8qi<6e)-DPtIpT=?%)6N>u+w}xVF2ud+G93AL>Vs9<_CQd-bMz*R6t2>~z&(vu-ChkVdBbLRrNphi&Q!PHmP&Y}fGHbp}q1@LMp zhN_eWhR8vw#EML17$O>?S0Dj1Acc~1fl~bPQ&N}!WL>i#HB^BCq_l+BSvNo;AjPc* zI-Rp8I2}N-@@2tPT?n*fz0< zrl!ovER^2B7#TFFtY{4eI3vDXCk3uCI%j+NML}Lx(NTdjo(oI#VF@;Py1>G*&x@jy zie;SlPt7W`#A2w0K0cn8re+m7(rjfNFYd*Wq%Tq!?#xmS+Q#a=SFtIMyleuN`Y6JI zoS)6XFvSer(8UtC!t=#qcXzk)PU6s=Fd7*UBPc)u8=O-_luT7=l%Hd)I?DdLvlR%49J zdVG9J6soETAt0hiE}ldH^uDT^MkHrNMDXMY0a?)$kVGx9rYubWF$BaUT8*YxGli4m zQ*vk~gjRXKIM}JHI%X+dz4Asxgqd^ZGDLLFtxwFQS`by1g2-Ys^T986_nM}u>ZhFrE0c5TH!pKp~-khb;ssGPXuY>vme5GX3GG8bVS z0a^;cU?n72%tSG3i5fLUc!o9bdH75`UozoSy-bAj6!;f>nlJp%|AvN#|53i|d*E&M zj3TP2OhzK)pQKMDvc0{XW;T29l&%GrX=hCare0Kj=i&Y|~6-kgUJOdyE@IGXvYX%r}{_RHlg_=`7h%op{g zgWbjM;@ex_e(}{;{lM36UcPYgKuo{A`|TIse0}xm^_$nPU%q^$uA4izzwKkZdigq` zyLIPoJY7L%j3OamE84VJd-JtoIPOG&}e`n>=++WT!R&g?5X_g5nnpxj80MXs?5x} z_}K+fSTr-+c-S11Pt-tkGCr!7%xxr6)d^RQs>Vg=ZsU=#^wLT&vVy6W9%Kf?oMjEA z9Q9t?%jQ|BpKW_bM=sXW4ka@)6`K(F>KrkPuwn5~ZWUNtJ`5;Qn^Gu^n4#&{C~@_r zS{f|~h=f?u61_oTp-*i*%$WfoXK{e!K-HMV9DxGll8uKsOJlv6Fq!~l)x=`n6_r)w>|!CiQWgoK?QB+6 zp{jfx+&YP%j6TN%8`Tu!Y&PSmm>#nv5mL@E##PseLRD3Zoki2OA%p@tU>4_`sFDjt%xr-n&R?USz+45n7VG25<7C_95~m` z8s~ix;{%`%6(Wf$0@U6WZO-n6og0_m4UR*=y}eyuSLn&xpCmxvj!cG00Z_PIpolV2 zh!LR#cK?v>*wdy%MBId@!ie50JvRqf1tNi{h6ELwM{o#)V;s5wqA{C-%19tD6u9Eu zEJ0%kW-29+#-6c@Io#Aq9xxyfV!-jRvIQ7e>(uZ?(zP*5vDhB9$)S!CAEVocxOxwBjzT)1@M)mL9`+V;D94<0GJrcAKkco`2d`LclYky@9v%+pZ@5joBR8_4qv`?`}VEhe{=ojOS_BRFTeQu z@zD|ZWZprWY{9r_sX++dn%QYg+zpB4VpG-RilPe48Il?TkpT34OsP9MI$f=XB67-E z5GY2DDFdL2mIm{x8$>i`RzNUffquw+pNQ6EI~ay!K*cU&s(l~(A)TIf1r1QXma9Hx zDO&k*-G?Ecp01puBGgs2A?D1ISx5IFN{oEE>}RufWFkd5UG*^+@78!2O{`CjPIh({ z1$X4AT6HmI84?2+p+^K(I9>K&>JbGj8!T5tjFPj03A314$!}gmD7Li$=hg088jmUF z{)~`d>K-Xh;+P_)$;?P$JyDp@+fD#~4qrG9keSR{n7*x3OSQ(3Ks$&^P#ZX#3} zGk1M|@zN!kWN4go-*qv@A;zk%=8N6gZ0>z<-i-tBjhlgxRSl3On*e#`Lv8EgIml&bkC8B&d@zMK3NX^rArsDUAw%qw|nQ#clYn#T`U$mJ9}1S zz@Z90i-@q8nn0PzIC9zNfUK59Qcfw??Yyq4+3vn?+WU_mKRJ4Qb8qkEYgYsMS6+K< zKAS&&c>l}Kzqs-0%LkV(`l@>H-GfJu9vvSYy>#>DD=*)8^NrWO`ufgipM3KA>u)*oEicr(z%aNi zPz3-nlajyN^>Nz1!OR{Vp8S{p@26E&si`TN(W>tsJUT3KW`JrS%VqcX|L{xI6r9T< zq8M|2_~eNwmceELD3)f%$bNe&5__%XfGy&(jXA#b^mKd8Scgqui)P-C8@B2;TPN;_ zsDL@=CP3Imp)1Vj+&GGbF-f;fi%e8S%k)jAxVqBv0Yq|6gh%i6WYQLu3%i#WiyiN) zQ8c5#rlJ-zn*t)SDjFC%MPec`>4g(25Y$c6)K%@m3`jY3F|`J@0-1<{a#9sQG#$Y@ zB3U?dN~VfLpvat0SF3hsr%^S|vF~$EV6Zb^)J;Q3wXewe%$#B-bnEa%Q4?h;20~RL zQWfEX&UfTI4~fNq-0^aCb-uW;yI=WGKF}lzETwf=M$v{K28o4PR8va1X(sTb>d^Hk zr>6?AzrVj&EIc_Jy_rsgy>GpdsnM9#1}q$hh=`K2fYqTgFeMNG0~Aq1XR1Tyfh3fg za!8`qH0`XN#mtd&7UmRH7}3H+LU)dsxqSKsIZ<4SF~-Bg!_{)>h<0~(c6WE{rg1)) zA*hM~QSsfaeJTLp50APh$6eR=>V69M>+Fy*)?_Jy(_n7ad81r%)CG+ zA~|zPIdMKYJ&if5S*WV2ZbMx==gPBMG=D_oigKC|3^FJISLo{C7PF>l{Jf#XqG}ov zo{7roGCe%*9~^bx)4_T%f(XuXR?hXG3(Tq5ba1psoMRT*3&trpdcmd{zJY)hfx3=5 z?s0P}q@qAmfwcxxjnPr&0bA#|h&B;Cp~EqyMGe$M#}&qqHk_n2|B;|5Z4D7TK!sS5 zs~m;mvjZfYuvLZaw;p9807y~g7kkSF)G!(4MuXr6%Wmsj0>sU^l3;{_5Kh4jpb8*} zg6IH5iN{zEL{(4*M+n{~ir@>1s^=(_YzuPv%%b<~w?73>IFA;vf6_(L^B*L{%?#z4 z^JhI9Jw9eJJ#W~$rM2H=%x#*c<^Xouy1sVhXlJ;4??Dnqq9NsP@7{ZSbaeCP^*7&q z?ciYli!Z)9JssL+R_sen)2i7pLHkp*MMDp*rVOgu!{nX}GZ2(wF$On(-+lV=^=miZefPb+yZ1l&?90_^seSKbgq%foan@?6)M2c`@z6iY@%pSjAPQ!} z07+CzppD#o=y}RARYgeyTb(OLp(z5GMmaFp=4MQExJPHVT*&m&(#=ti~GZ|uM z2F`gRQt)hgc+z$8f%lFGOMhtescrs1L(Zq&ebu}Lg_>A*<9DhV-?{r>(vRyT=p+DN ztTAekMejX4B6LGcoU^UDC+Kw?Zd#x6H@EJH2%56mVsRkI>O?`+gtMVI*Nb*4GiIL>=O`(QNN_Z->$-_wCTD48yUl!os+=;503ngLO@6iFNH^dl;s6v;3{py~RTnviy4pK9Xxp}Y zSXokG;v<@>IwB~2DCL}U%z21W754V_7K=sK4@6!8vw)7f6`>gcE&DX1N<={NtZjF8 zck8Nh&JkkY_soT^Mr4-D?A#Px;9?;ZX4VG}AJ^@inM=6)<*U~!@0|C=G&;snjW7ii zfNe$^a~}HD!G((l`+H406U3PF>FFt}0a(r)V?^(uyiG(_5Y;~A6dCBG>xQoDhnN%~ zRCQJFg%FD3N7Q9D14aagx69S|p@w7i2;wo!Y zH(2B6jn^O0JbKage3o0e=F63sE}Ht)2KGm&=hq#%aefOUUgewusL-X|1e#xGeXL;? z4haZ6mRaBk`c(uei;As7h1U7d>*51Fq5~XtS73o4AU1^SK_pE{VY+q2?5QE)Im6|c zguTu%dulW}F{ak6sVOAVwsO|Wc01(<8bBbb5LAR=1kM-~*#P~pD&gGs*$eUnah!8L z`)>J{meslISPrS*Ynok?^!~7V)WA^3T^*4SD~|_z^D5l9_vq;OWTmXbFm&B&7>3K2 zFC850fArCZ-+uex!TpDTj>xkp^C+|qp(>ObG{6k#J>cYdW?+%Zz&zcK$ z)2MT6j3wCK!NvDK`tfgn``d5t-M@6{A{#ixtYeV;HNg;pOda8KBLdI6zDL84ZL$e* zU0@a6c}eBlN^KhB2#v<$A|h(}txBTAx;w8bB92hUa?{Mz5ZF|5)=B8?5CKU>X%6R< zOR7`pX^pRCHma9YOA|vy%sBvXM5?ANoKrcdh+0z3%w&+&1RxO(2nHsqPNfcEe|Hgx zBt-}641v{|5t0c=mK3w1Td^dWHh-ePCo zwp9pdz`{9a5di}gPytgkLzU5$Agn`7N5@BfKMccA*I{R|Xxp~1PYEfrWYM;+SHp4@ zqi#v%Sli43xs0gHnlccnq9Ky=!VndUABMjH>1+RMjlhm2(x6Q?r}|06nQgaD-&)Oug|=@CS=#XTCd| z`KqG2_H7^!V5)<`X+JDiL&~fG8AGNf8V%y2J})h9>zTwC29-Q5UEZ>zO*o}d8uo1A z$a6=61<*g)ugZn9A5aKxiLy7gd|xs-92WS^hVo)6Q!C$|Hm{Ap2380aVgRkkDuPg= z)ypD{TcI1Uria`4rOnnkdQ+5!OP!1@oCVxfr{EctLn<^Tyoy`o;3a_Ro1wkln)1iDxzw) zp3klv9(K3yeAh2oRUbb(K0I7rym0Z_wQH}u{E~O|?K|Ja6jO@DK*XvZ>GI_ZD)QjL z{WuH`6ci>Bm>e?IUo0h6brZx?T3A!#8qrV6w5ukjG5sHTNU!I=f6 zSlCcl5!9+lc|(9Dga*nyRB#kcfT@Y90Y=fpECy=o$YEUx=OyQ*=C%$yZ8NKzHdG#A zSgk}dhCsf+dq|CxP+hf5Y&x70U>(?#WsOx$*n@t(mHueR^0lQ|-BAik}#1N_wLRD4H2LQ;KhZx6HBGV1_9c+wO zD)+WXKMehlPEMD7KXhHEsuwOS>bedgIOhQ%#z9O9&Akp`PT*C7$*iTFMcA9o4)$kz zv)~+!yB7hdb&;3daLlsGqUeztHHboehMuh#&5B;139~vo-gv>rX)l_X*!J-eo;^u? zW_tvw(7V>wdHVw_^mazLHC9MALG1)V*WGW0T(s?5V(_yd%JJBW1Z6%L2m`1ym=Frn zF#^`959^-98F;%+mXqyv*Va+e+>5+^<8als()8BNul1=J(Fh=vK{rxXVKV@dQFmhB zKOzJ?E2_fh{i{E8>&J5`hkuA`?vKTW{Es_D+!z{&e#rg&N4)WTkT)uRX)js>|3(mQ&D+QZXRZNi_z4zYRZ}dO<=Id|1{q~Nq zIdW)_G^!c0aAu4t&r+DxRb8p~7V2dFvuU4;IxOnBtb?@unee&DkH@|!5?YH+Y zTzb{8kNn`leb&79_~L7?{pc_M^3QL7``zz8{`AhBTW`Jf_P_qOKl$m;e|`V)!w@5+ z2suNNJa1f8yK2_O;kzzzw#)O`!ci*$Z9S{r8>2JKx@MFsXcpU)^)Fhzace|qy2a3ykqxP(;HDDiWLAPN z*bGI=CO0k5T14w*GX;Qxl5tuhDUgUJh_$hruug*rD}@tt33QRt#Q-Bw0~XM6n;k2R88xca~jAwuRv3(41ktCv2#w%yeX(DgR)5hI*q1JRkIkQnsr^5Qi?G? zc=%9MtE#G-dbYbmM4p_P30pC@0|1MO7@^}Vm~xES%sA(j7Tu+b_ullZAbu4+_ zw#}@q59?voWzMG1wlhRxQ85)01t4F75kaJ!AqZZl=Y49)%iJY77?}nziI~Wua(G_jz`z}T?sH!lZ&6~DyfP_?jJpe#*F=uA>ArzCgX5o}U%^^ijBJ$wD z0}(wuJX-Y(;M=y@neUT#P16FPh>Ao+s~s#Vs(kQ{Do+PBT;5&m%-wwM+u9K!5D=IM zh*>}IsvCNiK2uUi=mi3}pbVKgD-H~OwvHtUczs4qwFyU~=OlxCpL2ZV!cTwPY_D|w zh0gzQhlRh3o<`{}KBMD-&)dM%Y}&NO@fe;3PO6O=p(4TpitCudwX6BOEL6e7urT*T zjSK8#l)})~P*Bg-MCGutRc+#*v^V3k;%@Bh*v>|(8K5H~LQ#ZLr%rt~dvSqv?iIhc z?!iB9?>`R(v8P7E_|Ia-xTRb<|C#7nDDMxrMJDe2hGJ%>R?-M}7xUL&f2D5Q-~8^g zRo7Ql6^HKeqlXtRUc7$ur5}Iv;q6z)k5@|)kke)ZCo3kM&3@aLa={K-#$_Nxy* z_+WSc;QbH&tp5D-`wt$^cX$8(?|**%`n5OTe0_g^|5yL`o4@;qzkUD1kN(4d_;;Ut z{mqx(+~(D(GgVg3J+yOI&%oEo+;^*PnfRso+zyUyuOx-`ZtI+kGSrlUlORMxbOmuP2Er<=NF?LEZK@z_ zoK@JIBSR_@A}y+{BH&duMb661%;F6V1rUdvPnJsth@5>@gZD|8S)KDuJL^|nL!qr} z5}_z1Oj;2NE!G1GIz?22mE={91A&1ps=94jLYF~%1u(@8Ov(U9iT#uh2!zfI1t?Es zB2fY3$hqtLd-w16-B48xBF<+!^PNQzw3X%-5}B3SkyLb|gdl>;iNW(Q3}z-Q2pGa> zRE#n9%hl1*v2$)Vn>9`CiB#AWm{r(@A&IE>W`-l!2vika@rtNU!C$V_iilJa0m_LX z=giC$d%F@ z`6`6j&Q4u5!w^HL(sJpDJRlnknPoh3m?M{RUad}3Vjui$F`q4VLI`8pw;7rMfSTY0 zyU#fn{;IKQW=p~`pPrl^pBz6qK0>6$Y;QiBU%b%HW(!Bixf26I?+BbH@2U2%@G$dG z1wWs)2mAGSEX>Mg280Z*&v`ZE<1Y1y zy*#C2#!Uc;ZR6LU-IsW3({%>2o`>O>le$JItpnWkSrKdm=v`3^SwRb~+aFluZX>c{ zI--v?85jVIl$0w`Lo{dVk;+dfHXtprSY?e!hxw;f>G;r_8kdm7C-KjUA&{XHyhEX*JdOWk6zgGGaj)>&aJ>7CHjweXN5m`Cm zw17YzjQF%QZf_0;dY5Dd}3cqscEJS`e*I9!IXUB?%56Fs*_Ro$X|c6Vp?`Ms}>j*siQxp?{V?OUgJzP(L$ z%P)QS=kMOUdE-~V{LSIvu@_MhV9@Twnq-M%mOhIEw5Ep2Cvr6*=5+eq{U4n!-@JbH zFMjglU;O-+KmFOyKK$r|iw76}?4ysuXP+M(9ldnp#+P4ywmdod;KTR-KOi4I{`iw2@&3VnA>T}=8zVJCTR*ZO#jMF&MMY75lQ|svLByJdrjTG=u2!s2 zRTUy_O$Eo65~!>@Tcy3>&=qv_rl+E6imZN{lr>m9X=pZqNWst$|Qe zqTPf2s%nTxm6M2yCbc5$Pnolbw}P$`0X0A}6jcSKv2}t3=)i#@I+r!(m{?`(W0GTm z82hdt`u=b>n_awkFq_S)sv_^5bKW5#a%Nu#0%V0%w@Q7-DKYbE)gii_ojDOYM`g!n zRzw%7dPunnl{1LUr+vSl1prb?IcG2nRlPIYS?nyFBNHv4(e2Rd@|{GES#uWeCFh({ zJUTqOb?esMJ9m7js&;n$+DoBoy;~q+u~q_T?P)QqL#P6Q_v%r1XW?LGS1-(V=S>I% z2;PB5=p)}>cAq^s{LQ_iZyz3EC;#g8cQ0PLq5v5(vxp{DQ#R*(;XNptIqQ4wBRdy% zW{nqnrgVLsf(Ppb>De8lXYNT;xSLu*8yg_fm?b{Wvx>4*w`O_{(GfZTKbdfBD|vC9 z9{p5G$!3vIFfl{G!Vxu`#ByhbEx11Jmj~r3$J;Z$#59|EQ>1cRg5fB2apQtU+Zw4& z<7_f`jcIm&;MQ+v%w^wC5yP|e1Oy;ZGt?0rhHLEB`q~jZRm!XznDCUWiOnhpK-B2ZQwZD`qVNDw&z};@ffouEM3pYIH%j+eEs0=?U$}!ym9ry-Fpu? z_HVrPR@cX${_O9sUA^+-zxc`3YdgW?-hTV_H+cWSz5DmGh`jmctJkjYhw$T1KK}B% zZ@+`6iBpW3`@vGu6d@;5b$dImof%?6YIk;I)qQh#v|27-y?NuuKl#bWpMLhMUw{10 zyYF1Ra{2YQ-v0d4&sM9|kAL!$ufF-_|Nfi5`QU^1KltFit5+}o<8MFx#ozwzYwx`C zKmGWlFTei!)30umWK&G$0G!ofK{+;*UYv!|`|NIxr zp}%nPLfy2}*@fIzZ*S9k8b2eQGC#-WMANq2Y9*#^+bS4&Uscud@o@;DD3Ld7po$2? zxFmpct^lJ|gv&CV6wb_iu)MjJml(Q6nCjgB| z8KY-uEy^3&z?8wxg4{QA>S@-w`Rg)F&b6W3T+~>mWpMFQO&Bl0s?2KV>S$$fr%v+G*C4{QiYs3=WIkVi--oa zV*Y0ptpm*3-UOqxRaI9N5djOEaY{K=sphWhTuF^Zq^1gO4UUd;w$qh&*fuSaA(#^z z`hLjLuqqLoDT@UaVJ&b09lcz|gMdWNg=TM`=JSq7R8s8Nw62ttv)T#m4gmQNUK4t5Sxv}v>0FKC00U}@#Ppt7O6V7f*12))Fc~34aC{oAL zCG)PJ($`5ie_9X2M)ARVZC2GWiqEEK;WZ5v*I6@X+aLHGne&H@&FTOi}{P^avQ5{a?tr9B;!{o8E|)55w@v%P(KOeDJ{s?*?+;+`cW{fB+IxOj-KQ_Yq^(A;|@` z#ax|N^w46Bv^;ro_p{GG{L!ngz5QYHDF{MlPE{piN^*WY~e>o2~1{N%}>efYtX z<0t?4@$XKTr*FUU#((;&fB&mrefvtlHEyB80kX+xGDAa2STgVgVaU6N@k+h7eqVI{1(>4?|)RB9G1^Q8_~o zF#HC)6^Fhi`s{B!gPRQnmG44 zd2ZCqg9l$Hhl3SwV5-UQ&*rT`j=gd&s*=@m8PNffB4+1O%31|sCJ_}8BLHF|MndO+ zNCDjb{!()8R;0Sywg*k^37smc7GRpFWae`Hn8n60!7-2s4465_BrGbNbE=#ta$uI3 z3zDE8hG7_H?aYVTIbZ6k@+klS5qjrTxZIFtmU0%Af*RMUM#r`26UQS30A`lVV#fV2 z#Mlo*WahSQ5BB%l*=$`@tqJVjdmSP`>J3cw;p4}&Gw-{8K5yqu>m4~lW63!kA0LOR z(!w5}3M?}Sp)#}5U{ip87@YT2RTZACm?@Xn!XoHH#GG@^-1h?jR8`e9O;uH@8i)Ax z*S~+`jo03K>#bQkJ2^QyeDcJ5zg(`eLPd4m)=eF%fP|Sa)zI%YaOK+U;@*5`<{J-= zMu^mq^`zsj>km&(homCptKHe9y8rS)KQN+dJS0<`mT2f!EF1=eMjJ@e{LrIniDbQpcXuRXH(aO?xyr0H4PJl&ZWwRPs;Mu@u( z?S6p|=|%E9`|kl7#eW9X*fY!Mb1jPEVwqfBKj>|mXX*Ox;QjaC|LDE<-+O&Apa15!pWMFv-Qknt zS6_bhr61jV_x*Q5+kW=>7g2jB5n|>Pa~~-tj7eDS>#u+Q<>$Zu=J)Ts`_{qU-p_yji_??kTW`Pf_Pg(fcIQ9; zpa0jRM^FBj|M{=}-H-p`SHJu8*271-$YF7SfZEhTKGutO>NPN%7K}|{;RRcX&tT-QBkmYJ+W=-87(R{wh z%#R;G7S;KDt~nPcOjT7?sGK7K$T=^EB}>`)9FPOR7-LFY;6ow!;609KNW~%qh3&@G z`Uq17ZjzZrr3khNXf2f|dOh4xJ7%~sqOjXHXpnD5hn7PLBx zm|D(7HDulg@4RzF&a(jmW;IiD1>0vfX+%&JREkB>5J6alfCZRkBv8^i2@zBc&rPM52z!%vOD;YJ+e4hq=! zoHL0OovaHQn2N=|V|F{u#ZZadqd5L96mnX_wr zh5tWwZ{8(Ya@~jBB_iIEdu_cBX2HIZlmyzAC6SVkj=UUy7W;o&AI!(HM4F&M1ENSk zAPEdW%nW9FsqU^Nx3@*az5XNK%gm}?W&qNboTtv5p6;s3%$M;Z?)}~0!p>L(6p<*R z2%;J!rqrDtEDRy7!?x|z8pD+51w&7k8b}=&Lp0X9EJq~oL(?=Ok%-cWnHf(z>n=3t1D!d3(n6ScH$TM?1|M=3G=LJ-qC=k_bocOCWsl>k83`QUxqwT799RQjwa zHa5>oHq69;;6t>=-nn}}_;_~bzACL&oAtU<<=}-(HlL1dW|4z+e&pzA;uho4(b!E( zvJ6aU7!jap<$BXxUa!`5C+L_B@>m_kPV1ICb=Ho$&5}qogw=YJ%xi*b6io_8V013a zb7!m-gqUn02C*mqPyg$`PG@ZLkQfL$=`A8qvgeD#>_arkUQ$n$vhK0>OF$q5Ml{^(Sq|tcNzMbJm>lPa zhzA@j%ijXq>{8N)NWLM4d524-jC&gF5Yjd4w{OHR;O)Lk#d#&B2790G-HX`C0(W1- zw^EWQ2I=)geGf1|SqQrithX`kz0?4A|3yIU1E=?I;nfGgTmDgd_So)?92^7GyT`um zXYuBh!QZf2!eNaaUQ&7`Wcrn#`CM-P7iaPRX56ng1v|d!z4yx8-J*Om1e>lY5n4k` z7=kxU%*;f9IGat5kB%OH`gptDK78=t{deEJxOn;Vpa1Oq*>h{lJ9qCaW=HGQ_VJUa zmsi&zLOGrspB_(U^Xtu~ZW@uOAvATfja?T)@V*OPm4Y>d7RaQ=839+DjViwL@b0)M zKl}B^sBt!(&F72d_44V{^9K*^p5D3p;opArlmGZPSJ&(DbpGhkd;k7NfBy3Mi!XoW zgLmF}*fq`b^XI+`)(|5S+Xy7aM560z+jed4oVAt*kOdLOvz;W#Sm6X_~68 zB`T9KY!NW{&@@dl&vec?XQ>afi#wz#*-T49%AtP^GE4~*lUHx#+U!70g+oo_O|>=d zTOhrGXktH_*2C!NJt>goV2s#yU0N-@S1>~G!H39fy3WU-0A#Jhw9gPHwWbnnn+BPU za{!n)ml0C>-2ea}07*naRB1!rZZ^(2AgbGjh@7b7aEF@)HOw6UL5h^UI5o}T0`v&I-ejd5F5FD_obczMCbMiDzIM~fLbxAEOZ0_Sd& zWu*eQo;q)$I3!BFy&@pib$xYlDIs>94}f)ud6qGeM-0rtm=5SV%Eh+2UaeZ+7I{8( z+0?pB)O11HR+<(>oHYz^eYIT77ogaM&~;ro8X4x@aHfwlM2;~!m(8Y=vMdv|uI;+d z9zTu%#yKPkA)K6^5pm~3j51h3apG)+#Fs~CyLNeXEg}kdcIR%M=Kz>I`ia>XLxc(# zVq9-F*URg5wOwsCY|PPOakMy^PG@cbV;q>nXaJf|c{Pz|cv2zA#U&!_cf zJ+f|OGe!UfAHs6EB%*ROLPSMQ;Ygtui^#L*=Yr^*lPHC?XQ!vZhs|oUTCFzgweLDc zcGfZ*W2|#7&kO4^Vrz`EF3Yl_C`x0UDr~FP7`NV3RoyADF&Wz|EAp~*i+Sqe&D^ZuoDmVaC>N{h@%ieLC)b}o-!^K|jnIuFxlX94Lu8P8GV1GH0Z>Ktn}xa}(^Z_yO6rrzQdgPZEo9Sfyt#5oi zbM9Ba`uJym^UKYudi3D_SHJddo{vBNC?YxQEjFNCWRI||*AV=jJE!xqeD>tAA{1qLbbS1)Pd@qZ!;c<3d@!9I z{pDZ&^wZCteDd*U@4frMH^23*U;OfKKYsk=OOGDD|M33NxVSifcDY&Rh8a;1!H_3y zQI=hMT~(0fF3-|*+-Ou4=iJ%ZSyQ*4efF7QYi*`Vs+6WBJE!t~c7Zo9esXySu*Rrr zUDpW6#w2_wrG%AbX{<%U&~?>j)7Etek%+A`gy=(Tnx<(Q1h9skvvv@)BvL~{1O_BY zUzzHvNbI`K`;aOj8ZwoJR-xCs^x4qESK4HH9!3A@_Z6Fn%7I$&PzyP%E5@BLMKn>5 zfhj>FAz^7THce~TF}w`>w0;0_437w zrmDwfdH2rU#nDj{0%Q&*<+Ey~8W)psF6w+Vt=AY>CD|EvzH6E$be<6NyqGT*le{Em zkGS%|l?55of?oUX#iqJkSM7E?vF^@fJkN6*B6gm;KtVLbbP0{+%vb=u@F(; z`7ZcWKc$6*OvsGL)>tAY!aU29HB^w;bnT~)KZ^h+%YfK-{^;n~y1YNsdIn8Dt93+W zo+Dw`HrJO|-un>ZbUvFMEm9H@F&o1wve|5|u9nx=OI4W9=Ep}zF~lhG^z6)7n?NHV z(&TTO5_>7JiFB~-h^x(dwccD^ubQaQz^u&MYExKO8k;ZxFS6cNKr|Xp6fikpr9L4o z+VdALIuT|DRRWld$6eQ@8+J6Bl*Pyxn+9o2hRGl^vO#7xMiJ|-ySiRoUM*i-UR^D( zN0TWVSByq^Sr%n6o=g@;^P{8D=}CFEaA#AR%`-Ty37GDPw!dJ#;G`Onn#Fo1fVaUwbJ4lEgTKnv4ryYW&(1*$GstN+=9ixZ; zB}h_DK+rUwH8}XP58LuvOP^if;~W0<){h@B_3-UT(wkAlA(j#8H>}D2^DnUQO?MXF zWVpZ1koGMI)`8h(-zE^5WC^KCC`bwf;H)`0Ihs$WAAj`m%k$?SeDJ~7zxMUbrv9tH z`q`7m=VdYa%2(cb_|7{agkSvP!}I6QvpioMEslG6y{Kp@C{Oh)r&pv(n`0+DDdv&$? z_IJPb&2N4Am%sSM-+uh7JNNECxPRyVouliEm*?kC0{{>k!<|88Mz+hYeSY!MBIQMH zm#EvpH@@qbh?x)|_|P>?*EXPeAg_fA!FOHTwlPE>)r_av>1jEgmU#}UUGSp1S+BR-tu^NCq6TDw6jlNA z@7=ps6h)TjCUaznhb2OQZPL5AD+wISO{7(Stx90Bo=hZ4;kXk0jOotlao0BM<@Ibb z8Baz{+x>6<`@gL=?fnPue&g%k_~88ys=9gn0;CYa_4RVQ-E>`-yyrx;X<8qms2Xdtq`gXP z-Ts+wW=5!rqADDgJO}m((z6$a{_GW-zBi)0H=WtFFCuR~@J2f7&daLbC(|}nH%(eM z5(OZE2)3%Ka#ZGdk@nE25>%Ltv5D(}h}<-dDwO4jkU$ZKapY>fGR`7#+qFz&jWtLZ zWwl$*aPJj=$T(YPEJdBMzs=Bj6(wlQu(T!nbC zUQ!IRqF9vU5-qfy-)y(n*P*U+rcsd(1f;$TOdjQy8AQ*YJsXcFBHDIclsKJEi#(^{ zVc3Xh2qDpx5Fvz+sOX~l>Ellu?~QfLtWoCkc`+&xk&u}<*@qBg8vZ1aW9PfemoGQl zZ3tmHn;jjWRNL+I7cc6j9*xGQXJ@n7Jj=44JRX$*L9}j~`Fx&m*%W-9{BP6B2_dZ4 z>x-8!FD_m-O4iw226m5G?> z*|Vot+l_OMkWl2|g9mw*?RZ0oXpALhW}|>rQ@^~teDUHUL7wGkGM_E-q98Wb+B`4D z9}n~FV|}i*md2>WV)Cy%+R?e?ten(LX1RI6nUN%b={mld-n9{)7u5s z(9IQe*A@W>;Vx_DO`m2x%tB0BIB4qcykA&K-iK8WRl_G~q|`iW`#x zio_vj8lXqEhAH8|<%-fPkas6J4CH{`8RU%!)*=6?uNZ(xGzmd^->WpQ=}k@tsot&O z)*-j12lJqhgdPOduNHQP-V6PNa3>wWgTg5pdBs=!`Q^~1VqaB7v&|4c&&1)Cso!geU$0IKU;lf)2$Ab^3oQLlQ(zrRGH#Isch&0K z3#?mr_l+k_JYqm1WWu6w$0x^=>Ey!?fAP^LzkcVPcfR%QZ9`2h z#xWjEXY0$W;Jac}%og*_x_bKTGRwxti`o5qcfa!G53a8+9)J4y%kO>Zokx$JKYjAk zzy6PzwI@eM?>@M{D9g`2{j{!X!`31jWI{5|bj&ZWSF!2Fu5fIIWkb$ockkYJHv9PF zU$8y9sJRU6dJg}5FcpWZPTvS>#p;8USxUB#&+H}b!)8iKIB=(#K~b?M1zQR z&biFmELF5O)Gaq0I(xG!5q+(o0r##O{nTA=unGY*zE(PO;4-f}97120rLlvtZjC9E zc@-$sb*%u&c*2+@ljO~2ljnI}lxbY)L83~ppd?C1RNJ)JSH ztZUkqi7hdSYK-g6I?uAqWxJ?41XO{x?X0n*@pw9&sk5!iY9^Pvqj7mWok$4QxyfW= ztbv~I2ddh%?Q*$#{`^Im7srbu^?CPbaZ@tlI8i%l><~slP?m9NVVP0W>bV-e~^%f7-C&FmzP)1 z&YxFxljZsG@yXHANnRAm766gd=4;<3e*};?ElSIVh!kP9T7?iY=Zd`0fz(Sw;L>ur zytul`v)nNI&Yzv0jz%Ly5CI}X#9i>)?e@jx<@t-3tId{}N8{;eJf4hac~&I;nYHYk zv4)$bs_Hef%xC$-M<-`zN8@P`VtD@I;?qyhudcQcvV43O%(M=??XZdDBenrLAAOJ* z6#&^7V~ley*$Y#0*iQ+qiWke}R<-WhDciH76GDw4c<+7ZJMRIYD2hDGLX0mjE}lI* z-)^^tc{ZDx|2J%i4%Nav!Rg@Mroje1nPQQCq37+JJkZbekm^ZhJz|4;Q1QJ|!1cds z2Xe?Q^Uc?}7VXK!`(bDbFTkiflLSm|rU*N265iU^2GZM*nT)TO+4t@1!N$B}izK2t z-53M_dO?N040g)SdSiv?8`PGsDOP^7 zb*x`76Z`LAeD&K%C+XIiC6=ja< zK%GM7+&}n-|EMTO-~av(E-x<^i{qg&N!val0gyoNSBD6c(1jFUmgiYMDN;Zi02KLX zv#yB3WIS!Ft#f%qxZ3D+OjN(OnOZsN`%S900^0kMnMULH+mUFB;r2K zP@$>YWY;vFjLPv?qNwOV>`zq*5m4e=K%Yp1ZP$hv$D`47G*-~M?M#_-X1&VDvSUC& zmu2Zh1VBadA=FK?Ua#w_D$3C$FJl+h*Xz34X4Xtcqta!L7(`>}?U_=|k<17{RX|V^ z32ftokjad37Kvg&fXrn!D;NwhAVgAB87RDcug*zB5JaOWviZ{c@87%sAS;U(FJFHA z@y9lE#@M>9MZ~$R%nQp#dgBI>9*U9}ys;c(NL)Zbl-Mi(#Y>c^r~pFN7-I~f0aR4> zhLBR&AAsIDI~$G1MAUWNeu$K=Gy(O-ok=f7iV#(Ol&Y?m>s4J*#sUXAJnvVHA+-T`NSd+f~bN+9$9x$*Q$8EsaEUFD9ebI z5REZpP209t7Z;n&#>Y6CPEJox5h+Ex8U}nLk+{#KmwnfJE1X4liFmgUm7dHwFm%(c zL<)>*hCK@xubjeqpi$qmev`TZR2dJ&$ruNX@(m0I;gJ7xh)E#!B0G4+Wxh8E z6{TVNjfhH#|J47D^kzEPyAAf9kh^j~Z@!s?&ZQI#AW+0egb2K2-t0m>`k7|$H@&|! zJAVjJq<%)(X8{FO>FLkdvv-k(!c%TSjY!A|YmCDpiwOHX+Ba9c^!D=Qh89o<_Wupz zi#LzGfZlBLkWv?KJB7h5=JyvU<6h^*fp2rGx>f7kddfp}{VT@qNn7>$>!kVy6aspi zj6To%aM>mmS#l=lAsb2((4j(m_RWnk@eON|B%MP9hN$YhPK2%D6ll7bkN(*|`Td8F z?*H_!e){3hfAWw2i{Bp|&)TY5uU6;FrOV6tWcCOD%aN%Z+`yaSHJp||MtK8S3msWfB1_Z{;0ZIzW@FQ_wL>Q zSO4U{`nUi0kAC&hFJ^b|W%DWL#aO}QMI`fawfXev`R^Pp9vvM`L0F?|0J2~H+Sl0H zfA{bH-P7mKrjvPQGXq47z3GK`fXI{qWKG*PP0PqdR%TfyBB&@q6Q-Kk{Ahl>TCGfO z0<-sRk-1_%U9V9^QG_`~8{hWbxQT;e@Be$_*0|wG#mEArkmN~l5dR|zD#$y}a{#rw zq$I?IQi$vVOrgJPl(3Iw+`(E=fJ7lp_e7-&vf6B$rk#w(^ZC3BK5c8N8dMlCs`jL# z{(u1Lqnt?ooQnjflW-J-@b!CdoPDdBlYg7R;h+r+p=+{-~+ODpf7(!VT)9Li&^wd~)adG+d{MqsR z=yZN$3?rzBbWyNJ^!M?Ly+K$qPKXhStTppIW8-48Cbk(FMldNVWEhP^Bn1rsNd1mQ z)-Y35Rp-y1Za3AJzxLI84<0CD)wL#btIc{+PmhmJraeqTY2M+zZ`;-~5uqZH0wWqg z2{FZbCu@XMVMS0yvCP(F%$O`~>$bhVyhv8GiVSQ-1xNw=fF%WFGP`m|qIiffXus;N zYr1x|T3uf+yRIwCVmuj-Mq^{G_kOuv$CzL?XI;j`$Q(h{dqPT{0~!LN0#S-~V&WLJ z>w<_9({9w11WtKgia^_REp~O?TrO9mt7Tm`>rEq~d7j_7bI;~k%K7r%Bcih=v&@Xv zLRnBzWJQrLj%G!X#~7BY%`ZRvw60rgv(czrEbio)BP2xds^0gvKoVNDZRfj)h>0?< zh&(hihy(%v5>=zbAR$CCsM8|nx?(n)wh@3l&!fcccDvnds(KTB$g^xdo!QJOq9}$K zQ@pqN`^Bza`CZyioo?ENr$UVmT(tgkcq9?>t1qVCDEGpwbT{pIR=sRm`!Y)pc2a%g z!Jo8KpaA2LpNOe*?J>8MeyIAYCncuP1L>W(RQHJ+d&-r*seV2m@kX9E^>R-AEf)L1Auwc9VQ+t>0DQ9q zJ|vvo>QxS0j$R8ZDiOpOqIhQv8$*DF<*&Z?=;58?%d4wqyUs|9+-3G?z1h6DxVpT& znjalMymxl?-~UUEir^)RA;OGlK6389bxyU7KGv5T9F^nAD9f_IpbW}jIPao1p?i6K z{i7fL=->bQzt~=Hsr7f}i?4m~-dEm#G%i?tGa8q_`<<`-_@{sUlOO;18{ho;KmPrH zG|lqA`srU?UtHdQ^riQ|{`LRyU;fiS`-`9a;3q#V>f_S~?-E-Ttl8mc;=A^j=PxzD zqxqCG!=Ofph~9hmefb0UlRy2z)ARG`?6@dON0tFO0vi(r+p25oEt4tBQSOQ~g&Ejx zJ)x42M#WfyRGV#?=crMmCw8Mz-ZX93bwpXx{vXH&U;6=z-f&8|F~>tlot%KAKp7Yu zmQz-YC`m#v_bUz$3u+>QG;d3i{yhlyfQ-B-n16BJQgxNUf05JkHyB3Twj*tn3092#KFnn{`eH9sq2@yk#O;fKo zo6TnHtiAuvqhdPY%yr&-A4G+%AvVSsiP1|`-)V>vMMQ}pQPop?ATwoImY6Rg1QiJ? zfc-@#HqJQ-p=s*6t~Tq9YMhKl)7cDSyjm`?uJ-pn?o>ty06`>*@Sr4DqAvJfee_Y? zwum&F&5rXt&+`~#+l8ua6$#knMUhNL0Wc&e0RSWdQv@XAL_wn{Ya$a{GF{tdSr%g? zW+X~Bz^aNWNQ9#Gwo0hovu7`&@?Y8F%k$D0qYy$T3cgR7Lr9s6oew^SL?tBV9sN3r;1J0alNJPe zmUg;IlX8@=R;`Jh@7CMOBE7tL?n5+&%RHYPk5aluq9~<_F*6g9c?)SHVWxOPft5T+ zVb8=qlsLTx#Mn7T-N0}@*LZWtY#DNA`kSE-2~qt5rQLp9_(hL!RYlzw9eVSd5vkWj z@7Jmx)C#J%p_7}4-Y|%M6{H}#n9wt z-Ln&X-3I6Mb3C#Japz6i*-btV?s5rl{k}c@_O)u?p`b@HAQD2?cC7=o))GR-l+VVq zaoM(A+I^U5KA-1B`S{7xCr>_Et}egyrFX`oA_fiKw{_z~<4l~DCiS&QSl6|78^3PZ z=U|Kl?hutoMX%SZUw!t;CbXvy?u^S7ZL52W$(J4--#snMOh#kV`U;7E_gi22_~TV# z<~0BSAOJ~3K~zuv>Mwruoo|2l_kZu(A3VJGH-G)}Pe1yw-CTY1cfR{C|KWEY&htO| z;ScpWJ$Ue5XWXUtH6fBKXk4vV*XYaR*(7ruy4)C(o9}+>gVWRLpZv-9fA#6pa$>T= zGIK`6L`~gRp?+|7WQ_v=rlbbo8|K8=-wTssx>|{ZZdMe@O`AFIeBLw-ArTwq+k^F6 z%RcVreR{K=?!TE(Damuv6e-c4lbNWZQDjl+x~{4lz=2B&c%zd&NJvZvWUA{#WgtUp zh_Umr>%0mWWAh?IVq^*`Aqr8lw4}jh3k@*=Fra`kArJ)(+s&qK+N!EW;$ptIdvdy5 zubs8X>_g~$2bvtQSfoo37ZJq}o30IAuz5b3P3A{OF3Z4hRP`~mUFVD;X5!v$K)V1{ z+j+lfv1vL|SWIVmSvZ#iB3mN>KBSrwqeLc5<(=Yg2g78ho-PO?5K^*mWI$$2Myx4d zk}M4yKJ{lV^?cAYDn&v?X}fM)ZL6v_Otabi{{4q(tk!jHR^-am1}})#xr9L`w+jgY zRTxvaA7kIQE21(%mf7@bLkNj%&dgbsA#l@F*Vk9e>+8^Uqq00bI~$D(25g%K0F1TV zF<@`_xjQ#@a{erHmYJDJRAQ*=${2U=-aTtGRc(E@sq3_Otj*XM?MqJC^=Os90ocF9#XGgqeDc3VbHF_fDThe+81R1?$qiy=%sGdSbF=} z@g^fjZ~yUa{GL9*Ygm$c(@!9A(y6bB(@0rvrpn-(afrl>dd)-n?820uxa0cMfIUF3 z_u3bJdhnTm^r=L!@2?RcMQ-;-?1M6J7v}TUB)d03O}BVdgOTT304jY0tLpR3^HudX zlCJ(eRA2fw+jZS? zwOX#$Ap~YKo6hF*d6wrI;`M6Pc~3Eos1lDs0hBp8^FYm^2NGoCyG>KAwrfQ!N29wB?qx1BWC$t! zo*3ih#pP%^F~)cw5GnZRedq%vi3pI1m`y*X><@J?gwEN)Qx=)Is;c#BwNl+|st~%e zEbpA1Icu%8Ny{dfnA(mDvMH@R#^`+r8i9z6B{qb_#5r3)44}X!3@|4lX3jBD??#CzprP}jZ7yG4`VeCX zZd6d7jmpt{addQaR7^(3k%C&o))-@Kk>{iF$XYiZkB*P$+x7bClV{82s;e7gOgS3o zd0MWfw^j+MhNgj-6age5i)pK7W(Dxx%K!xL{7aHeQZgYE)fCRCs!=6I1%(W0k(JN3 z+m3PTJ0x_@i4UN?LHj{lLn&q>h=dpoy?M0LTM6uAt&)1~fNgs~QP-P|v%<~+b9b=! z6T`nF1sDf(?T{s!sN#FGh1a|)eC5c~R|=gQQaQXm)JyPeLaB#m+~Zqs5ls&WAHKc} z7;F?!0r-%*q=z7d?x4d1(mcJUE=ZSnml8BMjUp=UqkRx={H`xpZr~T21Ip{>fH*|F z{N2ZKZ^wM}xBtzI>A1J+FDE9Mj>m zm3=Jnfy(rD??C{fs+8(ryp5|JzQ}#h6%ros-+QVL?fKEe@EVwTG9Dj@&_JUQQIX{- z5+tgoSCEuSFkB6zWEDJ+DruH$W&suE6BNx1kw$}H01%8QSwiP*kl=l|cXo_mLWm$d z9l23{B7Po&_t9$|-aR{d_s(%uwQbvRo+CREl^BzvOTjZiVad?oaI11umiK1w)SD*8 z7!?6*il6CCh%t)B+qKmz4TwV4d%z>5E6+>`{@A&uAFfxu*TS?I zEdw=zCIa8NbB~z*Q~j6q~FEQD?F(T6Ss?|qhKkdko{ z(J92XZR@%g&|);2A04?oXEdUsgn~erzFm^fJG1G6zq+`7c7D!GUwZgXR0AS~b-6Jp zs!>|+>$bhPy4q9~IXhd-r;}-s<-YYFfBcakD53U4Js>d2dkaB%&zMb=xSr@nialhP zLIZo80Lc=GfXI5YUai)3*B0aQ^yG9j9aB>EC;Ku`(!M``e*R)qH%(J-t6Bs?6z_v! zCNhI_b#DkF3Ix=7-?jDg7cVcbR|&RcW@g@Ow~wDZK0P_Tb9N^y95bs#-?mj%MUl)o zO*gQ0##ln`e4DuK2e$m$we4oJiETR>kBYJw7iEg(_Q8h`g7%m<_Nro*D6RKC_^6s( zWXTu>3_;t_1`}PLGjr2=mla+yBBo(BJA;JAnyRXno6WYa+OAF3Og7IKlZBaYo>+9>~_2rA_=k;c5m`9`0+36kUoGA3^QK=v%7Kw^N zgdv0wI#o569n)@0PrzjIVbKFFDjxKiX_2OnKE&7$B@hkstQZw`wUW4Ms%_ik&f304 z(0zQ1iYiofb-mtPTwPUlZ4M_0x55?%bWsN?;(iF#A2~PYgFX9XA7s9g{p;GX@gO;h2UG^x0bI9Ue;>sK zH-bCyP4D-hEm4WNWy=h>w=yDT9mHWNH+KM;`+;-vApz|xiQS46#MoOZp)qWTNFwTR zwj>-bSvkWnPykfCU4}DJ6qOi55bb?ND2-G=dLN+#!V6IF(SsinEfEL>NEBla%4#a= zm=TdgkkD$>APOoWcA^@FQFPO^L`D@awiP1fMP`ig47K>K_3idL%kn%gJi_XFsnq8q zC=f9V7=yGm$VeHG)0DxW3aV_HwyLTcz>5eVCI9Lk^TE&csp)MVlATD}y%G9qT4m=I z^M%-m{S;aEEw1Sm#DT}#CCqvNytkJuRz)hNt1u(Upe;jS5WqQn%3 zUAHh$zjb#VXy4kRLISQRdf(OcX1QE1msyrgr_-~^-J&eeQ0&V`>H9x{!$#=GKmPG* zz5dcW@0^^Rq+o!wTlWfdR6%UpcDq^ERpq-bvvziJ3NHKGPap5BK0^ri@87?7?>?dF zx~{IP5PZ@<+RPbaKoYUKpObb$f`}lANY{lVYID{WWjS3eGHZI9wGa%Eie}ESLQqu! zL`wGSQ6vJm%vr>g&>VbFKvxv5$SoV^G84MkN#RD~eJ6duxPW$T^U1G%xvr~w4i9VRNWqRdNcvZBb!EMr0@1ktu_pFMl}^5uo9WLZ8QkCTO%vzcLv zai}o*4GmO6P}K-T{p42>kQm9N3y8?L*BgmpPU7LHA}XO1A_DG*?4%H5#J;hO3PPwO z!*_~u8R~7-Zn|nAd77_B)hN()zNzc$<+AQtAEFp$YtI%lLwXx_I=GV$4h)4o8xZ$> z*kOEMN(sEVXS~8~$G-;>O&_SNx>>E8wtGd_m|i9w(1YJ}eBXGj(!)}?8|oe48H6gJ zJr$yd`V|v3VX*81JYX2>t(_C!l9#QPfGO4Y)Nkpcsv1E>G{%%UL^oPk1VS|_d4|yR zmQg*r2BJ~Li-ss62{{jj6E`_vU$nw{yNCEI2Zy|_z=FS*0_*KB8vkxf>u}+|p}>+G zEJQ>CU~HL5mEI%^sfd* zK}0BsfPyN)O&5S6z6qGwIhSX)G|WT&gw%__`jFS&!Qn=`g~J$KL^~gvru89MYuTC< z@E1d-A_fLLwPv1Zg_+CLSB?{E)Su_~^l(2g<<> zIp=HF^I;kU=+0I_dVI0h1Ru07F|Ie8%d2Z9{@T~S{yV?>dqpw&?(h6VqU=w<|AWh` zR)+jS5jI2sgnbz_K)fg_5+Xgnm7EH7M^JC_+|01`>V9BsRHxw`h=#~7V4qv^CP zO2ZsPxNfX5I?QS$%67BeZYxj>A;joi=8Q3Wnq8veaN^Nh)vB(m;C&PU)jZG3vdpp! z5k+FthMk~_jR_$V5ha zgs$;TQ)?_I;|KTep543avP=m)s2dg8sBlG|Wtl~0AO;3SU=mObQZ>zHxvJ`lkd7C} zS)LhV44dRKA7a$r)NPzzhao;d31@P6k2Y7b4;GNu_&|`%aA5^OaCkgZFUTRe@A#NZ3n`r1HvOgl@c* zfk>oy;0wC5-P+Sn1ynRjQssywJS!0Z7$`NqG!Q3W@x4@h!_`wjKmk=DB}7TA=9DI% zHUv?U0|%URW%@D~llAVS6{t*aSfustV**M^zZu^=xl|w()`MJT-B<2?B}#k6s(=a- zs%qgZ+CqSKIS0(Fst62%2qJ{WWlD&M0xBZ03yt?(R1p&ooZl3bQcxYDLCfrzEs-+y z*k>xR_A6HV(7IvHwJ)&JM`VqSR%4W=X(1hB0LEII7uz;0FIUA##^b4?6O_i+3cb~k z0)(JV-PU!D2wCP*vL7N^Yk^omMN|+fiObekT~LgxHaeGOSvE0 zJu33jk}PH;|jizN%X z9lSYgW(nh#R21A=(w+C07t7~QpIf5m7uO-e_rCYNEOX!b_BV+1kN)WYytuqVVk8Sd zF-npKiYOxyGaJT4mPgcne^rT56^OYka(0gMtn;3bD8-8QN!WYOXaFE)WP17XB@-{^ z3nC^|P&EJ~3Q;tK&3fH*9UDG6J|0gdS)N&AFD@^vwWGZB(Fc(L;*3QCYuLB#%k%TP zZrGand^Vm;ZRTQ(P1`J&*CNWyE_0*lxM|vx<6~#6A&RP-YJ0U@1&LXfXNX?9%w_4b zi%Gqvnj+3970oF^15i{$2%_2zfRJHh5RGB&I^T7hw*A{@*C*rR{{8#&a^#qIF*2#{ z*{8k^lqthTRqM9BUN2kk^Kx94qps_+EK4_k*ZJ-Cdb?dmiD>ZX=s3@F%Z3oW_uHxp zF*@hUvaH&6w;)0YL?kgy>xc*kW*(%J3nXG=oy+n(U#^!;-2h^iWuwt3ja*f=s;ba+ z&YEN%n}m}gNC=^7eItRC3|k^jaoQ3h8B-KlUx2B4?;%8B0wN!(kjbxms!%c4A993?Zk zp6nbYLK@aWgg%iXRT4y`5@7%*_9EHjXf~uW#2C|mz4s#GoJ(%_$yvU)8%az@5m6A8 zAh8P}#2ASMHK@2OI~t9j(DTO^FQ{o;6MWZZMLwA>%5s!BXN&g2x)FnVK_KAiZ7 z+P^(T)SJUzkRAVC@l9`DznB>FH+NH@Th9xxLYKcilKGYbi{OihC*HVdQEtsZ^)@AH zK%}VmaqD$hBDd@KS4*?k)~A?eIkJzJq@=zhCN$P7wjnx3gNVc?eYDJmO%&-1RU#ym z)W{kS+p29lMboGKq73N*fT-MalnoOzDFHD7z7*{H~jHI&??wV0T9-v8S9lP6c#R~As!gw*9C38cn} z6B!2%z4ZFMEJpDN8G;7si6J}H9=;7MR*(ZGYtO>$m(5^v73JnVBcci>Dq@sPRsG-x ze+Gd6;2->6mYMH-_ZzD1pM3vM&tF_IvLLi=2q6+PTVssvdB>_ilyd#O?)FHwpkWpV7A6sLNp2*qJ;SWu=i$Pb{*My=N=;BjCaUP zWMUx5VzF4NDh)16?q&PYe|5jOyY04SSF5#_v@Bb#Qh_XzAb=ch-suc6?A;G>?#%=N zj#U~g*IjrZKq8ZQZ=8r7dw<{W>xca?44}Zw=jRXD+B~ilfFLoS`h~TGz?z&@f$E9;q ziE)tF-Fe6E&374b7>1jhoAq{6)YWXhuw{t|`>r$A4qgB1)vKH9>#D9!Pfwd!W8KsM z?)yIYK#11bwyH$5s;X|%Q6V9w6pi7ic?y=ti&NBFF7b1lCTAAqzLax?b5>P@4_)7R z@0q!LQ+sB0q7XE z!Ebk)5Oo&=Al>XXGcr%w`IC2_vNeP}ie69O+$Vk!e0K1+NixCk}?kb_9${W8#Y7GdlwI#lx3P&}A#xn4Ay3*qT33#ZB z-!dkU3AC3j6p+=6uaz?RmUkGZ;MUi~a8tm=G-&=}rKXvqMU%%cfo5+|ZZzZz+XSoq z@_H73wGrW0)z@EWS-lxz^PLK)Z_wfT?j$#bFFNY+3k|%tfF|&pm=M3Riluv{s35Ab zrYwt;B&E=Gi3^L4+1MNwmcOlGGwGcUW6EjLtZ}eFLQe|D#;Xlmmg3e1R`eA z`|agplTg19Av_6!n_ zw)ZiuXUj!ZSBTn_wFSD}@7k*QoezKT(dVD{H`n#7HFde(#nC5Z0K>b!L&8}_l`AG8 zIpD0Bm*2C5cy)b!L?x#f36aR49LMl@)s!#Q_Jd} z==T0IrwE`7fC_v+#0CHen7|Mk5CPC`KmPF_{b`Kx-~YS+tt`y%|Nc*j>Hqk@{>$~v zc8ngt+M>t_jEHwVwh)76g}b#yQCMTADG4C}CQ($NNr-mWhbB+}A~vdMtSjoKteV0W zhD|Q5cH6D0I%j9g#e=GvFBW+&6I7B)l%!FJbMpWaC@EZBUcG$vQbisP^itzDd+HDv`#n{gXO!Wj46kU@(@SuGbQS%qzl0YuB3Gh_^rL1LUXLs1FQ zkNchXV_{6?igq^3u0|1=ZiY#>UANzD4S-{+ok3%WSPHTv3fa_|Xr;I1ZzN7DcgGoK$6rpfUK|yFvtG zOp1xo)P>WD$bkSTA|bQP5s(>x877atL12So05GtXlk>Ko)h*I_JLCM0Tl3zmVB@TH z%q$|HNB{;9)QbB3ZhyVI_Wf8Ow?(y>HIzrL0-7d0Yj)Jpy~`gX-P@3O%1X%E44D?H zisWd(5Rx^ftSTh56K(^iV0X2WQhpp_N}An|3OVmMA|%kL(v8Eu@1J*@RkxQA4H{FF zm9?oTXD6p;XXlnF`wYgu7g1tfoGuq9CtQ|d9WWdELW2ii>p~p;sDhKr^^GGFkFbV( zJIx}w33{mqyYRi}GdiRif5F!N*8T<^y0*S$4FsfftATa~rnt>^R>viTRk5`I&$`4=mZl9+d&gX?}edr=W>VGD;EJToJbih7vxI1i7c z8UQm574BLwa_=+@i5A1}^_ z2j}OH-gz2BMB={hU#&KFyH%BW+c;zEqTK9vwkkh-`p(Cnezv{2T%4ReIX%1Ctarm0 zLD87&{l4?#`C{1=4l^4N#TM>^_upU4=Fgrzlaz=Ek{~M+O!h;WMoVw;bR3P^hBaY~ zVPaDu0_HfBB%;jsLl8t?*isq3m~rY5PgnYqvn!#IwPxvneAh>(g5=pz6CAOJ~3K~&=C zudZHw{^CVZx~ET{%;yU-CMNB=A;!qok~J|#L~Pr}xq{h@N&CLL-Rxai2E_u+Y`JjG z5hMc$D#Yk4_r1Sat!{2^%DSq`Qc^?!FKHadF!q+9D2myv&Dy%7kqC%06+MhWiO(NC zu6DcqtJNTpol7hUlEr*e0nL{ogxq|JF>E&L+uM!zVK!^e&L2AGvIiFcNztH<38LVG zi^s+=0mcwwO5P8BzfVajSIjbzHP7Gx4BNVDQ+z2vzy( zMV`;+m9YerQdCKYkXxPtI5p?_03fOyudtLR-RhJQLx?I6HHH*36F-FDoGZ(+EUh(2 zG<|3ZL^P?0_h5+uZ9o_ilBR@^R0K4s45Qz5yM5R7!yuxHuw;i|7}2tc#th7_RyVTW zFUqpAu5|9f#o6iUSzXsz3%C!y>$)IfzQvjO#bfdg=QFjGj?id)n+ff;?TEf*XW_v3 zxl4sXc>7t4Z!4R=ZBqg9E-pyF)!)jUr%9Ogt(!*pcK_Zt`#N9tw|*`8djFU&{YoJf zBD@WxaIc!duWHBQ*RQm%Y|DLvzj#0RPhX>D!@c&WzO^GrprjIgZx9P-ELoE?pzf9Z zQ%f_W4&hjgPbIi9Je$?EC?Um|e254{iXo_~S_6eOY;wJnjyZJqL$D5_M*PB$BS*rF zq!1HCIslE(keRo0OU2dAsvmvw-iNqcp3LWS!?fM*M07EmmxV(eBL!z198)_4L^OmD zB?&+ROb9`-7Y$KE5VWpdENHXet~ZdxIbPjvcHQ{s(ZjN?qiA9lm5)CAY;|+}@ci`M zcb=Xs7E$5F%a`?H@x%AN_t7W6eD(SBi${+h%;$u=o9#M^wbl+AFRxd!oVP_mxnG3n zoO}HE5utwk?4z#lt+insQPdhsY*7_Of%ITV!Q4s65l#nl5He9x@i97MCm>}$V|^1!v6GM|5S+o&;RsC`!1%GM3Sl? zsj*Dttg+TPWgs=Amj zX7f2ShY&)HhjWAw5Q&l`L11S?N-_A&dMz`QQq^%BM?d=L zMKw>t>#`Eat*JYAdG1@}dt^in2m&dn4w`(7LkRn^ABWM8qaOwpb;ej?whU1ucor>~ zYvX9S+zo>Q&dyHXKYKW@N@EQI5>Z~ILkIyBk(k+hGpDG-8|6eO_8;`pX zzHacsFDo_>-;Vv%Z&ocK9)nW9OK}FjdHu6};jhHW0{!}G_h>rHKEI>U1Mb-rUbp7q zF}DB^nLyGQJhHRa8q3UwB-%q8Oz#P-kN;zuBNkARh)h{!ePD_y*f1*gQ8h(Tu!gN= zViXmTDP-yH5q=HSG6|0kshGJK%GZ5Vz?>&*LRJS zQS{j-pV+D*Yx`l??{|J2mHFjnXWTWQvDVg2`|-1nm&?t2Po7k+xL(~>F`hOvXU)y+ zZH$AhDzE9)%}tukmb2#Q?qudCPoC6e`O!xouU0E#Y>JT)nG8(cKz)mm<)FLDf?{iJ zN+|?yjWuKdl!$a1m*_WZ3%`+$l|9CC)TAEm2c$r~Pk;1he<6rJ{eyp1)z!cKgWtCZ z|M!3Xv#Xm<6`ix}IImA;GtH(Cd`rX}{!4eQR8>0M1aJ}pXPXrmHhJ#T`%n}mTWg8u zRbvZ>pdzs!h8V)&y>YghwONHjxg?b&DH-Mue((VhD`*~aWzKCxjiO!ORaG^c&GK_J z3`0sO33wm(UAMZuwPl%2uZZYF7xPYqDOu^_jB(lbUXbf@Rby36^=L%=6O{zf>F`qj4>%CYs@%~qUycx`vGx136ey&k+psEAoXLQG>E z_kGyyQs2kHGh$U%XKicQ5^^>@9ToZtz(k-qQ3ob_*WnGk+cu~6s{%kuGLAlml+{&a zh?tx))3jG*3?YfIvuJWk(u65gVuQzNjs~ZBcMv+i`C5@fSabA%?x6S;m&`?bjY~Vq-x;nDlGj<7^S}U&w4+k`5z_I zM88#ubEH*$^(&?1Lzq6v@7e?VO)>Mo)aw{)b@ckd8$rLXH9PZxM#Oi9Sp@_}AW*|# ziOlrdNy~Y>T8JFuY2nCqKZ>RhfF~@ouc25ytms;)gu; zdyO|eHj{G#4`PaO96g3)jLVIEWBBCsgq&TiZoT)L7^3&fhjfMc~TSw zB8lcg1CdZcV+>;mAxacYNC{{p3`z;j;6qew&(0L^=H<)Ux<}_1-8l4q^ucepn*^#N zo34u?qUd(lzq-C%%vxuys6Ko4%zOX-``O-j($+iG}7b{EwnMS_^KK)!D4x~eTRi0;RJ=sQViKASC+CQN<1iitsWC|i$vKyS??qV#AFi*i zw%aX>J~}&nZ~m@=jKfeAB>a3Y*DncS>Z|r z@gWS+ONbI90~W}^CqkoyXic~4cGowX&00m9wte^Aci9-3&VB(=I=l|`_mseZsvu&J z=1pszlaxS{q!g2+5WF8i)LDy&t|+RiDr|LCmN-qvln}eFODQ2@zL|{Piy|}Eb)9+c z!!X1cbIr=e4EueIzMWmnX05T-8Up~sFx=e@5SgaXLnL*M%gQ-NRb^*wU00>GWGo!C_oH3=dj@T$L(gNtDDmVT9`Re9j zd!ojQA3-Eas>{l7j_d}UI(c9B`X;8VgUsxkRxrPclPpsVWJ(Fi(h>YM&cReAgqWw` z$DDz0A_@PpbM!aG$G`BV7$PD#=Tb^p#GN<6W67oP7O-x90#6zw%Q1QC`3t;qNqqplL`maOwxD-%6l9gWc+uYTEGL` zKJS8ZNT5XG>{BIUP;nf6*NsI{xS|jdB0gO#%c8ixUhVh$d|zKKm&?gvVSMMwJEx1q5aqVtt91h#Ka5@Mxip&K z`Ky8wUVWM|nLl}vS1z-&DwRNZX5Km5Z#IXRhs_`Qc!!GG|t zf5$rev%mQ3+ucB5RV^aRw0;;dlNTkUt|tiJ>t!DSkWL$JKBAIHl*EQkn>KfD_WOMt zeN|N_%SYDOvMe(_A*ljQ%EoaRUS3{q*0;l$!Vj_)(V45dbDBtwY3=qVM`)>_LSPjWK0WS;H=u3q*v|i0~kk zL`3YzvG03BoIB-pRU20jQ3zqT+wFF{{9ajWi^36Lzw2V~huU5Nm54Y;`Ot)lV#DpM zZrY-0-K?#ewyG*?SPM&)OI1O2Q_N;X)09Qyipn`ARv3nGvs-_@->!$S?`c2krVs1Y z3c8U2tD<-?J7pC*=*j^AkSF4wXo4>Zl+~5h?Q&4w9|yH~Ffua0*TtxOU2o}Ny-fg_ z5RasIf2^Z#`%?E+HFqcB0aSQTNc;~q_4+3%;=V2}@EbDUe=S|hZ*dv;2dJ))4Hre> zz0U>K-Jdh3J0I%d1_A;ENNNohOgtrUBZ7*kVQ|h`CQHo7I(1Pc9;ZbrbevDUIjB5L zx%7~TMP?jYd1*F0jk1if=x7*wGy6g6;I-4!q`ALM$=PxhIYJYlqW(^rY1gfjHsaoEw zy{vsdW&~Fl{Wy$n)(XgO*sEc~c(Gj6h1;&T#jJVv>64c)UW9Qxtsj4a@bdB|NKz3< z8d8uL5y1N(4OB=stJ}-VtJBldi$@PB%b``sTi^Pm3gFLzrng2)yy zOPwYMJ`zF_)r5o!GF4Qf3@EBOFAo5_zJGOfd2_Q`EEcA)WmT1BsWBna>3rc_F~x^u zPGQd4BMdPPUH|Iki|gx~rm4=)&#SieDUC6zO1JN>udh}0Qp@ z##&4H9L2sHHk+Nqh=7LKIX9op3pOa?V=zjf>O)Y>d^!LkTb3c}7(!O!hZu*xPZF!D zY-g=uCT0Na`(eA?ZZ?TjH9BeqL1m>FF(;ZK5*upr%zg2QYPz)U|?Id6xTx7`NMP=Bd_owOlT9gK8Ko8y7}VrR{bb!e|U38k|z4OCm4;gpyMjn%X{m zXL(Alh=H}$M3+sYPJ>dQ4k^72 zq?G5@`BR46fCr4CiBJdw(?I9rA#_bsOmp3a{V(7@p9OZ^gC$IuG#s9_cTu&+b=OZyvzpoCXIJ9r? z;8l0R(7QZn1;|hvFbPKQ^A?sAeFT6Qra>eT5fI#;2WBrB(`(fKyR)ArxRwGbD43SIh-8OLFmB)tDLUVbX%*K|m@&D=yY4 zyj-o7HxIxS>Z|}N{kZ2%wv8E%Ak*XMQ~xhWcf-ULRf)j+31-@Hij%A3dRp}E@UTVn z5huBz9*In~Q`P(E0|PNvSt-dZDvtpoP8v~t!1MfY=hLo2Z>bAFjk?8{$Ns_Vk9L~478y1$zp5hcJG{M{`q0-KkskLR>@q?-#vc}XOdg?G>pbl z+pT4Lx-oKz2MR}hkhtF?is1{qeJiox^j-Fq`jd^i4;9Awe+l$;9`eoqu3h}!^H~4-JSg3 zgpW`Oe=n`bGsw2QB3`pWaq*uoeIA z3X>-Q(=n<3OqyPMteVMB@jR02YK2~MsOs`%1#cNF2yh_SBy*U)9FBexK1cZ;k<259 zFgv~JNWII6(42-gVxU8xTXi`oELXxK+Q32FUJ|GNBy$de`Fct2Q~b=sMKyw{GpI8Km~j z{j^8jcKF^OPnkn;1tqzEwuTg2lJX1@U+D4SuM$l8)eqovLm5&<1|S)EUb1R4AP}=#l$&$zVDjkxF!0S_FaPCd-Lz_CtpxD zu{;57wK%oTrC6p1J_TXsrl$Cs4zvJ2c^zw{4q`fy`M~dV?xfTAe0Vo=;bO^OC^(*_ z>E^@C4fOpq|8QbrOIZw$R3YXsO-^S^`-?VszV?Fq)R;g@r`ORfAen8nX1+Nqwm4b2 zkVq4%v!?a0pWA1uvQ2=A@p+@D ztn@->m*fB5lL%9EiaLH5R``Y_WJ5#zJ8Aprigd^@dTX;Tf`iJWf5VXOdjY2fL~XPW zySWe39<;b*zpz!l(LEv|fRq$X#%&Ge)J`)pHG+^c@o6Bw#rqI}I4l#9BGiU#0V?$0nT7#KYD|xIp ziQ=Fi5`32;!iiaB!m#S%A;i(L=7|l1ExiOqU9x*)8>54MOO49<^?Eh+TMbJ@QPTB?ty}1MD>VNlGpIz_*WFhD zRUtqDj#ZF7c3IRLmZwN}Ff|%azw$88Yc=@m`;blT9*=CUyvxuz){ct2v0j`6fu@Db zhhwF)mbYr|WzTEi42xxf#^s^KPCun8M9vHZYDyW|UXk831tdVBWa8_Q+$(3}jIjfRAvmu0x z(r2a2TYzf~Cj+PgB@D9adc*m2C1HQbt_!C0WXXPrTo0;>SUo znqcu}B~E9s?K}W};PbbG>_J_h zBbdWW6Ha1E_&;V~Gu)x_Q-a=XFU&=a{^9I{ZF~O>VK=^}eT3vl zjcQq~{efzfH7!TkD0)s%Y(^EAv2Akj&|y8I3>$mL)$--2Z_n-xLHn1?7+N%c^pglf zX^qAw9EJJs31msgxSb=Ppo-8z)N@IUS z$MJ}x3o|rqc2H1Kz-?vR(c*V8 znAlQvtXa{x-Z$BMw$n(P(3_dLd*zS=7Y{gE9h?jGUWmOBFZ%9x7=+Ar)7I7whYcN5_4_1f+M;0#|W8S0O&Nc&{AR?q5C(Uo3fB*XZy{k*Sm8aSR^= za6q+`_2q}#&D}E~bQ(BhEq}iL-cLNHt-EPZ{5*LMR?NZM7x&}MUuZtfWTI)y>T(Zu z8A^WV+*hs9fAjlUj~Cm)FX_ ztYb*0*dP6d6)`xNM5a^8KwIxRmJjgLgEo|LLDdzz7mHTyv2=M%){gqxkBv89RB#sY z6D&HlCMRv|Ieg&Zs#rL<$TUoK1)pNAq@^?Qpbdrr6YF0WB2L67ogn%jjkG{HPLva$PecLuigW`)<253?9?P+n*K!yl5TD$VzB<7{3Gcg^ zOg={TK-w;NaLg+kDAd|%H4ZHo$r6chzzT^-w61<`{b-v=^c#%~T!1(6(}gh%1f z&Xymd;nIE)G`CJC?N41N6g)iY^M4oN(4@WcoH6sEn!F+OA^)p(dE=)sdMErVOC%8T z<|oh|U0gZb(^ z6j#*~m{>M40#d;vYx?}>%fD2%2}&6}$?Wqjr5tmw4fJWs*)?M6MZVP~K_dvT|FRUC z_g;RrXw@#;)JkK@MvH$IaWAH^ZiUFHC*fS+fSUWMgCn3)AVhKyJ~?c|aS!^b&Pi6woT01YQqhArRz<%}A zk16qH$!FB^<^0EX)qVIS@HRN)elYiL+T#F=F^>+Iqjv6Mgv##%4xV`4Un=NogUH}! z(LYjVxv6A-l40ec>?E!;cgr)itFJq98}|ANq8hW~Yl3h<39#HU9<^EsR(gR;Ka@Z~gsM4>r)tQDPe}<(6E7RWxP#f^ zv9Urz;L=h9E6Tk|&m?gc&llsinR|=eHkpYs@_#!wv6%&{F4S#0YtwGr)N3pblg;`j=)dIZMeeo0!h(&y*VyyzO1L;{7; zhc;_UrClDI1>BY7cC4$C9pGdTNIK*7KJevWz1WR#E~-#u^*{UbN2oeb-M_*XBL^P= zhx65Z0W*+F)QT5yI2yK0=BTfUB~lgJ=o*xytK9tB4`+emPOgHe`=4`5v?v zCOA1A|6!VeOkr4gGr5+$ua~UHa}O?jnbtzJiIrIU_zTITzah3ExPR)N<(81qWMz+` zn5=e*==pMu4Y(&BE}8;;y}cC%>YBecHT&&5!}=vGHXOtO+4=GYFFV?+Fled&j+V>e zZCn`-1^)YJ%>>kwpY0so)?WL{+jcHEHQGyrr)jjNNqApmx1gT0MqI{`6qA`B0s}%f z_Lw>%6_uocw-T}DPbNTLrA<*(uUpcF~8rdLKf^qZI+ak7&B7LVg?qm`9e;IUkI;2rnP5-lv0#d3|1mr>c>Rw zDU{VU#0-B~mqh96ll{kzjTgal4GHPy+`^QI1K~PSW=b+b`xro|zi@_HIQXn8?!#$B zn>t!Iv^tw42)XhVA((i9|_ z(!=e}$u|N_Q)+UvviOzFM~=qIQTW6|lP~ma9E#)LxNIDgii-vwt{y9Pm$C+F`N1xt z?37sH_;h|3*t_L)suzrJFXjn76#_13{QQ+?ug1&j0VvI(Hpf`8%28^xXkY>I0pp0S ze&Tyy!deaDzVRjQ3!zAP7mA~Z%|w;)Q^)?PHM=$OK7p#I;}=_!OF7~9PPcZP4mJtq z)T4|SxChk>y+_}FX%b`M6R5*1(MgkJ5+9IXatPQ_Jd7ITxIM@p%_vevZ2ljfI`7pK zSa%f&te*&zhwls_I8_7x!{j*-%faa7tool6)L1(r0x&CRjakx2KPPx!4UeV9JDD0u5?cjeRc z#yIQyq+^SC1pmn#z&Q|q-qEg$B`H`OfpmKgPueN=KmMDY%4NLo@wz-gV$n3ai@tG2fWTNLYQN&i~!{{;)T7s>y(0DqU^(+1OPy6`s_kSKE zSaujudhwQo^}~!wzX;c)E3vAFS`%-xz_Hl{}Rm%aYS%i5@Ia6|;HYb^&0L{`b>)_#O4ftyMcOI;3zE)HT3#pU4t$ zKnjYzmIw;VbTex7hlV+LJc=!{dm1r)aGsi)%7e~#`9dR6wVT1~3u8nGV64nvSwI|V z+ROfVERLQ{Tdeem?R~99AqQZkNFr0}etgq%Qi;eka!|S%&3DCl=cd+0EvcuQG~#|b zGww!Itc(h*5~hV9REjd^3r$T>v;gLtOmNcV7N1^HI&T(hb@>PA@uyy>N27(Hh{T*O zl{vKiabp$R@Z@vNpK1Ba4uWgKv2>!^!rHp}7Q`eZKpoV>-(+TmZ?0Gd<4=jlPmjv4 z%E+&ZVtZgSFl_ZUs*mu$%!C+YjMo%XXSwHX+{A1>4FB;V7q>v1=_KD{^UGfQ;G zjaDaI&=q*tx~jYL(AHs&n^wCrO3Ac(e71SC5!C-%OnrjoxlX8(Lo{O#(GUkQ$5r>v)Y|$MV_YpLT2vqFq?TP}AMALOJgGL(_pwButt<#vSq6 zbF9YHYUCU{3wwGBddp34#|@HHCqp2zv$CiK+|n(dg5X&S6UbS9_x~s#|9!MCX-kh| zw-)KWZM0Z{4tVO`XYtftPU64CfcCj)^MSJJ2OaCU4l9n^-25884_=++Uc2I?y8-dx z&j0+DzoMltjWq{~oXe#C*^>wSk%zd2w7gnS6xxX{%ne6gJR6|#^n-S;~0 zp&#)o1j21I%xNfr3O^$U`@_h|5DCG0e#SFZReiVCmRBYmgN;O1B_|s`Q`MN(X}cHZ zvlUL|D9&NKS)yFO>wMbJpEpY^w{^andGfHMYK`0%i+BCWaKE=Ti>HqQ@c*9|H4EB^ ztFF(q0r%V1fXX16r_?SXY0tMenywxQF9|%KvtBUNP|y`jU?liJtv<~|B`FCk*MVT| zxw&HtabrzcVu5FLE*>7|i9l}l!;!@O`SGy^BC|OC_<85PUB<+M;Y_k6u{5Z+*tYhc z&`lw)Brrn#y*yO3K)hfRGzbzrr!*)c4;Q~&m#;@y!DNHEEMozh^+PnN0X4blFJ= zsP8o*lz`lq7vF9{Me(W3+J(^`IuKCL=aGrhfVe1A`p!5}s>4ZH9Oh}i{ z0we#S756x};ozD(HsEIxfg57xnKj?r6cC+lVC(+W15h5l(e=pk49Oi7+rO?gG<5t) zC=&aMTCo=jF861LmcpnD?z^G|;uz1-=&l+rQ-l9Cmr3)tbV^s`0Ye+ z+}^&po$qsbICylVfM|y0@T~W0x_f)M8cd%oW@qyclM(V<5N7^o-8;3O@6DY`m{ZeRcr=La<8}L+?>jX7?+!RKEDLhxMYM$? zYNY&r2c`~NIyZi=ty^Su1<~U&)YUZH?br`y6CEfqks<(P3lH{QovQLkmZdJR{ztfL z{nUmRuD;rrKBVU%wsq7pwqHqaUfAmbpkMQnpG!YHmbH7-7FUx!?rzA$f(pt9+nNFC z5i?49ZAU%1qbY8QA00CuOXBkOs%PfEP;# z^2yS0+`6vMHC<=n#p&aMU>+t@s|Ym?65_s!5@ExJ*VGWVLSwp=9w_It;kC83&;nA} z{M^#q(h}njPjN3}NYHZ#As=6V_nu8J1P2QjZPP`jo>?5?13 zT8;z9D&4gb%N~D*$YH#5Dp?qu>Wyn8&z-#f_b4wfgzj5KsY<=NphEv?t%IlY$#uh? zQM@JoM*84M8%u)Jm|-YG5LTP?y6Jzlnw6paOQ|s&W4RjLme5ZO10vG_wjPdWUj-BU{I{0Re`!CVXe zpRB#*k2F`QnsxtX15T9Hj(=GWp_6-5H}stxqRRFj# ze*&V#rZf?{$%y~)PI^|pZFwdztej!t>CK@tJ~`u_B1a_4pUEO6$@-qNf2D#EvlK>b zugg}ut!+>FTAysUzn-f1Xofw)?K`q)bD$VsY_Sy=xVuf9Hx!>rk3Q7T{$P=(Vf9VJxf%%Dw>DCK&V=ZsF2oeP`Gr~f6U z94Cx?_H2fEY5eb_kHvTVuMTzxZ(yR#UF`Z%@@S~0?a+=NuOUYY=;z*9m0_z@ zrDd#&Zv9Az#`M|X;L+7b6iOXKUi5Atdbf(Hr{hCi-@mOtTmKxgHm|1d?(Wgy4ft$! z;JsM+Qn0D4^xIas%-H#2l^{1KUXg0l(Ca4P^si~y&U#lj5+!*{u01u)-*$c)fw~To z3gSj;HYAE!n@>ga5}#L<8BPfk*QA_?H915#NJ6QKC=XWayGGDD_R&0O0cH4%prBw= zA1qc2vlB&c^wBpj+T3df#UDg%Op(!VAO2t@Bq*WMvML zAQHm-DBagM%ccreF4TD_QnnX3^6fS*l-3RR8;r ziHJ63*fNI+USFD`Y-rTnakII6-5vAH$?=~Lmg-Pe(kgUUwvR=4r$9P7e&ZRz*=M+{-X=`e7%06ylg*^E>t!hpst@?@} zZ?_n3pirfM`gd}W5G!6O#BT02ErUUR4ZMi%Z-D94UABt2h)Aww8GcC67UJ2kk1pcv zTV_N7Rc5Aa25&(GkD@oAlzb6lDlQ^^zcrRkB~;~!*Y2t-av-OlDS5kfG&Qg`VpTVR zmdmju)~5dNbDmHRkiwd&w8m~_KH!q&72SY-jBpW$P3BkZgg&C}-auQW6dwt0d9-r1 zUFIt%d?um|hlO_K8O~`FEUgRBv0<=GxS^WvjI%A6m)T^}k_?GDa*=b>AI@8{bW2fS zO@si5_ief{!E3b%2#7I-cjZ$ky$X$e$P20GSRocl#@Dw`3GP2T->?3;^wZm!^RkO+ z_C7(I2oKf%7Fp)+&`Sx{Nf%aNkqbbwKwz&Z>b9@E-(#{>KDY;RDF7ZNELa#dV(HA) z`=hJhN52uYLA%E*Jl!`_JEc4AiGRMRs&1Z$@VLM2={omFuqry)Tn|C{qu@~#mnEe*^-J#^xTcI!*6-)MfbyY*QoJP-N#zG`6SlcLJ3D|P z3i|6$T1_amevba?(HrvPZ{jbqbnmLBhi4nA;jNiM&W6iNb5OGFcdeP3=t2Uyg**cC zLwc#A|Gp9UX>AvxRLhSK9sE2*t4iD);eG=wvR1=NaD~4UWjvF8jWidwI&7=m>% z6i+!1lcf`2(^Xhp=A!S{uoShhE4==LM`NhrksY$Qcoc+m{8i`ct|IBmJ43m-*~-k! z>khSPgz-g@AI-$RTJ2vjRtPiiFEq6&* zDBU0GCCLMEo96;ZIy=KGj^^vk`&;V&;@?(l?Ow1PY$6=7pX zeik{@>i~|xnt17jUr%#5U%TRE%>wFuQ0i6sHUHVgePL_8nOdT<0qu1P!ZB%{wG2g- z26=(D3Na2bB<2*uB*^T6Hap3W>DHDanJU)s-xj)^%QYCUgW=*XhV1c8OI;>iK_KVI z?|5+Oe9S5kva{jGyZzBu$Y~Z3EYO*0ktGfm+GfoDLyu5VQANA>xdPs#xr`L z9)<8x@!l$V*h%hF3Jjx&3=9a127Gr{(|nU%St1z%-DznUf;7+c2Vb(rKrgFofeLAXdR~%OZU5>rHAv}hZ*h8OI}NUqI)m#H+q_c zIw#A6AJ1MRYYsgZm1f)!2LDzkN0AL(kOv-RcLr&i`8N>u!h(2t;@sv~(2Rg zrl_9z2iomiuM2-^Fw@iwwSlasF}sz$m(>sc#TO6}#E_rp4UEIFY`G~dby2Iy@(R#7 zFb)<&WTZ{V_qhU7HCdC|lsPC!15OWOUeORCqK7|!j?I%Nz*LjPgn?R3BUYCGUkh;U ze!*oFpzR*BUCq5~{e?ZUQWihtBKo_?*7Y%9NcKefBReb>MOZrU=B;pm)xuY&_|S z3->>Z=F~XAC^>a>1&!CV6wKus=B4p&zgQA6C%}&FUxTzMLeFn39Dlucc5!j}V2DuD$_n$j51*u_*Z00cv=$pHG_1JnB~y9VnqmjVQwCy9c*u#k7cDm5rnj7Ycp3|87N$%> zZxWUiBc)Vnd9)+OPNAD)RTlQg|0PN`XWjcNH~@D?$BLmGYHj`>32$bh1FxVwwO)tP z^LWBUI`h&gg~vTACHAik$9Q+viw7JcGYthltq-`^{Io%{%d!)z8_zho0x6@`{mgZB z>94c2)&`RXFqXhQP^9_jNr)n7V)m?zgiJkIQk}S#_Jnw!%#)as}rFzIKK%^=G*sy6rZ#M7>F_;=v=MXumA zt;B8T!%p?XvBcd~>iuQ1qRaN(po6!IR?f(ogI30{c~7UB5$Nto^a>GIlisu(ntL^> zqy!451L49p5g{1&S7ZI=FNuq6ttuIridpLM!O||Q_Gg|s;^dElV5J$JORYD12e;ff zmM^OVPa2%>`e=1uvOF`BvmZaJ#S%+%p_5D`8}W{g-4k1}d^oUeqCK)VM%I$BfqN!IQPeorRt=Z%(aE z;g=HSZ%!ReY^N(!u;gULq$*eDg&^TfHE^KE+dy5<-=7(E8go*B>swp>Jv{VMqE=kw zp8!>a-pK34SW~u0`e9xR#Yz5}^V?goFz&63c$*rQ%;JgZE&^i0$&aE>$I1sxxW8f0 z&0cQyGgDq6}j{@d(q zfJjD=vaG0g_6WWjZqXY%;n*X4Zug5NF9Buue#W|l8Tcq9I5;}Gw-~|+V#+i15Qz+f z3GfW7j)i#LyUR?5V*>sAx4BGL36r@y0pGT7Q5^f$HN#E~c5aA58M8ux4 znb>w9DRT!i0!n348DuZGswRyQ<8dNZr@*0&7u4&r#G0mypgee<41HPuRGw!h6PeJ< z5Dxyt<5I6kPub(0b9!?Zz;)nWC$`=zogkfo;`yoI(C-o+hZQ7Ursi8|=(2PJu~HfO z!w@!ASJz7WhGV$6!hcN}G&LyNt3|1x)NR86e};t)8^<`)lN8KM{wkG5Ae7fuKUu`# z^Sn!#umQ%%3rq7gf(mp-Cj?JWT?&UCQVdoLD6P2s!909Z-I+Dl=28@1aP0^K(*aSq z1IrFomdt@>2T5^F*OikbGuT1Kly#?kJW=mnz4)%UKVd!ee8FEgKqlovQHcYB6N+SuLt$Ak z0MAb{mkd%!IK{i$Til}(s&;fZJs#0_#b=+IANvdf zDswEbnwA4ypk0(L zfbFO?fk4vJ9-)I5syM_nw2Mu)H2{U26;gQ^au`jhL3}!+A|JUMNdfUcJREH5yg8Xt zkmS9feWNn9@5bd&1b-lzA~$sUt>33pEtgQ5fEjPwKh(aj11(=&ZaH_{z3iix9GE;z zuI@O!N_Bq5Dy=U%5&o)ISNkgk{Il-fUI7rGdN(1VV*QSuov!Vp?}L8e{ih1Y9%5|E zU+4R>gv2&2N%<6s5exNhgh!K(#++D?24%NbUFZ-PG6YPP`F?>-7t6qX{4IHEz4O3M zxt`{7;2QJ8IMKc)uVUDLIc?tl57$B+R|&|d0U@66LC*K5Ypp~o<)GkQiL3cNu67qj zDH+K;hJ5-}X&cJT5Ekw#G!vY`M9w^&B!M3|&CCYXd=ng_6fDWT%Xa0bQlg^YS5%+} z8q09DYC8fORECO{p!{LFW}!iOPvZ=mYxmkDMBaEB4Y!EA&W#r!({0Qn!ATD)B!2c@ z&U$#KtLL+}XSIW)lc2ld%=(5+y}<}kuGl;@Mo*ByqLfjB zA)yQLGS*&q5Y1I$ru*Jya@ie~D+52G!ug}CMlA9CF+!M31fjLLpBt5T8J%MD= zG0-0rI+m$7I6^v$G5IJd4ZO$?3Y26pGee}!D}4qgMaOO=O!VJ{72HnQsx;FwLioQ` zLs@ueK-a``>hY}srmuoRQD#3BlLivltaQ66qNjTmHB3t0lV#U0D2Qek$}8t&(0|Q> znJT@njh2K^xl(c^YabMzcer*qw4HQt>?*8}7f)YVT>U-jnMy3!t9(SN;5wC_HEy|`1}IZqK^}B2sk;!isA(S4D@Nc zDQU-)qGfO)@Xwg9>Y6aOK?W#DlZ-q%gd8>z#grJNa|O%tBAza;OntCc`%nP#DgvvGZY+*{NV#09LZFL)Odh*Ku$ z!QQL?#4#b7OYAucyg4UY@_jG@D_IDHxq#NIAMqB)w`zs0)Ue+Or;zlsGe)%W>l4i^^LH;?0UU(frE z8|PP_c+ST6h>Uzqzu>c2IYkH`WT3D9$U?aF2DAxs!I8Z=##XiAW~U8Cu_Pt8n4!uuTocFI<{BPj4rMz>D}<($A7uKQC~2Rl7(v$+ zgz}(g2=2bENoj5Tb+)81Bf~=Y_drXuMONyzMKHLai<>W;9-oXaNdEosB1eM~;(R(@$&d`oGVQ!D4z^G|>33O- zw!a2#*^>n0@ePKbY8@$3LU1F}=4MsK34~7UXPR2>?(>#eN!Thj@GZi5?Fm9;`NP0c zl74aM8}wl9hnQ!Zg{Yn4Bg=L4=G36Y2eDVS|?1(WS6Bvb#QK zCUOy@kPzVfEqOg$N2>i|x>iG-3~RIR^}AoAQTdrqK~#zaGOZbLun@axegq<>f323| zCRD0(0r-|BvUgtRsv(0xYmTTq$*|9(z3b^W+BI)NNvXUtc5NZx%~15=%^uru+oX=e zwp$v#>8T9pJo$YhRJGhDNO?XfCKcCb)=|m~tFqtATdu>w`&yA1=(oA{aNJJ2ohxr2OlbES8yxY+>_PPn}=e*q2zA(O-j8f`6*o3;3R~yXTqi2i*ZtiXx zLff33O`Cs%`#*Z~{w1@M8)h3GDaOHQw$f`ihhxS38>1PA6P}_0VshZ2c#Wn7mm}p~TA|amRuiX<8MD1W*l04r*F7@Xy$$%c_PTXhnm2E9v}2Ir ze;Dd5>`!A$n8s_B5RBlE>lW|J!&e5oy^bVW*$n^U_9_K%N(q|>9LqZ1}jV?A}U zCTEG<*}rSAJpn{>Q)45BPm93qOP!={%D7+gcmlqOuK3R<0dV*JO4rJ%n1fSvPOCTH z=o3Z)sYf9f;$CItEe<i7})d!x5db**Y5gjtwL(aX8-rw66hM`))lJo;Z zNib~Em-&rM%E>xG|B<|B{t>5~kU!9II#iiz9N^^ZTQE>d&-Wrq1ohSCz;TZbtk(Rk zbZ4k}(thphxf*8FPo0xu-LDbYMqD|Fq;mid%W6?Q5Z=qo{5GCWJ-+c)k-_UA`zgH< zHuoHdIY^89SwfpNS%AH0I&34ztaIk+*t_YpdYFY2IfJ?j$qsr(`AyE~rj*iz!rRO{ ze&w|K4_~X;web#Qz(%+rl2v-;*7kt-BFFKUAP6*)P-HeNO>{;RQA7u{e|PQWwi!@C z=m|L`k&^4SVAs<;wv<_$VJaBJptL8W*oY%#+Cf|-S7{6#HP@CR2lIkhLHA-k&OPMx z3$pFCo2veOY|R#Hz>x|)>5!h5V&1mOHcI(BA|fg0B3{{f;VI$2#_X(Z@XsLdioH6p z{D^^Wa8g>Jaz{;Tz1EH*s?R}C$l7{s*32}fMzAJ=k)C`dP47bD8vwYRj|nm40h}TC zOP&EA4+bMHqBC^mKr;u-JyKlCBt2QciOfE1r=Bt;JIz1F?RW1sZn(T0vw*34{kp92 zRDGo3I;m1Mx9HW3*HhN;r(TKT@A9isZCNCHSMqKo?n<0H?n|)2*-Ap!_=Y|@cZe^s zoeEqusW(PKH$)Fd<-lpjbpx`Ed`*Qb(_UqEwF%8s!%|aF?{!Lr&0WwX9t$0(*t3x`g8tzvOEFdee{U8Ox6Oq_FFMqHvYuk(KE6TX*3=6IVja) z?Af|L+J>UV)_S$FnuKQf)ybnSKDyOT7<{9~l z8^8(!;F`%9{8yR3q$feCv*h#LR?-ePrtqw<-OgYBo84zOVurmr$;r6!B~UPeE$ z$vk1>C+C1U_p@DJf}VcdmuWmqBhitc3QMHsU|@WXEOS)st$40#MR5Z7eLonYZAT@= zD%t^4OB+Gudp8qoMRV6Wu7_sX^qQKRGK$AZy=sg^L`8DOY)9&sP_K@U+b1XMPkq=U z<-b=}#_HLXra9eW^=x-;19J2;Dcn}o)1nnzvzuR88b?Jk52l&w=jz_pQH6d+LB96G;2DD=&7eyZ zZWUSeC7cfd$VYe#5Wqup!gvy zGk;K`KL}YdGp**Np)#TT!%biYhqEtbOO z2JJo?VbUCIFSTl5HX)l|10*x7l`>*W8a9q}xY_fp4{gpJL`^xfZ7rkYva9-=bcn3q z&8M)9w6Zb?m|7X+>?$SxvCl|{S)8g(_d_f4P(bI5Vn+wPd0ev>Z~k6d?0&Px`t)s_ zc4T)eY+YIZbd>Y6842@_E-Sa0vF`MqqhRJsT3QXpr0tK8EQVh8iRjM2qXBXuFCjrM zL80a*(T*=__{)ORLP7Od+MoF~RHgreC<5}`-8(&89!^$hA2&mUJ}9RviAMYspt#5% z$NW5uP2`zgw)~q@p35m6wcN-|O|Nni%~sDS9wi|GUj&;$@h<8A(gCt*zOLOoeLY^0 zAXdgffU!F+iqf3df}VD+#!+`$bj8T9>+zO7#~@dafafO+oF}B7Gt*$0XuoFysL32x z62Mq`Nf>%V!8lKKujW`9-KT*stNR`r74@hHk-b%g+?G4Mn9t-0Wn>|o4qec9Ao;x= zBD4I80Pvc;JEC^{k1?7%1(8c+botKNpTfkF_??%sc>9vsg9icDhWZI`r;=!*gmHaa zF|(25W(gzReQMzQPf%q}Gj`f{KnwoS@_dta#XquWQcB;_@mW|LD)PSU4^OB&o6jhw8`Q*Tt%W#zsIn|?XEYzezJ<)b26 zw}Jv8LO};e%MHY#r)u;JM+2KXIHfY-ScVd-U{YEbLYPCDeaRby#po$Vq@ytO=i;u_ zzgL+w%rQm@v`Zh5YJM`*RYV60*vuSjrp2ODkb+o2(NZ%}px*Wb);tAHfa-5bGRk#2OOH5el zXXvU3@K*zWqR)W}_ve`PB?~~+IKy0+FViNqDbBJL+!7_Fo^O}V6O8ly^$@J0-p#@$ zg<|Qf&GZP^Ct$;ir$x!8=r$d9Bv_77{_V#{R2(li-8SYnpauWCh?tmT#?D;TvW^bw zNtEzCv$C~iV*5xR4LLl&%}Vb$kE)Yx)Mw8qhUkD#P2RtiyhQbW7ki-!Y({wL&354P z)l5ovDE#S5npe(FPM3Zi3-f4z_Rd;eK93otp7KcUBOx~@gEr7stQ>-8Q(zx%)37(W zv9WlgT69Yke08_fRkzABFFtTt^`n*EA&qBRSYNsvKs6NbLvX@I&G>5r!A$PJQZ zkGsP8)TTG=WN~}$2mN=&pu9|ZhV!0Cea|%u8xiYC5x(#A1_IN>7yCVsTt4f z=x~hG+oQzcbH{~=b1{vn#xm6MWd~$?bcmL& z_V<268|4M7RHYP2i*gVj0}G^|`Lm##WWRtwC~qXvrXaV6-b1^OB09M(3KJ8sS>j@AMv2Oe zl~!7U)3=U-x%bfU-+NaPeKWPMCAA3X6`_dHZu|so7boIyNs{+GK9&?xBC7_#1J~JE zx~sD?4rL<4D>d+xx|>+0ldzEK_|FD|7yq#_DrI>4<4|Mlm)q3ohu727$_6k^csB{v zqw0Z@Bclv-45Y%a!vR$d-Tr#B)}UA5Y1rPyougW1v_sALFO#1YX)MH{2m3ON=u!V+ z%AeL_k%zkL1b#%l0>s2~->0~9g5PDl7IOY~Y_hW0<>v|a<~z2@juYP<#i5g53=_(W znq-!h!$j9vvs+}Y=Ml872jP*g`kYq<`&=hvBw(pKic&czr!a(}_bRizlOUkhyX%Xi z=O9+^X0Da?-y|a#pO~K6_RT3SGmqsTEP);bAIQuX6@JpcP#Y<~z2#bMxn2hh@lr_# zTh`pnpM!tzIA-FEIU%k830I9^Td_z>`4cdWYR5xu6cj5 zMcd`+BZl2A_DSM#C(TRf9)c0$xryd!&~j=Jc$}1kN}G^R^UB&pGbZU0UwF+ zxX=K89Y=F>cK)`F!A{=p1-7v<$)xt005n`>ZwV2f-IaSz0I^9|;K9|o&{x7-@%HP# zC+j}qHT(eHLKf35-^))EE2~RKq?GY~SaN8(p#qdQqnb+}k#xmE#vas3<+jl=coG4; zPX}F3ooO|lcl*2b{E+{`3X-1h)>d!U$7Oc;JEiL>mVRsl)&3V3huuWP7JyyL_WZ^3iWCnyUvDV=4(*zwE-B~VxzbMF0oh04mkmFk5J zbv?{-m8AP#+@NH&E2jB;bFgK2u;#G(w{Bpp(Aq zkwl#BySO9T$04|ZO@{nx(0!k2dvG&W&g{e7y#}=sa8cmKJNS8ZBdi2#zyF&{zcZ|UicemJit+b1{!6Sk73TdN`6`qKxb*}pk= zcBdDAx8X(tB7deso5GO);bC*d7wz_-M|&G^l@9gtE;;ebt{afrY7*| z(MnrHM1+oxlasTJ@6*UB&%wiBWY7TbQtEX(%;N>ArhqD4csZ+vhQ@^Y7t~+IBo;bP zJQX;?;U#~xleyL#eIxcQnhpZlJZ9evD&=ogrQ>8Hdmi=dBlYDm`3-d~b?%oLYJ5nq!@V}EnB zF3RT=vrx(BH~AR|M6XIBQJl@xYKQ%WdYa4^OJK&+PShCasYONd!@fK(BvL0T;T`AYIZp>W_vN@k2hF~mxbD^35 z#L@&C(1)_C;7cVe3gf<3#g8smRR-qmcL;~bw-a@KbT)WHo_AX9EUj~I{jziRv+HK?aJO2&B9D_*nUjGb){HVb2n!q%9vOkODb>Fc6z5tCe%>Nleg1p8p|vOd zUt@@DN<2Vn^=`eEd9@|T^8RwZ>!!D=BZ!F(42(*W#4mP!7b4E!us=23+oUOn;@kJM z(TZK6VH=t{ zr+ihHASNVKecXAq6l40ZdFag4V`mAJvL+2cHFzHfKU`IknE4$IZQ6F-+&qQ(+uGs* zUd(RiNfkZ)yw3Ue@GmS)!uycgH284vsmWo?Y2l{mU!JK7?oSVD>3HWF|NFTr4e=I< z+&R@9AF=zR>(%#pT&TM<%0zG+v>SJQELKTvE(1M#z?)CAzPvGOzdJ=k0DMwZYSk6dx9=omFa=&hx4B``}x0)BE3t71S#*J21iI-+Jb4 z+pZtyI~o#Z!;uXduUh1MpVlYC_N0vfjM0=nkzZRSe0HzK#%cn$Qcwl2!=;v#nzLci z^gPR_x2J2Jr%9(R(7T%8%exBG2O6{ew?P5NlfjQyUsHShj(n6z*#VdX-mCr(lm6au zg4tPDE+%UWR4q^`Nz@@jlbikYr{wu$9Gf;bYb;d&V6Dt(l3J=Tpdr4xw%2vFe<*R^ zz_rpUsLYMPWyqH-@Z&cKx>s;{Ni*KvhWe0JTb}k8Z~kFR+?_^vzhX}tvzc#yy77Q} z%jU5eZcR@QDw}jottP4w_?qgC3w`GoT&B3vhPP(tuN{l|oNzP$ZudP52w43wNWn*g zU(ataUScg`+0@OBAPxo60j0BIC)Tn@y=wlMEH0yHq;VmGTRg0zB@Or95-s)3-UmBl z(@E2(d+EY!$Jda$`GYynmjyYQ#dP#&fUGoY%7B?{OzGr2+aUUUXSh2*O>xxgovJDh z_#u<`@vGb{;ayZn00o$5mIQ-BW%F^RDE?arkBS#r;)?p^--T7T*ory@{ek_3Cret(e2hN08$l8Xj^e2fLD30Leg1V=*|)Z!HUwWR z#;Zz2^|&&3*8jS;7+tk>^e^$($u;*W(gBs7g8z%T;ujnp6%Q}29w{$BFeFJ>_*S?^ zy##yLAJjD>J4j)PPhX>i02h{56qlnc4h0269?H0n&ffeK!#gJzC*8bMch5ikrw@iS8uh&#P>=Wz{eh6LZtgAJe`;N zh0Iy!^a2sxK;gg0IAkFJCX4j}L<6GaVRjrm3Y9l^PMV>BZZe8dqmU|)7(^)vl^hjX z%jsn_f}Iju<%8x$Ih3wtolH(kch*N#L`<}9&|@k4X}Daw+=L{izA_rufVbejD!>+A zl~RPIBq?kdDFTqKD&c=qkI>}1!_J4PeW*&E+@}#jvr?Li>r;zmt^Gj--nt+|OK)K& zE4Y35vu?(d`Bhy*q2L|Xn#1dZ1GXBIU{AQezmtF4${~|)j#U{?xab`pjQi(RtCSQ8 zK3V`qRcXh$c%jl%QzF(P0V7hQj;6mJ1v9IWa6BM5`hPOYe65q>q=RVlbaBK z3P`zqPloH8jRGQx))Bhsu>*3G)`!F6 zr=g!+9c|v+R}Z7pE`^q*nngs%;pa7~jbj-&S4`inn-P z_XOYcG(YuSo0{&~SzzJQ!@^^gp{G+g<4^yxKN$K?nEVF{!3NWRTJjaih}im?^Lz0v z<;3H4S75_@6Ofnz<$*ZSFDT;%n~w>z!JRx02lxy#KWYltf#u}=C+JlTzf-6cawL!6 zOR}?kKLgMPTrAT*-W>XWCDLL-Tb9C!mu__XppZcSYh`7x@6mK6u=bw(dC#A#qjse( zbUku_j)zr#i@9NFcopX{_Zem7c~np+`H8^l{t`VH$^2@9wS1eiZ!`|0 z4o#G~h?x#({k?R!-h@4x9~16)_+$CdxIG-@1JRN{Hfjm@_)(igZYHoqX=>P=%mYkE zLKkjGS4I&W_wZ+OYbz;fV}EI9$0iZBbxMI2o$qtA-m|~&Dr|&_IQ9AMfSlq-&M_+G zC(FN&{F`;)(JH89JH2SdTXB#v5lO?&RKjGf^`mulL0_XPuKi}=+VA4#bnE9=Awj`< z{y+y)Kx9Wz$v%HS#R56C$f>%i&MfNTTWRw~{g{7Imml|s*dtSa0T3{y#xM1m#s4Jb z5G1)r~;I3QV4fJ1D2^#IiCA%mT3c+s;FjDz5lk4yxMV=oDBrzqex` zA6Z>Z)*u3)$kZ=jfHZJM%NfM}v{V~rRH~R&p88!}hP1ahKm7}i0IP>*XT zJxX_V(#}sb1En#b1~8M~N5&mZ)8G2@`LW_d0Q?BZ257*k5Q@N7C_tTEHLK4jUWX(Z zK=2(#o9I8!He<`GS{mA1v7mMd(@1x*oYwyxaGc%V&lhp#3Jd^+0dgt?1!G8eUZkOY zeO;ZPK4oJAd$_BgXwZe7wGOM?*BMfay`NJZ-V-TK5A&~ z>$*G04fyCkaZ8iJ_|BPNdHDl%c2F~W4ESMVV`!s?<;{u7+okNs?dR*%$t&!&CqpiV z-r_IhJ5Wd@2YRJGR>$1jm7xna_ux4BIgvTWH9$hl_ z7jB+Sxq&Yl@oB04uTOc%z^B{YWG755B&^Htd2R*UA5@9-dqk2~8ySt@!!qXQ+s1Vw zi?2>LBD|mOTvk`#7y&NA>6H2g4v((pJ}XVq&DU2g{-j2n*T{@(d9Ly%?f7i~w`o?B=u7J=w&7a~sltXz0j}Zl zN+XO=+&mI&I%&&km|Dj@Je-yGAiEue8k{ zs#2cT?H7LCV!aY%oEF}U>0y+sqxj0y_Vv|D=lQKglO&*u0ATk?9&XvFUA{6Ns}vcJ zcwbNxdrH@33xxb!7)Af@kl?N_XG)$WP7<|$(qdkJ!loKGG zM4L3OYv4L6iUB`>A9}sf;9H@QL08k};^otBtcuiDW^j%bs4lig2PtbYe4H;tBZ-L~buoou{KmyH%5%b>ODg$g5@c0)ZYV?j!aRQ*(3gS@#-wN}2XiRQSyOU^0t#^S)b z>erY^d94{=fuJv+KSqK|8>1x%#YdylD-NcoC!czr?0C!I3P2R5Z)e1`!{_#Ff61_U z8IC+xZ==@jb7l2q^p+$L3QXPa&OlrU(a@;)5y|ye zGMC_slOc*-o!X|>&V-J$-ho{dGMKP_RDP*+28!2{Xf4X6U>#_5lR)7}aFOO-vA+ZX z*_c%o1q9bbbVGbfbS ztb4@fxx~Fsk$Rne8&jW^VtGENci?$DuRU(RIbLZEZf7p4T(@=U@V0k9zf9v4Iy>8W zV3cwok&Nq($ut<6!U`pjL!)jWz!%)JI^n5UTb;2T0UOA3lLJ&7P-Bd_OIz|T5bKP)hz_le$Xzl zV5qJrwL1uu>P}Y z(CTI|Cvm&S6?}gBwwp{lvE*v3#`Jkiy5+%tdyzB|{CE`c^;$i&bZdG) zLgL|e0NI0jG?FQRHb7|-+TE|eI==d`r*9~5Y`JGjmc9`mYnFQ!hh$1Zbd+tjEaE(4>Cep)#&r`^2j9dJC ze1xgumJXd+d^|kDOBGor)&pI6q6v92UM?N}+ZjuX==%Bp$VNc#lr6Z>#?!HLZ(YHzW|M=2^MW>b-^R%0crwPw zX7j-bQe9o1hoNKIMV^4up0Dy-1qBS+-)#4W&EkvFYxc{lvn%3eAEhMfH7qrL&0kuW zy!Yflk5WU??_|L=5%p&=d+p4)XpHnzHi3bCc3Yn`m{1is9JEQWQW82=bb3⁡(k{ z9uO@&vQb)vwe|dCMY=46s*1FXS0n2>d(;8D6@otoPPrGLF>Q%$VAnVbbb zm7JtpbJ{+zu~%vtrpuu0;8~87fWt!86W+}pI!e#e%M1jsE6zFn6Bq@6r1)7j!L!#E z7mIHgLPtYH<~Zo7zOeu;q8`h?<$elTyaiK;HCUb~FQuyyC{?oPizP}Wy%uezf@HZ^ zgaYHiq1+MNrl<_&N73}GoSal0>nbOtVc&+K>U*_m{z-WdW^LsG%8%?L*yZ6SL%p@2 zaCpm$MLzKY8=O1aEiQwhU>4=z+0oCe*sjNqMd&(8^MjczDQUW(FRY+IM%vL^bj9R( z-+kUcEM<0fBX3RZMMdn?95a20D&Go!b8}ztQ9r-e@;u@v(E{z*@McDGg(XiI_H)Ij7bCAPUiv~{49lNJD zDl2l+z!yDG(DZG97#l?jbYawFq2)h^ZBQ)a`_{Mcs^XxUH-E3|Wf`!!z9cB2x;s&- z;toOz3dTWGcpkRU3cOo<%%94~H@l6~<9b}oT`@Ya#fs01O#3$aSI=beck9h#*F#tE z!v+&k`j{1cm+x^BxwFw^ShkW?v&0Ni=ko6>bNv9`G6@O`G={gWhmOVJU^JhoE! za2)KtyFrpHF2*5od$E2tz?M$HOhc5wm9N0lB%R9m#scdL6K>SIf4ZWm+5Eg!t@ms2 z#p&q}VC|?Ke&-#M{CTD8erHaXyiDH*3xq%e(0SQP0zQHDt*%ej=V=4qGoXJCk9G+- z7&s2R{v^fJfXDzsD2g(X&7Zl9mksW_o|e~EgZVMkudgfC+Jg`F$6NObqJIZSa{+!u zZA(0Vt$Ey)2)6uBsbY9+=X@Ajb7oal5NpC#>87G9$kt0z;o3kla`N6!QHLf0|TV_p<@?=+)k>+4BQD(Zzx|GTy4 z+X^8U=VB~UVM9h{&!)q>lS`!e)7n#RuIf(Fi@<~P6%C1HV`{=mLgw$)Z_$bEq~zoA z4yvASc56DX_ESul_z+alP|akXfs}abp$muK?o$1js3Y^?`RT8%oV{!-ep#*c7xJ&* zFdTg&E8$Dgq03$8%Bt6CO=c(fE~q|ngK?hu(u+bEBUS;9?} z^dg#lg}TAhiU<5aB9SdEK|VhEBq@=}+X142eJQi8%(-HIjV&$dyOfBFHV*iVk68Ky z-ly=-tsPBM!r40olcmhKgwi39!t&muqojO&qn3{XcVtz_G*09Cxz$$BgFk;{!6>Ai zV{Fv0GgcIk-@GiQl{uO*nxcDFy?xYHPDe-Co_>}VA32w<=J6nshg@2C580YF5X{p1 zPdv#3PZa>5Kn&-1x?hj){UFmiY+u>Cn2R{5(yc~X?1;`JE&A|h-+>$F`Zn_Bk4xsj z-@Q$!i}<&F%aKtS@tP3>9!J?V2Zk&uyS}M~vfTiBDfn3@VUM-%)KTM3gMn7+ukY+T zcsspqTSFe!wTXWy74E+}BnDRMMrlzk7JnwOlljXs84V&;c4(aYZ@99S9$igVw!>Ll zH_=c_9-~Z5P4sXE+ArmjWdb3lV@ZTXsrk{FZ^Re+@zGLML}|hsbul98ElA?R6%oV% zVDv8>e}z|^mvGAMbA=uNKyX1V-9KtJuz}l1fVLDGCfI3?SPh3xGx9I_%fs?@X;-R_ zUFe@MpVuq8OUfjPHlK%;G&dv9NA)?BSt>ZN%~M5Z8utF&Sb3n1*;x6d1@?(IY<);} zokAe$HvyikjSDOOz}jt6kz(3<)6g7z6pcBMNn>WIdfPjSh@X(N7gNDNL#HFb;v|ca zwTG*{SPrQ#9d5lUDJkgadpz|q(j8bDHnR-893anK{=H!5?XT2U)fkmtNkuWqAlh#T zPby?oOV(Y|uUFQV94QqB1HMm*YT*(~lg6dgeT!ksrG$_~pAcsf-;RRwXLB{}@lk!P zhZ2D-BlXVCFGv+C=s>EWT*efnvp-7l7;EtD`V4(%2xDu?F7mr7$;{CTzdeBf0350p ze92Gg7iGb6qSsh;LW0cXWNxCjo{)G#n*}V@*xK)|lSW@3+~ih)MB)j{&?n9)1|IJ4IJ*dyv4>)~JWZ zPQ(2gK!&kJI_u1ze8J8a{|TCFjs7aMi8(pX4R-y=FNiA}TC=|wpqpwCqlRfz)D6LLg{@?luM&ZX*k|DfY&F~b-I+7%W|Riqqx5?FORgQ zrg`mQaBSH-cNFg>g+#~W$={pCWdm!RP~rknU?gZR;&E)&89k+z3IDW=O|wjUp3Btd za=S)sAy9~W_RI0_U|zNgcDj(#t)4Z#O+Lv{V=OaiI&+JXLfz18)!_3np>C$&Yoe~K zF&aqw6_PyoY9BHy%M1`?)}RGBLQ;(?{|y8cWbHEF1zbvOU&BC+(B5iKFP}i zIS6nLy7XTh{LR{3(tNIOj&RWbdjbA+8K<^heLT1-@YN!?qYMQ{YX2$(E)@FgO)ceR z?t{Z&T2QHP7%_!drhccl%gtVEFITX&&gB*)giqVUK%?sg72KN$uo0L{77NH2trV?F z@sdCCKbRgJ#2p%YtInONA>MWEyFI|b^Fz-h=yE%AqGTw!pUtHBJ&s*COlj5U67GF; z`1~i$8!~I9yY}>On&}cGz}O)&5eZZbDO%=Td+zZz@wG0QhY;^}T(gJ&8jROw4GsH7 zZOo3x=f5EuX$j5z?9f6gWCu2I)}k99_#_DmJdtNXUtQI2mY48(=r0}`oZC5CH4#bY zQP5NPZP)?O)$zQ)%7*c*1f_xAWY3{2!og=ZLmL}U!^5@n2fo3ZMryLw{|i&}m{Ej^ z`99dWTXw7rf$OrFsQjX)lH|0ou)=lOR2pU|+yer{GRJ&GByprrTM6siAyo73{QP_s z((s_Fs)}FDWv$cG!vjSCYV7QUXl;$Rl$RSF9t__uDSYxTbQ<_Gth?I!^!t44w2*mt z)$9|qO+f;dBw3Y{EaqD|nvKPYpyt(HeM?BBF6)>f_3eM(*frc`U(*2z&rdHr_*oB@ z3YALc;YdS+96g=a^g6~Y^nm}A2bNGIgA_T^?6B1q-HKV~W(FdboM8z1>Y*1ZDwI*2 zH0k3Z`f-&A3j^+?s^LNxi3GvI(G3|IE6rnY5lcVenSM5;PWWF`@_NqiAvVD zZW7`p`D0z41t!sXi-JUzvxj3)^5|y1hrh!%ZD6H|wb?#BeOR|E>}o$Gk&g68ZLPN4 z>Zh{%xc*#~_Zw0->wv)yAmLLlk!v~Wc)yi4K=pJa^{S4Mmr89P8k(1ExTb$V)T+!w z{~|wHjvpep7w+oj?{69CDfkxBeOmdA^fd-C0s(Yf7#%@B!HbS!&JaGY7rfInQYV;5 zRSFZ=nmN1>oSQ!uU$xd9?}_N@c-~_o!g*c(3Zp^O>Me-R`)tC+Xz}hSH)#9QZgcVu zg({RnIOiAh)Sp)ve7Q7VLnBHDR~D8istIx6kgk8_r-@Xgkv{jmbNjB`!Ti{oD4j|y zr?!$^;E{lr7UE<9l9Sd{8JwHy$DNx(9;9JCekIZfg^ot&dvHe1+KQ?4OT1rGP-j2@ zNngh+u8ckn&36rJKcGMf#%-e(verqL%CP>hOxU&fFCQ_;B*GBl=v3p? zM!6Ac@o<=UO7UzDAG@TUH@v+ckpAW>mczC4TJj527Qz4~C`;5Q2*Kf&H7C;q^|+%T z7h{|zKW?6|zZ%7{3#Y5bvRF-X9CZJ>?j~bA4Vr8TK9&>nhPEK4sKGM^x zVVQ#(7XP9AQJy+Zj?PVn97XTD)`Cw5YQzFg)`yO&uj!N$LFP5(tUxR&;%NHo1suic z_wbIomNE^E?CX%%WA%|zF^*k|o`xn}IW|$yDawpzMD;_?aV*4gun$#}j?J*c0@)Q7skS!t84Gr-KHYawQ?%dutI>_AGb%3{={$cqpI~wc!z_$=T*u zVrOsyr<{-b`qsAznUa*LEoG|*P^polb+?Ifvq_Vgo9xu`fogS!4Z}c&Y=FpkrYg^T z?$`Us^WRJCJmbEW+(>yirV%xVZ~03EvNZ+u&**qbi}-h-FJXGom0C;t?I~=irh8B$ z$lNZzZId!SOqiCW--=(}u@dL(Q}U5@(JT}%%^*v~TXp6WIv_-PhwnWv9)E!(8gK{t zOIbLtpIMv0@IN0b$OLh+prH;&CL^l}0}BrlZ=55b6orCNQ24p(4w`aCVn34dV#Q{+ z`036f0mS?LRB%XLb-6(c$TJ1HKtqn>ud%G&teIj%fQoa`@`Q$TbLhF zBBzLEs^+SaBYmM13vC|zV>`Y=!Qxg&(&OWh$G%kZljWd;%KN&kODC#|kuFK?;pc!n z|HNWy>Vw?h;$?4%m--%uR#*2NT$b(7U3pBlzlNmz+!~p^Of*0ZxYFqBgAQ0DCsqlJ z_vv69%y7jzpWQ6bPmOjcDCkxK+qSz$zTs>J8+XDAz`&!Dv+WY}IE#(l5aC|{j!)nJ z;2KP&i5e+;NFuH{tXb z``|a28o&l!I=Y?6Hc`<4eJFi9eSO>(9)xCxd}oQ)jTV31|C_ns`N#In`*(}@%HJr_ z^BdhCrd@&#dv#p`o&2rs1UR`n@0pn|+Fq(aG?k@5bU+B68L)k>kpAIl(IfFSeRk9@ zJ3LJYhkFr@7JVZaf@)YW9+TVaIPu~6keosUwzv{QEA7{p8QF8~2#!9niUkvOToYhY z=dr6m*6erL8@qzvk49g{A!jJ0_nNffuA(J!+i+S%mT3p-e6I|em#LCG`_N^cPtFP1#8sRT+2ZKz)TYfHXo(;wrqEgB!b5Ln? zkRp43Wn=Ukb^IS2^2gKss4mMy?aAu3 zeqO=68fIB(pd{h<7FAYl`h?M=_GW|fM&(BNaM=o@iqu}zwdzAQg=*~V=gK)l_(m+r zZVTkSp_W539Ttwf`HR@FB?@ZlvPn0o{t@j+$TtfI8Q6Cf;GULaAcVycINXaq3dL8H zTqyiB2m*l3MS|Nl7@^qo@?8lF@;K-?9CbKj6=53tni^xelq(dUS~7E~>f<2r$x7V|u4IFJI>6;KVi$C|}$+ z0H=pdqE1P1QE?a`4&rp5+!Aa1GmL*~rX-`@`ZFhJ!ghM-ugCLH0g8_4x9iR69DG>8 z_0OnN)W}$&3U3$P%$OX7pyz}Mn=8=S$?gWa6bb#UZftv5(5=iNm(5t4SnQi&r-q9N z$H`p3{dOBFdrw>H*@mfI^LqyaYavJRbXC@-_lm1E)K z>+~ckx%r8{5fv2|6VKuNo$rbocSdNQTthqsB?&^{Zl`w9cSFH1nxs`LjZIBe5+?${ z+BTvbM?p`2hd+5Pt0dFo5QcyM?!?s=j)1WA*0D+gBMG2&8O#=&pNtP>0U)$|Z)!zo zsuX^AbaZPL`T0#6G-PhX`GA&3#W=%0s3eV1Bf)K?TLqJO^k^T6_k7v)uwK&Tb3EDC zVPT?VC(o(8SDAub;vnMA8PgbKIPQ-Lcv>GS_}RAnVIslLq1YI=T^fHKvk<043Zdge zRJ;VRPASu1N&%#;LIA%MrQRR5pR2=miZR6DVac!UGcs8(yyXkJ0i~X?xv7ld9MUY7 z$Hz2~>+4iK6{eACK6&&I3e46j)1W=9e4KwX+83WqYi-3cKSctfNqFVom>UZpQ_Q4K zG^E=IDC3bw*W)HgK)>6IbM}4b!Il4{nOFVWqe=408ddT8vapOz@w+PrajJ0PnrFk) zi%QDf)E5GWE+nEqnLIe(TMyv3Ce&|EC#yk-{$Rwfx8_@xlPs ze@27ea2=A*FUNuf8vXs_fy&#VVJt7t$D9i=b>YR(8nh=Beb4YN!_M*!Xzu;Iej2to zIB4U-{iCsC(%zPdDapL+U_Y8Ng~xXl_$R71?^NpQicmvc9tAEzDMfb8?v@v>!jj3@ zM6bqo<%~+{wRH&VMtN)H<80*)ubbxP3=NcV&-r=endFen!{vnHk>5vIHK7U-KT%o# zlBicNUyj){+y-B| zzp|3(l2@Wyg*c@x-Pv#SPw>Vcu=rri3*laAaw1e3qK8jca|8TCny{-Ea6NKQ9ZZ+l zp?XzWBV#TyJb-#);fjN`((veb%WZ&p+{@}pvvwJ%tjdmuARB8mWH_d>Z!JZY8J*3 zYEMz)NHn-WK82it1Gt^hiJz+QTXm@&%XPr)~o-r81X&-M~|O3NG&v&Go|#gA#ZnYXWlRO(xpyf#2>~fT;(d?x8g59 zSfamtSMVW9D+4T23;M}Hkt6S`RFT5*YE-d1{%nd_0whT{@KunGdw8*54(7VvTCR|^ z=i|XE`j&Gy#zMT!$9$`8?Q!l?Od879xurAQ(wp|(=89ci7+CjN)OTupDO=3g-dnSv zuJ|KzPMl|9Vp@G}-) z8H2oL9?2qH`e@n~1VNKLCtZN2{fFmfoYII|Pq(e!tM$1<82~kf`29aACXH2}!+}|I zJdlA!s1I~q5n>I5S$%JSlB2o^5I@;cSf%1!cnYss?Lke%w!XgW7U}R{g{c0(g8X0xw!*8^Z*^t+aBy=jbc2YG=AoXgB9n9bW1lzmA^@#&lw~6 zBxM07Cc?nTBt}BmCJ7y6Q1p`MhYC2=a@gipC_BOW#RYz=f2wAx_1@s%(#m}sZi@HO zTveN?uiMWZtRfS6WIUiAM3)__A%1sZxfU*ZK6mApY6u`2S#<$pz5fl9Fy~8xKoCp* zXqvLC?tT3(3qs30c^$>LSK5-Y1Bo&S$xslT$8uHcK22`c(V=*Cxdk@` zA=V=d6^)wGmGG@6+I(~9wM~OURETp!dt3t-?7hEes59mUG&Q)p1v&}b47WJg?rvIW zN%*#tXF-_()$m=65`&E5y><^GZ*L*ph-@$CM#fMv6{NOS%25I+*4Xs8u}uLr;Q#!& zdf%Yotc4;WtckxB*}J?)-9;|Mv$U!#>l+v?lcO3M8n|LPviK)#<)rBHCYb?fASDJC zi%jUA?S*dS#GlYyjYM&3^PgVIIlIfnDb20&Og)&pMkk!QoyujYJfi`A0sGRw>QPWR zh8=SSQ9V%BLgDPbz9oJc=#C{ipIt@P(Q~OUMaMzay}X>Pv|9x#Mh@-_*Ws14l427&TtNw6K)m0C^2SQ_AaT$?weQ z6;%R-pp(5{rsGRIr$yX}P@c`K$v1A}_A^qX&k=CQ1rUJ;dy|DK%qc)N&ZqnUN3todxT>~@`P-p$#RWV7YpTGV};$gYv=rzqer zwwe}$U;8b66KjYfjvK8GZ{?QXWnpy6E)nFB1yV^47(=A=(N*j~X10&Kg38nd`9p3j zNx~n_DQZqn@8w;l9T$l6KMXIVs(XCVttD}#-)hO7`0b-b8%K7}G(G8~&5m0=;J?$| z4VE@@L+N_|Xu|TIWcawmB8Z$to5w|>9UKbwf-gB!K>+Wz+cCYIwKa(h)m>)c%+}`M z(^ad0vwb$x#ovZ14P?+TpVVl@_#R)qs*a42n`Iogwz}!T1IRB9`EBHjUhE97~yBFGy2* zAN+It1L9=wHj82&R~5G1vJs+U6wfyb67TM2RmcSqR5Zbb=(^UAnM4vn*Lt}#QaG$t zw@XMB`_x+DR2$)5`p|Gh^-ik?J}IA%bG4l!Zbp0OueVP!aLfte-U&rUa8AmVTr)oy zL40bTA$I*c?s`=sOE>h}(@vj%Cj3!o^+)H@h+M|!Omay4q|eiI^Xl!taT$a-^#1^x zL1e!4ddc-0my#4A$hkgOL|nuNsU-%VQ}eqnNC*rFbUyd;DLfYeNdzMaOG!-ZBYyf` z;u$hZBoMFwXaz=7VyLL^<2p7FF$?3k<<~s2G&BN<2S$vOgSj z2ZO$`S}B#KWJpy;6;(wFj3;9ft+i5Wu~<}9<(xa~B#kGNlhe}}UlYGY!V?iGWfUom z`fML=Qlb&lG|j3SRK#m)kSN9^BGTlQW>jY%5dM-60wP9)fGme}M8q6UPENG83gU}_ z*gW&zFXr>Au3PQ)O1qP$DFAry0K_?`luD8WSV9Q%x@PCfvZ|`8)9I|QuO~@@ikh1Q z0z$A#Q-iEs!jP7_2WIBL1W2S1Nth90G9D6wHY!PMlGsj`1*=-AH3}1ri9%~>&~GPc zlB5QR1z5*uOrtQhMuE{}6%mRiF~o_t)9)&+Iq#GzEnQV7?9#m8#iST_ zq@%bqS?KXWyPLPr1d`B?vgEv>lk6V=zB+n&u{`sq*Jo6a1PsvZ3LgWGrRKe=>i^U}^vuitBo z{Yb@Pad^0YczFEy@$P&v+uk}{-MYNB*+(=8q1$iYym{l{!T#|SMD(Yh?W2F|YcE~7 zva{Xob&WA0z+^hVedpmjzyA31$8(X4LDn{sn=e0?w-i7CP=7#v^^9g4zf^h;0Cfb{ z)n5MLf4ueHhmS8m|Khc4S2j0RyX`!+YMHYRATS=yKl=Fg-MdfXk(}rG>e{+e3T4R( ziKkuEh@%1UfZWRU&6l6QbN|U?AwIyTpY6HoCvUv|+@%W_TX_qWavYA1_8&fc^8Rl= zd$M~3h_MoV@ueHag0O1_Y3Jpjzo&yGaLzsXR0Oz`0mvU)?#Fgn6u`;(VIKa|9IvtU zGaUBcc=Lt7{^7e-t(fus4?e5v>1(gw+}XL3rYW=3wVO;QcW&MO`MbXvjag6w`5V`_ zuie-w%84Z~HVI)_SRx36cfNKtfa4evPtA1h>?Hi>n|AU1BYoyi#>S@BCiqYm<#;rD|GnS5|Jz%Y*Fj2S@Xa@0THowe^~93k zGY;HyJGD@d5M^1h3CYXp`Fa1*(|qD(!5yy)!a~n>?c(vcTrmP7T0y_xF-Ff9<>_dA zdV1o5Us+vKHbH=XzoYHdgTv#~=`_oeB+0ebi$&?2zjNpFt5>dUY;5Iu>*0g@VhGVHh8ZA8!-i7b$iLgxq_ z13(n8&t|jfbh=n9oO7|5Fvi4z*4bWqrV@S%!+tiNxmmP`q)2NG0;n_!5+WeS4((ZZ z7cNtBBdzr8m^tedHuruNnKgkq5UDK744K$Ks;Y848ZmRb(;lv^Ds54zD8TX|cvpuI zqB1P_V3jgT8!qT`r6fXlAuJ1qNsr$BujR=S9Ps^sjhmh{_lEu zEf4Kl)pFUEt+FUv6Df)_2@)WtoHOryrij?PAL87bHvy0mC3RVLIf=zZB!QcEI45Gq z-rx88I`R5a+D=rrtztzQm8PJSWFii|K4xSD5LBc9ln1a30O-B1>I!ntuF@<^Y1Hdv zPN1y4_iU}NN@p$CpfrdhsG*V3BQtt&fPAO%V`g%RC$mjt=&R z$H#|*K52UP*(bmDwJ)!&u62`^^=>qt98V^Dd!wnZ70F7cwYt8#((WuTFRiWhqDTXx zuUu7^`SHZMDlw`PnbuOa+-=218HI+#T36*$?<|NIqm9ww=tW92lGfT#69q*JSO}SA zo6Oul(#Yrl{A{gn7FBHKivnl?YsS(_Uip5%J{}bZ!|C49=x8*qijqBh5bN1_CJ|;Y z?1U`@x?VG0WB^bo0y9hl{-PS|)L9t=y50q6uQ3tP|KvWF{Mx{WX8l6+h^)|MDSiI) zPgX_s`s;5E28Cb*s0Sl^^!B|s-`~!%jG2W65vtlb=b1%GOsIAair3$Gd#U&3EHMa7 z%3Zy7_Qk=|KYji7@yHVC+aK?5?;du#tt3sgQr^RO0f~M-001BWNkl$U2%k& zM_%hi-}>ekFJIcw58XDI_L#hp@#89?76k(Q|AKZNZ z{oDKdv^%)<+RtvUbkpTtyW44{X{<@Hu(NJ||7d&ra8lMHY!tol{EZ9ex57eBvwU`( z@kR**nE}8MKKIPk!^7b#KYVLAs-1-oZ*6~k?|!G#ZnZL{6f;bx#dK1#2M{80%gf!b zf9*?`FQ3y`2bDjFkcbK@H(_9&`+!f?5+aD0fRfPlLV~%F z>C;+4!2_uTDEvYoImsd>fp!*u@r%zK_b0FY>~>W-5&iCayEi}F-&kKy(^LRU>!x`z z98YV(!ndt-e)GKM|Z zWj&qbqjAm>F^Pb^apT&HFWqRh6=DS#Je`8zDP%b>yu;0Jq*1~?PF=VF%AZS9MFd%} z83`|HiDu16p4Sb=n5CttyR_WvEssW%qyF*s{d*f{&!t(*d+xSct+bUM9UUI`2~?IO zM(L`uMOl4(_fBuv%d#wrGh2(Tg+DnnZ9@n}@nwY4_*??O2hXq@xko-U*i7=xK@wyQCm z1e_os2K1GPkObYIcxLCF4+T3s%-3ENxu2A4;VL6iS}U!iSf^#TF$2PzRNvcjPzE^O_cGg?DP z+H+1TrM33nPbTB-oqbfMs%@l^gxhJm9h-I>M=YIAnh#t|(@E|9WH>z7Kiu2jn@n@-U7W;c&Yu0;^=s=J>s#kGl|pCjv@VU(t#+%o zvZ|6ur6x(DSW}`^8fipuwH*&8bzK7cBsQx{Su0y<#j3%nBeQiy#ku#)Oa!ELlap<8 z@Ek=ZP2xx!3OUyEovFE`Y3|)bM4;fRZiu^#!7_*dzygJ%yq2 z804c#o>z5QJL^5N52+_0qJ&XcyafP4LDigMM4Gdu_Y43U=kv&4WF!ptzW|~TAhH(= z9-#)HaP~UAFrHfZ@lys`ze;trz;*fTg;nrD0+3QO4YMGEm{#(Y7r(Hw)Oq`@_wL?5 ztSqx=0c6YL(Nr2|TZo%bBuI#cbYjrCO4t%KqO?vY`r4O2A4S>E-neyiI0i4aqW!%= z?fQXFLlO|O5RqG5ZGY<WjeCcgX0M_ewr|BlQ=T# zn=3EB{K6N$_-qmZi4S~X6h?7I9E*TB1pyO>3sbxWyo!hhiNvu$1ho=}!iXMD!PXxs zl0?w664BrZ&?wZizU(h7u#|`r(ZT?r!aER-zW@lJK{nTW-}-}>v$*^EYwwOG6G6kZ z>^8ulCYb zl4kMUdw0vS1dLE3Yf-g3hA6M<(cODn=gzIHtTYo>{(<&0F9>5rqRn6ER3cq`l{0p$UE|H9HOB4D2i?^%XuO|A5(z*0jkK zk%!S}ROF?rZM)st+}zBvEcBDAsw(QrvsllF*lxFzIMV6_mqUnbwhpG*S^u z5}{61mMT=3DNpDl^oha5=vb*Jii|djP>~n~YIZJcK$3tW-~lZ{?O>SOgF$io&i?(K z!=i@cQBgXDro}ojY1hXsuYeV2QA@L6T^SPrQ9c>PS@OiSs~^7q?)LWG(PS{LCMwbE zn`aanKt6gPJTTV#I z|K~e@|CJY>|I!Pe-#WLs+KG)KL#P^ij{pd==muy?Y;+?5@!%O9vqDisn#5|TYeWR4 zQ7KXiwIXG`b4=b5d31qC(YSMX)+|lC-8X;w>h@7zNO#-qjjgTc&YVkHEkQscYpdMV zxpm}O0mn*3X_Tc|7ALVW$|$XoNLYNGPpz$lIg8?@rB)P0QKVu+MxjQ)#%}Aa_ue^X zwsq~D)ryp&Na-|*k|QyA757UhBFgmD&dUYrxhoEPQZ6vrh@ z^KvpC4+o?1q{wqy=Ui7}xo+MA@D2D?PELJ6`_SxgCxpbHStmr$)HtND>A=sTeHXPU zGv^RVSmT>J7d%7lSSlL>>EL#K+%84)-aUB!3}c)*WMD@2l$n`Qf~*Aym>PT5XXV3t z0WpdQjq@H^ziZm)9BBS-{^3v6- z=PzDfJ9DPnY9(RX#DE%csh#}JS3dW|g^hRKzWLs}xALME;YewP9>8nlEKR%J8Q+aS-eIuv!YRRz6Y% zDc?zB1vSYkfK!T}fBuD)^@}%eZQr{6;P7ae=e{f)i-?C{{U;<7QJTi*wt6?7d+Mnt zFR!m83M_#K5E2AeMQR92rIFU)5gPOw0xR;pE`IwP&t1E;^2Qqk%gam8Tz~r6r>|VP*wv;&@Cs@G5mCZ~-e<-!SVSKwi@+qO+E*kXfJ#N;@=Q~z zoq(iTD{uf##0m(adTfD3!G-5tW}L#B*{4yQ#D;-EPPq7sbNav|oBegsPAg^Vn!;yxwZ=+59o~<%{dfo!fUlKIk7Q z1R#>>q?Ke!X*6_yXTNr$kOqVPU@#g_rnPG>q$J5s;jQO}St30frBQ$yG}9Rjaqcs_ zBn9XT190G6kPv7Oes1m{rIT1IZJGhL%tY>|{KXLbQ$f*40`p{3W?{xGOP9J!ah#Ya zLILmGbUG>W!de?ANz%&NS~n&kk=i;IAZn6N9lN|N>$-A|wbq?ZJC0*OWM&`&M1=vY zD~3#f{$^1o#D_-*ckX;Vo#vM=UA+3#lf9L-Bu&d=+=_K-C{bWYGIwrWvT>4Cwck4$9#8Uq?j8)M!$R)f-hK78H?KZ* zV|i_ZEHDu2ILZkoCSU@?u&{C;9Hq@!D$d z;^phD7+?R{PyXb;z4Gz)_}aB6t~{}|zSdh^&bnN6 zvG(A+RMuBjJsg(({&-rH!)Y-oc~ZFPv@VLWDyo^*UumTU9Dyeg5C-8HS7#<%mB4?; z`RoLN=2mGU!dKtDbE17YAswA|bI+)(i%SE6gr=1u6~#J^V`H=?{ImiK8Ig@5C4lft zyX6oCpl%}9LzoH*A~Wpm9atM$amYxIfY(1A`O|P{c?OPlRz!#yMbNVhN7MdbeB2-9 zd0AIgSyi=lCQgzxZM9n6Zg+XP*X_nptQ@827}RPG#(De!_nAr zC}I?mUS3}AEq6CJd!25q6=<*|67n*gqmOQF_xq!8C0x3+wYJ`#u@V5p1A0VcuZjxx z4hGwM$AeLk=asNSgjOqCUhb`LY_4ytB?dK4!x9VN0Fb>AQQJGmdpkz}z~a`{dY3P6 z5?VNEtJ_|b!6>HsOt^wlfplT;9@0HXh-%RpG|?Tzo<-)0sOm!{FPH=Z>5 z7kdf>fIWPCXaDeUAPl5ndAWW0@|IG38lxgC$~mY?x4V0Eu;1_ZhgF$}21KXZSzq5c zb7rHr+)>Kq`NTTgAX*?Oi_J$LZTAPc2i6Ly_ z*4NjbxN=S#AFR_yN25D;cD(~Y=yuJe%V(3=fXG~K;Jw_vzjt&rVo`#0{=%7!wJxFq zaDa2d1vO0%A!}hgsUT1x6ePwOA+fAd0ZCwxo0&9hc8i7Wm z{LaTafu5_4y8h&)tfhiJ{*zI#LZ8}}#(>M5O|>4IZu-dBv01T1U^<=d?H-J#m`}Q}ATDY&E1sD_ns>~(JfAQ#g2cu|Q546q zQaT8~!b?U}jgTI-_x`On-?(()VwPrydwaL<-a>@6_0{#wjip}CM3IgnM7n$TO%lL0|1Q2%opSYT)Mw1*L?*Hv~{#!eVzxMLimzTQj zR^08T8ym~(t4piPaVw!1MT^i3Qw_qt2}DF@ah@HcXJ1=i)lgZsj;q>L*42(H>uV>q zW9PWGGAZiOB;P&Q9}EXpB+Xh&OG}-lrP{gD*5RhAt@GZIQd+AxN!qQno5d^3-Cn!Z zGA2?%sO1rX00|j{J=X$^$Wf#tZL-KDS{bdh(t;qu*3|%Dj4{RpJ{lq@0)?Q!hX|nn zoNd4hFsHkzkZ0P65E`>FRMt(4YHV>-@$o1hjz;52J}t_s@>T6>>+-U$oK%%B@`@b? z7>%F`s#ikRz)B!M&G58Tv{}kd01yJua3X5&Q7L@=gZs=ZJOjx-%w2f6z?%ODfdrg5 zA}Wnh6eV#KJx=q!P+$onYt@uOD4(^!nn%pjuU%lN6I^7Y-Uwi5^iG(;Iv2PU+$6xu zOyWUJHaMb)6YxY1fDs5dI>GtD$#caSUY!&IkW!>gtds!|ks8oZh&m5pEC7N^Kp_}} zNCX)iU@hRVQM)1t0UGw2P%(IhO2p5@LqrtL&$0+1W`F{}rK$T>7>YXY9XI)*2!zzk zc@e#cB>X+k;gb}Ku zsL@4m~oOC3|aU{o%4<34@haPl_muuGM!G!vOq)@4*hBlI&TgpQw!n&9iRmf z5{)Ora6$4!3c&~ypiYxk6h%shQk9zb56}))Qp1mbf06;X?#R8&X4xg+bh4?8aFl&82uE4@iy^Rs^ zw0Qn8P>#ns01%ZT#mvs~?&1E<&W<)_d1Y;BX^FHhti5}Gd++E-n^>zzkOYXmOeeXu zPAST=6p%&4xr)R+arWG~bDL3Qyz{&JM{j<3(=jGVD=^t?RlC~iP)N*#V$2*MPjjDO zc&A7y(#?0Os`B1PQFP+-;8QNZ*|LuP{$MZ~?;jiqs!NxyGJp>PcN7g(NAth?=2x$5 z^&+S!AnQPa=tM-k_j9FJpgZZ{UQ&8@B7gBeem0qMyWJL%>2&Ixi?m6T)R-v587ZZZ zNJK*NbY<&lo_jB8ni>-VrC?+xr0fZTh0%WOcH=Ryc7`0KPhr`jJKZ=v2EDJ$J z%9tq8X+lwiMjM5iAXX~YXmsOU6ECi`h*+_V^7^d(mfP#S*4d5TnbmA5GZ8Ye2jHedEaI5~LXAb< zd+WKfQk2$uwqC4b=b^0qXj%@&`N84w;n84J)Q%`?W$kt+Zncy)A->7EN>Gx>q;Z^O zS(atpZdV(PNQywCXpMpS;&Th7^>yu>uw!3U zRbCWDS$W6Kd-kFLHIY_|kht-XU~pEWged3}V;L^UR|siAuuj3dQ+bbywAR`==YI)U z`9u6hIqA%U_gvRD{4V+=%{xBq;rgxOV*#L2M5q*jbBu`ITVSha?TML8*8}(_aYAaq zCiP7o+NgsF8o5#bAdy0?jaCLp1S^3u==kP)1~mayjR!$O?u8Jb7pP{}SvZF(WFf3& zh6n_lFUB&1PXUD9bd$X>3(g2!%n*@9UQ;Og!-wfl#B$g`Cl@BmK9rZLxt93!h^7Jj z0w9P3U_>z*Oekb!{^0IJq`!DsU}L^ObfK2R27j+l1%)?tM)T?b>%bSCU77k988&zp z@)_O^{-w==Koow2qXxhyk5K?NIo$yu!vLU3LWd#{(gEF!Tr-EYgjgi>;VmTx;1FCW zUIi%hp&t^m2ZodYAy}jc=W!gfUr4UeGYOp*rOCWJ0tCSbWu77SnDnRSo5&axq6&=) zlFfiXbUZu5sbD@lIa~=e$%eL}CpL)`vnmXMR1jCq1Avf7&q)kQg&GU+6I=Nr@@Q0ZSgf>Gh*VW&6lW^Pg0act z3F<4Q2mm~XwD`Feh?)gw!H`IVq57IjEri88A4R6qZaeQ4k`B*Sgos$gmgRIZ8I8xx z+-kSG-KAEm9qK}658~zr_R}YI3axS^RabRU6qCusCh?i`=hoIY(lm}DtyCyDwbF`+ zjM1GmOOwPHZ8U2oajasaTS+&KBBNETFxF@k5dk46B?O4*8-p;S7dkv1zV+t2Kls5v zz5mh2q|>tYwTGg#$4AHIbYiCyMYP(|S2x>!aBpMn!t*z-zVyFdv+FGhp?G$s=#3~n+y9v_(9`(|UMwbF^st}dNBv!298m>W$H z1_&@ALP!A8go?1TTvWEM>tb3CMw9V0FKU-W>cYh>N>ZJqLgbt)ih^0vES6MtS}Vrj zQoGekVy*Qoc?q>vNPxnKAg;1yRhNZ#4uG>HZg;X)mc&V*??uau54&^XssXOybGRIzss+pPyhefmbkc^QuBt$L;UVWrZ&rb zYa)7^Sh~ftG&aF)Gm%3$^eJM6z@SmU&ehvt|G`sya0YZB1Q-te@{mmo(31!Utt4tb zk@dl8d;Fq;dmck4AVGd9+~nn*eiMY?F{(B^6>&York{4&H9rx7aq%$)7N$CnscL5S z2tRkZ0n8n80_aa&NnlQYWZdLUH5hpL1?`Vdd$HIIU{DB+7?eM@o6EXJ0N-& zJ1>ix`gsX{V$^M>=Q4N8Jrto8x<8?ULFU?foSCUPB#S^(;US>Ghh2sXbr`ru^Z*2> z@T(`Q2hL^kGlDJ7YCSxG_{l;8sew+1?2*|(kKmu}aMgTh-djbuva+nTx_^JWe|$JC zrWP|t2E3_{XpP;FTZU zx^utwc>coWtkYu_X1Bj{@80eAd!2Y~ef^Jr@5StozS?cYt7|>dJeVBzwFSYB(xCzVqOXH{ajcIXpZ**nV*5sDE_h8869}sAO-i{P5mUJ{{Srx_kxG zmMyTYdKWuUA`(Lt<_Ln|kSl{WcE$Y<`H)PUIPa=rB1`Sva&k-R@W$i|#FG^RI^>{QM4yV&;F_{!) zX+w9aEQ`9Xy$5D#8k>Y!oDznAB&1RzGy?S*QMs8z(W230PEtgGnY9E?2kp!>jo2Kh zy!W#t@5kKm4*}4d-(o;HHxJ7q;=NQXB5@q+Z~|G7ug*q0za?LOwx!5I6fZ~+VgjIe z5zpiw+GRrrqTwcC7{thI>-49OYjgES294LJfQX=A9vFQsFSrI=Jb7 zoRklO06bH3BLt@z2-8geI{&l5r9UsN7W6GbGcfu*;*uA(SP~I<*jg%|QofudmYlq? zJZo9eNoCleygyMG*L0`k6Hrbl&8gxOp2?^0SHJvB@bQl*JF{a1sq1Ubve74t|QDt^MOFf@dl5hNj^EOpw+ zwJZDk``bIad)p6|S66z=s~f8;is;^h?eTOPB`LBHgW%k1qlg%U*aLew><<+wqfKTE z2n0{x94qC783YkcAXU#;R*zQXCoNWf4AeI4F^&Jub5WFep4U~qdFG6cVp19av{v48 zUDw{%z8rexZEXobHPZ_v3z&v5B3xL^n*(q-$&mm7&Y@g&UFXy3Xf*QPYpv5XU0+`{ zQLK~>uhcP1KC#(VO36dx9|M)pS}kQ zES{Vp;_T>Xx7S}coy=&>7WSZYAEnf4{CraSV~s zSFc`r`srua*UzNdp!P=xyGKX;b6e-X{kvaDzWqDa*7xq-fBolg?d~72(*%kqqXP5$ z_wM$O_SsI0d~m$~;N7=hfBEIFf9|;(oleh~h#8O&LmUsFQVH6zT$l?^TzLtjJyL7%ABB?K)!=6Lz=aPXw#5w7UK*A)=~FLh-_ zFpdp?HnSyuaRB+-)V_KYF$IfhT?-7MM*ji|8>*oQ3m^ujM$_Fny`SNHNhJ#Xt0seC z2BN0NZ3}p6po6FS3iIKrz$1?kSXB!THLG}Vp*U;8AeaPaImU2Of}afRf->qeeMXNe zi{%t4d_n#H%X}`MrgN5mwyWir4l;W5-S|bs_0LLpo0B!>gHF3J^dYS|5cwX%0dCF| zzhndNF*mD-urwYtXhc&Y^Y1LsEoOfJfB9)F{Gv3;Pp`#3`3;=iH#5Ks5vEDBb@q%l zYIo=0U~kvfc4cL4ePub0<9FVBe>56s6SII)Dt;_yWKwOk9KzV;=}~C z(`Yg+%OZ)Rc9t!r6vdG?S^<+V0L^Db^JI=i5s3g;k(n(EK%|&Xt#d_LRArSU$;!$~ znk3p7XhO^zEmv3wgOq<^ml2tbBP;8slks>o8I4DPxU|%}a_z|^NrQ~lyE=|^tSB<1 z6et2hA!J3Q6eJO~V``=CSZmY}8AV8uF^N$M*$^t4p(tiZcmSxX>YaDq``hpS?T>!^ zlUsN0=6NNaw2qYsdUtTxHzs=W%7t%#``cgp>ent^xBw`3Z@u%AAOBD*y#Ca+mtOpW zNz%cnc;n}99gf|o#0Q5X(5+5yt*bKf>Wz2rRaJfI@>Qet@|msC;m(Kezm`u%X%e5^ z+^m->TOQqxOkNep*4qLN_UcC6=cQXt-+K3*e0uEaNn-Q| z@4WlU_x|bfl_z@3%U7>mJAeNC>dIe6!~H#laPi`$|MUO&<2)}ux^?^KKYwem zbGXy5?|k$Duw7eS%9cCKo>Bjji|I%0KguIKx>QyD(kHa zq8Db8EY?Y^v^FM+h_ogE0PlTKOiEiTrLr_$=`3rdobyFl3@1ZjS?RXYG}YQDLJ$TP zVTS-lVPqnu6(In7&(2p2%u1`sD8iueL=mWJcQ~B%$8MOrN$IMxs;aWxZZD-hh%)P; zD$skb9T$b2L(E zAhN|wXldpSAfNJ>pGBYa=ucc=d^~&_hkyI}MW3{MhP!Xx4CBQ%bLe?IrXBJt3lty! zL*-;Wl1~*~{wn=K`Avt(pFGQxX(m7vnX{XlY0}!+-J6a_WnQkXZ!E2>KKsnm@4WZ^ z(ea?w>Z-_qh_hCd5K)q(h@g~e=$N$)>TkBLv^658Sw>o&w1`+xB*c=-qU3wl#atw+ zFEX*5bGEj1fV@QU^71lb$YpHekcByf{V_lknNFvzHAPs*+ABryspHsru_Y4DS`u{Y z-utpB@_f3wzP7%$W{jD6FdICPt!n`cD)mrm&z0;A;s-D<>%7RPlj&$QBBgpuy>pi? zrAZn^AvglHQfU$!1OvWpBvGOiBG*O<5gUbBnzUPq(bUP3NNWZmr33_p6>|VMAxJa) z1VqHj)_eO0ue|buzxa#4eE)-+NtzN;9L2V@3IUmYRXun8${+l}H(q}Ek)3>E)MS z{{8i}vqS`dqyPzmza}z@h_n$e!gAt_6A@) z6p=P2Tpo%P0Fg#S^xj!tmt`ryL>Ork8xtu_h>9q9-Ok`g5GgrbR5bF(vH@MZ~M zgL(zz*@>BE=NXa(mdWC=R~k+9V|Thn;yk;HnMIuUK8V~;j!LKJfQxIvqa(scR=|Zo zFaYm8SV0g%F~)?$%D<5Pt$|C=e&HuI^I>*Z&&f#-2~ijG>Kk_+@W0~9U~!*#wBPwy zAmqP&{rXqy>1gDK5KzD2&-bxY&d2`f-{4RDjXx}&0L`0=mJpY^-6T$qkNdlO2fI5D zin3ha+sw9@TPC)6bY1Ty3MBR5f))ai6kDFslk=7a!6oMi|ku=t;%iZNpy53DX28e4VlBKlV%a*!H7DrJWD>7A88EpWd ztSav;fJ9nH#vn@gMU6QcCe!Ipe)8kL`tSe!2mkm_`};?&R;%0T2;yiosf#i;dVOu> z5B}iyzx9WIc=g(qJfHs8zx=bwXz<*PXTJEtvvpP9ym|A#{^g(l@JByB984x9M(wq= zi`Uk~)E)@x-JN^eJ3C+c(o2=KSFc{^^;QrpfJ0*8y3Qy0;P|~a-#~^|E1QfC!PVfZ zVSmg66sd+At8o;?#w1JYNo$n=EHj7)Th`^|{JAr09i_N`>;@HrMq=+L3J{^q;4Kl)&GseNJV?2Tui{`%Ly)<5pQ|H1pO{`5yrUAzA5Gf%zvrO$u+Tfh7L z?|<*Z58iXGGCEcY06`g*SNYH0eBDEGEp<>vNY`M&3J|o5WN>>@2sn>bJi&mV@MO|$i#6JYZGYaI8&u^ zz%2n;%cDuT+n-cUgUT4{0Q$Ur>!ai2qjskQ0Nx`rJI8hHMOawE{%eo`5lIPX5EXnq zibNr55Y-rfLPY!tqnHT==2DM9Pdqv8$Q->3f&ATQesD2gVxHl}%%=`b|;~ale zHP)%`{|gEvT{t!2yvc`xX&jwDcQ#A1`#al5NBfiMcy)c_nWvxL**!cu?h9ZP84;}O z+OxB^4x5Y78a0MPIRRSs&bfIbvbiG~Lh`ACc<~yT<8PEwVHC*BQ53b?ZLM@8(}Wq~ z8N;>&48jlwAHj4gq!c13B*4H-kzcO;DT^ysmSsek7bE9ugE4@Fii#x!+5!s*Vz9D% zK+j^GpNz-j$#^o(Yv2{Me4)aq@phyV85XP~Jjp}6Wm8G5R)oFxMQ*3lJVXg8O=%nxVTkJrdW|qEaLzq=@ZdXt^_@Tei@&&e^Cpst z<1~t*z!yXIM&p-WeEvWF$N&87v(J)IZ@>LkRTW?S!sp^hKe&JIPyXcp{^1XQ_|b0r{O6%I5_z3cmL+v zl_#Eh^6K-?-+1r+w}1TOA8zm5bKVBRDwtSQI>`MSAKV|7$;FFXy|#%o5P}jC@r^l1 z$TwCA($H8?ovUkWopYq9+e(ztg5){S-9^MBgq~Jj*OtNzQkh7bcGilFGMWT@FyAOt zGlxcSfB++nrqy^-PR3PUyQ!5?F2|$ta4?)qCYsd2!SNe!zIpY^mDSbNy0*TFFjXMX z^lX{{J3tDUNI?Wb40KsI=@8NEH?klzkp-;MJmp3jWMJU^2P(VFj6w34WiXtg7SAn> zF<(SP^gN`Uh`jf>sNR}ua!&r;3?n(v5#iK%xiN2q(oe*BVYY&lAt}X#g3a?#+>pS2 z8wN6q&w?8a0*F#1pjm7PF`WsX9{ZFDW}dfGXZzE21~0yWr}fWpnx`~-*ZE{-G}n(m zZioAn!bKX`0n8k25B)`elSsYKynn-KRl6|S+FNS@gi&Vf0GK& znjp#y5wUpxe2T2@q1SloXU&G+k1L)Yy%!p>*uvy=LESh5tt>Bh<1E_SKe)TSJsJ_-q>0EC0(>YKhnb6_ zD9e(FTCJ8b=Hy8(E-l#b{DnX%QVO&RUSpYatq3TN%$xy_Kq5SAWZ~jYaFVhd{L;;- z5>Q-O=4l$E^4y%#!85Z!-~tBwQf+xOog5z@mu2a!O(MOrvD)kP5HU!ji9mrEqF7U; zb&{BNY|=;)EuBoYGH+gd^5VsFtIOSphzQHP%BQvSmJo>)Ath;Ij8;lDCP8Q-Hfc6q z7*EEpzWVB){^_57?|a`H4u{q`rBtic^1dF9`pj%=_wWDxAODyC@_%h@UD8^Q$D^$? z>kl5>f8*z`z4C+azxLXz{iEZsi7G`(M_{6MXL&t6vP#yG^+SB80Uk-b%DA7DR-ma#Hc|IY|W91lF5o0wS?LF{SEqSG^ zBqEZJYN0%z4)%8^dv{9ijr0ET(E~djYXJ0&%xRJ)i7BhHf4HyXs3@mJJ`rD)`E+kI zzIpS*?|=UX>+5STz4X${FaOTVzw~b+ zto2+~6|m2XaypsrZ11FLi%3DkW#D(!9X_00HO#W`;&!Cp5qAQK5JFj%d0uq8kEOT>*Cq1 z3t4x0aC|r!9t{t7tMLGA?bz?x+)w*l^oP4fD=5bUa`|#65pi`f%14#6HGv~^C;(h@ zWyeRm)nqcZr_3WQLP5YONz3 zMOqm1v<`rw1xZ@>NiKm5Z#e(6gueDj;%c`gWH^2G6ojZT^ z|NYK)c8?CDbT#dst4+^S$3bg4q5j8xC+hNMvXnuhC_-*b0*x0#X4$Q?DX{a-dA2U} zYP8aEmT9d508f!>QVYGe%yXYFA`?j{APAKJGUBwXr+GEWi@YpK568oLXRp6=aD3Ds zjK<}(s-1)oT0!_&E|Ib}~<+JT&kE^a`*!O=~4I5tc9zMF225qnRCkEA! zzu}ylY4MtCDLjhvK8!!$f7K}=E)=$)zADgd#KxFGZge9x zL0W`JS&%@|p0OgSv8rs1zp=)u8clhsJmvqz^I;@FlqGXiV~qnv3L+(wR3Z@w5=73O zUw6NL>Bf`x-fPW=eeQktH5v>eIR?6{IaDgz`>*_27|wc_r&DdBxqq&h;yo zZr@rD)7=g_n~EY~D4M~>Zaq>^gg`1B8qm6|3K0ns#5cr%Z9*^zfVw)=mBMJUy}3c} z0AZSSy4`%Gztr#Kp;2fG5*NI8P1976WtsDpAGq2%lh`!R6Y8Xfn^KCRtm`ItDa#s^ zkh5FclW#ot%6DFR>t`Q*^pQs{eCWc12an}>*1hn^&!@ek-+B4Pn>&-Fe;}BCgG(N| zfX0iycx88MoSr?=yXRoCWYD&QLcL@56+-Y5RM8M~ZiyI(kQiqH%MxUcW<@d*v1Mxv zV|3dD1?Q!%!nBx9Dz`NlPReRDDRu^f-N9sgP)&-uY(nF_4+_M9;9Us8kp@ud_WGc( zetq5AwBPG-%s8h#r`*{-3$4#KF4#T(Aj>k$#CdQRpM;rr)t&6A{lp4D;fqinBLfOnTp6P9ZLEQRnHQkupiBgdidkWWk&Cr(!$N?=^OtgF<@e zH*f*W+pDgAoI3&D9c2Lc9-c-&{9oDUs_|Y(qviIt0#XS+_(+3QiT6Zw+Fbmd5Q2oD zjQ?FQvEKLOyx)&6j{jpY)!g9wCtP6ZPhXMq0l*QFC`poohYmKCkV&h?6H%V$A|N7j zkEjLBwE|!}7$KZxX15Q6s4UuFHBDVKE*cQ7uC7J0@EjQ1zlz4Xtqo=-qNZuaB5U(KuDF~=XA|Nuxra{vHTFRsvYH-2T2!S+^I47Y}pC*~HoFrNFIkSi$S{223 zIF6+5H0>m5SIDYKwnp9-&_Ms?H*bCW#dpr!cj9M1{?W5%&mX_{eE-O?cdo8qxj7oR z1l1B)MHZ2%(v@95s&}S!@7$s8TFPe63N2b*#ItP;Sd7f4*hs`ZU$kj_2;N7{10W+B zn=u<86oS%)s%dtupH%>&oi1!jl zUe?gk((>`+$8T-i9*;)7P8S#!8kU7*gPA<-u4I@Wu+rLl==Lwm?=7%kAA%*YFxhJ< zf^9go8WS6)IB{f%j+lW60lWyR3g8_b&%&qEJE#~7gbY>H0K(j+XoxBhnrOp{EpHP) zh>N`-2Au`nEWT)ArqD`5@y>bSd*_2c7WiY&uq!UyDza}L5fhvFM+UCGKPz?yUj>NC z2%;`{=iJ^*I*v3JMxybN2qK2`r?tSElLj%&*@*}w@cn60F%5UlbrWd~gci}}AMa_| z*9HA#PWbmcV7>GEiu<~O_6?L;%xI6wC-C18(A$@nK!Dv&ZYYF64$&B+LDDph4MwCC z?y)B3cFG8B4aUM{wp22390gW&t*Tj?cJt2rEe`YHUE9QI+tM^mQe*gYoi52j7kK$>QQLRQnf1pjx>z4pSZZ(q1@;gkRP@e`+y-Fx=F&RX&A<-yL- zH{#mb525z7F>-ai(@fom&aU(e;+n3irbZieG(Jgv6}gR*JnTLcL(5CesFfQF206T^m>Fi8x8 z9y@+~IxTj#w^x>ydc8g(f=HV-Im2o1*nIDxGkxFHbul3>&hPel1KeS-@*bM(A`f*= zY>jg~0}K2rj*j-&_BS}&#J@+AeaBpXK^LW7zOL&%+aZ~oG{%Ss zy6Y;i;8djVcY*H80iRp2{kNe!&YX}Jsw>l~>RL3O0R^;X1Vq*!AE5O;Z!o>%z3({T zdjwT#JzR}3V#x;&+8SxbU@=uqlBBNd#kZPYEMrUz#)-C4P18igH4I^UB)l@e{|poh(grYbj;2q?x6J*%DaxiQ%PgzTE5Od77psO)xcx z3eLI7q?t~O(QsH+H2_#^yPf6e{!o-b)mv+fK~l|ZYVtH8GDwWb3^dCQm~Ezb`SRsI z`G5bzfBw(^dHu#Z(tN}MM7G=MJoeaQpZUyZ9)9@YllL5-7R4X`@gM)uAN}Fgt5@Sl zH?kULvzc~}Q&9nSU_g7zYxkW#ac|yV+a8W@?!I~E?AgR1sW%uz2&}b?AU*^y zXatcYgtDsA#CE&c)|T@jpux1$>n1U92-qt>8e-Xx?Bdh@Zk#& ze(2$2hnAO&y}Z78ZCFf85luy1AOWR84R36eg_mqmm5 ziiFk}V8T`q6{+zGpez0UiK9o>Z`|14yq%|sNz)i$jYzFy<~gh! z)kP3(O74Jvc5;rIF* z5u)sewRB&sovJD@FdJs`f!{)DR-MG6m<3QUgjiv<2u6G2q~%=%!07Q9n^Dr%_wL6H zsR00yh)6)^WH=fXWdQ(5!f9%Ioh(h52mu4A0Pc(YYh#}E`@H=RxO>HNYUarX&im*F zbcbDsh_s5N`6T7P2b%_+B@yX<$nuWa_g=#G{1eBjG``~5+7I{s*b19D^RG>${~(-l zYz3#@OYMCO`6R2>kO3k1K*)*joanY$t%53`ff!jt5Cw1^F!28D>I+&OfZmp;*{p=p}fxF}+t=Xsv*DHcKJX|r*|hCSR)hKw;`$SrqLo9AgaP4X=5cd{&H zL=aKu-0o;P9*xJ-N!^I3GFxkVaWyC!MfFHznXO?av5c0{GLR)h$T3n7X)y&`R9}Df zwa- zHpW=P#?)0UqJ##?h-e87ple*M+9oypnGy@*j!mJb_ZpnPDPc{AZAp_m5stV?@z8CTS+>y8|?=ly_jQ-1~3h(b(ofQ9VCbnsFH$VW0M4lqMe75fYwApv){#^ zz^*Q66wIWmFJHR;_FI=PURtkfN5sUTlkxfcPCfSXkFG3r08qh$?AfMa8;&XXBT!)G zlR@X4_dXKx6x8_;trqXVPFvr#XzaVsoZ+XNb)`T643J%`x6E8Vu2MifIk?|odVG1OV^)$?mJ#61UP&Co{xY0LYB}6c2&@sel2n# z2$6_X_7T|QsTNRGt?N33;Js^{kIsLcPS;v%jES5(?|r-|BKlq~LA*EWx-QGoImgU- zp7+v(jYXhEgcuZJ?a@A%5ssp^lLl16NUp;7qhKxCAj5*Cyogp+H5?92(m8wTo~+lm zNrI@Xo>2^lp^#^`mnX|h-KB1pSz{BMTV_O1aAlZGi=v!PCX=G76o`!>YXC`r9I$u^ zB3Z(Tv1HIN8p4DiB}fx81_GinXc${lh8fGox#p#pU;5nVe*f!V|5{a-(c09zkY@Qu zAN|;`|JtV?dho$(*RDSE%rl?(#3#$L_`(QPz==(hJWW&Q zLRr7TlJ3gwjjP3Is~8X5bWFj43W5*@C1E6HvW63D z6W;rpi3Oo)8qkm!MkG{K3AndsD?-#F1TP`hRm^OSZH03xOZeF$n|U22ZO;p_N6N~Z|@9?x~|GHhyWk~XKB{$c2-wc4<1-FfxE|Z=0DgKJqJO z=K=5bDewm=aatpPN{5s1?6a>w^YjZ_+Y{FabHZd9J;T(}=Fff1A{f=s)OzXidR2Qu zGKSBbxhKyNe;`F9!k$2P;eTp-#hvrcMfXAo0fKlhAq3ecSbZ=3Xh9xvw~zW$qbgOv z$<)90#+##YEfOChr8!`XH1nEcYm+ohmY4en4z8>$TQ>0-A=NN5>P0GcFeuh)w{Sh^7VIIrgxww1je zotQ~cMTwY648I33p5t5qbD`n_uLB4%1fQnqxie?-ZXc{|I|dCFq??(3o-O5hr`PFr z(j;l=TQLB2S~ZhlF&Ry(x^8>`L^M56bfO`MfG7&1BBF_|c!n$^gC-U;!`5PA$QV{; zB1IBxBL)!>8|R;W?z!Llz2E)j)87P@Zns<4H4@!-_S`T0;^RN}^N($9?R@_8pWnE3 z>$9Kz?74I2zwoDDc;bmCu3f)Dgx176=t?|3}Ebm>a)KFK?)hmPKR z|3lfzQIquuux{Mut;^HV?sTx}sxgEHK>(Bx*ceOL$@4T#EfFKIHAJK#5UQ$5wD>0q z0^Zf3X;6hkRg@5k2?=9Uifwv#P*n(mG0`^y|Hi0@q7bPe6ok-n=8W@A(>NcrE~b;o zs7Far7rq|XRW&VrsB7h-3fegWa1OL$ZCZCQs!f51u}_lyE&gyljsiUfS51 zUcIq9DViV&Qc^439J~7Jz#-pvH0>fK5aU<~h=LD6z>BZzrmC9pv>Z*R)3TXN>bmw# z%th0t_S^2*0sFUNxNBs+>&%d2rh*2q}tjYNl;gN z2(fQK2^zFn;Mx!q8K%UT)R19J2n<4&nA8F@MAi)vAR0tu##vX6Wm$dmo6kJ?0Dy=ZB7kcg_ieww%xtW^Q8^usCpT{1ydbV9CW!(gP9{6WXnS-0s-N6W!W2V| z8W5F?vCOIEZYNI?O9}+yLp$|$t~IHNoK#f}-h(P5T1EmU0x}do-yNh?Lxc!XBblbD zF-DO9h=~YPH4t$p%kwN7PbO7U8pEoj;#@UR2ca4{G3B`0xN)_A;PAnNYei9Z(rmfE zG?`YR@pVz`Y^CqMvz6a}w3DVAx3(OQSJu`Z=pMa!W3;ndl^z4I6TC5W<)s0@(wRfq z60=c{Alkw%S~sp~ymubd(`@#S8YI-AsU$SUV4hiHjEK4ry!Rpab}*-VX}B|K2#SIW z!clvN`(|l#Eq^RcthEOZ9U6{CgTWxn(j-mhY#dc>=Z*`d)nbvfml7z80akb6zrUZW zpUwnBDsl%-Cav>n`-Wb?Iaj-;4qikIwNA|nDiB12LSh=lt zhyYay5DASj#_$i@q3`$H!r8EKALBm4MItcsSdSAN`Jwh)ZP{xKoNaCUZ~X1MFTD8b z*49oF5KSte0*FXK6@WuKG$-&{RrTi1#>FeQva~pUV&&7n`l+Lb@;0}KA`b>*poKv6 z$)%_{L;wYmSy8O}po9go4^r%#z3Ol>dGY1fhea7c8Rfvi<@5L6b8sc|)v&6j4?cJ@ zNfbaCSpIYAIqK|qQj>!?bI@p&Qy0gg+cf&ezrrxrCuojbVdBKC=( z413tMA_YL08*(e|ll7qj`29N^F1pX}F9Pm9;EhkB003jzghq^jQN^GZgcEC`M=%Mf zpeR5Pt({KX*6z)BuiSd~%8gGv{MwTo2TGEwFw7%IlwmEON#YA?W|b~Vav;Ete%=(cdNkF@&fHG&hn^RU%yswTe59wQWhm)-aR_ z)LEXNJa`~Y(=<&J%Zb6na%$NSG$90)vZx1x-J)(Ljb6L8efaosMZ+4Pr3wQ8#^R5e z5Rr)(gf(CYiN%B|v6!$X%*GHiFp)qY+7s3QKwVdV^EZF>Z~yK8`NDT!tbOghUt3!{ zd+z?v{KjuQ_~7}s-g@h)KYQx6SKsXB-QWK0-~Q-FAN|4?|Mbbv{lUi8K*a!YlCY{% zsa3p$5Eo*oo59ZZD=)v~e5jj-3E7Z_=H1s`7#04W)At#|;qH!B1Mnkg#+IBhXn|1^ zQb-e%Ce|886(X{1ktm3S5F$y=xhaE2Ewv@K27?64Z78IodO%P>(;xV^?{Y{O5ZSq zrA{&(-6H5QBvo15+T70b}|6L99Uko9{%$mAsn!0gbYUiQ`&WkXcMFeZc%-SosKw+_A zqPfTGOp4KNS^Gd}jUqE8RU)?5G8bqD>2n1o&IElezfrhOmDuSdlM zEqY3!03pq+L{vpX47Iqkv}z~zq7VQ;5WULHTeq)XzbV2%(CekY{L8=i;S1-MGKEmq z)ilp@#2P@9ScwBz4_449B}ztGltmZL&mNgKb`=sW9^y|%r-gPjETZUr2yF~#BmzQ^ z7*B>FCW%M*24Uvfqey!qj#kWuD2R$65QnYQiXWpbRC`o2q8^F@VJrKZ@2K;-P40Fz zXWRX(w2Ni=4~3fQ`>6mh=4pYTdcc4Hpqy};qyWMw0Kh`3C_w~52+hux~GK?Y6(SHwJ!R-o0X5)=)bMfmYW9b6@89v|8>~$<0j5u&pFxO>oD3 zx%k5~o`EV7N*gO7pn~%^d5`P?gMb7SK@SWHq=oxmX_kMj7hmw$=o$Np+(a|2qE~$Zx?~4sV9?ST1>~|;c&Q1#!Rb< zm{!-8x+$z?XstnDL}{x^++&Z4NYgZk7%5_Lh96y{yIFet@PRbVtTmQxk|b$ntRV!c zs%kiz3@4Ma2_b-p3h`)Czx?*4NBS$>EKiV(21Q~*Za+|)ZilLjm|04#u?ABEh9R|_ zSi?lbN+u#$tz#+zR#o-%)6e|w@BZF*UihvevPljdKKg5){`LRqH~*#J*P;On}oszw??N%++1 z)qBi|H{ZJY?xpo32M-=Owsv19U%xfj-kEv_0(RPjx7T-(;M~d8zU4%bSQRxv0|?fT zfF_o+#KvbnhCLH86^%-WIhYCrKp0w-E;=8~{HF;3LATBVNW0f8kutfto1Xx*F z9gW6SRZS+7Jj)WBv_C-eWSc#JDt^&o$*9z#KlI*73(Ue87J}>OuEQA-3Bkp;jeIH> z>Up|z)B?nY#i%eFvyTO~U{@Ju;GlP8g6=tR?iUO$6fB4k)2?SZbUz6z^I7U4-i=-I z16FeL&qYD`^|vlQ`|USs2LV;U9XYu4-~*@5o;`J7buCL%1rR0Yd|6e4-NE|x>zlVW zHaEA6>Ez&Q?`J>q@KQG=sOBd#_H9wZ88541s+bA@Xb^P>2}e3k>jtE4_m2V)X3>SD zVpWr!onl&erBqeUoj?EJh4Wd@0Mv#tNqPVv;+Yb!Mj#DBL9GG{S^+||008I|94G;26CikzIn3ztU<-D2CX!<+c)`v^fGs0DVv*3b6tpig#eF zivZ=vV)hywiG^Q$>}SrNJxv-SGRd=wuqdXtx3<6i!W*|YrwZ1E@cLUZ^_d})goN9l4q>Tc6cK4w25S_1qly|qCWGQV z0nKOC`co1BFB1Kl6##euN*v}szhR-CI*T`@p;k)LUfLZ11x4vlBAWI&MsB_u_WPs zzhjNH#v(%9)PtR3GMS7gli)=W16oz|L7d323`K+EvN6UQwgDsIOoDIil#JoTnv{(t zFbs)7YrqgBhK*svJX4P$v~z7GBHy@geB&EWJo)5Hue|C+5b?}?_kH$X{x2W<*vBqk zy7cE?{_{&0-(@rpoPXfA|K-0td-m*?zw(veed5W%xIA>^=!xU^dar|>?cJT5AyV6= z%`+z4qaYvvGo^Xf?IbCMMC%^=V(W@;s^FWznrdYd>vJM8o8LsOuU)QBjdZFplzPmZ!>W+r3{=HTnVw6I&t$ z^`gOhSC(XLo+d=75}bETY7Mw@T$ht&4V}C{xPAS~#kU`N_`(AZJg~9;?sT}}>)~WP zTs?H^RNCu+y?A|)X8F-0*@>gaE?>QMe0O6oaEK|YJ9YBFul&;E_n$kFry)h+c9uh;7@&uA#JjV_ zXtKR^`^u%u-8?;e`bcUK(ExCaaF1C6v4jU8=V5nT-`d)`y}47Bg^DMHJj+&>Rt_CH zeCWV(ngCKji8Dzbe``3XFJ8G(2Xp!2P0&=;f@)RKE3e&1tR^rqP#rnAcKGmt>sPK- zQ>la5o%-p-OJL%(uHenrZ*1MnF;tz*ow(;fQ55Uf2Ox2Di}#*BvAo*>`?S6!_N z!dB1RcTcyIBh%*Q&b6ys&Igg=@X_U^rJf4jxUo4N)!s``kJKDJdNA)~is%H$7{#P4 zn(=5n9E_*aY4lbjM1y8|dFjxBmE*@&dp*k(W7AYsqMw!mG>u%jyk3+J0NKK+d(U>d zogjX&JGgm$eLNgoc=$s{jvP>FR7sJ8Dl#`7ivqWHhBwx4PA8Lyo{_O>njSrN^zgyu zUdJ%`Sso|cRa=1H$MRO+BgR6@a^~K{k34u1)e!|kunL5Vh)$(w?pa=5`pREEw>xYA zvloip+W-I{07*naRH~{sH*cT0=foWIMZ^#kG;;xllj*pqCS^696lGb=|4^rsudS`F ztt~HiiAiUCwS|L0!kB9%P*=3QGugPk?Y!4k^=&$dId=5GQaA5)J87CGDS^tO&4fnZ zVMJy-nv@%xgU!vI@wiYC1#zxfU0FSR@X*0S2l6~Ih7ba^>tC4nQvx7JLRg2eJ1n=h zcegipq-tW>Wh{5PonyyOc6)j4ESp@RBK#qAlphrDw1wmbB0{-Si?_&Xu-3+Ms?Bdk zGHg3}KDU4m!N;Ltbbnvuo)b}og=1A$*L7S%Rkf~aKtLiS)DRH#@S%g(udT1GuB{$8 zPzNs(=BYhCgjpR1v6#~tzc?PoTz(Xfnh+z0tl#f5o2v9X#iT5X$~Df%y(v|~09t$S zL7Wq(+6V$$AN5!y5s!{@d?K>eGNK`DjTj7BgVqo;8>ZHSnw6PiDsL2CHFfpuv(NtS z@BUxUJol}tZdCE3Kl9<={$GFR{DTkv)n9%6OJDpF67`o>51cslTmS5z-E+^WKmF4$ z{NI24$HU=hY31PZ@@ju+W&Qg4#_i3fDZTS5Gw>VdVL{47X_{DT`~BY1$`XfWw7FiD z)p$HEr{mz7Za3|BQp-Y!mcY46oHK0#w=z?ZfHPrNlBCnggaC}S!8vg*wKhvrYb+8H zg0WU?oX(38RK(yTA(uGP(}<$0cif0I#OjI+BWNHpma%jpxJn@qWtKTh5)FX>)jQWT zUUX;k7MoocK*1zhqnnn4+w7;lEXz>$msbTmuyv4JzA-Tg9Y4{l-GM8&ro*vsu5KSc zx_0EyQkL2)>${Vw224hcfAiXoCBE-yr^{?a5fuq-Vt@$Ai_EClBHnrL*?SX$Q3)Ct zL^alttSyDNB}qtJcJ};;Ra;e{w%p^HE8Wb_Kts%HW}>BjuPmljSq=s}X__R~1`+SQ zETC5Jr47velV+TBoC_)Dh0K1zUmLa&g)Gs^Zh_pTh-3^gGcW<}8R7`EJ}!cgB-YIO z>DK=$8elLZDRBEnb7MNf)`BIDh1x90MGjU=qeqBT8)Mr73+`r$_@h@x`XiTD0;ot$ z6GnpqyouwqdrlsC=)tr74xmhoI1&xBwnq^VOrBErVE@p8-UH|FbybyR8G_C}D9yzZ zDk#BhZ0@}F`dcr&^7f6bX;F&AbZ%8Ryt9zDX8RNn6n ziW@hsZSPLDcLuw=gSwHr4nYXfAgDpIM9WLr*|UcqzHsLL`|j;zOwtevDk(A|Po~9R z{mpkSUbzj5{pIAJ{^p_8mE_I0UVrtKmp0aKq4-W``QYILGeQyvfVy&TU%dA6%eUTn z_uB4Y6nuy&(`*bet*x${IKKMOg+uqBKfTiHG6*8zzR&}idx$IWV(~S@Hd!Dy0m#*I`O2m5yzuf{@7^9yT-^jv zRFEJc%d>tbKYQlX{STab=;1Tn+!*i??*fhFJyayGG#E`^e(klFUwL=^#;`0LxDZ7Q zNNN*v@X*0C_ubbB1;{iGia$7&(+|uF#d-e?j0m`p9=5mc&dhj==~MxXF?pUR#?s7- zLB%7Yp*Z`PzeDRcDP;TRhfv1tTF8jgU}H7d&|yCnj|waR^0Dnz^+8$ zc2J3XMbN;8?;!s!?m#-Lmfib&&wsFESo7621ORS6*g zs5O?6z;Fm*ZUAGLTF(anB@DqMQl6v`f)CC&wFC!1mY~5Y+l@AI66dMgxM8!PoFdNk{Q#u0y1pq}9#j2sV-@5wMul>#STbpHN9auyYBp@1* z5P<7o-@dkcY5n$VZ@u~GM=yN*(GRWm6VeEoau5n&i>mR8%sGPbzHVIUyhjw2T8$vZ z0?|#T(|{tZA#i)1h{~p7@Tdiv#AbN3zjEr{rI%j0-njm_axcDm>AnZguP*m4eB>i9 zzIJsqu1970;wzVqoH#!oxmRAlwmY7J(gUZCuN_)L8#cDLuHM)hP6H8G3&&5MPV%mx zBI{tZ`^($EkAJ z=xBlfHW0t^+V#!N7cO1A;+qB(QT*kr*B*H2OuwHAU=Y7MDxZG#rRQIGb9*}kAyf-$ zRREAfU60CJ+6Bf8>1LA%r&Vk%$3cGO51(!dtJrdTlgP z=S4uh`e^M9PD%&U5_X5E3dp1&7>9ahbF=u)^KZTQ(mS`e2d*KJ z4k9Bl0sw1K%e0cs;rbgFx8A*SNl!_ot=Nx_~2trdZ$ zssJeh=Ab%@ltERcJ<1D2N3{9m@x8-M(zeGJA4bzjMb zVd|ttTmwNJiUJxEQVpOX2pfz;K&D7$XA{i^3|q_X#)R4?QHv_Tn{U4P#1l_^?XSM> zAppUH_uv0Jzw^JHJ$vTg{ox<|$$$KhlcHEzUj5W3Kl#Z|eTs-b_wWAb&!2i~I2u6^ zg~|(*#bh+xA(qtxt7LFzxZ@iDC5{uwJ?D2a#w1CC0982^(cpbkPEe}U!0J-JpCuA} zO#SlSAt)mOi1SV391#+=X8mPRFjBYEF+_D;qpCF~v6isq__HCyMk1#QG=x%vFdJlw zm8O9D5EMd^q)CzxA`?01RK#*?q6P{HfdDuO0-z{~O_F}MD2uWzNrA2DcJo6A*PNFS z{QA{PH?LjV9c)WoFj@;;3^l4#aR}fMx5o1N<-wU#D<@AaIVpz&avrYV+EHFQajbve znYD{oHYT-rO?FCrYkgvkJ+W+s`-1*v9pZ&;39_Z$l#FJ|6T-7wY!%NtPMtcLn%rqRsrBO3 z?Q-lze45~c_ubp=1lHo%(QdZ`Nn$?o4<5OAWw5zJLHOOPw=Q2>Us*eM&zXDA-hcM_ z=idlEfAzKX3y(}TZf&jKng~#qrT0B}zPsG3UGwg{m&cP@ft`0J?>Tbp#3>*nS`ov6 zwUxt%R)^#3sYy&?(j?8(4s(KtK|)#8)1q=t>Yy7t)4%%LZ{<0hzyFvQ4*-ak*tp;o zNYJR-qJ(cg^I}mh(KlXt*=_>u)^!cTc}s)D$FP(0*o?I=v*z z*_Z&jwY@u;7G7~Mk!Qa3R#~}U`X3)Zd2|KE1A0&vAl3LZaZV(X!}dOqbH8kp|DUHL_mv({eJK8 z;e#8y*AXQ%YAmH`nk2b3OCr7~igN1eIymQd2jTe_Uhl7T?|UPB7txTv3g?uBoD^NqR& zBtj$T{qk}z&$Bd3T#(^#JT2?S>*ntC>2Gb7_3&5!$TYOOUTVoM#5 z<(f?rW)4vwUKi8h23DhUCyyOj=|%`eRjHLg+y%S3V=5rCelgA%V<{E2))EErgrqEHN`Pk-h&Zrr%}mw)-ymtK0U zj)hpL0mM=^84ilc#0A;4rmAZs_M+-FAf$=OvJ6yIl_;8~vvaPgD~QQO;!{hVEMMw( z2_VD-F!3S8gbb=${<#>#XpD-CM#niL8Al5JiBXA+pd!NF?~WNi7p7 zAtrfhjRB;fQo9CKx}6LGRfQ2aO$$~w(B&m-wzL6|tlgJy|sZMA}P zX1mAQ=3jQAPb!QSUQ0$_2#Xui&t+nfrJbj zJ$vr-(sH8MD0l!^TFOqJUQwBxIDXIa+G^hELlyZwGwmFrqxeCeI% zo_~83ijoLX6bTRnP$;0P zfSM~St8&h~(;4<&%OCc+H?shcA}umP83+UdReAH|z31$`_FC`zysy9c?#_OxVy<4h z-_76ox4-qpPHv)I{qd8XYwz4B3NK_p31Z|ZM(kNsdSjmDSDrgDKW`Q4qwQ7&sy%%F zA8-8V^_v<>Xgc@f;7$-E3IHLH1VQj;&K;kc?HD_vAP}O~#AR7_^3=-6``MY9nfbX^ zC(rZTIvbzIUa!CLc<0?~AFQu$hJXhL<$LelK6YZY-F5&zY8U$b{*4NjxEB8%IXM!C$6X=p2-j?s?H?@CT`F! zW25+Z{xFF_qKSu_n3E(SqN=L4_xJk!o=BZ?SY2A0o}RYWqE=0YTBO<>8D)Mfh*lMX z1n*S<>RMHph)5?_K*S&+BDa(jh}1AjRg*$IN?T%wV3-ZFHO3la4YEOu>Jtz~a)u34 zln_RN84+!4ZvOHA^T%KR#y1ATA_Sf4w15Bie*X)f|H60v`a56y`q%q|;d9Sk`JeyS z|K+7med@8~(HrtZAx0(9~2aK3x*;Ka! z5=1-^TI&EX__`_z1hKK;B4e#V)i4QQZnV?E2QkbI(;rc#DuWCL{WP(mEGr_kHgzt^ z^B8o2q9FtyymdBB6JL8@Ro*a)MFkabO_&v0c8CfRP{mj)K|wteJ8P`P#JJqqs;Y{r z9F&iV^+v~K<(n5Pw`1|Ws2`FNp?AO_&erl#>a(18upb#uD zDn?0V@DjWYPJAs9Y~zDOs)#CtvZChD7fserNzupiwL|x@$j5+^ajZ&m)?``Y>$0wj zVmL@Fv*C%z_OLjMW;;<)iQM!c3&!jF` z5<>NevM_)7)WVf>EC20Ve|PP@$ECnvSYEyQ{&QC@FV1&CDDJ& zqXd;=VlDuvXH+o)mRgkdgL9y@jHL=SvL0AsfDHG#qWLZjkSlnfcEbFt?jLTx7$@MMFK#m z>QIMRn}SN6C3x||iBEm{*>h)(ce~D_l8OMS!sh0|Pu_UH-)GR24ZZa2nP30X%O_Vl zsZ#~=q5`zCyn5#B!qV#OxBmJE8ymfi z#9)-k#!3S1JX<|JKR=%$ghM}v#u^H|K&S$WG)JojK-~0b5rHD6O6y0D9zJ}~I)7#X z(EtdjiD1Z!m!3Is=A3iRr6y7=Bo4n3r)QGomBr%_3U)S{Z z)qBreIMp^x$>hQ z-TcWL59$hk<|3d^1xNgJJl=t}Oc9BGz@wF-VFN^jY^(`Bgu0&00*?ZHB83u>#;bfY&yIe;wY4=M1jBir zwep#kgSl2S%$e*_IMy3}RD%^mJsM-Ls7g#7fY?@G8n>7Z*ZF9>B2fSYYpt(qL!2az zP%VffOq?}_oiR)ZsKNUh0)qjzX<`i{H;E~YeXG~&fBW0t`NlW??BHM!1@|w#_|jK? z<16>?-TT9@esyPO_mwYv@qhY{|8Zt+=D+;WAAk36UhPgVb-Hs0Bg<(~)HSeZC^;VE zi2$&wrPay0Q}YVeaEieviH#kFJntIA-utQ?Rb^R~1)*k%i*zdpz8DR}2T(QKcxi(V z+7S805P3wAPy-kQXP7}SRKP&Mi6vtUA(BE>RcMkt&z*B+Rr#t4KE&PDdo@Ugji^{= z>oO*cozs|e3?hV(5D_vHCC;X`GlZj}sso66Rii+yEb9*o31T@VlTq5@boyYZgNkY~ ziBSa4E^T+Glf>24sIEsO6+sGU0uX`Q+^a*_f97oW!kM`{cc1L-i+H|wZBO)C2?7OXFhbUH;>^TyM+6YGtZOf!s!dhb2r5#k)WLfn zp!N|naMa5mpL{t=U4J?>QxU+BL>+3DCdH7ex-N@hmAaI&$xJW?1jh!IjMH$c;3WXy zp_D2%sG{M+IdeqLgn-Cwh&Y~SB8c}xD+F^ifU6~n!@l^v&bd)hgb;|45zWzgr$G{J zXnYEYNUW@59^Lr(H5n03QVMb6W{m4d++d6~lXDx672v;wf(UTTkpJhs%tT$M0koQ% z?R@1cUjTdU&8zSA2bC%}9k<5o5cQ*q7#rk)AOv5l)tcK zcrZ8fJfTCZ2?&5hs>Z30f>2Y0xZ)V**a$EMz>|6+Ayh!o;G^cCIlZclQ4QzMpFVf? z{k^wtgTmI%=$&gfS5}s0r>8GpzHsw{$3DpR?iPU|#@X4{nX@OXas9#mojdDwX;jfU zf9c}M`T1$YiVy)vL=jDz*b;Pir`PNE`~6W})v9D|nq*npPV;taYHIQHsk56;uGO{l zhqAG`d*XDLVjVIDu*K4xjXeA8`7eI{#g*l5w`EX0O4RUD2=w6I!$<48A_-8EB<{-P z7rWh=vMfS13IKH@86-hIb^6qWi|aePZ;20kz21%YKX~T+XV`J z^5+&77V0uU2#PgCIU5;-?8NB{=P&I)+Ib^X_++!V`Tp9O(FJYW^VU^py_Vs>`6)o!=C9cDrVt2H-*t0U6bkMLWMGzG_0R3(RaId}j7 zAOJ~3K~z<0ZYpFX0AOUR8YYOum`w|aUgFA*&beYVu*_MKB8X8>sv@B-YhP(%O`4b_ zHCbXaXEJBU439DS2&u09_y6G^|KJb4`smSP0Ax0;R_nKa`*-K(m;URY|Ha+A5C6M= z|KI=H-}#;4X!L*nAOF`szWzFLl6P0~&fKzFG-+pVx4XZ&Ui5a^V(P4Q)+;JGAXn95 zU8^&NzAU^i2BTu8)1IE1A;RsQ&AKYRubI&rlO+iuN~lp(YCkDFMIprBUL>dzkpfBx zaT=3YlR2AMlO@(!c8mss1&UIBLu!*WZ?&CEy!XEJRp~tk3Ce~X8)G>L5UL@<)CG|c z1OTnE#+cMO0x*o$n&^8XXjwA-(J&}@P;Ka0*(j9OrCDbt?ao$^Ztv_;Hk)8@CP=x5 zHVTEoaZIY%wgxEqJr+h{kRfyKVI9QKgju@Tek5pF^NA2WiHGC78#HAnl zd=Eh?KuQqJqz)T-NqmOb7$mCdn$Q}{=4h!%F=R0MLx>S4iM1%A+U(mC`(7Lrjxl1Q zhv}yxY{)q#Qbmm@9{q6S$ES26-Yp(YJTN)S|oKn$TK0#dcAb*!}&AkqLyJ*p5iy+)8Q zJDq&urL#A0-#O^jwbvWhZ-4reFC1H5ID7W=()`tXYulg-$b{ka+4-s2TtsiZzwzi% zKgZo=|?yWz3u+bZob*+udC>HjNNt$-Lo!Wb#KpKM3 zm(;NuG*FeoW$P}n}$55cHv0NvQys>LV7pgJ=%{hR;#6(7a{xnsubI8j3pf;DDt zE+r9VI+}3;qSnHfzVQ5WmoFFytaXrDb&`n$Dq(YThl#Q87|DVoa<^UF~}vdQEKvo;1``0SHg!Xz4EiXuyf^^N`RULB8rkKtwa< z)4-ulw4vUpDyhUG>`0yQ;en;bUq>|R9EeC1f(nBgjO`L5L7Yh#Nkb5jsxFTpp(Sz7 z8B0WUU5f~6W2u1g0!k>P0xAp&!6Ok8F_9uptZz{x!irv@^40cU@5$DV)*cDFQ=M+N zYpsn#7Dv`lU{prnSh|gI%ugqW93}Lk0*NvpC&rc@gJ29_jIc}92(1<`>U~xF5EVvX zsMG0KW8!$Uu1fSZs!tPcWm%`4<%x9`4UK8|Dg;2p&A9|n0dKy4>kt0$58rs}Em4ei zuvcFG>?>dX^;>uE-u&RsfBH}V+l33yeD8aI_w}!TtzQ_90MPVQXR6)V-`yPcMlN&4^8VgVS&Tr{5)o)( ztu+iPQQv_O$Cq)WLh&YZY{*hk6kddxGv{2)dj>I}&LytZLco51u-ESmin3Q$ zAvW5xwo(R3dw%IeYj$O0w-1TVOlPQ}81ABR0dc<{DDyQBN8Fpv=F-fo24qsj02IKj z?biKK@9b*(?3rceC!71#u#$t_(cDsNZi*h4p%x8b_DZ<9HZW{XEha4jrbbP{OvaEi zCUDRs2|-MS#uB4iMkcgORZQ>zB@K<>D9CsKc1Y;OBXvwOTWefUiik~g9{{MjEUkhs z216YVyaYs=cmOR&B^)OvHP(`0V+>n|=CD&W`FAtLKU&*0EvI-Fj7@q+!9Ix0lq5+} zRZb(FY5XFFP2vWlVV*c5G9Q*bj<**8z!;JzpiF`=F-(p+`70Ms6{S>F@S+N6j7^fnCe}LQ zCbd$7%5yKATlj~o-~IcmMWF$(Ka%a8UKNB9d>!iA10_f_JKvd^&KZS8`S1;HHU$PW zOj#>KHo;>pVK}OS21P;*<0!bXtv$|nP*8zD1SERi4|k2Rk1h84^(pRAd=by2r%$b% zT%Eagold)T`SOKF8++(km8ZJ-*|W!ufqs8@_wM?r0Ki}@oIP`V zdb$njQKN;Fsxn-^aqA~PxwXAth7if3hLB)ftU!ROu6lzl0Erw*iLF0H5u(XOq5=q^ z5)z{lc=fd+p^1iXYN(Z}q9kY)xbkxU;TDSklyRRPAJsXA6bXhnK@z0>gPs?!NJy}< zvbemm2zVs#3dVQ!_@<&L7MeJZnp{Ld6+?Rb*vy4R>g)3K{eY}6IKdJ$!s;ja>lp`>4G=edIjc(oFUw{0XRD&=7t50=0 zR*`~`fK@ceSO>jx{}E_F4TL^+L=|{^^P!?a;>hOi56jAH5b!}NuK|n#B+RYMG6sa2 zCVHDD4?ZSM2q>`0s>%XX`YUT+#hHK)p{i?9!Lf6V@UV%_q(pQCt@5*6%M9dLMAHF49Z|QSby>)O;cx0Cr$G-%M!~NR6<<^7PN^;txc_AL&Rzf#f3ou zpKR{_zkl-eSHJfIYto?NLrBx)(=Wfgyt1;jz4IUbhyO86v;X$Zzxd`i|8j4?H#Ixc zotieuU}14-_1Lk6m9xWPdH;Sk==Xawv$=!0*(m@RjEcd=#;7<*Tb-$?S<4*iq9|%Y zu!hTWRF#D@L?(qA%W`Cy7(oRH4N{25Lc=JLeMF>4jL}hsmWcrjbCx7o>RQewiDlN* za%!DnMnF=qM8qadvrfC6W_eZlZmT^U4ndUB_}V)*Xov)Z_^1xH7!gDq znS?oYrj_T$nA|1pR=(Ts%kJ*55>(04JZa~Z$>x`iPc5Ao@>Xp-)6>&cRXkZ|3aL#f z*u26PQyQv}dU42cPA{afZHb!nDt~wV;Ow!^>ahi(o!-G{celT|)LNctZ*TQ#Q6U3B z{mMVu>d&-o+9qQx22}9IaGJQrZVGB@ww9BGjb+2+43~tK$pF@I){S)o+SSm|Mw=E7 zP7vxJ<}4g}z{hzt4KB<3Fc=K2F-e+6Nn*t08e<$M(PR9NQ8&HsJgVMK(teH&{?ZP$5IBWm+vYoDoG}hXfyjmS7sVJt!jZ;$ruu zm!5m$>YXR$zN!Lp6$BKJ0EyUG@aQFsis5iH!WkFs+zn}Be4LJ8mAb5AG@TC+Ai6XT z0o-wGI8p~U(E|9PST>9!Eoth5r(n}#M7Mf@dTu&@>4j$=KHNSSVp-K!-+J%DxihU+ zXK8scNvscwpsjY+?o5f``<^QawH0K7D32O<6+~?-5nr+}M5d&G)x&2T($k~lPeefoAyk13*s%i_o2(%w zTLlIp!E zh#yB3!xcguYOhkq`K;h!3W6a!KifWY=GfJnYh@V#VK^EUWeLz#b>`6S@wEGf9T6nL(Fkd3_;zy}kXB4-|)9 z#F1Qx%#38}+LxsmN_^qpe*5P6bH^_|a{^GwM5jF|fMIH9EeR!K04M;2V(KFx#>lY- zwk#-`ni0y-QcFRARB7yxM%B3L9XU@l(Ep`IDl)*i8WbbQfCcETRs?TkfN)L2ZQ0a zzV+>IeB;l&7h|j;M5MX7>F1t%uG4KlbLrCe|NbBT@c;hmlP4SJ&tKTv-ye=fhRw|M zG^1>9tmW$>1)F4Mb~(w~v$He493AX!rDUx! zRXJi(Bx2OsD@Z_5@WC=8aZD^HLPHn;gc*>UbXX!rWkN=9*0i&%l_h!VoFU7YIBS?i zgaBQVw6ol%iB0lWmf18x;v`8D=L&0_H3&c)Nop8;JP)e`PoQac zh!SIxj_po&x---4?8C=fh4nb=r^qD0ra9DNOiu!@v|qrjhx@Bb?Um*E%nkbogR)=Eb+XL%tDwLv3IWXipj_MR zshKDz8+VK()eR%Yg3FS~Fe#oT7acLE) z5=}>q#ynvcU6FASn2hq7jWMyOK_Qeh+=6~n#Vkzsr9?)rXj1VBh~_VlrZ`5A^F(4Yn-@Y=)8{e2HQi%_o~YklTZ zmzEdjoHGo<2*?-^hE=t0HA5>*1 zib_zNvzbfVopyI>8UPi0$>f)u(_xnYcIlUA$sYhU{O%1RdM zA+tvi0z~CzK?D_y{YCGzYNgz1dDJSgJU81x+(MwL4)^ch8@#aG%^Nn|p<+@fAP8_! zMXKrWw!~k4fpw^AjjY0`AZ>EVapLS_1W-c+KX+bbe5Q^Fw5?!$+28ZhSY|^hK+x^4^Oy;$JofkSJ&|7#tk*vMgVkpYOC< z#&X=g3{gsyu}~vGL;N@i+RqlBHNbaklridMs=BJH%GXs{`>G062%>7OYqhdgyM+iv zF)Yi{Im?7DOIn$0Im{R>2}lr+WGoXi#o|&GF$8_%jW@sg)j!hP?y<#^Ak(5CQ=jW&~i2mMk(v z)-WM>Kx74q5EmdKLrAF3aGs^p-A*e_(!?01G(g)oR++S(lyLWOt| z8T5LlQ_UYcp3E#Mx#6hDX6LjX=83V^*d$3?9d?{1lU)A+`Z+TXh z7u#uKBuF>Q7N**xdZZX)^PtwSu{UbB6E~kCf?)&&CbWjs84(+5=j%|FRpMNdCS_U0 zcwS~=Ch(22DZn`Rw(-hA5Cy>_D}The)!wdw-6BsGpIPg^^^AHVU={=tYaA@H*^Zeej6 zFa#gEQ>~Myme&sMlA6(|e(m))&z|fq%yxhcj)ABMBw&Wa`t7Ult#9u6Kqz5)rhV+# zvNb#oxeEyVGto6oRRutx%E$-|5DW8YcY8XvHl`4P+ShCh0PgpOckiyL!o3IUqJ#+DcKh7fbFDN%85*V#Jb+drd%ZybgTzd5=Jctv zXHQtFRSJXNASyFh&f1A_Cd(6I@<9QA zC2ImfsZc9;Ah9+_XuCu=Hg{qJD5?+gb?7`joZ&Zd+hQvC!H~2BEJV#v;lZ`zjyD!Mp>1p z2$7*r_{*)XqOo^UUB$IH=$JC2LPzwbKB!^WfAicDmy{`UObGNInT zdwY9#U%=#3Gc$9Gv&+ZNT)4clvU2xm_+^Ds4mtw2eU0_GGc53CDi~Z2T|`sTGgdBX=01Q8EcI(hP^Yk z^1(0|!kPd=v(8HdmV{7OwbYYSl8igPWSqDL70oo#aM- zh~$nxw@s;uR$G6x|LUvP);HkscJJohx2LAApFO*J=Jc`oxtY9`xAP1Q$5V`I@V-7c z=-<7!{`R#yx9&bsG3*>kcr~ z^qG^+C4j=J-iOEQTi4#Z{e#!vuSSA^jP<3qs0bJmQ(wM#;>|Z7eDL6j$M)@eTLIr*-`ou1Vdc?x3@>zTlcTuxc|WiYjribpLKHNi5K|epS-oU{`lnSv-69~tvt(fXRUD- z4XZ$?M8xCW`%j*14+4;&W>&jXZ6pBo3v*M?zp(oKf4t_s9aZ|HAHO;5ufO#C#bd`7 z+U+z=8NmZc5E+h!`}_UP&5cv5E5{Z(ptUui;0@W+Cy$*!ws7)Cds%t+SjqW_ydHb#F@4kO41RxA__*ws~P@12!t~xB3Cb6u|T{FQ=MW_xP z>X`%uF(`$Yg&8yZ@Tk=D!xhOmRRhPd8;2|jRZ*0HLCFZJ0*|>jO~AHlh~hXTCBV3y zH&fLn)Ep)%EAM?(RpVWuC6dIwr(mYNhZ6%`>>4YdRa8pW?V zSt;P@Blt((Pw)Nq_V(Ve90sj{e27O8G%jhJh-{2?##v*nDjLJ0!Pm95wi*?o968eI zPBt^uo^GYNqjr*5LSumAh_JCn>S!?h>+gK`Z~yjt)*4a2usCO}eetE|U-?&GzI^$L z_x{f9+jUi!Wfel`^$#%G&|-|RuQ*gGjPp%^)Jr)mM_ToILtksF+g@5aHnVuFJGaEH z1)R9F)o!&zzo*{&s;bK}an7+jD0)atQT#*%3JjP!n>y?3N>lFMY6O*Ph0WbzS(Imv&2(~;rkI(!@>+vIKtS?p_6B}! zYm_YK&JjpJtcidboaNdYYpqLMQcIRfRa8}42QMLrtz%}ZsINj@RCQgHWnI@HNbn(A zXd5<_Yp7Hq$W%K|TOBqg4*ZECiH#;LC1WjFQ`8kSnVvB$^pIlL_zB1RBRt)Ro^-IZ zsWgu)LU9y#D=L8sgvL|)#snTl%`gtBod2y?##+3UbygsAHG|Td==ovt&MvRzkTY| z>h#>4G0X@D2fYUmo@{LGdqFk^P%oc5`I*nY(8?L1Y$Vn2^Jv$ahlLavqc4)0n*C$m z?f5rQL6#S1pS^Vc-ovc`t~Zc(uip=WL^#cI5%xj0cZ>als`e&`pPTDkym&rK3`)s5 z)_^mx!MVj*{$M?LQl%R=9}Igt%M0B+O$ikM`osSA&hEy}{;*V)95f?{@!4anq-t!C z9PMC@)wDq*!hT{Bh=_)6+kO7CFK+D&Zrs@xuw`N1xw?Mm_QuNc^vd!=l5n&e7G>4j zKiJyX8XWBZ+Lu4|%D?(l=A42@cq*9c7wM72v>Z^Ns)qIH8R`H4AOJ~3K~(R4_l?(n z@D6Gfw~eu)KhlY$*DHrbt!e=sfOc|o=JaabvH;#NtsY;^uHD)n)*5(oYx}Ri^ZgSi zmS?7>gL(xR^oI}EH@3I?WreB+sL8@T-1rql<-x-T?_7QF@z%lnw>M{J=VxZ7XJ@Co zovyVes*6zc=yJ& z56+xko|~I)cUloXF&qrGw>G!7cZ*{5<sY3t#xmi(A{TZte$w z^zK^!$&(*ly?SeLaXQP5F=jC6KiSxMvQ_qaquK{#8fzGT$?dCg;=SsT%vaSz46=@O zPbf8R2_H_n_;C8jQ(i)x6r-cj$a@7c z-b>|!Dq6#aIY|@CCIT0|_+D?nC@K|i2B5DJKl#aW30{L&4Ncz#Q~^UB_V@dUR>7j-?$q4W^kUZTwz@M}XDaJVC0Xu+j`~BaM`2Wg zXe-Ohq9}_p&$F?j4h@qfY$eWFQ$x^T7&Wo3mE~EQ7(Fd=Pq&45MnJ`XN+Ma6hUUnvMfnc#U|BzH~`f^2+SNp@V;WA)VahZ(f?$vX|-}B zbj~?rK@|xJl|YFaYbbHnXGsWB zm387cOOv9ktJ;@!4XECiWm%3!z5Z}mR#jcsfEXd_OyrDp#>AS*8iRVWpI~)a~jOT4Y2p_g8H?1!P zby@1SeF(y)83x8X$&gE1d2cZIrwXjYCiBPel@U=u@FNfHQDpGH=&xqTs%Op~`{FD9 z&3D$ewu?%Y(0Gqta8!ofULT<^hdxb=1ptVGV(Ku@@WT1kU;DMst*lI`Rxt~VP^Y`@ z*IxN#!tf72cxyP45OA*#`|mvjexwMYk&7UzGJ(PR*$bzB{Yx*OSe-Uln;1Daj-qU| zc!HB5@yAUGo82Sk#YT<1{uG8HB7$II+?8ieymj@xdyj|SV+bsQsmq^z_Tui&!JYe$ z6rieov@RS!zOc011{@(&(NP+MDB0-o35I2l(!#2_L;w9!yk!B;1a&;RCcz8t>$+KpQqA}tZ_^<;N% z^ZNUn3L$7fLI!0KOGrVkzjx=w7oW=)rT`Sx|1*;W6i~$O?}y$&0TQs$4B#X}s&Uv- zDjHC$PM*B{>5G>yo=8mKpo(y8W%<%GXWzblx2Qu|!Laa8cJ3NtY2F7^Ai{)DwF!9; zgg_)Q(g6TPd;5Kaw5sfrC&P`65$ML4INW5c*L5929cO~4j?aGf^DlI}Rlf0o8H|{G^2;N}p2leF*b1 zQ7Ym`1&qH8AtxTyJL&jl28BtpD)I}dX)rg{Oyzx5`3SWh6ApRObu-RcHhGpsse9r~ zJV-}uIw2wm1dk%Y*CIiJ7x6I`nvJCo|9+EPUHM3XB?>eNNUX~8z>hqdG;5_Cn$~6Mt7@u~ITQol02w07#0;^0MHCa;01=-&-uSP7 z_GjH2+ zLn5#?MxX!_riNS2cJs^-dW)$cUsZXUwOcJVY?<;rnVxEOS_z{@Bay1q-q&>vpzTh( zmFGwpLNLZyXCk3+qMmiuwz4b+iGm8F5@B6ealvE6BysIlp69vxAQJK{&GM|S>paVh z;kv3+6;Vk9LS@m+O?BF-sYiZsW_GuN1gbjrPcg|9bu2UA(sq-3K7K+z}}L(Z{t#u;{o zor{t-5D9f%Rb^3Cg@j;;C~=9i);eMr>l?>Sz8(=d=bHS3C{-i_W38kO_SxBYXHU#8o_hYp-mQBN-v8jv!?o>x zU%bZ<#QOli$OJ&zl&FkIg!Rm9dhy(`OP7wFI=#9yKgAqCLsJO@5%{Iq{3~Dj)Y4q* z>a|;U?(OaM>)?SS6)gT02##@Oar(-|^Pl>}v&WaG5?d2^P~RvO6ewnZd0{ra z2S7x2ZaRPF;&PsO)GD%Lql^YH5aH}}`x7r*cKG1Vy(b65;1vb14vn}4l>xNX%8sur z8#Z_EJ*dl4ylAMfsR*MvRa8WMC7=)xAVdW*AV?5Tp*do!c#lE-nRBcEuKlHV-o5kA zyZ6@~9h8-#k^~JJghWF#K0tx#jHWxeuL`1WBl-HpeGsHz5J*644+vmLQB-3#po}+I znly?Pl+d?wIC*mUxhogXT{t<_B?BWs4#@K}ozH#tlg8!mymx*enz3q*y{;;T3#yX@Rs)#7WXjl`Aopy5h z%9&5TbmipnE?|M+Jb!BO_x{~)UBCJ8op)}oukV$k8pQx5fEYsLk~4w;NS@d{ z&5BV0+Qvu>K_&IA1V8`jXWQ-RAOGa~oqLbVB1k}G666NafzWNICyy-%#jw zfC$Pj%~?F@VEq&%`$r+eKfgp_Y?ao3LTYdba+|0=#s9qp7_NdIwciwDK%TY^RgX+Kx5s3|mGbWMeFoMInaTm#iT%XbBU8 z36rx;Dr3_EKqg{e``2H8<8S}=d%pIfvb41L`@jDmu3WzSr(gg2xBu!p%gf7Io_+Aa z`?qg@u)Vzg)$DhTLoB8IC;WD#573{Be`UODy5`AaX@v;|}~w>H-vKPeuqcV`!- zJ1v$V<**#~>$*;ujB%}2J{S&1qmhYjevVN^HcxCfPiI;!OC+JLt3rY#)>>-;AWLkg z(`scYsR9H%By0yzO_HS5%9%-35y&ucOpI7F5lA2a!(=TvYn&x(fLRH_61B4oRI)U!a_>cJA4WwPKwaJfMaEbbMGF9# zW<&_1vShZztb}p@ZRA-|1IdIyX_6UZ%d%!-YaNn_Jh>>MIW#fCgxE_*lSZ*=A)zA4 zVWEYDq=cydAA4{9EJ=3V_nqzD%&e-ncE8?dFe`uoAd=W9nxaHeBw>oSNLk^q^@Ac5 zc7*wZ|0{(oTM?8gi42G#QYHsMk)Q~Z5D0+SX9hDp(=)xiy_U>-&pH0#W>(dEz0C>& zFgpSfGlSRlswy+@J@=gN_w%(Pms-01%Far}O*2ZVBO+m5Yr*(vJi)vB^6nQk^anQ8 zmjiw?qu!?jOB{>8Pm%ZU2N&K6`X$*+C!_f6)0dxm`toN!{n5L3kKcN8|KQ;C`0)7d zoja*h12EvC%dP5qXM20^!q!ty?LBe*(q!z!hEO73$}2H7b6CZy5neV-P z_m%Izaj<`UbaK+>Y>eYcv$eHx?eeAPo_p&0wabw~pkv4g+B2&PUjX3p#ht(N=@$|( z+R5b$TReam?*C9h_;0=N?B3q7xo(WP5rQ@Jz?vTl5#4OjH2ld=K0E8u@k!_C+4Gan z+}PQMNwsfL*{ zvnEtZ0K~L8o?P7Bx%$M7E0-@H9^9MMT~5XrFYE=O{x(GbCb)k6;^t%rQDU%-aYblD zV*u2wciey>fEj@8vX7Un2Xv@u;hEWp{@9yqgy|#Dl#^ue8 z5x62O2*j0C*^I7T+Wono`Si0-Kl94>Z{E4Pe>%@OIe;?yWK>;c6RojeSW^be{%QE!O8LQ>2x-q%{8e55P8*9dzUZn?d@K@ zzIWrs-neGL4#8-+c@VS;^wf<@moHuY#0wvO>ASDodgHCr8Cz)eQ$dr2pwP^q#FjHTjTK4pZv&kPv3ayrSHG|(yMp(50B=Z0t(C4#`wa8 z?dP6*>hj)&!~NSAHb6T=s6TY=Qe^0p5#A?-`#G1~u%w;V89@o9XC4-Y_wI!(z z&HLd{ivVR;AOIl}qC(y}*JE2^rWcDvdCx>tiIl`PcNZa%Duhr_SjGG8;AJ~e)$$^= zoagn{D*ne40f2@WDr68oKHPWr zD6vdnnMjD5Dvq1FjuH@1f(tH-6GR+0RUIQEAy}V@RK(7Rv5KLtL+CZl1r%PKQD*1{ z3NA=7#>se;x)w=9Bm`;dibvz=?1YH`pzFFIG9Hgbq)V;4)uYA{Jf|3AiR-Cj2uvla zB?w-=wENndw>2#+!QET0>1gMP?MvgUW8_c@EFnHa!0AnLXRw+KWz<k673=!Z2jObj%RU+=V=rXcU2mnxAU(0C@BLN{GRTb4$ z?dpWg%t-9ZzFlbj+S?uN?%ep)Ph4%gE~gTP=^@4tVu|iXI&pVFFWBYm16mM>1V8nYPyECuo&Z1q z3(Vvh91L}+a{6Jq0W>xJ!(aZGsh4)J2!gAwRaisd_z(nTdgF=RU)}lSbg{^4?uGya zC#km2e)?IrXUnxEqPkKxz}~JvKqUvY2!^wON(~zys-C#jw9|FgFx|K$ zS1&xH`czK2>ynz5@wsp;8e0)2QuG91fW7R`(7+Yl1LjLRwEM{?KlzCpZR%!=g_;HC zQ8kKDh{*{q?_PZV>A#Qe;K+ngIz+v188Cb}l-T*N9(i$9HVO>5O;CsDj-5JiZ7o^2Tv(= zT~|o%B~!NO!~lS?nDb+C*$umP`6~JXE(*5u4owAn!*)rjVhW7JfWX0l3ILf1d;gT9 z_9+}iB{t-2()~(k(P)Ixw-%TKPKdn)o}3t%kpq$dl8Xdp z0(5dCSSC#a08Xc~-~0XF|C2BNm%3>tsr#q@^nd>OpZ|Mb{F6WVzyHl|rkpv%C!YL} z0etVJR~Cy_%6?n6Ja?qtLYr09j7W&Mo@_k%{KuaB=qER?JqMwYQ15PUxpoHn>MP%S z`8!|z_TG4-sqWnTZd#l~Mj|w~lauLUv5-Jj6+&Pk1ae1LGt&ef0F8UabD2kwu+%XM z!4i(ggIYB_}Z1dmv6pR#WA}c-F|a#|K4Qpy42`E zK)f#Dpw5gwor9yr?DCb#jjMe7-r;m%$*NAn z(JbG(w-{Y*HiXy>7&(wA#VC_WW9on+al|rpBp^l(%;JV-gsOGj%sQ>B#?%K1HzPWh zwUaQ!ibTwifPJW}2+@(S2St_;K(6a*KAWZ7MW}IE9u=h?^%KSNA&LdO&CQdODUq;5AawVV;BLq$QQ(95v)+ORSTSMV(+m-p08YGLV)0t=4}&#v-f~c28vM{2`QsP?+1|p%#M)3oX}(FS)itF<^|1;0F1`6 zx^Rf*raR=B+UNfmv5HfJ!x%cws7OU)y# zt9ktXJ8*ao`p}q?lmixv3`5W}0faJE_LVuegiDzN1X;>@`c1NL9-_KCmkuTMP4!7V z66TUQ+Ef)W;P5t9w>qACr+pJn7@PqD<0Np8rFYXZkQy3wxPCTSKHZ9-2pGvdQeB13 zaVU>W@l~2)>4n92=mplX_P zQtxs`qPnhg%9e9v4g`T9NC0>02pX)t?MH%`jcW0Id{Mw zVA$u(xEr(h`oxmRh_&ZKU^eSg*QGY6_R8MYW~_o|9_XeHD<}DSI7#2lLIS`LVlx_{ znmR60Ce14`sFfrsCwD;E(jc`6GYF#kr9M2_KtX?9@yjH_TBG(=kuTc{F`sS zIU0@r&d>gxfBfse{7qgNw^s`pZV-(Pft(3{N=weR{$n*Vf0*l0@}5$ zs--R!j9@W;Y;0}rUffNfIky{I8zFKxxB2v#Q4j9E{-rF%1< zG%ErdvnFQZDg;v898X5$rm7+nG4o=vAfhV9Wu?`O#>BLk&ts6fimqBmF$Nr@n&5_r zRp9GaF5NpgnP%Lm!du4&M|a-3`dki#hVDezpA8(Bk(Yz|0?}!0Gc7~6A-uNlX{M~x zMYp%n1g6tzd-t|q+#6lHy!-l_hqE?0H0E;ec)q*A^)?fe0E44Sp_*{c=0J{J)7dy_ zQqStDUR9=s-leJn%cq`AB&sV;8Bx)83D?tb}ErIb^<5*WcUcIrzJM@$+`=Wf?^e6r(--?csfmv_W-b z>)!x9P?GC@{{MZ)U&6!c&@-ll67nrXPUPk`RE>1bK}X9_v%$5#RQBSa@peEnw6d$M zwzTEeUMdw^yG9S2)8K=(Fb>P=yjKzoAfrB3T>HT2{;wDg6PEX5DsAhXmGysid`w67 zteeZgy?+iI36YnB<%g?;&PLBKk@078%S-Ky=0pf;rpjl|uaCclaBvls3Sg*A-u@-( zqv8wwV(kv^ho|^}U;hr`mi^%Zto!NDgT#If3_bWo)>}CEs1?wcAcn3@T~bxc>d1nK zA%r?acduBg5QKU8T_d8Y&gS#3>kM255l^8ol=8Q zI=@+6{~nNoM(83Lz)er5)BVH!)7fd(92h_R?2{y8cBKJpx&DQ$pK@2q67M?#<(H(c zEvBtyMb_^)L+mR9GWLp8rqbX+K^MUgNTiVNamY)9`F!!0U-?Vsu)Di6YDWL)*M1EF z|J}d+x39f+lZYze&wS=HANlZy|LjX&x_$dL4d*~60v0pqa!%bmC3P?GFlD0D&2PT? zvPw0_dbD-164%+jwu{$a{^so9t&Iq2dT{rRle{eXzfR={a)&<}C|i+5DPflz2^Dk4H=K_VzZUG5PcYr%5;na?z*4v4v`V(>T_k75-| zKKE$U)OFqyL{p1n};J2J3PI6 z>!!}9<6Y0C21GA&u|ieFQXcjfeQkhc-v8HrF)s;8Xa>{i;>y-&d%HQh-OgwE-rb|U zz0Dh!cHX$XKhKM#agp%O(R^#NAwk%Y7$le@nn4w#DrB`PhNh}glg-T3b7ff}8#Ijs z392rUun&!3;9iejjvg_@tV+FCVo>X2@yyc_c+xbryLYKu9!QtOIVW6lInT)kh{zon zN`ZC8bGsywE;b(x$vUv7K>EkTo5^qM)F9_@4K#q9^A@81os~R zrr~}46=y&H`||#ONK63htF1r$Yg@@y~d;hNTuI>S&H zAFyOuNvJlTO{cT@!n|aX)=1(=ZI`;^#6)#f^Uxh62USfucU`BN5lKQYcQsYbL@d(B z+Jqo|QR9YKylCZgvsPx6TiJSb?fTKw%#-G<-Qn@cB6Tml_UdeQl5&18N-)nsY{un5%=Xq`5UyHnIIGmKM6AvBNVYX77~N0s+Hk% zsmk2pYhU~Ni(mLc+b)FVbD#U=7hZVbKYaf4U;grcRaG_Hos56+AN-;)|Jk4Z>G9E_ znW=#>YKd7!LL@f_Hv}rbIYvh7-n{wp{_zpi1w`0nkBsg|IN z)7;HN9ZfZL3r(F63zz>fGsS{H1vj^Bm{n6YB0x7YR5e0#Ge`7Z%0`Hwsw6Vpmpz69 zu_uoWbwBiTCv-1ismL)Fsb1gZ0)#S!M&TLLp8mr=%Mj zqv|NPElsBjfRoFYwk}<0-n@Hi#_Du1?GC1Cyjz<)60)#?iE#)aW{;v()TW9lB~{G@ zYoV6Sk)f($Hm!&Oz>&&(H9(=#X2Ytkr;7y)tU*K^{DHtlG=>1+F;>jnE?O@=eO#WW zif$d(*;jq>G%Oke#2s+01Bv~dvit-WP*yGvig}y5lv3Na$^G!~FpfvDX`0Das4EGP zh}~R1(ES_M7=5_5qyI?Q41ZkztP!XB;5JoD?I!~O03ZNKL_t&?qCoKN>~^>$6Fj7& zS6+F!C47)&%KGML52~<#81J-IOK%vWz3WE|ODxZsoJv?{K_UF;J!|LIhqK)#Tw3AE z-3(@6jy_CZ*E?@zN;r@R&f#O|yyR{jvS7uSm{TUl$#|2P&D{(f8Id|DeqLlGbOU!a zn|EE?wr$tN7y;4UEM-8ft11Q#A;%D`+ z+js7$I}4lHg$oyovr02&Iae;0#0l0!gQ7Dz)M?}ZRr~m0c{XbuL@e2-q^~#lB`IXO2PfvdPxBvb0 z^mMYZ;e;Rm_$NO4!bfkue)C)3`lgv{HU}pHGEYo5iMs#Bq#7b3w=;#^mrY!Wdqd#u^6FR-9UM0Sk7g%#UVG(3&wX@KkCbhRcOvSg1b_uP+UGW{ zK;pyM8L;rck(tpkCqA9&)@E!bagi1PGH>jys z{e=+f(d6oQlA^?@#C*!+p}SY zf{z>K=#S7=v`i#k(mvt4t=R4%FwzBs+ZN%Xt*&s{w-pfJ{>@Pm7+F14!?c9&~ znVzw`f1uCWLrzM?!R8PBo*!9uKQO%OY~iFsX;Sj~@=78GWq5?c$k_W)^75o!;(K5n z)~u@u_RzjD2Lm%SLX5Fez!Jg395j2@)O8&&p>TFZwfTJBwXLa^5%s)nLlvtkN(g~j z2$#vS=Q_t=>Sn5n0L)y3(&fxk=I*${P~+)r4lqwCWkVypcxev-yRO@uY;0~#+SKKg zG^g2Y)-I+`U%Pl^yJi+9$MwGMna0(*#d;ahfofhV3_~g%83hNV5_E6w3{;pP#^8oX zjKHSo3>-`F9IpW&;M?E+_8Q&N~+`{_^L3 zWi;OWzy9@azIFF5^*MczIx})%;J~G;f!HICsw%o0p^qv_$H&E3I6tKr1GH(x+DKqb zrj}FZn%kVv&CD18!3g_Do``_h-O13B8@oBEVghF_&J|R1)C`0M$ZqZg2!XliJycbQ z%hCkJ)a6#VO1;9mN5)vn8Hq&#vm2VK_u{_gqDQ?8hx!#&-OX}#%MRs&c;T|=L5)g; z2!==(b~mqH+C6IT)NMYv_3Hfa_U@%UBO#Wx#^t(Z6pQy^z_!71wHOZJ{Ts_5`zMPy zmaPq$O|xo+$n%+c9M8ixBvs!pHx$&ID6RZJU-Ij=nHC z8_)FM_RzVzVr|4gLlF46R={HvYw!6Fy`2oXAKE4jER$CrUGbj-LV~Y-u@9`k9*{-< z*Kx0X&{t+9Qly@XJ&y?QXS6~Ww>HudEk%vM&8p=#5C2Jd~$3^KBssrh0t?b@vF z1}Gw`+AbDpwn!-vQ3xT5NDvkYF&5Zs-xhW&a{L0jQtfp)gam|wQo?Y`E>cc1%#1|3 zIzRZ`yLZNujS%ZtSB@~BO_OG>f-}v!#cVoT%x9KUAilW0vpE^96f6Bq8qe!5S5N3# z_r+Wb`jn`cNdUdqxH%EJITq-HniEsOz@)ANfOfH{Q7A?hVrJn&j==eR{^A#2eCg#^ zLX4Bi_*0+y6cK&pEB|%6ScF(*v!DIhpZ)Y_KJ(&>fB2_g{2~L3NViy&YoP`y8|Oq^ ztn(xyA%+lQ*L4JdWT1&G6EV6$SMmfAJ!|e| zA+iY}dG(>$(icdJg>=5qj$*}@jt zV?ahG1YuWp5f8y*^t$$xEmu}2&4%ine1XYFqY*&Cg)$%lG7$)1XW_UICquX=yGp67w91X3kw028^hd+Gt$bB7+TR~TT%^RQgV?& z-JMFxx_fZ;oYl}AagFJUPKn2(FDDG@D2dDEq?_PW9+s}XO;}b*M+2YRV9UN)T$#|U3;mVnEL`tn4}cMjDqBb&1lqhZD~i9Vbl<2 zP-Id?xX*Q6BS71>L?l5Z{4J7> z_3Li1nru{6J()~;zr6#3&!*F(qoeV7teQ41>=XqSfM-?9*_Jp5T;5^#&tBooL3q`} zGIKP8te$g9Ih&fQX{T*F&)uRD5wa*W9>sB8Z%vx5jnU?K+(Z_EDh6hxej9@6boRwR z{^M_b;~TD8HO=<+_V)Jn(aFi}yZ1tF(}E-UzLps-ly$88!L#IG!H2v#f2l(|NZu zYAP-a17yZx&qAG}1-en8HLWa6__atIfRjFEF1}sxxARr+W>J5;S$@t#EAt444 zb4M?EJyeborIdGs@pxQS)qFk&048P$y?GWerKBl$Idz)5Y}pK1>beP4vo+o%4qO1i zJuMG}keP`YNE`@|koX)bspuL-Len&NasmL6(57^Je0*?luzzn~?k|$o_Q(fd8s7f) zdG06iL8Hd^DtN~aV(+7OtI_#kuddc%*Xs=u$3iaj<!sU{H519}Cs9uY6VR-bo&fmFEQn*h&gZO}?_y1qDW=jv1hKdW;*no%#POBMV z*~ZWaiI5#i=*J3iZVINJlBR;N>Xb+(lZgQscuvW*uy7%U5MoqYnc4xstj~c)@8v=z zo&@mx>bi28nJpV&r5jhyv1T?j*ni!_y>QG7BdGg;aVYtdDp3`NciQ?{mRe%{4ajtKmX}( z{?_lD%(5Ahqi_gP5r;BwVIU@FM)PE5NEBk7vnzD!PQ*bNP*YmuYy}Ui=Bmc*uyTX} z6lvH{c&T~ri3|>ajA-EM=I(}Q4ytO1L)1^{dvOpz%%tSb1|UQ5r>Ukc0XQ=GveGW$ z-%J5XRZX>M)R`!`2LLoH>=5_9gI4^508pB01P*5CR)%<`5-UMJS)#4^wJH3$qkkU38mNlx3*xUO5#g*s3&KRsRS z?TofYF-_fx7o9GWkE9&gQG^163aVmYih;9v=vah8V9CO4A;j@yqsw{BvgGD7QDmW# z^8qv&jqlyvM+YG`v%=T!GaL)5!5s)k<8eJ|+O9()0Pngk=iGH&o3(2@B8o9cjH5bA zj3HD+TmnPN!8M3PVj(9aE|>-)Cv;##0z`!(vqbNW0>C09Jf75YOK!gL8aN*u9nI&9 z7~^DnQ%WrPSuW`M8jX)QO`db_KWsj@{;z^$NazS|P*w;HYyv1cvNj(hz z-7M7j@XfB+XdcKfeNYJ6`&Ss@W00v2Gee!b9J)N7B4~NTR5H{{u$3=SLPOOB242RA zOpLUiW!uXPN}SvZ{&~hB_0T%6{7|84_C50RAtz__^21S$kleu(jL{T~`o{M8@&(_0 zT?g+v$>|{!_y=4RN3emsTgWIyY=e%I1gukr0LB8mfB!2^I3GYf(vAOu2T%9^{bLvsS-esn~RI5-_GoOqbMm;*ZquOEdzM-3E z2X-)rKForc`@EE8CL@pHm6dRL!UQUJkrEbVdMR!Z+=@7; z2;>X>k%N$kS$4CML(ANA#lhXO87vSHN}XLM17=XTguSiDy$>50&I$uozR;NrKp5*N zqpE76DMMZ?y0%4*ifHR;9^gw?)8Ha3{WkIy_i^d`D8o%Mpyc83*eUqt=7!l~*0~LN z7J)HT>_~*L=sd-;vltSF$k{9_gvcQYXXU^lFsoCWh(Lr!qpCeViHydqfZ*k6@*WdN zIB7=Xrm>uaM%btRmF^_tKsqVIeUxzT&fS;3|4OWD2XC5YV`FoBdy83^1p7LPfQVVj zNS_B#7844U&4wBJ!Zaf&p%NOSIu|=`5}LU$Qd)Sc$vAhN(EQ}&iK|aszIwG8Z#t5i zo$p}zJ2CjIjz^EIFdpq|`x|7#`#$4*L<{R71?x)rxWeR|SJ6G7tbFXO>VugOEwPh7 zk_>_e6ikm3zpXRzaJ>kA;048Ac;i39cQ?MP`vf0yx+pW9LW?O=IUnx)61|*KN;#{U zg9D2&OD~-%BN71XGdXBAWJDAeN8lg2L70Ws3fVz`^(d~YftqJC zRfibk&h7=^n#cudJQ_7s9M{cw+%y3y$hANvCYTtEK5_2=@2)|LBkY zXnJ~z27AGgu)9C^^e&VM-^K1XZ|Mc3;H~!skfBxR#yczA(RaEOt+h$TRLf5ve z8PO2b-BQjuyE%i4Vzs$*;l|V3`}YoBf8&j2vLR?~T0qIX=>r6*_%N9TTnp2vuY7w= zx0|`DCPV;^+&_I_U?(6#bh&@8b;d?5_W~%eO>4tk1CC#lHAXitM);aq=UjF2c9V z9y?cU;S$X7PC9fyEM?_8KS8|HEAMM(3Lm;=LqHWFNiv%*<~ip=S!4 z8HnmV>U?O#5-}%L2@(KYQ<*dl;FLZjcvvEFEzif7GDL8dvQvI5JdtZ zogN)~m#HFiqhg37mq374#b7SW#%M|zyv+R{ckEj0Yan6_VX;sFyRbEJ3}&eksViY} z_AW0{N?KJMql_!r+-OEk6@>{gkTW`%^%0KX2=Ll#uYL8aUkxH5NSpJ#YuiP8a(eoa zkN@QV`WyfIbl&~zfAc#>bKkmnor!mMwpH81gS((DVUBe{x6eVr)w4sF5jli7;cBxU z?OwQa-5|d7>T9#bVibir5QWlqus&Q-2mwKds1&49dkwAk@-=4w0#__8NzIP76f&+w5fG$W(a)6w3sh-P}kOl`v&begu0xdKm`Xs14^MH^9L)r)`VO}IW*vk zhKw#NgK%>1l7cVxF4T1eCr699FWOWA&~!FiD3NMjcpXOdb|9jH(djK63?dwYgdi-! z0XTS2LWI$H#KLMWh+L={#Na?uY?XkB7d$LJx_{)684%e>|RIj73p@Z+wy)nQEfxJ&7dT#~RWAAAHfqutl@3C|JIe$Q*)&sDX zs`lcUDuL`}Y^W#GshZXGsE_0>O(r#mGZ_{`{Nob(*uNjm+0+*8qFuCHe0wVyJrW_9 z^>Xupa5yw7e94}MAwzyi{q?mdEn)7h=%sUJUWeGVi@J);A|gbHts6Z7SnMR!8I!| zATR?Epk%6IV9*3PA$qTH2PnYLvWVrJ2_c(v#_WjbF|Z@|7Y&e#s?OIN3Q)A|!>}2E z2j~M}$$m!Uq76qTmR_mFEIB3U*^tXTx*{YJ76G?XE%ihOSfd&t_f*e?g$=nRAbDMST>1@%a)TXom0OC4S8{^3?QbjC;!ClOQBD=F?P8m#_ zSXtI)Qh`8co=s&9?PVwk_qP>SBidni>biEiSd<=2=h|txE*q26ALnX*&gq{tOYAkL;Bw;qw zoO?D}&I%5~%tiIMtWF2(T~81oQXj&PaETO01T0ZIr9?(V5h0T0-d{2gy{BdjZ1aK> z_j6BR4`N?#KxHXr5x_*ub<qmvNhuA*Q&hOJ;uPJmLA)K6=NZQ&O z=hPt*n7VdIBXtDuqeY%3uLK1Nk${|;g$)S^ff=eQRM}$4ZiMdHVyt2Yi%r$3S$54j zoi7fLk5ZS0DF=@?H@CNUw{~|pNH#;nW;6*Rh4bYA>JTJO#v7;8Y1?*$jL1}gRft-^ zbX0`#1XygEeu`=CInC32Hf_6B!At*XR8`xP4Pg;vaUusYCj;^V;_`qbF^~u&5XSB8 z-J|2v$@WE4O*yOkqcvC$J@T%{t-PH@^AU}%^Jc>zXc4w{dIK!c5Du7;0RvNTN7IZ> zM2=ME-MQbfy$Cx1Av58_6i)9$bHbTO%n7Kvw}1StZ@>KN_urUK7ho6z?QTz=xN-5h zXRmLK8!j5>hi_Um7>DSbXSZw~8*W`+1&ujmH3vwh>%S5oatUlWML2+|fy1a7%@JoQ7b2&x zO>2r!U5aDh09P^bPK2t#JPO7D03ZNKL_t)Lb1p2;B4&@V+~I}hwSIUk{sKS}Dr7vTow_YnNixh(ttYA`ucq zA+H!lg2>3^%pe44kktxF2@#SR0R|R8azF$B_P4+JS6}~XT~(W#o9Yhx`z%GmLWR=#=6ecn=j^$WrsZj z0HoCf+04)ooS-BZ*Q+*Z`(OoGRzq{0a~_u)4bJ$8Uq0+ zx(TwH1PY3rF$AuvYNQBchFT$PZf?H0zdxFu9?#}EWilhcrmnVjcScRa65RRToqLFk zEP$jrxf$3R$`Q=WDDw8s_VMv??h+#jvmzwqOq_|7Knb04R_nUlwq5Fyf)NwB2c*5t zofw3`(A2Y1ml&*Ki6}xWAvz%tvPgfd>S=Z^jFXMcH*ej!@g!*0E~V@ye#XVM9%^#t z@q6g}{^14I{W`6+pp_rCR#yM488SGj^T|9P9iE(?F1mS_+GLgx4Z)aTG-@_?c1Dv) zUB?(nC=E(is&&z4$Qwk2hG>DAZ2@W=nLdOicQl3hES;X_teHcs>KNk#Cdf;QqnRy%Soh8H-obnj`&d*m4}d;f%#RKa2u1`! zL@r*~sGF+nqX0+_1Wr)wsC_QH0~_$7?e5&!pG{jr284}`>e9|Q2>L)={K54@fz9CN z&0D|w`+t@al1+c^r=R`E^B^-y{l9jJ5x`c7$7kIGXLF`8 zcbanQ_gy4H5=3y%rs@T|)GwNSj%<%wa6~ZGWinNH8xF}I)G7wp(iy}An0ST`-9RDe>-S>&h*_4psuTp$v9{A+yb&xu@-JZ zh#@qU5J0CnWlf-}sldmBNML405n&=%18`#Oy6&&O{`JGd!)DYN_-H)7bm_{k|C9gm zlb`y`pZ~>IKJlrao=mn5a@TB*-a2@5|M&!BHQw5u&8CxaHEAf#50CF1d)GqlG$r%W zRR~v~c9KC{?La%{?x}l&Q-%eb&S)){o~`~ z)6-+HX&C~$8<-asXfLfR;=BR44i0WmQo3W1K3bSV8B>Bg0`_JFD|YCWH)y!@R3?Ii zLWOz{KKzw(f<+=CVRY{Kv?3w`;HtUINZia#!43Pq*!}lO>6w}X8j@NM{Xn7^VDezEK(_UD6!bZwl1+^4sDx}1RVocZMX2` z6lqYap%U_FJh^mv@#d{#@@eFbAcN06wK>mKJJY0E*dKvdgvU))NoZnZKuZa-Qr9uK zAc};56hal55s-;VSc|WpmSz+%wL*9iiTekKx8J(c86GYc+0TpI?~kj8a|ZHrXz9nu zC(kyn{DW%qyvHUMx|5@*i$Zn#?!h;|_sVx(y7l@ScaIKdIhp6uShkW4DZ-P@jSCmI zuU)_N#FJO9ULIZAZbmg*%J2J(&;cA>4PU+a=I8(8i{EtB00DTYcu`N@ww`P9{iJb0zLqVr~mcQQUc`xgt7#Q^!%t$Q!N z_@%TEQzD@kKKk^}{LH5>ZjX^lnZ!%m2Mh$x?AWI2>)(3i#XtO$d;2HgXlecvAAkBE z|98JwZ-$|}@q?_|0g+U#%{e6qZf1|Kz|S@I9@*I~yqHQY8U!;otdNA57}uyrKT^!F z^~AJuf7D9s2$;E=mBE1BL@+2L>4Z|9?Nvdb*(yh;^hoznJ#s9$o`Op@r$TB5wr!{8#AvSb`OI>+SnQdFQcCs)bmC>$?SQyhwMBcDw;CXZ5H>d^A|Z;1 zP(VmsIygA6oS{T53rmn7QJ9$t+|3*jRIQhmAs!zce)Vf#o6cr+)2RA*Jo&kw|Ak-r zrO&Ch6G9ekp>A!)gNZU4bRqyXr z+xvCdfOBp%8fE>#&fa)^c?FycZ5zd;lptnc$N*6EdXwo6604cZva+hgEX2NxAdqXo z6fG$md*OLF|A$M!%=A8rMzyEV4Yy7=7|X5D~U2L_qQN zIr)zy9*djk;wuLIYByBwR?4WoTe`I=z0Y{P>Goz2c+8Yx?x#N8Wh-M{COi z{?<{E{eDVp{KlY&40wNBzWe@1UtHK|!Ks1waAJM9IvR)Sy*d3pSaM-m?e73QaN+6(}IC?;Jb&UcY|pe%@O4@av@Qot-u zO&2Jd(Vz@KDsEchWRfsm?|*bjjDPytONUl_W=#}kbxM3hBm)$|PrkVR5C8bV)oT;5 z%uGONJTX9Li*tbQQl;7NJMa6$p0PO&UV;(9M8^G4{i=E7XDl z0aE5&KhGRU44j`Uobh)E)4%bv|31~|T#>f$wBWZc%(Y8NjB;`$@6e zeIr$L=HWsE>XHgAZCfbn-s3kYcKK!yg2dp?`0qOBvb-QfVg^73113g_!y5x5W-`F8 zsET?w)FRGf?_gTasqRl7Af(f)Y9X(l^+`zqY) zc{6p+Il!os2TUR!>zs@@pN$~`Iwm7V$43r3Fkm7HVLF-AbqOL&&Ksb=7&FeMFH;K z-YloP!_}iFAAZ~n`ZsR(S69b%qs+tAHEWvbWEU8~0;V*P13MZ_cU%+|#ED>B5n7_U zOW>F)jOd&*=THriykqL3@a9FzOv5^3p%G=yiJD^i6=YyUAW1SAt8MSudq+fOY6|3> zYOMGiFlmq!jX8_TvB+@O#kG4ByoaCwF>r>6=g!0jwZOA{XR`;Ndj|`wgU*~NFJtmZ zAPSi;4zH|MTU8sCXUMhTUfHbYc~s}8DY7a6GV`F{SIDwHO)70$sM=;cEghjYP0#0! zQuGTaKPCdQk)teYR0IqiwMZqwK8g|q)Y5F)ggP`#RE(C796NF6?(NXF{eIsO7cTb+ z%8m@mf^j89!^I0^b z>}>CO=T=r%a+Lt!zO54a-dZTT&xEsZgv7(^yFrw{m;Cns&BHzF9=U4mw;!GVo4gFBu9uYh!BRbawrY8S$0`sYn1+1p+M!B^**~;4U8W@^|Par~Paf-Z0EF z>wvTf42;Ntl#~Gi^ZeB$V}_I!jD{44HDHEDgs6aK=&~Fg8!8wva^`&QeLQ00HL8)~ z6lwjj^fgQn!`XJofZ{d+X3xa`N2ZO=p7nbw;buMyGeZd4idxKeli5Wm*0$|`s1PDIr-O&nRpx+>4}lzo<7D*^x$B}6kLFd`EPAp|1h z$n1&8qd90aO2gp3VO3(pb_MrrrMP$?MEcTwvzDUhS5;#Qz*sk7f3m;3vv+rEdt6SJ zmy5NvwZUL{Y1kW%hRlutP%TQkQj|`2uS0k3rK2D&=z~<#NjaS&K;}FE?tu`MQE9Pj_e(JB6d-KPf<}9)oimtn}C6#1gWdgY7>1HF{aZw zKkN+#D+BL+XH&?SU953dR#x`MdxtHkiXk{TND4hT%8GKXMLWTLV$hjQ1;4QyhIur1 zLa_k?ih<5TR^eOn=Dt(vKJzy*AVqTy5+dmzP*l;PDajB->FUOvzy0}J*ETEV9IY+9 z96!8r=G4jK$BwyZBr$86YC0Y7?(W^Wd-wL8o$0g=A@qCp{4>w5tsEk20j1-U5JHUk zrWA7x(Q(ufO;VT?iUh|*NC2Rq1gtodQaeR2;J5dh-F-3hfOPuQ@t?l_>Zv2k-V7Dp z>N=wk2r~i@#T+pJ0Y~HwQ9IXCl7XWd1(Tp%g%>?%iU8o$NC1U$K?-OAh(Ls(A&5bl zsBwy72Gk&HIu;@(D4<5wd5jkIhAkSHF<1eBF|!LPYN5zL5jkFw-2tGH#;2x=#zcx1 zPyq6%8J*Vl!AFY(a!!mXLlsrS0M;TZ zpv;~JVg*BsGZjPfmb^s)MG>^qC#Q^#bnGh{7oyB4+)cp<**RXED|^Qjv3!wR11J_Z z+Z3VF2ngUzNx>A_w3?aRfe4*)@*SoXliN}oTy3&Z5!h9$a{80LES-< zJn*RuQbf!=V@d@EhuGF7j)sUX5~U-7`+iXb&eD_*m^-8Y&}KV81fygd>_AzI={iQl z-gCb{+}hf?xp{Nr_TBwS+3ycdoH%*r)Tv&PnP~{p)Rn2CC9eoGGBb7hp!?<&@gcW} zV-MWk*@VUB4&d7d-V?DqrHl!X^LN`z*%zq|kbN58F_ikO#Im;dUo z{;DW?|K)%AU%&qP#`605qZkw9gPf-5WS;95iVc3ymsjLxyPUIMQ=PQw|4ebX>T&=t(Hd~8upil%fmrl6aoND zK+2%pwOFDF*q(MzRFT;`moZuzoe-GCQDKbS=4b;@^BWAy1@8`gBf$$&SjT-A?`#AU^CLtU4JmIxH^e@TEJX#tI2K_wqVh))MSRt$0RbQ;-eH&N3!Ai6QGW#scna~k3k*UtL@!c^O zM4HgnAv8^EDIMOt<9@HdJjk%)0C(h+v{6$(mK2&BZ#aF_$~JgZ?g@k*m$LyTu16FCKx z*vDhsph?w+_dfU%fPVJI%j+vy+-gj#_OtU>{{EkTedXqkNZ-g~(wBgtGa^OQE>X)8 zT?PRhQ*ME)%67+-vMd`B0WiQUcl|-p%U!?7d^(1r%TGGJFaVMv2ZhY{ng(`v_xJWn zu&y&97z~H~{s5Q+y&0*YQq&bhYrBbBRX2C;?d?u$0PJOMsplLVuw$b|HL{jfvpcR7 z3ZiCM|nMH*G*Z}ILuFATqv?|*s67vwe&z44`Ug7hiBos>h zY@AATkk~WV?qdMwA9bCj0e4p85xM@(91N* zeb9C|Ew~)>u%EXfB=!U%k#U;Ca9pr5QTO|#MCmv!k3;Mj@NnnOoeN)m<(LiN<(FT2 z@ueUB*T4R6Z@%?5`K8_6>E5IYz&CH-+uqtM$5S%(W^2pC@nmxC%4XZv(v)@8n)(Pw zS442mXFXR8Ru3IJa`KeR-K3mw=0|Jmd*f=fy5h5}==au-9Xovd#M0^tJC}Jz2_OO{ zJ~AbBHk~;z9wkTv&iGe$%o)4Fk#pi4J7O2Zi&8t9#?EOfO5KNQ2BH8cB5m8og914i zqAAU~FH4Z8`L+m5rEP?O!DE!QsxIT6xy~e%eDgZBVg}l zG{HroA$)5TMAr`BYz0Y+BCT0qrKOz*0;K^N+3Ip{TI~i6X08z`TOH*T zLk)s>Yi*EhlWnxRJ5hz2zUYE>l!X_~68#W8w5G8zro zfm-fekBHj93XDobj)>J(`o&7WU+<6kuw~x)%%k)1yIUKuViKl{sH#{9DiX<#&ShEF z>-CA!jz0o8xJy{VXx2xY=SM7*Mk_1Jm#KC7X^k;wa z0x_7e0SK~!|N7eIZ$CeO>FXPJ?(Wo0h`UQB>=oHVXO5jXdGy$^wUy<8XW(e)Hc+)M z&tH81{qwD6Oso6*jcBfD0Q|{kmoHwr=%HOI@U>T7I(7UIfG?~1y>~vnb$3S;mY4dk z|Kz3OaF1vG5Q1Sa5CC`k*4D4z{&dmbOUo*NAiM zoU5B40F#E^{_VwHzyITxpE-JH5EMTTJ{=(NAH@2Ffs)A^F#)l5Ao;ZH|*vXTd_o`r^hysb<#TZBZ?z7Lo zc=N6I#}ymF51u&l(hHB1V+2V>&K&kio11rk`POHXijc||pMU1Hm!6N1B$$s#0T+IN zbIgqca3S!$t=)^4FMoCZ(&pywblNsS0NId+!~U7mr%s+aeD?9t(Id+Rnn!`O)3x8J zS^M5Kl^sNFbwhMC1l1stf_U3Dv>_!TrwPbv^6ngun=7+BR)n zRc5NDs0ym4f?!d<93@vk2|t4XOyt;k&)!k)UFOg;GZ8cS7<-pgO}H=+M2p~tZs6B6 zO~O0?c|c4uE?UqJYLYQU&=s+U(2CCbgoRZy&J2Jv+u9skh5#a>0)_-+Y9UC|v^8+g z`>e>*V|GBl@<1#le$(IIohSE8w`QO_jJOztCP-tXf$rU#oH#mK8WhdA4aTCjUxxKT z<{<5w3?vdvIEZ70+yxMp)_DicmX_D1S8nWz?m6D6%Bqz%s0MHd1Min}e`q)yiVXX` zBcl}uSe27zTIR%n@w?0(!6_grXW7zVu(h>SRV8^2jcD6gmxL3G?WjvZM(^@G&3K8K zkqCj~=Nm$}Z&8{)i{uogM22nKrfJ$X)OFR=^~T2a!P;tTazNz%pi1alYpe$bKhOXF zZwY~(7v>RWwzxT1ILp3AEXMcNg8-1K)>WI@O@b`XkSUm&3Goa**b$wHqD>}apBFhm z (`4>YL?dfM_|0!WeDjyTy|+`#xM7)0E#@@IIP>2qrtZO`-j3+y&p&((cPoG{BRVIh%l>F|vdH0r5hr7v!rJh}4B)8`&Ndn(V!cY}kbtnc2w(`u$rndNb>D++si zj&eZQFM1-t^Y3i7Hm(puxp$Qeu0U0=5c5;M>+VZ|>|@h};Z@o{$I? z00kHKN3+qUbs;?+sTd8c9S#Q1KmYWVt6yKba?Qj|OZw+GKWbWe{q-N;yLz%Jq)TwU9j=dZl?-e*^@-`(4(MV$h+NC6N4 zcP90XJJshGZoKo($3J}T(VxEh!()d=h=LHhzJL_`_O8D3n~&dl@3(ii%Sqh|ctlPT zx2bOI-2M3CR#99)5!rp{eQi-sI~WU-%EcICEz3`XBx1xyK(~EeKEnYV1hU|Hd~CAN22bCwFYx z(>78CB!m#BRw`*<3xr+MrBQ(v^TuN{sj6b%)ELYl2(zJ(n3`EsS;e1n&Lsv(Y73J> zv=iYZuDYtK0U>3Xch1k2ZH>l_q2C+tXL-(uQNp8(qG3CL8Zww`VZQl2BqB2qk*cbj zrY@_hs!9pLIX@f>meyA@pJjO-he<}DQb{AGN@&AgF&qwtMb`6qmb-r8904IEyBYqj zPpCVaopT9H9wDkC3ukxYpCU!ZW_-%xX4GcqdQ;cu&z~QU$ISHXbI+YSckX}tuYY~z z+Ks$__~hw_Pd$3}iRYenOU3f>laD?3LN;0rb+a;Bu0soX@q?#-u(rB(<;vCm^7^ei zn`XMSG+J9*6R^6jN2BG_kDNVm>U2@WaU)HqRo3rMt7^Ek?3`a)ThH?%wkPrPudA{w zON-HvDJRhYfL)wf880k*2+=V+$IP60&NKE59ETz?7C4D^W(+@@o9(-AmvwQI3h6uM zvW(Io1VBwhOcgrkrWyo56`3cE&V-y%rO-Xe9b{y2|6>3s0+O7yCPA8}4e0Ws$nrc; zm)Lr+=1(h2goQOU%u;z~!g=d%bz59sB?T)|682%;wqhujO>1pxT_5$!YIod7Fq$;d z2ox>}FNuH|*pS%(q;BfzwBFsFZtd?+%6e}akp0$pqS*HaMV@7SpOecBoM{0@pomsT z=&JycA%~b(U_fZZfMyuQc0|3U!QS<&<7$!(dltu(NX(qYDvBx6UlD=OD50#8kO1SN z!H5zuY*w`pk*P){V$-xu)wC)i3IN05FwgU)!EkM5rJ7D3dE&7~BEu2!{ zX2|~zxyBz1GWeeB3N?&C9cFTw%LzbHfb`nUjjt|Te)5TjGEbmnqHPEwGTz%24WW&Z z^%URd;Zm08&XEzRSx_(oGGKI6^oNrwl(m8*CS-?99P0-)3qe%@neT2-|L*7SR%QLi zum5OuQ~(Gw6JX})(Auci*PT5LCB}2Em%D!9Jcb+t84da#z!^A!?8fcAU;Ogj_kQ!m zxYAZJ2F*HVhX4qw7+O)oy`AZJZ+~xR55%5)>QU!RArL_B{n|<)m_k z>pOJFD?|1fCv7Mgm;>`*Oqj)m{0u1+rJpfi71RX!U>ZZ{FM$#qm^r{qE9}{Y$ zzzYHcG(tq6tg7*|FE0GeKm2m@_P#2CF)}!I%osq`Ohi>wg>K&+|MIPmCgbT}{ORk* zkMtObP!P$KclO(VdGo_xy!FA}q-I}`bAaTWiwCb6h*;ZdTN;4?IEa;QGz1tWO$0i% zTp&XX=sc2(3m69EH0Q7smBk)?4k0t>0eP2Yd9HvA=)8A{aM+#rMwqaGfRjn}!TVqQ z{m$T#*f~O^U@A=;98ulM`Ac{2-Tmj?pS<|TufDK4$`M;I{T@aWdr;~Y z9^8v1?^deEQNdI|%vuo%5>x?Dx|7`wW;y8au_({R+;w1qdOCY16hdu&4Jv zv~6hGnY4T+xr*_0(d-p}eT*=UgQZxBsVM>)r~@qWd_0+!RoyRoQD+GUq+aQPPuEx% zF>qjdl%)F7G;LW{P1A&sUX|sg;h@)#a@r`jPb?)AFmoWQOa0Ms*zXs)cYsC~Py{V_ zU{J8m-0}dI{(YMvOkHu>Uzt&tPGKPpr=3VNiBspEeCm-Wo@^AC4BK9X@;*nN@W#91ey{d9UzUM#!o*7=_itM*xA?n?aUEHh~cVK_IZYEJfOx zwStjj7NlchLIULE)dxVJIKCq1kmAoX5j!Gg&(1R++|XH?5`ba6-7N7cFyi=w2#2<9 z%}iNmgTT0!LPTZ)gwVEX7Aa!XiP<5|R}vi{j#>zjBi{pP_7*S_Q%A=DiZzxw^_gep z2(HyA>bH5JHNypTC1cE0OsDefBVUos+Gyvr0tFK=4Ru{tbyGHF*@QMQ*=W!k3`Z+1Osl4xPR<-Z+}4dqKxtgtWEOF% zplD=@A`Au^)vp8+SG>f41ZtYhy33;x5LRs~2+ZWz&BD}OjFC2=?z+J)b1^mx)X7}p z!765L+g4Ro*Hv9s@e#`NJkRsh<>jL2Wm%TzStPMEQhxl|S8W^Ey9c`n=LbV_4y31t z7N%t17DqVK%YPdgtCRa3R9k*y)wswlz=e>C`Ji)t$S%sg?o-r0@bK4zwV5mO{N%AC zpM7;5tO0~7w?{pIJ^Zrz!* zjZI2?=lw6wJp9noGv`p1)DZFHv19-FfBv7U7Jv2jmp^~=V^Bb_7oUFWPhWd3r@+`4 zw0Xvi28h#I-hKb`x8D1ztjy5Z+mS<~vu92mKfXR3c;{SMmRG*Ma`DpUy?ddl@W$2M zcj>FOwG$^!j1ZL2o_ykoW5SkOj(V==6ip3S7aD7bp}ycQUAp#< z|NOy?TV<<8G#=MC6HQ zaegUMSJlj-@h7dioa^`d$r70A(fKjbMz*>r07OZ+V~X(11EY5nNx^p4l`&%lx zAl@sYaF(YREelb`&e&(Sp&xgbQa4-ZW>>_89Hig&>ecGe* z?60z*(vHft)|DogPir7RPu@GnOfg)gTh62jR@^14 zDbM2pqr(IYL4pKqLCsi`bwgDaApXRJM68;g-B1F`Kx8%|HPraUq&k}xa-(6k?wk#MXHWa=9>x*xKDWe)^OrW{SjpAOgpb23G)t zC^#R{#gC~8O=#QDHciu3RTcjT?_9rEtgeju{eDpt-uuWyJ;(}$rKOQ*D^hbt-#x*a zi|h_~IDZe3`*#DeW^LQQH5ez|!AY_52dxvk@f9dg=KYH=KKtc`D;KYABYHEpy(jN~ zbTuj%leOK96amUMqWLI=t0YcTl-_shOv6~T zNk7*opE%LD5RIuA~SQ?MCr-P?Kp zgO4{hx9gU`)2Wk({`9pUK6&okaA}xj9teY|gh!uy^5M7Ne*gUsFOMsz0(|i4g|iPI zd*jDXJ0>x@v$g-$dmnF4TO>!OXU`n{^FMjz;fIb52kbnUiJ5`X{wvRZb^h`{{p)Wo zU2PQzkfY^|3=JZGFwS2L(3sFUb`A)Xh&!Nw##4s9GZY0iAOhnAHtI&jGc$KY2WZS& zqy2ID;Rhez+}vr+0ok#mOK<$~E6>09gI>>Pj!6T7J^%D0FaPM-x8HvM&0l>~2~Wq( zd+&d8?vZ0B4)fx%`+Y_3)Ojf&%5)^wRHh;jRHEZf6*Ss7$_p?o(As{A4 zv{BqmiPm);xl@s_Fyk^XbDrlZvZlLywcFrCG4fDaZy?gi8ty@Gi91fR8qm3`Wtg1542WKBU zclPmfM^7Aap3A)o9U^fCnE{Gw&vRV8qoMB={o!b~!$KsWZaE)S1ekc@sg$L3m(Xlw z7fTpDD|IfSJwgag+ghZR#$}{);LSuMJBx`Ess`1FOaT-PkeE8=9~b~3Yc$G&5izDF zA_F8bFeD`I3_=*|s_1TJ=Gmm<+eOlFpYSfl7@E#uf@o?&giIKHy9(3_0Ycfz+K4lU z)5aRHX)v+4y-P8Ekv_$2AR3LQOn^WLvOMgE@jkXqe`%>rUm9Da?{{nLrfsUGR524U zg{DR3p6YDkY7T*k`$e(bAMEb!qN*?0Arn#r%5zFBib+NqEUExHD@h1MeAcP`;DnK?R~6$BEYFg-Ozmai?ZO!mja(a3#^Mru|?J-AMKKt}H(E^^V(`G?eA z-&2Ey-)BoWGfx8oKzs7!`k(#jkHgP@b>+skTCTIePhOi}6!WOVqXbrTk@r$p{-`XD6lB>w0XCHdw zjX!$m)S6=;3-KWWL+^`+&OTB##qGPlxqWLKf_(Yq*N;B&(D0#EL?Z+vBTzt%)**|g zAx7uWafjhUMG#El%&r_-fMj-|Z*!1%!UiB%1T>;?lzjpMMB2$b!v>RKbEfa^?s5%; zI>_jm$Ic8r{qk2IesSSWUDZtOpm49f`pi#Xec|wGA3{SyY=-j&{QzEMbMxjGU!8AS zVwbrLU;oLEUwYxOAsb<97|b9eunZo3_{iGQA4!Y9{@|*bn>6)DpPYaG2WQupy(oV2 z*;lu=riM8YpIBe|i$8zk>BmlZtUNbp!AuYVkc*{k<%dsIRkd;BqcR-iYR>XG7KS}I zA0*7qXhO8KM1u}Do&Gz65iCrVX5nd|s&Mt{##a}w*H{Q~UgSUfv!6Zx;uD!O(Wa^) zLqIhqf8@x~*M9QGt=siypI-yOtJiK_xN!N{`Z*;0w>wVa7aa{aVh|MCAnjbKa-cJc z1&Nr&mR^z^gy&mhqVy!2s(8-_SDHBIDlZ(BQ2~~-+iTkK{2$Ed2QGQyYw|!{^-S2_o%uEc{DlxyBihNf-Www;W}WmUziq{wpT zJuv`j^2;(hqzut9hY;3Aqusq-39Sa-f<}x8nF`Uo2%vc$Xc`mxc{(IB#{$e$yP#_X z0}V18O3%c2@hx`Ftt>C!y?f{A$rJaB+z+xw@2_p`+x1f46uHCik*D^}NRWTGe{hCx z20?6{gJ+&OyR_8*@Z&EoUAlYg_I}$o3ax^&qrAw6{oe9$I2iO|LtIt$m8%=Odo@Ca zRFq};`R5m2dg0l@;1GhSnxU&2xV3rb@};X+u5D~?Zr4p{S}_$QC~`j>4v!o;JQ}T; zGLWJ1?xfn;-N7@5ZDEHI<&Yid&;SBp0Mz&c1Vx~7THf5;3?Z_ain7$tKe=-L(~Ahf ztd9468k!qUOV_k4#(=uLH@$u9_L-AIreF}jERGzaKr`0+)@i0_4CULGE^iD6 z{wJ@#@an72t*zybnnZeBkZE>KEi}_M=;qB^<7o{rK%ldyjz9MBBRyvx8#Zhr1-v_C zSJ(Q_Jp1IwU)|mwi$Qk#-tO++cBCJ8xIalPl>-S@I5?|-0X%=q_GYulz5gyoa%*{)S0M*d6 z9c(@BM7o9ELHqUmqnHyZJ7qHb41OtE$N4 zoL?R-=UEp2P(bsJz4OEztLR8vWJj*>jL1y0#x?1S5fQ1#vR6SW^4%jD-a0 z@j%0$9+XrJD4|TIdpq0PD#1gNi*>vVLS!>RB&4~h+rZio>ZU2sn~Mt|45F%SOTkpz zHUtqo*Pu18MW6aWtiY_K{op?)vw4sg5z&I6g-4HAN$T`QX&N=614vi%0 zQ+2UxMIuB~H4q>)=_bE~Xj~LMBqHaQmPg=RoEOcQ%HJBE^`L877cOr-5D(v-VHkax z>K!>ILJZL;4e47P-<7&eZ*R1AsFu()Z3xn| zt!h9*V(#^NMNt&JK9h5?3i3XxBmsyRnG#WD*zX@&Tf21iN>f$KOG`w~XIYkIvlC$U z&ti-fEJPA@;NKMLJnL|6elI7w`Y}|Kb-PpH#h`wW#HUIIy zLn_X{p(;ZILeR*vB?AlI^1^LErvN*<`@8#NvqOkv3e%cD_~?s&{HM3JxAzU*ehJYk1)zimT05Rx zym*J%iz)&eSO`sBS0aHq#k|r&+mgB^I}mGtfP`$)l+)5g5rNR(xUsW!=L3)$EvN(o zp`PfrJ*LNK~h~CLfU7?`#u61yWF98 z5*i>IumT#OV*(5jB;#Ck(}BYjwQH2-F$&#k5R8dYfq)~|h?7H47=;`?^6>G${2$)< z^{?JJe(cc8ul#U0bO1GI0L&H@gbN-JMP$dmtQt`?WF$Uu?8xfUkYG#}0FWU0M`jAo zV<(R-ua54HcL`lx*W<}l41(x*Qi1|l+aL1bV@r9C2;rMS(ur;uu>Bds$LjcZz6;wMmWx~*#At-@al!1bfam=IL+1(Ff=-3qNTL1N5KQU9! zLZF}!rEX~6faB9<$c7LEZ{OKz8-c?8&X?#xYbO+-nZhZEv_VBhqt6LUfo7$`;`u&v zlftauQw@x>5dFyNrw9r+~MCgm{ zVw@|auTL#)*ivM8s{B01JI)5Z{@!@HHy#HOt6OPX5LFETz)VG?Iygs6k;F?xK6BoC zro?bpGc?Rx&glj)6J_k&UhyrAuO5>pW;8}}Y_5~vN8~ju(6n%&Tkg&fT%>%(zqY9< zfErb0d+qwo>$i69?T^bwLeSj1ev$WkJ)h^CO(x}dLZ*(1(|JEzn{_lVvZxLeQxd3EGN$0205l@1QZ;qQ3A3gN5{D|H z2;{xbvy2crB6o+dQjLZ+&+OQF@0@c6&^ApJ+cC3q}s&Vjw~ULI6cI69fTMGepeuf{+_Eav88wjDYfa<{cRrf-Y{W4DdcV^=y66 zg;vPl#K0?mYU)*{s)R z=Vp-!_eH)gwlVjs#-lkqrA>h*dt7{%BF7UUtnaSz?w|Yn;O|U4T%3-g z0RbwK8i5%|K+___lgF|XM-O)gsi9E>&&PDjnYQG)XO4&P;^v)y+1mpI6KLwXj;=2e z`0C4xfAjahxU)SWRHiWM^?P}qu_s4CLRpoemA0|anx>rsh=4Q!Oryp*YO;AQl}&0C zIe3#t!@7t#G(|;FCKGAELK<`!A&_=pwc#|F@!-=%DM>v5MVp|kdvQ6 z(7@uaL~w`=;apf894ObiW7qS@b)Vt|lbcSDgXsDc72G9rhh z(oODZ&@}1;1Tt=s6hTqILVP~VEPB+Lh=CpTq!nqMst`23m?)}| zDrwB3K{8IYFM&mks;a?adtzXUAjV05#g)9bdeBb!VzVj$M)E>>WAhksQPxJ$}Op6%-ha zA_Y4|Ju&liI{os?FWEZ)XrwNu<j1)=$v!xGVk-45ss*4WnH&z8|x|`#4&ouU7}>%^|>s|vMkH9EX%T3ofZ9_ z0FX-IxL4$iBq3;Y#UgSD$gCj%BM>SAvom5N)}&Dvvjiy(QNOkrWH;Am;QeL5gG;OE z{8a-|h23#GSnv1pY*Mub$S5&Y5mksxkXq4{MT0PdMjM&2St|fRF~sVaJ%Mq5X{nXq zGgolY-Pj41t1*?q43U^)1`0*?n6}a1ABYIdn5bXC+L1#ijvu>o`%c|7dB2Ys$@sXS zs_g#eiL%sf{T8tnb5MoNS`$oky%YdQfSn}z-HjM?kM#505X+{nn|d-X$NSCA zo7-Pq`1^zOa8~Jn>*_I z?^*s=Y$1a|W9U+yZ9rYA60>B?B;G)VU{O2BFc^(|=Gy=Umgn^HD^K_P9<+9*IM=G) z|3Wy&D@#Qld9dH|qQ*KW+RNfo*F|1pP};n6w{B#8{Yc8LjFB)lr~KH#sd)$?gtl#i z1gV?gUFN;-^?E+bW)PqUeyKCAdebx^1VoJfKVlG-0}yJ{Rzy3od8``e*?<2JcklgU zS#sTZ9uslRb7{+)_Kr<#w6T3;a zuQugPR;7LB-iUL~{t$8Rdzn?$hV0d9Hqk&gIX-GXjO z7A6ux5Q&=fv8HA~fK}nKDrOpqU@)ki8W|uOGc%)OPH0j_OzuI@pkhqyc?nxTUI1BA z>@G8yaxOD6kwbC_o>SV2iA3#2`Dxb4jD)n(4eZ|(W=KymNVq6ha!8OALf50S}{gR|3g- z@0h*!RaFfKqoOQ_lhI&2bY<38d1hFmb(y`R&?fCAC#yu^(Qz6cDv}LA4XY|QxtYn-hQravpM0{nw>w#1 zTishv$iB1sB^!Qq)y!hu=_@_*ZA@Z?C{bdJNHm$OF|z?66JQ?8ZfeU;p97u?>Y54HN>xYL606~nS@nF0*Awo5r&lh)hcG(v}X;||ge)kVv`}&JyNCt)& zOn`FF=-%B~8{@qP4^~E=_NW>#?NV@JD@d1YFc@6Ac;W32che6#M=yQl`KO*fM_DN^ zS;b%&f-Dwo-e|y7#Xub{QhsRup`{q{f zbN}doU1cI0>*KYxA+c4JKXrPG`9Y8vqrUUbm9M;TseYnLlOIHvN(y2xN=<{i2aP0M zS_%_Q8v&4NEXo2Y-GO-h#?GBPduvafQ|lsv0Kgm=XpHkkquLty6E^??ti0#0%1MgIAN!aDuj?u3(mRW zaOjwurfJ)@tbIDy#@J>b9Ad^BtZP8KX-Y~-xiLgs6a_N1 z1pD*ZYL9Q=&}97}}VIhMXN^30n!8+9#_m0+6V_kdYm+L+9B$=Q+_j zSFG7;`v(X6`}-+_NLAl>mp>|NJM+Shh21r$kJMrnXq@ z-4l(NrLrLkWQ>iK~z-Y2k4N6(%b4#bN=5piUzv)}~tGtC(txDp4fHBrQp|ge4gq zk#`Qw98+Bs?1Co_KB!0`B1Pex>z)|FJXlPlaET%zMpXl(R5l<2BbQ}e4eH@|G+tjD zj)#-Uq-mO}EIm8toG*)_C_)VR917srRaF(L3YjCAQHQ@;5momn-beR1a5-g$$Ebjo z^K`>T?Qj+bm9N~)Bp}(KW;GK{Gkg?#@V2CZP?@qD|TZLrlh$vdT&DDQ8JkvcdyRRo2$miO79wpbdao9}B;d z@t$kG6M06x(dJ=YS7srnd4Z}U{PL5`e)|pOE6TD(U>UIn z_?WJuckao{PkelJ_h>2r@X6JiKlzz^`Q;Z+oj#MI&>hImz1vqlxc=s^ZZr*pWmk1} zN8_sXbD0`~%XWQY2_*$8667gCSBBA2o{OEk2o+P>bsrdS#+aHpU0R5>=g*yb@!2PK z|Mg=LIXJ?<|Hq#r=!?%^UK{YefY_(|Lbr6>3je2)h8~WFP+bo08lfR2Rn!Fy!X+MfA(G@Ah=Sv z0s<&|+&r~D8dnEX0pol34u0{|x7G)fjg5i#2nLQR3LG9zuUxtM=9?eJ$Y2Z@Kh;l5 zW<)t;lFpwy{p96SZ@qm70K#1U{_p>}Z5A)Tba`vNVkV}fY)fgiGM~?8v+4T!hA({P z^(ptD(4^~BGc^;_R+6X+VvNqYs;cU`>OxB}o#&gT!4^~{#t5K9R8vStKqNA;wl>Oe%RoD!uof0Uf9DkMqvCG#nCB4>qVacxx-R?PyRH&a0V2P-#sQ z(1CneU}u2uY7(XF1nbjRut!|8a;m9Bpg@IwXwN&vW`IN~-mYK-g^W?%iMi@P{A#>Wv4tZdluh zw#3Bgb<^@hLPP}Gzl#K>NdKS-gJh|OAtGfBUWzp(1|u*r0R>H;vZ<&7QpyYfrzFg3 znu`gdlpLU{P1A%B(hCt0(I`=Z#Ds_wGf^=~;DG~juB@uzcs!bnHrCgs+uIu(8wo#K zgCSyi9H7&~d0&9{>^K(*C&L6zq&R=Z@M^VhvRa?@KM}$0O~Yh3SR2=Ie_DDj3Fixm z;2|Xws72AvL}<%qY(hU{#wQ?xNMhOIWNq!%?YrjO(QImlWl_{+IT($KqNvKUD2i0} zClOnEAt6LWI$@ABv(ac=SJlqWy{2jE!QkOiCmC_1OBPH8nu^6JA~B|BwHXn*x^(O~ zfiwua zHp|jfnAGguci;czn{Uq>L>TVu+T8~q{o;-HHaDv6?eS!?HXIJCy4IY*3?YR3J3BY8 z-9FflA{A1F)~t`KZ@&Ju@z8^{2;x1hO~!C<24)8b^MCyQk9HsIUb=L?EW7|L+IHvO z&b6zzuU@;mvpW?rL$5$YY{Z77D7{KeGp~!RQ+Q&3cmqUa0&;}UJaO?GFF&_`{};0+ zBKY^;zkTQS-#zohxu>2wx3yk7CIB;~y}hIRJNvh9-HFCIa=c6aAZTPsw6 zNyeH-;BdU-vg)4e704h!hLp%hK&XalgvX@-*wKk_sZ>+2l-W#%3`j<(l*QtplhN?? z*IxPHD54?lQwHV=gK&imJPckjRO{F6^S@uc$}44S6Bee3RrAKtiq zcX!&f0zPe*gp66eWPrN8z5d)Ymu}s;t^zICPk-_5-tN&$FFw7wxsjgJ2M>1N`{2qa z*KX}j#jFN(fRO-mBJwdJFC~68rQinu20XL1@ttqJwsYtE_jeZ}aOdX1U;p*@-~P>+ z=bk=)YHOpa%49oen#In&yEkrJKRi16-uM3G#h0FA4WNK#1VBj{C)&2H#E_I|$rRl^ z<^+Jiz?yQbQ6L2mD-l1tm8z?&q-3IW*Rky5Yqk!0N%4B_Jv0* zymMtyB*rVPB=qIv6vvoO#t6;A&1X|}zN#u__T;d;M|*v7zcvyQb?nTC{PPN6D|Cqj z1W*L#z>79ADw@U^k~S!2T&g+7pcKTg%U+X}2;mNH)R|-;Gc}W52Z<637JG;iVs}sh z0!wi~iTtFZLX1dCKuD^xx4S!^&wIt~ojZ3v_~3(AUU}swKl$-*e)GoV%a_tHz&j36 z=Cf&wR273_NbBQzV_cP0y|p&HefR#(?W=dLzBg-{gQMxZjd$-{Z)5ZF*I%zE>k$+w zyJrkQuseXJ`%Pn*&))p$Pk!-F-#@s0Qx=EXEF5c+d=h4ym8q^~sw04EjH;j!)zA!0 z(kPOETq*zz0Fap#FpZ1EKmjF9CX(V(C56$dCG?Y*#8jhP4I~^uu7)L=z4$x?nayTV!fbjpUn~}j#oBmMm1QxTrmk4u1o4HdtCGsn`2x{_QEJR|*@$2O z^f{Uq2#?4`=yTJ%zb5HAcoDk9t@x9)i2$>+M zhbi^c2lc>A&!0QXzCa{Z%}SLeeZG@krG(}#zVk#afr!K5aAR}h@bGA{Sk!~TiLOu| zovZ*!k(eCv8Z>!Doi9t~G@Qr}Y&x}cjJ}nRWl3x`f}*O5LG2z^&L3mEewIBjy}nf$ z?8CL!aalfmN~YoO7)NLbXkVbA)klu8bKBcn2lEH23k3qiMWAap=htpV<~gCmlx~uJ zJjsAxGF6V0@!(l@BFIp?;)}R zh-n*Q(*y(uR02jYRx`Dj&}rQ#hMF2;CSZcVoe*8S(+EMzX$PoF`oll?hRWhcKYDZ8 z1eNmOAiVMGtG|BdI&<>$YUZd(h%tI^+ZWGlpWAS(eUJx01Yj`9s7yeB1|S~4UX;vz zyKav1dfuaV1*u;;baB~l%OR9!j@EE25Jb5X&Xg-;?kKv{_Z#a?jL@9 z@BZN;R(BS-w|niEzxtRQkoPfa(*!ayOK$1*<>$}-$sfLc=JY0D$TQi({fBRUWi~(h z+0Wl=1EUr zbqjOvyub7A2Rog&1Y*=SL_jhw5fM=slrT9uHJd%GD`J|ZR z?856)(vr>^vXUX2LtNfF+GaXE0)VRW^`PX=Hnq||mtGpx%bpU4J?++YU5`eiUh1BH zI8_tQxmD=`5qa+tI;tOc^edlqW4N?rm1UXM=n%qUK2Luk5qa-Z=wMlvRaN*DEVM!e z6OrW2CQjUK$`yzK7!*}qv760i`+Ivu;Rl|pvNY^$zbhKly#3JkZ6hkqf(KnJ=2zbRS44dFD_|0#wT^Rv}OasnG|mV8K9YrdSdcOldMzmgR6bY}-~;LkMl#ibRo^ zIBiL9lp=aNs4iv=5SXZmSP1d(-~a)d`MfN0fRZnY@nlS{Aa86?GK;ALPLyXwL)5N3 zNFSJd`u5trb$lFyG!yJB^ZbI?z1`Wx?cv$=A);xF^HyRGDpMeA1)^C2h(=wlwfc`D z0V6UaJ5r#kEMo|Z`C_fAV^r*OtU6)Rb=#7?DRU-%+w-4H5j;0mznp7h)2rY9#;lEM%%t( z@yn;lUO4{`#w5J$L?z_pe-k|AXrvUAuXBID>$g z^5d`@K}p^`>TfAD*!);E6g^Iu=Ry}xMNfE>grU=HZS2+#tEnmD3^!+q`F(u%+)E2d!q5C9oa zPZn5YY~VJW@Mk}J^ZM<57o&h$6htLLK=TD{tgjD7o1a|07ex__7@VVYek7!v zu8AGbe5I8|h+tycqA7whR%n8z8NQ0W!~9r3Qgdjnrt-xbkSS?QKt!1gi*Nt_ z*G5D4;~&3$<&*nOi>lDHBEe(2v1`N-u5eR3z=Gr;Scno2j}EA5(X=ewXgo};pNB)S%zCk0s$F8%xTqoGXiz81 zmGwOeGc`rbImT$(Q>p=tUE({6_imYB+~c{3x@A&BjBV4*=W`K(obpS9K{Xf*3STfG z=b2p+6B{LiCL$6Q&i9kCOe#xY>EyXEWunS4DVs`EYXWcrg781w$n7Qgcg91yo40l8u=HJLkyM!0`~PqAbVb z@y5o+#>Pg|G(^-k&C&E|(Y7iQVhl01ZHSTy&Xz`=L;QR=EhYKyXU>{Jz@ z0kEpB%c^w1o+Fbh2}PBgIZ5k?jGW>_QcC#LE!HyO>5)9rmH*!{3dzqyI67)BZI-HW z_h1?YG_h2Wz^E0I1U%2xTkbbwj$9-{BT_>2#r#IIxUq1iTQm+$D=&cScY7qAqWC6!s*Rw>pNe2_L&Rs zUAcDU<7*$^xV>mK#N;d$Kq02O^k>eTzHssEh4W`TWprJyNdPo}P*l3P=_9c7Wg>rB zreYdGn&2Cej6J{f;?rl(p8M#d>({T}+TTBF+BO|oPM<&X%yUnjIeX#$gT>CBzdf8m zijBj}xT5a$Yp0_+MqnWV=iv0|;dHKqu(?$`POAg~$Z8;E-*xW3%LrO~yRcb_vYBmd z4VkPn^Gmwp1|_}r>T{PaUbu4Q#@law^x*!%;nBe&Y9oN&j|Sz|#^}PiwdbF|{LIsr zCxf!2lvt82UI+>hFP`1l`jg*(;kiq{{>{7ZetdhjNLuX(D0R)-+Z$)koPPd=m-hD# ze)NN%h7iHrWK<9+cJ@I8Eq#3Lm8Z71>)-tP-76nmzrAxX4MBhasVsPHP(Ag;g_mA@ zcJKcEpZ@fxZ3GF$Xo!db0niiyN}^NiLkA9wH`WTzZGt`krW~?Z5Ps#w%V*ARU-|g@ zyB~b~(be12Srem4R8&Dk=eVlM?d`KqJaO^#*{yLoX{S-6I9C({M?^`+v05515W2quf;}kTtWFbt>HlHA(&M|Y6^5C&U*OC!)>|2;U zq(xCg39G8!ezXyzq|nxMsZu)4Xf!Izvhdy|F-XUrUs@|bnUM(@vEyQEkKi>!5lyQD zE+MmsXhaZVoX>SC=A5hRx-838?Sz<##z(PoQ1#?dyLbQf3to(t@}cLmS=+XvlD6i7 zFNup@wb|3ZkFAtB8nGjLB`H?QA_qw+!>ZCWQCeu3JXyoIm{DE%vhY@wb>&pO8FgEZ zMTrLo`#ogn`4?Vz_0?DY>7W1U{rBJdZ~yIo|Jv8S_U^lHJ^ADlFTecKox8Vp@82KP z_15OPilWK>-rnBc-eNHY$8C(Jix@&Bu5^w(qA8&&wj-wljIcP^xqyU@yZ`_o07*na zRB>Zx?{GApoH}=|oU9=hsh{EjV+w)}a|R()Kr%E&1SDRn+;mA7H8YjYCuU|!2vIGD z(6nucF)Bp0HpC!8?2!nF)GS7+3PwXFPJQJl(V`+@L(wrt=lp0`RMmJg-q_gK-rhca z`gFSS7K_FG2M?OI4I##$O$==tL@a_SP&bIrInNHMa8#9kP?dv0g-DE~qTVqxhPGWS znvpNTlnDpkhp2A4Uo}U-bVLx5^<=4ppPtvgn)&;f@?eRA1w=!eFB(-}dJZ81raa|j zCg-pMEnU_?8T69>0;0~%1!$^OSYGPWHrTdIR8RsJ-@5ZP-B7MW;s%p2=xUVP^CZ2qhW%;t-uqh_&aMWR{e zLVD*%qd{F2by?PR;TTmHXt8gkGk~Egwu92W{NknOo;<&pH}~&9h+>LJ$j@x^DNIbuJoilme2 ztg^sF8L*7%9A3J3>e9ut?V^cotEvE+f}qM_iQwx2{6HUI82WB?5ws-#s$Nb z1a1UmM11ne^Z(ob`ag@XsxZdMTD7Det?m)s>+fTanDF&iUVia~7sXJbj>q+2=uJbm zv86)Os9-pMsyw^(+$%3VF+FVN^FYPN262_yl@YuBG#ndNJ(Va zQA!Y&VUZ`6h7gm5&^yPBInd2k=UIi=)swrQFWVhmA4s;XL>Oqkgh9mEJJw~RHn$G{*ZWuyin-0k0=Hx|gl@S{WYnZ!J3KrJA*P1hvcO8irX>#@I`?_%(1EB)R85&zrYaIeLfbBy zrkTgKjjEQqI7#(OL`C6{@iY8COENcR&IXwQHcdO5EkrDYwrv*@TS6$AN{6FCHJQ|e zLq}-ly9};=Oo0+*v1rnT8xBW*{%3!Ngn#ole|>m(@L&JyUwr4=-@bk8#(Xh<>+QGN zb}>CVI@sHtPmju~EFBvdkf}w8(NvigkxW|{A3LiXehUSz{qIf^WW<1}nGMQX4sf87LFrc*sP&zE+6#A*LOX2`nKx z!2qC1oGJiG)p}~^Ga#c8MkKDBTO0W^r-qn*lNtbn0jiqL4Z_CAZA=CV6&RW4a{?W!Go=n!0mIXu&!3;x)QM7GilD|es zfa?CNO90>q*2jY&rs$mWXok`-E;WYzT^=QhNh@tt)io7vR61rO6O(`-7w&*`?o8#GNI(fv!rmipyd1zc9+Y)G0CQ%F76IC%s7X?&a>F6YQBkhVZD9;_=B zrUTIhQ%hg~qEUu*S(KXwj*y5W!wfoj836z!wVN`(gERkO8WpWxfCrTGk*ZrH+Issuo2|)j3y}Z`B*;0Hf==bg99vbb{P zgKvH7o9EA8I6T@vIM_22LIZ+XGizdlnu=9Hgyhg9UwiKgUz$N1B4}`iB`zM^{_xiI z_hX1^SeVI_Z(o`3-`V1F4WHMu=Pv;2psvoIJM$|rHSgk;B*LvocmljHy(~ggVAs> z91aFmQ7FK0INaRYtOmnIGy+Aikj&>qTzCW2&_=~ZwT)6$wMkUK%6lc(#<-Xtg{JY| z72Y$K%qS96C3WQLqL{U9p)nrpxwTVVRLi=`K6jVm_^SE{TuaZhBp?I_P?m)Pw5<+D zqiLLm5CKRNLoNZG(N;HT1Vmu!B0>-dQ!XKq_kMk2XFl?d{WjKR7K-=~;hF5PFV$=yM->efto%B`ake5Tm}%$FK!74sn%c~w zLIJaci?!|!CNe-00J8`-0|TRcJ4$!O35>}Q7G{Auf`a9iK#yjIE(6F$P82pG$JDlY31yYS{)~Zy&-+{!6)|~96kNa3un)d zDp#192!ffQ&70=I-oX!l@bh=xy8+0ca%OAeiHjG!0|ZerGeXdZ1(e++R*YKGxI{US zlC6L@j}`H&N-Q-%vzV!RU3)Kw{os;Ek@kF2!)$sB**66_W0o;vqB_JK9$Rlxk%YoI zo(h+Fv)yHaoM5FOG0_l^6v4naw{uJoK`o~IJzhq2bt#T&nknLmRS*s4DYuIO0f8ML z1WysHNp~Wm0lEwbLInUeLzFIvNSM%4UK62NG_w$+#0+C+!j(Kkz~!NzRuvi zrmC&PCTIwfzy#I>mxyW&W#)}z-V%KaPY~;AK!U!NW?@?6wXTL0ul;RSq7T7z6vxb z9VcH!_TONVDyxKMF*h}4|I$}pSX*1Wdi5#*s@e~K_`}y;`^Ke9m*05v7eqjSD z4MYKBY(fY?SVHNXV@HTaY|PF;9IHwMnTFX87&AoFQ6)x8=|rN< z7NLn+k4pq5#Ht!#3hiJo(RLpkIAZ2?Dypa|8WT^Vu8TT=F)f1BfCgFi3d`nkCR{u= zE9Eo9&3n@{JgUk?j58I(jPC1qy<<@-34E0OV@nkZ0t|*j zCOVo#^DTMjl(9=UiWHg?b=a#{*V3N8pU4lwxesbs9 zW?!|z-u}(UZ@lx-Pk!;?lTSXqy?tsjo|L{cf)K;4+qXab=%d@W586013xhho_Vurv zKD9}3gn3ibPxUPTs_@F>sk~3f6>$w2g@x7%^96H5ia1=APbkDFzPm~a_ap@XVkWXI5$TSkD~CO!4gjathdUqp zy=gR=^Le|xj#UL}&qPpz9v|OpKAdwR5>5ZZ)s#Wb@f9-VNa-FtVw`tn!a|KKeVXv1_mZ-}rc zOCnY=Q)y#J8HdTXA3}_=t*Xj79u3P-a+Kz1zwy2z!W4;9_|a%s6qRF-JNIwB`>WaH zTi+Q@Mw^>!qsds0#4IASFMQOPAxrtORZ276E{fc;yGN6-8QC!y5)nIKm(Cg@B5Cys z5x^W^T(lM=0w8nhZ&-IO!9)~s-a9UxcSPv{OLuuu6sJ#}s_Vhg-oYa3B1AxR01(BM z&K0FYHy#%ga&=kH!=Xd0i`t|mr?qz=F@)y+{T(DdQ=Lv@G9V;IU^f`MqbTK>Eh$SO zz--jEW6S(wV@+0OWGg}P$2ML>G*GZ)`z6!Lab42xUYNI92OZVrbRL3QNS!J@R%0DI zQ6r=@Bt#}uO4kLAiHfScapUHAvgV7z5PV&wXNQP#O}uO`ryXV4!O3HXObEB}+S*_^ z+}qn*EEXwx%Q`2d9rqPJvQ55R3_((ge5ch+zrv1$BOb#(7IPzyQZJFDz#%B z9_(CH&asLmjmR<^(vD%}a@DoW0L=?i7fR|3-HmIvKlx+_V7PanKl|l}h#xb1B8SpbMJ1a9+Rb@nm9GZrio2ErJCMY6bkvmpt zmUC@wZNBir3-|8byL<2Ma5!Y9gM)*&-+KFd-}~e7Xgr<9AlQT^gm$2Vx~>7J)i`e! z2_DPLh?e*TW-=HIM#I{`=8I-;cYk;H0W*2$o%2vJR1N6@B4P{&JBNGsZmbV3t&OVn zwb4;?s7=Gnh|si6l-O0MmLLeGY9grwMnEPuVq{4C2hQ1fjLCh7tl6QF>uHai0^Av) z@`Z`SjEVpRsC}_E8jkA$8<h7h=w_b~hWCI>a&!|9~mR zjmi4??d`Sk2sAh%Hre01Kbs!J7#`feUsP^b*POJgiP%*zuC4j4?E_y#B12mpF?FX< zeDt1;kJn@M(O$MR@gW&2jB7U4S+iJ}+ncp#*XvQ`7GWNtu;UG$9MNG$%P8TFZv{CC z7ZKR;XguE8d5{9Itt)8KX{vvCCCABREiv{%gK3i3Jwf$wFj-$eI-1Vs^WkvVKTtWH z0aBwqH@!~uq5Bp_j8QaonzercLOWT&>*U-|0u-}?4f*C!6G?RwDg@8@gvp8x;k z_x`{6g^#Y`6MEe=Mu}+xgt0s6$QJxEDG=H$~)+i%b}0tLFf>A zpZT#b!@`m*E{3+va+3tC$|2B5fZ)7O|Is!WV^9%x?ASR+K84bdGN75QR#%^XA-bU1 zV*1;Nw%L)KPJ8u_92DWJBU>c|z?%aHDdyIp^ z*2m@aUPAgM8~|z1ekn5~z+8kPAYmGf8?!U)ffm{&NFft@UpOK{&XI!#pc+F6Y9L}U zq*6l7n0ak9USAt;jR%9GFja{mVM|lD3{BB&V?2K5@})a>ckEzV1r}8^Ncqr3Sr$b( z8BaFXH#R40o;}0cjd_5u_}gpLVL_mC=kX ztuQ^Pq%ZrlPhN7)udlCPzkYK*n~la}?cs2pH1k+~)T690D+7ip){7God=fhO{0WlQvUox31Xz|upFJnx1mXg7f7z|9w~t(0Qd&cLY%o1PM7Y{c zJYh0`N1F-_R&1KT%Z7w29mcGvMfego?1!6#U*NTU8OVv>qQ?3{RRS}aa|&QFf?=Pt z@o<-7^~UXE{<;V@eCFAUTU&p2{npOi`+FfOBt#;1rU6g_DXZf0<%{RepB~igP*7u< zZzBA=`}(2)w*L{n5CCbs4Kp*+O2Gl% zIp;kv8&E4s9g0syz<_|Le>zrvOHU1b9H3a2NXFEhH)izSIp>&t`t8mY%$$PK36Y&E zh?*9MgSzWf0d@L8vPVDdt7M(N5!F|ah)as}N^Sx9a3$&kIw=7& zCxXV&bZVL3h{W!2Izw`sn_FhU5~!F;ofB zn2{ZJlIm{Q1PtmC9AeLM6A?A#j4G8xZ}EtO(PVvneS33rP?sfYiAXA_#?X0XRKSc4 zD(9Yg@`=6u!(YGk{*fG_bAnL#Vl*00)+Xy~>ucl5#$>WKo)pZUx$urXA)t5b7tU-F zL5u-F%hC^q10+^-kqE^Uu^Nu{0n~sIVTB!-9J*kudz|(nZ-rx8(-mKf9e;3bwG-|c z9l~MT1W|NghDWpZ%;sQF`B@8Sz>G^s)AC5KghpMPmk}MYa}>>(kwGVuiGdv)9u7yN zJ}9jp#HXdBFO`<$mxt&CW=6#8>+5Fv;K74)=g)iZmn8%dAS5dBYG}=|E=DK92cTYm ziP)8fD-K6MKs6>{axChspE%$Oxe=Grgw?iuzxq6^OkYvYtjK^@P^0}R8h_jUuTSq< zR?{cuaG%3P_?f5G$8EZwr*e8Y@aMPqQ(sJ{{}AWmkw2`R!br0j#wew#n4;pz+2~2F zAFRkYOhlL+f)LooX1%s?=|#JM1S!;plFtrJQ4?C72mxA5o~CR``*+v)`7L^Z{|>rS zkGN%zF@cYrJ7}55o0Q3FsS4_}`8kZbuXy?fOb9tWCczX4u`0^K`@;K&dCCf)pqOtk z08`H3aO(0Xlsg{UG2L0Gt4JE~tnwB~9>Ag~O7F4o&T;Bm_0GW__=n7?(n3NNQE5u= zm|ZFzPz2 z^PIvq)8Hu;piBgah4;_}FEmY!yO>Y+9_$|M@9!TR%;)nMQ{uLH z2QfxW`3-%aAF}4;apIe#6ZFm(RWTZGRMlWm4~BzkSXafM@?}}pBUjXhEQW2=QY=cA zHFlF9Loy&doK6o8rxz|jye|=x z{JaH3X4Vkriv|$~1K3#K9FNy_A3QL%!ufh&RT+xHZEX0_cr+f9E$-a8b#L$9wJ<-N zAI@jY*`904YK-Ox7!Vx0 z(hth&(#4DG>+9aT&@QZ*F<6nOjfriViuXvMW_W76_N}kJIw?kPz4y-1bZRNKyzpzj zSTBmPo|F)n-Dp^ihnsa-b}_#aRYWx?wnnT#fJ}yLkSgI0yO}O^7t*5r zG`wFba%@x=07}O@;Hf}NBR8nCUCdi?pRpe#%wC=(CCb2RFOHHX zXeon3!=;rSR?mX=IfjX!A!A8}9WBX}xZ;KQq9pe(eY5=ZjG!-Z-~FxYfOLEz0%9gJ zW-_r8(AyJpnTIDestOQ^vb~*w94QhoA!UGOlGgX(jlG-?xG%H+{WXeK>&wTSAO6St zvd*#571)MAY8u573J;JGD62sMR6!)iXf#ceR*NJ`NU*-Npb*h9f!;%RwL@S4%Fz>+ z%DWESOsnA%u%fF7AvDb*d9nL&+_kl}vMiG*wKGj8W_pra^>Qd;?qJ@gNLCgu2j?X> zCTI)+K%jH~L5do5Y?cTbc(OvZZVZ7v{_5nI&P>G+k^6y5s&RTVpc-nI*vQNPRutSv zj;#v2jyI9hzZi+V_vyOC7^l-|syL61j&9w$d31Q#HjPSTW(0CfMiyg?(yAt+m-Q!Z zg=4a=j^S|Z+Bxqh>+6BMD~IIENN%nMQBlDgHe!uf5HN%^ndJ=bq-BE}9T?udbN9-X zD;FB(?EcM976%V3w6U4TrqL*_s(_KmrTfN^G_PsE z01W7fn3xd@a)juJ89_xwqsA1cllH*u>rFAm9toMaD(kY`+}vDWUmK4`%)D4Mi_oN6 zjLjf90}xb#iC{J{IB!^NtXD6;w7oXIdi~nbd_G&uMI_FrhbrySVH}ODS(Ig=bp?ZZ zI2w$H^=Md61_S3f-+~}*Xxk_NAOd9BN5n{uNV^UBAz(PJ4gs;t6ITT8+_Rm!XgOZY zPUmzoNc*j6N$QEwlmVC_s4xPW)ZPtCQ=@_-=LmN~AjH_0cPbh~h*9VBX1a(6)5YOD zia8*v>w0Tz>*(-EL|oxlGY?k#rg;48k^ct(s|#1H0RR9X07*naRI1wA+T7pYZcYOIbRK&vu< zd+ziBa0NO0WC1#KI{dGzW)ht!X0)`U-@XJnB zYVagYRav_JE9oIJOHkEJ5y3ff&N5vCkmH1775z5$$$ z^4#C}tD?hv3_d=AUm3JP9~fv|4U}GON9b{klpMHb%Vb&TqHj`xwIX;u-il7@83ja0 zABgw9ZQFx`gT1}I|A)FaZL;IY&NR>B9?RV_k=R!P1oy2}i)!i8sMKAhmd*T#=`Ul} z(`I8f-G6DUKaQr&TBDI{w2w-)kyXW=AV>fNi9M0~-6Gu2IrG6I;@(UoP$X-SR0Shp z%=N~Na6f*|`#$e;UkM5qNQ9cg!|e@JkTEu`__6 zLZX$$y?Qn>^JQV=6q#IB_WDJc=S7}qUeruFQpbZ*x^^Av4?cMRwbx#I=9y<+fBk0( zN0MdEJM@kvN|1U!kKQ|G$}+E_)7ea-Ip>*OT?cId_Zqd%GS~0-vn&&V`Fw6h%ziK! zNtiq5RLy&EDKFAOJ*{SYVg1gnIGioEx@9gg0y?1Y8V`IFtH&vZ%Z*OIJ*30_+-qB-g z>`tz%3>`N(nB`Cq5_P?EPVM{F|B(zdF~$&T z(G=cW!@^sW=BVVoFN$I`8Xi4%G|Mw47LAAq$YL}O2<%-;a{+ja2fC zTM#J@)d?>Ct|rOW*CtdFrFh+Rm}oKQjXCd7Tml{{)cY4+Y5i+2v%1+x;8x`IY-zeB`-_M_kHJX6sxVtdZ}~P{uJq)MVQ=9F~+*8V~B+0yr0iz zAw(0Y=JVOCIYZZV=$AfCKcNvDwLf4#hGUVau~;|Jd*|4r_eEJM@^mVLes67UZFOZZ z>=(nqpe)NQciv|QxL-{-(QyiieEDsFA= ztUuVOW_75QfbxueQMfEm*00ow#DodUJbwYjZn>Xl7{Oa@Xq>Wv?8LR`Mcs?~+lDEJ>|lRs4%jKKuptb0Iz(zH#+G=(4!{u>j0jNV-Z_s1 zW?Fdf9ReUYAhVp=W6I!NbkhL9fbz18$Q%rvajT_N%Qw; zv+7{y2^T3m2!u$?wlW%pI&5!kojiF`Rg#Oj3SnMVA%@0mtBQ!uyFAPDJo8zv$TII; zp7D4*{q)xD%a<RO|u@V+d|ilR(D(F57ThhLdrbr^7j$!Vwv zXd+Q1#JY|#22)|8MgOC9?lk=>QH@O<@0eYdcPzmq7C}%jBt%`v%#xBC%rqT^i73l5 zx9Sln6+@+ z1)GoRVQU5^n1ZTG)T*jdgktKG)peLoX4C0(KA(qqRoAsjXzM}M1pLLMZR zw($Uoyl3aR-|tga6lICXY??Xtj>;nIl|^1;-g{z)O-L^#jc`H{5<}u~nBkQxAKtie zbm~uqpKm*y+K*_GVht0$K&1ccrVL}wIfG1H@DW;A0RsK zy@)VVmS<)d>sUb*qQq!saWbBIW&nwdsy3Smqvn}c2|4?noylZ8GeM1jNZw`rULPIL zLJexoe7X7k9Rn8Ltql94L4Q>C`dL;G^_(k_aw10P=ViXKDyyprcNtYhEyif=-szZB z>QL975zztYOruIbFwZW}iaaliqL=x?xs1t0P$Y*cNi$582BT?;?20U384ORHI1y9w zb91~PVoFw#6yIcKQH?sHrX}|_Apod&VoK3&o$$JKGVlTg-h55l&N5oI7q%;R+9I>0bxENFhF~E{5ptj1xN##&M0Q0{6JyV7!+lZ=NS?y;De3LyAQVr z#3g9qA{8~+VX)aMyV%YH$NJ^tEWv)rvNU|;|~<6H+l>~Fvd3g z-K2RDxU@a1QsTCBqeJKt$eS{f5sg5bcC%zVDWlA@M{WtScYeAoEFa2^=;OFsAJULPh7gFn1LAs~|ph40arT&qntPj)O@l;|c zi=sa$GIq;Kg#-PT$FU6T$xl=3yPi&GG1L;p)Cj?QUlf^lOzkNyRaa(~BprlEnIp;` z!6+DjrnMd$6`z=PQA>@K)y$~bNFBi~6chCf4K~!k;YY2u+qm>osoJJe(?)~Lo{KbFzU;oqh|J}d)umAP` zFwqO=&ev7_V11n&6B(lAx%b}p%M(XdR;y5ZpZPJ11_T?8M$S1^A;J*CbXpmpNCXom zM`TeV5gL#Pssa;;sadU_rqdWh!cH*&vSa7j5D-m3tZiWd0y*^N^1MJKGy{niY7rGc z1tuUOv}z6nF0oY+6;ME(jR;+o}^@WS+?pJ0M)B@|!>v(@?8KGmECwOsPB8ov8^^4pA6^(G*CVS};AC zN{t}W5RDu30GL|$FtoR|QA)T$AOuGV3EGOv2^pBMH4Cdbhnje&2Hdc2)2(7+hTszO z6HEb6lO)s>4IGgpcBFz4(FlzhRCKP9nMb41ysDDhz$_Jr3uAklwW?ViLKIPvC{dzR zp>BjJ006KuTFuB0d&ASGPVS7yqtzovj~`oEU1eq@BWrDhDTCS?go$cnfItL|P!>hz zy=gpq_Dr7V&N(D35=pl4?U|o!l>M*v#uiP3NEk`qGY_t)NwEcf~4G&zZwDe!a=xh0Ck{;_6-~?=-hHCA~uPUGf z4C%1m<&!Ta#b($jj?qA2DWkp(8PLyBA$*=r%s)>DaR0eNe}mntN8uX3!8>x%WUG)0Il=pgtb418y{D>Dg0T>Tlhes{3k7@?e-aoIZATdUbF{%iFdFL~i za)^-#x%KNbOf}WiQe}1x(rSr)WnCT66f)LTcSL0Ss^O$|pyj(|IXW}l?kRbuTbG)y z?Q#>^ED6LPcLi_>{@#^Ru!M3*{toQ0U;7Zg`uTXY*IdDZ$_IhRR zGw*su<~=bXpdnE*UIM0!Fh~G})LlrTz4R9R^d~?4qwoFE_rCYNzxmt0n$Kom``Xv< z-M>GZP4YZT(69M?7V4@j%6`8b(jdgJwzfK(orpopvhTf1gVz`(RbxrLgFyX3kBR29 zIht`+0B{`?LImZU3Bkn(3Y7lu*g-QM4k$7@dfd=pB1h zLGA97L_ArzoM0-jXmO^o)?}7`IHDneff@oZH4Pe3MKmL}?i)Ab5KTuWfHc7) zqVy>WrYbs{hk0FBDKDz35}`vylOv`xk%+_~5=5d15VCWb_gR(=%aM1^JMX+>=G^6M z1ZwBboqPDsJ9(b>`vYXw1ShdZQkLeV%#56v8kj7a-D%|f*)!ny?1hsJcehC*HcsUT zYI<#%=d)){?(FTk#~p~_G5(+@t5udJ3+X!P6WU0RcJ}tKl}}J%9XQ%9>Dzy|Pu9jgT7WJ~7AXl9fjX~#(@8KRO1My9<_?~_59r^Xx7u4p%_xCa4v6Lc zHHwxFt^4gahqV3e-IA#r9YsQ@>N?g@LLCK64aW0IiM;o{UZ0TY5W@Q*&)|XVzeiCf z)}ol2vOtBHv#iMTjF6n;R{sS=m}Qw`q6Iq!9J|JrhzMq)(lxvn;*jQF%Z;-`TnGnR z?A@37$-vJq2b0kS7Rf`5uA(8u4Q-NiGl131w5<}K^jt~$$Dk3SNHg};h zrR+6i1c%UcqyP|*7Skv+BL+iSL^DzQf#&yHWWqJ5yr|fkC6fqOn=oxvWKIm)CJ%kqy_OEM;hW;Z2OM84nUwK8_;vMSuC<64x|@P=%(@NfE@(xgsygJ7Q-KH|Db$5p~WMd*t^2Jcf+ab`lW) zo6qNozyx4KlsMD|z=)pNrzOvEcb`xz#iV96!4709A`RA=mSgn}G_IBlEIR;i>%e9Gsj>-8aIAZrO5q8}k}uvV$K~Hj+m2KSp^hPns#xcgOy~0UfUZ%jlh3Cs zpGw1CuYcso5k?|JCPF4a5YwPyOhy=04I$+Qn;8;zIYQ}rA|Nd)X;MwkFXnl!<~%Vo zr!Z;{lq2QHIryM+FahAUu4)42+d_?3M=Q>`x(cZreDlpW|LI5n^n)M#V0U*%L|=dX z_0dY%>*s0dMnobk%U-|NzjW!Dix)3dRXBg<#{2JoxVN`Eo6W@3h*GCcGy-U5j@i|9 z4PbeeJI5ge(FD}QI>bGhkn?44FdGN4Mp~+(NXSH*7_Eu9plWKO63J?TTF?`61Omv3 zRV2m`m^q{on&A?yADGjE8AYSYcrt#tv9Z3fp2iyaygG{TK<-N(|*5>BsXfQ1DJR1%( zpKL3PL``I8S~0r7ctmRFgQ*SBG^r5>!{Kl+c<|uCkz+@(c@rhZXeNjRV5$)S9AWa@ zq#s0SQj2JaiIy@P4Vp<%6NqT-4%=*j?07U?xJY(CybW_`6YI;(Q$GJ!Ay~S=O&d9NXuB-c6ttlUH5NU(G`QA(?vBQi-s6x{ zHv)k+GTSC4tI;<$BZ?I5%$(ZMv>bkx<{U0HCYKl_wj{!8n#yfPddqw~5TcYMeIh7g zhQJBwhalW!CF8GOfD+M?5-I)j3yf`BsKFtb1`SIIkO7w)0?Wg(e+i8`RjunfS%rJO zp7%K=j3T6nW9paXWHL3gP}eT=oO+aYQ0sNTGYCrrolXNZnT)Gy27r#4nTy;3a$YVU8`mtJg^l<3{LE|EF+QArJ3 z6?npKRcRTu&u2b7V}T)0Z!O?+^d*Z~ykM zZ{ECl_T0&$=d+BWJm^7nJj;25bmJxa)2F#e7 zs4oC96_qqrUT%p>u^sH*qm>^|E0lvUo@(6X5AULgM9<>hf;pW4QoxLM#$4;F& zvo;(RnI~LkG?=N1f>F8$fs*VUv`uY5L`;DbO$3i=S(Ym+E89EU+uPfH)hx>p(NK}d zXPI-3&=OORmXrVlKuK{yxH1~eCetp`CebPs8ds>Isint_`h$^sL_W0uBPnz~?tNv` zfr-fh3H+mfk=FCsnG-t~(xEe#NB`r#;p1YA`#7O-QVt%DG=FTf2Y?VgyQp>Ju1=`m z7I|wx04_)*q7VRmYP7cAj4xPb9Xi_hay23@`27b=odAY0wZ@qhB^6Cc9U=g2vJ#V# zk%0^Di)u_} zRcw^$O{tGdUh#x4==9+Lz}%odmM~QNrh%%eOEF6(q6kqIoqPabV(%9z&dZ@s%OR?r zxIR@XF-Ak6beuhm0CynMqPugtpzAI|BC3jrn9^bdsTvgl(#5IkP}d>3|LVF95=9dZ zYf;N`7x~G~42j)xgod_Gaza!CASMG~5)eYjvOLd=Qzwu12Ltww!Khix&0rb5*jVv9 zUA>wTfpeU(3xotlkm7hr4HZa$1i_faP#fu(E~(R+fkLm>%kpe_lzH{))py@{=Lg^a z{->XQHknK~Nz;iXS`9JtSXIFt$!_1iy}rKQEBp8EJvedV)JreDa_rc#@nkX&_4dxr zWHL_Tm=K&9l||-#ZYs0sL_~m^lw$%?K?PJaVB*XZP^{~uc}N;kG&L0kb&&Xd5TX%C zEmBGJ#A+x83Mj}55KS!xkAS+69h;dEifL4>>Uuhx&O?pNqt(^2-*aVNRke4naGu$r z%YeNC0W%KzS#bG$9#owH0eH@H&vl+XSg$rV9`5b!9jn7|Wt5c#iDCxaVAGq9Rq7lA zQ+LWWN{xV|!~*ZQS7fE5EO(wslF*Bg!PAll2p4FMwig3n*r0e#L4c(7FQtQ!+0v@s z8t7AXm5AhBtt}=3W~cA=+eK@9a&t_9oNm{Mz-K zmDp&sHd+}mV4BXNCd#Wd>o6jLf~GMyJ;CdpKAoNG_xqc>yCHxAIGqUw?cjMu`ez|)3%t|k()~ELyxI`kdzP_>X zaBDbRId|?H5rWC*A4aBz9XvuT!lj8YEy<$yH(5Vdfqkf2{5LoyY;gliu|Lq943bcS zohysnOr6WSB{KQTOs!2yOL00Nb(9$Ex=y8ls%BZ%>-7>-$~*GTF*j4E28pebmS7@j z@c?>3g}$D^9bl)i&NX1XG?#dUW7C;f!1ifk(+RQJL(EX3L`xaTO>LL_+k8k+>oO<# zpy)HLut8)wJ{I;POS-O7*D8yx6|qY|M`R+>_P4Dx*|8O+C z^z_r?@%XjZUcG$z8Dh@!Jo(Pjm(8ZLjg5`EuFVXI#(U%K?d|RD?ai(2AQ8;+JU5eh zRfQ0oBW4hZNK6P(GzQ7COvEq+Apuk|h?)_RCor@CY7o^@X19tOX)3L(edL2c9b<+R zG1eUCk(rPr5huWNI<=#jrCgNMlC4xij8%-2dA&QGWknH*_NsbsUWX8zni>vW224m~ zswM`&l;uUyld48FG9!b`XBqq5EQ>MD=kxRw_Ep(upkQk0Ni($tvbo)d#h|f;Yh!rG z@*?+HhEO;%W})P9O|{Lw5ma{@bQ2{*AZk=a1n7X<;a8K(v7{BEMlqBEC==$YeSFj` zTI`n2_RP~*g%kQs)anqncXrF+k)6Hq`sU8&&U8ALlw3L*uADe_?33H~wsv<0!#~eFppMNcE)?t>3lHgL5u#hr9p-or1WS@xRE3dXrJDFQ@=DW zUDm3n2G@aQ2$mwcY`-e1nGY`2MN6kv`w~j5?jUNgEX(+HcPRrf^gDa@-n&<4lWBj{ zf9d7t^J0~%Izw*ipYe!3f081F(^lYTL3$#Ln{e@Nc zUM#AsCJ1(4YsV1K)ZM&s|8M{Ljmwvx{~!OSKj`I+cRi&H+mmX?UyQEWyN^A#fXRY^G+wMBJ7I%w33?9>4({FkZBk#J*-9HuB0& z<%lULrWF8Ums{<wYRTbDCPVRY%GQIuIb(1^6_|j3tPd875e3 zUDwn3Y&x4Iby^6LppM@Ax(*5Q?wm_6ADar5mz|02{jBZ$bW!#>=RyeH`@vvX*CB@J zT$bl~p66Nav)r?Dp{~nb>77SHYGstBE$OuzBdCHdmijKwJCUu)Wk#St0w{F=3|L7i zIWu_gfslw>toLH}ib$i;%F4&2GWO*{3#JIb@y`6+Ks_LA}^FlO-xONph?3HA^~F{syWP|fpsW4)hO&i)e)z=DD8>0$W%fV z>UmXfjwkCoJ3Wzm8=GpH@>ra6!=gO4b`${n{eGy6$@VVu9hbQnBPvJ~6=AcagCZu0 zad&5DI+@O^uy*WduRjPO=6Rm(H)y&zZA=t`fvK5*iCMHJ>(IF@)FCrPBv0lE7i4zR zCikg{>1*FPgVue z%xg!EIOe1rUH&Fut+Knxak56Q-<=Q*RJGUZIq&zz*qmT{;=q}m0? z?c33wFeQ9~aH=y2W0PH#@~At~27ak?dqsAbbnmbJ;jO*B z@zJBB-s68sJ1XMFrio}U*i>CXRdhR4a%d(zMvqjcuhAf%* zP+@7deQ330nBwFP`syE7d?>)~q9jO6dEqt@}K2_FgDelA*GqoqGVShiZKSEd0mQ?icV3Q#yT>!{6!>crlXID z;FlECkE-KSPyk7Kb&{UoWnv_JQ62Peb~yON%CEVS>4_`yd_0-N7<1>6v_j45x~l8C zs^+uVTt$$u%K9*k-Ee+&;vK{63H{Y zUy>eh)z-Ay)MQ_haM20AmcN!-fpFTKn)yqkmB4QLc_2b+NwMCr6_OJ$b;6REuPn=c zzi$TfS+%#bJDbg&^P|ydc^V6Z$>_Z-T7?BgVsZ7HbIjy@CL%F}vM5$pSL>=Ga?bno zQBli$mU%xcdre4SyT}rg9R}R#nvdyHFtdRv;&eI*p`Op{sES0R)zM&3`XVn1?>!)K z3OvU4u-hG(hlAmn(`T69>~@wHUwm;e82tFhKQ4;wKmN!6Wpi`=^*4Tkh;=mw6OmZe zweubco%i0kC=!D*OO_RBkMwz-7a2Pap$35IbT*q#nX&AZj#*XfI(YAkJY#ki(JIxp z)oCr~abbLfRxsMMtWi+`OblxY)4EZN8W<87nmG_dLvW^)dNU#hR%@Ks)p$1Bo6R2X z?C#EH6#_iCucmwBab4BU@s7`?^LbTO%*2eUGM`O*{n9ySCUsqFj2;nvhV0VqIh)U8 zn1m>*I$8;XVU(iG^PIgS=Kz76OV?VlJ-f6?p9Uxb(PTEShV3xIk^pznI9VX0yCf)B zgsgOU(FJa&TW6QIp47O(23N4(i#@ug4Hx z{mL`FBC8@_{php5{=1*txwnnvD6nWsYEuDA`J@s|EGGPJ+C%|FO&AP;>!4ylOhlwA zF{<}Y08})+3kWSX&k!McMqm;o0g9N~ZWxS1FhgSpgvNkiq+pej2r^mjl8_Ukk|-n_ zJEdox$g#ur-BENAIG_)}5m3?+s$K$;0fPd0LXvj9jZsCVIo3GBrZ;RR78DJT8JG|o z?HUVmjEV}3kax!)At{kPP|O4U_s>;Xc|^E`7-LlmTH9_o5tRdon~2%V!|nR|A5 zp7+YqFUV>2%tis+)L6NMbbGuWfIgyv*2`ncQ+b$oAG20IZBg|sH!hS|Fh^81=gT{=VCsvcRZp>pnnN4=a z)4h4MH=E8ys_9H<8<|6h(KHH*RH9pTsAG)tYBm}SdcATm=;e71p!2E%mCU(8QRYRj z76E1fNR;r*`*i1_iD}F%XY_;) z*S@_PldEkJV?dBpPlwK8TDt6_Mcw5h7=Wg&nxJ(lE+$=x-)f1(F&GSHLDfv6TI(r@ zQG+y|#}I;OB+e*l!S=6{?F{W;v*r;Q_rlHVoF5DZo4Y&dfV2#BSUi8YD3})I8A5td zMV4=GZdJ3HANDnYz5ot_2T})XAyg++0RdFdwnY#2_@lNh=5*bAWsCmcQcaiC_!&EL zz|4S(@T4T&LoI}9*ov6;*7RqQ_>x>OW=(e0=k8lUl5;3#V(!MLw?Dplw;1-Hd+ynH z-n;tYCl6k@yLs{aiHri67>XGwU<6i64HZG6@wC42+5PL+Z;iM20I)3kmo8p9d-}wY zBSn_cd_I2tjbCnVOxD&;f9?05>-8BdyY<=jJ8#_(x%=`f=PzBptU%L>Z{OXyeQV?1 zy^VTadyl71tv&nPxwEI&3I`f1k$C;){VP{KJ$iKX?QcC>pduKUo7Vi}H$J@gVEoEU zm!Es)wBsse0yMHDGu2otDUOb;jJ7wo|NbA|Vc&b@<(EGE=+nRce}DF1Bb2@4AP zU~_^MGAC$Nuv@q8fBezSt<718Ru=B$iM2~lpFe(Vz=Vb-0>60k+MWA57oNI!jD z`1%V+1`de{T#WI`wYyiZ-G1i6v9G*z(M;z-?%dzJb@$<&d+Svd)zFbYwzl^CvzJew zK9Xf*CW0)ORp92t6_aNTfv#VD_{sH~5W>k5t1rFsLa$#cMdXSW{SxN&QDZ`%;c zqC9){)a7TM8Vxgs`OePPn{VBi%-w|x$6tK$Z06=50g<++@fW{*ce=Cp^iyZQ@|Bke zYSqxi&+R{H9AYXwlq$FId?X4vBL0RVv72*yGYCi~8dK32L!M>x`E0zmBO+Orm&IUZ z(sR_Sr}9`6&JBBTmT@3U<;Th zF=yzS)_A$=tugPJAnAek{Umu0CUSzea?fvO^Elc!k+?|_gLR9kQXf-(S_pb4WXph43i6tgD9 z(h$%pl?1SENKTgERUvaE%8@wpo*1J>Rjp%~%qM%Z$vj%E7LzU_L^e>sSrpTdA=V*O zb(qiQyL)@9gF&w>GtWhyXSqve*3A21zrVVA1c~x~551pNRSflb&*z@Kqs);bRAw-6 znO6}+R7wCtY`Ezr&>YR}$l8(q%8DQeY5*`@}$HbKvV^3-jVjsF#`m)7_DK{w-ZmWRC-fia=tk}y- z0-B7c{Xrj*)uc6tB^0EoLGnpBY4`(_A|kb;SatG>FVT%}-@-18!n4brBZtm8-nSop zA=4ZlmKJ=dm+;XD6xhE3;L=uvinKef-u>XCS&)~1?}hLD!MC?3vnyAwzklWWv14ni zz0`68H4|$BJB$E~Hnyg3{PN1%?|rnrTlKPn5JS-SKfHP7_|ZT3AHII!;u?EDTs``; zpI@I|*&2uV&2N8oI;sBp?_U4p`kfb^9}ZVnf!*G?{>3jp`uST|r&CiQ?=ltn=#zWb zZr=Xtt1o=@)n{@SMD+gp)*J6$eg2vAzpu|4HzSr>^y(*fKE1tt{``4ECpN`4RyU1| z4OEdh>wo2|-`u=&>&mtF{_Y>%ymfo`#*Nz#w`LcfI(OlzXWx43&G~HB&JS=roxk<& zl{bF=?)t-V*;_+&bv=9c>h#>^X?9j?(A%NCl{Z) zG#vClzWK@Sc68V`qiPoFddxKc+H04b&(%~A0-7Y74)~q%{1@+iJQ$QOz4FZJ$S3bx z5V(2k!5eRVSU7v}xeIyb>skFzKYioMwcF13iE@No6|Y{~`1tz$Klsk8FTQZru_>aU z3rGP0yq^Vq=k1UG>Hm9sI;qbe9liMCGd|0s`uh(bzVXJJ?|yK7GOvmzl8>@buY!e`Rkxd*iK}>zk*}UO0YarRnQ_c6a?pKYNSCo_pq51V^j@vTqRf zYd~&)3mvS+wj5MLs6!p5vuRz=5veE&?|q(SMOixMQ%9N5B-RpZGav?J&I_L)*WJt) zpo=B`mF~{R7K+P#AZa~-%T09W)31aFD%YkS&9Wpl7m+&F++ZiE%T9iR1K?0g4K7dx z`%ZV=_iXU=vl+Ar&1P1XWioiT1O)2!%IVbR^NN^EG)9rAA~7Z@Ron4ObVM`jPS2@~ zbSWd6T7Oh4$!b@2Xqo{{fi;*{RUPWQ>?t7$Ip5cWy^2}A*S_r`y#UVLVhe!a9aN!4O@EeAPnuHDn&bhPa&YnGYb~>LE z(U~)6vMjrH{aQk&{_uxC{J{_Y=-+(jyVtK@+uhwn6cdqH$510Wi6)4u5kLq1J`(Nh z1ephk0%l4w&!;KhKL>*HUZLY3EM-Bn9Jga#s(V|LIN+t#iBAH<;$XNK< z0o6dzYEd+yDx`Lhs;YM}LiCh57bUXeC^5!3o6YJ_`z)Jj2x<{9iiE1d7*uq3GOp(H zp7$$d4-i}=Kb=%{<(Pa!(17V|GM$Wv{od)*r=NOC&!4-n%G_IDzbm!WGTtN4#0;53 z=g0tnsl*oV(^3Ev**@bpH4|#2Ry+dBzOgQS9-xi^*fnc`q_a;dXRy~RXZJU%x`rZa zIw>uAxIK2@{^8_ez<03BYIHaVV5_UEh%}u}Rb`oelCY?-Y=K{v=(ew}@Y$g3&FAyR zLb#BKSZB9PFTr)kxYpYP%gm}L!Q7vqEN>%hk`m3iMBjDD$SDb9IVI>zYIdI>Ca}j; zV0NI`N}LV=04nd?zkU6a+r!n~voBs8trai7_WadrH?Lg1`OM{~N0*K;djn0EQk(b! zn$6|Sw?F#v&ps@A{cnHktCuf7%Lt*a-~8oUAAfXB{_%}J>HYqxll|vke0Dsszxn%j ze){?~!?o@0?N4q!Jau;Mo8S4`@ngqp+RSeci3svk3atGXK%benaNkb{`E_jpDoMYY&N<6@%8uKyYj;y z{c_mPpL*)7k*mcE@aFb-(9bSke(LPGBdaUruwVZB@Bd*G$JF25nf>f%KfnKA@6uBj zzw_PiuB;BE(M~l?VE`1xI$9kJn28w#00}sY##i} zbMsks?W2#bUA_9#pMP-d*y!}>fq^NCU=X0K-TLDXKKRj(eqLAh^u@FP_B+3K?(7j@ znN{`A-@Nk6cdz$`^atN~<=nZa332s$6HOT_HtNpnAEdJ`Tc-GE{WNla~=QFIhU%d zEAHJM7Z-QC^2y}j9NmSq_`-)PQo->Qp^UjVy2+a^K| z5dl_LS08R}^oCS$QB@Ut$3D%utt?Aw`b)5^b|oh4LWPNv8pI(Xq8LU=0Y6QE2_ZX# z6kX&I92f&IfkS{OW*`Pp#SyCkVltaI8l6)oPn|h?{?_f!oO5}RJLewUe;^{xxvj0O zpZw&f-~8q`o`3$iU;N^AM5yM~d_FT12i~Q?6i^9uT{~tML#XDJDug;sQ6U5)az&n( zWf?<|ASNmrtGZ5aeO=cKR2F6BCtAmamNVT*YMt{mQHfNQ+I>$AA{a;{FpjB<#Ujx$ z1f?J@cb-jDCDb9rI2eu!a=Q;U1R)~SQDR-IS%|R;H2~DA^BA}$Vsa7!D8&YdSyj`? z-ma-k>v_2{dSPW{aP-JP?bKv^_uk#<=GJUBV?ttd%s`kIft)ACEIAAekx0_Xrx|`S zfMuC4%2J2~EUF5nQ($URro zu((uLG)qby0s%zP_UM&-%t(l3uT<4)KDS}7Y4PKJbrjfgrwR^BTxbRZOGVgdWu++c zs;a808V+!OY*g3D-e+-MH17=%px5hd?CpdQ$vJDMtKEFDwF{!_X8&S|CT|CzIFH*c zY`^5KQ^-LJK}z`V5y$)tYy)o0FM zIEADao;v;XrSl(raQ(v%Za#JDsP7j50x<8&a|E93)mN|Fsw@A@GnX!3ezq(!Fe~!x zg_mAhzrS()`kmXi?w>jRjG4Uj>T}!U@S`7H`QZ=WGOdmtDZlgGuReA0ETYzP`RM9r zp~_C4KK=C5PY*|#Y1GV~d;Y@a!v{A${^b4lKYZ@;Y3~Tp19WR$y0^G36JZgTehB_U z(PnuzJ#+TN_x|t|&-KS2e|rAnu|NFY*DhW>a_9C0Fr-%%qfGW@@4kI~ZwF4Dx$x|> zuk;25fH}AF?6WUztdBprapj{AZ=5@GULu+)0vtbn^eeADcly*Y&ud0=1n172G;~q2 zPe1+T&fdclCs)4x-QPcP>bTh~QCrEVZ9^LoI>)%AWbX!B#10^lU4byWaN(Ktoyq3b zu8b=)muJ0m=Pum8bN~K>$-|B5nKP>hY9^v#duQ^~pS=CvJMYbB`t`5A`0a1Ka_UII z4vgHLPwu_@{wKt}Z++{fS6(?+W=F|9nw~jvXHFkKbMDy1izi?I z<*g4t`s~uvr-$WWee2=v&vr(=Bd@;n;>xfGP@Bd!A>lEk5c_9CkBUe&uR>5W>=(uA zaO9k8;(US3)M8W*>rnQ3BC(mL5`uwu z+#Hq-fUq-ePy=W%1ZX^;37?pnLx|D_6fv@6=MWglId+tkvqmZ`ASz-Y01-eEOBR6$ z2#pK~aAjrX#EBEvu6-P1Y$U@=Thxaie)#a=!^@YS`RJn$r_*tk<%9sB-uw0*&=BKf zJO{w>cou3)LVhzb(==DD>w0Z%E%Vvd=H_HFQ4@)AFdQ=T`n~mxe3oZ)MqbA$HqG>Han34(EGkQYR294{CLkz0g8x965E1T2VJceKz&7x=> zV~8vAyWXWR9S>WB#|Vxl^CjOW-&Uj+O!x9j-EI%SQ(kx*$d}4H#V;BjpudE zRplp>EX#pe4P9~)xgSfI~P5Y84%@SxN zl@{6*Sj`j2nDjS|>oC=)_W0^b+i$y%Fkopwn|@V^Q2|h*h=E9>9{_B~2L_P&Y}o6? zP(S)C@Ao9*=cg9|K#}Le;c#ySvdEwBWwwv*WCVB`r9euLE&e(q0O zQtx#tJ)nDcAAIn^C*JoiUApXCHk(E7vge+C;gcKpuU)(I@U`dr{SjboSU2)AGft&tH1>*{4mX zKscRFH#fFb{JlHtfAQykNj!IC5`%MjsJZY*Hy+Mr^LaKL5HcugOcG!;Ri#8{cWtbJ zJUSaiAT}_I1c9hJcdq~a?|6NE0pE`SXt^!cS&;Xg{0!1E*c=&&uu*K_VM9RN zU!s_Z)^!XabmKNeVs3^89Y8!4F3Sa0LuW8}oVRBGiuC`J_omO1T-Tl0Ip^M+nUz)b z>g~OEqp>uA21#%ML6Fpt5^ZW`WLo2JXe|E)p7Cc-jQ}0AOJ~3K~&z~R$FG?d(QEPo0*mM-s?sKq7)SKN7;@IKs5A+@qKeJ1kC}_2 zVCG)07ju!v<8fJ4@ybOdVr57aFV)mOW7?93JJu&S8m&Cs-OaI=Bu*7#dqYS*suSwq zJc%P31fb@uWRYmc+Y0ZaO@NZIsEJ9ujV@-5c9c{RYEwf%1`23A8iP~<2nVdmSH=P; zK)>HRxxF<#m`)~>s;c5lvu1pWjz+6RQJ%kW?(ErfSFXG#f}v7h6*HY7p|xgZG+JL> zQ>25*6reJO@;o07hhF$h>+qt~87W!;0wGq)>Ln1eQX(XVqAfEZcxC30rrBtH z4UFBneP=wI&V5x>QUwk{SW(Fk5g;iN16Cp!g7F>zQCLIZ5LASa&`@vC-`w6x^He|( zVKf?EeEQ<<{rk6X-KvDAMQLX<)5|CciLq39a+LvN)kZH~A~0wbG%&Luk@d`TttywG zLQr7UnvA9$DXn&W1!~kP4(1z}2&mD+5k!nE`srXR%cKSAdV$n7#!T9=`@yBQGg9`X z4g?TUWd=~JiJOaK8Ud}PVLub^4b>K)?FDpL^~4hjdA@va+(fzh4xE_ud%N z)+k69!6k59VlpZaQj(>ySsDxm0$ zpnhY$&jH9KA?UsPcXxLm0;+(y_uydnVDHq43<;cd28aW%ZLVH?X3IGVevYcvBo>`T z8TQFqLNZC3BHEq($-#7zt_~GY4570`iAcP$O9gV|HIs@J1p!it{mjNj_Kk0T4p5D% ziLvl82|PxU#mSf8+RFBsvui+LtU(YY1q~XC)jnEOQBfoiFesppYWgUYCK>(2cj z{^y@eXZ~wn`^xh#T(XYpj3_mvCJ}>xf-0b7jU_vu`<;jL6B`>y0V6hT#2}*@1?xlc z`Y+#p^NkOOYb#&)>I*BQo&W}Kb{@{&zjCcCk%Ny>R0hy0R8^IvxlPi^!R*b~Umx~9 ze_}mVtb)$LOoEi^)2d`p6HC$%!rT`J^Knq)vW!WXtMg}0J@eFwU%&Iw2Uk8en1A%) z4QIpi&p*}gXDXG72nZdrql9kKu;~o(<;eI9kCnP~kM~2q0G}+8>lm*QQmsLa)e0Ht zlBXI*0x36>epwJ+YYk}YL=_Jp0gzfwva}5}ud3)nouk*RLb5JvKUP~mMGd&9BGRIO z!aB&fx`1N$wm+WtcB~UkTduViR=-G-fJ+7`O+2%& z0!RNwm73K701^l!@Ar%`s(^&6D}()mF^dwCdL~fQF%%%s+H5L5-&pUr29QxRm-Ld< zmt~&kRR}~t1crbJL7 zvzwbI-g)QU@ucv+BE^-J)ewRYm9a^0FxWpBKX~x)U_8z9ewJlKMnq!_oH6G7`SVXd z{q$fk0M%Q!ZqDbkFrTJbIvlO642JW`1VocO+eo)uo{bMC!ZH~2MPxp&B8W>(@NlFv ztE#XP)(Yi#mzX0d8CAWpdqUj9=gML5h^(OQA-ogH~EM`?zG6t0p$^M9-N~%UR zMAuHwqBDbN6+i_=h%iaAm0^D2;>DAvwp4?!3Wr1hTbpaozxYB?7W+H9C5O4Ma_=i& z8fSvIih~nWVIx3bfG8*^U=R=>bVzaR3xc8pOQ!{?+GSIQ#U4O;kW&0#68r z%<9T$Z6&+=@PQ$|aPjP^)7$-iLWpHmaaAS><*8Bjs^(yS{No?~;@-XSxpU9WXY=>o z`*@J&zxR*6wmQNjm6NA7-}~@g!u-ss(-)pPmFEtGQDr`v8l!6~89`9h^|jTk2M>21 zzW(cLUwZiqsZIBGCf9CUf4IA&%C*<-aks(52qi@X0##CO{Uu4k)L^f~=V~+>ojrT% z=H2&@W*07AK6Um)k|fbZw6aiAQi2cFJ7r*!tbNS}$zk2gm z@5;RV2fy{@6K6IF<;01nPHx`5c76Yi*RS-_=T4nGgFv%6|Kg1+A6&g_OtO7ylTbmp zmu8orzi|E9?HgC`ahdMz_>1RHJaul{B5UwiO9kmSI1@aSQt+EF%2JA2ZavPBDsE+f z&1R_BxH;&8zzX#>;X(`Dw0S5J0|08CIxM7r5kxnK;!PjVh&onW`6x~CqqfdNT=j(w zatF{l+S-0vg~4Ow&++0d029Z2B2el&Nq3C3YOJxJ=hJxs07;TCb8ME{pNYX4i}35l zBa#plaJbUH|KLI1&k|?Iph2~S))-+nCjPw`VprGEhNzhhNqw5=!YNo01PI8eVL?*s zfE=rM6;BkZfJGR1)~aAbYlGe(HO|<~QDPu5CWg&L;O*?$vxAl4&D$T}yLa!_ty^c$ zobB~`#qKOi?Tu?!-+B9;@BZ$0PnTe2zv+n2a{p5Cuug4vbPoG~~ z9kMTqIY5${ z_VQE-0Mr6$!`a4KjZX#v70e>=tj1>Aj;ao>=u`}VKvCY%Fe9V2y~N^Q7g}P8N;(mP z$bbfG4MpP(q6*+yLd-H(GA^l#GE1rH-835gN3QuG%kCDXilW7103CeX@;sg~hKPhK zqmebHD2w@gp7oM0)ZI?%55d)~Pkao<84LywcXuSPP3rAYQKX5Ai%b{0G}wSoim7?r z|E+mJMD=8_O@3&wH?3DS&}TS%7WOT8=v_bUsfJCTZxyJVS6ANqVDDi6;`#Gm`}%9C zB?2KpL15tVZ13lPedX%akKcapt&=BSMFhkGupkU7+VA&X`Re6^;-}YdzW;FV&Y9CE zN2{yGnDKajI^KQx<>z1i{7dY0I-URJkN)b$&4(8+Ui{8~_00$OAO5Gm`0+dM+}T+D z)z`oAoK5T(zjXQb{Rba@bnVaoeCOoJt?jKXXR(~kb{;&uaQ@6UzwuRLlsT+z^q+tJ z%&*`2@JBy>`<=J%s5mj_kayNEd|X!X<)7Vk7~8G)Z2# z{PeB+cW&Lf_Gf>#f9CAz)zwuM3BJ7l@a{{`J@x9BUoZ}g7u5oZRV&pwVhL)I?0g=6 z_S4tj|KK{SnM|g?`1#KP3Z#%&dj9#Rwl^#pCi0?lmbrlT2kz3P3-|8tz5VvP5AHwA z`?<2;eQ^KbK|nGBii9??o7-#l{aYVh{m}kU^S<-m-@CVS@9y4YI#&o_JYY~2QlAl@ zJF)upSDq(RjRaDuMJ-L(iiu4e)P_--+g%Z`kB+`iR^Sd z`|#SeY8Jl!%8M^Ny`4}+iVA%8^!nMeo9|uu_+W1?EYCi7el$t}=BgecAjTOGK7Mr^ z^4WiUVez-~OJgYv$C4MY>*2hVP}5xZB59&g`EVP$+$h~lH00PJ%9Q2U;g#p z-tNJ8sv7q8_jmVp^E^+I^yJA?v-#XwH=Rzas@mV*XXZ3X;#iqEWN9`&IG9W(^ZBeS ztJ}A44~N4#&zLaJ`-9_a>7`SyUnclo5ggBXG0oNtIO)Nkjw*RY1Xj^am?1yzs*F zPd_ynWc^+`$P;6Th0Cf`5ofGHOnb@G&t3%7Teof*BPGZwyeC zc6WAfT)Q#MlP|se{7cWDGsu?200<(ZuVh%vr#ts=-@AQlKAq-Cnx#6(RHO>QBf>M! zoTB8bZ@zW)>h=2{eRzY+ZC^2=j0Ucp%p?R*{q-Bay7KP3o2#3zz53Frlj(`A?Q(kY zXFqx4SFiu)?Tv8x^Dmt|vHA~x_nU9L`R>(^Zr#3h>&Dfaz>+1_8FONDt1NtP#Tmn+ zmF(NU_3E%cxboi3@$TMO4hEzA*{9Ec@Zq(2#nkc3QHb;<5CvmQmb%$AFo(!F=oq01 z^PFXp^^~IvjCwNo)P?PD{e!Q({niH`eRS`G_pTXp8z6v&JSSgHg@du0rr6KHnleiz zu}r`q4is))yMFuD?Zg;^?(UttckkQ;oFj;%Y-2RsSXonHGLuiffr(vxxeOKl=z4ppWJsSMIc?_fAFnuZEtN|e)d#uU-{*)etGle ztzX``t!fa>_SWV%UwP^CUwCFTAO|I&RRim5gU?;Qc<1(w>Ezz|^JkvAaKcbP@Q7v8 zjl>vtJl?}ykEyZ#ZcD4j58knj=@RT9)Yt%2D(y@m+6r`?liN<|Z}^EmmAAs9C|SqS zr`q|Tb1t&!z4zXSC~5w*mF|TW3KXMuarX^T}k2eTdbRF(%D2U(AkG{~#f<)G6*u8+@GxT?T*i<6C$4Cfr|j z{ZT#`uGp14wZlBkE#-!ChbS_c&moj7P(e@>HK^9~QU}h)k2V|*FJHd=gCG2$D9RuG z=*R!~_x|y3|IY9H=*K?_Ec1D>x3^yurL}HjW3!j_vae+a2fOzl+}_=N0DzOpbUvSN zpExlb464eDuyaX&ZPgf>PNy;L#5o&+pQ~7FvMdcDtU1dZh$!#%#D~NhV@W}iGy#K% z#->Tj;>ISSeE^&FkKNt?PEK`-B0vx8(>Hfh%Rrz?t)&^P; z7bGM^Ll|w-DEf}55bQt3fiJ#dxo17dE(&PEL>{Ns^?q z*>q)P*p2C2bZp0gS;tpbZL$-9BeOOdjc?p!4sla!{Ti?lg&-mUat-$$+Ls_nT#_V3 zQ6_0pTM;j|eQsi~)hrm13x|xwEbU2{O)dY!5?L}-Bif7bhuT<7SZeY1r`p#ZnY0(F z51&MP?_y>PLWUx%LY}#AeEk)ZByFFteb^f~X#USf&lJKz2W z0BvopyM#D|G@)moK701``G-4`$z)QLC9`I!8x8Z*XEvRIAbR24iOv7^yGc6QKDFk| zK9GL(%NL(MKVrW(8Vx~$wRCE0W#gN#PG7EecMg2zg@bc6T3K0L9rp8-FsP~_b87SC zcfY;)mCx;t4<;m(4f`d-&Vzf^!>M(yC6-Yq+IC}o<@f&4cbIAW#EOB?I8e5oF|4nT z{+oaJZ6sJ*%~>iXLJ7~DKYi}xiT(ZA!NII5gMv6qYwM%6l`KsR3L6NYf8p8F+b0Ku zr01-NQ9y%q^2GM<{?}Wqh80DPf(IxNgdpG8$_V(mXU=bLZKOTPlav%#dC>2@_SzRN zJ$qp`Wz-&^vrhltAN|#>k8k(V48Rc5sS{hj^X-k7KR?;un-yi5Wl6t37!Frvvzf1E zdCo-StaqVm6jatSEO%lXNU&32ajv z$2ZQUNG3|c^^g&@w((`C3uXnyQW+GCwI@%USlc{l^PyKoB~-PjPJ#{UJdihFkmtpN zyLZxra%WZtgUp)5CDxj@bY>07sMzW3fcMN!P>(}xcpL_6m!N&17qnKNf5lgZt? zcgwOQqBLOOB3l7i{ zI--QgsAkrzt_`0$ed_e)dTuSVDmnvbz(kM>6ru@jd}h-uTiaNh9GJktkRd}DACDLn z093nr0R+)fBpWiDIg#imD(2tQu<4H%TohR3ZvKfHN$jgcRqKNC04sNu8^zYFQYJN68g< z#MQl}IY~XNuOqJwSp+z-xpn8`+rgI-0$OVt{s7h4*b#+l(qptXM1&4(mSyQ=GFus~ zv=aebScVCrS~5`cCm<%>#k&~|Zy{y^Km&9ir7|tmbPWf~fT;mNUgVWRG+dE7ZW=#j z?;9;vwMGM?2^?UYqZ28J)X_`0%r9--aC%!%1yP}h4{DOp;OsiU zDn>~>d#h?34K{k)>uIwW28vQym?IcO3YA>F{$ZN*M=NV9gKZVqKNw$m>y5pg-IE(@ z>+7pZglZK$Dv+9JcRR?je{leS03H{Rcx$|ay~I3qZX*(?P`nBlRg0XY*x%01Y-L!d zCo}-71O&AR+Z%(mQ7#%lN}-gDGsfk4kI(|4sxp8`5Mg0a79?f%Sug7k){Ieu8sG5d z&8w=jLz;TtxJLD6@>PTnRMH>@I-^Y|ztqg_m6ZjL|`Q77LZjXVu4#lUkh$sml z7#j&9q4eb0TI;MugVcaIk0}b9Ka@k$N$QyF#E?>hm^!QwB}jAxh!C>Y!h)r*C2q~V zBt-xp7zGd{nu()|YBPZ7(nOjtA8V+WCBmLCjZ}MMYrh6ktu?|8k%kaV3{{P)MMNUg zI&cwSVrkUx&&nX7G9myb1Rq!!!5UyhllM~V3Ke=@2(jWfe|8V8XyTyFQL6Wpr7R3i2d~mS0zrDR_t+{;prF@XT z|KYnuH75(kVVb6CmJuQ|CyCqK-1NSxs-pJ4&|oagipkE-&U7|&&L*i52~|~jF37ro zo;gThVXZbR}{`(4Z1nBI*`3gs=ok1KoC@1 z^Vj7CLN!Kfl4Spq^JVu5%sh2w%nR*K03pi-f+2nGZR zjrZlxe*V`V-yW~7Zf8kP5$5yq-n|FntCzlb`Rti3ilKtQRJ+nibZI&ylc*hsG0IKr zWaEx@cv0{)Vpwfz5vfy;bO{9}U>kErVjw6A=%b61It`Q_#Sr>iiW>Y|{nd%4*CRE7 zK89%8tuK$V^`9gR=uy?xA>;Mq^G}cS3sqIox@+!)jj4!~Wm#2Kk~l+XjX4TveR{@Q z9lc9NEutWbkL(EP3|p4K&d6&~f;3Hld{ugDZDS0*2t9-&L2L->2nJcUH$E5+hf%Fy zt+UQHkxdH-OWW0LjMl>A<=z<3AfPgGs7sh2ERwh+Nz=^P%(>K>G_jobEAa>h09Az* zjfkpg{0$KRx3^Ec{Dm+6@JBxqkzfAumw)=FfBH}V=^uReyWjo(_y28@r2Rbq_}0z; z_#gj*Ieh&auf6h>uNXs{8=D&&o1@W+bA}8es56+R$z(R4O~>2Y+ga*nvjaqQ&KhH8 zv&r86?rb)zstOV2#mqTZ76ofyNkj0F^=lxSbt0LVF<4X1y2j&Lmmv-IPYcspB0@ue zSX9-#EPP-zTzT0!7|*MqF$WTjA)6@GVd0=4LLdo%BXWeRdH%UemwxNjubn!5DoYbf zpn_@Yj5RT8C@9Z;DW%Mcd0CZ!n59{oB*wXXFtBN&%py{Spa25O8pG!W$ta>{V1hIs z0Fo$b?N_DH0G8OX0%(uIu3@>hN$$9i06{^%z7T7Z%qjKFX{)P6I?aOrP)7_wt5~M` zCv~wWL|9coL|K6am_-$gF(I%CTH9z7q5vWpB7?Lt80_4?*Uc}+PTGMs#t`jl@8m$Y zy!cw^+wn@pgv{E?=-$lHM6li@DDSnF#ob zxe8U~tNFYv%c}CW-LOOimjJ-efQ>i9$>Zp~pPr50ZkO2Rlr8G4)@#4sGDW*rt%rB{ zN1u&$DJ9wf03ZNKL_t*2$TMNtDC^JDO;v+1a^&_uf5KOcHbY)Y|7h_uLmg|Excs$vPTuW^iHX=k`#emsU& zb*M7y`Xf9_TG$Os?!JC4bL2X*8V-9*psJQ-iKt05MedN$KdYRu28j$&Vo4;ZG7%nf za_-!{INSq6n4l9;;ReQoT3cYP#p5Q?gqUTi>@y34F{)BkRZ*5@S*hAa3}eC5@zuK(+e`w#A^ z>JNVKgXf-m_7DEx4{qMPVVzBqyzJRD`oMMQc)% zg%AR>L5$!6i;xJi0H^?$UL;E~Nfk&Cr5)O6ZNIdnB+;W7s>YFNH+{HCk8YcWPUWOv z;*_;M>Kdj{Q>xa_e}n2oU4=k{Sw)jQhUge4K@6GTgAo=2uIH9u>WnT;lQe|DAvhOF zTGA;u;_R~>c`sF9O&S#m9&W&hkN`GTSDiIQQM6&|9Yemxo0qWb)Q*S}l)aQ?SRMOQ3+l$FZRk5q zZ8RpS3oC7kDecnl^f5CLJ#NCHZF2T!MjE=jW;parrro34IgL)j2Dxb)p!7iG& zK*3Pq_y`E>&i^{JPkn-++o24Wzjq+kCpJ{N)X&J`;i%ibSmQTwZ~CN6f9(F);q@X5 zG;(=B+R!i-zBp0yD54xV+8%Ws_>P#6f%ky}lQG7SwU)@>^5X4&vyV+bY&H`BLSsmT zwA0q8yoAlZr!?h^F|c3Ml33( zt1($o4ID&te|j*P%tZysgb<3N41pVW1xS*t@;sZ(nbkUnq8tz@^{k=vsLUbs(o9(! zbtcwYwMIpE%tnj=7%lA`0#x1?MNw3haY-dIo0mlyIH*V)B_5(@GHSF(QH&-yAZUa` zxOx4CR6a{nP&UR80Sm{G3K<%V2E&yhSmL0Q$xIb`S(^8AV@=``L^O3I3wY*8mthe^ zMylb5bTCK{84R;ymUlom-d0XwOIhtJQwd(F+NX z+BMsj3^fu=OATW^22>cXtgMbklUl=Qqm5`CPz801Q+ejVRar%=+oCMTlj&?WpG>CX z$@tF0d;Xm(NYu;o)wMNBoXavZ=#REGjkT6)z7a@m6jomXi=x)%o=-B=JKi{TfoZqd z4WCh_z66zjW|`98;Q{w4ulBK#k9DgM5=UEGeTCGAR6!BR5)ya`ff^H|qujb{6s#w>fga{e}yusEQB-YnZJQ zAt2b=3LN*IN8$#KdsY|mBMni#>3)u3`E*3eT>xyUBScX6|Ix2*!d;Cpwdt-$SHV$; z>9H;h)SL>BS{3++r&Ersn>Z^_St$9s?pH^8Ap}(xWe!Z_D{h?~h^TuY9l_>5iEfYe zbKf1i9=!!|0SkaJCd-ndD3FL*V-GW*&$Bd*qr*6ijxCBb^sI-wd#f88{r=Fc5c?uc z-O>}gG~U&i9H_v|vDnafV7Fcpq_zKM%YCTFoC+dhEr!ZhMVTcANJTIzA7ix7W1e|2a*2*RJ0Hz?(O3r>Q%2>eSu4 z_g??yujb`MB&L8vU_k_CWf5jk3D%lC&tviuvl=32oiQd$d(3K$O;gA0_xJY5B!j_l zGMN@dVT>L2`-nuAtaYkIhqA#(&#M?*(Lh`fyTTwWssb3QF!z2kD-Nc!vMdoTHG~9e zJg|w-AQ=RUF^&y=Ro=LHb37jRdzmGS50>|yMaf#{Tt4X8%;kgL+!t4G+*IL>jkT?< z4d<*G8fz^fks67}I-)9wY7jvYK@j75D{C(A3of3HqtwQueN4CZYHWb(vK4g+pl-~6 zV~bl?SoP2+B3O~Ft97k~O*hk2RCU-g1JwTQs?tQEi%6QLQhSp|qqjPNJ2uU$>l^d3 zT5Ua(A-3_0#7!hXR3hn8Vq@bcLPSVy76k%!g=dijYnXWxGJ%6L{}Jp%w7cs`v8 zv-jSYRaJ#?F)w`OtIGS}nOPtx8*7s!wW}K!HaF5N=?(hUx&F!uIE&Tp0TxvVdaQ>Ts#KKBlsH5_MH$R~JRAC;%RbV}KW+(MX`znx@(%^*62AvZw9Q4*rOV zz%eJ`;hAQgPVguzas`k&WDTN)uQ5o35tyyHUv=^ws4_FwzDiJg^VMs){=(!4&E-+| z4eQ|R<&2c(Pa@X^I)Y>Yhjm$!i+?AfNJah)$jMe_S)C} zuYdEe@7}!|m;vC2KmPIh=Enc}FaKo_-r3!$f)`Mi+8}cE`n3X;JQvr+fS3`FxIKo$FcatW7K;LnLCy zvrh@hlCg#WbUYrHMd1vk&JqzS1Xd-qE=kj#-7&1JPN(Jk;qK0$-xF199g?xu#%v`d zB(x~3A)0VnP+|eEs;OJu+O}D*0y1Q3Gx;N}PV=}%K1*#797TzB&qNC#!*o25w9ad4 zvKWpm!xpcurHa@dw#pJ%G}7Cdg#}q5FbJb4c#)tWKsL!99*jrpJyD9q0-+*B{syLL zy1Tm*ySaLgLExIaAHOd`Gzy& zVo?;#fK6^2qS3@^no>VcT;dWtNK)r);#^{_F;*e4dSCfjRUJ(CC9pDUbgAcHO}*F_ zQxAfeA)^SoJcL_LdhQkw%|D~BbK}INhpHMy75SUG<|tr$z1pCK$BzGwIcD&av4+FZ z9I8(o!t=LxQcApeh@_~BfuPAPMWiUX#YY~choh7p8`880mwbW(_)yjxESr`gpdl0_ zrCNwfbrc;ytEH;-#tU&{%wC}GAWoxdxBIB!qpRy8#T=?eISlhb3`iQ{0M zV~d#2T*~~H{EIrIeq4fyyN}NTrEhy<#82TiylDUGo6LvB%lOESh&jYajWkW8tD*2x zeomWO2n&2`K~ITS?tLiBDh>^ubH*Ze7{gD3_7PExWDOy7X_t$aX!s&En-36CowKZ5 z`N~*V6a@f;5a#o_bFK;;Z)uh#8yg!jN!CBy2gR(H69{T$3^hCD(KQlPU4Ue?;{#E< z0U;sAtZxudgSEp`3_W2LQKNu1anspsO-7cCRREzd4kCuY zfBxrx{=M&g@0;KJtyf-o^{uzws;Y`vXR{fAc<)_;H*eltTN`a`tS3q4z4sOCV&ntX z(&^LZrqii0*_ktEcXxLV4#ui97z~ZU;45d{px+At%F35Tu`*gsTvC-`Jf8KEEb9%3 z#wwlw6yqH*HvR*&W5{sxJ zh72I7Dv?RkG_}SU6c*+{Xo`wKlzs3aehJpvnW9z__GkNh<9(aBjg3`nZ4?q_dDhEw zG6skMR04z$R6#%xhy@A>N#FHXM%=70Jq{;5X2WXtJwyc!A?)w(5Bhnpm(?VB?RexZ zP-|>J>qiZT>LEj8HWoRw5+P7wX6DF>Y=-z4HDlB9cxAMTQ3F}aB@~PzqH{E#O+!^! zn{YI9ZH?!FPz?YG*KsC6*oRQ~YF?JJ*=$}EDyV?*5&}!@4NImZml^s>ZQN5&u#k#*L^ zjfUe0R)JYWga}1zoOrQg!6P_MtqPqv`XbI`s%BDdwbvi{=coNsw}G{an3n_P!z?%0SyMjJa?)Xf>ho!tB4?y_j2{>josbd z{r!WToxKn|vrp4xIOr1rbBGx*Y1%&+kNf?>=Ehdu%dIs4YLH0u0TI_)8|W~I+AO&x zTp$GY-gB^`T=}Z1D(}SyR=^}l0Ki%ef#dcZ0t0~|M6iTtjZKnd(C=r?k}#=SLz#1t zepMAELYNihd|ru6D-M+eF`A^gv8F1+bUNGLA4jKtiNG2(!|Vo#Qbf-@3t@FM>h=2( zR}ztE^#6%_bz>GxEGnuyJ3D{%S3h~_#mmn;eGzd%=fP$!)Jn=*m*J!Ip+!bAAP8t} z)r2g{BA$b1_JLWVEV8CyiE6a7_f>($HBN8Xo}M;IE74hyETI@#7yyEV;DadpP)+B> zy!1uk=VdXgssgk`4WKbr0n^N;Nt$L^uZO7vLtu=tW@xCdFfZoQ*=%KV3ju|LArjS6 zbS@nc8%1CfTX=3}%t|l%Yy@fU_&!fuuYfMQwzn4s_(;*<;RCN_f*mIN z5iS$-5Tzz(cZ}nuW^dPc+#$@QIoj!vM!XKkJv@fP+B62`6A`i{<=-)g%VW-}!!}5Z z;Rt>vM%XgB`M5d^8;uxZ8)StY{yiulK`jH(){A1Prmd|^1Qwh!JycjfZc?}O5n5y3 zPrhA`DE*HGNsbbUaM_yo=neThE`Dl1ifBmF3I(twt^VdYiP*tqwEOIJee^o_>QTVh zf`b)btlhlOwap>|DN2K*S!<Ej)`%DpX)4ZU765dNx)2eg#bTPyi?Y}2#R4&LHJas|OA;rHDolV# zCUtKA;2^U$OPsYf%Ti;lY0%n3(*z@9DyhM-b#O8@=t!>Is3kl42AjIi(N`?qE%aW>} zS!>cH$+FDY)FsXsv$3&(fYa%;-_M7`p)bo27?B{FuE#7ss!f05_l^KWwa}7T2#`es zi?A>QOC4HFh|XCe5{Dd^g`+p71`$v}6bpnVbv94aL6%ui5Xqd&vXqFXl-FZUBBm2M=>1>A+gSw*Z^x#4a&?xn4v7yhpL>D_j|W*_Odi3O0CPCO^r)4o4Rz6 zxZJrcF^RQNxL~6-WouMeBW}udBOs`1m=V;*cNLB2z1F}n5Cj22Y_02~i_3!cxU@rd zRX_EDU7j4pLMzIo@zd2+UHksu{FI}yEhXtBfrA1lw=AR9jVekJBB7xp{Sib{54eFM z)~emwvyrMqM6La;f+($8_;Ji_Y~mbv6ebUJMP@@UP;(L& zs7J8z^bmBa7;S^GR^H)aLL4D)G)Tr6W1GBci7AVRN>5&P-(gWx!=F!VPai2(MAq7N zK-n=>y%4&kVT`KzyjY=TLoo>xM7q&t7~g z&w5x(PmZ}xg6LMKjahap?Iu-~D4j%z4Yzexm5QSB6&EIiDx}tCi7|nZ zkO*tGG5``?x^(F~-}%m4Z@Tl68b$IH(GNT0)CP z2*nUHfg*qyRwD`=5P*;{Focj0yBCaHJk12bO3ZREZ7-D=V8@XiaPI`{{clRF*7BQ|o$J z&lrPfnt^p^1kgGDYE%VbVMMT;JsS0btRf(+>P16Lrv_k<0N@qoKqXLxRB8xh#z{6; z%*Zle5Gq-{au6=PXTtlv{NZ@4vne3DBy+t%ua~D;zh{xGQ7et1oO;ws#WM#Ll|TS_ zRV0BS1Yl$lFFKDE6*ObD%lQ8ZD!5ebH(8dO0E1QC@Q zT#0IchnbtvI*KYQsDf3B-WQ}GAc}xUNCZNP9HsaeAGkP)V{Htcmk(pqC0ay;xLQU- zbizha0;yd+KM5wONp&5#i-Dny32M?F@rZFD!m_abcwdI-UaSBX$=0s2apxCl8M_!; z--dt|DcQ`71ge5629+h)#CosegGnzRCP`0(6=E0}BZ@-k9NsnmQ3bI<0YybI=pz6q z001@dp(W!)e7twG7!o2MGP`Q-x*!9YI!>YXohL&m%&hv3~zcrd!tAW$bh1r!5vZ_)df#iSC{;uy1I8Lqqb#AB z9!mYzYIJd!)Y%sAQueR!|bBLpN zl_DZ*TpBfdt}II?1IEUUAQqz>XOR>cF(3+vrec}Si!60)jFMqR2IN|30+GrEg8lyR z%U^nBb7SMOQeXOi^}qcq0{s2&{r-QzAi~VX7*t@cR8?4oH9)8&REoomb(dvYn+w#Eop_c>2gq+d0k8vQtE%@^<^A1z zcR&943wwmO*TQR1OoiP?4bZNHH-qtnO>Ief;CU1?C_c7z9W_17Za_5uFH4 z)J;Ji2<`(;7!QPI%(t_Z3MiCSh2Q}V7()pp4thPX1RJYF=$uQfHHyeWs$Q@NRaJ~t z88p}+DB=Kn)~%4qTvB;nTN`dVJ4EamO31j{4jmIBS5L^5Kzn&M65fh7+oBY8w#wQV zdejHFVx%X=IZHjB15nUPxbjklFf0AIC<3Sjh+gwCRHMnvK}A%eC!}vu$GQG8pSpIj`;=tgt}5+s0mULk+CP}=Jls=NGSu%6@;rBrM1Wa#clV}~!dg38 zT^X&e0E!^*PsY1D4~SrWbu<|CfviY!a4`9^fB&Ced+pnKPUGj8g*G8czBqlP<#0+2fcUy z9$9zd#3?}Z!SCF^pXa^NXcXnMvTSOw^lgHf%;q~c?-J2)IL!OK|Btmd`;zO*&O7%$ z!yRItasm=aOi9cHiGi31usESuELB;uN~(6-Udysu>h86=m;I)f?$!T-+5_7d0-2Um|)Yar9N#uy~t z@0@)piV6WxC2IQdjPIw4#UipNP-keLrC%zs>?*FbiK2L6ey&(76^h0FO2>MAAYAi1 zY^B)`ZLsV9;9A;W)$WAtRx6t;M{(G02S!^;s&ai^sT7Ee0j$>QaYEWKH0W?Fm-3z~ zj8Te!3`vPv5u#xT+M4!B+icc;u*TXp6#*DT>Pc}x07xLw6KxW<+MW7Jmka_LDKMAK zq*5+JREf5yAu@mr!BT3VH@u6ZXnuai^Sw%?@`MYJ22t^V$P5|IR&S-<`TBiZ`0M@M}6)w!!(8 z%bcb3X!GS4NGXX{HBW;;G`p5+0^j$W&8Fi>!MRQn8=-jX(_7;k#xwbo2Eq~m03ZNK zL_t)X?|Gc_L}_E7)oN;!Fb4EXZCd)OMywqyATfKS)j-N<0LC~Bd;s>TgT9`QkQqQJ zWXex#V+EBA7_-!G)5Bx*#ajRXxNqOSqeqYaP**58uE4#eezB zzszPczxR9JX*BAWuU=fKuV|%>jWiO1F%E#nfHnk4qLgZPJJNG~#{S_)#|u+kxq&4fc9eJz8onDu%$Oo*4sL zCrTsJf^#Bn3^Qgh_g{Nw0T^)NlE?=(nlJ9#x$CJ-oAcRhI+c=+%%svpz@_j~Y0pm~ zP#i~55=Bvmv}O{O3N;vzoH1}+RxITVC7n*kUdbp7xs*aWMjN9cR$3Ejz;+lph4T2; zN$#b3L@zSNtZGtlbp>Ai10b2-}458d_rc=L{=X&IJzU* z3Zu8LF=PZ}DfVln9)>^xb_fCkU5zV|S_zU?qE{5vlx`WQa@k_MD`X3_LWl}Ekb*cP z#)JW39ZwoaYtjm|Vu^t$igia4I7SNqjwl67IWjFgpP|o%!-dN@<4iE_NnWkii$EX=*}#@m8RO-4wufB*hnyLKl@a^uFWOBb&K3dZD6C4c1T zp-r1MHk-Bg-a9+Lupp((Wl|?jJU=!%hA3xdAI>ed-Bjt;?a!`Wy_QP*NfK7d`4cCP zR)&gXv|!v8nFc_UxqbKZPNy?8x>0c6w|(@8w^B+wbZ49s(S!RB(wSVjTnW1I=`&|H zZQgYB=rICf073|(buYb>02wkwV-h=$Fb3izIe+1DwbuB?>%TQVJ|0EUn{T~0Il1k~ zkz>85g@{NG)V`~u5a7*b@Xk9IA3t8;!pY}SFTV7(k>Na{F-CX8@RLt&et7XJfFyv? z(bDtJA6`E;Bsnu$GYfb})Oye>>Lr+3!#S6NjNw8WV>5($-(JpHtJOVy`ojkg7l~LZ z&7VJUY}>YN#@LU`I7dXzfMGv9ZEXo|+vm0mV90RfjB@~PArZDhVd&U5!}tJXPl)!L zfcCj#fQbgiW&gm^QythMF9@Rx7p|4dr4uJk3MQ0J?8a%=nj{V%K6*GhGM3F|l~#zz z8AsNe)HfR|r%zwlzyH}nVYqiq7!m>J4zBsO3nqJZvtC_Eh76Eq%%&a*0zUJ2_Wk!S ze(lBA?%lgTH&<<}v=B`?E4FPLIeP4X<4C2{<;z!Z-+P!!7nx?IT;}A7!y_X_&bhrW zu_gn+83V>*6Im+`qAd{(5)w$uxJNXAnm{oIMkxSzG(9avX5G4tfIwihHXmRAXENY0Fo(GcU@ zM)+~Yj5cd})kt6r4Ki~y0jfT)vDaei%a-RCmZqlX8Y`_Z3bUEiwryKRMu!;V{Q^dl zQ3LR%A&XP*305sp)0(3DqfPrJzA8@V$q?*cWudUvOU`+(a6v@Q>`L3WGp^CO8l$z2 zm5LMP`@WR2+wG)$pNv7o(a}*q?I$Y9X0!c9I3XI&F^*%`lhiNPaW#~aU46Yvth$JNBTpRk)ff{b?eq6 zvQD#e_VkC#3yV6ja`=Hmo-C=p*Q&9HEg)@7tds@JD3yd!q;$VOG)O<|OGy|*PLOq- z@zK$-a;2Qh=Q0^7rQjm%`dkPuI0^|$X+tJaM%(N{9Y+xe5UxbQ60MX@99KH7jACwK zS8es1nwp#b(lkfAe$o6XqVQ|*$!#HrDf;U8A7#L&H>2&YD6B)pmv5w$%4Q-;fE1JS> z5wwX1#6pA0Fr`Q-gT|oJkSJpeR~mIB6bVC;$N?sS2_VOi0C2hRQ=aFz5{TK+27*A6 z0D?#oa0AR3qYR;95yHxf>qys?LK_Y}%f0o=GC*ce++={zm2PvT87B!^`5S@OCQ6dT z=)~xr4cQoEXjcj$1m`FucUtQ~f&deuZjvNMi#3H)kJ;PbXnWWoGG-vAp|8*s zn=k#Lb+^+A!WB=- zLORQUB}vq7H4UkB+Vy>pvFs;ZpExx!vE}^v(+l&<+qUgMhAWL$(2cX%R5s-Uvas7l zqEsqvjH%aGgb<$Zg+b_eZrBO^bOwl)t1EF7xn3%l%i9A$6vy3eLlb1unY8aPZdrGF zrPW~4jUpW)BIJr_&i48hYvF*V3-XN&BwsbUKbBecw-%YPMU__u?dR94`psB#Lsm zY$ojzvLs0wE6u2*Q+~FTFL8mLP748~U_qe5FnsIHbCt^Q@#EQiF~uYjVH75=n?7~w z^=vi+pj}tCx{*#|L)2-vrIf`|2{dR8^_3N^i3~8tv)RJ_1JAEtKdy~itA&g~7<610 z3x&KP)P$XG5Cj1t=JR>SaS&OeRJ~SLN@p_ZVzCe>x>~K}a=9=HeaH74VaYd<()Yf& z^U?L2<;rNGP$@aGR$Y4IjrR^8KD1-UcC;eeHL#5Vkh53!tbvwkD}y&=bU(%It7x>p z%;xwNVmsuVYpwfR6hWU0X=PxR*kz11J#jv>2Bl0U(`+`hHYv{o03pOsWoUY4dU0`a zY;4S0i-^c_v!w9ZYE6p2N*cCSjQ=G#m@&O7mNCXSYMp3JgPxW_tu!EF5QG*$s+7gn z1LJo3L52v8by%Pj^7!%NM~)o%(T{#ahHl>cq}%NtIB?*5-}_#x)w*-{?qB`YfBm=r z_7DE2fA{bHpFjJv>Bo(T%!i*tA z5L}?(j4?zGgvJ=b(Q%w@+qUi4v1?>>%$0tp-I;wn_tE7m?KtV3x`=E87zZIC{nnPz z205CZMh>*0MC&!6p;a0}-=oSnK`NWc~jMhqNZA_xIA>u*+K$0YkbA!mV(FVv+LKG%RkZ6(4j&I(~xln8J63kb@ z@CM%yV+?SPcJH=iSOfsdX0zM3Z}0bCEe?wYzC~D*INa~vArMnaH5*OO^Bh-7=^CS< z4}MCBLc$PHNlu&rBb^w9lq4n!<0#UJB236pnvuy8pdm5_2_=C5lA2rs*;A#UWZ*F3 z#z@qzHV~<`a37@pEPx0I3`5H=)Bs5s0U61;pk4~SMYh{w(J(XsfE*B|pNcdst~3~0 z=5S9p1RS}PZpsy0AVVoRa?Y&UriWL>fnL+Xc(pN{6EG0)Bm?kEBtX`;f(_CDpM1^Q zKYuk6VGYHUS=rxj%3@}B&FE9cklM?J3hMl>BC1$OG_PNoadf9{K<_wPwm(~vYvnX*`2FbuZCe)BEIs% zi<>uX`Rwlf%a<>4q*5_+Os&xdgQsM_w8XE3Ay8D5S{7i*`bl~mtTFI3FJ=dv(N6n z_x=ZAlw>oh!v_y;-nj9jD>s66`^3o?7-Mh0_u<&s*oF-o-#`6+v0PcMH@^1L%Z-)B zmCKjgosQ>3z3-Wom6fv}e6UolGA_1HZhr2-vze?1V3I_g{qWp!y%mPg?8X}> zCbfpgGgH~L|MH73Zl2h9=d(}GojVuDiSK*Ijvbqr*!0=m&)2P6Pw0Md<^#v|s?};7 z$4~FwyJP3B%U3>GSZbcXc&!sg`wtwr{_*usKfSB9%H>ioyzoLgleu~89v5lX4L3x^4+?=1A;taD{`Rc3ByRKYo zJ+msHd_Lv6OvuFbc)5}xhUp%~Y;cBZ9`mX=%zGrvu+5PeLFQy+oM9`k+BfuA* zFFky?kR-cI@b(=MF9|Exz~eJ4;Jd>By%h zw;X!zIU&S_ix+R+x*f%8Y`F5`%P$#FZ@uweHj`<#R$l(v*EVn5h`T$w*rI@V?d%5O_z*xH*Mu`SM zh6Wij4VW0txIk{BLF_yUk%otdf9H38=i)EjJ2~TV(qRls#XM)M(``O` z;LxeBfBnYwo40P=*}Q4v(W3`FKV7ZYYt6>+=!hmoU>;6CeCwUJTdj5&CtD`BRcq~c z-~DL&_FY@HPF%ls^W6Ds-y9m_(o15qd-vW#F@Nd&xie?Zm418p@|A0~mG;Z8eq(NK z_RNPDN|n)_d!BjlXnNzujeDQj@A#SeN-K&~eR<{dJ7>0S*|KNv-rKis-GA`7GPLfq z+jpgKpWgR$r_&%5#5f_-XktT^(a{YXHl03up1FDkj$GxL?9(x-Rt9zT9OTPzfT1)c84A6+Tr(wjDobDkh2aT2!L?F|zfh+(25 z#&|YYkkSpp7{Pt;;PE%Uaq{E~hpu1y^K&{?6cQDzV`0vv;V_)##Wk9b0uIh8^=kl5f@6#VCvE1<%D@pKYJ(y_TKqR<;w7> z7hiikJvF;Hx49EtyZ-6)eDmnBV^I`+eC^`;b(KAZr?dgBb*;A2=_D_{^7ZMNnfK0I zI)41f?;QTEci(yM`i<-5N@ZcGwr+f4Y;4_)>mOgde6>&-TCT06v&D)sQ;%miZQkpER^_w(r^hxhH; zv4wM|7ZPK=+h7ckW=5k@5E=|Mq5;jACHpf#W&j^PocZyOf5Jg*-MHa}lgB4_?EUFa z{%)xn*6WQ!M-O;jdZp1>T5i1Z>PaEsowv_ky>=&^8$SKPN0O&seC4Gt?%jL$%(?RD zc%vQOzB_&7@ZOy}wrRs2JX+YadF1G^gQ;xBo`Q+-YPIo;U%cg~)0tf6>#x7k?8J8- zF23^e@x#ZD|LmvlUcGiZpRZi|_}0Y4_NSiO@%CHqY}xWuCRW*Y0(Is2bIR4ff?V4V0$qkZlAy`6gwHe2yWA73dK%kzuZ#)ivBj~%@C`Mr9p znJJ{1U2TDjHS<1N)7M!`O0`~k(OXKn71ytIZ2cNs9`+Pr14R_}f^xO#bi0W%j0@NG zeBWoiK!$;{kJ&S{QHnTc3|+yE>vUSpd_D)rk;s$o*zj1R-eAOB*X6(k3Pj|@*kIkY z+aw~cu_xJ`xCg-QnNE5lUe388zJ}aqbvE2+VrXZ`NE$SeLEh?i5^aPeO~x2uI8QXO zL>n@aqr=fMHZ5oP(4j*oPMrAu_rKq0G=A`dAMD$=@0;KJ=H<(m+wGQ7^!7XNY}>Z& z#EIh%A3ivL{u}@n3i+p=dTP_AO$!SPa|^Rd>w2wj1xeZ@VPLc|j^ntlWQ=hp8BCBGukBW8AT6B2NQekI>j6f;H7_)qY zFbres?Z@797yER7upSLy#GoC;Gt1Q=h*FM|mYyp`#`Dsi@48Y-kxpkE$1zCCB$|>y z$Br)xGG}5Cj9dxX(`gH>Mubc@n`pJTw6t-o-l5UEf;Vl0@k^Ax)Gd6zMc~MQpGW$ppG# z5+_C}Qd$RLc=z7D;o+f_kj9V{LJC((hdVCk_6iSz2ao`jQAQgi#(*h{cmRXOj{JL= zshASdXcCOcFwUAP$Z5?wEv^(AqqQ+WiPn~;(d*&}&JZ~l%oSX)Oxm+)lJ-Js>a!;a zkTdh8`lWYSdI1Ki=P;!h$S4v$%ZypYSJD#@zg5ET+U9vL!04BvbAOo{w3cJt54a}I z|DkB(C*0R|jp_+bza$;_??d?*fP^R(f^FG6F*QBSIqrRWukZWWY`WcU6M+yuk!ds+ zqc|3h8^+=K4ePgTo1A?-_s-jIa}KY*`s&o9>0GXm&1Gz|RXUX(85z2N|Nb-ko?bsb z{&;Gk(+xIlo!q#2e5Db6{_cBGkbuUK^6<7TPo+{$V{*so_upNZUs_tOZP~JQ+vK)F zv2@|WrFy-wW$QNA^^3(~rBaEa$SP3Ujg_$7*}Zeu#DBxN+Sv=7uA~Y!BJHPA?M_SSgmD4@rOepa z_|`3xOmNS+ws~UX#*OR8Mn)Fq7Y(3ry}3tIjdr`%Y#=~4inPTWbB0oG-nMPS=J7_m zb@%=khEaLAB7L_!Tq%!KTJ5GmdN@5Lr3~UYh@(&?2^j^3Vp^(`rV-5#>r{XlMj6>gkt=hDL^7|E<@v`K%%G zJU7ugUnov)-!(i`7~im|+ir6woy!l+&Mz4d8d#}3#25o&wm0rLa_5fiTeglZEIxJq z{MkmMGdsT&gvtE}Q;1lp42MxttJi`sS*q5T>#a<-potSm;NGsi&+K_-w*#7K0Knzt zdX$)Kp>*->xAz}-X8ZQZH{N(NlSwnqVUX;J=E=xzT5I%KD>Pk$ron%bo;d&tAu^ea z>$(Z?U;msj3_kzV^3tTK(P$=#A_A?HAz(<{HmiUP5VO(5WKli9k)bk%v{EXufXKc> zm2l9a>xqz%fhG!#qM#G2#Ni^vr7MLegeN8EC^++cPe{oGM`nTzShv~I?lw#i3blJNGaE^8>25{R&W&!O+bV}7|zVj zo_yiO&D$oq=jZZ;9;HYtG}>W|8Q=_(phKiMFjUIb-~q)5ilIiPQ{LUy3eRUoD*;JrfXmzw0Th7xGsifwe+0_<1E^R0rpdwsb<>M8z%n1-)dmyGF| zQ=Yi%JyG93X6+*&0u5*!S8muiQ63)t$xnYg_2}X5J$rZT*m>c?#m{bkHZnS@l)nD) zC#iI1{rLFjpWprH>h)7!|K{+>a5|li<0J^ehYzQ&uLtA+03ZNKL_t(0CN_A!07w8- zv6S1sW3t_@KYH|V@4lz9InVWIX68|$lv-Gv&1QWez?gVtr8+nBC|Afme*CbQ&t$TG zI_)kmFD@=F&dtplqtY24QEMGH8nsqy#dTdk#klc2DJ9O&O=mLx!-oKZL4CgW!ywqP zV`mh1cJJ9G9rvBL-}W8`YWl*(6Syod%(fl7MlLl5>Qd=NG-y^87-5cx-m|akIJj?EYudxt!aH zpMGXv5On9KWw~5ohzP_5cN|wrmvccxLT~_3iPBm#&TF;$<;#~hY}mMS=Z=+?x;@V! zvj%j9<*dKAU64QfCJL?EPK z95f}2kv1VR?Rh+vO7Gvlx6y1aEiRTTg-4HcChNF9CooG(OPzLSeEqm1Wlthw6!vYo zTC1LtoG~)Jh5;Ee2K-bSH5npfbaSOKHT`JE_Q`5>d3kwpXrxGn78e$0AI~|G7Uv#k zQf@Yr%4GavE_3M6fm*%VSZU;o8G?ih#f2g;fRPY-X{lPPH?mnNTn-4*VbWpgjF(C| zS}D*GM=eP^4A2-y{%*H3Gb_i2%AUYn%Gter(vjZuEYW3ktd3m`ih0GW7eKGf1S$ZGJLH+;qPnfHOV)~T?d3-XR`qxI9_GcOPAEl!> zv1E(2kxHv&9ik9iYb~X;?bvm6SNj%@T@yyw5Hj2WfrKO>vp?=0C!jsV5wG`!5 zoJ!B9iUY-V|M1L_S)k8q*@wuqL1VzEgn)W(O2+E-no=20N;j4Aecw-coC8{;faOm2 z1h~K$KX&Z+sZ*!^;xGOp48!k#|NC3EZ29hYzdJoWb^ZEv&+|H+_SDqWv17-6?>pc5 z!4H1$;QqtuscFWT@B4*vY1gh@g+jjD?RLAJR=YVgR0*SCVPWCX)XZ|ND!4S7YsC;G zkx>bFg=`^TSzM?sFI}lsSCUw5-Lloh>WeS#2SI2@vZOUK5)3(7w$T$k8wAi6aAb@& zI?;O2z39sfQhDV6z|x&chjZ`APpt~(nb*x8t!PIBvIWU zn3!tlq8CXTCJvPG>RL>hbt9V3c=TM4bb9P`%^Ungp|W;aTiE) z;G9;u{-y`7K@0ORW-XVGLyxj=sSRL^HVRZi2AD8LuTAkoMEtUE5LP9h{dxSCwC4k% z8LjzQPxP)B!_`HE;jc)^`c+F3!fM>N9ZRn=1@PAdX8Z0?Sc=`;YL&W?PzVgxwBbA~f=-%zm-uU~!b7h*5*|U3R*l9KD^@9hW zVayOIE{yAfboAs?6L;_4d;Iv(?%lf%KezkR<%@UkTr)}>Ir3aS>vD`GS7$$XCyGM` z=EWCZSU*-iba3Ch@4WNh{^tK<$eug6XVb4E*xk)x}s0(*V*AqsXWUN>?c3|JR3s|kQ{wSj18A( zA3q8@4F*O?AsBJgWFpCRE+ZTsa|~0y$)rfIIGfGwd}`w-*ROI^6BC<R~!-+gze zJnT8*v)iAhQ|`fo&tx+hfC#^QCZx6Cg)fm?`->v$zux?JXt1yksvt{jk`nsbCR(dH zx34sYIOkCm7~@#i5h6N{69j>uPFo!n5S7c7+1c4{x9hr|oe!)AU91YremTzv(6Tqy zEZcyrFXI6~Btu$jrB$3HiPA(QrEna_k;5Y_vc}188Ot zkTY(3a>YX7Ti^QD*|TSF-@bk4&YeH|vp@UeKmOxC{KG%`lRx>BMx&9>Wj?)q`}*~d zj~qHw85%l$`m_|HP$*cZkOvK!E94UEDFeap* z&Pc~a#;sYG5T)y4oEShZBoGUtC{7e0Y6G#MFpP%A*6%;C-}Akw)0BROh{ZwN38H2v z$dxO(a>eoeT(Ouhlv?dhs1$NZz*5=lj@>(}je5OaUAJLFI-9kbNC;*Sf3+JkQ!}tVv@wfiP6R+fQ=x` zI$oeDCR9u)rW1s&R*f)I;IKNyQ^nrUW=svgIe$5Eb<^vGX01jhU z1Vcn$qAX)C)>MdI*^WJ^7qgl;S8&gjcBuMmI#^F2Z3qdl(P(y~1UYA%bH)%+5maj{ zvC@E?01dLfJmSmoIBSx87(h>hWzZ_TSfkbLw3A|CSW2<7QVTlm(a|yK$T*7Y^_6BL zWZWrLGTEF%NXS_bM2ibGFszU-7K-V+pM84v?1kU`&OcA*9U@(?x01w^N<{#epIea* zRVpQ|VPRn*j>CLzq*yE>Q_IUsK*TujwA+PzzF5c`t%MMrPJ3Z~-cO~5hK4-PC!#os zYPDqmC=?2f#){|pg<>&@N006 zpDz>&g&+v()oQ6+c3m$Fx~+DjQYkYA0I0QYw>yiARYO!N4VB7e(guiDYPD{s?WfYE zN<}(OlqB_fZE10#RIV^Y#(6H6TUwmY<+7P{hI7$rcbBU5cDv)J{mM|mb*0v<*$9?u zRo_dM^QnB=bp$d_vC@kRb;n6(^Myo*tyYlDWrg6)Mkh(s(9lSy-LBQDNfKo;86YZ_ z%F9a&jw@5C)XGXVlgVZ>nRchsYBh(3N2HYPcDq(x_IxjwD^!Viq4k&%*=a-~*_qhzR3 z;fw=7H`0xjcClQNu0uo%^K+i-h9G5JECm$fts!ok{0CFV$+d zR~mKcdT;#VecvxW^Xx9t?LskMF69M>SW&Ios@9eZ#p2NLh~T{0XvA?iGMwW~li^{A ztww-kO64q<%n((pwJ46sfKnO}3dNk(7~P*FItUhgIeb-T$=|Mu^mJAANE%zf~| zyX)4CzVz}-wc4^P9N%}Vi;F`;!}(k;>~y>BW;*4&j<>j2ZM9mQ^O4cA<4VSP7=+bo zts6vzLa|&fE2Zl7TB%e>r(LB31{??%sw;o}!=LTky>H9rt?hO@pD#L+x7!WL*wAoU zaD$kzzUzt&xW;S5-m7|v)r2cHD6ok1ua#Z>+T$XC>DOx5i#bQTD-0$HYt$Od5E)}S zosQ>uy(ShB0EA&E9VeAebIut6AucahgCH0l9s$stnGIu=QpOdeY*$A2m-i=l%sr-E zqKq~GAVe$FpWS_|3>bniisLv&Kq(x?7~`B6S4#P=!x`h8OCg%gMyt89Wz#0fQF87` z=13t0*E;b$=}P7@;z*wBa^4HEZnm0#`lo;TAOGY3tyJPT&bPn)?LYW~Ke&1G<}coO zqf{!UQz?e@zy2@(bG=&oi$DMKm6er=iHXtCQ7+{-f9v&fxzud8y4`NdPf15Ar5xAq z25~2dqd2~K^V3V0u2gHa`MJ4Tt!_wLyj~PUaTG;S$Qdi;a;_tiC^R}Iqd^%%3IHTy zk~1!_Pn1PuuqOBqwK7U6>;ALec{_`-@z{b1Zehm2Ed85vPT9nb zK7O>>?Ml}#mMUQwFDzE4X67PA&z(4t$`>?ngWPCZSXy3Ks>X>~Kfa+*%zysHgLbD` zEaX$ZH$FNl5GC(rAgzg5Kr&`-Ztl_4gJ++8*7s6&1XZim>-GBh__&b5Qr5`e?99yB zvuD5Yjo0$|0@zSvt+m#PGEuCeSVxJfHM=wOwaV~tq#%rRH%i(;+zq2d>&Td;7DOhb5JED}xZ_AiYOStc zzp-QcQ~7KLz#!<}IM0sN5XlhlwJwdFhCO;XJvKbzIZlsSImnwJ002cskx^!lYeR`9 zZ6MJmN)r2E22s+9<9ZMg<2bWa{bf;S4;@5oP;V&%$`~7lZ40c`7e7&8q5XVP2t<&A zNw$h?u#6eskv$p2uRaJqSzvLcb+g$D;sgjlFz97W+ducY z>b)R7wwj;QM~3xMWe5ZlJ)r}x0XieVmv7KuW?{e(?+swl!U6jzGQ(Mq_JP!wZdyj5 zh3E9O%L#Ix?jHm#$MO`8wBDdKE_ReDuI;dFhj&cOF2DCwOcGkgz6H;7WC&m3p)oyPjQz&Y0J(>& zF|;=Mof{_Z-2ME6Gv_jyOg5K`V?8l3zIXRd!3?57(#VXx4~((j1pPwzrJlMOEPMSf zK7(JA_e`sSO9srEB@+<2J@VNaOZ8C@G?2Cd0#Fnsi0HcRS`T2m)y!oxekx_(Q<9j) zrR8F&h)A59jboK!CMBVF%Lu*{k-D1QnHZDUNM0eEf%)kA-6T=g^2V58jBzF`@hH(M z2m&F55S(%3$f77*n30ZUe06xbDjhb|vw03I^JKtkcWnDW2w|T) z0lfreG{n#_qmT>&31o=Kkp!o7${VVb$JVVI9UjhQGTCeFtHE7pr_{a3p59=)S6ckT zKMdEdYJ+GU`(0;W5rhb9qQTcF?$^vBf5nND5cFCR7o)X8`$4c-zY2I_tpxxWt`r$7 zM@fu>Yq0w9^x8Md%#(3F#^&ZQAY#n=o;8qp(g4s8$X=7dF&LNj$>mtJ* zLz}UFri~T$_7EZTm63v9b!*HMgIELvTe^T4WD0{YWHziDa*iHId7Odj@5%sZSt4d_ zaRpDLP(PUn0EWX?C3p9)FQYZDC;g=)Ibh_bNgQ^4T!Ls&^1VJ)T<|n{xOKHNj?CB2*zq4`gNeSx%NRbV315N zEN3nEq_;`4egY<7FRzMlHQ8o0+8le-_yIy644^C6zTMl?nH)!D#hd*)2LLqdRWfV7 z?#A>B<^&KpV`ytWJ6@w6lGPTO)aR-9sy>2|O5t1IJazy67oiGYdf~+O9g~6)>4;;( zRqUgY^a)iLaaq{;K9y-}<~(r`4l*a*jmY^qzOJv%h|{8Zy?St`9(5jInGc)9rR0 z#}UX3knL}+)K@aOl;B7f;rnY9?)}x8tn$ndB})0epUq0XCd!aguZ=(q5y_~83&wyk zqLk}-o~LzUtS!@!RxAOMk{OjK&0}T+p$1|ILiQxQlarIb|NFmx`}XZ>btw$Ox8HtS z2=SfY`_6a2``!QipZ{WcY4QE{Pd|VB`F+pqYq#6`_CD=64v`)GD94om)NHnDwFUs@ z3uTpRoE;SYa$GMZX?s%d`7mvXVC*r41967F&nF$q3(lG&9XoZe@7L^}M{&_1a3> zPe1eY?)#7afA-!q%Cf6E6Wn{BbMElQ7&0R=m6<3dB!dPd1_>l%8Y7tkgTYK~GYM?4 zX&2?yZdWh6mVb2j&#GQs)n&VuyIr<%+t_%u4F+s%Yz7ICEF>WWNJ41Llrkmd7<0Vg z-h0m3yMLT}?|UzX%*a#94SH_-RWv2qB&m~6r8iTh4iBjXMC#Bsy%;=>`yzJ0s*?VBe;;e0IS zZ#bs01k7l<&@vzEUHh!B*%AuI>RLj-v17bcq|AoY$t zx(v3>QW^CPqtt_XR)u3OJHWtW$I4f{nNbD?jE7=On$h7X_iyy)+ouTQl*;lLzGk{3AwgnTs)SwNFx#|>6k0N{W_U%|{kn5K=f z)pBIzh#*9$2yI~j;-Fy+>qD01ab&zOvXCbvAP>T9oz*G|B0U!NKBOQ*qtU$Srkn1( z^UhEI)n6*2Jj?F8@4hIG-uaGqeDot9{o)t@?xF90|N9R;^om!!;*p0RJ#zHv1N-+o zS1c?nOwUYdt=4<%d6oz6bCKHzAAIaHpZ(i=?!A9)HS6~a=a_>}D~d6w5jilJQ8m(3 zDe`RDdm;{~t0D}Ekj{A`VP*}1g;HWy0hSfP4fU#sFmhnIgNU#DIsqjmkcCgnEG;chPtRO>>80M;EXzc= z(`iu!UrU*JD9qwL7oMG$!u!m*+(GU@R0PT_t**5@)1F0&!V5X}%))@)dqDDz4U$r% z0V6;X1kwS`(qXzBVqz=h1s6jR@hl$5vnz_s`OFr1UKHMYDYXLLd!J`nQDn|q1ZPVA zl4>@S$e1Ka8;!JSOjvb|*2W~-wBvYBTz*7Rq~i!ct2iRVB@pIp%{jMwOf6(_t+ z8uz5H!|X~VVLQ)x*}TebPNdtQ9T+#f*s{>s1m>5|f|KrI3QD$LUAvPSDK#N@{+}-= zcgN?)V_686`EjMW%*ILx&ng|COg!E)g7P^E=5ed{UOf?ReGaQ=fh}0jGMPQFVGt8| zp|Z_ZE+Q&Wm(S%L)ovs37TC`Ab%BsXUWNJr0HQ8u!57NV7ei)7DY8LC9YVm- z0gJG&vPJ?YVnQNwt~{p-6;vTWj8vH}A8J4-uS}S5rrue{_`~=>QCbPW*eGhk6m*;g z9}Jk^fCj!ibqM3wI5fxdkiIj?hZzqGV;+pV`AJ#yq{fA;O~fBy&Wy6djTAAjP88*bcx;J|mj``wc#PNZqv z?lxPU*1>}pw_Ba*sp*-i-Fe}jI`Z^if97-F{N}fp*9U{4tDDE*Y2uw@cFsDbRT9UI zMkCA(%TYa-BXvbo+Z6$TbAnpcjEk`JG6%IFjZ$LDG@{ZcU4WH@>sTowg8VDVAYxGz-h0a|0-o7fXW0if&tN#T-sOc|9}Ihg;m|tN zde{7(W~Z}09Ac4K@cTe|>uXOQI(+)%LbuhqBqjEzPaN+pFYn&loSAC#fql%7 zXo_Q#=Z3=WId=5u{QTU?%JQI@b~^1)SO<2>_`)Ir&1UmuFT3W}TW`(tqSb6Z z{P07KMq_$)Q)Q)sz8^`<&>P$N#C$RV3|yUlXWd`=aM^8xsS=r zL^fh$xJ`k@%t$2Lyy%ktxczkYtoP=|%3$K3=Tjt|VRPMdWo~S)WXwNW#$sPbJn=HU z%#U{_2n6LE5YLRb2yOt#Cw^4%lUXE8!~OUWyyEdO%7v=bCqT(9%d=6+#g4E0Fq^AM zuH|i`6aYBqv^Jxuf(U@LTCMe!)dsU7Ag#%3Qpyl2q?(^NKAzm*0TD_ig%sw{rSEi^ zEn6$Zu}06Sd{lwbpj8@a+8^|TOCnbc9${2kS?7U4e8}|!=e#1XwF+e1S6z4A2R?Yq zfA|moer0vJ*Xs?3gM072_t>##-}9b#-*nSWYb&eFeDL7KcYOV8rxfnpJOAjTPY?6q za5%i`%BvcUw)fKS4Q~JXKiz%zx7T~aB6r?9=72ggp|E&n@kIvSnwX-FKFPBMnD2ul9Pq!LUEf`~BfCv!J6!yDQ2Ja_dpRdzEKT zJpTBh#~wd@^3W1@Jr+dX#d*wVtOx%oYa6i4Po z2ljvOdk;K#@&pk+`p6?!UU}u7J@bu53PPoY2ufXO10XYBb>&so+E0Aqj}9L`^q%*; zd-v|yrNyOa-e|1@uQLo#y%)#qEDtl=&-4B;UmFx_gQ7Pq1Yu!m@%YIF&+G*-M8qd&( z7?lI)JMMd5z*Ys;B#1S!bYsbbp12}6@)9@@pFNim#;SG?g3%TwJ1B-G6wBkp!_oe@ z^-d5P4&MBx1h%cNpd`PKuZHCw93G0df`WF~^`7C^5I0v@ldpN>S-|n)pe(SEHayOm z_s9#~uhWJ?YK*cz8ZlG__SsMWm}s1~8P)A<)0@0Rkw^rPXdM5kUWp2!*W0`d;Ij~G z%6V<=d^_6A$|O-3p_O$7Q{O_>&Q$)i#uc_gq&B<^Wf`z!1H!7v|Y#rnV&3~3`ZX)E&}S)mLefpWaw?-zOAAM{CZWp!nFdFjP3 zzO>m&_n8QEa_F%~tYcLk_=;xOpE`DYadE{7(=-l`+h{cWaA3VxS_^R5odoSDdX+aMH2uRNP-e8b++G_m3)%;vUMWnUnQKANFZJ4L>G3czf&i>;+{NpoEKl2M8`q0fcz5Z3N zdevY4zYiaN>QI(vQ?t_xi}daL?mP0-v(0ArYq#C~>@y3_EAN>Ff^%dr3dr+J*b#vu zq0)IEoDYv!ipCj0l_Lv55QQMBycpU0V53t49$|;`AnXwcs-$2DR965+&`cZCo%VFA zeQ^JQ7himEetKGwAQvd?Y@V?L1nX@a#ep1a**oV7TMV*nkmW35y&L9skmZBCSnFqN z>x07i0>~+CmB|IsF?t{ZWY!GIvuBQyq|js0t{sRYQW@b8R;}ut5y?d(DP7G)tB`C^j9Hi|N4U~*CW_=m?C#6?xxv`c*Ht$5rA+cxnfyWn+u8@-rph$(# zaYl%Uq9}@@NGalqY*DhR01L~xXJjsf^;V;ok|VrPDN}apT(yE_vo(^ph?Jp$00hJc zNFi(#LLX2SVH+FCZDxWK1QQH)4^`nhrqMnJ#Hc2gZ4`k|6j+;RIOPI*rg58;)tj7= z_%n7GE3FXJHUnoSpaomPY6w_cu!J7H`s;CCj+|q8wCyq64(^&P1#suU-g#AZcpmdX z*d&a2j)Tz+hTZ2qecOm40M@Q|wVTP7GrKK!@y#gj51&3XUPo3pDfIjO)2A1_gCt4Y z&bL|=#}U!^BoMb0G3-EiAqX$P+x+1$u|mfbLN&(m5~Y*~6PX&RsgckmPKJ3NR5^fH zI)XFfIQwe6qno^`DY!l%3G-UNmvlQD7ike3pDLNSUP zi6$v>0Hu_(rYJH*B2oJQy==I+x;D&Qf9O{Gg$JN0p|p{)D%LY? zv=bFKOq`fuW}SoBs75P};<(jpMkeyY{XxIi8$5RC&eh%^iW}`t``P2i7nfIt!~FE( z(&FOs+}z%^_5P8gM}OvRZ+rC(H_YyyyZ!dtzxIu9y!zGG&&};twfF-=Vi2;(x4-?} zyYIg5!?)aW?X|CJw>wMAE0mn45ZL=h-?}SXUI*Id;xjD+*B~rcv~g7hkrt zyf!TC?%nf)yjWaZHc^svqQ>m5T?Y;%Ns0*T&UFbT0YUU60HPI`2uPtK417v2PCQgH z-}F?3fX}u=AeFDqjgeQTUv>kjW7tj>zdD?|sCr4yr7c;Fp3G<2NuZ!knUH zB7~j^vGQAIQ7Y^gLP(`;XvM5NQ&F*j=2@Y&wE}a?>T2A)c$*R7_>ZLW#VVhols#_X zKZ}&Uq)?0LH@;d9SQpB6;2g?W{zAo-DMKR90_Vwi#~Bt!rPPJx`)>zfj{kS(CEDiS zzi<=DvjQ0K{2h=@_sVwDr5$0M<3~vC zWLdA*^WFm}Ywch#h~q|*M9-z@FBepNzEAZF_fcX8fPk$-P^TLw%!Wf)tzH+Zjnla$xNGaeVQ*o?9ha5#Q1gL<@0c)1$%WJFsEO(w6U}- z=<2k&+*`L<9>>5~IFSCJAn;S&Mv|teRAyaP6n9Rb>zr(gZ^bNc?l!jd+)u6o_gxW8(wqm)mKMRge4UT z5NI&SfAH|5b9?qWmVR$=`Q?{4(nJ~Uy{&3)@XXc+*8_G=tQYIW3l@d7!A*#zkv34p zE30dcd((~9?z#CBCr=+baDjkkb-(Q ztVx;dy|b2?iAyB{2`H`7W>dA=R8=)Zpp`BqqAa9T6lugUC0S*k$s*p`;hm|jheo9q6trsaT)|wIs;A#)z3ZVC; zh?gW-ae?5bs!RK46&{^;2QZGtFc~~9dt9v=>=)<&xnqVJP34$Am>Lb+iN31Y#&gZ$!^SmgsVK%hh`BD>v zVT2T5kLUb6Rr)(_;bL{hncucQynvYB_7n3RJ>7`BUpw6jVbB!<#Kw5*u-rRBQ6b{l zdEd{n-oPqjl+x`^Cqs+wJ-24J6vog@6oMX$7s%qJ(Y*A{wx(rct zPAL^;B5AWdSX!`L4&yX{MFAG2jrU@$3upi{S<6PVNXYdCP#_}BR`cEOe)rL%NB`>6 zpAH7X&WTbg%Zq#O`_2tF-q;&t)3dwZ``!=i*}HEz9Nv8MO^rtTYhU{&GuyzuLL#k2 zkl9IKM`7^HFEy9d>;jw%I2J_&3Q>a1FO<4MDra6)F`>C6CQ8Xtsh4FcWko~?C@c)@ zZ8jXNuq9}(tRNRzBaLHCxzUQsU>0Kx5($tH3MdB1ZLz$z+RqAM7-aeB<>l4&ffemR zdx}scg(mZ`|7K&I(YEnhaZ0E&Trm%@ZiDOnHljOfE)ve ztgR20mR36L?##?|yVFh^vDW0h58#$CcxLaoC|s61>v)*iUY4)*2P^A?)%D@(dcW5n zuB`NzR#%I{&+XZ(q8OZXy75b2^3q0{-v9lFR!^UrnVvGS@iy=ERvR&ERT%P$*boAt zA`wDDL104CN>u<8;s{&?PzvK11vFupv z!M-!dETkk*GI%8wWK$ZTo)v`<5J2&z0?1?O)H7a=1PLuw^xCRvgIW+#j}=N_FZ3pa zBHsPO-~G+<;vxVeASv2@`4a@*9?3aVQ_Wnf(E)-v4dRtoUvvGBzs_$p2^uHBg<`ap zv}~RMorP5NTw48-9t3B=sCKwHZOPQ$zDgKr3pSsFabN5WhZzu&tG067O9}jD@)K<2 z1%`#SeyrLwbi+2Z&81O}o@L{9UYh907K1Gr(dEYGVr5pqn3QCqw5q-iEe~&aO?V+j znL7guD+vgI2xh~4adBZV7*-6-;K@LQ;mRcj0Rjd_Dv6pSRvnGl_JSJ)4HLYy4U_1) znBJ*t=*Z7i##e@M2f*{abv84x#+@ca{8&puWsP)(x)006k%FzNXKNh*Dj;M*lEAL& z4~JQnX{~h}@0xA1$ol#!us0D22X{||5F-mf%-;LJm)~&XgjQGpjn)h>D2B~63G^fl zfR+1lZNeNI<2(qX5DKy=T<`bWS>8w@$83R!%Dcz242HRiVsXe0#9Lz`MXXg|l$2br zx%v4IefX9WCy(9v&2MU@y>r&NJkP&**WLf!>tBD}b=N;}_{j3g`p^FCd(uXu(MX?t z_85TnEX>YHcykP-ys(5o-co#zfXFN;fI^iJkgW)4G=!Q+z=sK=1lL2U7Y<i5=99((qwLx(Q8S{7iYpK7+dn-u zg-AYREqf8h%ob_0xqJ6+W-+lQt+>oC1n<4IZkXl6+zy6CKeKtkYrWwh%X?X#J1!gx znJ87e;`Z#`i$eOdi4#PXWm!?=FMHWFQ{CysrKQ&1`7|~}>^aYKid)o3bR*Fbq0tmP zT8$zVs@o8^iMSaWFb;?e z0!qAR7Mwt^wxWI1Z-naaD-l8Tfz$@b2pCEn0M9JMAS3-9R|W{v$>L>QD_NWHAjnf8*FBrs$^G-1^ z>ZP^bppYa3tSy4bCv11g?R?a3klL}4ke!@Gn^i(n3c3(n)x%8JW!-)s(tDnNRGq7;R`D5Sc0 z0VxgQpf?x{26=AnAS;|lCKS?9qt%+8OFL6dk(Kq{>iQap>U5{}?tc-XRSKSd`pMI$ zSB#0RQNY&Qtkp`}%_b3f=e)D)Yr~T#PCxPZ6Bq5>JG*;#quBw3RwF%e;$)}OI&mD9 z7Ek}+q3<7f(Sf=7`K-uy@7lexvb3}^Ju|a=m}klu7Vw@u`(`7({`%|o?3vR>2W^{Y zW)8TSkT#KMz(g58$Q+qQTog&+3eQ>L2Zb-36qzf$U0GdQSzXgn7DY*;krcLATU*_K zU|*6%!fs}!+iE9?p{Z`%O|fAh(x3n|34u_RJ2uuOZ@p}kKc46!r0nF%>^q<_pt;Vw zK*DY0>Sr}Q;A-vW@eUmT^%<85-0X^8D*!8pE<_g8+B18ur`02(6V(GRszTY$Ho+_L zgfYYG36a%=hjf@>;%I6rIN=s~CZ?Bwuq}#eq$p>zkdWuPb&geOh=eHKJJ59I#}D;E z35mWC!@)DuspnT!?4LC2lreR$WGn8tx zP-&WK?fU&eP&}oLG)-frLTH)yS>9E#j!^+Ih;>er zszx*Hy(pyuUF_A@zxtPd>6icWZ~y0~o;n(2|03}1`@Zwt@7;g%O*f^D<|B_h`q)<= zZ#0_w_wRqpTi&v`xb*lFhn=&*XFk|cVI>kPTdt8{Ds)!biDLmT;;lrA4I$}rI6F2P zDLtH_GHV7ARE$6fps@5N4XuF!R0Ied%-yXm1^@^?(u#t;8v&|{I}3z_)^g#UwHA^f z5w%p5d#~6dp*GY&15!MFS$ao;rT~nSOsgN%m)X z{~O=9b!BDclFMFv;>3xim6iPm4j?M$czJ1YFz8=;>480a<`LLCU!wuRYAl%GTg!#@ zd2S2Kg>}}ttZ-T3trzdZwWqt?=~jD6MUnS19QM5r4hZqCT{8;{r+R}mmZ59Ltu_UZ zkBCr(Kpv^^2?7d{mS?@QN^w1ox*eR9w8`j9)A{l`Wt^*s8~zOdpwH`}O4~&$1IZK< zDQ4?Emjb;qqoHn4IM4Au#u&=X-K&JEqtLGhKY??8$+nPSY~EMq|$~45ls}4XQ-u-0{?&2 z|6TYJZR}JjB8(yc91e#fK8j+c6k-{o2UM;993@F&Ow<-8 zKvD{TgM(3-WEGer2+SOuB1~j%{;8W!FP#3J-~KNPiz@&WC(Vm4deO@2dT%fURCnF| ztG4gKi?<+qLNbV&IQZTXl0sAz%)NjRfSq%a7wig98kM3@0Shyb z0;E7P3)Ym(ff%GvsmK^msl}KY&8X27tsPR~OWJs&*>Sd5?`LMIr}WHK*If75qmLYY z>TsGBQ=QZ~Ulga4n5H_-km=rRwGSM)XxQ(qEG^8;%#eDov}P<~qqv)}@X5aoOe$lk;8+@oeb3o^Y>$ zosfAZtfy6l#d&5xVg{z5KA3pG5bZ>j)F=Qs+tSs?DzkAm!-hUys)Wh&U9YM7FOJQR z&dbyCoNKI6i7jUxHv~b^j|_J8LREO90_#k*fk>H|y78J|<_mHNH{)JAzJtyQ#F~IW zwtsNkDog>kza_>G+y%SN5wY257-Nc}U}o=uK!waHB1+T5dl3Mwb&19c{L9C=eJ~>; zAsJ)5_jx`PVMIMbb~$LffvVJ(jY}C~7%ytAw}M4U00XX`MkdSh0fQAFZ|!i{ANKpU z7!-MKZE$jR&XU$~oalBt(ON6LTStVd(`ls!BXI_WP%NTn=?(ggI7$)|E1g8jsPPV{ zdL@EkA#XOD?|Rp}R#sO3@DD$+yu8|Kb#m+f;UB+pkerTmhD1 zXXOwAW6|`A-UW{*scW;2d^fg*g~6sVr^PPj<1!fGrYE#5IPYP36@MBL3?uIv(>*CC>>{ zaIG!owturfp}MBV_A;dJ^7+)k<)H{ffo;P6dzq~B`fJ#y5&%!t`T0x~d-MaLmnPnW z65qyi_&0~cFC{&<^EK=K!{p9iJI~bcm#}36E-|FJm3dho&nvB_26-*99_Q7L0DK5X9_aU@lwU51-6#Q&ZXM1<- z)Y{%y|2xOJvXbRPqP?_h+yDb8OmVB?l$iP9F#hiYSDo5>?F>REqrCgv_20gZx}z5L zWJ`!E;Z|oa4hL;zxg<91rs%YYU+5Hff-ZRq1!Ep@A|Y|B)L9DUQ12oGCg+DyB5kZ z7vZ^)ltp#WMp8o~V04K3V(w{NrJHNJzie^Wx1a`rn+h$-coZAkn}O?`J`S0cM_~Y? z!%F_GJ*spiq zx76iOTb2Uh!hBW@wE;Oz2-uDvd@NlMh~*U(D3@<$5&aVrv8!Jt*UE$BM{?Pc*Wb>} zLxI)#qYr>6?lkL^Ksh3qB!!PrxMh}N1 zW}MuuNH*c<$4dlA?GSTDv}wyrB>4SkzW8w%$I@R{VQ*YE%awmu zSN_^Eq&sN-!J{ZFUpm%kJZQG`)hMaYMcGh`u8FFy^2q&f$bM;)zUnj1N0L$u2qi$q zL6JY?!}2(WR(xp?Y`#U1+!xe*t!y&nfGxy^jr*Iaieh5X z$O0Wk_PINL`2B%WaxU-ndgB^N0O#}4xns}yopr-Q5Z2md#oKmG!(V%&o|kyX^``Fi zr!b@Ek*D>yAWENq3U7b0-u|xKtzm)i<+Y;iqmTm=-6ByYs3SfqyKlL_+W z`&4M~vipC^1o2eJhQ*2g5mC?o#mtFnsuT_GL(oP`OquCxj8qMlkSWDXVT!r|YEXLe zR4*Nx=2}cHJN_BE(9!^MI>K;WHMu{zAI~+`w*B+t z>3|?Hf#_I{tDT4sTl^pj92gGOr!1QltOkdQo65*1yyjq7|8|&KRK!i=h{Rkm)=(vr zGEk(5I2{vuoqMHwYc7QXPYV4tHKtxZ1%xviz56L=FChU|09=+qBA%J-C22{6R!X{J z+dj)K@5nwED8yN8x)K-sEXLl%^0`@aI9mQ$y%(Xa`*OZnv482!YxiJwc^}uD?LHlV zIBxwk1mE&wC~wz!@ICqQxU@wXcBOQcJt42~>Nh zJ;>@f z2n-dEET6WsA%_V@=4@z^&c#~V6{UntPWH7DDWIVp09A8PGpc_V?+B#NXHbXExo29J z3^1xPCvkSF~}B_WW0_h_4z!`q&B7f!58N-ofDoRhWE#XNN~vsFHUribVJwfo+npu_{;EFgL70~iLBl{dS#qyaTTmZ{89bc5q*Rsvn8AK5Z<7*s>Af6k^ zPKytwN=&i*78NBpL0^w_c6XL(kTrG=J3ljlP7C&S~x8g!_?bY2h9cjx6qd)e$9 zKj4NaWHe6o5(>la_F#`xxXjBgIXoJsYkr##_>779Rmrs%gJ%LkNR!6pv}h)5H|WI4 z07Vl2X!UXwc-aJ^rxyMpnuk=8Emnd>0AdcW7KmKRen|W8XZ}<$ff}6Z2ov65Ea)dg z(Y=YeI6`D(7VC1yet*xo3He~&(<-5+W?IA&J6m|(%ke%TA%U3ZScLz};@f@*A?5SR z)Z0n23i(S-&szYqG>~XA^}OKtvhenh_quK15fG!W1rHYv-^L&Pm0vl9V+fME7)AIw zT{%x*hu?ZBYBYP zJbpsOhC1f8$;B3CcGOyn;6u4(A&$(P@DU{p&NY#Ody7F5wFEwAR`Mf`bQaBb#i*e< z#Un7O%63!IG00Ey&w(4?URihY!_31*oggI0p`Kywp-_#GDKb*OE*!ZrC89p<1_2oK zX2!vr2!+=S?OPDq%~!B+`rn_Ys%xw_N~$CICiFN9`}93bRfh^bJ)pz6YNlp8DI~Py zIJ!=i=z@7;*`(MKNQE-(u`3TXz56hmLEdLtT3SH00ipWCV_hXwrP(pxxWHOd<-M;V zMf|=0?_Na0;Ooc)8s8bRkXTev3v+ENt@57bXXRY}X}M3p;TnAlKd=SntW-Q1RpQU> zOqH(#2!dObWKGhrdL%0|ESc4XL&aLel z#4<%LTdt_nJYpq+Ya73tvJb0k?~(NFc}nb|sb=G~=Pe>2;BY4j3;6VH?Cr7VWt#GJlkoL4MtT$W zz911VDU$z|R)&c9H>7yhnrGItT*$qCX}sZPH*6bDXilC{y_kCh<5&i2{YN?!L=@x} z=?I}tJTER^hT-@<2d~YqEqm})=#w>e!DTX01r9fMnP(S6pH1-WU+K;9)wEy+`jqY%3?D_PJ-i8+6 z@>E`bUC)h=8GgA*)iQMM$Kdmvx?6Q!l)@4*j+IO?=&1^`>afp{mNVipcNWm`V9}{1Mju zUli&d^IlIJ5tj{K1T4LyJ{y_XDxi}=ncNq67G8~a6;-)S$fWx$@utEf`sH9?*S$~z zbxP+TfmRv#xow>@Ax$E34+&N4A)uK1zis3W2xrHO4lgrxC3*MMT3V26+!~*kR5qV5 ztf7XYkYYJ2Tx`$}8VOYF*ujWJx4N&~%{ks%mH1a*EOQB~7t}zF^ZSz}E#In9S65@~ z!o*ChX+>C(6E9r`FK1W`nk40sCEJ*k@s{1Cp{L9&?}E}I?T9`k{2==#I<=5LmuFHa z9@$s=NrESVnEB_BGHbfCrU^a`@*>t|csfBM{kj8Q_k=r6bHbseBo2dEn@hfV+I-W^ zEE?LRKoJUxB9H~6nMI$(5!u?@OdqKGjUisIs#(2AdYhOa-B~K_LyZZU+2&@OUu+I8 zh)9p_3%e819qRg_tDD>V&JdGh{S;$l5Uj$>go_HR7++2?ryalICoo+GHEEnR&U-cU z#>obguS3Xxvv1IunVBbKR&97<7gPn|HDZ?zU43(g>ynI2UPg6Qh?J}DfEyw{m2-=^ zkty5T*ch7)CdX-u{9RhHss`dUBM3jX0YL-C#m1V$o+s!xq1VS(R$?Uy^e{YbA39-K zWW3xY@XE<`J)se=2v3vKV+ty<*E#@r^m|%&tYT&BI)v7=KkV_HX61-p4{QU+#Fm=7 zh3bHt8@^R1GqOwosbJ~n7byP;xgJUa`18m{_T@c*)TWY(#*d^E|1xzz$9G&)g(S@%AAxfA!fYoHbySQ`q5He z?MEB{uP9{TRU@`Z=npHY0A*KNMc=wseZty`k{2l z0+J3D_*?+56CYhU7?*`NAp2BAyY7sD*i!L zi1~}H{Ps}|ls}qP_SG4|m!d9@@FPwECn|mt4us%*9H*4-N90JudkKiaV|h9VQF+R3 z{c(X$MX5>bC38ynvQ|sJ3V7Aj1e{*w1ss-@tiLt@s8G@kH$a}V@nt3b?e(lD(W2kz zl~VMzM(p)Mrr~Bd?|ysthT1ifb&uT^*Ya}J!DF`ZpYUE-!d4oG=fB-D&AmUf5k5NA zYK$S+j7%@gfnbf&I5jwS6KFPUzMK_`ysso}EGFYzoJkTPYlsgBMx2_1Dj$ay(Uc~6 z;OX{ENPxkY;b+E`aEbp^22tvTepZ6d*&tUjN~Gs)SW~VJbCsO5t}TvI<%kU(phgA! zBFt<)7jzMrl9m?alZ9ht^3e^R!ZZ&t9h z)@A~BD@-1Wz@^oS7#YYwV}>4E+O82^=3wYAOFgSD3q3C;DY=HASZHd)vt0|azB@mb z1e40lNA#9{$f2D`sM*`L`*t27@u0!`LkuUYa|S0s${in(l}+yAZj~8DAOvIhcJ>cO z(Ky=u5T7b^NI-iEX~kM`20D>wqkK=Vl8*6hmjL7IGrJ-fFtHJ&6I3-7v`25ZuACHG zlgxkTiMS7s3^Wt1-# zk-xc+T#<~zuc&BZwDZ=63iCi$N>+6Ic>gpjgvj=6ZEd@DliNN^NPM~(?zkmPyo^C}R$AA5u9GrwL zx8py~G|c8s!UMy^w6M}{@_!?gR`axeIIccb`GEeW z)_CvUEE<(G`5)KGVp94GPc3GmeIul<>zKFcc?>5790$uXK$131>K0C*PWI=sKZ280 zuH8Fk)LgA=LL#{%YG=%ZZakH{H#Fn< zbFKlsoZ`sM&5_GA8zmHlbG>d4LSnE@__5`k^}6VTnwfL2&)uW@A>(>{ANG0N{kk_U z+MvSQ5KjTKe_nkK#Mz0l&<5GnXBK{fv)T*7+!mYSFWuUPhKAbuPLsrDjSJRU$|@?d zYClqzA%4j9aL?%^wp<9N&kjp{RUB#*YMFeo48N_oi%Ys>$6eUsA(agTW?`z5`J^Ni z14%KDo)m!`#q%~y^bMlMQ`T9$X7&RgYipLdtExTXrt$Tb8l`v;=O8CC-_JxEJh2h4 z$+Q`JO*EN^==q6+XR@_^1R*fA;-#?4Ig_nDKJHg1d z6%~Nh-|kCe)GYUxX1Q-UOKpBRn(fVQ^?5bcoE*mbQHwwED56H+kdaV@sBJJvBybNB zl_MpjiH4GkR)QrV@I`XAN)X9|BuEM@hMM=ZG$0J!U&NDaU5b= zCtgw;@a4!P<6oc~?uIuksH|vinp`RuhS}#ebzJqi4!9vFg>0*ubY9=;?kqRH7%XOP z*ey6r3bY`wKE@kk1%pVzuyi^<=-SLHnhd^RbQ~wCrS35L%Pp1BzJn!yy|oM z-v`x>{#SQUcPJobt&utpl+5Sw#=(vvYjBNkU@?=~XL!v7yQa_E&}Vgw3lN%ceaDXc zUb1LnJXl{{1N(02%3&UTPDxX%|4gR{zY2#v4c9JQM2)ARh3I6t5|&@Sbtq*#idiqT z0>~1bv~jkU6VSI4+i6Cl;mqf;ZWZQa6_-Qi3&ZptW0;OZdfJ#+*nGsy-V`2iH^o?A z@!wibe>+vMy>L}I2~W8};p6j&sgR%Zkn^QTBKwv~9m*~y7I1So50XTX+l{ z1t#Gtj9d4JEVYTOa14L|0hxOR2F>HK4J@CWqHRp`TRDrZHN*{AJJVDUqe5i@!?ueA zqcslZ(SsGzL=#h};3^L?u*D%ER^yO&l3V<(vZz@WzW3*S079)wule<550L>9uil+l$WACVK_4G-48*+SoELNI*dwRQ|oYZecEw(fb zSL8pqgJF{5osA{`r1>kKVa02Sgv}%H*Yms$Re{F-9}bknB3fbjTvk{Jw~RTgr7JRe z2DN!Sb}aU9S{j-}5H=YN_MTU+MSLWlL?XI=?`qTgX8R3M9-evYRQPiGavnwnDw=8- z3=JMW_9SD8&N*JRD$SK(;>0Y5QnS@ApQovph6IY%yUDP&rF|n`Yn$2enwK$I`uFcY zf8OuDo#O*s-DgJazSbrMXRP|p=<)WQv)%s>8sP7AU1Z(Q#)1iiQH4yXV%R2uA;I$! z72xt^E%(yH-!)SBl61N;-ju$oYUTG~tvGm;(8uRLozd*sE?dAC6=$~GO6d`s5XdBw|aZRXv z>n^OX@AleU<1@_kR*W%toFz@fp~hM-!UTN zJdX74wMd744Pv)3XjL%D2%tH(OEi>EAhpt~fx}5T3o-f;w1g`xb##?gA|V@;r!JJA z1HE?o4KK3OQ6@>H^ZtbAO=BGW@c5o+qp8=PtK59SMm~s8Wf`{>o!!(FSOMJ(VLp)H z+bW8aZ>y*l)ay_0DQaofB zPt<(Nx+)4>8uHdItip0PU7YQh94^o9eqvJhqb?6L9K5pu8lAeHBa z1R!749>5$N&bI;Bj7ct!%bh4kkr%s`l{_PD{R3#1{OCd}A-~t<+}^*72uk70g1m>! zU%wb>qJt9El(?xl(8{SJu}C0D5{Rky#&9*MK;{-z>D?hdQ;?vx>II`XQgAvE``1;i zKpT=>`*b0f3lVcW7ssLZL($o2L)mi$<_rj4RY)=Jgy>wd7N?ilV+-0k1jj_!F@;n# zUszpCA`^{?oB8I{W!pEKXIQ%hzhG&4=QOOAl?Tzfnv!kS^2B`s(UL9@S(3aj=C@b~ zv_+(M#F%C0Tx~TW2&H>qLe(l~mXg`Pk27EU`n@icsQiQM&Q}RR{b%+QBB_O!!%58Q zE9-8qoSHjGv3JbNsJj~Sm>}~XtRw4{mFMglBTx~?-hI>f&H%KBxCS@)RXJ6Y`D>Ww zqBgu`w1E=1lgWp3S8C zu~ybIVn8GYSIcPUVnuW;9kR~ouz~C5;lV60x9W-%Z@?RjE`~Pm5&FOxxpOB*7ceqp zg@MEO^GrlevSWlSo=M{k9U;K6LDuR((Xv7i5B-OvTwq`l;UGk@mv)*ZmI2WnJgzTX zm_&?OqCBmL0Q$_U6mXd=*5kTAso8PA!WPi9auS6~#H8B8$M65VLt3KzHtUh=cO63M z`}|qV`}j|tivJ~U$CtC$p4T(6*I`G$6(6ZuRjdqRF7{6}quK9Fp;;NLl_p?B<&$Vh zM12N%_OU{ZK#UU{aG`L91{Q1~UT{b+e0*$qH0)Og6*-xi0B5tM=4g930e5=6%V*+vJhOrNe&uds5>nH1F*Hdo6!`#@ z8MY^yFA~s*nEj^#o&V>yF6`%hce++p4*;I|fCLoh+vBCm5#XJ4izVPc zcE=eSC%xe4Zc>F^UdK?Qktt^fQ9 z3#+KC2&&5r19NJ1ZV!jwxx2eJkRL)R6LqeZ*p61caPsb3dv0P!W2 zM6Y9QA&ia^mXn&q`1*&`9JOZI*hkp>O}qYD;wVUXemuwNSDmy}83CLSoFBs7{3~=( ziYJNsCkV(Wz1Xz$9T+Gd!jX;VtkVGnaAp?SMhg&v9&o{?oF`gEou8RS^Y!iq4M=RA z0YGTGHNFqHdG}!ne$V^yWFn7_uM+_Pu4O~?!ox`DWe*`~xlMBZ8v+Ebad}Y!Ay7XJ z%X`G@^HIEC8{% z#W%hwyR6)CGMxS$NXMsk2UUez2M%fYMpf%VH!Cu=>+aJ#f|y^wz5|owf%l@$i#bmy z7e5~q9CHQTpYJQ)8~If&9+gowe5#2KKDb=PHt86l;P+e{7Jb}Y>+k?$+H(=0ycL2W zzQ30%7#Ad-phOxsy|y)%T@nUSp&(K59!)mYDEMjP(yvr}OqPXZM+8`wa6GABY_mr& z?hvGCe$nsAtxw=C zjLmnmY0>a0?``<)m(N=Xfb#8mtmqjX@455oxw`^by+Fe5$&I(s^A_Rzl44P(>w|_V zQ6FHf`VaAYpR@6hbF$JB@OqW^c3mR&67lxBA$I>eg!1Wrc;YW$JzAy&-cyCnAJ}|8 z-~RH$$kwIDgt)O>rAs+WmJ2Cbe1s2YbG-o8zpeh`BTY40N7X!iyZG&T zDMM%^Grvc|+qjiAMZjYdcljr;RMfS}YFU)n1(9$y5XojIm&1aS%Q?B&zhz;;U`ry0 zCkpZM0Qw!p9sW8|Gu2i`j;*e{)fc^<8@;=ApTEEYF6O9u|8Z?q&V=0M!1i>xS3sj%^7+y0_@H^ka8%*h7Vd&XB6C z+PCanR;QUmf5%grxpEmx=nfyRQyW7O_Y^AQs3SbV0FgkXK>UFjPT!C)D~(M#ETUX; z@@&W5@se;unH{0_d9l(qF0KWS7DDMS&<8CXE^Y}LlTVWDP2{@f;26%jg~AP5veDgK2|Y!?5vI)$2sdot&GYRPqCki7i2hyG+P&FPPn| zx}1qXs%{Hj1~QXRf`>PNgq4=c508p-mB>kQlZ9xQ4qv%xd{;}@xG6yBSVqn9IF)5A z&w*qu9r->Zh*4WH8iMdCP`8othfzc~?}wk?gl!zN>FOu*WY3k~QGj4;^-i#4D1&&B z?=zM`amrtETx?D@4x&Sr84?f+)*Lomr$j;|-sW-NgN)x^UjVgtP5B{^lMI;heQr|1UH&OA!^ynKyaV_N%I#Ib~2f&ntPwQZwk?^VI7L@>_nwDhIppN za^<>E=zj)XEofLI;H*`NRf&z;jo(%zU~#;8=k|W5lcAWNo=-`6*NeIs4px=!KB}QD z!4uD66Ls}mai%t6mQ;EA=;wgfP=O5BHUw)!?mdOQs*M?k2K1AQ9C2NZNJ<#b{xhk! z6RsBfL>wEX8FniaPXx-2Zm3F!%3VAf3@N3N+{u0im}s^jyNXoG>^$${_FpuVvtV(! z?3XxSn0qdlgic#u(2VYX8okUL8MHc08;AK<`CT zKP1rvefk}`!HJNps%5sl&9%}Dh~dsRBPhD<-|T@{&(Bl24>Nq-4_)cqe0)NS;D7bP zQ`j)7k;p{gI+g|>%+-LMk&u?NjTKfdC`{y#l{!>uJBTEB!4Rp5QltBFOS(e0e0gyl z3A^_X>?bZK9T}aC}+O~G3tuznO!m<84G z&6y&FfCsIB2WCL1g(ZC6o2(+*L&ZgMy&DbQ{c*9kh!!rK#MseWP!| zjI6FCB7(zb&77ACBpNn9XJp8+gJkeT`uPXks-|tR-TfYY+c7Z~N|L|RWyGPxtFKoQ zkN>HiZMX3U^AV&vx`}7y<@NYJ)D!-?T-|MR6##jjb#&#HTIwv=G|?9q3+8B2=!r7> zE!El;BZ3$?M~O6Sihn{X{MjfeJpgPV_IB_*iAoh4jRj(Z0m}4Y6 z<=|*9>VL3i`H&g%fj}38NL3+!aZN#5SX|nfB3U^aSk-x6K%*Kzpd3A^rQgky)%Dq} z?6V~YKK7ZPs>~>-B}yMM)Ocjf@PfqN%YJ^(Ir)nP$1z)0XrDN86~(oCr+u+Ah6l$; z262`fu_|>i{{sRd2`ml+?toNVFf8P0!Ra5DIF}2n&p`pw?a9i2aM^p6*ZYK?n`^F^ zn5zkT2#DS|r0=g|_cPzH3fbH7zUbZ3l)nS8B#L!Bg#i13+un2PrxL)OeiG2`vRfHy z*i+FpNT)@RbE|zKrOe4I(8S>P&j-gQMUIi5d`5#Mj}p0B>VbqZ}%NiRuDQD z8O%f=|4O69Soe#E-CA7(86}q8&p$TlLLT;c2FFhi#=T6@RPg%EfQwnA)^;%$u=(Cs zcbw%e3mc>j+SYWvE(W|T0`2>x#g_9D5FM#1+jeoqVUWGMvQ4*p&j zf24_&LQad^FGRJWLM;cwhZHi{$m_tfOVgUCW0OXa5Hr;!Wy!#o6zIqxl1v3RcaA}> z;4JNkWv}3Pt9Yf6sY~e&eU6`{Ye~Tj8L)tvHn1!ZrjECduI|D{%FIJDlcs>aitz;y z_RAuR7Pe{7#q*Y^sanR!w56Dbl#^)K)Qzsp7#l0De72OIu>XTNpp7KoV8KBJS5E>D zO(>wRWU1(#Hw>q!+ynW!ew}YGsc2I5gjmU0agZcutW|k9DZ&h}WMIl7;Ie2tvd-)S zXw6TvvmWct`z?T}jSJ9#nkD#|1EgUfF1bV{Z@niVKn)KNZmqU`2NWkSM@Bs-%`4G` zt!Ld&%AJpg5u(=sCe7#gXV_Ja@@L>{fkcv2h0I#j|3L+2XJ;=&va_@8npV7WJI0|< z3o#Dlo4Af3$B)zJ;^@7H@OG&Uz=j%}at zy0F&X%~aqS-5awXxOYS|6#o?w%G>ucfHvKgA7(R;)ia<q1MeY7CpfAd;K zPabbaJwA_=JvYE(a0@J8-#hM3+qZAmeC|$s5Bi?OUdj@BZkH=+D8w#iVm8R<3K;aM zjwYuX5M7l2z{oYC4QTT!7Kmf#VXt)|%BcN}`X$?MTzLNp8-|kW$MEpb-N|~3^;KG- zNRW;R9-h?nUP#1QZ}98pl9qVwY}RVaTYNtjnSk5DIRLfb;owli`*8NshL+y*cs*=CnkkDO)wERH*pk{xRmPN^;~f>6OdNhFb@2d$PV#neZy>9(j-}T$Yo@^F3pUS! zMBqq#Bx-t@m4TU+TF-*5yY%`~`3xAM$YYf(Paz3T`twX3&29l5QmGb!nbv0koAm zTy{rsRfI2osrZfhyxr6UbZwl~FwZ>m^E@q3tY|^y93Psnrr_SKBvdhG)ZFsO#>L^wkAd(@ zzlF$Iu%-=ipR~`-j9OMn+UMf>=2-Y}ll(NVA@)&`oP439h}7vGneR;+vH<@D8p4z~ zpN2g>GxPNhMjQ%@FgQ)C@UuYHP;2U~ng}=QKq_A26OU_cb~L-`3M?D~Zd_2h)kjY_ zQ;u4OAst*LSt~rGBhtudru-x`QK!GvT|TcJ0C(s${p~WZ=P|XW)A=xVAd`qkN`ltt zX+JMu^LWWsMdW5~8jI|y7fH+$z^%l)k48`kI-UPDcqtlI$rA-4-oma3*$lh9Z+5T@ zyFDKpv!bX;aK7R&2IDZ+@gi2HlymM>aThB@>V(BTkf=?J0||x;)qX8!f4XW!IKreA z8YDSNZwz!+{mygC>{oya>hA)%hl>4jo!MP?W@eT2G;e=cSlC(j^~=7I=f%?JJQ4q` zAB58B9B5qM?;sF!8-gG`i%kl_%icOO%0FE`S~@!*OKeL5XV~&26iY-yQ&56en65g7 zGDN$qc$ETCl|~l57*j1%NzvJ=5mu@w#WZ5<0;kw6(vo#MJ2HoK8QS#G>=%s`KE8NG zxu~D_>A(!n$%No+{fM4)#cbw5Y||L$6z4EzP7FJ9JoW0uB{jSZRWHgjoFepz$48;IHlptfS3Mt4sy06EIk!Qpo2SMt>r8gK&-Gyz+x_hFfKsNXKL5q1*L z=Zg3XTr~rN-L?i`zOv_k=MmuH>|D3zKMVDLW_mR`o|N9&;8*8=JtgmRrgDPVlX@eLo`m62ePy|8ZLAXs$<4jZlw8 z-{0kY5pu-@bM0p-dIoSDv+L{O8JUa5wbQdWa;tz$g$|Q($PZi^;???|h1QSDUOxx`9=)c8+h=2D+ zvy3%VVp24q2PNX18x$^~CMCwIBESXn#aK@nM^l4Zk9)Js;5 z6_*+g4nfj&VB#+xyK_o?B0tZp*<{1^#fgx|sD(h9j8B*7hN1Cb;OrQ%SOkxT?bNPl(=p_^MkT+RQ@ zN?G<=V$z6qXJuJc^+*IZq;>K-X+jg+)Y~%`B%p>pt658te$X z|7ykcmiM&;w_6)uvKGt)Z@p>+Q5%h3l(Cbf`mwrq-|-7sKqsk?_d9bX1aqVpPfc>( zK?R2}&~8GP+F5-@UBi?;{wydkDw8j=^J(;(maC&!z&SnAfWz*z+X0utm8s1H`q1w; zoQ|_!v;=CFDH*3N=PQ~ocY|oa8q-Sj<_mOK?;{2W=|BfJ-j=nktyY#XF)<+3#T%fg z=X(Y?V=Cxxz7M1Lpweqk{J*nVJRVFMRSJ4H#|7>U}SvzT4w#@tIa1y zIxD3eXIZ!RK^!JJ=I|LpOk=QfBs(QAL`<9*JScM(rA*`FcHYky!oR`jHq6^teG1qKhoZFBeP5c;_9ub$+{D_syV|=jJQJao z0h>P`(AEs6dZ~p%v;6Di%=_)-PD#oAPeHk<>kB+K9F@{# zDj_}xw3LZ*?hp*Ayw!Zd6VhI6ibTL>!wH@G`9WGxY(PY}yse6$hzo-n@rcB= z+c!@GsrxQ(MKabVh}<#WR;h)-JEiEb((bi5`R@X=A^M$}Bs>XHQ;^X0JadaxLTz!U4eK4=?KB=O}`9YJw=olc^HY0h0K z113M?ro8>OFuaed6j2IVftO}efxp(C6AV4PKzwUIJ@n%8>S7j;{*J~`S_ZPJC##@o zw}R)zwX#dGDUFiF9>zhBy;wW$$XvVJ`wZf99z}w1N_kb_A1ZnOb~u>v`xbVS_5NX@ z%h|E*r?zxrk4en=LSAas(@2G+@#K^v}qBjsUwy0#c|*)K)XLWO7u8zIgTlmTK#MU?6OXuF95aCA%%Z z(3sd2{S_a|krO!JmHEySlABHg6l@+nbkr<@1^1eRr-wy|zZc_p%=V_IIQ&*#x zQLVhkK!K%`#GYo(IWNiroI*?Elu{U@4nn=@y(x@)Z_dq10Xt z%yCwv%)#G%TTuOypVqFac4g=dJ&~456qLgw@%x>jK}1*EO32JD!3B~JgvgETv`*&~ zveK;INuBV!W(y1p5bC61Q)BN-bM!P`KYlAY?e=+V&iQ5#jsyDcm-{;wg`7^CB*VIv z+fT!XGB_hEi!l(3%?;3X<;Fb}OqKhzN_-PEUh#Y@;BbB+56 z23O&#><5FDToPvth)S*A#?Da8pQtR)zw4~Mi1#aFOQkq>KlDq5#SB(m0s)rBK&S2g zBnxx3e)p<@KKFDz%ON*PTt?lyor1ClnVexto!NPxw*huyckykfPRYA{cbxxe0Sums zis-nG-I2UB&2@M=|8}6C<0WBV`EbQs8q+V|@5?9z*s+|pJihLGtrH*V8ED#_%}(;$eN}+(!>$%$Q#9eogjQ;FIf!Ut>Vs&&Ne5f!{Td+OIsVgawvv{) z;<(b{b+x12kwI~GywYaTY0y08>+5T0=WS|Z)5(A~&czPB(M7VHYj38qD8Yr(H`Sn~ zl82H~2_YpG?~DgZM$*Y6YZ0UyV*3efE4=jmyqbDj3wRyl`=bQcm>JFQiHwLyOLQlR zGhM&db~L$?AbJ^uCG35?4(Fj1n}BP|5}D;o&Mqy5j3|1VR!A*(juY&O4UIGl35>NG zAkv8IwP;JC5*pW-lS^@(8)~g&%AlPm>i!JMFAY@cCog5u17LTh8UKF%q{-mek2e@1 z#vLZa?R0EfsR1&ZyUw~e1$dM~Eo6w9k_)2Ck?>{cO}Vbzkqe87phVN4d?GHFjNiM6 zbH;KeBOhoXpktTaY>CR1MDTQ@L^P-(7-qQhBM+{)wE2FeRT6XR3XE!^X-Ofaw*tlE zA-l{$X^d17DiM6Ac%mvo)gXFb7pcNLlUX028@phZ13`ZdEOO}O$O*z{EIFA{l1|0E zgkl%@--iu8vV>DA5MD9KoMN0@eLwl>@lX4*+Fu~uexv!r)ave-miJn9bmPhi1Cw6n zr=(fA-)A4XN-2|$gDAIzC@0jZ;f*5t@}r?CcP7?lLL34dUs+AQW2_F5Vq=S!!IfIl z*O$-#R`qg*Kl5#uO#^e zSlFcqh-I9l^5N4`OZ6X2jgU&^uV9en$(OQ!5s>v&GgRD#GMoj?bohnudz; zDvc{2CW*wc^Q+4NN>Wr=SqLz?F(XG{->N*uvxwm;Q7y~Aoj;9r-1uv*TlU z-#z*dQ`+lRYK2%Zh{a7RI306)V(gxK4?Onx#~yj)13P!_D9bWVF6z_R0Pzp_9CiYEClo3>JX|RKB%aLNJ0t`e1&mxEkSdaS3NTg2&v}{U=jTl zf)9vptes_UVR3O`_L`^?W|_+}mosPaRWLIk{@|5YW@fgCz{}r%-7zvEGdf3khB-G8 zV&IUNFb5<6MKq$uToL2<)TN19h;xImd@&(94;!4*&u)U027 zASbrm^#-syh!_Noc%3HKS))-`(ZIw|5mgO>yVYgrrnd@%(Hw{MkG89;tHiEQ9my+e zaMcaSdr0`wRAA`{&Sm}Zt@d9|;wDXODv_A=hVk0jZ-!EJHEj>+U-n3~m zB3-+7t=sL!g~@v_5=^yKmWarWb7+;hX_W^nC0GAwoPXB!IlOxZj}>*5fhmNbB2w4B zs=P)lpcw#EbzRqWQRE}^wB=SH5t)HVXcR0E5m5ov6jQS%O$}^i#N-VxJOl$P^L%Q2 z{Oq;4=m+1jWebBDD5rrq8+l9sOFk?w;<5~xM1A5S$9Wr}St-WCeqPa6n91CoU%ZLy{0BW^bci(;I z9e3>i@=`>P^iQr6MEKf#N*a znT*c>o<=-N=I*&Wzwdr}{+~1iH53IhHKJ_O%*>v>w?BB~$f3gz-g(#EGc#LVmNm3K z9nvx41r_hOU=|E&wO$YjHHo5_sfntHR6dAU2*G=;y;gPbqCwPvR4IzA>C=dEBQ^36 zB4~uFS~F)rmL~Nu&!{MJCM?TxVPSz9mmQd?3IM5ssX3R;&COr9bmj1adzqaySPw%0 zAX5m2Y(NS`$Pv&H_kBzg1F1d&BM^>65G139`jLievGJNG0$i4H#u)+{nur*pLhQQ7 zstsfRaL})c(uo%XG|-4@kbyU`5JV&(Xe4lwfuX5_DMI{V5i`3r1Kg5Y$dIM`lhBe^KX!RxQ>sm~M5 z!(;7|E(as3Dg|=P04B{RtD^;$Mcy_Uf>whbITv443@^xri9M!hkP{E8+B)M#N@=Vg zK{U=ViHHG+2!QbNu)T?h24TV?&k)f$$IK=!bBv~_hNdB?4+2OAq89U`DUQ6_GQrq} zz0=I`%*^!Gt8VW2AMyRR))n;D7D+Yl~fz%|37Znj7G zW(-OcfPfHz*|AgRfC;RN3Xu|-Bb6rc8X|LOFY~`o`Rljc{;(Z9gK;q>WJDzG51jVclTGc_!+(wF2Iw;ZTeLLC- zq(miI$1AF<5fsbcK+6`+=5v8W5N*Bz5hx*eA$k3qa4Aiev_{fWNC*rC0F;Dkgp?sl zunIne*FjVM&=zG(OW(#v>UH=_8>0wEKEctChBn^&SN8by*2h0reaU-Yb2JvpK8-gb`mY+8c?m{pCiAzAI)84aZ&$)Bw=I7@{q}6K0 zsgvm5&43Usnr6&QVi%zqdBbM5mw>fl@#}IgfA!19)QMRCi{6P(V=X2sZXnka*w%h@ zw=lr~Xy`OG6hPCQxp^-l5o*5TyM2Fv^=$C%!7tfwKbMm#xr+4m|MSU5D<^r=|_mR1pjuVn#-)Sc@(gURJzl&+JTH2|q70;rpSPW%icGBR8Jt zT(`~FyjKW6HMG5x+7;g1x80P=*o0}Xs0rS^4-5f{qS&=-SC(bhu3hc*da6+mk8(XY z$H`7i$sROpd#(HO?QOiJ8@ye&3fO!PE`XE{25J8@g`hg{br7|bCTT0*7F<~BBDu0v zP?}F#@$a#EVaMcHgTTo0JCvz3HDY+}B{U4j9eEo^JoToCfFO*}Df8LIZe7dyD_1+Y z%TaPnK!sMBJ7RW`7oWUdsuD!lIbw&Y0*Go`ipDafP2*$dE-Vh((k{vZLY5H`Ii%d> zS(ZhOGh(iYD1wY&BoZ_l>fafczVZ4=2)?&4*PEN~)gFig zph*lvL;@s8`6-43K*)&1>&YO3t|H$`)lgKuCIW^i4Ad6U%@52> zvQTCHuGYRbt%6rk6{)=jF%b|o1q4Lrm^igqi7?Bup(_r|d{qau7;03uTI3?7iV)F| z6>w11*JiI3d9i8pII}ZNU{m51VolK=o134%e0A==gNKovND3NMH8oWrHbg{GGz16K z#KHoZA);W~;Zr3LfmhA=NWA`U2DC0BzV@OP#DW>PT!~k#y2~R=BStG*UcZtt2-np-eoQy`pVm0< zTJLOQt>{)hjT><7Z+=Sl-JYk-^L*>ptwc0CJKO7aRg5}>1VN>2m3i(W0FaR!yVw-) zA($!=0bvzUF zoeWt*ByrQQgMctB5u?LKBJKz+c3MVra~$G$s|^T6yR~CtqSV?nfT=@bY-+(cDTnDr ztq`9uRu(BiIvGl0f{7ZKRaJ%DYj?((k&yd!=npCeL@)*gup#(2<)p+^L5o^DHfTy< zqOneUY^=3+&(0%99vJio-R{!D-0bD^=PzHlaPj>4t5>e{mzEaht_`|9sjE=e@%4*= z$Eez|k;8T|vu);qM~@!&_TX=PGMMc0| z019w<J&S|edKtK~fBxZ6B zR3#b@nAm06`Sa)VvdD{~_P#kIp%EaF7!b1o1~q5qp@ybj*GSt+B>E&B#cQOQUX4_> z<^LpfL=KjL!epb1IWPjJm`Su~|BHD%A`+tr;{7Wk!PiU_8DeH=QToy*-=M*nN6@@` zYrD(xZFzHR)@b<^#Jas6lzCa?H0()1nt4dPR8uveuWl;G#=;m$P zCTF(7@&#u@pZ~CKTh-GP5#;x=7P5AI{Ha_2ozHiyvk*ecik1S<{^Yo zSG|S#LBC&DgR7UX%w4j_oOKTR76Z8t}NOJ1S-|VK}AKuhMA!l zh@dLO8Y09GRshW6r$A`UrIxg;6zOOxA>^G-UKDXx1&z7}M)pLvH&|Ng60@q-RV`6~ z0!qo`V9Z<;dD$5o4Em=|o!YWx3p*B-c=d|_5Ev1lAQ3Y626g6$`U4eFlc;b;oIf$e zE0$8zkTP}&^3kYL2_*+{_JEetUmN^o z{5>fbmiNv)&o^)0oMqYN%a?oIMbXgev<;!#>&FX{iKQRmw7=y))&Mwe!X!YhY+f&@?M7T=Wxj#Ey#v{?)7?Qkzs~tI#P_{aOou`j>U>9 zB4$};O_MZ=^=sL}%W6dWuVj=O4hAxDS(X?e00F{8r#-j0*zI)({XUGhkPt*RXn9AE zjzw_xN=rsmb{tbXcYe^5FfItLY0qFhNTV4T66r|hISu1EEm;m@vnnR^MvGz`sxR_l zvD*tFI7hXa7>Y=X9AHFLBj^zJK#jRqHH66WiV2Wl1dT~+xYcRw^dg|kvMkHN5XPsr zYym`2F;xo!psUP!s0vKTlz?S~%d%Xo;1CTIfgtt25_Cv~Rb%LPY-pvSF)OwQ6j49%G4lchiR^JLjSyRHdq*GBb8g%oL%P zpdOGQ%Uqsiifr+?9BInU`=~eixakIBpKVmiZhULl_4|^yKJYP|T8e=&A!rDaj*uyl zVtHL$RbZ)V2+&>Xy2&=ChkH@jG5(x;) z&Mj3{t*WZ3#3-u=p_93(A{)$A3v=^3w`?{w7wu3hsT|AeEm813H>2j+#@C9?_&y=b zwA)t~mO==^NScuJO^|0ZBsqG2nKjYL>BTT}inavcL}el%GQxgUjiVDYM9A`dets^m zt31mxVi6-%R*Xg|Of?@6qD7}N#b>Pms3~|y2*Ej*1uDk%3?# zXiyy}si1_gR1GqhwG=WhW@?}k9dZ`4=n`cuRk11MG5s&OqrkeoJ^&6XA6cIg$qlhi zAo3y#79$^+*-~^}a_5YSII4R3%{Ql~r}8Xw%-|d&Ic7v;N>EEhjBs{FV^B0>L>4o{ z5JZ~}VAJ@G5lRS%ifM*J4N=i3*6u;$N@Es=a<7?zc^@P;*Hyuc4VYO)x=TxgezyYD z*nR};_j+ZkrK*wOWdJ2%%zBPP2dbzB0jyFnLRZ)IXrFa>6UM)?CLeRvEt;gxW-(iL zdsroRty-|eP*oO}dInIIMTkw`^sw=J;&BE5tkr7IY{9|6U%hs1ZebyBmE#j*%p6u3 z$PAkT)JC_Qn_pyq5*lGY{d%8%d}}|!RRxx=854b%(rF0IIhvZ9ATYgrX|dPuSA)D& z7I{k>w+yAIP$G6X?EnA&?7c~oB*~Q~_7+t$^Ch<2s!)Xj&>LnbJroLO{tz#`@MrSI z3#UhTXc11M7ocm&%FM_J4|lgk^}RQTr)qAoWL5&`1%*KZQUYYf;_haq`sw$+MWObz z{*hm)#q~k}OJy=x=)eUj_`yM&NbUz~8r-b9#lowAsA6f#DW!lMWAwAA0dU>Dh#cl{o-q{sp?-Zm{C2de9{wv}jSyyW=0w9c3jg z%9Eo`5*9>MF*EaUlL9O~zSEXTmNT$I0LV$zl#m<~RROit2{cwBN)0fHO3pc}n5TwW zR!dounke+6v@vhcI7!jen1Y#zim8~1sHqo2n@YJ|v1DJNh)j}?$9}!pa$qnd1Fq>I zl5H4=DP$CHwX_$*tezvvE;cEN+j!n_T z$A-n zMMH9$_3e~aZQHg@^{by=td(>s1cL-RDgj}*zP^Uq#_;f;LESlOoeJ<}|HW ztF~?3#_1B*B^q0@-}jdftlkIN9S@=zOjR=znJOX8ImBRw#LNtUH#aw5|MNeq=}*7- z;@PujMD&A({6`bQGWdQ3JN{>J%>8Mk_@e`?_HU~n`sDX+0C0A;1%m18Z;#_x0>;ZJ zALoM_*8^+W5k&t0AGIewUi=sP$!W^dG|fW2s+I(ux+1SEbO|yNS|IR1fU?a2c_t?LxKnc5 zS>WZ6$I)K-8->LPbN+%7#x%2(Zg)pBQz^=`GMqDYPV0oWJ;=cffL!98QVt=gnwU*f zQUqp(!nS~zWl@g?5H(dxDQ6Lnx)iZVamop?O+&iTyBK*q^y4^)2&tiJ$|5QXAUY!t z5Y45k8)3CtA#$1~RShx5Ze>I$s_F<6r<4xI<1h>qm^he$ik6svAhZ%QD8_F(UH} zE9QI>|BrhyaK>K%1RyyRB8ZY?KR4zqmQuqM5IyyZY?d~G%emMJ(#oP}7`}V`8fPKc zeURmEmdeeB%$|6{0FY98|Nh zz22<*aeVk@tH$9WcY^k>cc=bK1?TQVAO)t&Vq2;LiQsAveP>N45B?{9azv-L~R z3L`w~S#_S@nHeE*h|@H-ZClXx^7onnVi#K`5|t1_Fk@4X!-gW}UebDxRy+eRG&L*< zhn2_yG^D^BLl}mEnbicDLTGlo{{77@8#b|NLc?|Y2^5$a0hu8X`)~^9F?(%X5y|5? zVcS$xhXv08s#>wnQ7z=L5~NXu`cQn1bH0#*hytjGnQ0j)R+mggmyU7_41lueI3*DS zVl@~?K?X2#GE4!y8d5|>RMc|LIVCYQLlMoQ$uMOBj=}Ke=5_*G?Rzmb(;((SPASG%46)>lJQYkl4^aJqJRAkGA2H>Ez$`gPLgs zX7&K?oU@s^y{GuT$hq~Wv*@a>=#TYYBH!$M=ewVJ^C^@$f{_{wqrAPoJ=<; z46F=wfYhZj#-vCh>T&R*YJjSWAK>^!B!p0cVMUl(7q0MHV<%>?Uaz~Zeg9tX?he!Q z=cF~%sCw373?T%n-R2=S<2Z>fcelFeAsFDQYnkcT_j-A$W^^CT-rE=P2`d1U7e+;` zr7}kz8bBMHG);7N=A;HQuU8w9^zzjUG;d5XL?z$Jt8@p56fh8@opQqb0;Ft*LmxsU zmx7hJB@>mLH8Q!czllM?Fx7RbHZWCQ3XqUz^;4*Do>2y_~PpFoB*bjk{}p(G_0u_QC4LD zT8LnEflududUF#ZiXnyOr@#2~|C}>1L5(x5SZujtmGg2YvJ>=*M^QPY)TcO5{gp4?;5xO=E;fGUZ%2e%D5LM?p_kdi#Z^<-%@SOCK==O(!%s^V=&SjWV5|z^~s$P;;RuHhorc&h9_gGRe zx5^EZ=H0$+S`LV21Q3YWb#DHli4H@5Ovy(}fuIc>Iokbp$R&}$0HuXSYd|YP&HGXG z3{=F}gm%@1w)y_u+n@jJtA-*W)bI#il2iUCiHX6XAMRsFb(_8+QGoS&z3-3L$GbMC zjr-N>mzmk(Kwid4Gdg!u8xeavy#W%(d3!R$7@C{wo6W^JQ$PhUB%y3>mrIcXZwODm*3wwRJoKG;{0EgqD zZQB@wc|A!npw;ugSk=dYS{5}5jR0si12~KcnU$K9R78{HEGA+p=PW9spgK-zN~s@) zDdm*1n2OpSL$AC$46xorq{d^lzywRO7=XFdz38zFvZ#m<08LXHV(GK?uv5`I4cRoS zrj*qXDd=1PQF&A{6H_!G07Fy}A_CMm*Kbzqj+wxK7i}=;?gKzVH_B+~2`Kj`&M9a< z8U_M~B4S1u=a{RRJ1=86q*iH`Xe~l^ zU!sE4Smo;5QK$GQyuE%qrZL9I%Cwp*l z>cS~}4$ufoDk%dp5djGxs)A(zo^oDAzMY2u_Ba2PL-^{epK&BRm34zk2F(|nRb+a9 zeSH|ljKQE&2x=fDj}-t|>O|8A>JO$uOYy0LTW*^Frg2~<1O-*B&qcjfP?4q8 zm@`w=EO{7)VHn17^vZ!^SBz$yL~@S*oOI}x$MF^4Q0TTcv5KErt)W2 z+IM{hM6_PD-{0*76avjKqzd+IwpA?*VyB6ZZ?(?7!7{tw5CPY1t0J>4(*^HM)85_P zJ$rVAplV2_sxxH*^|SZGj1eKJ`H|Q&-uo#Z`f=H1(uFJ3zN?V#ChkF&qhrBeMctT*fV5>xG#gE@p# zPm{T9TEh(xN~n9u{ZyP2X=iSwyl1RTAmkVp zqjMB}q1=cF2?C+lh!SAewnR3K8AZ<4Z5u-ddwy{))A;)K=D+>T-yp!xe)c7ScCi6( z6g25tzPLCehM_;+9go6|S_c$~gCQcb0)W3TM6R&cSDB?eKczH|BLH+=*S0MKoL^ot zvzd7A@C>jXCCHS3S2If~9gjzjkz+*WoO7ePjJj}GJ>M`Pgw<+wet!P^`SZ4I{l%DB zO1YR#;7^0UKL~X7yWy)(kAnL+qWW=tR%I7NYMXYwUiZ_Ob7tlc3=m|F9rqrOETB5? zh_z;`h=od9;g27h`=TeRQ%Wgk6|qy+X4x3<=^M}BQ8n32mAZfGa6D{RP3R&3)zX*Z z{YQl3@!03&>pO$B0RwkG%-MOwgX$?42nkVU5f~Ajot>>#>vz}hzkmDoC$C;0C@lIS z=cDXN$O4#hYKjc2zUK_?8~%2*CQ~W^fD<{p{l4v5oV7)zp)ZK`<21#< zp38tI$w!%<>w|(5bKMf}4+p~lNS;8OM6#-9etPLjRuPfW3oF&8tdeC)dCYknr(#%B z1p}hM$b_M7D8#mU7eQ3DI_Au55;2TqFp36*KB$P%ufsGqv$4v5ZvVH z9fzQ5Dwb8G^gjVEI)>|pixIhDZjik?$b(z|>6@>UO6*zy5>o;y9~64@CRJUKPneq7 zD5`Z#;B@yqMMckaFcU5Pm|!L8zuePH@V2;H@DzfBP<|?unVA`&kJ>G(jFQHjiK!ol zLCq}Bb6rsZ&si%ki4<^BOj(ga0Dzn`BIcZ@Y05dP>NHK$G+9a@0%l5No>`{KNbK%f zQ}kf3lk0+<7Yu5AKm;)&V1L-N*}7qw0998_^X%%fSJ@r<|L<@9 z-*p2&{o?aTs;UTvXfK~VYcbp&4}(FT^07~1IW()#w1DJ{9{P~Aern68==rH|&%!iK zo6Y9gvu6%>M8qjDRC5xJkdV+3GL=I(IC*7e!#M8uhiRG)$KyDRYHDgor*fWZD=1)G zM00WGP)Tu9Te=zk^yd!-UHz-@hz}^}-(g(%he_M`A7;L|I3K6!c<4n$L;{j0Avz83 zLL@RnBn&6EwpcXqkHNufCkDbigi!U9uJn_zesMRJPm7SuN!m0XQ4s`Ptd|+4gp~yS~2u{MC!V0Zi~T8E}9# z*UB3L10E%RQ21ZOs%uSni zckA_Ly07*5Q4dc+ns3PcNE-M;pL`3i~3is}^0kc9tL5^YOS{!Hitg!EU z$!XiRtM$t7-53KAjpIN7OptQUl41-@fJ|mt1#*@tWg?>0Iz|K$Bm>ZK=!gE8)5J^{ zXJ?zH4a8jxdA#_dWT7EMNArLX5niYL% zKTKoFQ_53v3fGSe536nc$zoz8;?TslD}(Baybw|66qi5!`C}hAK4~0#(4g>R!lM-h zM&|RgbIGDfr<^opQF9->m=P!f1Vlm#A;cKH9G9F?UkI7uM;s$k9CLn!(UcOMp`65Ap$VtcDvn=g9w-*p?yrbSO3gxqHpQsBJSnOLNql3 zxHvz1`>wmay}8@pU7eqqDVk8}*+qwH^W`Ie$U(DUt+bgTv{?p#7{Yed4aY&cb@qbd zr=FUk>(zT@vP78G7{NSoXdbGf5fC%S7{+1hx{d!>LiHknckgdQ^O6YF%tU-Bhh_$1 zYUl;Po>t|bKB7mjdi2A-9~+li7tD)9*r&W7#z{&(5+Nv{h#66lpO{HbL{_550kT{9v{X-eP?mU_zJY=>4s%5Zj>Nb!fRa6I9nTTQ&WYi-02M{o+X=F}zF=0SLCL(U5_n$(s z>TxiS;g+w86SPhKK6mQ>=%kQVCct` zJOY`XWc`Z1-R26*laUT9+*y3DPaXhKySCkKV~hbntNux6FHjR122bIpdOPb!-Yq?R zvo$MVj&iEuRR-X!$(uKC_xr=;`B~1H=b0Lk_cPB&1wtgUY3kdyh5PbS-?~|K-SFMb zUBBLDRZ^k*(nGZQ;Ng+nRmO*>Jra?1K{=}#fh5VXiTmSmwb@R|+e*L)1@U@!w;Km$ z1~Ue9kD=S=BZnpgC*nLPztLRKk z%lHY=flpG~_bGO2K>n3u>dW1DHJJBnDzA;>?Zr604djfHx7= z5i@x?GN>`bCI-IUL&u6}?Bf&%W8_e6o^wkU05wp_dEdVQFp*qPmMR$PqHWV~F+4TH z2La{G6llF_o38uszxsO!@n(NVS`>?VvXvnqBM@Q=%rQn{0z|I3Y1Uy8AR{p$W6ftk za(ib9q=oWvN+G(+>!@Tf1fWo^5rSD`rhsx9b0u}r0-^yh5#<~K8zR#Ts)lAYk>AN% zKK0RJ&DbzC3-cV!AMBKpV-XBN0gmHDV5TN{2qw?gtMjfKC)ppTfD%z6N~6k%8o&Z4 zFlIJV(ZPTup-#CaX*Vq~13=5bAVd%X9sB8UJmxflO{TdY$1!2TJdTo+TwmX&WPknF zfBov^%Rs!|o`>e`&9~nsAP7x}fuM;YatNqK;I<2zDcR*(>3xe{wwh{n*Q}synkIyR zB{>2BunG>rOhwXY2@w5mt9Jz`7&3*nArbI>)N7#}=KEBduxZ+htIO@#S=+WvjQ(4e z%Us!2>`yG#9|>ReB+^=rV;)-te~k1MAezV3K=F1p#FyLc`Fbs)rs_uM!+w9b+sQZu zK!57gyF8p}S-{*%f!L3e(M2#+$$dXgV^W2=S!I#C_le`erMk$xCXSgloAuTCrj5ps z5fxBR;;uTIY1=mUL#0iAJ7ih8hnaV&8SB*w;GUC#5C~KW&eQ5}*r^zB04&z-B8wq9@uSs8Zu5Z^0f}pn!M$cAQ3b@N zY2Mwwk0G{A>kz|`6fCDSPUDNK7jw5W0=dAt_U+7&(OvyzRX0R6+#mbr&t6EW%ma57 zu)(|Qo6QCTheB)B5=L<#0%&OJCE4g!T2O^yoOb)eIRyjDep0WOpmq$JD@oKKYe~i` z)-*86YCwXJ5d|!X=Ik+?Wk}|xG|4$9-;GR>6l}BIJQIXf82Y~7A6kS8-%M1Jskkvq zQPdC#!9-+s$~rf}HIr#Ej3cc7sZ0(Q3E@1I3!GJtX*#>ST(8z01tbI_#rYwbgA0m% z!PP$HiEtFB0EI6y6;tr}LBX_)xivg^yi-a<6k{yCegNRMT}=umK%4DZGmW=*@5H9< zs@*ia24uC#1zcc^Dh6W~;y7ltEN$fVW}QUFoKW*HjDS3)d~4oQGu1#lKr8(pWTt8e$T5-^OFBbK=1+&Zlb@N-&d;}J z=d0C zGqfC;Ej4trdvUQRw%uyC+xOFiNHf$xQ6`dX$HTB$uR%_;%+kSE&LLXtWng~%M?m6u zcXw!4Yo9*ptitvfcPal@47E}*4!g3Vs$w!l8C4X}^WaCxv!KNQhG`N}BUFI>euoH2 zt=pVq+l)D-!?Yqe3`ZKLX2$b~T4*>XL}D-SQwkyaX^Cc2{mCsk11y^J^`UelE_rTZ zM&|Edzjj3d0s1^t@m}W5eE%z)ifzh=YIS5@5SCy0+3ZOMo~^;PWs(C@IE9Ytd|wF| zsJRsoU>;zr0jM|hxk=9f7J{jc(|CDtq3U9GDOY(B^DU)w(~q5?011r2!h?rRM8 zfToFopkWB61km?+%K2`8c*`N8Y#M6Y^_N%Y+f@jnI;OEV5fU>ZoU$CmL?;9bWHI2n zu_Q1YkAsjxIA&46yTg7M27nw%O{Oth(uie*i-8aq%=w$K&yMJbEk~0K^!#+ilY{&XWFa1Hq45O#kim zTL|9H;eWg&)xdBX#;#p&HfuyOl_{me;V_QlX0t(rrfHhCb?ff#?#|0G_WOMn0YqkQ zn#QYOni%7Xe?09~)jBhbE;;xe9)vkTumrFAgJAs&G&o#wQ!*=tFIAtFo*_`eM2xgb(XK%XIIP|;S{`_n^zxSClP^$N;cL;iK zATw6Z2Nz686GGd>yTf7Ib&J)+)a-1*mv`8S#->HY{b9dat%1?m zAW(=QtlPHVAHvzjDp6Y0Jw+Fb6U0pfAng_G$^CA@mGXkO^CPqeSdejOGCUm`|PvNhIcoO4=2G~ zOjIdDFCR2j2uwt!@T#tN4^yL-h2=BA@)-9rL^e~AyW3sI0Y&pLmcGVi2-@O#DWJ!_ zh;ZVH%J7lNxo$%s^Jpjo0wkVSX4l4NDeC(|BF-;)ahlO05~Ru)8>%n@fTo-PAWwsz zmUGH;8CYq?L^xG?SE+thRIkbr3imZbXl6N2+{TMdceaWf*7Giy=uu2J(5(qAbtN$iD2ohPCN(2ABMub1_NE`cd4GKv`V}{Ua1_}e4{4kT zH3x`jOw=MsRx%?4RBHiQQ-3r3!{1KlIKKMo7Z+#UU;X9JP1F1LZz2fU1Tq<-DS98!-4ifV=@+76UbM0_0oj8MQ-3>l;qlO6QM&TmZN-lwOc$qf!-ZA` zA04Ri_b^C)OpkW|_x?V=%I<4q>=TfzTZry$OCED;dN>|;yWQR0UElX=I#*@OQ$2LPOiKh6`JK&?}>cJ(4f6w=2)mjM}kd^@V`=6*1 z0x$+by1m`4x90{mUP%SPFobCwefTuT1=s0QB{5ED&Rn3B0SqaL+}z%V7_myZeLE0< zVVqVTRCU@+06fed^qx(0_Vyc0qK9E54kB5d0I(v!DqOBA7+J~1ER&XL%EK^bfJ1*g z_DBDzXJ=%e%GZjMx5c9lTQ#DIfrOqDAQ8zFGEsZh&p3$Y{RUjLH_$XII z6A=x4ABezhibN%Cye6U<=(12<)uXV$MA0D3NX}iahK6E!IO5p6xM-hs)Sw#V_M*#& z{@bGnVlR?SK}DxDPD2olU~QoYnK(kkGXi6*Q%+1o2bo6D@6v(yxjDp9!PFXq2*^OO z>CU=_H~;`iYD^;NitW6iO%qmYU5&qKB(&@2?KyA$`Y*x8zx(@t+H^>qGK6fV?h8Q# zL_zh6Z|{=_f8foy!d|Fts6{~vpqBlW;iI*h{98eWNnL*1Z zY+{50rj#|KW=RuNQ;!08INNr6-gO+f&iirH}T;dCS4Y z&S_7rs`pEYmdA24TUKqjUX0xEX#fBq07*naRN-E_;KyOkN5>Ph*j$!7ePMmej>HfC z?Z3!|sG2_f`VoL;-WRLQ%CC4$%b5eubYAuk$K!Xezq>o^T#sM(tG^AcE1IWe2 zMbk8M(|{rrTZR>I@Mwp&la}X0h|26kJpcv@cnT1zaW8(ql#57DfUPQ1u+xH8)G(?5 zFplG~KiuwabDqX=?E8M2k_$85U%wTZh-mH!X$!6jF-ER~pw)VvQ|kLZ=j_@vpD5J< zt7L(I2*8Mbywv-589jM};YXb!ABSJAIRA+H>j7C(&%!Jj`f-?2p3N>+&-o|WtIf~Y zq6pP1&Iq-H82Fkaq(XpQ*PWfM+lGw*H4!2~DYGGmGFCeI(0dxd8=%W}LJPbJ{71!GVu&?lF zKn7w4A|{fP0hkej$ANmTn?8B|m$D-{3tOrfp?F&Rz7I_U1Ym-Iil_#th}A?1sOF*M zR%g|VmCYNsw3sQ%Z6R5RNI(z-kvuLIsmz%JVkp^b$VDAS=nF4$aZ36_i(tT17l5SM zby4K2N|yCz1JxS`sI&Bnz;s@Re4QdfATk7l7(!UD*LQb!sv0O#i4xXv7_YC>Wk{DV zw!j1;k@5U&^Ud)%=6riRTpswU;UOP`reFvJXhaNz#(wH37RKsMl^~ik*kmdxF#WDx)y#sL7Du3N8H=NH?y>jDQ=aVmMfaPQkFc8W6If|49$8x>;l92#RWJTFl!>Oy4H0%e&|F~B17`9J|Uz)z+|9V zvlUwti0f+r)Rm)nVwoR~r(v0@g#`CYRA+=T zcWm;WH(tLegs^V70Qx`$zm0L#b?bFx0x>aDGQ`>@iL4 zGb02LqKKi1@%r|5v)NeL&z!_Eo&^_+o6<*(f(Ve42nsA`5#^&)0JAPO?^0r>*tXsY zLGrObGCFmMFVvd3Q}p)A{+u^}FjSr`2lZlvf#I5T%sTlup`w zuV(>6sIv}x*cKW%v`yC^hx4ne&@!S2eR(|*sG5joAB(8g%m?)7g-C50H8xFTQvgCd z9*_OlgJdws{TP}E%m&CY?)UpVPKcmt<1n_}=6t)+>0;A$@4o*IM7ZRP!d$=N9h9a< zh6ol+DOZCeqSUQHKOkZ$;gOCn5dn-tG_%{g-D{~D}x3$tDaSs8_W$vXjp}0UzO;qzVB9mz8^%6}X@~otMG}aJRVhqAo}kSlw(R?U*EO_XX};_6*+M$)E~0yIKA2JSB%dZ z=nxsGlmP+6h(aZVOK{$UX+rFohZv@a69fYmKqYGw2q_W<1r`lH%D0qk%0}B56$}uD zp-;yI!)|)>{i~nB>asoGbie$IKWq8dzxmDAB8G+pkjI>oQjEwAPy{BSMooA7<2WWH zE@AV`coOQBWH+X+7v=d9W<&;;(2v@jt{b_qTWam>2~YEwFfhWM=@2&EygP@N_BOCr$pZ^$dR!A>dPkU_bt-ng9Tkoo!ZMJUid6xnP0-EXHtgadCIp`{A(43QwbFswTQ(22@oQ zszBe5PvjdOq5yVX_w~DXJtA>5%MqYOU@Mn8fG5l}@<>3yW*9^))RqANzj2*;Jws)zpPw<2bEWt9l4C zLR78ettCoWTmt5>+a0>ig`w39_af@Ga?Umb6suY^BQOA9FdfG<{?8Ce8@`VULq21QC6A{XS6OTnj zsfSH{t%T*GY5ZOUhZMi^9$vdA#yED#%7b;^_)hQI*IDw7Elj!l@_HZ@ILE9Nmtj|Ml_ z??>3S=g+s>v%mPOU#`~MX&l@Fa~!5&5?}&iq5w!nAp;zTF=Z_`Oj)o_2fKRAFLu#6 z*w=4#_d{V#gzdVPnI7zV$DvP>eQK^XUe>R$0W?k1HY+1?A*y?I+=D~aG10bs(b4%P zc3oG;y=Bu~9)D~xuUSq>5K0vhRDY4*TjYk;C&`{lGSO&77xl|ee1Lsi zYyWuT_Xk(!lUjKTRM3FYOs-J*AGjbXPE8|te^z5p%@BWULCyo>XhBfV`?@~lJm~Ij z_p85u^Uc@)wA=6fw7Dov!MRI~kovZ5V)*K(Up~9KBu2llJbKMVmdoIna-jCy$3>6} z(K2?@doe#a`+9O=-{O_=>)h>#Md{=8-4U;s(&{oD7T+QeoRAhh&WhQscVyY9v1CWeqz!BlcesqeZM zT^k9EA(NFmW2x0x-eU!l;>TDht6%h35#?`~?ja5XoR87vb1~;`5fv~i-0p^)5)p;v z-VEkjR1Gb1$?&NQ+(!>p_+tRdpoB(*7w6kAU%hyKw(f%ab4-^Zn~!XZ2vUXx_{2GC z-kcslEBk=hU>22LUR?hDKm6lnd%jw)MdSfQTd&uF!~SkR^i#8Kz=gLZK0)t2inUOu z%9aZYX^MuZVo8#SUhnrhj)+Wz=d1Qb*F_FRXgyEU>peN2ESWjy3`>5lMnVEW3}MxE z(=-xYETSgSOhbu!Ps=x@C-oIB1V3;B97xQ~YPH$j?$6IJ=l*E`5;Uc7oHBPFNGX0w z^JQM)6e;HNd3ObxnTEJevP}ZWA|Q$eWLPEb1)YPGe03;Xo9ONSjzd_lR%&%v>G6u3 zRSl4GPBKo2Y+_`fAu50eMWks;YS%Y+v27wpLlP@U-fHPhNpP!vL2_=?kbqRPr~%5N z$@*Sg2m&!06XS_iww%&9j%k{XD!%r63I-LoB6(f|605<`ACWk?0;lviRlPfUI6HxQ z2Rc-YT}&BxkJ4UvR~4<6;}kM=DKD;+FBpi*lyfO;0t0{{O>K;-;`a|cP6l2O8H;08 zxwXP^e;1kKW_{@Uam^#sKW-;FMHdc4rpli9qmDoQPZtepNF^kX%6xir6PA@-f=T&>p}g6Bez z764DNO=i+^AXfVEgWXV2qDs3H8Yd#?a2 zM}anP^raFMUD)j|^Amm`IGr}|#H-z-!F~^bRX>I&{hL;dDJ4O!@YqCoYR2K%_lIek z)E=7qR9%2c0Gji3d;9+8=K9sE7es8}>^_tROaNbWX7o$tA{w9{xMrBCvjWHu>>pyV zPGs7BUZ&J@ffkLG-N$3LRHU8k>#Eu{@n>It@vHy;Z}LAPDEBEbN(c6qA7VG_XH#6mbL=AI(=NiMI1SU`aG26$hD*8C zBjWa z`2o5T)iMujnx<)f{p(-<)h~ZZCjoNVGupQ8+V=hX%+ZaR8mXd-Wq-e&7LP6#MUh60=*YO@)ct!bS%D_f$@ z3J9N`_*p>w4mDG1jkfD%^}fiD@hidehzTffH@4dy_eZ z{pjKJJ`>eN1kmPP#}I%*!1}L>PR#%iBQY?iHb|gGAzDdPsQ{_W%oRZj$zY@w#tbPj zu>uH|e5^%jQ9%=h8d76oW-Vq>is0VDt;Z0(c>V)IdLAx4KM^ds|y_l|)v}LVgKEIF%vEoNhif?o#~n5b3_A7YALIl7~~TtH%liG4a5l+ z14wyHc~r}Q#Om2R?5FyDw!aJy8|gBH&B_ z=*irCLIZ_XE0N=9i1_mJmw*1tzxcbq`|n1^ZCJM(50k?{z#t+<7Mpl^acO49!=Y(I z%H!+rzkm7JtM%r5y+(#AF~~ zCU8o{p$GhY#Xx1RJe{rKVGznZHMJ)-Q8OcE3(ej#TD~Zlk3+h--4DZ5GBB4lA;p*f zKs#8hCSs;A3z-2?$#m87)#dq%moHXb8~i~k_9|QI?M|0(@t&&@s<>eI;O;nspQZIvH38`{x`l8a?5HPFq z^UHV0iq1xq;W8MRI-~(D6#+HW-jgpj7YcSm>^gEY%qgp=Y6eT2-2WW<|7HL6`Ec`X z<|%&m8$90=m?=XbB<`B-r$0UR{a(eyFo}uRAcBgjYRbt(RFbNJ396zBsQJ{B)lkJ$ zK*Thwr4nvl65Z!CDlBPJ<}ve5$BAhMQ#M#m`Z#cmQB;%2ap)sL>i3?jkGM<`tTq`W z7qZVXEN0hu;=Km|fskAYZREg_$l+L(J|fJ*E?y*{MAwB)xzERg#xSYaBHp1|^Ks5w zT7U->162@FA_|P4ISE43gtl$_aWKGY0xETn0O0wZrb=d!8#S8*83ICy9#BL<4uCPT zHH=_vZg_zVFc}YO6QUp*g8^j@87KiI;zX1~K<6^bJEZLYWlCNE2@pb)kPhQ;ySw|% zH{XBret7x$R~%a}n{ZSFCGg+e&um1748(v`^Dm0UW#)32sR&q3hs>LR?n zk}kG}jiMH|$z#$?RI_PzqF)8Y^0Bvfw|E@Ub?+)p^jleetU64ccLf3nA;cycVO+J_ z7tg!Pb71a>FDM3p$xIYPffky=rM!G@oum&;g+3G$ZdiN7>J$j=p5?IY#2%enPtvE! zM{yvY4Ae`A_i@LT`h*edv9j6*msUr6=pvbyrhC+xE$EjLwc`)fQz;A&td#dUS2|lr zz)B%<%u_z>kM_cdU5j`!ZotWj^}}!;@8^sl;)lQ7s;}bSZ8+Z@S{g8{AJgsa@pv3X z%-y9nlPw6R<@es92kYRVia0>Q^8aA&&7Ledt~1ZGxW{t0Tx-WtAV81;MXFm;+w{y> zo3+g5z5m*IotH7|={8ZCAw`O800gQ4)RvWd-X$X3&pGqp9&zJlB|u6oGbw4L0R*aU z*3G!?XZgP02NoRDgL{WZhx=t&q>)v=Gl6pbWRetG@BD%L!Bs!fvv;MHcTKR~-RTbr zCyCxv_=3oN^wCF`SJy9Iyl~FV=X+IEr+yiU5>Vsh&D*`bqsNaQdhZ}fq-{&>jsk>e z=(^AmlL1D6&a@M~*);1-b9HmwS^LvZKKSzw-`gt+2G~1VoWK9%SATe^=sSY~%>y9m zVBE4D1th3}0m;_cKtq>gNK%$KpI?a%Q z_P-_VQzG@$L`i6tXMux<45a-HAiO z()JD{&Z3RMVr|-YW<4i7t&fPxvgBSeqpG3nxX&dV?gQ&VJU03c70eX156nhH7ek04 zIOobqeRx!#o}M*bJA`ScuK`Sese&fbjbS2K00;=i zlpd5KKe>p&WK2fe6Dh}_=a~Z$qOqB=bG|5?;}}DfaC7$dyEkWsPEMN|~cqvxKjKM(=?`x%(XIp<36NBb&OTV@GxjNMlXY*t0WCKL*cWj<`x=P&FJ3$aotM@kceq zkZ@s;E4*PRr2x5|>rbX$cnYe5*007!-z(Z(0W~<5f~SxU0>pQVzrnDOR5rY>8# zE--DNK@P&KBu^QX3zYAJEc8vr*))|S+Q$9nRuOPlT0lgUxK`)q=ZOv~(T4*&5M$T22YW|n=jUn{RXt@Yx^8`ZeBUCRyg4h10@0~z z*Gc8d7;WN8SCkr2BcLN92cy04t%d<_L8fl~)A4B42BZA<`DSl9K(-}10Von6b#1)7 z+N{?>(vdUp0Y)R1ThxX<{_(^6$DRoj=+SmYtNEAT0;!mdU9pJY zOH;$|ZLjX&u4$jv5@S>YB--2Co6Tk^^)H0bw#(2-ihn_Xi;Igdzxcc?+`+*?y0$Wk zD}~$kM%$aVGlb+HZ!~sMF0QVc)#`X}@*h9@v#0lurj7~)Q0NT){G<2&@b>zA)foAb zEY0)MO$x)plhRf^E!EQ@?~Du~`Qaq>jlf*&9~hW0V^yZrmL^;SLNS{S!wAb`D{Mjn_irr&5D8zNhHCd)~mJ)*H4Zg*Hwk7z)Hh3%TzGT=3Wrhu5Ch$ zY4xG~T!S&gU9CGqOMiDbqhy$1(fK)_9 z`T`4+)(Il-tdJ0?*U&lVrjv>Hz6~MSF~lUjt&I>gYiEH_jgSEtGzCkh@x6jYfROCw z42ZY_x#~7W*H%FaN#s39&k2S;DJ=}l;v@8mx-itAsd(p@)^hZjp zlueWbhG|fSL&1jqF_UF$1}SAyx5iZ5Spwp&&(3xL4`#il5@=gZ-twUJJjJ}vOHLjo zimK5pRb5*rSML?AUGd=Fy*F=O>(ym2i!s7GV*eaaMPQ&YMl~hc(i52|$^0o7ST>js zOpW_>-Yp59?R>-$dL98GZdRLJ3GI)Xxr91SCoZ!Wjb>hfsq~iNm=`%V4~Eq5};#N(Ga4UdS9T3h<*3% z%SVsiGeJkb@^x9%guGcb{RCx$=v2`JX61BJRSsPrqGBU6=dBXzU0NpIU2f&;kl+W( zEBoHxSdD_%dL5c3h*%1h8+%=LQ@zJGZ@LrH4n@$^Ou)k4yngS&@$tdFV?Yxc(UP_` z|F9DSyse|`)vdc5``v$S_pNw0V*IxL9Uue&Bo#ANMS{dXGGgXxQdBjD5H_2QiZ)Gi za`GmIZhwE@7alR;NdbwFQcejP;=1jOs8MOvHn9m3C3Zjl;Qjyb*~cFp%_>l|eivsj zofh}+-@knRI@Jf^teXG;AOJ~3K~!;}r#m1c8d6d-2qYe6e_LQbc}&(b#q=>na+o?| zAOnVBo0~O5X+lJ*&N;$lRJBxKW$kBP=Wc%T%SB%lm`W{1&}=E8Aubo zg9;T%P!%jn@a&k_h*B4fVBawK@pfpqCn93U;2#zL6dNdiPsm9{IUv#PF|W)n?IUwBWP?xQHE z>ev-&ZI|LvjkdTxi{nmeY# zNSpXNlswCtfFCJ>D*L~BHxD{9$%PM))12X#)-8%?K#G(abi=`rnW+ScOqH}DdE1D@ zK$J3!#DbatCMg*+_XbfiNbo&1MNtI=X6jQrQwa=t6N}`$C-0(a2*D71S-Aca;+X;< zAY0nbrU?gSOA~@IlA(zJZ9CPZ14yD!P}Ba1?}Zmc8Q_Sd!#xTLz+$!m^Grl|CE+@B z6RH@9dZy6GiPxt>NgDH!q24XR8p)eSF;9c7)O3{Unl^v3y=6uXK&I;E6CJ_$E&!E{ zpSB-hv8O#;rea`@QymXbY}eb?pZ*HNhO95h`bi#*hZe)`EN=|**5KB#V>@QsLRmB7 zB&lb`Fd_y>O|kTo$gOS744LWp{)2n>-fT8&P%#lvy**N~{E-MTwxKgHbj;RkGLT@{ zDPR^>^@u)GFfu{d8HC)m+cH2hv(;+-)mL9Vd-kmBy7_!w*Y!BpeEe0Gema}&9~`79 zl$o_{J9yefBndmNudh!}Pn)Lk-ivS-T10csRb|2GG{$Jwn5}MZoO5+uJLfj*Rns)d zwVpSggyp1aPcJSmt`OOKuBX-eAHLsp&GYBaudc3Cb-h`c#rb02VyH`hus8QSAO%Ou ztlc~8pAwaAJDGNOZwYPeIUFqxv1{YarroqbHAnXLt`EAy53!?=9F(+aIiifPSnNH1 zaCE#scZ39jX=e^NuFqh{T!MF*0dFS~+O1{i_Y<&gsdN*Srt9L{^UF4h2#O|wDVl1G zApv}jt7S}K{f{NKDh&dk+SE1|T20{P)#~=U4fA^Ea+ItmM zF(gEYQBKaUzIyrg{B(6Nt0!ey66MpH$cT`L0h|F6DFGtqKRW^;(*P1n`1O1eBpqkU zhf8Z#@m2+E9-PSEtMs2%P0@`IQhZK@7ILYVuC9E)1aOft*}y&hh#27$=h zP&ZxSi+-p)m{bQiy;<@zesgvv^-+yeCmSND4CmfO6GSWuCWa+jNrq;k5eP!ps)mDu10pk&Y@p}^2Dapv z%%=yD7(*zW%i{wC1TvFxs{N+fyng-K%x3kZDt+mlciALJp$jwJ1hNQOBhe6?OP;jEstq1#-qymMvYQoYwS zO$c4-eCd7ZTyo}%p@L;vEgGY@L9w%|ewM7~%0^N|bk4aLW7lyi%+n8;KmMnp7KLKNrTzJ2@p_3O!G5<{q`_2JRsbT*q!CrJ46<+t;_{ZD@U zqr;;;hjetf|LG?m-&|iOd^Qjg^K8C2JY39XlY$XJcJ{yTY`pCU0k-x71pGe<1xnJ7 zYgbKkv)puIG4r-j6C4sr2a32V^bnvlpGb2DP2mnEX5t7A_7_hc9?vF)LnKRCA(kD1 z{nSeBR@tN@x#6w|a|DxBu+#<qjcxCbdra%I=3G(fW7cX9&w&FxNMD5f% zwFXo~3NeOM=MW<+yLvwN?52x-cFwlzRV7f$C?q0Z7`2^1T}@2m1l?z!JpGHG{`jD9 zKDSA%h-a7AFJ8SpIlF8kKG<8hqG0FQ82Y0%@e2@erWgs96h(rXBu8q=#+Fc>c`If8 zggWm@EuW8RA!0iTdWvF1#6V`$8}ZSy2iN)r-vofTNNDgDx$6RfdE|n@3{^!D0_Fx7 z3|NeT)wxg=7&>OoeLq-Iz7E7RB198PMGNL2maN1k1Vbgug&!y;4_jj-N0N2;odwcV; zEG6wa`-yrQ>kV&h-=?T)oJ?xxiadC+t>i4D`5m2Ko&^ny>8y0VWapi8#4ZcZ*@%E$ zv)L^67DZ91r5Tm=QcDxq2KXikbmDw$!C1Xrs&9%C1BIZsF{TuOT(FqM5Jco~?@$45 zE-oFyB!fXTbg|ns2?Ohx9Wpvl047XDd1AySIb6Rp$b}#F1y)qj)HH!oVqvE9Hz~M= zklL~=LkOxicp-ZOCn2VjA;tHk3?tCw!bm=8qVxpCZT`eISkv+l1yZ&aFafg;-!E#? zohWKVh|rT`OcNd*6&R_SOa*2F9Ag{04gk6!F=$FOH$-$k>C~e1`hQR`5VZ&zO)(OV zLS}UE62x}qvG>-uE4zgz^hm|tg3w=tY(x5r z-4ZOPA|AkAzkd0T|Mg~TK|YJ{htat!yn9VdPf5; zDoQK>O&6Ezwha=K9yt?7)2L!=aT~_K*2^cd10`Ex#5+7(OddZxK3G&_28qyNyM)W} zv=YV%0%MGo^`NrdVONsK0gu>7h zy1bWx`9iC@^1hf%Cu!HySMJK7jNlN_Oo80>&8yQ3B%D>{hwnZ4i$D9(LFp<2P>4p2 z=*!oqUw!jpxe4Bvv)RNK1u-&88t|vySi#Z^CkiwsYiX97HN;pIg_}&UED13csoH<6 z)v_r;6+{1j>ky5SFC;}ZByxa`vZk1Ng+lhl5eZr=+DS~3m&`Hu)PQ-AiWvn6fYe-% zQUtSH5;F3nxLhs0F#>9?_wqEo=d-9!GJ<}#)f2n8+ADKxAU6im| zwlBUr`R>`JhwkSe{f%3cuTK7--@N+O-r>WayuUcUH{Y}^mQ<95fwk=>hTy%oC}7b$ zw^^^vv@EN21e7^rt5rn=*U$ZfJ&e+}0pCb~nrGtLy98Y*zZBAodx|fJCXl zA|nbaI9Rf?(HRKA42Yb>m<#|wq-Jf~b|H#L zI!r^5%qSY2bIeH@Z94p!h=xI8TC0MgsDXtbnmIo?20@>F*>Qp z186i9#h9y86V(u7j4_HvkWMvrZA!=#1ydT1m~^zH?943w$MFz|@@{u`c{2Q6BAOLI zq`(Ts=&*Ot1KMt?xWXM3!O(EVD5{D?SXs%+wP%P1A;8 zU?P$vS;SlvMKzt>yMKQ+pWgxz^~(j^ng@sG+Ir5>=tui*&Dyrjt5>hS_~MI`lN0A$ zRZWVbaLy4Sp;8Z!8Rl52aI~EB6T7ZU10?T#J)JD(bML*WgtqP476Fzw*Mv}4RbAIb z;hUzdilQpKsa#!MrUAD1ezVz}ot?dY{d&FGFfp^A&*$W5wOal9x4-?X$@IeyKiuCt zMuL~GUL71Prjyzu5pk~(9;B)HGy2b&I{mP(;!jLf+6uPN0NM~PuCLck7lmY0`sfHU zb_@PLAi^b)6-~j^6CCc(-+Op(J}E6Kkdf&-$XpozR(;pB6CQFaNaXf$-%EMSG(|Q4 z@Mkd9X>Hdkz;v;|V%{_m1OZ8rH5ont7}EimLc`R|4h|0o6gTz^RWKotoI`6C&8D-d zygfO)c=O5A$A9sYj}B(uDHuYhaM{YU7jM6O_N^Gr=ZEYFnGuaF<+q?JQYIH*+eHCe z8VT6dX6X_3_h(nvHKRS*iRh0ow8w*a9WkqvaHAz zfF3A?L`Aa>RKTvAcHMPN>^kWQIcZL4#srJ9uGrN?9*GQH?<|W5QDtLxDcz~Gu1hEb zG(!THNMVdd1f}B&9iy^k1?Y|s1M?Q5uPFKlLPb=CdVK`qAD+Md-9NlEod%Bo=YRi) zM-QrhI9XnIlbe@sAl~@>pG*qEP9O?eFm+5$N!rk$X;~I++s@|;B2q(2@y~$6v@|d0 zvsVj5G>RZmqCfVgpOh3Qjwq=PPEJmkxvnY)#7NwOuhQkq%;tC#y7^)s2u<>5Dc|6E zScik%E-wRmY26O*t)G>QL(Fs-YGs@(b}>Yai|O9g^;H+T$z+0vUDv6_#2OsBg@NX; z0H#rTWbW1knzesDK5n}OGDQ;sRYO%Lh`>WEGlh_#K0riB>>QcpKiW$2_+ zl9>?*L@`Dj54Q6VD<2vJFrQ3jv#E1VlP|gN2a^!ANBlvT3?mAiS|g?kUDvH6HlosX zIoU@0+}l23Fh!L2GY{Jewv&7b0GLuhA&$Ka{c`}0OX8XH;)<3NC@&4Gk_sc$h}*l5 z3@9Vo&7pBZ_8?Ni(Sn80g{~_+XURocA0wpDF9%c*mBiqjLk7Y|?JTwt^&w5hW+?2v z3wPcacOJMIPyx18Y9|VV8^D<(x$KDgy;Z{A8WH`G=(hja>(0J6z_<^&?ENe|z@qO% zhZ>9_G`HWJ+c(a3bd)9!loiF9$(`BHIJ~X`z~0_swcN8PP1CG4>kwnpGyou~fT*Hr zJRCx3+txXkoBq3SMB}S8UE|+ZV8s}lrup{UZ-4i@-`(8YRJjH!GMlRJ6LQSc2<@G+ z$-V*pZ2g*Qk(76YU2Ua*6a6!rPWv+|EGX;RUw1`26a^%dU8;B>{_u*M!+phZ2-pS z+mX`RIz`E#0V5J72d)ShAhfEj1|ykP__I$xJen3>AZqNG&ztU-pMU$s^S4DcnN-sa z6oMH5U1d8jGohJ9ja}ES*UhHu8s`JpdcFL`ryqUx(UbrB|NZXrdJSC&V6`x_IWh(i zKmlk)uGXt{*KL|r`e6-CcII7ziHL|@AWo`kUQPBV(?vNkMKNn6tV6d9?c1BHgzTrZ zgJ1@OD6#887ut<43-2dIF)QnWiwZpg#27YRyYAX$=vJGXRkNu;3h#*>We8r3F>FFm zu-1F6CKK=b#7_1-u22n>P*s_kw=_UgGX)I8j{^8=bMfrW<(dmWDZ^y?x7QoHzJlY& zVWYU#7wd5Us{LR-FT65zOg;pQL5iY4)zCB{1Vr55+e;&}lu41P3x*@kTp9)DEW#Ab zZ2hgSCfhX$(d*Z*x)Amj3nB(lB&5{iVcG&QAT@1QRJBWCQ(z)$TW-iUY{&Az6?*0< zjYBVTaiiMP+DAt0gqzC{S2Te6Y_{&&oAs)29t|`^R71>@__8bkQ4uLeuKaaEoPSpIo+ZiElP;e0g`jhIT}he*cB&1)Fd_j)utv>G6f+_~10ID9=LLirz#qAb zYOwvlvtaO&P2x_~>B%;ND?fc@sg4F0X-7^GbHt>S36( z+6boqebv=n1gr+eI}jTq(u|LI9p!!reqk+#8dgVV$j*gq9SyyRm%$ z%8W>;rUKT4cGIoA!=L~3)A#P}m+1pfe70%+?l-^x#DN$<1SyhzI zGx@@KA`*qR3)5+RaCG>)Z=Rp6S8dxkq^UzueR*f-6s_YU_K zi}|!D3&%_dT^Befj!)xx85~S4}&qW|N{!L*?~))x?$vK7R7x{?Xyy-h4iv zr3#7>S#8y{mpAK8*S&mma(TUqV!kK|$pIz~rw#mJ941&`*t33;*%8Q$g5uZTy?L{4 zaX$5n3GdHfG6T|1nz(M^x(gTUXD1i?4~`D2f@6%aQ#C|mCRf#-`QrR+Hk&zONjWye z+UMrwpKCU*W+#(~B>q{JH*6n(A-z1du~ zzl^Eh{|wq(BJ4fpz0%>119PAdzw7478&)$>V0KkipPipgCzGluad>pejF6d=W|xTw zDG5Rp6P+DZ-z_JQkQ87?1q@_Bpc+Yt$i@CMV+aD)#ehJVe6hIQ#z4=K&;D4yUnFz2cE1p|{r z)i#X)5g=NxtQ;_p0~pMwp*mU)t0PLFChvUBp2_!CV@pzM-L;R8pD^vqqn@zxZeQD5 zQ*y4tFs8W+3H3d)C+vTJ=#li6Bhh!ulRu5-KE^-V56~s7&TfgoAHk!;)2E7t~>5#)aa>X;{!iF1yK3g@++q>n(xz9WSYUcP$u z_Vo1S%a;!xJb3iz(ed$dUDxA>Gmpo|Pj7ZI^?@X+=>b@;*T4MbFP}YoR+eQ|RcS^w zoJ#4d@X3Up0r-P-Axmh}A&R(O-iXR-wSN8T#gj)5kX6`S3@$;&#GanNX`h$kxj&t)* z8Ex*IdWi7P9eoY$sV4A>!m4R5SIcz}1y0eRI*M=}juXRFRO!&n^lf}ZlhV`UNB55Q zXQg8@F%{;Nx{+oB*fU9Rq_pb)x=(2sj&QI#JmYU91XV463cfO}9Qi+I#x`!-^0U zgkWv(o9EyBzyJ8#s-Es0l;lbQ6oC-Jrrlh`u5>)Dt4TGTR+HKlG3v5uCbRmppFUCS zzB;{lb#|)J9AIcSxDY(A|jCQ#-!#;yx{v--p1z1kox{!o+CN0_k_ zWo9uY#IvUlfBW?}fB!$eetmU5o9?NEtLw|k(_eq~lOH{PFrQW>lkYJvreJjm0Cs=> z7whE3Aoj&Zp#gn(|L`wAe){3#quP@P18|~X$;wDzP=YShtoiui zfBXA?{Nm-AdT)g36EwhD(1gGOf%I@=FcJi0L<+1LflgNT^|{b=&&}s{d@P5vSeNM7 zq_gX#ubSZ9^Vl8*sr`QKg+wHnL>VZ9Z5NJ??jaG1m?~is8j}J?%?9f9EGguuA{^x& zIzpRgHa>W64$2UmWQGA0I)Rwl%e_K_t(T zbG-{7eMCzd$!m^$P&5E1I20wO2OtWb+*O1Ozw-P^zWKK+t}k21Bf- zjR)n1XlOiyyY)v;!myiKS|?^(DiSj*QKuSJ$uyV-(+DO#4bp5}tEI3IQX+@Spk&IB zlsqXWDNTEoiM->w@Q5go5*o;mln97CQGw);6hJhZ0wXfg4;Df;z#i_bPE;-DOj$PE z=6^~w_8bfpb7>3nk4lq#wfYN)S(xS}j z2>~#YXkjN8ijqk3b?Oj%IA+Q9S4@u+HWLvd zVuWes9~|vJJl-o9HAXaHGDI*1?88XkkywpagaeZpZjI!}8^d=?DA-a|wxMj8#7PDQ z7*(65?b6&eTRMOYy(1{ndE=R!NIvQ^U|_UDPqTL#;dN{`4pq&X&~>r<=|>;z&nB2W zN(yZg4ywt2`OkkdTg<&LkT@mCwISSGuWweXS0|?@7niTroBhT9K{*Ygs}KQT;^F5% z`{@4Wga7+)e*=aE;xC@Q|BIjf+5Y|NArir=T)H(7q&kY1n4?CE2aw#)9K}l z*C*%8CwoVpuz-YpiWZ}Q+-w?GR;?I_J)RD9&(!jbRSTu}>TsMkKN4b^S{M|R zX_F^rs3-);=ydFWCSvxIo;t)n{9znR-4C86WuoKQ7_VxoDt*AFs0LHOEEyZ}Yi!hT zt(L2^v$J+u@VsUuBUZ!$k#+lOs@8!u{e9LcnjsPrlS4`?3{z0CBytC$VOa<}o6Vfl zm@tWBAYl5&`-yCyk%X|4?mD#CHEXg)VuX}e)#Ir0imT^e5jl2_i5Z!JHN(=4kN^cO z1W39)=bUpapea8g`}z$M< zUK8QJkh%qK#ohdK74kS5TiYl$CrcW0d_DG3-kmh#cNU)89qJ$$v~0apQ`$1Q4G`14 z*L7XfG^^DrY?_A;AKp7UZfJFRdD%2g5|xVxArbbYg#KhmE?odvtyV--*L8wXrP}Cw zDy`dfWY={Gtv)QoQ-L+~e+ble-F!Yx;SXtdnc2rf^e+Mca8V%Q{{H@lAAab)Pa_ab zF=5Qkxz%cwmXcLfrByo<1prlD?Ct&NGi&)9DnE0EBuUb?>;ve*>iz8lV~mmFwkZvk_Bgk^#G;N@(E5ZE@cKn8hfm z7MHM?l#h=04i~e65L6iZB-0VcYWUBn#@c!{G(Wa*YfJcUX?1%*rTXrCYnXe9Y14Hv zO2(PwVM+Fi6B#o)WpU#z#kdO8EP>2G!wer9>&8;{^QLX8s($$3e!<8Bh`;~`Rk8Ts zy@X8aKfHzjT6mcrFdbaJ|LB|3i{E_p)tifRt2*=LN`sJs!K?3H{py>SZ{J@2^!`0U zINY24;q}{Zp1*qf-ZTm+;`OR~dwQ{4F1xNvjmmU7yLbO+ zZ{{7s!L<0_e*Tk2;@|(_dCL0KNEvl|X-o80Izg)Mih>9W-yQ(Uxve-Y^ zt7znKSgM-3(P#|JJ%xKr`1PceH z74{aRzSsb|RcP5A%fX$Kgb3MPTwa#GAm@gt8tZ?fAv#Y-NQR-pVWc}RM7ljw&!#v9 zhA2SjZg-6Y40$}Krgv>>hK8qiV)X&6A|j%sA`uNqd-hsN53t_t+236%B4QdvqG^bc zIrsR8=nw=z2m~Pjv?{HNsG4eP77U}9#wbwaW)3S_%R`Wrgg0`c3tSYkf_Zu#t?#-W^4nI_71P2C=l`L>MDdVolcLB zkMG^PH=obnReXN{Izh$0-&Y!dU0+`()%*YmO<&HDca9Tl(JcM@M3mI5+vz%O|9Y`l zR8>`$<$Ar|Y?`F#HM629SF81Exk^favZ|c(F~-eiQ&rWICr_r+sq@ZCnb*@&ZSFiG zgb)ECnzA7Q9v&Uf_x27C4~nwHUCqM3?yzcHu?vD4bZX0Ww_bHBXok5&w?V+ZZQN2$ zQGWJ%w=$@Z#c4?o59bdL7mm;}A8?ES*)_Uuo55kdXnkL*@2KGI2N$NfmcQLU^uK!) zX}Y!zk}!ChSe!$K%lO#HG;vYQZ1e#Tv5nL1SJLTkV_(=M*;WYg@ZexRt*Iwd8K#_j z)P!`(hCD?}8zR#P`xQ^#KR()<{KFStfA!*3%mK^@05_}U7hiw1hB`8J0AGCd{O_NA za}#V8ng@q_WmRjR{b~ah*zy8e)jogr-HWSrS@41Y)HMc;bdT>J{qKME7ssVzz{AB} z<^7A3x1aslryo5!o_k`kHrh9D&VKvF^UIrNkPwSR1vofZ{QIAO`s8Rb0XVGvzx(9r zvzMr@-jRwZb(K4&+roh%xauHZ0p7f;_S{*RyCtLOD6O}N@;oC_du2SrhRGCicF z{$H>8^Y5+-J(EyqkfsA-mNvu~SElTp5?R^{LUL;<850<3J{DE;4w_)s?5vum^(j{C z?dfS%)oFrN*L8|aNh2u(21IhjrtO^b^XZJ)A!JjbrY!MPKMkCA*hc;V5W>jkKUz}` z)ff}?N2Clwh<>ilPnvs48SbMst|I2xzkAO zlHWK=DkbX?b$PI3s*(%{I3_*cwYNee1VVD;93=^SeiDG#se0nj#n?5Q^?I`bUzc@V z6EQPeg7}-D2x??vMl6Ub<}$e)0V#(9XNoQYN+R)O&Yj)eksJI#M8-eC^0)IO(7&b( z*=%Q@w>zBEKKf6y5VW`HGG$Mc-HGF}Ehq_lr8DU05HU1Ew6^W8uCJD>Wf$7FZ{MDu zpLbn{2H$@BZCzHL{rUOD&CN1v$t?xdXKl0qAQK{j`PFK*?7!-|J~%jd^yty!N00XQ z_viEZ5FY{CY)7=+T6jL6@9*!Oo}Q*MZjiBW^+*Or7}G8UAkDD=FsY_e_`$f)S+Ccx zUcKtN?yIl9Iy*ai@4fdPJa_;`RawubvFkcQ2SAQJpxxZuh-z6@lgX5c$Z$HHE~nGY z)%A2zho+IX6Vyl;Bessqa z%Z7vCYAeYyDH!e_9~>Pl9DyZ!1Z;h}{WFClI{&bf*w^Yx}yAS4&wwj|M@lixQ*VKe|^r zrqNQqL&&l(fpmY95ob3Lq)Vs*crcszPd~Z2x%v8Z2~>hYisMxz1rovtwr-^n#;RV0md5|eX#i4A>e;L!0QG9R*<62n^7eeQJ}MW6z|N5&1Ag-UlUd0O;26Jo zeet)y{_QHDr-}F8F(X10*@W=&?Pd4tFaGoY@|m0X%JlK!{FBEIe*fzChtv7IatuNQ zU%z<$cVB!R0~Ee+MP-VrN>m~Pf{4la)eV5L_X)J8W~$Of2?m=sHc~@BhtT{}dqn0sat`V0m7_?h?9N1kUCb5s(V_`Ro+`e9W-~mH;|6v3 zm=IA^UEW+z>k>dkr5}kUmIG1_xJ>azkw$k%uK<&A4(iVC4tHkB0wEd*U?&R5&PGw~ zqu4skvZWE_&mf!5lAKdjGf7p|0HUE;p(Y9%K+@t&4Ah7i98&s_Mu3n+B`RjxXe$Vs z{&;3Vfkl|i8!DI*HUMbm6r3mRFet1$>BP)11wsyKtJEXC`&l@+l$o6s^GK$Np|K+s z7;>?!p{Y_cPS)YAL>es@^0W&8C1f(BoW86`l!QB+R?ChU%ODaZHcd<9 zs)?s$re{t;Kn~CmdE|AAvAa z!goVREc@qqa2@Ob8}y%DW2MeQEeEFJR@u8<^55DxKre_!qy!lz+qq!+?`dlvl>yV% zZ})MFvAX>UR2*qY2KWn_k|~OT5g34O*3HG~S<^K2wD!)g>&?=wBq)F_Z1;N8^ytxh@4Ywc^JsG~ zl|@=KC^zeR`q4)pKY#u_f!4-=mUKXg8HhIPc3RJdbEhn-uIplqh@`qBurPp&%d?ZW zZ!Rw{R?D@S9UdJ4Vo{b0qGXWlx~{#rFth9B8qn3#xdKIl!h27&_u$^?X7lRuswBV= z!SkBkh5@`kIygEyIP{JjW(;0_uApzfw#uQM8scAMzBQt(-Z3#vpLPKg(@x;>X4P~m zhGLKi&_nH{*r$7LVb(HCn^HIL7#|$(9Um+ThpG`rAFE*r*guGB1`4ErYJK9xXqc*I zYM5k{rdz=~0QQaXXts@gG@scpG}F=B*oClMZ6+67 zrH^U=lwY>ryyrdPu(C;>LIn}sw1LAORH3;e=$! zFj6`r0g+O@Vq>&*(=NN<5Cx0~z@SlGs~#R4JUCjE1_i)P7k~Zr^Q$(_rhA2}oFQeq z8yYy(`uz0b^DnoJ0_Wc4505A_4hI0usvBVI7E-o(D>()76_@XRJL<}M3p_gb5^+US6yqwJ@ z)9J*y6mYjK+!%Sxl)|2IHTYM?lJ?BPS3m&AjF^QHsSD82xj{s4-@Yv?UleX!9@&7L z?Gr!;f$z4u+OmCY_!hQKJOJGZGyw!)z*d#gv@Xg}U|G_k(MS=Y$*GyP54*-D+qI2} znn^Sj1m!dd&N+8L2ChHVIxq(yDH$76&Q#X2SyJSyM!*iyArycOnu$~~M306T&6*fH zF$F?HHdP%t(vq+(VVy!KrmCY?Hw`$?o7dk>uAKw zvMeB6uU03oUu%fd=`@CTd3Bj~WFnH{7tYSlb8LX-Sy}2ml6_banDWA|ZJI7*P!#qmR&8-M}FuT6K zF3WPUSPV}_+7-6#h8>&Pt)7nv%d%XpHf22#07EJ#lbQ1drlRZ3x@nrzv-6AV>*;ht z&WTwR>!KJMmlaN@XIIw~rfE@fRf8u2JUTqQ_ux@oPnl9~3I1Dn>@4S}rRoY4FdE*h z)~j_Z>MX^3k8}S9Z`YPIX}0s&MPk_7o8CJF@7HC>co z<^T)lo2GsF`mFiM2aB2z^l&lXo6R=OM$!+L;QrCkyeiLcmS84blMvyGNMI#$?TgAe zLpFja)=FGAjfyS~79W1_-o1MVlWFN4r-&~#)tniYCC~&2G3sh{adz^}S6|+opH`lo z_sz|6!`$60Q!D)X^()7Pib_$$!uhiH?96~Y?@cEDXlm~rHO&Xjrad`5eevex%h#uG zua;4Ofl}NbTAu}BJxS3rCl>)!b+uYuU0yM>XIIzLsw#(tcuM6{03__X5Je6S_KC>0 z1F4?-JvzD|hd1LWSCEK!sJGJ5O$J2d9Otm-z894~;==&0E-%rvC<;iv=AJA;J(4s* za{CuSCZ@5E9tjN7OQ+|2+_~wkpb=C7P(f2f+6vGT@gYZ{W3CQUJhlNSWL+T%3&WvL8qJRQvnWjJlhN^^uAPOQ9MIwQS zgc#cxbz6Auw4<0acm{HT!46iV&w$)*i-#4j7>G%)5;6iT6pAFkOt{r8wjfo?koz~x zdCxoGDFY%%ynhw3-kLyZutC_zk0KER(QH!Ro6Qf3s$|E+1v3*e10g9A#7tKuR{InKl>=U@cvhON58}_x-;A z|J7b1ioFnhzaZ2&ItB}I``6h&24lhIg3VvM0_+8CX4NMwC1Q4KMM7*i5vR#hbGSy>^37~|Ww zZ`-yFZTrdhzdxHydWP~%$=Ymo@abotU0hzgeS1C{jbI-G!$hbMV_L0N-NWc zFPhr6xyd`Vj~*Nx+`W6ZZG)(e$CKmZ#~zzIwT9(W%Cm1f)%g52jPS z>i}oRCq-GcsID3n)o3)T9J!2mvZ{=h19@=k%y77&L;$?8NAr&wZ`5i*-{FNFw{(5Rsb&)-{;>K)@x#4%U!#Wm-*D zZDUw2SKDo!azY}eB!-FUX)mU&8l2ORx_>TO|F-hY$bq z`yU;9R)K9Bo;-aPns9b>ToN;ZBz^VzeA~9;afL`0gn`*`ZyZM|$jw)qi^b~pXa=CJ z;K~yXIkfNGm*laIfy?*w^7f=51#hddtM~AanHL6C{KVL1% zvUJR|*=)I4fBvgqKmOh44?pIirV@JEM|5d;aX? z`c(mH>8G&KeXZ&sB4;fV&{Ek{dK4sOQsZ6?|n+?YO!#hiH7Cd zP^1rnnMBUqCGlKSi4G!PY|-n#NncS6-frnK574=?=w4OnL>b-uMFdrlR5DeS0GJ1? zRPAU8qH1vc#jDqm0iCm<3fUFuKv0ShKwA~j$RW7-V!YYvo6Dvw(OG(cNgoLdAD9C$ zBM_oss#$c~gr=b!O{3T3**NrR4OiDZhae(k;x5_&uVJGyMBe)20Aje=n0ypS5_8g| z5>QS|W>P>a(*m z@4Y#1LkNq@%k^e+aCiuaA;lPD8$#VQ^Tnd@h4(JT7*e{1Zb~V=efu_qP*&CVKl#KF z4?B;z-}=6D=kCWJe}6vz`?hVF9dmNdX(k#YB6;tdrdckRM@L7)W>w)mA~a27R>5JZ z%FI<&ZMWM^U8|}gOwBoEpWL>sBq@rbCq$@7RE-2U9*v61Ij5s>KsOmx-g`o{lbn91 ztK#3jx*Dt!*tBsm-)uK2iIXm^VCT4%>sg;&Gl?{xi*Yup&W>l(k;5Dtr@1y39F|4{ zR+eNm9iV>8pYCthVK^7|$oOlIY$uL!&JnY9wAwZ-*Xzw@n?#JNELo&PJ*cElf!ZBP z2S_1u?1Y$&k7z4r_Hbkf<)G|C$Xa+(69Me~fH6eRBLZKbF98f-DvAW`U5Ug`FWy`< z^{uhTq$uhjRi04w&Bgq8U%ogzt%%B#@no~yJb8V!4XN~A0b(1Ty_jEKtv$1dM2*(U zy5^=-mCa_&RGb`)-+Orb?yZvtcaDxL?*vv&`10w~FTQ$QIX|n)UK|}`NGau|zRRMT+9=5rR7Ei=%9mHmr>`$>KRi7mJT2(w-+S=m5AJ{}X$A^KmAYvc>*fzn zUjFLKuh;d;u_MH)p#Sg}pWeB3#;m9TB_ax1ixW_ky8KBYO>dt+`{s|oKY#vW_4X~S zmJ>;fr%&J1wIo3V@7Q~Pbadpr9|KSdFTVcc>({Slw@x2CeDvO<4~p@W6+Ai5geZ(k zB8WIG{3mx#-#b12_`L`J*FXOD@#7asoFhj-Xh{|WG$yKs6ffuVrfIx$v)MsaR=wv2 zIufaf5WCfCRTkyx>1mF8q1?RcN_@@oV(RPr-Q%OVr$zSNBqlqiSSKt&j-}d77*#slYEdA(jYZ6lH+ zrc~8A0?_q(Wf!e!8cpJui=rsYa#PplQizfy<-ftg`)0FQUDvDi3YmwE3Pg0y&FAx{ zPoBJY|Nd-xFqrqiKEwfwqWr-Re)#(J>u0a<`<@mP2>>z?krJ%d>(}$E$!Pj;^nl0_+6!wr z@1`#npDX2~kKC`!UGQDU$1T8FW%XvJ*}~wQzJi8y`c)e34V(u*%kVUcQZ|xUZc{MAFVmh5NI|Xdo_UdZ6T(9j5 zlS+Ph35RcX{~q+xuAXySzfR+H5=hwJIfT)P*stKOF@w>7SNyo znt_G{M2dB2m#b|$o-q(;LIeVFgar79KR%JiDT2nB!nXbU`R`O3H0pFFybM<41?1(QHyO76hIg0XQ-6f+~`Z{Qbj&`?t?- zpPl^e-~G4wa>>p;{N9Im?wq<53lm`H)MrdUpeRN^7FA7{!qY$g@$dikzq0D2EDENx zgM(1|tNDDrUK7H&@QhfrjkXOT$B;I08y2f)&tJ@6pWivXCC-y~ti(V>4m&C}0u-Rm z(?{=}0DpS^`t{|!i4sVud-l3wnh=RE=a=*Oye!K}H7dQgvgX=5C?eR>a=AP?IWZnh zrq}eR4b0{#fqnxp5bvN2GNY*~5mn=obF|%H?)C8)41{X{03ZNK zL_t(0nLLFmrny1vsl1?VXhj4E0d6>;2&p0|?awa<4X|sA42l4>q9GBmxc7ecXr;O&y-SiSv0u1QI}%N7eC1A8J(==uP%7stF{3MDy^fDriuhhju=n>wM)ltqbCr zye|+yQc5wlO^cy*5=R(MJdH=yg~)2TPU{wlto1CCP$dzx#Dcg{B~(BlkVX|%S=1>| zMecI>RYOGg@87?3=gzRV^Y-oA$B!S2NbkM6bLaM>M;}<1 z8;_26~zx={Kd!~epbary`;iLDx_qj4dTrHO`UcLf=h#Dcfm=2jg`1B`J zU!W>Q(U{it_N%YIipj8QT$I(p;laa4kC?eAii3lL+3a96p2V0`flT&_h(u1oX3q8s zCrBp5>6-G2DkJZ(TdK_+UDqMy9yWj`%}=ac6ZfKJC5k{k*TRm#gjqIZM~0y^eXs5H zZjQsB_+z43$UzYM9kyMflj=2D{@xMUl8#9COT0mM>fJw;AS#gbukoNM*jaf8!{#n< zPDMiqS6B1GJ0gg&wfF>Pw*E5!EEbE!Vo_Dq)zy`VIO4;D1MmH0GFdDZ^UF(O*S4W; z+oaO8Z48mwn~usk2Z*}ct~&jV$b7N5x>}CMQ-Ta)QNjL3<}M!U?C|iXKl}M&xmqk1 z?7d3~h)|HbHnr78^ZDF<=6-QB`1@!y+H5w~ni`taL^Pxb0CiorZQC!D%jNR?{M=@v zZC!8I>(OW=lL-&bMzWdul~qMB^T z$9d~Y1nP+#bHM=QOalcd9uWwLxRbFZ5MjjL1|<7kf7PDaDzhnjz#;-FKAB(qpTGL; zi;D&Nk$R63w{=Lelg?>UO<*pn*fCk7Kme^#HV7&}eTPGpB+bgv<@xe|``cfB|KYvw zJ-Rb0eSyGC0#E>pgFsL?s1T1Ge)jNwxLW#OX*4QPWmGV0+f9G7RN0*O<}nme z5;{IUtwz&V&tII!wqUJ1SA{Dl)zPG46{#Don|5210-%49{O?imfsB?pB<4s9pQFkTmB#0Dy?Q_u>2f1{4VzkYdv; zgf7-=4vlw!K;_}|YVf5z5nRpU;M>q z)JMlCRAu?*^=l*3fP#qJy?gtoKm7~`@yNgV^>2Rv#pgr}c~O(I)6>8B>@y+;0Cq)E zseb>(A0B@dUcas39FYpdU3a?#w00qC#_u+qwYd>75loW-$m_}GR{Zmy`>vIGVFr!_C}G4 zDM{TlZ5s|IV`LN*feb!jXUc>WLTKC8$fBxRjVF`IWVKo?77ODD#UyPTVvHivHf>5m zowSOXLoVxgFn7Dc>-BoExH>sGb;x3@H(=b&e?f8>0G^(ne)Q2tzy9^F+qSg>B3rFP zyM>}{+s$Tk4Yg(6ve9T{aMU5Ygc(E1*x(prS(bKOF*wC+I<1QG{LS0h!3+RG+ah!2 zN4~0<(f+M(fIJtXvG;+$C`tDQya1U4OVlE{Mr>HBrpnsvRiQKyy4u^RpX6wnn z#~z$Ty>|x(2R65@n|3~5tT!7G1mKt~)}!NNqqP)e7n?@!eqUm%R+Ba<*YAy+K&V5p7MQf3|jSk&pR6*xAvYpctG6EwzbDVL9 z6YADVRWlZ6HH)Ab*hR0+P*uF+`TXKyargGYh*b&k^8E7mUq23hI`tm0h_P9(H&Ij^ zdV;DdlV}}cfr&{~Gwm}fwJMFKI)sUHWl=B@Xo^Wv5JE5NE>__mfBV(ve|&s2sip-t zAu2eJoIFc~A3nPMgZp=;027Dr-#r_b#Z{!s)#hTksg9-|DVxPX5ly-RNjtr*Qc7^= z_QU`DpZ}L%{qwJ$eDn3i+n0;g8dE48dFMvV1>&?gyqdq&5Rsu~oZY$o@Pm&&`uL;w zKX^2o9gN2#?=7vAu_Kvf#{+<9Qh>H@LR-6GCDFAjRUy{xd_FIVVmdo0i_#l)4|8JR z@KLJkI>cC2BU>Sd-K`z|1ans@=dE<5IkjR3NgT(Wlf(9}CeAZJQim;Y770Dv22Z6+(!iX;MlOBdD^2 z((&P_AQG?18)hMgx2vdViZ=8{H86@=yTc(db59Oam9}lYcQm}6qUJ(RIpsk`B(y;c za=im4NsQ6CJWowAnn>BXB6Dc~3Zw(%CL~n_QchBZSjOm#t*U?kqmX#L!L}s?hadn& zQU`!3*Z6_(iexn_w-HYd4^KY$;KO_OXGK+wMve%QNJ@~IdzgB#bLWYq!4FM{DaM$j zD-i^l@>6EUI@}rK{v^TErWhisO>0MizO?C{EwU%FlMUidK;G+W{|x5%w+?7Dt6PUh z=hQpi2Silu?qiJ6+)pO>&nNyJ5^FcC-{%9_vOr9q`k*!A|)Zm!emDhYGMuM(4q zt~9T4U>e?TN`iG=uU4zFES+Q1Q7spX4gvx_Y+cn7lbq$u7^7imr|+wrx~{L5S54Dk zQFWu)y})X7eIa5|6d!;5@q9ji{P=MuO%o%V>T7iHLAvAV&6G#xa$?dwf$TF zzpJkLlb9mcA)YVRZ?86Ws|wlL-5K*#1uO@&Z=MeMpGIDEgog*?v(ste#b_y#iPhR8 z+hxc@hrNWcYclqsRS>$)mgv4^aVN2tzJsNzMd1w<%Z{76xxBnwuGS(#N3H-lf&6~WUE=G(xlXhjBkrU@YVCWP0oQRtk-^=vxz-t84w`)_N%^mTA{CF5`R zD5Xvt$bD8I?HWj;nk07L3PKyV+s$+~&C;X6FG)lR(8PjCQnCtTzmH2D94B|-OjAB6 zL*L1Z?=>offI^7mNcYA!j?f``=gPA1Wm%*M3JEC?N5Y^2skIY?39<-*0Rw6T*b;6~ zBcfwhdUb#VDk+Ji7=oyPh-0igj|=puB7!m5%Wfe|0-92Um@Ss5fMA)ZiiqsGAlt6y zNFq0TC@KuzCn8`b z`)LWA4F1$A*HB$SyJ8aF&L)z zRk)-GDG>rAGBFdI`XujyDa8;?>dVAcRW(g>b#*lwjjEzlQPYoiYsBuNc<-I}HfU~} zrfu6KY1e)xGLi}sp=hX^)U@adJGx3QBJQ|f+Brz4)9DX?_`~z_^TlFe$}nc|h)Ovf zK>_NzwhTmO)`9xpHowtm)HIDLmqpajwKl}GVY)TdUcP*ZhzExUA%vnVz4HP}>_(%} zcsy~=0dk+G&?Ax+^#5Jm)jPi%c0TPJBf((=I0}LQ)FHmPyt-I5O@z#1$yqdNkQ~vW z9~lRLbz_?+1sPT4?UQNgl{DGwI1J0wy?DWaW!3Nsn*E3Qq_CU%Y4;%%?UO_YsXF;z zBsZA=%d$K=KB`6)G1uGn;$ptuY&ClZ?L{{uboM@o3NiuSbkpv{mS|sP8EOb7nu+mx zvQH;_%-!ZbD#x=!z*jF{r-!$YiI^4O&h4{L-hb~OzWBN&@MZK_cnM8Pi~34gKmPcm z$*AmK;ks#FzjZHr2UT!xJ z-uuz0@**K3Ef!a8XaPAU0Tfn2AXiM2b19}6!7E2eNsG&??Y2n?fK-VIkz#@-!m5?$ z7gx*G;%G8HIhf5xg}0CsMCznvMC1qy=L+Wv?+%Y94(>ApRZSSlzi0B>thx$ z%;(GHs;a7@tcs%a%p|HtJTa(1j4?(4xVpL`qSIQnE2 zKt)8FrU@z7Qc{o~IUGCmn(7!OS)0m+TFKHZp;vWUg&_(mN_`VA(|_ioJFyzV^#)W!WEWJ4*$Brzm=Oa(!bA`l~4eVstd(dg*x zOiLUWl^acw9U-%EixCkrkA|5g+2zgjstnLmKn1bpunKCzPUlV?`K&u%o2x}~ryO!% zOeUtjOKDDBy@@+4R6l}J>c)d0z1*@h*CAeG8TC3a*z*Hk|1{7&PvmZu?laUdZ%aK` zL3%s92&7yyLk7m$yhb`Xz6{a0!_7mYHd~XV;jX7L@RDLS#q>GqDk>=ihyf%LfM*V& z4I#vsR3)^bZJHQkQ4|DZVS@c}jftFdP?lW|5;~Wxc0nfV3pPy?+cviC4*%MjTL|+3 zD?g(mqDcW2UEc~aTYcY!Ld4_a<42Dk{_>ae?RHxf&JhNMKB$6-ilW$THtY3zHk;k7 zPnfwZOUpMz%xNdq`n4J>rL%XIPKe9XpSxESSq{5tcmc& zP_b22otzw1qcI@XO?Z2Lxn8fkNiX%)p;&Yo3L*j_B!Rud#(wk{blgBoLn9>u5t9q5 zfToTRk>`T8irN#21OSd)$;IOQYEy^Nv~+*~S{CkSKlwoo@T;%Cxm;eNfRT=cu$qlO z`}9Yje0a|hpyX(c^ZDw{n@f-)#yGhiU#JbGT4mj4GE|C$*5tURx zv;O?^ukIZjRc8}cxO+VN_dog3=I{RLs$Nl9t?TC5tG5r1Cxzq5h<^O>2Y-0`i`9C` zY2*NbNC;!nHtBM^x_jsBqldRjhbS&2c=GbiHUvQgXkrLC|29N67NoKlZ6$%=xEvK+ zD5@~V>`)*{8iF)}v1yl!=EaNi!^!w?Hkr<FuN5 ze1Jr@L^|Y=FUnEL-UStQMOnJ;9YsM?!9f=?26Y=2>&>ce7OQ%jplP&ilICnV=x1u% z?RK$Pn2*>yN1f}kyXZKy>@-btdV1=MB6Htv=$78u&4NJ$Q^) zlqA4R-SN_f7i0m=cJI6|k+_#sr<9tem82qSqL#ri4?A&>^{PzFk-tzRi|A~H5+x>I z6s4Ac&KJ%Xv!#uZS6lt7Y_0w{{0V?-mPbh07^O%Xc~ zT(2VMo0=ENIEj7=XO#(dc(Y6g%M-`E;m`nv{oQ8!-5Bwm?nUbmfesx^y%5BX_PLPg zoJ*(~Y@vw2s97&>zewMU(mlAo%~uee=85t^bkbuTvf@iXA^XQ{fj13G(%5PY_GZ_c zCbcQGmVX0GK7lrMn2eN(8Q53^2-LRGxq@hCSN2|0O2ac;D;nF7LR3?u+tR7(*a4As zHJFeLo0o59NcnmZF_48>0uTr&l-~XD`=87&&L2O1+-$ebR)|1=?47eFZj8~;qeW4e zfTm7UXz!@>+9kQ({m~tB z6!x8Oogm(h)RLd~&Y7%$0A*1eA0Ad!r3g*azCE8Wmz&)wNqUG0*&HMnL-}sg&}=@u zWCMfQr z$tU-3J$dzFes!fuX4C26@$sFzckiAaR){PhsDzkAzJ7Lo)g<)n2$9i9- z0IBa_Yj-upgk0I~DS(KMG!^KH%K3ctcmMpm>OcJS&eV?qfBf+Fa`EBc{`!k`0|4;N ziDH&^Ft6&#I(eQcu(;m7aY`%nMwv%3d{0}!H@i>qHh zd)^=jq{G=b1wFr9v{BnA1fH3ZJOXM;Cu8?N{QM`kkH-lF5mwvnwh4q7L##J#IT@+= zkW`agt=lKB0-=mcS5^LCIzF6Dr{i*5A*ecbOrD{rm=vOFv;=NdvmF8=FflM8VM(5l zq%%#Y&XK5sA{yG*hPY{(bsg7ryA2w_U9IZ~$eBfytMCxQ<@`#4ilQWTod(~Mrc}B) zjEErWYI#*vMOpfkf_5V&ye8_}KMnUElDrg{3m-G8iby+f+c0EGB-ryDQc%^xGvqjy zUJ1D)gwjA(qPZZTUh!g7a5k@e-fHqZNOmI+Oa>*_gaaoQD%(Yf5dg&%I7kbzAY_!% zWt0_L$%d2!gJPY#f5-qHu;{{u?JrJ%QBeWdIbwp8R3&LjnnZ;`OYbU=C8;A}REa6X z7yu<12_vB>bkS{$$jnU0gc2j9*pG^a$F7?*!sC;ZpZ@eOin8d(!1wOn%`*`&*AE<@ zp8dza`A;%H5Z%9jFA1cM5Fn~2r>8&v%fGb#5ECVlGJmJE1PdSU zJ@>;n)5mm%zP#UzMpYV!4|I>Wzu(I1Lzhu+l2>s@xgWrShJ>w~-KlHu$+u##vMAQs z-hwy1^VhRQuBA9D^uxzpG*Bj%Tnh%WK94b`a|wofGLs?hA#?o9Ns~m9s>B$kMR9g` zga{|oS$%d}ITO6fhr?|_;PZop=#-oJkj0i1WGFT8Wi%w(0C`H<9{{KLayHh_2N zAbW&t`SRY6CS$W4P9~GT`m4XXd;9jmY#L&m9v(RF%d#AeMn$pfhUWkre24hy8tM0% zi|rk@z`@t{xaaSx-E*s-FlSE=u)LkJ!bnla-cMqRF{vsc12{zLeXheWr~wxgd%GzS z%x2ZWgh`UiUgz%UrP;jESAE*)`Z`?`Tx;O=k7Lh?wn1JOhM3)aHIOeUkzD2iHj zwODRa%7HnmJLmb%Ig%kj7B3(jBk?*hPc85<)Bb`pxCDS8oN_*$8dN zKFm!%Ge@W0UeMtTv(*t)RE$++bu%C-cpyiGEBN`_i{F0r^yo()l!O!FPe1wK+2zGA zzIp4b@$>V=7vDTT_~iYmn#R3el zjq=-Pub!?qI;v6|e)!4zA3wOgxL7O~SL@BD-fr7As1Oky&ZZA;pM3o2?#Lr32G!@U z->$Y>=1P)mH``HBd2$)U2cjvZ1ogH-tS>K{QMDP5%GszWN*GsuTo%p~F%YZw$qvsritq&H9|moV5$Z7Tv3mIZrHjL9<< z4kblNA}E5LI8h|mj|h(0Ip-WX;-DI0NGX{R#MWp-TV0b65aNUT_a8iXFhtB}5w~`J zVAZp;TX*i>g)ZpS?ov!bNdSR}1mNWK^z_y(*X?#@mqd0Z^R#vA;OO}0fA!aWd26Fx z1WJ;a35m@Oe|B(mmw5topgbnWD%6eV>}T#=OJMy2(4o!Enq|liMqK3mRq+O!Aj|iR zb+kwA{1b}vj3#;~#(iJGcTHUKU1l)+E*-P#;G5~r#@El(zqN9^VdA$l4&A6=aG>SK zoyl;h=f$Ds%35Yt%AtbfmA+HGq!in>O)1K-GnXy&$ZYZ4{4Y`wnaJJJJaONa($lcY zva~q*-PkJQZ3&0~2YH&^uWxCF=2%1kM(PMLo$+2oL=4%`SAqFZxMRaWUtrlp$?BPO!vLYCY5?|=DQ;2(W(_t+DvDxsFBBij@^Nu{|m15gB1 z)t9f|{^Kuxy;#=lO3Nfr(FAgHw7e4%^f-(zi$ruN5$z9-;E)kfQuxguzPWdL{KE%F zob-5H{`IFne6jk)Webu0KYjhum7^a$x^r04sKEDcA3r!fY&AwvKw!jz*+a(XZi0OA z-lfLe5?ryW>9SEX1l4i zsvPd(tBoW;=(e?s0YfV($Yeq(#Tc|G*m-bHQ$k$)~(x`?!Gi%6=u zCuGf(d=eH}E|=5Eq+e&O7qoBGgS{}A0XM5J{msFO03n3Jdm>g+GELs@yi9qHlwZ}} zmDo+nQ8_2M&MTZCq+>1bEWzKI_;Bf zm^3>n(e>IK>Eu}!iQ|2xW6}_}b+Z;>NL#V-6_MsXzj@p=pNWuwSQsed$V{|hm&QA; zm`h(UCIWQqm?))SxC&8~C?e5nOlJF~*fFzJTL38uYGP&!IR@1bB4XFC9z^glU++4? z4xOCM&w!L`>Ip`$$49)q-zK%KvcC6q+>^p#WaaF z6^EV4MF$l|e~UB^?QyW5aKB>XE+~G#-*in5HC#4P|BM1_zrUozmep{d*vC_S_k?&2UhW;6-8?#ucAl%U&Q`%Kcx(7m0?(!>CkqLblgUA5cijpo15Qpoq* zq3C@j+9U}oqMF!oj)Fkw;nqWsPrfAx*LK_u_|{p?RlS%Xf!aed$J(qYeFVB+ZU4Vz7KF<&fKD-i(TZWU1& zKq7V}+79jo_^matc0D|}7LJg6_X^TgSGmE^O&dj^hese1vM0p1^Y#Dz55HM||NZ-S z&L)*FJ(WmF6cg+)5J(ERYIU*RzI^rekAM7Xv8ss+cAhc>PR#_rH{&0w?fO1k)-_AF z60s7dHj=VuM}$m{D3w?(w$0!D?yG}?pWK^y&-mc>@xTB1XaD=JzT5ybME~{i^S9gP z)A#S)DT|3i2Q)=T+^KF5gFqeNP2GO+^3~^0Uv9xqiV=m_kk@T1NnL>zq63fML=&ng zvH~WAO@!4ZzPY^mr(gZ{n`am7Ca5F|64G|NWg_+^0RoUJphQX8peF%9l_4?}48#JU zHtivin4%&mGUehU>+rBAYzSnLvm{MXLzEC81gN*N*`&=jwMmqjh?^#al*Z#R0;MR% zY-vMq&ZVSge{OU6pATx%X&m=0TBWBT6HD!OOhQDGEp8F74dv= z_3G`*Z4g9Iq3$uKep3<1YYTx17Qv-{L~@o-#m5 zR3JG*G%rn##Ubx~Vgl8eQVh{NnT+I##zk2&lL`|$qN4Cj;2E_lC;_xFso~my5DV{! z?Mm7NF#}*kz`5>ttcn2NJb4-=cj2$0DQ~X50+8~7iN2jc2zFDio$%0b7~jJ2k^RFZ ziUJW=WqI$+-#Q5%6?KO0o*y5$qEK~1swJT+cLRcCLbRT(d96(9PV_Xa4e2|3MT-9l zOS_Gw5pRlUZb*;ceIfr;=S;h@NL4{pI{R*h1P+Opnk}CdS|-GJuR^~!t?XDmlu~!+w@xkF-^vkvMPz#G51|*{Zn`_ z`<(T9UDtI_#Lg9)V&a$in;Xi_RDG7tfwGP3@V= zvh?12?--RjGXW7*Rb_`u3w7x=L@8x?Mv7v@lcWNOL~b-1&1N&_TuLc~z@EpmnLVMc z>|rl(a4GZ#QSjzw-py6t(L=?3uhDl1+jk8Ml;P1O0X9K5^)^a=C_*%7)5C*F>Gyb?{UU21$ake)4y5Y6q%*r0d%f6TTxf_0?73INR-YZr z0WhVwUawc%O|E!%uR&(B_vNlt96L{pxv6%vdfi_&v@=r<-PW44vvMNjuLp$P zG*cB6n8^7N0$wfG|IdH>-NCFnJv+R8`}Al!nN*cS3%Jl2)75G-9E? zI5#5am>mIU;;MFu*5B5`%r{OHln?+ELF>MldELY}SKC5x(<%TLj?vZz1SVG%#jDlk zAAbMjvkz|@cCwo#L_m8-_948SC0-4-a9=ynp6|dt~*9FF%Mm({Xt)uDo-Op%7_AT7V{|mlw;&PhLEK_G*5$ z0w_pX698&b-EM0lMxoLbtfZ<4+&Ns$51JgXBY?$TnF$g4KE|_fesnmx8Tk<$E zA`+l=)Gd>z-_5(kLNleJ_l_BmKrja}qlx@F8bc=v6}1{qTLfihMUUiAad>d*PL`C+ zgMy%dF69w+HpX=!EY6qHq8!Ij3UB6H5d=;791l*hKrV@xP*RGJ`+)%9Ewn{dVw4zB zloXiIBYHwM)d(OHP0GpH*-0}ce|!h2Xs%X^%S&cfO>NsEQx=x(B)zNv5uo(0sz$yn zRCT>tfBodiSC1dtXf}TVcJbU@vUA6YDVh)kAVf(qUBe3W@{U~b678|acG~vc|G7^j z8Xi$0sRY6_t#1AGXS0dK(j&kvDv%tr7XbvJ-5ATtJrt1?V+;{Qu$%E}w@Zk;Gg`3Y zSqvmB1B$=ucOr+d+oT7)BJ3R;ghc;}E&{+c^pW1^7Img-gh6Cjj$DF4-^9orssb7S z&~Z7c(ECI;t!LP8sC_7*?Om~{oAnm#V4X#NyJp$mwvs3}enEB{9wb$5n)>Unzk2oR zMcX#{hfU&(;`H>?IZjDR?>#&2&S7R4BpNoQcg2Bab-jN5db{0*5R8V^_q5K=&dRdf zY&Q2E+z+BaZ0H-4{dI?D%3b4J$zaz=un`b6O?dY5&DUT30W=*R9unG5Gs zwQidva&~rR_Gz=3^=Hj~g4wq1cDvndHr^L^?%ch7`}T$z5kri~d@w!~!FtvUDv8YS#-5) z7k8}@>I&`Ly92kF-FbT(C=A}8r(ZAM8nvQE!iNnLGe8o<7G5+gnA4cD-H z?j7baPi#!y) zMhT{lzZ$O{cZo&>9C&0_&%n15 zdr%gqm>{HQFV0`SxL`!b$kes)M5AZ~OoV4tqIzLcf(;b`+tu>w{Hx2)pL%pII)})k zko>l7Q3Gh3WZQ_u1R{W?Lsmsa5g|oLK{l(cMxZexdxZiJa!!~aD8?w8Iw1gQK?({X zi8!xi<%)z!&6ODnnsc!ae=-}MX@Q_-#+Gu z&?IcyO-zw}F`2RzXlWXZMM# ztMiNVH&acr+OFq|MM%+X(J60tgzQvNh^eSf?%tcsW}@=+ni3ZJH&3e-n@AEsypND_gn~-P??q33S;NocswbJqHUUOU5AkR@d3U|8zkK# z9T6MC$W%K$v~5ZU8R+;!L>o& z0AsrQ`tF#!*K0>G+osC5%(`^1Ab(fm%owrzs`cK}Wu?yUOmDjjk|6YyEc+*kM$o7l zz)oK35Yx9up!8%7BRvvm1dXDZeI&h3S#N5{#0L3!sM7VZfK(+4MnQDmqtRYeRSypj zr?Z2)X;4GQ=ENS4{!Zg@e>shYU^zL`$+2zXrU>PDR87X?=`1Rkez=EZ?L+P|EwXnF z@4`2I`QG~+yu-ag}2qF*#1w3k~s`BXQ(0lHBRb6!@&_~Zm z9vRznj+)(7yAmgVw0prbGBeL)Np_E?0-&Nh z1)LG=T{a%S17P_{32qBn(N5keC2Lh%GSC zG~;6Im88%_ZDVTN*tBWAu2<`gT_`0k%SxTALEOQ??C^jhHtTI%Z3?7A=fie`F_DOd z*lz1O#3V_i1LUFtf-N1rjb_iq(jOGwy)F>JPIlQvQwf1C7Z)#|KYRW1SyhzCel!|S zXESm{h)SqPicZl6hvo#-0hV^(XG2WrVhSfGhj;Ft03^W#DAchndwyxw43PDKS(BK) zQ1UFHE3kliUX&mZQ6z9o2;kg)Dv3$5L^Q>q+wCSq0oIQ9Xgx4blqIMV_!{ zOOYZf5)qY?>D>nprqk(Wvw8mfMLWL|{Z{dHAARN69UmXbxCqnHcrvr@>CXGIYZmPU z8I<>P%)Zh=?4Q1CxG<<~5Qb*DLC;ois>Qp!jeXb+4MpyD%X*Ugx4#Maodd$_d+fm0 zF%*&Lo|`dyMzqIb>8>dS=7bRZE^XJhj7YWb&{~62-cekcxTdRU75hvSlYMO4W*gd+ zBdHMp9P`PoTV+|c7Z;l1u$+2l%HB1ko=L5V2to)cn&lQV6c5JZaaoqm`;;UCE9ACL zen?S>dO!>Gf@LDjxIH3fm>nK{_|ZqJ<#My#R^zhA##uZ$JLijHwOUnGb#ijj8ShAA z>cz`3#=5Rm_2}s6{{8#RPDEncB2hUS`=aRer#n(1fc{zi%|C}F`Y-$RUYMOggNPtR z;5zBW)pi>&p$BA93=-Rv5@vAYE(r<;TBW{$l^Z%@t6N#{oui|}QRygw?m;)Qf;DsA zb1yLI09rg)MLXSkK0xl~s8%u(iAX=OR)y4~brI1~FV>Wy7G6jn{VdZT(Gc+(E5*5Vk2oTV_RJa;-gA$ot<*4vwN>$Kt)GC6H!UC*`dRU10U;4RP zPb0GyvH%khDj{hCR!I&LK|w68pa_aW$U-EHI(DF3)Gefxz3^G7+L=CgtXTzswhha) z3NDRG=?`q3Zx{fmO-Wlx1SOXNkyW-yUC^SDvLMIE1kM37Ib{S8rIb=gngm+WZ5`_- z)OFj`VY8JOlnIJa<$M(rwi?s}ASojqOh%J&b$k*w+j_AGt2M;LNwjV^t99KpCYDbz zCXgg4gisX4?q`12*3bi0U>BJK#DL1UClFQuXzI;oedRq$N=?0)%#Mzaj;GTZnAy+@ zEF#5S`g6ZY5t%H)+}4C$<+ffgkw{e#1yKN{XBKrkpxLx@r3MNyL;_$UMa|p~007~x zzbps|)O6S>2{F4ucAG%}4G4t)ow+xAvMV{#JKa4Z&T`jWk=P3;*1}?u>?V5|wp!wY ztZiiTGB!`r>->vj^Ptg;WG3~r)T^3JvYMc?; zCMOCs;42&shdYxg3UggDvnnt{%`&ezEbF6W%*nvmxtOBRP>EZ0dB;X?50}j#shRhXbxB4P zjcKH60Bl3tN9YVe%`m2y7KhkuV^LyxcyM_A`t|$wzxK6Jay%t<5%q=&;dR>8F5`*tz)!3^0&w)Yk95rF1dsI;ggt9jn9!~O{nsn}7kpYcduNxWm z#QX{^%1wKrgd(ixC?O4_p-T&B8KDq~3qYWRf{mt1&UK!#qXWg(c4M0C=917DWjje1 zT-pol&4@1w$Qn}?x4p6Md+r>2DvC3W**^3&~O>z(-fFY9_V{Idmwqz(v)ERHFKrKlz%~K>J=+?EXf(vX|DX{g7tX={u zGj2^(C5BLo_KQOza%e0Xg9L_ZQZel`L4-s>)FC)TOC*Wa;7lEW8-cVUL`GNFk&6!U zrf^3Jij~v^$m|GhBe%qu8>6Bu3|s*dH~tbE36;xQ`;WNu~YJ-!vH>~y)(KI-*+X9=@8Es789lB(8c2?D%$O4$rXn5u7jp1+% z7`Y6jgg~(^(!CP`pvGkASRIIj;5m2=9CachY@Jg@B(rIlVF%mZ*s!SKT@bK11RFa) z5M^7W5@MtVHyzA!I5-swSc}+WU@0 z+GM!sRF3b1(!eAjac*yC_vr9&ytMZBy-f*aS^rgf;oTolFpZ04&9K$K8bjdRnT zo$+*%q-l0~T9;)AAutCBM3ls(-5BaMsC(|MCRed{!Lc>{Vtjm9Q6d8elpE9pNaJNw z>?y&ceG7G~a*Zc2A|xPY710nxL>WO0MMni85}7<3tk&!Kd}+wWP^ozDGB-JivHkq= z<;#+Nmcj1r+E2{WjV!K=(7EbZ06PVPz;+bS_O8K`~3z^uZeB7jWD(27@E&}ai9M+HJK z))>mD%_Kxow3;|gT;Z@bpq6qn!kqfxYPFti9YC~Dufd~d4q8YE96X3L--a|qeUTPa z-fqH#7L7woXn-h?G}vfD3y=wtl9CuQPC>}1b!;jPF?Lo(At3W6V1*cfrAe+7P*Aoc zXjC->uZ9eviBV5+wO|1Wfh#0djpI~AB6UPbW)iEZMVq8VmQ}e99O}x~RnVgLrRS>l zz7FCA1e`&aC$;+3>qS`>Zjc#t;K6{ctz+YAD`X5MZeWw)U{DQL<*So&F(*gEQBDqK zGarP7>nw53QtWhwsDIm((h+zD(S;D_ZwA3cO@1%hvR%H#`+7ECG6R4a46@z5!z>#h z8l)E2t=J5Xb#vHg>#RnvUifl0J6*398JlKVn&oI5nwS=&hPpW>^;abXibGrj znkQy7$|F~hn$tr-f#}FnA|L}qY781{oU=2u@vz`g7(|$n!#wzfuPY9+@SO8FgS(OzH00HJ{lBaHvrFF4Z1y)o+X5jdglAX<$v-wh*y$xb! zV6>#f8otexi05@7fO@@p{q*VUr%z)G4LMMAy6Xl#jX0ZnYfV{}PoF-`(xfQYWw};m z5CoMtNbF1wglLfnkmDGIOkIcNVpZ35Rn>0<8etMFCw4~;Vd2| zqfShOSBqIyEDcD6rGYWy@$km&8>8tsFpEXD1T`{qQP;*8P7-IW0o~Y-MdFeer*GYI zqpC!<%@v5GZ4w{>U?qrU7J{k}Nr$e+22TZ%tj(P&ysbx-nTV>gzW4cOpM3HQ5pn5Z zU{DoHz=VzDtKH$2^Lgr=vyK|*4l_$t)kL(ryL)_myj(70Sm9){f3Uwh8V(6DUN5pH z<`~7s8gvx%Z$g8dlU4O&F&bem#7Z&F*BZ$pozG_?RTablP2NaQ5XG|Ale4m@MbIhP zxEioPU30V_#ClgY1$}D@=>?6qqM`u826b;b-kl6cSutqKF547mh_S;cO>2c3a_y#T z)p$8Jk)tZADBC&Ctzb)Flf>NW|05~zGUMbWQP7Q5j(WL)jqN2C#nMZSy3o+t3ck|q z|82DU0IEV7U1{A96`vVy<@pd)3g#7u8ocMqD*y`!LF0@^M6%W)7-LN0j00~FUF5lo zvdFS5s;X*uWkBALr-pab$ST`ohe?toA12lapwvMerq&HcX`Q8PbnXBQPQgqnF-2{H zvJbWQi>fNC>MWEo1EXLr5UJKES#*tiaWmW6B;~OHO75(+2Fb z)bEl8LbU)HYNnuS+IxTE zJBhOv)FPTVpaelxi%3L5;1L4=i`JrE*dA;2M5$;%74)70FML>dA3p+Ch!$l)s0jjq z3YW^Nz$WSd5e*m+QefeDnnX0I!^Bu+3EsD7G6)K+$fDe)#7nnbc1vr+e!-Zub?(&5 zA(YD%w9A!VfD=NC)$fOFlx6wyGgF zXY<*bRHVj%k%3jEcrVB%KkrSmu%4~x4O25}of2R`5y;q>7Et37SFF*O@h`6{7001BWNklSSKb%{>H&xZ zj3FWg5o@h5pPZbGMmf0Y84Esi3MehlI+iF`;XXG z9nvy9L_~#+aGtxJ(J&!2z#t6GdU@PYskgy>yxf${5ptEGk;NfgT=A6Y!)S zfEl0^@FF#Xk2e^ruZoki6(TC7NX}SyxVM`@BFYm57ONn!T~8)P&_#N&4wKZc>g9S_ zW4L*=vuljCF-Fd7+@g(uVe2dmP{upUsd@JFc)2P~YHjM20f;L0Ud1JFbCgd;gYhs= zk_21+zOVg!wX8*#>!MhfwPFI9X$+*)G>{Zkd{vZ-#R32lmrZwf^Wg}M0|M#NTbo@1 zH*0xwb4I_1prN|-vy)RKGS&o@%#gK?toiJVFGbin6U{F1NNkYEnk2DFlEhWoqOoMt z#O>@%_xAV3qud#YuplH7U{!9y5eyMJHOQi+NG)uSt9ASQFsWMRL}ban5DqHHZF^Kz z0qXcoAecy=C)5@efz6V{(JW|;%@ad}>(%Pa+OjO8?j$x@8!VBwV5jy`?JSagAWVO) zX*JTZCy3n|Aw5fcAK=-4jrU$82!|$y{adWvzOKFJ-?Zjnk;QUZte3nR?(Gc|9)auW z!!9?mZ>PlQ#*Y?z6@A_GrM)G*3=z~5Q(ZDZyjbV`mL`LjR#z=Pr?Xa_*Q<5~Pz>2N z2$2&fTlwYR=F7K3y4Vit+08C1Vb4zwLkP9^n|VCZbUL|l^QLt!gn)>{!GPN4d`vp` zEFo~+$~d*1r}Pml?G@lI`?Mo+XiL}Vs1u?JZCMbTV%-#pwxE^RHk0x6^!4ZW?#<_O z=Zv*BO*1mITCHm5R3uFkQ9%%DL8?_%t1gFwp);ng>#D9rA3jb;Ew08WY9)W?%ikIuKT6+$lU}ExM zlQpSYRdvt!_Qu;%Tf-eQtBMK{%HcTQ$;p66L~&n++tUb z^ze(_$iB1bbv8onL)g#RGC(huR{da$*5BF5@0(_>Y>{52e>J*eK%5_5yj-1I0=8+i zy{p&wZ<#|K>Or3Wi=X`HU^jILMu9ujeY*guXi-#8o<4i_{P^LEle5KK(}5r;7!f_# z+x^%7^7r;f#wZ{vX;W${qO?{XLGTF6s{YHL{p|2?`UfApHx}@sFU$4MU%grY76j9> z9u^^6*QR1o@s%&CYF(98UHsvXzyI#7qeN6u@6U=S|Ih#Z2Ood%qmMsGRWij!6m(%- zjWhR0&rbf2|M*{DuZoY}d-tb*_`S?Pp3vX@;`6`w+fSClA|VH7NkIj;+4O>l=TO({ zgWbsocW%CW=lYfX>0ppV1&#qA1@C!Xgil|ce6?IZt>kQ_E2G1uq#;=J*Y-z${F8Tg z9i||N%m4u>L=7TfJWHjzKs@!?mzi_Ik$NtfvAlp!3;Gn4L?rEE|pnqv=%9X!O>RamL1+ z9Ry-#;Q$KCz6?S{20)AnUaPXoQmqQ9%7r0`LqY}cQr8>-VL%E}a~(V@Rw}iME$g~J z=?b6%vX)SRD5z=Zxe^r{PLx!LfuiS#RH$?Mx2-Tx0L}AkcRKb}v0ANkHVfV}bKoEv z?XIF5S(~0axn7Kn=o?j}70aA^WmCIF>TA@#byZsrYIY8(_l?W9w#&`icZF^`)9&QJ zqU;0eMh)Itw0m9ro+l4M`_L+Vvs~#-1=b}qzD=>JUH9u-$<%+FrPa6p`*z-^7vL1X z!3GTfxF5KIy|kPvYiyq7d7dT4s;V(&JQ(Ilx-Kd;CbW*o=5A~uqK3#)ge}una8nFz z?hx+Sx0bdRHi=e`Cfue&gVuG;UizWhibzP7Xt`W|@x>R-46ixSSFtc zH9vk?d#|dK(a2bL?bI&E4Ykb-p=qE;gpD|;BY*;x;M^It-L17;MRdE3Ct`~dcRyR z7iDp9IK6Q=IZTXUt^l7td~$knx|`T5sU3hM+K4lx2k7sPcwTkwNW7>(is5j8xdp2* zw(Nb4G$KW<>J$`HTURV96-cRGfq(FwyFdNIAKbh$9yoMup(*VrN2!BJvUfQ6$nzJc z<=;F#d309Q#Js4JP!hVKgRz4Ym53Ax;^7eyVwt6&gY4GMJ0IS;>J|R(-u-28Hig|G z4%CFksICCf^`>pwfdWxU%UtWyv?6i2Ic)SA4NX!|Srqfx%q7XKTeoiAzGa-H#0ioRal@Jf;l{;} z4NBd_`EBsELp3T~79_qdX3w9^($r>&Nn+cJ$T%}{##&>YO{{a|h)4iykxJOEp1x@F zNuu{#EkIqAJ_Jw(Py*7TEMC4+6}3hM1zeh?))_^O#^5GO%@Bl8mL;hShWWwKmBs9| zsLDF{z`=76WzmL+tS$SaizCHv5_ESi@V+(yF3<34hlhmcDwThL6|JjRnn0yDV5zCs z86pLXU;s>{m$W#9*2;WAmA*YJgY703w&?ba^zW^sz3rP!-?T;HWis#IYMFJRAVz(| zaBvF%+av7>yj zp3UPOBDm2G_Y7GvUJ9v8Y5)KLYpqMtq9~iYi_loxM&m{0({To{`x@(VK~SqlgY>5|NgaW*H+8b>E7Ps$B);mRZ+lVLDo^8XXEiWPf}6! zAuLv_kY&~wQFYGMb^ZML^OKVk@4Yc5O_Tlo{VdO)KYy-3ZOjP-=AtM-L4T71_L6+@ zZC~GI<_v9iasUAe82Nlqi>_GVX3|MA)K?zUDj0<0pQkyU8|B9I7-vWe1Xf51Opy|*HHW5{aV7ZEPbeM9PLkr0|KxX zUoMJY-+xfE5fP_il?{+r^`Sx713>fa#!`lrJqAb^n1BL&cX8>u-s8fMP?7kV}0GN>!p7%UP+ z{14R(Wzc4z+mc(HAxC0Rk9M=4{^SSupFCbmh$?9mVAQH^8WJ&`H|~=vDhi&ZsAOGn z;%Z?r2nr-XRS2x07@I#x07PgM&{AgQ&egs5Z(Mo)dWi_X^WnRH^2gsl8d(GZph}Qy z_Mw4|M9jKPEE*C7Ko^swQL!N-v^U>!wXW)rWrN{pVy%mAKoCJR-7!@}Vy?v|h(V+) zz`XbK*}Sgn8#iz69~_LQ)4&0(VL)!WU(i4|43Ra2WDu8Ui}f

r%KT2jzNp?O<~E z#ye?}0LXBVrjA^b=0nyRYg@dj0wF0t5UoT?7W?|If7vJnNG*}I9{b>zIR6(jA{AUc3dDFwnyI#>z~-*&42+$8U|k!Rb?>aCsW(hk+ z-)iuNzd=!Tfx)BOPWDbve13n$O>NZfD(4{j-`pGP+3S#0^zB=|cKCb%05HZ_;{Yh) z5Dc2tVs-zE`+1&CCX;9t3@l`<4`CB8+E&LGTWS4z-KL3iiRpe>L)JNKBNHA(x@^LD z9C6NdLq;MJ+)BTWD}Pm0kDoqW7Axayl4Un<-@f(EJBpZO>CM}>7OQ1Z6bcelfOWlI z2a$R(Fvf)7>$)Z)aSi|mgZ#yd=O-s8T{85}&Tf(UMNDYxLN*k}tMw_MQr-WNiL5t7o-}X^iFM7^Fsc#p~_x>Jx(}v!pvi)=r94ZDC z1|w=okfQY!_2g{+fBn_Z=QR){1c-!5GT7Of932erT;0trr3|$|Mf2`OdVhrgskz_*g<9pZOt6`xT?xw{>9>ScYm@+=m2-p?9jQB z;V=6)+z%76NIfB)H+F91>i z*WtLd-7Kmgh4)4oRjg{N#K?de1cZJ(;3`SSJA2nAlaKBmzBe>C9E@2$-bvSf{NESz)0&x`QkyG}bbPY<&wq38 zq^eaxNg33p$$PhN{r-0jCIl4Z=9S?G?_U4;qbCl8L{R1R$^75{#i#QU0vJ^ljtxPi zIB-{Z^!k+5ga9ZpTVARlfBKide6nKi+?Xj5azxYV;O^~fSFfZgKxX0YwJZPWFMc_k z?*90P?@dxm%B=X}tp4pPn`NRw*cHE&s!2v)1rd_LdZ-8ncsjBx+x07f** z>}=G+0$GEEWDF9m7ONM}pI6IbG#DffXQ#*S-kARG58j#Njt~LFC|DFjvBD1kh+>Sf z4fk0?h;UE^5wY^(q_xl~69|C^Wf9{8F%tkOP%Vjq4M3}kDo>sR(aIT(QRpHevL8ec zAtO6Y605YXYVQLQwZ|#~R74Xw4ZSuy;AI_@%McpBS<~WN%<*~ZQtxZ_Wl3*pU-dG) z@M2km80}snNO3ZujYWnGphYuPvtwL_(L5;Hav(NN{VwW~2t=_%Yw0B}KWg%AzCq+3 z|LJdZ^?rM^!i${4K5*!b@hQ!Y+luyo!=IzgkwHcLX2M20jqQ1{!5EWenYE^>L+oaS zs$TkfHJ_ipdgZ-Wg~@nqV(Le~c)Xw*K6l%+F{NmoO_IbIgNBSvhQpC_NxL~l@y+JF z&y{G*o3T!0?Y?~V>gltmbzP4JgUMua=gu8#t@qv#4Tr;9w{Ecy^ZC5?l@CEJIY1<{ zS{K4hfVy4}heK!V*?cjd&3s^MZQ_!H!-K(KaPQtdVXxlf$hZt=ONuN{^lqw!!EsRBM-6sxsowIUc01q^`c7fwO6s>%@jTaFVw zMN}uEQdJ%$_GoW9ObL($8lj5xy3DO;UAs(4Xoka0=TbHUIK3#t+DN!IB~Al~X##dy z=x#ik#~Q0^Yj$Un%L**qgetZN22sF>TNAl(1>oERdhs<~<+o7*c0E=_l_tEQ^Z9Cv zK0yUiQ57Hb;q%uo*MgXsc!5j zwqEK|rDmx_KfH1EV0WAlfM8MApMUiz2wIacn#l3-0w?S8*N`Y>KuCfOfOX!tR6u7FFAAJ17n}?$WfeGd-|BJuB_qU(je;&-K+Sg$HC|y38 z)3fCVOZ_+Rj{oS|;0Sn!%=h-j$CIpF6`Uo8i~&GY0XSW({_2x^uS@oU0D;Lc=qJB^ zarD3a@yE9&1~ehKakT%dN6)CWZHLO=fBfoIK^*-LvDPL6(8~K-L;w&h0CkmrVEy!q z2fup05SyfmDcFS2IsKjahkx?Zj}r$*;L6@K0UhPZ-p)8hHY&?X|HFU&^FRN^y;8-i zG(js0gk(Q|l)Ge-4>WLHh-kfmD}9!JBH`7mSCb?WQR8gxOl;k8Q92}NooL_?6xG+VSguZ9pK?`C$HPIA&Sx(VcE&&a z_u~U9jt!v^ChS1=4>t4qGOugp#da25*!F+Ojnca zicQC06KR!XX_0Isf+Masin{>qe7qocjOUds| z?+UvrrO~V5TlEUTg@SIl9$vvaV&|M=142M-^qMX z=`IYl4a%)l%_xlm@Jc~N3^CBE3afRwD%mq3Sc!2rNaqDZB4t&DmX7hpiof5p5kLhJ z*%@X#qa|G+Y)aavT6-$1H~jA07up@Wy0GVs3Vxev)j{2~^Y(S9 ziA{^Vx8Su8TMV@6#^SvvqVJ-YOXq{_5T+^p+WgmELSjtE0cn#WHjUiaOEYLKDPoc| z6Hf!=eDMG6XP;F8|Ml;`pCk$r-o176#%E7oo~%Oi7)0YfDp|3Kx6T`vDbp z+By4$A;lD(eeC5n;6%X^9_;Ll((L(sq0A^wGh8XCJu~D0)*_!g zc>3SIc=*EO+zpmyfZ4D>EOIwF*ni^epFTUC4rsiS?Jyr%_ulUK#gi8WE2=T3@yUCU zRaLJG<7*Wqj}TP-V)^y`XCL35pdyH5S<*YK0w@$gSD^{~X<9)5!Wsa%BR*;)Dz55U z!Fkb&l~f9(8rUeL2EKmvs^lip8f3eug}z}A!UgIb^;Pa zuK+bwRcRF*W^owSlp-wa^_rPS!%?2+L`J&X5@Floq)}CgNC;bcAp$r(o0Ua*_3F`d zXGZ|);C18SfV!@Uj6n**%#4I(Ri3^&Ma9GYBlVtC-n;wGt(#ZS;Gzgg1B^5V0a>Gc zJ8C{+F9#J#0a*iJ4O9Zupw>oEI#3+YN+kVAQ(6(AiN6KZ2V_ow2#^#2krkAMnNbA+ z66dboxPI;KJ8WQ8SEVqhw;^y=X8TT?k-^j4?(3+v+R`~Y$U7z(#h%9n> z!!qhIo6sXPP1Sq3O-(e$z-<8_V};c)(2)R?aLd8)7FBkXNsh;3K()@T*K6;6OrVP( zgQ}{WwGvpEgAXDSE5ewvhOMa;w@qGgr?=Lw%AzPrz{qnzG?ZnTb4kZAjs{ZgSsGWX zl`)Y#7%n^yIy*ai{``3eVK~gE)9HqV1oEV}4c9Qmf536<2_JvajeQ2lP z7K5tU^79SH1=$G5LudHix#vd2c0#=-NgYkTk9x@HY3 zKoR_}zxZmgu7n)K)c0;0s!*xa5LI@9`5Y! zaH$o9NvZ`up$47fvo;lT1PhY-X{BS4VC1XI3hH380RZ)i# z#sF*u5(G6UhJ;X*fUIypqUm%Lk5!^t)uH*w2~i#G$0Uxmw( zM22nj6)50hv05%ys%B?0^`#GGefReDt4DiEvM4J=B@hs?##%>Y+5mb*V2yG#Y8Bri z6o4v#n$T{-PMbJL?QG%*gaBj=VQhkV1wcXp1)|wE9st__(`8V^qZ^tEjC?8=)MaAxfMx#t>naCA-s|{r&yDy}j{xWSa@@*6BRPd0RyX5CB%F zF3XG|RJ9Bgv6t=nPCIvf1 za#2?65PZarSZkcI&RPyZIiN;v0!lX-?3EX>^VAkJYPnn{X=Yt&j4{@xNfPU) z7P8+IYVik-i(m}-Y6~^$YwC}WkB^U!5iw1Z>2$igyW9EZV1u7E@p&f`p}dHQhX)7K z$)qfbSFc}x_Um82e*Kyd0m!-J!|#4{>()C-k^;c*{P1_L-@NtW`1tA5XS1`pG3NTU zYde#P!3`BXevFsu0?$e7E>u@BEUaT>k~T4?sz5=p7N`}MRkc{xYcCAc@FtPYwUqje zrLNU?X|b@?{cJW9ArK3)KiSzG4+v_IfPhVqvTo5CdV@dQ#Nfp3wyjy@0z+Zz|1^2U zy*5%Of#2Mm+HB_A_2b3adhaL2w*2a~skEbTT?hp_-_nC~ft|hjFB;CG_-NH$Pl0t4$2AK001BWNklcsGY;qS~X!+tsQ`K zfK<3H-o1HrFi95R!I~8eQllnvk(1LF;A^+@9D4z#7wZ5XmT@A__(* zZmjr8Kva*u9k*feCLWU%w9C}5aP_jZhvG1NoQL}Yck zSQmR?U~ADlbp*Ir*QFO}H4KPooJ(?-<_?LxN?rMnZeF?j&H(}_p$~9+wosOcsuPNO ztI7a7XcB*8K#yt2yRKvsGy*18jh3in5KxISCqM-y;qfT@_~Z9eYXBgqE{cH88AMR< z3V~&BcjxxOZgIS>gdQMHN&kOP=TxuH&TNuSclVMcF-Z!nAxH>pZF3SsLkcnaT4(d+$;nBU=EK2wwJv=Xjt=+J z(fD+^1`tb{Bt(jal3G!i(V#VkqT5OYgbBcyM##aUL7`UgfVPd)i7D-Z!U#er4cRQyUaCCju)^@u-ykR`foz-Uo9 z;x`)Apkfq@5{NX}Q;j61xtZFi5Nd6Rn+*A;g)6MhxgT5gIJ7L84m=;BLDKc*+e+Sm zT0%57idqg2u8c>cBu%p{Jvi9k-`^h&hn-a(`?B*k4BH~c*aij6+bA1Vjil#xu|V9y zQ^cU*=%&DEwSaEM3mQ?9{S3=X3|4q9*tw4&zO3I95tsT88zAD=Fy`C|cLQ?T(w1%K z$l~S*0%*~O*t`YRUidV%DbVrfG!2Hj86veeM)zXH%_+RGJ_is(peE*a#*c|MvYsYk z8XDF}G-0&D7er)4R3S2XJ{aB@tkF4{Pw88;o*ChQu(gM+(w@5VSn z05H~Gy>fKr;PB(`epHsFh*)c#vl#R2b;JI9OWl9LK&w5T2)092fd)7Z3KSHAP{BH1 z7R!nQBN|6QfY_?gwC70P?CswBswz}D>VdXL%e~1}*TF&sRij~)*`vKdVwjraSR{`^ zOa~HeR7VZFyscYg!xvQsjC>7II#*puZ#>xKXh9D#s@OHv`UTc`!|@v|L6?KR;_)r= zN)@G{%*)m*aWlw6pbIUmW`~pJd&8blrH!A8_i8hQY09jis)R~0jvBkb1!!?uq=Kjf zNJy)q0>$XU9t~3iVl2^s(j!@CD`TKF8$*N z&)>hYKh6w^TtD2svAgs1)l*CdgeFxv+?jlI=jI5&a44BRz4!EV!3+t4MbyU9f@lDK z@WK1j{XOm#@Lj$n1AKPx!KV*iFl4&z)gnR-%FPn1D4-yMOlTHGI9ttUzWDj#>=Bw` zFwFF(s;{qzsYjghO>%!yRBKU-G+;jccOd5EB~ zrisqVC`cqC24OVFt{)!!iywdd{de{<0U~&L7Cw9Mtf;&)pPd%t!`vCWzq|9l|F8e* z@sro>cIz)GU(Hj^`~DxTdperV<1Ts6GZ`?Ef-!m&-1OF3Yy49?3}FF4W_!o zaJynNpPZZm;I-@5ZIY(LA(0hj4T7Q+v-MQ1HI?_|?b+Gcvu7_R(_JuTzFLM5#>3Hk zwJe{Mgl(`lD736iAA(A7))0YlWUVDoL~zbJXJSr>0D7>jXst1@?M8_QFzn`7U5sK> za1j9@Gi#fE2>=GsrYTqw0I%YKJZb<8g0*M>%NPTRsC!Ta+Y$n|2}P(Vu>ffjT(t+@ zh(jWS7|GGB8sii|74(~n1H4SGzB$>q+m3T?I2;ZJgUMua>(;H^-MuW!($u9%lBP*4 z6xtagZj~0Q2w-$${IeZHwTU#kWOCO2c-rR0e;Z)JhC7IxbeR8Pk$#Gq0uncwn9MYgdCgO^3o3LIb~J!y(6~c zIVC}$Rv-{W1%N??a8>zNv$YSPHbomTSHhw#*WeOcYpiI!_pQ5a>%4K%*%|==>Od90 z3kboW>`h0*+!8Qt(wZfj6Su_a(R#jFIwRYmDIFqvw3n81QQZz5JgP%2yy-dar#)WU z!8$K;@8G2(9d5UA{k7o2H(+iM-Y_GKysrzbIP5?bZJ!D^bIx|&hz-3AqwQbYq~rMQ z#G`w&rDJobK;%X_4?rsWBe(m}UA9f<7DNCd_?0}G`qlE@*N=56qta8YkDtAIdb0fP zJ5yjDX32Lyc=zugznXa_vI*jQcWz!k7&-N*a&of%;=z-3AOD(yAxnT6pOn+>}a7eWSp|RJe$qS<*CD`#>n0wKz_U^ zr_&uvSk7k$`G96KDQClji4!IDA%uX?FrWa-fECBHj37$G?Iyf?WqSL{=-sUe0G{i_9gT-+Owv^PMEIsnuKi=Eij3 zjAd0u2*6&s5?y(G_B&_)@z4JD*AJctz{I8Cbv~PyWtHc-F|Ipic6Zvv4niNp)}5@D z%VkkjH*VcTvQ?0wP3lOfkj7Ug%vJDZRoN_C73*g&p6~4K4Th7~uU|Xo_6`m}l|v|e zXzzZCJ_{l+1PaCwB{oTOm*?4FkU3`n1rd!QA`lQ3tc6(A;yI>bFQU9XNo(wU5u!Bf zgs`wMLz^d`W!ZFpzn78Q_aEX1!{2TSzN*876pm^DouUB2Y&As>kvw90JqC{i)iLFPS5cP7VS98Wf z21BS@8%p;A*&;H=rVD^WB8uPx6D0tfSQG(`4nsmvh&2`wwRr0Wq-2bV!>Ykxc=P5B zMSgz#Y`tDW;M66^66M(u>l5$nzUU_wSR2EONC+W>FdPmK4-b8i5JH+})9G|H8g=5k zwy>fO$8~O?7B304gQMB(bh%tab=UsE{&YI!Hf)L-0a|<$GKP$aNe>Mg9#jxvu~^){ ze}B1J4TnQ#-R|!0ty{O8bN#UD*e;dsSs=WW#CGnF{q?cq$!&wLI_pCmt58|jj09xZ z*waNdUsfC?CXo#T$|9l-HvM96EG9qJbxE+nU$_aR6!NT!pqvjpM+0ed%D zr$XOQtTrrPZ7bTIi}V7WM7CMO(i`D*v*4|v+l5D3FFQFyaF?i(c1WVlf5lE;HDT^U+18p@zwJa~M3 zwg^hx<*!7mKQjUtG6vDc9ti?R!Y!x(I0W(xZI5yrsMa~98{&)WPhj+&b zW)x~)3c6a&r(Zq&v%mSI6qm;|cK|>zM9t=_ZBa-NM|%(tnaT(z?qLnA7eEmLhwpvw z?*HOy3B$n1 zF2VJi2YY|=KmDKo<!Yj!QG`{Es7AHfdcA)6^3|22qw#q9kw1qV^9REc$NSpiWWEe$#|YeABZX6b9i*$=L8Vm>d zAQ_LWv#roGwhyqI(>1}etunwETUjg4C9I~YPFPh9qHA1oy{=k&Fp}+XV(hrO%^V3Y zX%Y3PNwL@8x(?dk?Y4)A&e~hIZomKj`;*Be%QEL&7f1x4L@e^@JkApI9W9_BoZg-2#IpP#5 z0EW@STRVdgB$uHU$^yFabUVmX^H&t~iS zqWKwO$~XdwaL=|zQ3Tohuwrw?T6=VKRTWRpX5;a6I-S}ijbe^|i*-|6bq=P^s*j3* zgi#3)d|kyB?B3ptQ=Q@lE1{?XVzhLfB(R zjX879AgOWys66)^-vmUnx_&WRGFcJG5UhfVvH$}?maM^~E*lp*D0x|l2L0;(!|%R# z?atLP2<#1qAKtn9%Lk|HP))DxU%#^BfE93F^5+jX$JY=VZD%pgL+o1U$1u$_OS+@o!%Ia zX?B{d7k75XQ-^AFSroo144`SIB_z>@udM~>tLNV#{O8{y*_PSZ4r~nTw*BFIRb% zBjV#nj{sme$U%emEZVpz+c;lqjI+kILQ_SA+Iv|BBJ8sWd$LO_U=?EiWJI1s0%#PC zAQ~b=roniL#J`D0&%gm%6fps&X_7jZSgY0<=YYCSjRHuN>ckVgK_avO0RjI%=HB#4 zvg61TbN7gM61)fwf~*gWMldylQdds$kALR z!5NYumtX@#18DS7cV*@EUPQRNK195iFSDu}2dUMTksw%=m6iGOMTGm$e}`s8lVy@; znJBSfq(7*dmR;E8Y>5c9Z9wbJ--|3v*MJ~-0)uuf2qLxbqQ9_7L|esQQg20mk1=IY zOeT}v-Q73`j6~+^o;^3)qa(D5^18Ne>UF*Nyn5)lCKbA^$@+s7SftR~F1{clb)!+) z^Buk0N8*i+3Eg|$nkA)Afu(B=rQ^?PpClsdxk(FJtS!gl^CcF!Dt3V($UX6TETrQV zqBQP_lRl{H+POMN0Kl@WG%za4?_@F_m#>yt{?s`q zfguw>i$EBaj}*NJq7O(*!0%mMYA2FpObny~pe)NqqY*Q!cEwrhBnW%oLGABcA%uqy zA1;>5_}FSNIK1-$TEn{bo48hEB?RmG!2MYacSJ={ldw#pRwbl}K}C_!P~({yG#i}G zR?}(Y!Fsd^1WcV>e5;|`hIsk~K?p%Mgra&KAL@Q2af|~nEQ^EPoy-u3PZWFI*h5>g zjcnn>-QCzPs$i>j*-Q`o{d%0|aj-UXtF_-`f`0lUy$Pf0WJA~MRM<+Vetu?#YIhky z0a<`CM1QV>$=DLGaLuq-H7&s%6oD1qeR%R8fA&kshpJGdF#$4>nA{Ai`KVac&2Av_ zY8brdr^~C4o}9jTdnW_T4ZiW}OSgCKe>A;(?MpB2?Ti2dqkVdI@!*rw$XQA7a}0=! zVK{+*{Ij3`6!#9u8oZJ)SZj=`3SzYM7X^VhO*ED)0>yIN7;CH{#1Obs z5*whZEC+)M(yQqCC<6#6BSu&iBS}}4fRjctVTMR4-3ua@3jsuvrxbN`LRg0Y#6u#g zHzU4=5E%xY_1C((koAtI;PGJjoKzGt#qeOK~t28(1?cjt6 z*G6NXvB1JDG0*4pUjLK{qAH?((QO@WGSXkWc|8Xs!&E9@5B%;-c-O?Xn`TU!r~!&%!($4i66xj*dd&Kp>02a*R9$*7^z*RsR3hF5dlL2=!Kp0Y6?%;>Dgj7_h<^BOx1{*xOYJ( ziRtJ*?Nx1ORe}gX)Uky2#i;bFowP-46a=86k{R9K84ik!Kq%6JRlAI@q|EKDY*kK1 zqcLSiu~$Oj*0K<|!7W{GGELY(t)k?r2i^Bu`@V+s+LNpqilUoE9^62RZ)b7XJtpn3 zx^9_UJFr%39;fnaN7MBKpV3El`fg;=$nFh_jp(9TjK}4RFWj;qNa(zrO=qeUhgU#= z3I*iTsjLPjL)hgYM%jq&j{RhWL9bK{5d;;_!s1zGUVr`IldpdH-e^>+!em%|<;6ph z*l(g2Yo4XK#p#qOMuhi`im1 z|H`W`j;owVK;5e5(~B7*DXJ1NYD}0Q5Tp3JkI(;?zy9U)_;|IPHO>WQfsB<9&|rcv zBjIG#)MwM>Sz{C=lc)phe0{(n0A@JK(WUMOG^{Q$7?c0ZlsEWoIW-hZVBMR&- zWkpdihs(>WAe`Ic==i7!;m(~G_V@RyvWTEQ0EmPrVn#x1ESX%UyYX86xVZNZxWG$k|c%~X=?*bEmJt{BLt*GC~;gF4;yQ2o@H5<akXaornQ+cL3#yx=uEs?Sr^qygb3X!rlKGyCsN!`dWkM+HQBg96XB zNL@PtB)K>!X=@=JwNJ@HXxlCErmD29wUm--3S(+702=CBqxB(t5Cqc}~EpF%dMXn}$`(yqHWz)2sQaUJfP`G6peG?4Q?XteeLt$3b#q2Ow=A7l!ter;UkOJImv9LSKy}I1Kc=66zTKyHwpNC22BqmjJr95ayyVv00!_HYHod3Ps!X=g|X0{Hm&;=_l>DgX;*06E2(uG@9K4h4mJUK*j zxU*9NsF#by%)4dN)VVcpz4q$3%t;|AT~240S4$CA5NWfQ0ns2B)$_B<%d;tIG^?`F z^9mG9l=mjdtAL^a1|SA2m?1%oBupGHj3Um>$;>)Jf)wyq_uqf*&f&lP-WvpH)qMAx z-<&P|Cua*&404Mmvj!*_98JdK-Q8uggitFBD+f_l^Fr|;IeY@8Z#JB|CB3!$#-@nn+c1&dVGpf$VE5P}aLh_cLHTwG*%&MJ?dJV8S* zz4X%V-fmeGg|$eU=tjnhvZ#_FB2?j^&@}$?YIb~l%EH2Oc5yYHOyae%q!zXHG%!S@ zK%S)$4#IXk9>-N0IEZp|izv(T@bGYd|CS0IAD^6`pF8JbLTNl0qLsv;EO#aoW6T18 zL#O~Jd8udvKmcWpQLHG*7qWA;R;!Q!<;H|Ot8A75hNceQX<$RKZ_s$+c9{&l{aUFd zjFX9G4xpRzr8tlQfGo>)c6N!(a=CQQ1@F`8WFX73q9}&L!Omo7va>UpOorppcrqD{ z$Nhuw#!}{n$h>PqW85_R!A}91o{31(#tF}rDjCWBy<2%Jxta~VNGK{Kv=OVdbJRYwa-!%15$C)ueMmk52 z-gxmDmjybAHU5>nDAM3NAy{gV)`bAJ1MAKqT;$^Xd^VfK?jl+?z;hyuaCI&iebqBXua^Fc8xIF>hxmq=;+*ov3X7$5WyJ5XxK&T+=XreN1GN_ca z9g2f+(?Sp%XJ7606lP@)0N&t?u(8E#RD|7$9gjV!Th^MHA&~dJ6up<1c3fQ?J)LB_ zUz8=f;JL1wMYCMgb6+pM_sut7xqI6vcmXH$-UlBqS9Rh?^vp5hDnP(2W&pPXmAJQ& zB9ip?z$~)?%}PtDpSheA#%OADtfW?%noQiWkP!-En=iq?O0ukV5p!ROjy<+`jX|PHcI62#xbm z*nps*yg{jjZINuBGaW%6W?n27d7h7kLqIIcvZ^X=e*^%|x%qNAn@v@)9u~KP%92|L{ucA)tF{MNSbCBFd2`({zrc_8jjD;&lZb? zcRup;iKrS>E>4WjLo8-w6n>l*0mA!djDKUD1Bk4gMR&} ze?WTs@AnKhZlpaw{O(~X4{>wqx^+F)@i%K4H$HRAPEyd$Y!8z_RUx^aGjnA5tS6wY zbz_@Ug)LJU6X{n)kkdF=Fa}17_7KE)RJB7TQLx4;pv`bF7s%&1eN(g}iCtO53Sx0}2n*Kd0>5|-~YY{a%1t!Oa{Le7C_NlUS7Wc!G|HJ!3bBTw`)iUTxOl*p;Rpt zfHVM$0bkkDmc-;Qn;O)i7?e!KC_H?0{OEZ4`pbJ6!p<PJU=F3YZ_wt!+Fm z4Ti!}mKR^Xclc-D`^KGd3CawzSS(IYFHFyB;ZsrD9v=V@v0kl2WOsMZSZktzbGz_W z)mpQN83YpZziC`K9vwmrN)dZCJ{HD-Tz@7|redfi#xptwp=`-7;ElYye24ZS1*h z3ksUVvO<((>)9jIXi|_RrVSw34A200EsB9JLD&$55J4B}@uD&j1;A+i-`TAZQG6Hz z2n(?6j>lD54#%V6umUh41VZ$nn)vb^y&E@nc#OW%XbBAxwmBCTQ-x=YK~y4AP28!7 znfC8vW}eSxsv0NbyOT*(l(_lPl70#ndn0qM4?HKdj3}rEpp{qWf^z}0!ODf>iwm@a z+b`^a$r&{;d&eRg6BvW%D1Fp~=Os|Qe>cSGPTZzA1QgwH0tQT@DO?xI+>*2nz}|Q` zstTh_Y1S->0oC3+g5)JQAKIh~HO8d$2c)Q%5ml30Rb{q8g_#%2C4;my=q|p ACa zgZy?Yjh=exVfqXzRiA{Q-OhCrg4L@vqi562Pk6nI>-9f339A!`2Lv%D8w}8-EdTre z=Fc1;pg~bUvNoHHhm(OF8zcs2V6l{+|K@|=eRK>s%0WrF<=X1){evHT`x_tCO?J3@ zH?s$Wk@tK`^kcWmMwPKyGp!XhBcs+DW)iV#=CkI(M@KK;-N|esJS$=2<+tyDbb2up z7{#q13F$#VLzKM>fX(y&>id8E*4Mt88krtihk%Y{y72$UkA8AGs~aziRbcPte$`C& z4!(Er31xm%X;paVcc|FQGH&W{dNK68H#5~z2OxJwgEx03_p&O#=T=R9wOp!5Va(2; z+T9&nOQiu)n61K(e{uim#S$?a7ZmwXf=J0W9#b%hs)+$h>xL*ATnPXQ5(62OySMiL zhyV89G>pKQA=!jwN5^^eO8@lUOo@UOm} zq574Zj3%SW&a@8ItpmHiyDF-4X3g~5Z+z)4h*8M%ye#wFX15P^_p5v?oRd1TAAWpv zby-_2Y|_nr4pwkn>5Xf~;|U^8FE8^vUoMw};V7>v04R!rnP;=Bsv3;Pqob#f%e;8$ z-b+Q6hsF&CRTQYk@Tq{&Tva)t9aO2SjxIn%8yc#%3695Y@^1x6266rI<};vjZ3&;(POh8TS~rc`^x4H% zpVOuA+%5TY)l6SFD(Bh^NUvkLEeI&rhcbk8eW1}=+IPwrz41l%ePRu6&{;4h0;lab zHP*5T8Q?}x8d7VzD3lc1X&9}YcN=v}Bk2y2qN+lL(I9}$^1LcbU^alvEFcQH3EE*x zRHt5`IH(E{5rRRqM1#TL)^J!>rLat|X0zE$Sh74XtAVs%n%;)lLXQL>GsY4mzI6zO zkR>J{N5D=xYm#I$)MH)y#`(q>#LSq?n8U-v%w)(BsuED86vHgheK;-)K|qYm2&DB? zA9~YlZMm~a;m%-!Ld~@FvZ$TSD>lV!Ue8w!%oxblL6mDGgJ5Ft22v46ek$OcZ<;3J zj6}pyr@SGHL;&1opbhVAXF8U6hT12 z;Fb~BCJ8J8VH*=n+~{KjTL4U>pDSX=a)16Na3g}%1}xs-YZ}*P8~|u?0%vSVKBPFZ z_G|ZEP?VU^pwclY1VkG!CsY6SFYf>HS06jb70{{@3WEkfQk>ZQm7U2P&cWb8mfzhQ zRwmzHx<_ZtWwbv)1O`Nev-#>*?|^oBjmvQr7d4NB)~#j z@0TQ~P6n2brZXf*WMg^j6&Sz>Q9Qm83|U}(`{%#8d;8Y6?%u-bs=2tF?C(!67dzvE zY&KQ@-T-gs`HPwTMv?7|M|qy-SsPEH5INKD{N~}`{N2w(Knq0iR#|JO5Fv(fQhP3F zx6YGcp6F`T7-Oqy004XY`_@_!F~%@^Q9Zjno6qOt$xe~m2M-?PS@!bFFK2mvc6JuC zpCib^&U=YPmN1JXML^6*6ct8QjFpKhx18#T4wH(4#FeTF(mEN0zzS+phu^aTrzAJP z8wr`P8FP`K#h$1qQz!rhfe|?-1Yu-ctXDo7(9%*hO5218D!^@}j$IRvJ(g=M&WPx9 z;K0lrxI1`42ps2y05J!Pj2VrFli_G>hJkC1;dQvBo9@N>KOtDjHUd;O^+Vg}dW+ny zwWIonLXz}aJkEas2-a4rvTos0z4Bt4J%XwG!kZW)*Jq(y)1R$TNq2hc)`QzA!B)v9LC*>V$h5 zwJb&h0J#~lsQ>{{AQRIj7F$p&&0{N8pp2H1$K*&?SW9qRQFd#l3zoRZ|tdh6zf zQ$!MW!V;C>6c3`7=A&p5Z@pcdL6n0m>iXgF`LEu4^q)R>)C3YN3>X2AfP&~1jF7Qd zRb{?3D`^~H-ONVgy-{iJj>g0JnF}mrs3^nUWOlXO@j{GbQB|ItU3~c9;o;7khENea z!22JcJUYE(w8>~)QBeg%fk~NxJYXHOWnw%$0xN)kQN@()t*#D!9+b!richTlkq=Ll z-!*Vz$>oNCD?=lj+u-$Tbtf+?o7v^kUR~|w`6Ngru_Pe8n14KiBhC?(n;u!C{Myt9uHFA`D+h|loA_asXga{_3kflP!KPK|R!Fb=|CL$04K^R{J6z6$Tbc_&p># zTc?#(VURxJAzh0pLWnj^pKho*5VnajaHALb^$QYT4Jnu|kPbEo%xP;$&mZ$Og^aOe z+Nu3Ey`w+e?~_xn3u;>Vv~Jn+Z1Byy5}-S=`-e#%2X2!DljZPp7)dcFyZ6`d{~I55 z{V$@%iu*o1%Zp)4MAkAkpzq3l;|q}u2eF$s`4$A)#?MsOjli?S1f9!&>%Jra7(`Ji zzD^=#iRimVky`|@qKY>~j{vYLqCo|tXcU6A!P+d#5K$z=Ur9%1O1v@GODkA=ZxSL1 za|oV;&9cl8A%JjbM1uEOW-D9TENgsdnnt*9T&oCR4DIjkR7JjAuGl-*)VU?6>yn5N zOv*&ngcZWJD|aW)De?l_v=d0gQn@ZYO$Sj@4WNQyYIeR zqIV^($3IOjv?n5?=vOMOl(`j(-n_IATfn7=a%O)EpY zq>1PHQ}vXOUmV^>M3Horqmr&!xeq@&o}Z5lD}V@c2b?l1GuO3W%vVoNPM#c})n0?z zcpt@J*7>}C|G~*ok&e3+;=FcKaSq&cwmO?OfH^YW_4MA!g$Fx3o0Znuy+I{tz(W8d z!H4>t-#joT8&(AaIl*85_M_SXqCqtg0f@4HQAEV!v&Ap&Kemvl&XQ!jNPrd)6-330 zOue5r;bQ*)Mw64fcRtGUClFQ!Rb)`}t*RUlxwG@UcDHRlnqJU!mQSw^2ZIWL>iYcr z?4KTf^5Oo@-e^z`syr{OwW{cxpU!8qSH^`4P0?q23zW4soY*JXM8CtYz?O77bG7Q({1pF+A`E^4lNU+wnS9gC_PwBN2^z0(r_G{byXp^bhM>}9Ef1^FlA*vm_eJ5om zMq5!`hX+G1>s7Zl=Kdrp_TSH$;>FjQ;IDqF;Af{a;WG;g?SnSkrOEHZRmb0ldJp)V zJ$UPxHxx4%goGk^ov0UD|2k{!YWXn~H+9=_KM+zV%IYk6MBlRW@0po=iNxltf zY#Gr9q@-aKB|#;Pz8=w|L6lT`5FHXg&&#Tdhw52aMG}uNyT(QKyEVod6R$#O8VSKz zJ1ELQiFKB(R&|89`{K&o-N~(k{fEnkDtvx+`pT;>CntLB@QR-3`59B`cqkhy-XLGWjAuBmCqiKmMQo!+!`NeDj;%xbxzj#<|&SR+QCf zG|uzPWLaL6i{)~@ScD*5^SKqHdSi8Uz06uG8l^Yz>+3?+mRxJVtG}l3hT2H~5Ix)4 zGTxA3FK@s7>u5hNpqw`N)-*sMFpB^olF3sW0G&=hyF8!$pFey%rWe}Glw}5kQg??R zu9mc{$AUwptQZt!X;!m3FLx*7kB*PTd2j4+Xlw%o7S!m6Pv@UJeVYIjji`DK3O33n zNHHP;1SmkN_80HG|IV-9i!Rd$6cELj_?at0V=!bU405`)R~#J7zWP-JyJExvoKp67Uiwcq!6{vOYK)ne^LA6qq&6Of_EHMI))j1;GoRF zi~u;a(f>Q$b#!ui@xT7{-^IlkR7EkNaJ`SUm*1p-x?I+O^P?XZ2qNBrw)RE1!9q!q z$>crfI&4<@!+&^ZARvIE#xv$%lA0Qotg%H7S$=$3FT>OYx$XCYXLCV@9PEPhHmc#Q!5+3gUXDcb)WyWul_{nPqaMEtBHhEzTx zUdJ78pjfR5(H-3kKM#lOrl_PfoU%S=umv8XSEaND-Ld$Ow+^c$=qZ6?@hzYz#{?aN z0LY^20*ir!8#;Ga@qq0FjL&jPggQHi#n!JPK zDjp3-ufP8KC!c(>SS-#jFO0QhOq5Yhqlqd9R#h)9 zuipRgp%mUZk+spvMVzCTCR8j}otA0>>5jXm*Ehk0|B=5Iw+t&^F>I-#TTUgrfhqM!* zAtV(H@e@^IP-$O#%Df^=F&z)oVAshc|LuU>G@_(r0Ei$EIS`NI@&1K7U%HSnWKJdo zZ;kdp39j1Phb()1divqzRR*$`We1p*h#7MTffO}x6spHR+WKrIVICnd5i>9tj&8gH z3xZ%WuvV>+vh;^LW`BpqX$aTfw}pSnZ<0)uI46C^tItL1QWU*8l@@R1#~K zUxK0{!gYWEpg@i=vIRD#{AuK(2x5hDL>8?bs~~_?B?QfYp(PEHwOKXH2ZN#<`4wNy z>iw5qDa&g5 zF|lMdDaFQg$!Sri1OTE8z@%x=DhLb`5!$%_SZKk|jkSbPPI9e?xrrPTWBQ&~I;G=er@9=|4adcpuF$Fmt}9>QM!G|fKlr>FqGLit zF6+kF^x2V>?Hl}51WVJMu>HHwC(%DQqUV`E`qZLLZ*ot#@u!=H`1q;S+a_Lh{lVK~ zzRwQPT{nhZBcO=!tZH?IahWH#x=wx=6X{dZ03i`dWO^}Xxlynpx)q7rmZCRvu=(&@lWkj%+vOE)2li3)T3aF|q5)5HkWPv#_dlgkR*4W&<_T?}A`rTijpIsgwADy3_ z-M#x_P}W4dRz;44GF4KH#-vDq8B%GpytR-(L?VL-WYW4c$(}UPOI!SxdU-qR{3vbr zY5{5luU6i%I@YEMm$Sv`bk;Z)lN%%@lSXx_NE+b*1W+IwZKWci2V=}5>4pJ7*!VQL zBiQD(^+*bHqTB#OXElr^X{EX<%1_9m4fZrz$hfPqlaPA_NofA`_^a=Ej!SD3;8 zC<*`*kU_NRnh+^07prCMo*p09jXOCxIXgSMxVShuIhjtUA3k{C>gD0VZk`!tnT!V3 z5P>ch!lDYc%Z*N#(ZrFua!Tu4Tf_GXulO#MB8gBsBZkh_0lVaLQs6Fdv16leMt-%n z&7_~ke1DFlYrDxoG_4pyu_Fdi`!5)E7~KmD6!gA$jag3 z;J{ri{L+DvL73S5OVywj;JrN^4u^MKy!jW|=i;3@BHN+Rm4Im=#VI zmlu|$%JM;xjmg-+Sg*pWS*%v8#;+P*dv-xIT7qIHCrcj!wIiwaoQ+Yp9Ge}5XcB^i zLYAz7Ac2{k6aZw}cpOVm)B3g*IU`&#a0T z)|e=3Rg}Qug8|HqHAKeREONz&5a{lmJ70bC&7c1CpU+NDA3S*Q!kxQhtx7yH686ig zXO~klxVyVU2pNC{8dOzLmg^!(HIkV`1Tm5pI_ld^l!#5frUD3{3ovuCa4`2gy_%h! zov)lDTdFA)tT2jb0tG=K2qG~8qB5Zp*+>*oQ2`=sQ(2NhNV}Xc&HW+ynGg^XiX{9> znA=I5W*xCtkx>Q22Vo`zMG&AY&43YEMHHLB4<8>LpUv{DRJ26akTsZwgXuqUfS`y< z!)o~AoqKQp^q)_f7= z3Jp;#>tkSmz)hjfF~>kqMO3j%b8Txc(amu|aw>=aY+tzM(IY^XNR2V`rXx+N>4+ce z^DQM#B52EZ5sZX*78FZ@6qM)7;oi93p}AgJ#*sC1V9oMSuQF$MiHyzaogLlV15^}l zE~a%8z>8mcT`V;O03k&{!$e9Dg|cc4XGBGTMP|yP7*tuAmsREq8wi%()xo=!N1edZ;{7%5WzpVxz%;4~AKQfZ|m(5f&wF>(&g>0D_{?*080Aaa%u__y7PP z07*naR4Ae|sEQstaE3tbf2dM~D!~wa5!=?4SMFpTGU~+b1WdrzdB>`1v~@ zefSX(F^3=g>GzZ1A-)(xWm!1q0;@_3FRVlTdi9oSmm0p!a953^bV3!uIPUIp2GI~I z^y&SgkUZ@-@6ztc`U2bEkI>m_+9K5@5r3mLA60r3eni=D=YpigZ`WNs@<;)IQBj0c zghZ`l1h08*$AjhWWKla&P{LaIXg(ubj)s$5aqj(sy=0gVDs%gm8Zuz45;@OJ1Inlf zXuyyVibc$n0P*Wh@%OK}s=*mRdw#18*UO&$Rf8YLqX!{WHi z#G~)}MvZK4(e5x2ZKFg1Qxp+Iy=U|r07u{v6gaaERf!A=3F}J18Y+tl^MZ|#X^bq< z7~$GCcy={AJ3e{!#k&I9G|j4BP3yT6zm$53PKYuxL@H?OCAZUX-N0@1Q;?T+L;VpzmnIpO7I$La=jq?JPfBEnFVinPF>r?d~wFu)@#~wgHU~zen77` z=$p?Z*NbsUa(R`t`W8u)HNghbGK5tmvV)RWiioHnsEatPWL|ycmHaRAAO7v%9vz+h>}Nln zOeXsWw|ofBHPfrBM@LVeUR(-b6T-#ir5O*0MPY147I!DR)>sj7&d=s^5y6hd7%c;C zxTw7|6%D8|VgU4FmR>(Tx_JN5$?0r0_mY*R1-zWjgA2j4^V~Gv`@qgC2cwDMr7?}x zQkG?fF=S9d1h5Wlq)`P9j0y;(*t#u5+XG>vEWzJC*#G12d>5@@VG(IdU;x0-+M|g8 zg9K0(U{>!|GRy%?r+5{GTJ+KJ#mRJO>_90~GSR@jD`B)3JVZo;s+vxxU;XOW{{8>> z@Biwr{_4@=Cl}`zS65SG%n!c*z3+YZyJen>C;_0TMH&=EC|td)xy9DEJf-4a!i~;q zv%2c-neljt43#eXqO-=0G#mopD8!7%S{qTduCzoyBhmi)!}=I`dJ6~ysE91sdtdme zjpi2U-fr)zf%G z{__6NfGPt<>{dloI1=WyY24#Sj~_ldessR@OvYvkWDrarDT_h`kh}YX|M~~t9b|}V z6zt=t=l{>!zXV%Qo}0m7I4-~W=AD-&g%ziYKmGZ8zk2X^cQV-D-*wJ4%jKf3m(Dj{ z7cPv)<}d&J2M6O_FSKgpum9#BpBx>rY7Cx_C{t`KD0ui^Y6@e{VP#P^(v8uY_m-XG~%n#2IP3Gh1WV*3fA~mhPlRWfg6EYHeLdQYCCC zL$ZdlC>1UX>%0d-AA%~{jp3l`7c~K(n-1m;BFZMra0BYF-dS!EY|2_St$I_E0}-Ld zvXtT(2%X_gFS#tjks&y1Gix(uVdj_&+|`%Q0kNL*uG18`C8h~(!+yAV%sL>}Q67$3JOy42Ug zb=N;m!6*?6u5U!!f~_@!O*JmPczhxXMuS{{IH3n-38JFHoS0AEyAW7{DrCl#Mc(=l zBS4B-gN_A=$(1C28ZoatnO{NY+`G;k6c&lpsi*+#Koh^~5ePwoZ|bH207J%FHNDgv zYT*|mLeZCAy!ZV-`ICS6$A7wi|9<2Ax4!kA@no`GtuCk2#cFAY$~+H^JAHb*lif2# zWzZne&d#2-dDArBh3RY-RBY_wkfik^SR-(dfURx-6+{rpD=a-fdVKNzM~|PJ&91!8 z9IsqhdheZg&T(L6MIZz+nJw}nx7OyF%`%`k!l;1KPZQs?QtbGPog!r;X|%XWqru?d;9zfecWA4zYQupQL^Pm=Xuzu| zs0Ks;4J2ctjEM5wBH5&?Lj)u;8DOqzRDuuST<*DYK6AmY8dSV+Bvo)3fAaKLv0x+{81>lqY z@%{JSJ887s8I?P`3?Z}Gm+tP|0(DFKZFlc$_|{rSxJh$Ql|p2Tw=SOo>p(f( z!cPea6^$_l2@nGN5I9;;ONYDzB4~hQ&b?gKRash-dB-4eO4?b5Vb?8gz*El{`L)b1 z*$@H{cD8AHJ(~i1rZg$=b<>-1{Yh>Z0#a*QLcMyhon^;Cz9g1j`<`XJdN+CeiUf+i zaLEqA>tcX$6Bg?-*#JPnz}mVxh3BMMfan$(e-j>5K-HU-em53^Th|=>YR=6&6g6^o zo{6p8tbi&6V2}XNAR#bzOCGHdH9mO9k55j2`{9${K5R~B zi$;PAT)V)cfN02CEQ->WnaQ)vSc_=LP{i^GNyu<=kU_@+!a+pBP>pcrOfl*oTXu@1`zGq2DVbOI935_ivSRBWmq_PO z*&5?vO6*9#g)P4(5nuZ57@Z(|jgoHKrEZ=Ysi$I*#(M%3RS%jI+7(tHqd_qn5F;q_ zVP2$fJlQ6V>xQ-^{Gs7BSO zQt-J8gU089ZD4T?I1lU%bFP$Io8`s;lBhagFMM!5gwQx%t(wLK&nhX94p}1Ho^~U% zJ_R>7KwRryJK_oTP8bCg#7OrsM9w=BwgMJeqGu)AXonl=SA<{zY(Yga_{;sTeDlk9 z|MwsMkDMR-Db;Km7Qgo2I6e z@u{7!WeQCM;5E-Z^21gk@I>a8|bHP<3hTmTS2?s=C8cQez2xktp!1lTn#C2>G3iOjo1 zxSN}O-|s6wmA|4%&!+wbArSzgfVt2ttQAHz*ye^c?7A=A?68hbXgVhzkq3naF%+qr zl$K4OAZ#Rq!?0slhR28|_FDsBQceO9Hcdku#H>rX(8fl!|HeBsnLmmkw@tfBY9i&1 z8Yhu02;x-?2hFI0O}FNaC}U}JE| zDlaG}8lv3YkQB#wgQ!go}EFu6o zYsx9-oKo)lPF0KK5lPF5$IOgN*9rh35XYvO&*$x|jUggo6XN#v7DvXKWM?H3r((FA zK|mY=#}F|_41t+A1jZ6;Xj=L>PTTCd&dm1r_g}kv_we|5z3vW=j=HYf-PzgM-Mu>B ze(>PI-PdmK?rg7D>#`0J&9=5*fB42XkDn~p-P7mKk4{eR@9vmcP8k4@cxYBlO#upI zN(OjveD?82pM3q~`HQo>NZXn%cdA(;QiDLufdhxgAy#JW zI-Q<(>lJOy!}groMguFM8i>2c0Ak%U&5X@BtM!ViEJmtrpIL;na!M=;Ijdy%R>T+@ z83%j@(JH|z_8mXxkSOe0d z#|O_(PJ2Vbz(5dqXKQwCXLe&5z%G{gbc0I9f=`K?VAp z*OC$C&;IyFH?Fj3NezGV+Ydke^ixm<<%$2;RF#V6^#YWk4#BG^h1_WZ3M#o1FkGvo z)L-4*xwgBDB3RM%1c*fJDN%33Fk#c$RH{KXkD+yl8R}G z_%ktI#Y{Z5Nz^+VSw#BelF1E9du`AIKvM1ceksDsrAy-jGaoTC61i9#0iB}BAq4+l zY?{!vo=_e5cqa@Y5%?{iLl->1}dT}o+dd;9)_``2&Y%2{HJ+gn@n*=#nO z1!4kx@#5g{@UR@#h(h3|Y3@CE{mMrlA0Ho|o}Pd8$8Rdg}_&tBs<=G9WNTM!=lwX#oxV01AL8Ds>!#K$J0Lk=(LMK0SVMu)3Y*%m8AL zvm73u_9-LYSx?3$5qvYD>@!48V7;hF&N+jbGnon^+pNjTQfOVEMqLVE4!DbMs^y3-yA}Y^)aR75 z*_uqh#$nrhtL{YO81>(;D^1`lp*|GPhX|M~I3(MpUWa6mLBnNxiK-8Z)a8NrK1zv@@F zuI?hhz3cmLzjo!bljA^vW3#if`}sFdzr4St?guadd~$g7vw!%-x)W8LBxF_?xS1-@#k9>D6oKY~)23-+gaqV`=P{giICTq#Z4{x3_wx zb=RwrmXRau;fetjVy0p_iA_cGXBXMpCyzO z{NzMqz)%U-Ej!mnEnd=!rzP3tK&PQ4ItC=MGBRdn3cfcHd7lftf?_0ZNHK>H0yBjW zLWrS_E;3*)l^7uQs?ui>RgsiZw_K*a%gN;(Swu8T%1N>)00PbDTSS2a#}I+J&ng5; z5{a0Q35l3Oz!11;U%Pwn_17PsoiA4F?suPm@#b4^?eFbV41IF$cm{xM)+aeRJ3n7_ z+uJ*4)-4v#pFDl`_(`|!a~4fX*3YSlp^X%o88M?G84|E%=l7rjx@DUlCDk zA|ZhR5w~p{V7StdxC-93r#VzD+D&L@Vq87()!q9AZQwQ&SZ)r2xy6 zJ4>Z3lW??LE3p_VkQ&MOQTvNSMYGxBx!@ALaI~4INEHmT!fDDYp-m9OD6}Znipk-3 zEH%nG6DNa$@n%s2t5}PTiJJ|)WWyRGG%RK1;Duwv>U3$IL|q{0WUbZ$S*}#GmlRc( zcgR61=mY0o^7&$sGq!Cdny@m>TMk2w}D{ z9r%Nca|Zt(B51|Xs6lQKn32$|U*;!^lgCeAoSdBhumAQZ^I0IoH}39#@4>Z?zF9)M z42M<0B7@aeNfmH=pN!~gD2-@mm#LrFb^zx&lcfARRJ%Lw9gDK9u> z90=A8`=XBn5y1k}ojZ3PJb19Tztc8tjKTNZ$Q0@Uoa^4_Lfm2|CUy4CWNI{I-uss4 zHe{;TqagMLELx+KMxZ9<=?;x3gvO-Bm}#07lVSi6qmb>gE~q?+!PYr+TqX@08{l-4 zB1onegd4Vpf@*TB`2vG#(?-}!HSaJP4jKTe0wF}Awr#eywnSvPSc*uWMGOE)0Y$w; z4c=IDFSDwui0h7!h&kpiXH6=L7@Mt~z4P^poU}MHr;_}sI=*&AE;6bL30$?z%aE-q znfwXTzzD@jaVC=+4gqQE(<+98;xDsT8SzF@J-QlN>R6AgWO4fpV9Z#gGO;QeOD9@; z#lU`rjf*V|e5RK;vB}vwu4gGD;c-(zQvpvaDMyIvzE;Vgie~N#t}?VqfrXP5cGx9K zjZZWQVZy5XDC57%TlAm3PV$aa7RfpFU0;5ivwKTRK)O4`)Ko-L#m>R-`q)@DyQtaf zgDxIE1Y{UN=Y9oprKA9`#TYp>?#AG9fTE@eP17(@V2;t@ArTQn2+YhORMZIg9J9|! zB(K-&^?Kc{yFPV&*GZjfnif}5$tv*5jRJEtLP4SsfmsQmZF$x-{tf+m5rr6cIlT4u zyI+0t<2(f9~*aRX5!fcvT&W6MR0adKes>sJ`Hmd29_Wl4|3T%IA|7o*O8>1L6%ido~lNmnKBfWFZ zF$BqE8JkEZBq_!|H%&Wd-r+{6$$_+m4pJ|wDY^KGn3#QCWHf(V!ZLS|A2A zWDB!S(?_2^{?XlQyKleF2)ix4^Tyq;UwmWp9h%SjyzV=A>&-j++iehC^!DMG&p&(e z?5*!Dc5m(NAiQz=*7fZ#4*OGW0{74+{qpl~es}BojURn4tKGSA^-tgb!Ds)+->iiQ z?8k3?|A%khB2@+a;>olB@^?S)IsuJfWCa&8j>V=)$2Jh%2b#GVQf%5S4s8}>0Yf7K zBI?C}T&`O7K7^8pi7;6D-2taXLytHCaXBzdVF=15BQhH4%H_h~$*F(nt9f2lNf5G9 z;3*;-m|2J^k7LLULm2w)JP`#~@k$9Y8Aif5sX29UJ42~cN*KXJJzmdR9#!X>`e#>^YdsPG4ijD}7cQ^?nF|1syw!sRZEmALYglu~ z!0bB8w9%!Agho&ms-{|+Ob(S)%LPV~Q|eQnvgE#gXciI4^+>tDC@%m2AOJ~3K~yk` zo&5Dt{{rfV`XQFZor!4G>ASK1;oxiZ7ti~+L_`GM6=LSVOpHXt(W|CF-l__*X<`#2 zGX?)VW+pCHP=8!WbIz&H>vdYM*L~lolopFc*L6~)@L5f!dm*|zk)16{)whU#%m^XG z5StJg$y7ze3o;=}ITOJBhp+#S|LK4FZ$JClix)5c>6gFQ+1q{Nt+$Yw6w_*Ta&q$R z^B3PdJvd)WJKs7!IB6+r2*-y;nM;W+PIh zq+}`{vtagdKrb`W~-+7GZD9tc}Pe^5E?iOpx_`*EKVH) z^SocZU@W4lg(#JjmFYpTQ7crJ*0eF@E3fLNB9{EydUv7jdF9_x5z|*Gq)j1BQ+*e{ zbUrxPh>7ZoRND9iRklCq#SJDKy>a%}!sfA={Mxu&2MY76kBgLo|*S-AmvxA2Z-?+{i0k3cG&%!~X0F2#w z71+N2;7$XI1doqSKmPXUsKZB3Pk(Uh3L5NfZT*`EcmML2zg?_)HI~I9t-D|R`jdzE z?%ugNpCSCwdk=s8*{6T?$>-O1=Kuar-n`MWrT$FhuYUH67sqR&IZ{LBiR=N)Ht0E4 zQhhJj#_OU=MfmN_YVYir&FUM&~PX}p4)f6Es)-Ot7vx(CQ{6h~W}Neg zH6F^*T1b_bc<6&+JxvbNK`h3dQn^$=BaVhOKdPax0agtcPAo)k#ZcJ>sWxf`w5irl zE)BAQKxwsErU+CrPpa}v0RWBA5S553RT0WvL(|S2dB0&`71pBB>A0>%S8;Me`S7Mx zpK{8QQtne;ue+}6iib?gWXD9*Mm@_=85L)im8%Y6B4^nMo3>$$N%hGVXOBNQLS|xO zW{ypC4ZF9dLa5MR7h9FC5xa$sz)-XFIZsq#k|j&dNzTs~{kreF-1XjmOF3oN`RwhCu93IK&u3 zj2uIZfddmWA{x>v!`EMY{tT4C0ve-%iib#F2Ljgb`bC z+fJKh6JCJJ`@5`VM2IgP5l%ENH2G?HxrOu6zSm1J!e*AUs+eR9LVdOnEU^%A2#Gjy zU?wCl%uD2ZktmE<0zmb~lPQ{s8knJ|0*F}x>qS!XDZGiGf5%))DzULr)k*(lER`lA zjhBr+>0jTinryMt;i4ENLFpABDJUTl1`F7O3E;Dn^YfIiZUt1?-`<{ukkl1v>v!L} zcXMwZK@I4O$4`!zy~XyE-#`B2H(#6YHWBHE5AXltHy=JZcyL)T@Bs0}^wF>A3*QQQ(lbsWgxN(}@HRD4K&5*sEA zzGgQB#qdn*`mLehBSKBw|(9~+(P?K=2 zE(hZw!%Di-aG<%+be;sg+fZ5!U_1pZ*DN8nA#81J#TZlSkB(0Je(j2ld7LBSYPHHa zZ*6UxN#Awz*(?S=KR=h$Z_Q>Y<<-e?jE$OxrdgbxoSdGS!Pf51{?5+9;bFI4zj*%a z?!9|^+uP5dy#NFBgLkcR5D-AfawNLBe`RlHn+Uuv&Z1`4_dTSuJ2&>T$m#QE-MRzM zq@#k6)k0aek%>A~Xr-DetK=}M_dR21AeQm4AK<5f>7G4V*s4QMl}cIVm(^fYEQeNc z(|e)XdbS86*Q-4sGY1-dsaPSdlM=4%qcB9hjU*l%y9rgsI#H^ZCYKZ;h?!chBRSt+ zOUh=EFVqXdiDlydOL;0q_XgFv?{l^+nnhicKJ*rf(AR)!A@vfzEBdKjCu`OP7;KR? z8xGp9f(9i5BJq?P{~#h4U^=zI*Mw3{l5YzBR1&1pWb`qgy8&~~DY=8u`mWb3DY?X2 z%GE(weG!GLRn`ta+Qry3O$af>HpX@~n>B6IG>sQ_fddCd!b*H`b111`=iFVPu~qV5xV@jlo6#^@!$KLuz#uK&RRh z5&IdpM1_z7xEtVND{e!|xuH^+vPKb*$Fy`9!nQB>_NspC0woa#IoGSotl7g<3}%%X#O>Hz)P-!l2w(3$bd`%lz^B~EhPX0TXtPm0cyzdY}QhM zF0Hz?Fs$EwaBG*4O^+Anj~;*1G;L;ne0=oJUp=|;?!#?^>svcNe)Hki|M07&igqGN zlG-mm{NkPOzq#|~)fVBs2Y3FrfBUCzyng>mBt~3z`LBQW%NM7aG;%?9$b~07yr-`c z=V3WP(Uhm?9Vq}H0wxMoHdVabLL%WAPR;cfNMel3p_DvIL1rM33J5!PFtORft5sUcix$eyP1td3vX5H zq_(Q0A)Ux&3T(Ze@u&Dfq1SGlL}O3 z6<6Aq70yDDPfW5P3muaxVw3Qa@SHBP;D=6D`I$<&V?#g8swdRTuz_(|3VClfjrx)@ z7ns1x9J@ms2`V<&980jPyU(T@U}>F~qHbtkZS>4ti6dESH6=NDrz+E8VM; z+&P!Jltl__ePW(~n&gP1l&VfEYMT+w1l82Ut$`C^+~g31qv72fZ3SKFgHNA;hKM0x z;NjPXY{(e=jO6P55*uIUo27irDJQ=aQ!YTxl#&QYnOpiSh$h-Euh0pQh)Yg$jIn8( z7@KxBi=hdz;TXMZ#moT^4NwiT8bW98QrD{W0TUCEb+=wD7bhp@SFhcA`t8BzUwr-1 z$DhX-nx>u4=S|bJ%`ApC#n1UmuvM}wCIU$`i}xGL zP<-$_5e^!6D2yr>OqluziAD~gn86IW1Te%ezWL_K!GY+0GV8mu4ee&dq3Yf@*cUsPPeV@Pm_Bo+$Z*O1Oze2z#M~ma*6GYqF+hGcf zaO=kP7-opPT&UY8?E6gQeKm0AT_PELbluoQpA|3_F5K!D_jIZ@Ohf(18_T^mpqt$v1~GAc7- z9LS~swd2Y(G~$XTP;t6q`g0LWDXU6$$yAng*QGx7eM(7FFWGxmDW|?qDSIM{_rdDg zs28l?GzuvZ@FmX5+8ywFn=5P`2Z2A;TB_XEHRrPwiHtE&(NGb22g`r$FGvXtwb9q8 zl2vl@si2ycywTC;SfpiubrR1wG4>9@g>HdC3d9^@46$jNHpbY*HpYfH_=EHVqU(MH z#izHusfbkIS5nc`CD(W@*UQtzdCqqA%8i`t{QO)^i6Q_8ZewhlI71*6QdUKLI=mx7tda!t)4TCnlXvZ5S-oA~5l0IE7xq6gjL?8kex;0J1OisIq zk=xj`Z4;URNUM}3X=goU3Qf}jZ8g+3F){=MK>`aqTRTnDrX-O$5QV^iZlrO%PMsqJ zcD-9*qRHWhrpSqbX@>+vNhJ4uO6ln2;P`YU7>pW2YManBOjt1(^{uYqP=gP;c%ux} zL~6>&=;o`UcZ8x51I0?SP@TY;v78hNZrAU0@`+)|1%}#B8)I<1v_N}R?x)%1Hq7O{ zb2Har+Sl3WU|o(*AI6IpOoa$QNDfj`0RsgPV-n5&s2F%SnLt5H7m#v++ae7cS*cD` z4M5bAl~=yhrZPc9*WvV7C|xM943O}pocarH!3%cOe^ojpPDFm5RzPB6W~9ZVwMJA> z0CsT#5vlb_`qZz9<-PAc*bl_2iu1dflC#ANPIV%tC1V1^}qSi+LM0lB&cQR5LR*P2|9VXn%iyy7I| zx3?FI#cH*RO&dZGm9~vpga~77rNHv#@aW+7?bjCPyNk1P*GcKnZLJbk1Y`rvnLrWH zB&kuUaSUS!H?Ln$0;aIPzuPqQ=+T$6S$y-&*LQb!7ON!yUcGW-e|PJ%ZoOWwMx#Ti z1CHgW3VQeOv;%HpX0oBoa9t&oN?T+AjR)8K;i8r>5@zY7yRh;F?hxa zGcqzcq>Yda6%5ow1W}0$nFlWNR=jYZjm$jqur!BOZ~`r|Rgrj4<|5P?_#L6tF6 z7Lioflv1Rrnn#nSl%$uGQkVL!U$0iHuIswuwbYdItexM!_1e`deQ_otGBW^~y79&> zw3f|l(2B4{boIH8^xC3WW~jld;}{Up^=*z7$DvRk_0wLu0hk{by|?coKn5mc;&R;d zaw^8yGz}3Aziwk}+a|WnqEC;0|Fr;KyMDcCnwWVe8GyKn4TsnSR9G$L*^{Ts)6;gg zLq?|7r}gQ{@$K8Uw|4h{Q4GaQ02L@O1uURZxOj=#M30FI>c)bkvg*^*=Pw>TdK`DJ z&v*BmrrEZZV?a>GvcQTtS=;=4g)k}&NLxO9Oo)#YV6g8D3pEuZ zivn=1ZOa6+Lfvb1X2nZW>n@nSMT0D)*u%#PY?6MqDTyClEgS4#9JXOCpG_MQ8FB}*( zRApzj8PsM77b4|0$}g;T>)J_EAn(Iz*$c#=ce|AvSKZQ(2?eZ~&6=ihxyjMV*}>`Q zBFn>j*WbEvea9>)eg1s;^G}{_ZSVc>|I2^6GWXm**=-vYV1S*#fA-GXfB)-`79P@I z!V2rG|Igok@W$)6=GW!{6ij=e|N6^MKl}C!Ahc@a4V8M}#mkdW+(<^6Mg@%3!L-A- zv7?~^T_#Mzs7uD85+Prm3_(z(1P-|Z1j}i{0SKr-;KsfBTH_$FF#y4l;DE%)fe8bJ z0POJ?7`Er_hAVh_{xBFqy~kO;S)C~iqvy#sQrInHc)|z}8m?+XHB_>i;V@j5hzQKw z&Svdwmb09koTcO|yZY>=0t-s7Mntx@=Bw3mwOX}pn^IaV&Y4hEpFMl#u7Q-&@$qrR z!eStjlnH5fXMTRZDA%{4nJv#2-QMcPjcd!rxrqSMBmmeZ4uDd&kfBIUeKxc{B{l21 z?yE;%o}I6DcXr=;>&?C0?Z~jRJ>T2iIyyRd^5n6Iy#B@;yZigQyYqv?gTBw+wghB! z<>kwGFfX0l`%Z2+QLL5C;GXWQvIxi7XJg{>&v!WvJzy=Rrl~L|+&qn#*U`hPImJ ztOGR3(+mBX`ky2zWu(6Xp<>%jRs1O`nn4!GB7>*YEio}h&zYe@ScpVS!L5i9kqk%x zEvu+uHo}X!pF=U1y4<^HKBYdT^?JQpt@^&tIeXramRA{=0@K*S9PZo!e^k6GL*1l+ zrk7DaKI&#-LS`6pnaV(x3WCF?H8A4Tt_)l@JRk#RB%soU^+q0}6E8SMszy!6Q8Z1{ z&Ss%)UMvnCef_lE+70vlRsyb5vlal_+6jh16qoDtyDuL7`h#CJVHVLW_X>1)a`=m1 z{`~#-e{|>GYkNC;T3MQ6N{R|n%SyV;G8)B0fTEDHbxD?8|KjlYt0zz8+1b_Wx31s3 zP6Su?c9=s@0aZaI1DQ^t%*Zw}aO!JMMYgV+`N*}WHC_NEZ_L38W~Kw^WOEXTBj&66 zl}a^&L};RyPz@W0x{F$(%MFQdsj`hPLK9$wMyE3u5P=uzpQZkX`8HwrA6^!Zd}TJs?QDuDsJZHTRe z8K|R}@87$%y%iWm#LmtaC#!V^eCNU4>szy6W(XgD`ul_P{--~E_rdM0JpxoQi%{^j z7zp3Icl-Mf?!I{RwLn7#1eDD_`}*4t{`t$hfAOxOBIt{QlfVD@Z_ayV2vj5E2hXZr zQe4@lq;KPOtL4;2dh*47Azd)Fj!rM%6AT0mRmtn5`id&DV(RyV zqp78w%q)u2y&%Z_;VmWVKsK%!EDcN{D8Z3v^elW1GE%=Pd4R6efDBff)OE>}KVOXdz z(sB)qki1RGmVsBb4()7oH7LV9#1i!VTf^PQx$PiVC2G^W8#UZZLFgPh`=P<2*hIq)xfgp zST&B2t>GD|=A3N^Wp@Pt4#ogb)mpK6SKk4g0U3yjEir@;o7lE(;NZ>#0|FwqqxfJ) zM4?QA)EUGjNU=ViN?H{a%SpN}4O2q54h)7UZ&TUyC{;9MSdWaw!Z&zc{Qa4=3A!s~IuUL>Lt{W6emy+AJdcLlTnE_fISsin*$!KmCc!2(vzB6DaUwh$YL46%V` zX0cgj{rcI9{e8T0Ge7$3^T*#jdF}SiKmN%N_xAP}Z6)dRN00vQAAfo0{)2~azV*o` zzdJoYLxiKF!#<^hgTv>~pI_VCQJnapO$Q>^r2=aMeCJ+`q?)oke}3?r-+uV%@4no= z^4hACrfv3i=k?-K7{jkN^zx`$uXcX~G)SHt&|zamg=RoxQ@daNnouP~^wJ{0y9R`4 zQ0_QyP~pUibU|h`j{n^E1T?JJ(@N;2W!98#HMj^T^ThA^R~N3X3eSU=Qn)6PaD*xA z;ZnDLvvKr?R#D$Iy2Do#qlm96uwFKkn3i8S6y8JxB6;%Z3Lpp>k(kthP5=mu08s={ z-+KK{i$H*#!i&>I7Q3>&_0FApJBY#b$;tAw-+#5gbLHXdcLlJ|8hoRnI`cHx*`58- zkAC>k)5A=2%-llkCFk5de)3f0U1Kw_gTvz&Cue|xhys=B!t25d?W-ZO=@qXSs_!Xy zv6G;Kq~JSYV;=ulctZea>g*c-+e~IC#fXCgGaC^ggWm%-ZU_Dd*q!o(7)x8uPys|U zvX8J)5W}U@tzE#}4P5oY?%NmzZWLG-{z*+2HJcQD!>Z&dVZ(D*mDy~zwY9TcE>BKR zQ}%s*2uv6dBXyZqG=tS@y;v?)HO8hQiSg`gL5R!|k&lm0>pU7`Y;#@``zPzs@$q`S z7E!g~ux)2&tD~dS{rxLv=Zkfh#9TdtzDK(MJfJj;A_j;l>1x%h+4i=mp#pckEZ1qh z&d4F>wC+-$MHHHLzPEoh=bXh34^N-JI9{%EN)CE(x}a``QcN+>8>G)^WKGF}t_!6P zfoK9mE2`Eiz_P09o+{+2+9C{~PgzAu>ve?N!eCB?YCiNT#QzwOvO*`Cb5~i{YAT{) zYNgt6M$eFyVXrqp}ygCeuf{M@!5LMX#M z4o%sV15ptpV_~M2xSxqSY`WtNITwbL1)_E*taRE$MROG+j*=GzP$H{GfA8}SKfuFE z)cFizszihw+NOz36Pl)N+oowkjIn6~Ga4j+Su4+CL?alOzzFqKQ!x>(nzoX!n3H6W z^++k_EaIIu9h-tR+kR8qQ7u?FFi3{WZ`=#jHhK?J?S%oT;pCq4`MR4}wFZj#wdutg zO|rd}LD{9HWga3NCB~*{m=!{{m@P(V5;h6iOl`&{K@&sM0k4%~cf3g1;^}g|Tz6l7 z{q=7@`0dHV`}4@pzkL=7){EsgPoH9Fe)N-{-nf19=yY}X$;Ssrho3+CeT;30ttfQ8 z7{MAdQy@}vzF?ujT@;6m(aCD+{(s;;={JwR{r1IC2HxMlB5DT*M^~?1S#=qiL!r+X zT;-q&QnRd^{n`O)V3mc8HmI~GgOz$-!*QVi9UD`Fjbdy7R4jWvkHH8vDJu94 zst6y6F0v~&qjIJtk;??@ak|vpImmefk{S0$ZSSg{^HfNK=}XwAOJ~3K~#_b&G+wKYt0n&te20! zeySore&gYTE8DFqfqwPPFC`?@h{iC10dv&X2g&(~A@OvM8 ze3&T4ofexerPFTJ%vxYj1TrwN-Q7KFIUqKMV313gUAanz(=~v(JYvX^D&4(ORG5Me z2H01{4ADz9UN}rtd8nOy??R#}8>Eh>+z&CdHE__pjuglWY4ftxXIg%dkpVJmVLV}& ziU@U3xewCyn)fp>OxkB?7JPfyhhiOf)B z5Lr(Ptjc);lq~0qWlnwIfJia6v)R_s(NSc+di8qOb?4{jF~+OcuAiTsA0MBz?flBs ztKU9*c6N5UwX@y#B3WyoL3v)!zJ2lVjR!lsdxyv0i26|sZ6MH~GTJ=DIs+$Lc5-&U z64m*9t_G^qXH&qW=6!{%uvo79-j0q=fAir7tJPW*)M(kuy3?GMnd{9$)7f7M@f}~i z@=4A{ANuD8n?c$xC`&Rdqf9oK#s~fNW=pmp9ESp!OY?xtF^qLzH3NYXaHwJ;c~IkJ zwO&Y zT_{*6?^HSB-+Od}xyN67@nD=0EKnI!A77ne<= zX3VJA|I0Ec1=d!_xWJ4YjhSLFMBs>_1&)d#TL59pY#0OxL@8y&`OO=5k57-+T~@;o zTcVg1mR)KH)%ecc2iv>*i^Y2J=t+nTB7gq*qpp+JA3l8J&9`H_eR8(ip0$XKkR5q} z24saDT_5(~0z(5&lCW%+6_#Chcy#*o>5FI24wWKO*xuVeU#`FY=364(X-dLgfievP z!mi{{&{9(hMdUvbY&mcyahRDoif|^zo$w$_v!^k-KUy52e;W48s1ZV4rCj@X~VY z(!jBPCceCuns%_JuO5rA8JiIrdwM4tX!4gmqY>KPZ2m_-`r&{4<9Dvi7)*re(bI#E zzI?jVw(o!c!POa&>XTR&#iJ<@8N1uJ+mo1V)05GJqef8>}{O|z)T-lqw_vYQd z{@^psCcNcf>FiuiCqyF6x3_H;8{%0BJ*NvMhOsH*SogBg7iEW^(Q`H((*-u#t}=qZ z2jcohRSnGP2K@ z*&-#;GMp|?{(QAGwtM&P5rxHSsYa7`)Bpqlld>WkP!<#*BUTKelmx_hxlXfHCuUjg z?0mgkKYs1bovSylzW>9YE>}wh>U#O;(?{!W5n~v-AH!Y^mwKne$~A>f!3e%0pIjA1 zHW8D%6o3ek7$y#vK9A7^kyELT)qp)4$q*9s~_uBcH>aR23FiHm@&}A{A43J5Y0>-mQp>jYzAh|g)X@&1vD>O zN->qGwm_)_C81Gh+9t+%8@FfkWkhO~+y$0A#=bNXWqzX^sG6iiAOxI0mDj*eFJ$sOViSMx&HWO^Gc5T)S~q zK%P8#dUATYv$J#O?)^8v_s;gbb@&?)5=S65q^n_O2G3s{UB7vGkfp0A(1I9{#Od}nJmn_s(evrl?(@XYY( zotrl$CnDk)2hLo{oyC$?rm6-)gfYQ!}lXNPE5hmt&vO2JcOp%wXw+W>v32ShCu3x>YW8@HU=hL^Hx z400iVOrL|P4p^+gmZIhz2D9vhib=G(PDKmoY{Eh3NL`oC&sQlWHB+T=(e_M~8W62j z73LYfAvW{*?BL+A>k=Z0=*=59&rZ$`4-dDtwy)o~d2)PwaB|c(&1^P1JUl%)IX^gh zv9q&dfQ$2G7FCZotH~$;`PsKGu3f)*cukx?CTft=CCbS+k-d z_5w#|>wdLZty7c zg1B@Ir<20rFv?69{Z)nMNJeh91{HvWm8vyV19;IuSI`3+YWkXFXJA=0WyvBbNzO@X ziCuj1F~rz#j3Jadrb3|rKtaF0Lgfeeq6hVI5HGxac!-L1#5AqHhj#H)`ev7{+K9kR zHR~@Fif#zR)dv_nGJyxHZAsWgMq>XKd9e2l$s`pHq&5X;8-h2NM;QKK+;oMOYOSV3 zMDqyZ#)594GEpM~140{9MavRO=Ia3rwuM(R*L zZIEm>eO0C8vZSN-Wz<_440GPe`z?f?8HfeMfQDdz#M*zxDe4NZj{*%J%uA z$6tN@RDmjb#|TEK%P3C5jsMCnhcpBXUGVKyvAJ%@o@^ZLO?e815VhHMy3laC%v`v9 zu$=rBzgsFkq7HC#ba=8$zJ1t!+f; zy3TL)rfHr(e=bSQpzr(BlT#4|gSMUR?ChRDeVWix%3E98^X={RTKd#ywVZ9WT8W7B zy;iIBqes90{`cSB+1WWbI(4i7`h^LgYRAWC|M>F{O!CR`$vTOr<@{fN`PXRa{NyyH z)MxoW|MG8$=dq!+VW(b5xnP+n}d+NMN`3{e8Z^*X{uO;pvS zsz(fc@ijwL6Mru&*{hB^)X58`=IWsfhUTiE_U>Fwnc>0Kz#N=nj$Fc^2dw3wEc8yY zpsC70=^qMro21zKe`*sCPa%VjwN+IGmeYrcnh1ap7!h!A`DCbP31nuN%mhmt9CY9k z1tKm_j1pkiXI=GTmX*XnHJA~g61u?7{lrpH7t-~8PPuaKCFh(|mfT}X=J9EsX6*&5 zbAzlvVJ}W6YFWM!z&;d0RH`nW=5$)MQ6Laep(?=OVjFKn_P#Z@+Wp>QxRgX7yAe5FZG8mb|2@M0F zs%En+)^)JzRSml?pD$O3N2lk@bxOkA?Cf6Q*ciZau}r<3FILOtYT2drdVP3!NJLw+ zwvBPVHJ{C9JM$fXc0|-Rd~J98>i$l^Ja1rUD>6q(w~h`^*9sZNCJ@?pA*qI5&gL;@ zLsL67>W)J<+c4I+Wqar>4PvipS#!B~x-1~MR1dw}ulJI#2Adb`e~;e$a#8giwb4a) z+spp&GJyV7-(9UpI4(a1y)@9+Y^0%#a33=;!Jy27s1OKnJKDBa1jRd2;NM9tXZz;a z(O>=TKYsk^DG0rJ@3n^yUjqU~d~ve==!12^PtxWTC71a)GlD@&FrRNpKn94Fz10rZ>gR&ort>35C{!`ivm}(nRZ?7x_s;Q z?I%y3Yu9hwxRFwScyPF0t!M50jfW4< z&d<)y&YPxr?X}kyi}PpCo?W|k4H-EyA|4zZnrYLtcW>QJNj~}HlPpq@NovQ(rza<8 z_wV0du0CI{`*PMoFhmhaIX`{+3_KG936c6f_uZO67$9;WgT>joC+jgsga8U>$4hYj zJw+f2Ax<%1U^;O6aYF%9nnC6sgED+TL=FPTfRZhMgy>-dHPNpC`Ji@29M%sdsms(rhXb*y zsfh}f{DHz<_um%8NYSc?LU{DRznbR*h=lA>Qd*=uRsUa40zP<9KrLfG(2_4fQUy?! zGMGxKsf=L2jas?O!59W*;oyD(UcB1uF|YroahvWzdiNTJm+pl6T{UAB>Ta!x5(&MX2dS|wIqK$Tsy3_;7{ z>vwg{`5J2G$#PcKvcg)l&F-qdKDz0F#eoB9qlQxJ+dqVwV545g8?b9m4vd%}~h7%!oM0kNfxiKJPLs`^meMCzxmC zomoV)Jj=Xq?F+3l13TwGGZ#7P`Vw{~lZ)!CqZ>uxriu1mn@$qyr`S8OJN2AfOC>-H!{ySif)n!=`3}-{17Z$HA z8dH*4aw1&ICcoaixt4g-mvM+}bxnxSOJuMSE?rB}>DlqN-Jo0fGJR>(HFEd$;_of# zF*nIIgg4~RZ_i!1t#ZOYQO$l^_v@A_>K)WBxG{#jR++(7#nzQFv^}yYQfk|(uob$s^x)#=yYJU^eW1d3ecqxard^_Od|m4ExkZ%-~R z6`ZhwMpf>)Sx8WXSdsqt_4Cg@eZrH01D);f-#@&2e7eb~V5f>SUvAKgGR!x%f;w^; zQI6E+KW;;`lF~y#9bqCkrT4DewFOCS+M>9{FHmQ0Vvq!_fDSLR9gb~d#Z|T`@X7>= z=)`P;SLfY5wRcP5GvrTN5M5F_c36`R;bj0@RBZh$z8HiNa9@PKayU**a2AOngcw4% zI=GZW?2Go$Z&Adyc$uLekpM->$}AA&w9B=bC$_n25^Hn1D^yr`t11(#q(xGH3Pn@K zhiYmjdqve`3--tyT|P_DUUlOC~Y>KH}Tvegv~m1Z1AMY6bAB6Qy5 zVjcRo>z5=qvM{12@`w;s86b$VBB%odk;pN|rm;R1#E2n46SNM}G_h&CT`B7kqCZkgQh_XC)&SgbjI*U9GDR3fyaUa1 zDe~FQq+Bf}1R|YGM}nx3GHzbJc)40GpFDp2+2^0_9UKTi)l@)qad9CEb!4a%K~?f7 zR7a?zRE>J?a)*u(k&|0qv0|Ms=FgtJe0}`-VsW`#tyloE{K-cjKY0IPR^;Q^Y;SKb z%k#|n&1U`EFTVKhyYJ?U`N6@#!QTF8ILNZ>T7F0j0VRwz&T@*QTo@2BL=F;}K|0q# zD~D3OLifB`D|CYhJAFCl+lQ=E%Uq47x#85i5&r_Wip}4_c7IDLc6$fwdbjC@`03Wv zzuU)clG2H;akjcP|1HH?Pjhzjx7;*WzN5gxxAeE<2Bf?H6}A4c7E!5!N`L?Nzk2#> z@lY~)CMQIIUI2iR6hUadE-zL~Wz5Jq8aPBE`TDDGULT)j8geWbs}&MD%0Zn9b_q)6-R5iAn^3Z=Nsz=l}J1q#;DUtSCnIh@=1@_FVd; z#YzVzYEMFTdO|`1AtIl7?3lyooHf&^^S&nomP1rbz)H1FL&xH6!zq0{g)Mj<+S|fkEh#5t3_3%6DO-FVl`+K zHgW70GTZX3Zn@plzzVe$j$A9SS}fj{FJ<@AlP8Z9;p?YQ>$(=PkZdyp8|9fosK=9H zXF93Nb(Uq9mzTrgFw3&e;!6Z|U3ur0%jIY^vUYk^R#~3K7^l-I5|vdYBCB#EjCnDr z>M$NpPft%n6Iry0!R{#{`s9;OW;;8-{nhW*RT)A+=S)45giR@Cfk2fM5P_5n2p;3X z-t_*_-Fxrd8x2R~NJZ^H(bUc9#p3zvvzMpmn_BFf>gQbEii&CVO$d(QnyaTPc2ji= zUF2&Bft3{m(b|h*nF)F34RY-ey>kx9IRmgeK(*{PLPF+k!9Xd+l%ntXE~4qY^`ddfteLl zD2hZ80cC}zX-raXI=|FPLJ)}LD0AL$qIsSdMPZX9%P8@V2p}Ug?s3Y=mE>b*j=fmU z*24}-Y1r)t5hP;Y;fSbeRfGa{Zrq+~xHEfUuYVvxgaKHA0ThUtV`wCDtYfTequ*DX zs;L{x*$FXnGHfPLhKk%ernv&MzvfZ8nmT8>B3=Kf-{QcYf2BjryH@vR-U4kCMrqqA zNf_8ppPbm!{Z2wp*X+nSa)!IY_QjoZlzGcoG#DN^OS?}3JkzC0o8dzQnIrEY&wS>H zW321CDmRz&`T6PTU^F^<{|Py-m?1hDsH)1PDlCs2fIfHv!lDS;bf>T|LW`4 zzxv{IFc>+QPs&b|1KVoq<zhYDtUt zMpluI$^k?vpN=}K1a+*uL_0**Ny^Lw z3{+%(=qb0^N4wFqBH(uYX$`@G=n|aDXrJAt(nAxq&1}N9YXs)fLFjl2U3ifVg)%Skz{lRc}c5wl1 z(0aeXQjG!wAi7+w#>3%cGV$Io77OqF(b19lrJj87!Fs)BRp;E%(GfZK`qit+beiXR zx!G8mIGIey`?}`ka@j-~4#%6aEUOx}%|Zo;PoIAC)1Ut2=;+>8-#i5bZmj_=Y_TV$ z6b6xubTS?M@IQU@`KKSuW@F4#KAA|0Wpx1SO70)e|L=eNMR|N?wz4+kYWw7DbuGz{ zB+Agvk5~*HnFQfB?UJ5AoX8QhiA!LK7aakM$YtJT-Vu2u=O{}FFIInpG(jNP=ZkFE zcNEZmM2s!O-e*3yZH+{=OSf&~F0{>nNYV^rv~+?oZJWfI!P*S}le!H6h|YUQ&gvn1 z#G?u;MAg7e(}cPSbrYHpqoOD#-W(an#D=k$XBi=QO3k|5lXv8Rl)9&=t&*PiA3HCyIQui~ZH6-_MTkN=N4zGlOSLu9*ENYYm z4v|@6)6{hx8{>thRBRPHauOl1U3BN69|qbg<}A2pyTyvAYUDoTPWl?>%=@m&wL;40 zxs~QwmUTP#mMzj7XI$UUTB$w7SYN2fe*LheYVS zbKYyK5muF^X@r}?`{`uhkP7cyF&GbX+MDs+JLUTi&o3^Pm-DLTGO`Lap}9Cak0CsM z{5bcSs1kZjhi=o-DY*<3f{Flelu*Y2x~UsNb$~I1x~|sC<;m&k*YS<=3i&Hk}>uEn~QM zlp61#XWm*&bT?Jca`pd@6m{dBXg}KL1{{I9ocOMbe=Vlw+MbuVC|7fAZaOG$61J|$ zuteTrx4ap2y#=@SgQYE$oSb4xjPZTD8lp?y3+kq!DLV^WL!4*=KoeTR-WGhfRqeVK zSS=}jMS&1BwM^MM=YTn@0HC55#fGB<>3$ux|C8WTTUHyVH0~7K*>1E~a^b3bC-uC#-T{Dh%*iH} zh=9O~L9qsnpuP#wmOGml*y7q6JG67>x?ZfN@e>n0vUkpiF>V`}(wfe0`@?!AalJc0 ztT&spv$MPR?!7rZZDK^iHtHb_;4HXxy0f!cUlu-_&1U!R-8(%!t*R=^G9qf4X0ccd z27^bB9@)Dp*Q>#BxU;h}9*<>juPjSdy>sUdIQrw4PszFIa6Fw($-7oOLJ2K{RBpo2|>(k?j0%7 zXlGg!Mcq_M=q*-jUOy@Jf!fv@0Fd`ZQ8@C5DA*DrdJ(oM^U|JnX7ByB zNqNO12OjLnP6!lh$8|?(hdP-QgCYZ#s;ZEjqO*RJ2!vSIZGW|44lGfX+jKWTaz>H& z-cb^{BRcOKk`kaxl#&FDbC!J$EG*`hl9XYH9sOJ&CI6*KWe=X15GbwpFQwryN8u*0 zT|s-EGqW+;WU~bdU^@7;RLE4#W6RCDJ_|qrr#26Yu?|gBho*@kly%)$i$B50byeR#x<49^L8LbB zy(p1)&Zy470wIRFs;hF{l&d;y2!s$tn7|E+BG2-1F`Vtccjw`x7z`=Poy!c_fg(iY zDEW;v9hs?{38-p}k%*?#o#}L^uIs9*nxSiz)%;$4>c;7T?6s_le1>be^U8Zw# zIxSkjYsHQ?tnMrR(*Y2*=}5S1)$vKkPvt`-%p%q>k=5o$?S>0UDLMiHbNFO&ob7B=l|S z1QMVFX(zFU>LcuF?j5L09{xnk7r>|*KpDgn(T!LS?ed#Ut9#A;l-B6pNdMaWsJ$=o zrj)X?nnMpp*Ig$fJvlk~^s~<%K79D{_3OwYEQTai0#G6c%yG3`)>Z8W7(%!>Kd-84 zwOXB=oT!2bJLhJz*=RHp)i)<6o6W|1|K{XuXJ;~=OcsmzVzCgB!D!4ZWm%S0llelp z4WKYvrXq`|$g^iJ?;PHF@4W|aPS2~l<~E6<#TJ+!E0TuEh<@~EAN}A5A5BNOMp#$z ztV~4U0Vb2;umAE#cMoRIpP&5V7r!ja2EYqY z3ezRPlv@HItcW7mA?6W{mSa6#tm~@9Rsj)^qb>;|$!I{$y-rDXYkn)hP0vyf!4@|y;EW`9jb}~i?DDEF(F70$vbC}5J`n^>xg+okrPb^rKMveZW**` zSBhQG4l^58!N^rj-BeW->llQSbw32#-OI9GE|)RH5K<3XTIHRpI&T1rtSAO~o@G9x zMB_I;8g{MA-m+_c0cMb( zW29Pvopl-Wyg&l)+~MJ2jJhrxS=A1k>3DMI;BYV+vQ-<1fXEWdy4q~!i}`%HTvSz6 zRTW1r3O}0+_hysb*>pM{4Tr-#A9$BpF(?X+RqLp#(XgF_i0aU(gS4}Sz#JQM^4c`g zd1vigA{q<^ySuy0O;zqzbv>WYtEvo5Ga8Q*D2pgYF6+42Y>1p~52)HI;w&7gG1-H2 zuE=xe(v_DU5BHi$`A^4bzTlcPckd_n+}*6VX?8U41aoO&;94_ZJJc)eLO^KdvMa!5|i>(|Brc4&6v6rw8X zcE3U~uV5SenyfHX1&1DqeOKtT<_p)k@UVmFwA}!-Hc|RMwxdKQWaPzaNz#l)86r9Y za^4Pyi0COx)gZJ`os=Dn3hEFD)NEJ^sKBQ8wF1GPpPyeVt*$mLkud2VtVPl7ne8Tt zZ}+TTr;KjJ@~L~j9sjp~8=JbmI6r^z;K5?CoX_Xjrj*zm23SKALS1{L_yg{N%^~X*|g^>cyh` z#V>#VtKWQiF<(|q)7WbPh{|X zC~{ATF~-2`Jmp!I7lk7tKxSzeBBN=_RfUK%r`|)Bxjf5#MhKLOgD6d?L85oXXprwr z2S@k!@88)!J~>tOtQ11+iF~H2!CC<}#1jP;_1>HERg^na%yF_Yi@GSNtZOp7U>|?RkH+QKvY45Xx##& zXtQC%Hlj!JY@KRH%%DjsVe!t&Das~xAW-9i)^*L%SY#|Mi_GSa_LHc(GoEsc%<8>! zfzy49s9=O^S+7=A(!t5ukIf$O`N^te}ln zH&pj%JRVObd7l6Fx4#*W$J5EQ7!*G9qTrCqvZ+ImE`2g`Xd0`Gy?1$@=Xur%>>~3u z_`;pKWY7z{?EQJ62*Rqcy> ze>_6Os;V|s6+{-R)y~e&Y=5sTDKJI}n|+1=yy^7P_-Jei(fEGE;P+5VmimQ}Ud zRFd%gV9s^~1?6v_y|{OD^x=mezIy$-uIm<5?ucAc380P&`rfCX?d?qJrfEw4fB*3p z|JUFBYPqh-c_37DMz{ckP2gs+EWqX2&|y$%X0z#MpMUb;;r*SRX`Xx47-Lv07GHn; z{Hw2C)D<@>2yTCG_Fw+yFJ?Q#SFgVNw_pC-{=vbM$4~Cxy_@+wvMd&>fB(Zb-+uQx zh;_qwSkU8#_a8lac<-ojyzyINjHz&u0Bcl%NPDg+J7e8CAt0?sK zH_w0j#c%HJ?f&RT-*be|zJ2!M)vLRAj~+aH@bcxGFaP-U4?h3=!O=Z(bb5CB%U}P# z4oZl^GM!C+`2A02lTj1nx6huvcy$t@5P(D7nN05<9!{o%(YQdez8KYI`Q?}Y{^t0Y zAH8P-@lQVa_|b*}Vp6cNPIb~Gjb zCGE6sbMDL#s>&duY=JqgED22Ju4*|a(y9l=l=UL4%8*FJkOO#fLVEWR^Hoj+2mF?^&+>Xp!9=;+XonvWaFC5#j+wegr*7B zc4}qp&e3o*9!(}iQDok`Jo9<(Gw(VZW~X>N>F2EO`@iN6rz5 zpm1F`!y>=Dod5pIKls5Uid)z9#l_`vxm;XcM&>-r27|$5GJbHdKbaov%yzxckTBUV z5gecbBeQ}>6<|OjTNyzW32jA7nu<09#GFGSLPXwC?!3!vgY${YDt(Jt7i5dZOd1t~ z2lwA|bTk|cvfTO10YGGa@$%)#@kyheTwxo3mSx3g=$u2eEGE5GOMY|C@V2?tmR8lP zr27?B2M)b$JO^)6$M@i;&}YnE;nPCb2i13SM{kA2zn!GsYnxfp(XHdKw{aQz6=DDD zy-w8pj|QgK1JQd27&~#LBh!uftjP-)(-F~X6xS!c+Hgy@nLk#~5mF3nMO%vxB%7H@ z4>kMNLis+G)Z9XZ)z^a{#BjvDa zn<-)IJ3`O;XM%mxz!G7qtdic|gADV$$%}He+TGnv$K-8}EVXvSF5SjyNAp6|HU=dL znF$4;78X!{|Ni~A+h_?=iWXceo>Dq(hY;;fXIHF(ok~e=Xs|@V^i}qJO8>{0`Q^)3 zkDoj_J3T)?Ki|ggfC7j^clXY{*RNlSET_|HQ50qb8xBWDM@LmvzkK;}Ja+cVCVpq; z*RNj_Ws}M1{?XC#@$1c|%8NmsRmX;=?l=3$9&woG2Yb5?l!#tloc{jHr)8z!2k4z)F;Jsg$}t+r8$Dv? zXz%dwFMj@$&%gKaXq;spSU^Ob!w}y4;PK<5yMO%0fBN<5D-KifI zc=XIlbgMyfIx_`8R@lW{&9`A6^HJ3PEI80Dd9UcW4Mr-S$I zPY{7{HppEaf`|ZucQ_s82YW?~`TTtFECgj>=DT-xKl}89I|sYyJLWAq1m(%a+3EW7 zl7I*>bCgX+LJ$BLd=q7}u9AnB)MRAXF;o-H7!x2JkPxk_(MC2S5vA|~Z0|?y1_F{= zRKg;OOD@XWM0Rxcs}MXQD!ByPR{#}c<(_6IF+jb64=oz+IA0V`YV?-iR`?Dr z*wJ)6&I=3U&P=ZEyf;Il_a0qRvso?D_q&M*A_$VO)`3|yaty)drVN5HaO1g&?7c%# z$6A(E?%?j-ee$1t`Skhfa(QyG6m|Q1dygMKnoOp7QRG=p&H$$_oz7DRpruYGq&6nx zG^TT9J6>+BoXn6&uZWa+S7e^hIqys_OF&)p0`z3mH#byO_1;gX({g=j+zOLTUM^R! zkKX{&WHk2Kka{UMeH2hXvm5)(7`>7&k{S)7*Q#f{Hp#oq6ZaprI^Hc)SGdh%c!hO) zgP!%LYu@{O`5Ofj+|W*KYl}WN=h~$aP`aVY>epLDsCxVRw2HZ3p(0)h$qpfyMYppM z;ms8Bu8EFq_r_6we%j&a>@jxEF-u)lCcWrUTU8}ACgsW`dGdE3D*VSY)vG!Yw zQ`>%s_K4Tnxs+~$>La8z+zwIJK4MXjtv9*7THE=c6+YYlPnK^xb4x4p*Y@9_cb;~p zXJ=;;oAG#T^3c=(!>*l;vu< zX+mgi7LL%j8;hs_Il5dfU%z_w{-a0Fo~1Hlre4ez88vXq5fsU;X&|-}|J2zmjcW3<5AAgTU{*S-= z2W3zVNa8%~@9*sF{15=Es=U0YymPy|v&_@O_jZ2rqt8!HPRb_i?d|^H2cPfnPe5UD zu`XAuhFJui%SMw)=Cj-lAd<4l^gx-{>w2+j$^aLa>xLyV6Dg_e?@nj4ohY!Fua}pL z80#1to45-{wsQ~*B7~*}U{FBN^=k3*#f!S(M-T3P`ss%c9_$ffRX1f5>pD8hDQS|3 zC{s<-@et&ExsKq@&Xybj(TSJ}QvZ>}BzPMOOO#-d zF{xdE9S?&H{*7dVO)$i~%?Jqr$$@t%gQ^9(q#y-@!J1?T(ny#!s+wDr5FHzdRJe)O zsA@FC7$gSf5X>gh;fP{n6(w>+$+B~mBnMaEbG@vRrfF;p#FjGXlCE@9m0hG2BIVv^ zJ{t}PS(dx)gw9r+r1a~BKwqi1wvK(obS9=mo^<4>?Ui@YhcSj2Vq}w^i?yAG!@+nw zC34n~PiDZBa+EmzS2e}dsUv_#>jwgYBSah&gFz0WQkPZJl%#;7F~sN{5i)QL zF~(SA{_xM0o80N60i^|D_r~gbEiw|JgUa4bxFGq zNQ&mtl5Ic$_GLg_Fkidq#Sog%GGwgot#eJ z5{q|j?cFxdbgT95*BS5X1^o%$z<1VI$@$gYZ&w_4y@AQQe_h}6*n3!RDWUp*oTGjN zSg%yNsyDP-$)vdzeW?idVqjX`H4$9v=JrOa+&(+~8oJwsJM@V?>DL;B*J&Ceg#C6P zUXw>t`$=L5X#;hxzvI7y(fW>7+^u~q5h=^kenqcVqCTCtmn@z#Z^SYxK(7(bdd@0E zM~<9Its>CZCx{vQ+s&Z6GSDRlVyl|(4AEVh4=B-aI5;@ipU>xc=JUMh8tpD|X6Tyx z!M+qn$-3P=H%6Eybb{b*f$nB}S36Z{lB#keu=(n6`AW>fwy=AlH+>Lk5w`{eGu!zWK3 z30$ z|M9zL&(_P;-tO+te)`joK72rgckb@(&c>@($GfxfY&Io=`NifR|KXpHU%rZ>07Nbu zjdl(X@138Y*$fI4GDmgfufO@`@BjICjkpFNb@R{}zJD=ae)H|~XD?sR=j#xnZFfY# zA)KF|zq#0i2u)L0<$m+y&j>&fLfy>I&Ig0>2TvZ|ySFbaO$c9q^ZfbCH|uo`;6ObQ zRrQLShT8>ey)M7_-M?R!O&O@JK@}5E)i4jxJ~@V0M}-s~Yy#Mnbwem(r*kWgggX&W zh#>_98q3Z*qQro}OGMcpnaeLJ3^R=*CTU? zO^g=3%rORKiIJN+aENxO2{ANHlO9al=TcZ^Y6W%qGpb@|+*_PJ0BFNKN}Ml5Eb<%y zEw>S1+i%9J7;i}<(ym3ZJuG2LI)H8wRMqu*wb^X;_YcfL9b&ATCWIJb6lTCg0m!p_ zFc=trKY>8EOJ}DJRtw@JJNvgnPx~iem&-~nJGiIW0We3CC)OdBRkc~Ko4Q(FUS7@@ z9QpC%_wOIwjgd1)AqbI>)5x(?jR^B-Fc9&OFu2-3OOtLRe$(NbsBJqanj^gf(*qHK zb521yMp7e1yF?^T44rh+B4dE{nycDEn=PqAl$oO{+YLGx3=na-Tn0vGl;FZ>_OzeKqQD)o;lq zyf&S@T4VJtE8d(2-dd&M+r>uhL{hio7kfHvEqQw;&y{~}!tGm;t=CQwH(~d0(vMjR+%r%4B?Xf(!L1o{;8xzr{Zeon%@uc5-Gg{EK@PJz{z4lc5c;lu@ zfW5w&&)|E68^xR7R(lqpURWrkkolBXi(4sYYEuEg zVzD?mIk|iH?(5gb>-EN<56tWwjmM+)dX?w-Xf&Bl_o}KoJw2c8>=F7VgsKkjJ$!id zFgrg#+tkhe-Ft_Jho`4!o6WKqP3|APSCy-yqx+-D^z`)N`1lR8TDgj#xp$nnMCnGh zE9;!|E)xOMBO3%&)%1Ws0L;>M>(ya95+~_2t$mrHphi$cefa3XWHJ$f#eDfM|NO6C ze)*LEafH+JRWTeL+?nl8NBeuz4<9`~IsRpg5tUInHu&{dPyhD+`KR@|RFN02PV>R& z{?XxRG#CxC(J&Y0%xAU>)ph;)`1t(dOaN6KfYUb@-+lMOy!_+w5L82CRh=)_C#M$? zJ-Qq$f{F#iRaN~jzx?&@zW8djsX5ZH@O4$0#3t6w{NnuVYz>$pqIX&5GaJzji_xQp zk7m2G$B!Olo+Qfam#4q~;_3OKRLa^wb@C)dKG@Pag`2urU9JP<3VApBY4d`Sz|i@M zB1U&*wD=)K#F!9@oaR)_NqW*+Ux@%+tCUa33k6d)A)$AKgs2V>9cc?Lv5W;2Km}tV zn2IJcYs=pvpE)8!9JKg8wFn?PS%knbN{o>?R#k1@`?{_}-86O0tj=l(Yo{wX^0vvf zs{UL3@On)i+ifZ-*edl!Frh)ax-1%6OQhX_s2c^Q(>kR#7GRIg*3|)R)KUoR_4?%G zIE0vGd5p1X8uHF(*K68*Y+M`KorZu3aG!Z1a^ATt^I4Wvb6eTk<0k=2<=+jJ(erP*XOjE_2>{;V7ci1P)PH$$38* zP4Ti)xzXs@YK^VNPA;uBiJ+y#_M>52o4T1GEb3fZ4;cbFMQK4*NF=GOk`O{wRpq7( zb*-vdmgPlO6!~yCH0X!-KE@D2t*WEpcu)+pq7b07i_5c%rL;LBo!hSas&7Y`1Jl)f z(*FM4A6eYWK*y`Pt9Q(m-sUKLM<44(wBL3==}+t4R%2ZoAl{r~-ja8U*Q=|WRQf9* z^|tGy?fk0+Xktr>>TV>wMs~OnRdfsWV2hM%f6Nw#>$16iyAHeQD&7iZt*R=<*h(t# znrQ4DxreuuQ|(@Vqo-(UHi?m)%d#v>5`1j?NeDMfy4%*Z9uH5krzL>Cd~;iKYnn0I z&qNgiw|5#%r7gq3DIl~0EE_p=G&68A&Dh(QJ9R{xU3S}8(TMKPxE+3xqLC9B04 z0|!l^l?1*+|JAxF&;F&Cn>vg%_G^`HEi((U1RMSM+ zd30{IsaS=739tO$~r7AVBD7FdEfNK>!#y zun4f~s;r-W`}}ubJ`Dl$e7G~ts-^@|RU`+K>11Cs@&oVlo!L&7IYkgfa^CxVJRI(f zh9nwU&MxMgGLXxaY)FC%Bq=u7fI!H?QG%rnsPZ;|50b3CCFm!{s{pWoAqu+IY8OFh zJD&mTlQ)C4%Z5R6nfIBUQ&7p73lFUjNhz7KO}|z_?Ue||zjTh!Ip;GVn?XU_$WV7UG-L~CsQ(_(H9;Y$AV6-k3B2ZFqvbJF|))s0dwB7r(IH0nu%5qayRasVs z+Cl)I`ThMvL^m83qsfkmyG_C$Vo(s4Xqk>~ODpXqhPQJNmpPZ`S)Mzen>~uW6V(u7 z6GGEmY&M&^s_VMmtk;{e6lR}g-Z^imH-Vke$hS3a*JUq?Y>+tzpi!F`z2rt(3(OYX z+yuV7Ttz`KwCUA~p=(=pJC>pKVU{JGZgb-satEyVB zR#jC2KrtMQMx&kG9h0C@TRfvEfG~3mak*HQ>nigZ5+LQPGQ56sUIkIiwA-1k#<|>p zSTeyj>omobsz`T(NyjPPj)t!Yu&zbT^v1`q#hbmg3xaP!Xtslt(BFW!=y~0;KJgt@ z+S}6)-`0|8cl}rX!W9GrXc-HT^0 zU&bha2*)Q1DL&}U*__CUDk5hN&(1E6-n)15>h&M~@P`jR_^=7#^z?MGSSBfju&A{q zVhZY2JUH0<k4?=n%lU*1Ld63QgqYYIW~$fP~ZO)Mrj0B^9I)#chU^ z*y_#LhWCQjbzRp%g#?_SLyW9|YII&eb!b`O$(kib8gE3&DS%UTk{lGk9P6rn@%+{C z>(l9n_p?kNKf3q$;ho45B8rkKeDv`L|MXA)^!&RQwgDreqK3d17xOY`Sv4HW!)XSh zpvXX&731AQhXd#GNuh(m&~6MzI4H8gK+)yS8EOd~D61kk1o8-;6g0#j>rJ_-YKANs zDlM-X88b;N6i`v&HXKP6Y@E&95~P3EaFvchnm|Kydl}wqc^)QULVm?8ah~cb(xoM)|71pa&Q#W;0)pZkNu=u~! zg&@K#zrr%H`&~H3nB+}uBN=-n>E3A%r~hv)OESe=p0j!Ek6Sb!qc0Kol&M2v|g749n$;5VI^-psJ2% zr*BTq7G)CwNE2!;0)V?(16^%UaXZ4;GBwh6-*$=8{&8y^^A_rQui%uM+x9IjwCksZ z^r?HnELVQ)#-Q_h{d6-%@E!KOcPhBM7E6CTlWLbC+OVer z0d5BK+zhdPhc4=hGUw_9sT&5Vi1n3KbvPWpn+My?Qv0ubJyfyfRamFauJtxgR}lc# zXHAS|inUk_N>@;?nkD+Tm3Asm>e|DpxJ^AM!ZhnN)L%Mz8UUGk38x5smocQ2 zpY%j00*{f90hpN;2~b7q5VE3hS-D)TW;;8I5ZkXqw?2^V47UlPX`0b+G#m{b5urnL ztXPXMf!C{9R9(D}-dZ+wij9PSl`E7Q6P1Jzn41u)stL@U$Tcxw+TWD0Z>`Rs5M7qL zfg^8^cY2a8E-seK@wwM5r0*#e5+mo8|iQa(!{Jm`tXjiB(l;%KO}wx#Vy>8h`rPr}ysN+iW)f`mg`m zYUk6!lRy=!ps?Po*Q=H40g=0Nc(}j6ceXfBK?>4o`LsR$5@5Rw*@;m!Mix;)Xrq$a zxFtZs4A6@bfI~o06r~WcVI~1_+6ZuJb7Eu+tf%Mmzx}&^jN!+JhqKY3$jF)0&Sm5? z`sm}MCVcPps~61CPAnqYgm8Rv(l9yl<8eOQ-7y6Wk<0SYa5x1Rs6d`UmKD}kb%a^w zvrJi$V+6IflOUKV+$?%Q1f0vrxvu@)GwQePm+fLCAu>azVA}FD9<&Q%--%1l8hUch zXNIQ3bn4S?8McR0Ow-e8xw=z(WR?JimSRix3(4xCEkLS8=30i8^O<*+rGPdl4xy>* zx~%Hex@@9F0;Z&Lhv=Lik2C8%n1z>xBQtfrzpcF|wVJO9d;1G-A2QTFjH1G*J&5xS z2flrOUCKf#r`j()?HPuCk1@trS5;Y6p>BjFbJ-xzv%DCOC*EfkmSBej0kuryPPvJQ zmd~o!W=ZA%05ou)Bo1n@iNDF;Q%)Cx&$97k;`3rQn_0}LspjjZPKJQ0<`^YJQZ2l_ zsmzjmQZvlk88plCjK~d(!a2tPQJE|bxe4BZQ}E8Qu!shZ!QO=mk$OuLZ<|;gV`I06 zrgmoEcHKruxkTk?Iqdd@TLo$BUR~Fhi$z(MRaIqqJ{k@W4h{!{!d}4INUPPVpXC6e z6j_-;G-?bXL=I(H4u``$FNlh>v&Hf2i^z^VAv#EL3EMc7TT2QXyWDX6_b}LqaD9vg zeMZkaizmG)W53c7Z0mq7G_xPIWLNwxz=-Pw)-{XYJ5*VAE#BdY>;G-LLAAv(rWUfj z6Yo7-N4FyqUc*(SZk$SN2Z%*cY|m85$!t;cc&jNA(~uG2Eg3{N=Xy7Fb_Od(#G)vA z;ybWD!tJDZ)xhy>m{Y3~MZ0#FO26}>=$)%WGaQUU3@mJuFK#ud>6m+a-7na~aM?z{rKL! zd(WOd>-wvQhle4A`Q<_tUcY{2{W$Nv-IfH_*J)q8E6iC>j!)klpMXG~=bLr8x3|BB zbybzAE(dJ6eA$Bs58iw4D9^K}PoIAK?RV?4mhP;-G@VsclwTXgVWF@nteB8`hTn()Eyyu+#?ETv`D>SxpIvNv(zaMXA zkc3@)kbL}KQblqn-d=AX2<3>dRj-ue&A)=mAWL=(A1LId3YW}&XXVm^-i3!=ZoINi zd;^fp=1W`{IN_2yA0y%MRMjy|J)1S{j%Rwblydd;^hk+M@O91-l6glieAeHdx8umX zdzQu_CiMoXJ@NsuC4O#glix z(xaf{=@mXy1!(lbxDl9xD3IHb>WzO)~)1-T{EF2f`YLwJ3G6~W_*0#O@k+f z-|$y*p8ZgLGmdt)^x(zz{C#gZ4#Nqau?Dqwv%(1p5lINCMg9A>WKy@~@6M?paqPAq zY7!n-#kQd84>a(4<$oO9=pFhRJZ)t+P7h{Z15~|dywq$)=86?NWe;Z9RLPoe4_EFd zmDUTt^Z1pMm#&V~Vhi2>m{>TfEQ&o4R;L^R#5EV@iEClDH2W?u-9Ut)mgNcLb6lM8 zHEG9{hp$J|?v~30g-HvlB3N0)N~mnU5QzFEs%!BL&Jx?WySf02`>aNk9YXE=Z&n1=^}rw z*I!L%`@pNBLtO{I_eC31sJ?{cBB9AM?=I03fm0Z~KYYrH!_FY%{hycHi00KctS4xFnuo}d3FqkO+JGW@7h!Yl33 zMt&nYrDZZnZ{0E5;bAc^IDsG40?t%j>caInBldfq`n)}~^KiYdlq;-Xy-*sQM*7N4 z3cJEdwIQ{YYUqD&De_3of_63P|9DtvL-lrdY$)t=_q!sPem;blBIf4|pw|03`?aKX z`aRITDigQ1uPzmaeXcenmNSFTij9oR{oTp4q7q85H8kX`Q&ku(Z%WezDuL{?mu1g<4PSYQ0~t?CMJa3s{IT?7_w5_S44ipU+0;d7~10g0N;Vy*+VAv5OJ> z;$yx*`b-|~$EsKmS6{V{Qg9Z^0AV*Uxmf&w`|Vh;r@*^qnMrf^#3(ct4ecHs&GK^0 z3mg-fz(NwxPs{MGBoFgk83HgLHgIED@+wci2k7WB2cKS{A(yOdRi7|w4zxM2P-`6g zYLprK0m1vX4}+_`jHH1B&j~@(Fsl;Z0AP(D3lf12Vw?vfR$?>~nu<=ZpZz14I&N)Q9bjhS-M(fwuQ1~jeOrv8P&k^LK(>?YrQ|i{-0?+H^qk{L5~r!d z!Dqi1``z6IO!mZj#^+DUqHQsqET&e_wT0h~TF`*z7mWeB&%cTnWDn}xoqoUX2+^fH zJ;<=Gf@WQcm{=Vu$oNzTbRExBd5~|f+{ZUGX}!1gh8t*1(Kke3PP@!o7vv^UddiU> zj)rFaIi>0}h?#rS`x{l*K|}>)D8n#*uNQB+oe%ejSc}a;3P^0NLyvbmvVxk1#!NA@vH;JeFd6E={8UN~SDxFV+jO|Wjcz81 zqj~(NNwj!{&Um~RJ$aAL-N&v4Ly?zmbU!Co*PElca)LruV8H{WPkKyyJm{M9dn)0& z4E}VA2s8m`@*>1&7{Dw_L8hbQ!M%wqy(=${p) zN>{|8neH^g&oq4V6ySbg!Up`+Z@ZQv*$Q-yifekzdkQnCVM{^o_eEYVM;07m z{sO&Mv9V`pNRp2_7>Kd&{hzjOyH{VP%y|E^(e+N8|Mqrq7DlJ=HvH%N>zDTE#M-Re zCsbM1OvR4-2fAJ@VE^+JHte^8*y%d>)FN3gD{5g*pH?OQeOl}Z&``%<1=y(nRDDFN``cuQndDF%aB)_Q>e1N?1|xDmwzj3(W@4Y=pEH5l$ zJH3$NC3h~HI_J%?Fd3zJXZ)1{>*feoxsgyO*$VA9rw;0nSv-T&XF$aiBoa8k`pt?L z>oTtM2tl7C5qC-xeUQ>VVCYd{JL$n7X;IKf2Z^O|)&0#w)J_N794(@{#hr!WIAWGa zPXhJn8dT{LXl$Y3(&PI9eyl`3sVn`C3c}W}BK>P81K)R~uQ@n8;&^SVcpUAUwKdF= zgxWziu?G9*ui~)Y(@|>((x6s~JcO|Wu`aOqy^}TfkY>_M1;f01^JtP+)8gN;z3#t4 zf{J_Q6Q6*~uh&-r%uNS}J7{P1LNjhSC?-J|6c8F+kEjBP4eNcaaf}-XJH1KnV>&jmaXCc@1|s8}^l=QF~U!;xv&gT%|GF1*C8P4=+^`D8Z?b*z+gZu(;YpU|$> zU}2=CJUfV+;9}B!h!IEKx3cpWsgnWyjbs>+~YO2t)JVM+V3u3;&q{W~!c zP)+^QU(r=1E{cx0TR(|m6M`CYju<1X!~L?Ezc~~aatPL^q`38B>ZGDbnMgi@4akLY zrl1VYs#|8u-okpmaz@<3apCXNRs>^;ckx-%iDi?AOg6pem?&eAd+eX=!2V!?=+*a4 zr6H8p+z^?3;2mVyM-J^V;XH29P5C#{TkpR`5*JB8{8 zVGPW~?*%k;Rc>WPpTd?2DiLHnb3{?&z2i&JehUi42Vkiaf?(rS;_)~Zn!~o8@x>iu zx;b}c`$#b)$cBXN?uCE20Q~xUiHzt0b)-VS8gGXi*3U%+#+W382N0#Y z6!Nt?_#b^uR(On043x1q!nB0WVlbj+qKOsq@R(d94}DSi_xJZJr<#UM2GyxiKNNrQ zah2S-gRyeFcW#pLG%O&%1?YSEkJ^xrBXd`U_+;W-sgE|Y3S?puvs4^{4WqHiU~KbO@4hb$qOH4alN-m z=J%?E|8_ROqc!(L_V@Y8|Ly$IkHEY1c*#cNHrV&x;@U&x;UTk4;Ml^3e%I)==K!AgEN(icPZpr{?^C#P#|B~Wls9n474V0t1y;XFI^0!$!|Lr-{BLy~lpy#%G z8VEdYykuSI zlmr>C-*L06`^n(|0K|s|a(&K;F5TO=Ow|zL+2QO|yw2|3z^#cL7Dac?ot;L+Sq!yV zV^nMoNTy~^98NYS2y((e9tB~EAE>JcqkdG?nCrXUtuPoZOXnIV3M+c~q`6!a>C{fv z;8p&ilcMZ+IRorY3v-PobS^WoafwA1I*INaz>5l9a8KrzCC9+w+|g^)V?HixvbMm- z9X^y!K^UR7=~8_`V(jWc_iN1+YZ6JO|3S1uERI1&ozW_leOQv|rTPtfTPGp{gh{BT z6Q+mF`Y)gTZ0p&kMNpS{9BrU@iDy)yW#)rvw2N6u#uzStpfqTj^YqfVZT-9fXTB)z z!Pn2r?{cdb2=;hWh=V(h(_u9v2YY(fe1z)mpzCg@mrjFU!{a$=Y?K@OHR_jqThb=> z>%D*&5CIm(1jUU#nQwHsIOTh>X6rxU(g_W)OY7=HFR0zK-3TZ@1L4m`D*BVsHrY3K z^s|e$Y~v!jU|QjJ8ozDp`_qb5!uD_!BcLiAL% zZ}o%3tAhJNc)tC0X1JGXR6lx@BlBHps`}bg2B_Jf=y>NRg)iTkX5^)4NrT_EcG&Qc zA#7ox($rQ$)i(!_H@f!>2=BY60_~0h%vHT|pjMda=QibU8hO8NKrrQVHf^g-_HAin zDk1P8$|FgO(;Qt(&6UPjMj%lm3dqyLxiE`Zm4?Qcg$qf{2h+ql)N5Xj&WX|^o?TeU zl_CnOi|{P<)l$)ZVpg`65of_-@D@%FBcM!-)mu&oKOPjGx*tn;UhgTa-?#O`Qr)rg z44H&(ZHHg|X~vaqyxY(9f4yBWB+1;q2dwGaah=V2mHzh+___XbHg z-zM+JI$thx+uzo1E2?aHTwK6nYk!~GR-QWFmL~jPNBkWG36K>88idecL&+5cIAhM+ zEhNWbj{RWH&B4kO->-MQxeafj1dkixdnvUk@5#le;g_0E9sRFwSza%5Gh-1p0KsJU ziHC;_>SRn3pWj;0S~u)Xf>=r%f{~rghxTx~`r_#K)Z%jH+g`#HnC}kG9NRmt?lh=g zAoIUsOC$ur?{(aNSby8Dew7osxc9#RytzGJT*pmjZ#mwf8gxM2?r+PV@W~8<3&jR` zse>~*fL9~%1_RMue#8`%GrG(|roc=P;dZ(fVfacX&d#*;M1d-C0h@+A1nBSWyyX>@ zdV<&V7pfmU*U^KI{)($_gmu9R%7GJ|c}Jbw!&}0P29s|C&l`&)r#P1_L?xJ}(R(p| zmtjxL+uBx~O;Tb(L`9ElK_DjU<)B-pVrU$Ha=}*yx654;+eBgk4|v!vpYsYybVrZsl%nL<^$1 zDK!5j8_*^~FfiimeLQ*3?w`V*p2l9_D94Y0HkVIY<;TFd|MrW>I~Yy|(X=O1IM9X! z&p%erb$5jo8@D-5g=u}%HS`i5xC9pm;an}Z_Ak}*#~ivkx(oBxP8bRKU4cwGrc+q) z5%b}TJ{bqPA2S)vnF{MO2*{P0d8p44yl`wYI{RwgG>VtM zExqMhVnDF`I9AAownrwPdZZTW&Dj52gc!Y`3{951FDr=E{+msj5jg+6ZRe1RnyPOE zStW*!|8?dkZ=+96iK|?Lwy;yAwElwS@$E~m#DZH?tLB|&PA+-bF_U{LD8Q0{TEb*f zxU+@+^EQ!YhW!Bl7BBq~S&}x{&%p1y;eN8Da3V5kpUw%s&+HIm@)5@ZJKeeeO(9vk z@59yHNb10Lt-WsU72i+7ynkW2y}m?Cr|#vqR}*h16U^0B9X=1M)qXEZj_2GqDN0FM zJ1!q27;3HhV;9njg?_aI*y1kmyGKAi)0$*ee-3tB-{F{gWTO65i z=Vf5$%h{M+ZJP1>a7ayyO&Ap-Dh_BORTpDWoW(O*{g#Nc^} zEEHxQb6>Y|4LUk}&fE7#9)2G`0rKqF>Z*l{zn|Z0umXo}g+Y5e{uH^$;^~Uv+oK`S zH#t_HX*tq2N+=fJm4APAG}cSLcUtx2?|*l!wARt7&8&`ckyQLU>i=GV8X@A9Zls7b z(m_Rmh(ub56b`2-;t-bgEIW}YMx%YO>S9qkADAbM79KY@k)tVRf?=PSkP<5dMi_N1 zEM7I88Xj%bV1dK3};)v)%7QixYoCFPd$-@+fcw4`_Xz)o9h4aqC} z`?ZB%fT!NZVyGBTo%r)UY5x71%Y{K-l(rM0Dzzz!AfaWf+B7^CmTL0rfoB57$Iz+Z zKSipd>OOp?ob%}sCr0WZdX^gLb&_k@EsSmgvL5$l`?lgLdksQ(pk5~fr$LWdpR4@% z!A>&_gZE;yX8qJ1y>0cZ27R=+YOj9DyZ!Z|H*Wse?UX@I3c~A24R3Ll%->sjfO_P% z=;#3zxf#%ePL`76ua4~3FYC1FG3}51C@;UhcHt?ntRLr_OzsH>V_^clD>xt)(HsrT zYG*`qB7EwO4XdlE6z(XRUpO}#;qQAFlj1AL8Qk+Kq-ed_TNNo|&?Az2XorZnG@ph4 zWw|L}b1u{8lXoxn-@$BPdpr3StllOckT_Ewf1U+cYkfGd`wTH^axpaBYVwk^V)^n3 zMHp?LGsY??GM&*u$dOSJ>UlCfhS6hU7G7AXtU;L5eF-~Z(o%O*7#r=5ncszuIka2X zUSXID7aIrgHU^cmGqAq81j@1Efyfap&Y>$F^P1v|?}Mv!1HTm#j6~}oX!E9GeH62l zH5-Ji;bH|*a7qVhFI(kYd_3^Meuqk#RfOE9r5dXi%(+TJqYwGktU~o3T-YE{RCYXP z)41aB$;4bgvUEyQNQGS&43TccMFqizgkMy@ZL_ckK+d1O>V&Yn!`7l=2#$@@JG@gc z;!_bhS{O*iVKfq@4G!2627{8K%KU5RU*`;8Jl4W;UrsDd#ly+peVpP{d0-u!ZD9xi zmzjOWo3pLfItEGIAyM})EtH)Yv9H57go|tYV8~jhffZnn=)GM#Thz}v4 zAV(C>(%@py{XFC-N<>`%s{!GDoNvLO=32sZWc`iLlkA8P$W-R7ZwObbBAfbse#o+d;_!lU8qsW z6c!0kfR_NV7Xkxk1cOQGI<9>TGwG9?sAndeE1(%2Q5_xeVv%fAJo9$ElHgiJqhvC0oF0+OWL|p zuJY;KUr{yWCX@Qv1Dv9(YrE*NhmU);Mk0TjDkSKWjQNgS- zd(6UZckgC_g7(!vxU~|Z22E;RU_GQr@=WVsY=*uH2Z37y)($+)TX?1{~nWw zK-Z}R{-n5g$2Q76%{h>C{8#54OmBwpk4z^zWVOH;VLZ+GN=-F>IFs-0r}J}ZWWNhP z>*lW~GxBLqT-C838YCd1Xor-%?Sr4vkA<+IpPAv_;aoJ0qKF_o4t%3w76cBWu*!TE z>-WdE>9w(i5n!Nd_#e>m&eMYCw6i96##5{-oBWn;sybuNK2HR@cuot9Dv+&BnZ(0hey6$8fN&1GWkcS>!{w-|y&ts7G3RtC?xhGIh-lyu6Q>jdk%t&@s(z9}RGwwD zO*0r~RPY|LyTK4rRQpr$8G$ZAtbsk~Ma?&?$X^td7Q@a48!Ml})DCAMv9=YHK#kB; zN6zIAvjXedQadq+#a^hwTrbDjvR)NJPxMaIo2=jZi(PUJ%lJIiCQZ#f#ScOvkX@@( zEw#PNN!#lpXQ-8MIiqda^0-BPSs53YHZlgHN=0nKY~!=gFzOmdP<+0QKA&X;*F3*2AH3>}Oa=InIhGX) zrr;bfUAWf(p6&-b?#|!8w5gSidwvF9_0=B>JD^j-CZ_P>YO}?MNv|Mg1k5&(aA2Dl z(TWC3A>{nX^~bswz~%j5N3#1-%@TK*#7a}! z_LR1dpPzB1fPk){fxcD>74-`q|K;#)AcOA!EJ{5(MQU)X{pYDPX^cke55dxAlaszJ zHT?vp<*fz0BckjmND+*&RRpa!7@!#R+Sh(ICAjJ0YOHlVJtI&I9v@%C&+Mk!Iz(BC zbd#*m3tqUNqg}$;HS+s#-YrizpRswfXst27^M(%Ku8<8+!V+7CvJ;}@u#+feIhAIg zwrjE2XBmDloh3;kPgjcGFGeXZaK;dz>1B1bKW^vgpLKgtAEwBe6uU+v%Dq1bpBkx# zBSYsrYNm}5VouAga4?U6q2^4(`U)3)T5@%eBD}DpzyYaf!trTMhE~-6i#+!`sj&U< zO|2Uxbnlvvu$NWwn^%u{I4G|6DQi(J{gbHD`*5{unQf@4&E%zL!~FREbx&z}+_db| zCkHDmX37VQ05eG6k?ycc-A}sbT3f>48pvY@UBU2TgmrL#P8z>gdIExkk!dtnNWp~( zdy5W%O9pOnUOxX4CWEXsrf+gW`neoCPWz0~p^Xw%p?P9?{J#OyN9zZmBJel#dM`;y zqy<2aagSlE-P4~^$3(bE<}Fot-<=%QpZm8ORCoS+z6OlvS59{9q13GKm=iFf!~)H} zAPsuh4jSf|bjfhO+v{y28pyke~3kh#!s=tzyuj! zC{-mcLxQM-kYNZ^U0b=vt(cNwW8E_6Q4*Zx4T2JPgUA`h$^<9_DBvg|CKYv(r#Sa^ z>@#NGXv~inHotJt(@7F(5LCqeAgkfNGXk`WhTcgY1wfs3UxCgv=r1I&jr5s7n+z(x z@2BElFOBlOAAzBsju15xfgVI$1#%m79e`Cng=D};NO^K3QE2g*%12Yd8)1@(?}vq- zX~>btfr$~(F?w4tBPJ8s#uKr%t0yYl#tBLM;nx|hcVEvOIz>1Knygng;4ri;%gZw6 z+=R*jkb3>Gt(JyNRJ!z2goojsYkv4_Otv_LJc+EQ>u;0&3ilckG^nghwYVhbwvbfL zWCotjah2ex0Dsk{uY!yVUPeDxD#Y1s4hI51X;VkmO78o1;q-KM>fS6wdRJ980YKuI z#~p?Lbg(e+h;Kce}v6?{5g5t$>%p=p%4K zi{YBDb1{&-Cs!GVCHOsI`cB5uDJr2Cf|WA+2vISvQ36X&yR^b!>=JX}j{XUv>Qz(+ z3tT>LC&3p(kh-R|;@CIY%rm@>ZtF6N5lAEjoMpbm9G77R4cc1OT=I;i@E^?VYUC1e$SRrf5d|c z<@tBrl zR_%PODutBP#e*f4kRS{aniZO1UTrMQeJ%&wVC#xF5=PeJnpk~Zmhk_f@< z!#%Y58FGPmkFmJU$D{I2?^i7{|MTtj=e=esiX9SWEDJPb6K7}V%O%TP1AYDf?zX9K z|C9icTNsr=Ptjf#Rg?*AuFjw!*ne}tO43(0N^xK>qKH)(D3ait@}f3j={=ZJK@Khp zAMzYwPXxV7hYAYNnpNWLGmgVIG^`w&mNu(^pToXf^679e%Zj-cS6B;yFpmrxv|SLQ zd54Tia3ziUuOYEjSfZkcg{(BjB!mEl=T{B7#KQZv0fgn{ITJQureljLxw=!*GP5rm z=~uwuf2|!UOM-GOy)o87VPC@Pa?$-X*>w6^vwnVuj*hOs@PH9sQuWtPbN%n%Uu7A9 z{JA7wP0qpLgJ;Zg*cFO7&gI@lVZ)R3kKDZRFpvJG+e3e1wCQVonLA!QSX&(YQfr%O zaUqN!DTW`fO5q3DsP*G|#fdwNdLL4W^j;B-qCtP9@f5i62@3voBohZ8*8_FFuN%GS z_))ukeUfW_p&NvG*S)4*pS>??;~S+^tic_8fY0JaVx7AZ4MEIbd`z4T9wLuek>3?A zq?06>_uw0muv6^Q32O|Ep@P6*&)Q}5W_`y z)vaPB0-Z)WvRfnlenX2m@(=T6{3d(y*KG5n`?n^wlPb?clM2p*{^XN;GN&iM_Fzix z1*<|HY=_dQquCl+Nh{%8W||ZhSg-AbtILjxKHbAplaSRP&?(?!fGLRMDw{Yhu3PHw ztiR6*BFsvFeLZ}nx|!@S^6;m+ZuIiq zDm3wJ3Xh&$kRT6yIi&Lqse}`Nr)5;kW!okfsd+F$weKW%(;=dvMS3j z*`F~Sx1!0T5&M`57$%I>rD!hrq;EfFz1ox$gO^m|qCX9&5OH&B z6c#aLPQCTz&YW=jW5{20L$aY=B#3!q5nn+eVL=euYwYju-?@Gc{Gbm|h0kiZ`8n4b z z%EB#OQ-!~j7{rp$Mj3005VrTYsvV9Fk0qL1tJ8^kRH6Z9gI~&j!oTM@cv>S+jSh*0 zO}N-OsQ3^f4zFfI6??qd(8XWNEbF(85iXxTpf{>SnKfkeyf^ySjSYGBqr$?MtkCy@ z>F&?eHNr{UT*)2wZ7-YTL4dcl>NvX1=c-%?ujc2kH70!)1no5LX;#|Oon}mB7${g_ z=3}rZIs<<(Iuj~y@$$D{2hOjC9s95$wP}R0ofeZZTI9BLSJyB}S_39JmW(;QfMv0a z0Y0a0S?Nv5hF!>^DWuoiTVX4#Pr^px)rb+A=!%+rt z;aIxX%6<7E`AxCKz6iIAz=Z8Vr}kXnF27EZhxUhtOJHowX9Ww15MVv}CBSNw#f%_5 zQ&)jtP)3Ov4`f&^3nt{@v90s_1RHiilw2*H2rVT$FxmtXzdulqpwMWZ9YJ@Oe!n)0 zyk4FeKaCi^4x?we8hxZRFz2V&tgkA^XA%AnFOG3}4@kfJxo;iTKG`4XSxgyD$nlH| z{+2L&yF)44`)G3+KY~!1t1cjUcezx;dYH95IOCr%OP4vwE9b}{BzY9G@YlGXw7zrV)_<|lcS6~gQ^DQYT7uASf(2Pu6;0C(>UihXrk6qN( zUcY5nV|mS~KV#<;*5v~;kBnoO$6;$RANPRv zKwbdDTDIG*o#q0^e%W6`rg8sE`23)Pl0pXcR|nnRKi<$dm;&wArnZ!dI)n_PJTAnO08 z`)2O*@Ra>hS_r@LEz*-QQSuP9sU>@!bjv_1atpi{D?iefKBS%|vLzuyM(^w2s$#rs>K(3Hhv>Q0Ck`|I4!zh&`LVAjj%x-x;#J?|mKz z2-Z0)cy2;kqQj+|$11Q|YdhOHL8WnMl?cr2P@u{22j zhHMcZ!!g#R^T`S}cJb$@$K26$bzSl1(4*`pk@|RBhO(XTb4{uGr8gC(y^xQRL2ov5 zUk`I%pZ7)lAFedOV%3U*Cl6u^FZUvk8=pmVE?lKVYW1Ne&9o#Q25_1!E&O z$!FNK2>cLo;yS{P@0e<}Kj>k=qFH%ROxUUjxcH-+>=84oK@|LFeRpyw5;o^iVD`Pc zI5$fH0?LTY5)7m4J)P+nO!#l5T@7Z9Us3Y=K}PHk!&qVU8Mh}sWNb(h7l=g}b5&p6 zPV2D5_lfD>BPlJ?;l#kZC0~SoPS*l-UA`O*qrc=vnEJ=Uw=b2dECLmzq4l>>-YK)giG<2Ll ztsPJ0pz7FK)Y}N>elC?|6OSC?mQ)a>C&s}XA`<;tHUAV(_*k`a3OwWJPcN{rcq2dj zbRaDNm($B#e*t%h*OnP2$n)HGwJ=GIEE}3p0fMJwD*pNf)e=t3UFGw$yrAQvoeI-6 z3Vo$bizAg9mZ_a=bZI%}HWI1k)&3y4JOTKxS3jo4nUf2iL-6(IA z=@%G_>WLleA2{}iytvBJUU^|AsHqRvk2Hc|-9GjzmcCY7K+u{Zz1;y-l7#e+g{fk( zIfz-4Kz93N$0S>u6&YSFG|F8)qscmR+qn~{xEZhf4!j5UR1f9DrYMRLhDBts(^;CfErSg<^tyeHl!UG z#bC($9ba)0B1e-<TWT)!>hNCV>13>Y!6uFxQiC@|F}_ef7w30V7f8uM z!)0wc>2~BdCZ&TSJ5r(2KIs%xB3gW!DQ-OZcwP0895h8(!3rFPBk?>);rw3#MC5luR==_ zG>Q_~PBL#1)KS5IlefWap{)BAI*^L81kW#==J4e62Mn_0@WHjr=j|O(gE$>&{?qzm zRq41X6e%vz;CuZAGPI``hh`DLfww?4W>VYQ(o&lu@u!P8gzw*+&2AYA_8Tv0UVVZ1 zf`*Wa@#x>#DcOol7!JztZHFJFA0hpJVr#@NvRjEzF>OlZn2})$z?@Y+Go(^Qto7ld z3xGpv?B!(-VAukmuTC}nfNAm`$gn8AKDW==oF292Oz7$BnqI-seX-eYf+wu~(Mhe~ z)9jsEUS50r)O36|VDaSS@8i?9>VQ6AQJZF{r{{aOWI0h)r5UA@l88M=hC(riBcty0 zcx+Z`s4kEll+Mn5mw*-l>9q^C{3c*^TSQL-l4_hRc_`uEgM-J7M8q!NK1MR%>o#clt+@xn_mxiQ5deh^k%~q}WupZyC7072C&t7C{|P ztG{-k9DzAyHRCoR?5&tsC<#}78`vHq&&oP7d0>>xmFc(d^E}TiMh;}u(#5qBFB-so zsh43=jULSaXR;yuj#0TUz2}(sJ1W4yfKOD3!7Ybx6krSD-pgJ6dvYg`Nn;gM5gxw5 zl}#yy`~#_vSAsTsFp^mmRxUQf8#XqEYFbnR4-HiuqQ7!vQ*jzM=p2I%Cs~L55k>Sp z>;Wo>2*%8qJUE~~dB`XW1w*E@Fk0ta<^``!u)Fz`6;&8Mj#_Fegq$Xylhp@<6A>u> zd3i`XOE0(j4ueHq8k3wEPs56OHJck@hEivP_OsDAgZCeXIFm_1E??j;f_^3sA##PZ zcgR@RCr3vtuUiwH|F*7KI-c1>tk89sz5{#cRw25`QR^%4%YS#fBittI(etzhA8X8% z+)&kKazo()7I7dM&{sY`Huuw9`5xJqql!syc`vWu*+uJe!|CExTD+OJQQd}Ezo%u0 z2P1AsbA#sPfy4oQm%aGUm{ae9OWUgk^G|_GE`!hx-&!1X)w#w-jiI$MxgyfqhyXK_ zs=1^Z?%=3)r=T6YBD2A~_^mAsaKZU^cLfvwDFPT&Vv|aic*rMql;Xrg9&>ped3sPw zRB2ke@j*MfEavQ2@t;QXUyjQfJkk?gI38_=tdgiY-^TegZUVQ+uswq$!CHkIL;v>z zOzGH$SGZV3qq$Lj&bN1OJKc0zJV*chzR84wdSBgJghwh9MROt*V`UjpCBUmu4~s&+ zcdGx-JB%Py0<|Bsim`wmR}A4Cmk|BLTp9K10i|n9(P+|2aZd4)1};VV3r%e=XMXi9 z(5Jh*Gru+wUfYTJ^74_9c1~tAjC*RT$5qpql$<1$qe>CA!$C$e>bY{PKNLo1O2=?> z9;>xNC+@m1)Dk1RSH94uG=R!2YolkescN9ZNwIbEC`0$YIQYR72C_8Cey+`(!jcx( zkD|ADe&5SVZX%SsQ2)&ZSK*sxAw31@yJF2U^{PWY#;TRFGkoQzi%X}Ha+~%q8X7+o z*T@Is2D9k$No#gxi|cV(?C4A+^mq`%ow1lg;O(0>@QiT+F1-2sXJ8zspQywFKyGb^Mg{OGOP|Zi^d6MVPj6!3Q&gh#5RRZ> zu+Q`5Eq?o92cGrE$gb~-&XEwYs&QSvADOf1(B|C_2Ska3>3BWKAS>l|_^YBx=DXGn zYl`fmekSr7tT+U0)AWRIH2?DNBSs61XM({x!T;R_HE6lu@lUl?U<-&M*LbI`D_<;$YCKe-|!Cv&6=(WdviQZO=>9cuVo zt$k2RN>I>5gpixqX{3#25eJe41QfL=67+_dsuLQYP{fKfl3K~j^ZpbZ4`&!ybkZD3 zVTBLfFokJpQo0%J17$Hgvg@!)jw|TN&qWqL`Fk! z&#i??88jbVW9{qPOPP?~-voiBK|vDvZ+i54clYY&0t_EITaaMfI4b6WV$eG0Sc7*5C;<11%p-22pbSU&WEj4P%HASM~P{g{GuWFi&*dxUg1Ibh&@5O zkIa@RiK+IdKh&)Qe9;&Z4oa?lp{!C8kvGuhbznDHJ$Dc6HR*8TXyyk9#sHl|W+smb=)ruknsKA)mchk?W zO*h2mNc-73mxO8TcU^k$(Lx8h(gggQ?R6z}#*g@a%F)y4MtbuXeWMJfsOQd-WM926 zx=Wmb&(1@V0m{pmgq9=nY+%U6h^KdCi#wk(%t5^TNX$x| z+h`!ThxG?R>>sP^^&A$=a#Q2fI?;9jW^v@2^e<_soc&=fe5?uqB}ITItYOKC4zDM| zQNE(EEAs}-`$P(pgcm;%K(f32@Yh*nT3CAVMxMPKreCrOS7rdO6xj>p{o}`gwS)CZ~cAr76UgCrKi;q$rS1if5z zU1yhK(aZI9N%*PTA7K-c`VlSGMA>>YN>$dlbXeghzF5Ge&dAtD-Mz3*l~_|E6$s~+ z4K~e}-Tk(Xg;xJMH83P~RQ!RU)_}C5@mLErcE#`gI6n4bq^c}%Sfo;&0G7DuzL&Vj zKW^Q={Iz--JNDmgalmx_7HowxY$6jD+!RX+<7U0f6GM7SuhwFk&@cllqcwXRL59g_ z8SRWr_1#;2s8b3=)Pz7UqKkiDU@9pM=ET$9l^|IO3-?08#W;s9Z~_u#eM?)r&(q#m zX7MQ$e60g@cJ_1gx;@!@sL$Mwy7dN9^0wD(Ow;dFky6(&hrf>q(`Wpq#0pw>Xl^^b zySqDG(W*Y<`5?-#`-ypc0vPK7+m~;x`p_FjSl!1XoEkhBN%6Wl)l8Y(QAr6R>edgYBpi~|SzsPhp7I?vZ1RsPM4x~E zWJMAo26jn@<`w&urt&hImjCpf+}vypH^3ILzqq7Lf+*_&vlSiv!}(94&mPcdkD#f_ z|1;$9piNQ~1gCA2a)Ft+2g&~-KeqR4-OAf7KzaZ3fU}bqnnYsBBIBo{hUJJ6z2~5mUHa>nMTR!=<%;k(fey^GmL?0 z`d{y$bUovI`$w*|)@Hq80cwm}V0iNc)hRO7e0ZJ6%G$%ymB2|z^EaZKQYxu5>ca_dk7%D;Q24lWN-VOeP3N>hESHmrAXy`O!m6OHZ2&Ck6IO# zo{_aTB*OLF6|@>@_j>uY4h`Ag)2QM_O&QDgYb2I#DMSrz{Nt2zwjs?D+tt(1>iNBT zw)Wer{1XF>Do1cePgZ%hi)QKKxB~yaGfg%sNs z@=~3ds)!U{^m=yT;_qiG%>gB*qP~_uXV<$NoNqLBfom#8*}h_?qgE~vH!q8n4DTbX z{o!n5T)1rVX5i;Hl%^(1OYwvthY&^j(D-e6o$K#?VX*Hb^6}X65v*4Z3iXLpWGDfBc2YPwV)>w=oE|>;yj)BixH!1xqXtDhr6?X+Um=nFr}VlOGFOIKvn3fh36j z3K@D>v9){K>dFcrV{x=F5Dge|>ZBL0k9sB7X4DS*99+8~ISsj5 zuYw6|ig@yONHP~|)Df&9^W-R~e#*o$F1*5az!g>kBWDay1HBso$Nur|S8J4ElFvC4 z2Uy^;Qbm+RHY(z6a&{J1Jmqp9to}OlDry#ZQ2%GKNgMe7LG(08M!2+#AZeyW+iK*6 z2^#=fb<@XhC2N;e|E>&A&rooopR%AYSHyM`ZFOP%bm3%2WIFnl@Mp|Jh(8uha%LhM zPOK8w$$8{o!Zsa(nMYbSY7mU4AaT=*J=j<{cfU{(4ORNz?E#~7y(BWio`EV=4Xc>x z{I3B^{Q!vo^)F)iW@d8{mQ&iYNQueb13moMf6wpTGzcXZiql}3C5g%2Y%-B*I!Wkk^@s$_8RHF#M2B3cos{tJ z)6EG+lVAH4!e;0kJBfU9*Yb+91u4&Sntg6FTpOo~znm8L(h6KRV0`rnB2Z#KAX*?A zXHAF_T9YX_()msq*#e*#+?MHN?f#qII37{-0Gb>FaSQ>((`d!NUqMhrzq@(kj>?&% zAF$bwx7~rofIz;cbqq;WTW-TNui|u}h`2I;2hlq-0*Qw!CBC>ZL&mud|IPE@1N9Hg zWF$g95grcQirJiUhHaF3U>y$|UMc|aaRYuk>;TO_b#c^fx$cL9l3#mzXyfPW>FfDo z)2)-S*1yD7|AWFBO>_Ue&;Y81MNG1+j245!xTc1d0*5U>J3z;Xm2owjXx;njO%Im2 zG9uP|xm~}i7epfP0&#vP7;XW|Ubgl^V}^mzUIun3u3H~Rz|&>B0C@gdE)-WDtXg<~ z<^f&^pbtUwzt9J)2@0($Xflt;%~I!aBhCy!PqJR>B&C5ax8n-v2mmX~;l!0&r>+pd z=y(Fus4MXKu<6#sF*c&hMNju7?--ib z`ij;OSApfhwZ^6hsWD3|LVewR!Z3<8Io&lrb6%lvO9nzAVc;%T*e?u$EsN z;zIlL1Ns7s=o61?=?EC(U|HckI9ZBYv@O#~0%b_jr(p~_Tp4Jz?+kK;>QN>f`EurJ zCJ+H}=F173cwB;DQyGBH)z(`a+4#;BPqYopW}_&))6B+&6b0BnNDus|%U3G}#eVB!^EQ)^Lr$gAt8cO-@yp2?-f zJ5n%fC^)irZ6G(4ZxN&+A+X4v{l$*->H>}p+IV4p*TKlZQO+TH1!lafw|Vq5$AhRB zg0$~7Xsi%a--Ff4ry;y9GE(YG?%*N8GI{=KzA}&^$pmQLODG)zlR-x-AE*3AE3hf^ zwU3rZN9W3#a@{^gn^Bxi4ppj{8(NGXIS`R=@QM_S4H=jek&oz5X21U4<;ddxy+<@P z^W@K3%k)v4xwHrl^rvHe@#b~*tJ1}x$v1>7Yc!XRnVFX+$RSh+ctPC7m49re+cnRnr zY&cw7++yju`yCZfAkk}q{l<|4zugrOyJvUR+PU>%w(#&9PO}P#LVW$5l?5nhmtJ0+ ze(5o;0P4P0S1^n4S+{}Sc|^bLbDVH2HF`0O38}-J)7s*+fIqj>ajt;~#G)sg!sFQR zUZZG+X8nJQi*+ayQAJ?zf+Z*^Y%G6HpcVu$vIP2WaCUC}2S~G4>aIASt@Ih2od4q(2{*AhJGWuu(g7AAz2XY6vH2nXP~b#}h{fhJd=2zQRwouh>0q6I-jer0Ab^>>&gnhj&LETv?_ zLm5Qk0QsD&j#?ChzW~sGetf9ns?)dQ!bbsmQ#*foKK6Yjs$Bt|;Yl8B%&CBrUD^z@ z3_Mu$wCMVJH!Nn_4g@p^b7x*H-LT;V3W!|AkHk~@FU|b({N>XU8<)N--;l!JrYN85 z1%C?pUkPZez%3EHJjFR6-%w{Z;$44h26t7Gi&O{A3MUYOu3-A zFQwE?|J1i?$S*E|l8sIPdqeK7t!YL4nJ_%1RASQ{toH!>4vkO>$7)t@F%cjkdTLoO zr!W>I=z&ySn31XlVa-?(nZf_Vz;v2Nwt$!R)Hoz?px4k&=g&zAn{%ath1dPD)GxWD z1=|QN{C|=AR`Ce^aQ^d%YFra1%sSUYlRA2zk*=YRd6ElME#$_uqFh@>paAm!D zgYo~Y%MAg-nS?+3E7@Xap2GL^4QNs5P|z}+-;sB(uf4Uc`FQkp#DA+7L1j=z=tHTx0+@#&_a9kkF_kei=YKKCBmQ!MnLg$+P#^TRGwj#Ry>x+F|Z6cG9UjslM>|B{QdFsym=vGLb6g#CBSxn4AHK;k2 z5kZ~1X(IL_DNx1BP$HTPBDmKROI^L%J9cBeM*FtgP8u+k?Vbli0kX- zLz0dvL-U;#N%I;OS_?`FjNhn3s3JScqU)~$`?OIwm_w`H*Q8jV0 z&8tZs9PMSPo&=G_oARN}T!b6nsV$~yS7aDs?;ZE>3%8yfCajqv0pY=L;r?f#cLo0# z@!<~XcS=!qQHy<8tZP*1lR=1@$EwED6+09dv-7tIYCY7dKpv?7QRe_}#!Y~vyCQVn zD!+lcHssTw$%qvdy56LgRy!fyC;#ovQ&jeR41KJuGCpY=J?C_mXlFTz;LJl54{;eL zPD$Ac-wz`q7?;$&@ca{ULVV6OoNB~}G#kFFKR)fC4r8V1wlamWA4R^G^;r-~K^(7H z19}owS!>6T@c?c(}1KHPCRez8wVm*Uj6*EhN;_&fUY`)2>6GDvgDh;0P-2 z_W?K9B`)lS7bQ0qZqe7?jy_nTdav|Et9fI}=gcIea7Seg{(R2;0+pU$+!z59jxrKX z-=K#4r+N;=XI$f23rGkZ+Ix03ceb{6Y#-l(MfmxIIz9cG1UofrfUgh%Z84XgG}4B77>1%CmoX+^dB@P%z0>pU(a+i4+Z*_^&hd8heK=nO zo(kYV-@W*h;(>jGChvvHmL@@$4lPAHMc=h*#!q|gW!2*d|Ej181C_`!fIc_Ki_HOs zAx&JqB47mzvrALOh*c0^SwW@rz`^D*t7V%l0CJFqhTs$j;PzA%kkR$9RHb1b|2G(U z```5dGH{#xtXpoX6b&rf8%T~mmf+hY$4ST!h^VQ7h{W5-4l(#*p{$N+Sp&jiK6=4; zJRRMRBB2LY3ST0p`T60&-Sz9YZESdl6E=XOm&SRyinXMEe5Z-|mMyGO!h@&m&GeAU zy@SvZe~RnTv=)K_@Ly?XDGiutju84)lNdy55_>eVZ#Ypk*x~#2G&F4oW2lCk*v%K@ zfYx}URhJ%XxkEXTgXf@3imNjTV!eHiEeg&b=f2dK0iN}VYRKsvIV!P&MFFVO$hp6 z(o}wcAt0cMUfb_jHd~fW?ojQ9V<@+~M8AMU9uq`P} z7(PWZ^ES_#+4t4+M_GM(8Nct1hyM4zrm{2&8wEQbTx)GAHWg==BG=4?HMDhffJ!bmB1)P(+Mi+nLnKD zmgf}OAhJ1*7P$XLsRt0ht$XLz)>hWmz<=`5CwF%M$PWllGo+pkIXSwzI{P_lt^B_R z7rEqrw0bORjVN%$xD%7QLigM5AH*Oasg!4_37<8&pTZ&1k=9Q1i?2xI-=g6jFnK#A z@o~CJ5cIm@Q8T8VhW!_qMT0=-gx_EHy3br(u3rH(yU|(7v#jRo>H6zGEvR{uml>TD z%b>;u_Z(08UZvfbe$@PYd@5Pi-7?kV)O3x;VfEf$=pp)MyVGtG18At zox1B@4OcH7C#wfre9%*uR;g9Y`YQZ6(|*zuB*k;X7$9LXa=8o84C6CnX=ZnH@pyfQ zPTa zYdw8@ssRo?9og+~haOFg|4o|zH=2@$VWUSPA+f;<`2jaY3arKF8shg&u&d(Mi`eje zyPgf(rx}GA-5tb_UNFiDxr7M@J#|y9WC%D!Hw`_C0Jn;<;|L_OX%GWm-@nKn!M`fah9-@3Xl0Y4wiLXar- zmdk7}#6u}1Ql14$Y!weYl~N`2On9SKa7&ktF%|+AIvk>FRbVlf^HfkH`jqj~k$TAz zOzZ9HfsBTlzlEJhU;sj$G51tTmZ(q+Pb#Lma31_4p%!CV^LG9JwE$O~73m!W^3f;W zm==+FcjB%bvWfYzQSH!+X!&w3Kw?JLLz}&j-^cC#>!EAg#)Ftp9$*^=FvVGC=g=WA z`=&iqQ(GmOf=H>TP<4l5+u4J`=g?X{W?O4qm(#nb$LVK$zYj>Id)p|3Oygj>ZW7^{ z`MTv88lSevNN%kT;oGjmMMj>C=|Ji7k1YV{C2e*NCu z(e-@)()n^|s*VB2GQs+&McSXoAu9uNu5j5*am+3g0R=rlfTuEQ@JIZyAW^g3I7fcl z-@CrOeRuHx*RcjBtec{-vO*-}*U`~Y8Ob`~Y#bf;MC^aEP=Po>;!1nA>lgwsPr4xHVh&T4HZ3fsHd%a89G zE5WED0*}EfDxPWZh=J?NxUxps0{EF_`;6ZV0gb&opLsrQKc5-;HuSfkrV2WN)XvU3CvZKRG3 zczJTFq61Qyg7|HiFuAyTxf)721T!fK3^jM5+M-DTv4=hAWQtx^aG>^zFprS6==d(Q z1uG>Hg3d$>IvF%FO6d-z@Sxm){bvJBJv(f`uSdV9yO!$=FxG8cX0_r&(}ikiVMr)3 z{x`A#V3>Mb*4v(c{E^9^8C4waIn_FNTJ(-m(^Jvdnq`rT%!x~xm;09RM+5J3X)8?! z%mPwsPml;I(G0;!w2iiO#gk~e-|HE<;d==2jEbpRb#-U$S@G*O-l|#;77)G603fo=?Owic6N7wKaPcJ91%n1q#_z!BG2) zDmu9{2nvnfk|iK1G29@_gQQW0ecbw-1||k~-DCbx@MsoOr2~l!bHT7RZ6cbj4a2`* z&1>*q_dHzOh>b|A0-TG^D(NF3l20#$W3g7aJhf!QY5P_z7oin@R363n2&7UC9OFlk zh_2Sj(onYQ0%KWh`0s;{nl?V+MQsM`JD{$?`>CO_ik~T(1(Ykzor}A@iy!kz=@%u) z+bs|_#(sIvBP#yTZDD3Im}k`3Hv=UV{w_m5-JGam$t43im5U6;h$IZ{4Uit^DeYdf zbw9iKXsg@l_IcSGAv$Y(^>BZ?Svc-g*jZ}I7;~yYjJ}*pAJ112y#kpk8M=iNG%4~d zJ{ViT-lo5B#SkFgx!^^uvEU|9#OuafI$l|)Iaam+6Iiu=Uff$Si&?j(j*iY`rL46) z3|b_#vFI7T%58)mh2uYm@>XWjRB)7b+qk;3w3U^W?km6~`fw<(wc>b>ZiN@R_eLgO z8TV89Z(<&j*asCZt_Rw`zZa0KImH3vyeyb#bHI{|2w6>6V~HMCc!0Q~FsbIkMAF4d z8Y2=vUsdUVPsQ?+DSS>}v$;r_XA3K-LYTVRhz_ZyDNbSL!A3A^2J)1`5z+&u%;Qsh zqF}HS6f(ICuEmA2_DmR3OZ0R$=`k3dzN8AlzN~G1FD!00vTVy~O{_hIU9Ps`TCS>; zl3}3VEXm{Z$?ahX-=*JcUw=*iM`73Oit0YTvTaTdCUs2H1_LIR&szjkJ}hL#r0; zDYLtd+VRG5hyYo=btRV#*zA7Dagq7zl*ivy^=FZkTsW%RhB4I9{5$C4$J`Ek>>D@& z;TNh!kSYjh@Ug$Y0GySpHqd{(sPCI$w`Q`b+JTxn#yW zc0T#HglmSk?yG8vnmRkX%8tY(@GcPHtj06~b7P#;sem&A9NguiAr5q7YR<)L?MX*1 zK7E2I=Q@Uj))MecYNgVJ>H=h({LUjF%${mE`zk&;A!@0M;i-pVnwutT8Nfe-Dq>xd z;v}Xpox$(#=lfFC^Gf9Z%Jgq&YO97t((>D03~1D1@B^WI#=B>fq-%3W+Tvo?b<3@3 z?V^=QVJ3X*2Y9Nd-sI_!k)yBo&x6o-e}w?e`F8wHkt-q@qd<;ZB>!*-I@7y)4eTxr zLqo4u*#)Jp(<3NZL5BL|Tl#Zu&vtTzotE|`8-T+V=cIe+Fi^o|pcq}W51 zd3!POcuTp-3|K_gy3sj5LMTEsW8IzBGaxza&M4eauny>rH*fki*4RvIlouW>Q9`081&XmRkS+*k+;Y|m{1B)`-4h;Z7V13V3*D{wlV!q2jP+BWV!8P%EJ?k^U@ zgW9no@|OwzK0xdeTy3bEb%oDMl4)|s+-e|x!`Nv%4x;j9~P zthTC|f{p7nCPcqUWzyxa%AxAg9zs~wCZ*~$mfldL(z{2`_~N;i&KvPtZn2uAUoc~f z@2lSUvDYrwY>o`YagtgF6>LE|`>qNuU$&^vwmyC7$y`$2cM@=kAt()@LRWEHV9meN z!oWgTayvPB+EHEENZ+Ea9Yq;%E`7qCh5 zRuqGN=6I#T%3DDOQDQg#_Rj~)yXWVNn@<4Ic5K+awk~O7n>za5?IHW$#ie3n(@wna zE;Y=RW=t%i`mDEy4*88yPWR{wj&0;AcF!j8IzBGJD9?67eGgp5 zruV>0I&3RGTJ7Q&>fsl%<;0iLIUF()d~8fTLdOQ*iB$<*`+x3`b|fdRWVy2kgrvMWYL z4dNm+qx*!lq?p8XwNs1heF8a;Z9K?%EVO8NHePEANC^mA2Bkqq$oK?ihZ03Pvu&H! z&I_z`Kq?hC(jJe-Ol(CHg?>L1fpEsI7I7#`OaaX(WCg3JXX4Tq{y)fV^>KS zy1(FHfxbI{18{Pu;$`3B z*&)6xv4_#N%oQukk*ts=ySjp>G0n`p?SucD@c+t`y9rwA1Qv+kZqoI8{_FGvlnXBR1A*(wr>XobwGBeuAyK~&V!Tw_O6QYNyp z+ohJxoS#+=a9{T$x-9#(U>O>?mNZb)@baY9rWmB!xln|@{g$cRF zHS`83XcFd#Ry>|Lgg`W=76Z%vl3f_c=&dg!n?RC>tC%_9H8gA5zIf6;E2OThtTew{ zGvfJKecPodtK}5?L$U7uP$BGGbfOzEJj2GKxk2$b`BKep z>e&$8HdxmjNBt^B9X-V9@cWxtY76KDzw)72l2Nx8(%%7Y&!v|4dyn6L*tlDA*dPp5 zvvG=2QcvRkHph;Hp`=Y5{tS(V+m&WALO0df0d8bqizp~0VAuLH6yU6}nqC0O(&-=4 z8RrXUw_P1p9H~Mdx5xBJqMaQ-g5zf14vA6WZ2Fk{l z1Z*^ab|Fn;V8qXDn)tf9_mLS@FW-Lqlg*w5#~q)#6ey<6y(>j2MZ|%~n`w8ULe=#+&m{93VpsX@S$S*$Nq{oI~;Ih=APhw<${3t61_(w zQVd4Ku@JNRWx}|T3paRB(+mFuD`}(PH=J}OYPLBkSJqW|tX^`nF=v56qLU4Szw@^FpuhdVPV2G7BUUBmXQ_QQ*h6zF3uu+B}9|oW0)O7SczVEcb!Rz6Bm2R#~zo zqH@0~3^DaZct}pTkRF^u>BEs(Ne)pj!U`eab(r<&&5X;MXMEAK=eirR;>==cS{_bJ z^XI9Xp&YUBJ&pV#HTMk^kdH}CK`S;>1N99}I5~oSyxx9zDmfq!Gn67>&fgGrRhf*<); zOEx|w)&h&T=_Gei09p#0A_90&zT}VnDD9 z3qxZ#k}xr;K9#yZ%&+fV`1sPsLnwb40eax`Q!iWRreZZRApl9fAe6}Pz+$xW_%Rv2FZCf1^5SXIh1H>|Wx=riVrVAjHnBLl%ldLk$GXz5T#fc|OqlOV`(Iua1S>kHe zUtvc;{Y!H=Tq{COxEd-Rl}Ac<1yPKtjguB*uB?lj8Dvs(_Evkb-s)-+!|7>u+L%3K zZmN}0I2y^yL^pO7B`T>8LJq!%*~!+T3)L!ZQAdI4ots6_8zlaL&jOt*Dq+H5e^_M+ z^h-a!`R+U^r!%HSMJ-k4PE9nj%YOCtjOWc$(@4TW3|;sesxE~ix9tE)hu9h` zrn+=F=yYio`9ASAqKlD%BSCZs?j|uVlNj?9V%V{xygYu-@%jcNqfz6l7CE>{_`%wy zTBXgm=sq_=GJ>UG`tQnA&XCxMA?343AF~8*St}1`6Mj8x>zlgzJ6pb*lh_&a^WPFa z#er;2G}X{3L>1*>muS9qGGTB-X)?3jZa|=|r@vxdvv~NQu(E_j%Vm#m5Iy1|Lz9Ok zn>9`r4Oc6Gx1v_kKHk2hqI?zg=hr6Wck51|Gs3cM2Y5BTI8_9FO$B8rZW4#=f(RPO z;woc{wS_pGl@PF!{~`o_xf1eMj1)^pLsb9rQJZ}ar9|%nU4x z0BNPJPTI%Uv*1Hb#Xi?uOs1n*j!nygo2I)n@+^@TXX;g$?P!q(%1 ztGYVn48e_`zk#tjHuf;i3wJuMR$$#e_#8R;)~X+D>>_clTVLyOs4~L3c~OK<@Q0%W zT?t2lD0_aq&nld^Qdd`g%k%NS*PTIgE~eW!r zLQu{JgcY-$5OMMzbm=DtN3m)eIws%3`>xq-1T+4Mz+gT}GeL-aKD)EtL!xjW(|;B9 zLVNrgAc#VC^OfR2vVbIL6x?4_S%3k%Yp4&fezt8~r1!lf(~P;Mk;TI(j4j76(PWN`A}6+xVAjG8`5MpJJh6zl=|J*NYA`f8p=B*j01 z9}LS+q<6TzRVghj+7VPjOp%SL&}s;fu@}@kk8oLza@#mU%sv_!mw~zV*qYUvuZ%_@ zD$K>^MBbW!F(k1SyOp!>H+$r#9e{cY@6KC#2v;Dw67&Tuig!`Ku?H&7Vl`E*1<@fe zz!Q~!ST4WL5@hhquqIg+$yY>6vhT9VAKE3qsguq}m?p>()a6nSOd_HAw@|D!+v+UH zr>2;mWPf`tI9so^b$|P4u*`Nf)dD61>i?okyiyM-Cs>Qrq7|sXzB6;D6(0Q=Cc-{M zmsQ+EDUr(63p#kZHTKGDC+KcF1Ns{}T7jmbvj;$Nl}Z1T@o3^ux!%=O&C5{OXLw)< z$@-s5-XID%!BKlUH~3EG&F`}w0aVc#Y>1stg#``s-Mm#=ZmWOWR+Ycc1fq8Z$n9;+ zBm<5d043~<0Hpn}f5nGoXWVb)-pE5XA^fZF4PatW`3=Nj|w@0+SKC zr*3yBj6&>BsLL^FLQOES8~vAU^9I8*$+y5ebGw<&Khr3OmMMKd5+J_Jdbeu>$cKf5 z1h@T78`H2SfaP{oRaGVZVRHp(dw-|cwvEyo#2MoBL36JtRE^@8ll&$-0Qo$T%U_?2HqJ%6!yX(hit;c^v%Gj7xp<4Q@GZJvLU^E zknpRqnQoAta%6T?q&@Wg)7KzV=+MFfohj_Qj{cL@XGyMC+kKu8B&^(%M70j4zwv{3 zh?UW!7TH&}v^9#5NljU4X&uy!g$7|Cd#eZoOH=Z>=E^o+=y-3vEQnq{nkb3klmbt0 zcE$BICLi|^M0z-+dA?A#ptSFk6tdQ;+M(ifU|@I0{-1T^FheGudIywj<2c5wLPo^o zbR+skX1MplHjy6h;a|^D6IvL%kdL$F`y#w1>q4D1w7o{YtBlCs=5piclkgIN$T>VM zIt^iN#+0#5c^9;gwJ!U>8|*O@3ip@qF|S@mh^jqDl2Z;V93fUdTMN~>vY0d)}^!@ryPIA`&?8Y zF#(q2pRcUrSw=0aXcln!Fce>DoacK+S;407x-{v)->GUI1_6TLFDtyNv*$lbixvJPP`vNvqG05Y(1 z&8Bsu)UsF#SlK?D+#LfD86$LY^Tee$!C2~+*qXp~OZkksR04SbY7Ub!^cdd;frn3w zh^muv52ViF2x_f&*(}D%hPWxV`ya7id5UgIR)2yC`@6c#eZ$(A!yB-nz&m) z?)kW|YvTfOwYB-*&V1hgx%J}AGas&3Zp`D6)}8XGUFJ{o5Id+%vO#8?UL@@hUl%+l z``wc2!&UNyrZPxNkrv*%2Hx_ras7Oqj0-~1w1ikCJxh)xp$X`bxw+YE-?6T-tF7yK zyS(#hi0_Q;|6-s>cp<e)oIuPiOEY;mn=?5u zD!FjvZ%>^9Ntem|E(RrQU3F7Av%MQnAy{#|oU(}Y?=etGH*#q6I%Kwt)yR&Z6iJ%F z>+g8r#L~G0aoT5ltK8NsGhIsHiQR1ABKd@oAdAL_XgCZOXzCC-aEk#jr2THFxsn5d z2!x&SwRM@gkT5@-(IEuRJD?#}$>tl+aW+0d5`OhJXqZ9*aj0U0zfGv6%=f|Wi%syQ z3_bVwMNy=2pX1K;w=aR-P5~&srS*&hScG`0t(Xrp%%FC0{NQzqno!~Llx4wTMmg~T z4f@~4U`}2~63Jayn0dGN46yEkZb!;bt$CzHPPr7d@B8w%F7eJ{3!DS9SMGpaAFQ2v zyph_@uC}TXja`~Rr@L%8MymHD1|Ci+j_kV-2Gs4M4M0&j=_^m7r%4;Gv@-CN$=5c? znTCy7mc($5U#(5bb`cxkg0dl(bLENi2uhx>+Yx9Ym>{8L2p>RLamS$s%n$*+R}Xj` z4T#W&j8bX3&shmtEG$XRt(LLjAAU`GLYw~Ho<4-<%vF^eSy}q;H&1OVZ4XwKz~1pL zaE<4(rm3}ow0===uMZY2h~WW3ReYpti|CSw(C_nZCo3&f0n3!fWc&tMnGOk>mKTis zY`qlq3nouEEv0_ZvZU#+z|Dj5M z>KI-`88(GB(7o&B~aXA~9i`?(zQ#4w_=*w|3^J^ahTzF==;_M1L8iJ7Fcl!vM+r;I1 z3Di!-l*SlYM4#TtU zU+rk2l$p@m6%czpij18w;9e)B1wk!ij5Vw_s+71RsqM}`7^bPZdUI1o^?D z{H?ofIsyS+G&x9eF~6BJV_q~yH0D4j*Ho6~`vK9oK}ha!X>_i;W4;s;6m(N`kCGZ1 zL4?Q%zd8#Q75ssW1_F*|=5_2lO+OBq-C;+q*y_=u3IQjBf){=t9dj-OO1cb7`9XY{ zPgG)1mk5m_GzSg?W-gp71({|@?76`Q3*Ns0f0pInKf%CIMrFiBR6nnr1iY+kTI8?> zpU(KGi<&)gysSSEtaUmeKQ%Jd(7Z5}gv~qF7fP-PG%mUVz$oO!uG8lqEH^lZ09MjG zw7FIu0}@y*@*%w+Mvy^B;bRn|3ln1Mk>Ri4OYme%{#GJ`d*a6XI-n+ui}L`uN_;om zrhwvr&);;RK<*{$AozsLW3^4^AiWcatVZ-)17rSzz3uTA4P_OBO9B zQfgtCn%(M9A8Ah*mo(~D9Kdn~33y>O>DnWOlY#5%>iNCi zd%6OFo{k)OO!B$lv+eMtJ-aASC3PUf>~Qzo9Yq;xFxK` z#aB-2J;~VtCnecNGouqff+;f-%gE%>rNoPx{V_>G3ujU_5MpIYGYLm_o_u$BtP`~G zlgu-S>x>H6ayL-PjO8T#oc3A3c)0F?$r_M5{ztXEuDj(-%W17lEFBIVKKKYSjVr&- zCV68@dYB#fQIJ^QR39TB-s}T;gL_TtiCwc$w`u3DPF{)&cxOKK?yTs=sHdDpNk6&? zl6>hFoYz^w5pf*yog^2)ek4G;{ZbAS0e{$X{JZ|)_w@dLe>f2rr@-V3h-MiD{oZ|^ z_V%4xlx2hKoJ<}Iq{G1a`m>5dv*ozwHo#`krOS4_Q*nSSuomoJq8&jJ1(8ND^8TU} z-sIo))TJxGZnV5zoGt7REDU@wuL9G;OrDUgp5BosxZsvrf0Hpqz5(2@NZyG|EREkX zUP`J-GM7^!I4Vc|W~lE10E>kL1bCgQCYF|#)O2SWtA$Y%z;mxy^Jjk_YAKqFiA9R+ z-XsT=jm9ORlDyufaZO&dc8-jUJlstH?!ToeS3L|cVMYW!N)!$bfr8qc=#2`>KTJe4iOX;Z)+1gXbpsd%f{FNpR zd+pm668s-RJG#xs!!U0Y5xkqfCm$0yC-FCtd4pR7rn06@ zVKg=*K4%gXoS@Vgqhx3@(i`$guPwD|*Y@wu{?n{}T3h4b#i%=T%1k07%K~0F&OHjP zirZR<1-aDs{9bV=L37w|LF2|uK0E`3zAl3QPL&tSnKhY}5`8+u*^L-)^kI4p)`t!p z_YKOaLQ1N#8yVI$HRlV{aiQVg2nw#nwZ25x-g0^MF=2MLyCM3CXk}^f)+^l&S6g>} z!p!{!YhLq;E3b{8)?Z5;IIGO=yjpbBCM498hir0FD0rw!4_*GHg1)7|l*2NcafvEM z%fLf}fVlo>#wei6yb8s)1S8vC*WBAH-}!BuFxtbE^v0Lm-kRViK zyKb-~NN8%k0LWZ%g#cOHn(xMDt}WH(cUrd55oAu5RbEit>~uBX!U`_dy8+4wKg%APM&A*GuF=0kooD2B|Y-npg0A6GR<1d>G=HWJZ^m*6J1^MhwYz%Onb z0g!#_?C$mO<>cn(@BuT>-VP9AeXb21+VW&sCV9_@L?($&?Q^34LH#YbCtk~`Rims2 z{tUTeX~X!VH!Hw+iOKF~FBA{vUKE-|QM~Fketx*5=tk?=!`;G1+r?`O?d^XuYGfj_ zri^(!@>Uv})IwSWlpxV;9Ma)WIdutya{~nM;^&_p39!K}19l&;@6W3b0{{cG72erJ z4=e<9PPgJtEn9MCh zT_(AkvQb)aA~g8#|0x-cg@;bN!EwT2VPtVLJx5g(O)sMS+B zH&j1=8D#y7`JOID-}ux38NQ0JZJ%F0$aZAbQ9}1#&V@JyI8K9BqWp1E|uPMxiU9%K(JSSb1J#zpQ*X* z0ODPFoJdt3_*~IaTt6=cNm|gEUCO!$QeXn4N3wOVOHX7HwKW?|nZ}yb3xMwC6<;%(7VNXoE((~3^rb`rxv>jsFTyxO$OD*>W5kX1)R3s%DWIx9KVd?A=w3r*;;5mPEApOXjbojhPPg4&@JQ1C~1lCYV3vIE! zY$B<%ZCJe*TqqN*Oe*8Fyk6iATz}8gDT_acEo!2db79CF1Mv#smnU#hi=ZLFQ+8WW zlI}iM!)J%v?Z9S!{-I~{-AQuhoe*V)9^U&_^mWK_bXFw^?`-fkNT`5*S7o5lODt(5 z0PM*A-=lqs4TFRd=1`?h2LFnr`LM~l#UV%h!ocz9!S2EO$Zsjm6X)7epUu=!UU!?0 zfrc$06nLQFj5k3!MIr&)Q*9<$B*|3U{DurAI}TK9@hWC~Yb}j`e<4BWhS#t{PBsi)V{a4*U$qf3HFto2aj_oNy|3;@xq+ZuG0uLg5inh z(3uU5zVm+!w@J{OpH5Zq%~MsdP($aqy(Rj_@DKSlgGDQJBM2r7krEf)Zeyy0mCxb) z-muHfy&~%I`|aQd4tvcYmwW|K}xG*F+Bq;Cv&R z=)~fD@%szxBrt{_RIvM^*fp`}(h!gVbCGLqQ;z=);yXmhQ%i@3?mh2^P7Npt<<5gF zH&Cd(a}|I1F%L@45x~+Pn+vz$7buU4@n2&}g2D|g0F&t38_*XFpw2@zvqtiBpG7O- z09`6O8bY$@GWc#7<(+HQ92QE@51C>gH?1A-91kyk5zFEA2^?o`!VFm9eG9Q`Fg>^= zg2ga4uxT(_rtbI!8dM(Z8Zy!iJnTQtN9F358=$sn(JhFy0dskdK+b28m&#@vC}WQW6dMNbeFvhQkCH$=(0bo)I{;JW~g zJ~OWKGbVqtEdm=Wo%qHRa@>yJdyoIq;mA&R7eC9dnLNRdF`*opLJK<8G8U8On0>J$PGOe`%&_J3&v65xmAE(lja_Cf$w3Ww5gvk`Z z0ul27ObDormic`u4|;$7IzdUqk)qZb0kzOyM$`;JlKVF4hXGjUEIAwQJrja*oBjUb z{@c^HFWyfMQ|pUp5E#9g~fJ(APqt^VVAI-Fro!%=aK&M#3|4uIl@bvWj{P>`? z{`BdSSl5Y3O%5KDvL2mlfC={b%^;(5!qX+{&ByIDM>=%N z&XJ*2Rc$t#*eatiPz}3(8mSaFN(9u(>u;5~upLWUB3MVxQSYpDFdDzrJ8}eod6pM> zZn8}DeA3F7!**(y4o2x_@hENvW-(r Date: Tue, 19 Sep 2023 09:30:33 -0700 Subject: [PATCH 14/31] some minor optimizations (#3821) --- nav2_mppi_controller/CMakeLists.txt | 1 + .../critics/obstacles_critic.hpp | 6 +++--- .../src/critics/constraint_critic.cpp | 4 ++-- .../src/critics/obstacles_critic.cpp | 8 ++++---- .../src/critics/path_align_critic.cpp | 6 +++--- nav2_mppi_controller/src/optimizer.cpp | 14 +++++++------- 6 files changed, 20 insertions(+), 19 deletions(-) diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 4abc9c7454..9c3e5f6fa3 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -10,6 +10,7 @@ set(XTENSOR_USE_OPENMP 0) find_package(ament_cmake REQUIRED) find_package(xtensor REQUIRED) +find_package(xsimd REQUIRED) set(dependencies_pkgs rclcpp diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp index a026b0fb2a..37e14cb02c 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp @@ -54,7 +54,7 @@ class ObstaclesCritic : public CriticFunction * @param cost Costmap cost * @return bool if in collision */ - bool inCollision(float cost) const; + inline bool inCollision(float cost) const; /** * @brief cost at a robot pose @@ -63,14 +63,14 @@ class ObstaclesCritic : public CriticFunction * @param theta theta of pose * @return Collision information at pose */ - CollisionCost costAtPose(float x, float y, float theta); + inline CollisionCost costAtPose(float x, float y, float theta); /** * @brief Distance to obstacle from cost * @param cost Costmap cost * @return float Distance to the obstacle represented by cost */ - float distanceToObstacle(const CollisionCost & cost); + inline float distanceToObstacle(const CollisionCost & cost); /** * @brief Find the min cost of the inflation decay function for which the robot MAY be diff --git a/nav2_mppi_controller/src/critics/constraint_critic.cpp b/nav2_mppi_controller/src/critics/constraint_critic.cpp index 4dc2bcf1de..e9774c7775 100644 --- a/nav2_mppi_controller/src/critics/constraint_critic.cpp +++ b/nav2_mppi_controller/src/critics/constraint_critic.cpp @@ -34,8 +34,8 @@ void ConstraintCritic::initialize() getParentParam(vx_min, "vx_min", -0.35); const float min_sgn = vx_min > 0.0 ? 1.0 : -1.0; - max_vel_ = std::sqrt(vx_max * vx_max + vy_max * vy_max); - min_vel_ = min_sgn * std::sqrt(vx_min * vx_min + vy_max * vy_max); + max_vel_ = sqrtf(vx_max * vx_max + vy_max * vy_max); + min_vel_ = min_sgn * sqrtf(vx_min * vx_min + vy_max * vy_max); } void ConstraintCritic::score(CriticData & data) diff --git a/nav2_mppi_controller/src/critics/obstacles_critic.cpp b/nav2_mppi_controller/src/critics/obstacles_critic.cpp index 60383d00a0..b922563597 100644 --- a/nav2_mppi_controller/src/critics/obstacles_critic.cpp +++ b/nav2_mppi_controller/src/critics/obstacles_critic.cpp @@ -115,21 +115,21 @@ void ObstaclesCritic::score(CriticData & data) } auto && raw_cost = xt::xtensor::from_shape({data.costs.shape(0)}); - raw_cost.fill(0.0); + raw_cost.fill(0.0f); auto && repulsive_cost = xt::xtensor::from_shape({data.costs.shape(0)}); - repulsive_cost.fill(0.0); + repulsive_cost.fill(0.0f); const size_t traj_len = data.trajectories.x.shape(1); bool all_trajectories_collide = true; for (size_t i = 0; i < data.trajectories.x.shape(0); ++i) { bool trajectory_collide = false; - float traj_cost = 0.0; + float traj_cost = 0.0f; const auto & traj = data.trajectories; CollisionCost pose_cost; for (size_t j = 0; j < traj_len; j++) { pose_cost = costAtPose(traj.x(i, j), traj.y(i, j), traj.yaws(i, j)); - if (pose_cost.cost < 1) {continue;} // In free space + if (pose_cost.cost < 1.0f) {continue;} // In free space if (inCollision(pose_cost.cost)) { trajectory_collide = true; diff --git a/nav2_mppi_controller/src/critics/path_align_critic.cpp b/nav2_mppi_controller/src/critics/path_align_critic.cpp index 2585193ade..795f166c1a 100644 --- a/nav2_mppi_controller/src/critics/path_align_critic.cpp +++ b/nav2_mppi_controller/src/critics/path_align_critic.cpp @@ -88,12 +88,12 @@ void PathAlignCritic::score(CriticData & data) return; } - float dist_sq = 0, dx = 0, dy = 0, dyaw = 0, summed_dist = 0; + float dist_sq = 0.0f, dx = 0.0f, dy = 0.0f, dyaw = 0.0f, summed_dist = 0.0f; double min_dist_sq = std::numeric_limits::max(); size_t min_s = 0; for (size_t t = 0; t < batch_size; ++t) { - summed_dist = 0; + summed_dist = 0.0f; for (size_t p = trajectory_point_step_; p < time_steps; p += trajectory_point_step_) { min_dist_sq = std::numeric_limits::max(); min_s = 0; @@ -118,7 +118,7 @@ void PathAlignCritic::score(CriticData & data) // The nearest path point to align to needs to be not in collision, else // let the obstacle critic take over in this region due to dynamic obstacles if (min_s != 0 && (*data.path_pts_valid)[min_s]) { - summed_dist += std::sqrt(min_dist_sq); + summed_dist += sqrtf(min_dist_sq); } } diff --git a/nav2_mppi_controller/src/optimizer.cpp b/nav2_mppi_controller/src/optimizer.cpp index 55362fd7a8..aae95015e1 100644 --- a/nav2_mppi_controller/src/optimizer.cpp +++ b/nav2_mppi_controller/src/optimizer.cpp @@ -286,8 +286,8 @@ void Optimizer::integrateStateVelocities( const auto yaw_offseted = xt::view(traj_yaws, xt::range(1, _)); - xt::noalias(xt::view(yaw_cos, 0)) = std::cos(initial_yaw); - xt::noalias(xt::view(yaw_sin, 0)) = std::sin(initial_yaw); + xt::noalias(xt::view(yaw_cos, 0)) = cosf(initial_yaw); + xt::noalias(xt::view(yaw_sin, 0)) = sinf(initial_yaw); xt::noalias(xt::view(yaw_cos, xt::range(1, _))) = xt::cos(yaw_offseted); xt::noalias(xt::view(yaw_sin, xt::range(1, _))) = xt::sin(yaw_offseted); @@ -316,8 +316,8 @@ void Optimizer::integrateStateVelocities( auto && yaw_cos = xt::xtensor::from_shape(trajectories.yaws.shape()); auto && yaw_sin = xt::xtensor::from_shape(trajectories.yaws.shape()); - xt::noalias(xt::view(yaw_cos, xt::all(), 0)) = std::cos(initial_yaw); - xt::noalias(xt::view(yaw_sin, xt::all(), 0)) = std::sin(initial_yaw); + xt::noalias(xt::view(yaw_cos, xt::all(), 0)) = cosf(initial_yaw); + xt::noalias(xt::view(yaw_sin, xt::all(), 0)) = sinf(initial_yaw); xt::noalias(xt::view(yaw_cos, xt::all(), xt::range(1, _))) = xt::cos(yaws_cutted); xt::noalias(xt::view(yaw_sin, xt::all(), xt::range(1, _))) = xt::sin(yaws_cutted); @@ -358,16 +358,16 @@ void Optimizer::updateControlSequence() auto bounded_noises_vx = state_.cvx - control_sequence_.vx; auto bounded_noises_wz = state_.cwz - control_sequence_.wz; xt::noalias(costs_) += - s.gamma / std::pow(s.sampling_std.vx, 2) * xt::sum( + s.gamma / powf(s.sampling_std.vx, 2) * xt::sum( xt::view(control_sequence_.vx, xt::newaxis(), xt::all()) * bounded_noises_vx, 1, immediate); xt::noalias(costs_) += - s.gamma / std::pow(s.sampling_std.wz, 2) * xt::sum( + s.gamma / powf(s.sampling_std.wz, 2) * xt::sum( xt::view(control_sequence_.wz, xt::newaxis(), xt::all()) * bounded_noises_wz, 1, immediate); if (isHolonomic()) { auto bounded_noises_vy = state_.cvy - control_sequence_.vy; xt::noalias(costs_) += - s.gamma / std::pow(s.sampling_std.vy, 2) * xt::sum( + s.gamma / powf(s.sampling_std.vy, 2) * xt::sum( xt::view(control_sequence_.vy, xt::newaxis(), xt::all()) * bounded_noises_vy, 1, immediate); } From 4baede34d5a91bee1ac34491319613c801bba8da Mon Sep 17 00:00:00 2001 From: Anton Kesy Date: Tue, 19 Sep 2023 17:31:30 +0100 Subject: [PATCH 15/31] fix broken behaviortree doc link (#3822) Signed-off-by: Anton Kesy --- nav2_behavior_tree/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_behavior_tree/README.md b/nav2_behavior_tree/README.md index db761cb31d..b2c30c432f 100644 --- a/nav2_behavior_tree/README.md +++ b/nav2_behavior_tree/README.md @@ -63,4 +63,4 @@ The BehaviorTree engine has a run method that accepts an XML description of a BT See the code in the [BT Navigator](../nav2_bt_navigator/src/bt_navigator.cpp) for an example usage of the BehaviorTreeEngine. -For more information about the behavior tree nodes that are available in the default BehaviorTreeCPP library, see documentation here: https://www.behaviortree.dev/bt_basics/ +For more information about the behavior tree nodes that are available in the default BehaviorTreeCPP library, see documentation here: https://www.behaviortree.dev/docs/learn-the-basics/bt_basics/ From 91b688de212036d2c33b15437652dff156a4ff66 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 20 Sep 2023 13:29:32 -0700 Subject: [PATCH 16/31] [MPPI] complete minor optimaization with floating point calculations (#3827) * floating point calculations * Update optimizer_unit_tests.cpp * Update critics_tests.cpp * Update critics_tests.cpp --- nav2_mppi_controller/CMakeLists.txt | 3 +- .../critics/obstacles_critic.hpp | 4 +- .../critics/path_angle_critic.hpp | 2 +- .../models/constraints.hpp | 14 +++--- .../tools/path_handler.hpp | 4 +- .../nav2_mppi_controller/tools/utils.hpp | 44 +++++++++---------- .../src/critics/obstacles_critic.cpp | 14 +++--- .../src/critics/path_align_critic.cpp | 2 +- nav2_mppi_controller/src/noise_generator.cpp | 6 +-- nav2_mppi_controller/src/path_handler.cpp | 8 ++-- nav2_mppi_controller/test/critics_tests.cpp | 8 ++-- .../test/optimizer_unit_tests.cpp | 12 ++--- 12 files changed, 62 insertions(+), 59 deletions(-) diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 9c3e5f6fa3..5cc8a8c0e9 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -47,7 +47,8 @@ if(COMPILER_SUPPORTS_FMA) add_compile_options(-mfma) endif() -add_compile_options(-O3 -finline-limit=1000000 -ffp-contract=fast -ffast-math) +# If building one the same hardware to be deployed on, try `-march=native`! +add_compile_options(-O3 -finline-limit=10000000 -ffp-contract=fast -ffast-math -mtune=generic) add_library(mppi_controller SHARED src/controller.cpp diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp index 37e14cb02c..fe17906bae 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp @@ -79,14 +79,14 @@ class ObstaclesCritic : public CriticFunction * @return double circumscribed cost, any higher than this and need to do full footprint collision checking * since some element of the robot could be in collision */ - double findCircumscribedCost(std::shared_ptr costmap); + float findCircumscribedCost(std::shared_ptr costmap); protected: nav2_costmap_2d::FootprintCollisionChecker collision_checker_{nullptr}; bool consider_footprint_{true}; - double collision_cost_{0}; + float collision_cost_{0}; float inflation_scale_factor_{0}, inflation_radius_{0}; float possibly_inscribed_cost_; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp index f7ba486a0c..b137270aba 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp @@ -72,7 +72,7 @@ class PathAngleCritic : public CriticFunction void score(CriticData & data) override; protected: - double max_angle_to_furthest_{0}; + float max_angle_to_furthest_{0}; float threshold_to_consider_{0}; size_t offset_from_furthest_{0}; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/models/constraints.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/models/constraints.hpp index b7f9b6f3cc..5e1885c271 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/models/constraints.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/models/constraints.hpp @@ -24,10 +24,10 @@ namespace mppi::models */ struct ControlConstraints { - double vx_max; - double vx_min; - double vy; - double wz; + float vx_max; + float vx_min; + float vy; + float wz; }; /** @@ -36,9 +36,9 @@ struct ControlConstraints */ struct SamplingStd { - double vx; - double vy; - double wz; + float vx; + float vy; + float wz; }; } // namespace mppi::models diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp index 468e4964a4..eeb28fa01b 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp @@ -151,8 +151,8 @@ class PathHandler double max_robot_pose_search_dist_{0}; double prune_distance_{0}; double transform_tolerance_{0}; - double inversion_xy_tolerance_{0.2}; - double inversion_yaw_tolerance{0.4}; + float inversion_xy_tolerance_{0.2}; + float inversion_yaw_tolerance{0.4}; bool enforce_path_inversion_{false}; unsigned int inversion_locale_{0u}; }; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp index ce2d0570c0..6baa27873e 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp @@ -309,7 +309,7 @@ inline size_t findPathFurthestReachedPoint(const CriticData & data) const auto dists = dx * dx + dy * dy; size_t max_id_by_trajectories = 0; - double min_distance_by_path = std::numeric_limits::max(); + float min_distance_by_path = std::numeric_limits::max(); for (size_t i = 0; i < dists.shape(0); i++) { size_t min_id_by_path = 0; @@ -337,7 +337,7 @@ inline size_t findPathTrajectoryInitialPoint(const CriticData & data) const auto dy = data.path.y - data.trajectories.y(0, 0); const auto dists = dx * dx + dy * dy; - double min_distance_by_path = std::numeric_limits::max(); + float min_distance_by_path = std::numeric_limits::max(); size_t min_id = 0; for (size_t j = 0; j < dists.shape(0); j++) { if (dists(j) < min_distance_by_path) { @@ -420,23 +420,23 @@ inline void setPathCostsIfNotSet( * @param forward_preference If reversing direction is valid * @return Angle between two points */ -inline double posePointAngle( +inline float posePointAngle( const geometry_msgs::msg::Pose & pose, double point_x, double point_y, bool forward_preference) { - double pose_x = pose.position.x; - double pose_y = pose.position.y; - double pose_yaw = tf2::getYaw(pose.orientation); + float pose_x = pose.position.x; + float pose_y = pose.position.y; + float pose_yaw = tf2::getYaw(pose.orientation); - double yaw = atan2(point_y - pose_y, point_x - pose_x); + float yaw = atan2f(point_y - pose_y, point_x - pose_x); // If no preference for forward, return smallest angle either in heading or 180 of heading if (!forward_preference) { return std::min( - abs(angles::shortest_angular_distance(yaw, pose_yaw)), - abs(angles::shortest_angular_distance(yaw, angles::normalize_angle(pose_yaw + M_PI)))); + fabs(angles::shortest_angular_distance(yaw, pose_yaw)), + fabs(angles::shortest_angular_distance(yaw, angles::normalize_angle(pose_yaw + M_PI)))); } - return abs(angles::shortest_angular_distance(yaw, pose_yaw)); + return fabs(angles::shortest_angular_distance(yaw, pose_yaw)); } /** @@ -447,21 +447,21 @@ inline double posePointAngle( * @param point_yaw Yaw of the point to consider along Z axis * @return Angle between two points */ -inline double posePointAngle( +inline float posePointAngle( const geometry_msgs::msg::Pose & pose, double point_x, double point_y, double point_yaw) { - double pose_x = pose.position.x; - double pose_y = pose.position.y; - double pose_yaw = tf2::getYaw(pose.orientation); + float pose_x = pose.position.x; + float pose_y = pose.position.y; + float pose_yaw = tf2::getYaw(pose.orientation); - double yaw = atan2(point_y - pose_y, point_x - pose_x); + float yaw = atan2f(point_y - pose_y, point_x - pose_x); - if (abs(angles::shortest_angular_distance(yaw, point_yaw)) > M_PI_2) { + if (fabs(angles::shortest_angular_distance(yaw, point_yaw)) > M_PI_2) { yaw = angles::normalize_angle(yaw + M_PI); } - return abs(angles::shortest_angular_distance(yaw, pose_yaw)); + return fabs(angles::shortest_angular_distance(yaw, pose_yaw)); } /** @@ -650,17 +650,17 @@ inline unsigned int findFirstPathInversion(nav_msgs::msg::Path & path) // Iterating through the path to determine the position of the path inversion for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) { // We have two vectors for the dot product OA and AB. Determining the vectors. - double oa_x = path.poses[idx].pose.position.x - + float oa_x = path.poses[idx].pose.position.x - path.poses[idx - 1].pose.position.x; - double oa_y = path.poses[idx].pose.position.y - + float oa_y = path.poses[idx].pose.position.y - path.poses[idx - 1].pose.position.y; - double ab_x = path.poses[idx + 1].pose.position.x - + float ab_x = path.poses[idx + 1].pose.position.x - path.poses[idx].pose.position.x; - double ab_y = path.poses[idx + 1].pose.position.y - + float ab_y = path.poses[idx + 1].pose.position.y - path.poses[idx].pose.position.y; // Checking for the existance of cusp, in the path, using the dot product. - double dot_product = (oa_x * ab_x) + (oa_y * ab_y); + float dot_product = (oa_x * ab_x) + (oa_y * ab_y); if (dot_product < 0.0) { return idx + 1; } diff --git a/nav2_mppi_controller/src/critics/obstacles_critic.cpp b/nav2_mppi_controller/src/critics/obstacles_critic.cpp index b922563597..80ac77e10f 100644 --- a/nav2_mppi_controller/src/critics/obstacles_critic.cpp +++ b/nav2_mppi_controller/src/critics/obstacles_critic.cpp @@ -32,7 +32,7 @@ void ObstaclesCritic::initialize() collision_checker_.setCostmap(costmap_); possibly_inscribed_cost_ = findCircumscribedCost(costmap_ros_); - if (possibly_inscribed_cost_ < 1) { + if (possibly_inscribed_cost_ < 1.0f) { RCLCPP_ERROR( logger_, "Inflation layer either not found or inflation is not set sufficiently for " @@ -50,7 +50,7 @@ void ObstaclesCritic::initialize() "footprint" : "circular"); } -double ObstaclesCritic::findCircumscribedCost( +float ObstaclesCritic::findCircumscribedCost( std::shared_ptr costmap) { double result = -1.0; @@ -75,7 +75,7 @@ double ObstaclesCritic::findCircumscribedCost( if (!inflation_layer_found) { RCLCPP_WARN( - rclcpp::get_logger("computeCircumscribedCost"), + logger_, "No inflation layer found in costmap configuration. " "If this is an SE2-collision checking plugin, it cannot use costmap potential " "field to speed up collision checking by only checking the full footprint " @@ -83,7 +83,7 @@ double ObstaclesCritic::findCircumscribedCost( "significantly slow down planning times and not avoid anything but absolute collisions!"); } - return result; + return static_cast(result); } float ObstaclesCritic::distanceToObstacle(const CollisionCost & cost) @@ -137,7 +137,7 @@ void ObstaclesCritic::score(CriticData & data) } // Cannot process repulsion if inflation layer does not exist - if (inflation_radius_ == 0 || inflation_scale_factor_ == 0) { + if (inflation_radius_ == 0.0f || inflation_scale_factor_ == 0.0f) { continue; } @@ -197,7 +197,9 @@ CollisionCost ObstaclesCritic::costAtPose(float x, float y, float theta) } cost = collision_checker_.pointCost(x_i, y_i); - if (consider_footprint_ && (cost >= possibly_inscribed_cost_ || possibly_inscribed_cost_ < 1)) { + if (consider_footprint_ && + (cost >= possibly_inscribed_cost_ || possibly_inscribed_cost_ < 1.0f)) + { cost = static_cast(collision_checker_.footprintCostAtPose( x, y, theta, costmap_ros_->getRobotFootprint())); collision_cost.using_footprint = true; diff --git a/nav2_mppi_controller/src/critics/path_align_critic.cpp b/nav2_mppi_controller/src/critics/path_align_critic.cpp index 795f166c1a..4ff12d4e55 100644 --- a/nav2_mppi_controller/src/critics/path_align_critic.cpp +++ b/nav2_mppi_controller/src/critics/path_align_critic.cpp @@ -89,7 +89,7 @@ void PathAlignCritic::score(CriticData & data) } float dist_sq = 0.0f, dx = 0.0f, dy = 0.0f, dyaw = 0.0f, summed_dist = 0.0f; - double min_dist_sq = std::numeric_limits::max(); + float min_dist_sq = std::numeric_limits::max(); size_t min_s = 0; for (size_t t = 0; t < batch_size; ++t) { diff --git a/nav2_mppi_controller/src/noise_generator.cpp b/nav2_mppi_controller/src/noise_generator.cpp index 60173789f0..09ee4ab92d 100644 --- a/nav2_mppi_controller/src/noise_generator.cpp +++ b/nav2_mppi_controller/src/noise_generator.cpp @@ -94,14 +94,14 @@ void NoiseGenerator::generateNoisedControls() auto & s = settings_; xt::noalias(noises_vx_) = xt::random::randn( - {s.batch_size, s.time_steps}, 0.0, + {s.batch_size, s.time_steps}, 0.0f, s.sampling_std.vx); xt::noalias(noises_wz_) = xt::random::randn( - {s.batch_size, s.time_steps}, 0.0, + {s.batch_size, s.time_steps}, 0.0f, s.sampling_std.wz); if (is_holonomic_) { xt::noalias(noises_vy_) = xt::random::randn( - {s.batch_size, s.time_steps}, 0.0, + {s.batch_size, s.time_steps}, 0.0f, s.sampling_std.vy); } } diff --git a/nav2_mppi_controller/src/path_handler.cpp b/nav2_mppi_controller/src/path_handler.cpp index f1022513f2..ddf2b403b6 100644 --- a/nav2_mppi_controller/src/path_handler.cpp +++ b/nav2_mppi_controller/src/path_handler.cpp @@ -166,8 +166,8 @@ bool PathHandler::transformPose( double PathHandler::getMaxCostmapDist() { const auto & costmap = costmap_->getCostmap(); - return std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()) * - costmap->getResolution() / 2.0; + return static_cast(std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY())) * + costmap->getResolution() * 0.50; } void PathHandler::setPath(const nav_msgs::msg::Path & plan) @@ -190,11 +190,11 @@ bool PathHandler::isWithinInversionTolerances(const geometry_msgs::msg::PoseStam { // Keep full path if we are within tolerance of the inversion pose const auto last_pose = global_plan_up_to_inversion_.poses.back(); - double distance = std::hypot( + float distance = hypotf( robot_pose.pose.position.x - last_pose.pose.position.x, robot_pose.pose.position.y - last_pose.pose.position.y); - double angle_distance = angles::shortest_angular_distance( + float angle_distance = angles::shortest_angular_distance( tf2::getYaw(robot_pose.pose.orientation), tf2::getYaw(last_pose.pose.orientation)); diff --git a/nav2_mppi_controller/test/critics_tests.cpp b/nav2_mppi_controller/test/critics_tests.cpp index ce2896122c..8b5efae8da 100644 --- a/nav2_mppi_controller/test/critics_tests.cpp +++ b/nav2_mppi_controller/test/critics_tests.cpp @@ -380,19 +380,19 @@ TEST(CriticTests, PreferForwardCritic) path.reset(10); path.x(9) = 10.0; critic.score(data); - EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0, 1e-6); + EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0f, 1e-6f); // provide state pose and path close to trigger behavior but with all forward motion path.x(9) = 0.15; state.vx = xt::ones({1000, 30}); critic.score(data); - EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0, 1e-6); + EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0f, 1e-6f); // provide state pose and path close to trigger behavior but with all reverse motion state.vx = -1.0 * xt::ones({1000, 30}); critic.score(data); - EXPECT_GT(xt::sum(costs, immediate)(), 0.0); - EXPECT_NEAR(costs(0), 15.0, 1e-6); // 1.0 * 0.1 model_dt * 5.0 weight * 30 length + EXPECT_GT(xt::sum(costs, immediate)(), 0.0f); + EXPECT_NEAR(costs(0), 15.0f, 1e-3f); // 1.0 * 0.1 model_dt * 5.0 weight * 30 length } TEST(CriticTests, TwirlingCritic) diff --git a/nav2_mppi_controller/test/optimizer_unit_tests.cpp b/nav2_mppi_controller/test/optimizer_unit_tests.cpp index f27471d28a..7c7f8a7691 100644 --- a/nav2_mppi_controller/test/optimizer_unit_tests.cpp +++ b/nav2_mppi_controller/test/optimizer_unit_tests.cpp @@ -432,20 +432,20 @@ TEST(OptimizerTests, SpeedLimitTests) // Test Speed limits API auto [v_min, v_max] = optimizer_tester.getVelLimits(); - EXPECT_EQ(v_max, 0.5); - EXPECT_EQ(v_min, -0.35); + EXPECT_EQ(v_max, 0.5f); + EXPECT_EQ(v_min, -0.35f); optimizer_tester.setSpeedLimit(0, false); auto [v_min2, v_max2] = optimizer_tester.getVelLimits(); - EXPECT_EQ(v_max2, 0.5); - EXPECT_EQ(v_min2, -0.35); + EXPECT_EQ(v_max2, 0.5f); + EXPECT_EQ(v_min2, -0.35f); optimizer_tester.setSpeedLimit(50.0, true); auto [v_min3, v_max3] = optimizer_tester.getVelLimits(); EXPECT_NEAR(v_max3, 0.5 / 2.0, 1e-3); EXPECT_NEAR(v_min3, -0.35 / 2.0, 1e-3); optimizer_tester.setSpeedLimit(0, true); auto [v_min4, v_max4] = optimizer_tester.getVelLimits(); - EXPECT_EQ(v_max4, 0.5); - EXPECT_EQ(v_min4, -0.35); + EXPECT_EQ(v_max4, 0.5f); + EXPECT_EQ(v_min4, -0.35f); optimizer_tester.setSpeedLimit(0.75, false); auto [v_min5, v_max5] = optimizer_tester.getVelLimits(); EXPECT_NEAR(v_max5, 0.75, 1e-3); From 1b13476dc91d9bde130506c03332e39e4d2d9aac Mon Sep 17 00:00:00 2001 From: stevemacenski Date: Wed, 20 Sep 2023 18:43:40 -0700 Subject: [PATCH 17/31] 25% speed up of goal critic; 1% speed up from vy striding when not in use --- nav2_mppi_controller/src/critics/goal_critic.cpp | 2 +- nav2_mppi_controller/src/optimizer.cpp | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/nav2_mppi_controller/src/critics/goal_critic.cpp b/nav2_mppi_controller/src/critics/goal_critic.cpp index e38a98ed6b..852db11529 100644 --- a/nav2_mppi_controller/src/critics/goal_critic.cpp +++ b/nav2_mppi_controller/src/critics/goal_critic.cpp @@ -57,7 +57,7 @@ void GoalCritic::score(CriticData & data) xt::pow(traj_x - goal_x, 2) + xt::pow(traj_y - goal_y, 2)); - data.costs += xt::pow(xt::mean(dists, {1}) * weight_, power_); + data.costs += xt::pow(xt::mean(dists, {1}, immediate) * weight_, power_); } } // namespace mppi::critics diff --git a/nav2_mppi_controller/src/optimizer.cpp b/nav2_mppi_controller/src/optimizer.cpp index aae95015e1..6d0a3ceb6c 100644 --- a/nav2_mppi_controller/src/optimizer.cpp +++ b/nav2_mppi_controller/src/optimizer.cpp @@ -378,8 +378,10 @@ void Optimizer::updateControlSequence() auto && softmaxes_extened = xt::eval(xt::view(softmaxes, xt::all(), xt::newaxis())); xt::noalias(control_sequence_.vx) = xt::sum(state_.cvx * softmaxes_extened, 0, immediate); - xt::noalias(control_sequence_.vy) = xt::sum(state_.cvy * softmaxes_extened, 0, immediate); xt::noalias(control_sequence_.wz) = xt::sum(state_.cwz * softmaxes_extened, 0, immediate); + if (isHolonomic()) { + xt::noalias(control_sequence_.vy) = xt::sum(state_.cvy * softmaxes_extened, 0, immediate); + } applyControlSequenceConstraints(); } From 1efc96c3aa1b80d4926238238b56d45a9d7a8993 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pedro=20Alejandro=20Gonz=C3=A1lez?= <71234974+pepisg@users.noreply.github.com> Date: Thu, 21 Sep 2023 13:12:41 -0500 Subject: [PATCH 18/31] Add nav2_gps_waypoint_follower (#2814) * Add nav2_gps_waypoint_follower * use correct client node while calling it to spin * changed after 1'st review * apply requested changes * nav2_util::ServiceClient instead of CallbackGroup * another iteration to adress issues * update poses with function in the follower logic * add deps of robot_localization: diagnostics * fix typo in underlay.repo * add deps of robot_localization: geographic_info * minor clean-ups * bond_core version has been updated * rotation should also be considered in GPS WPFing * use better namings related to gps wpf orientation * handle cpplint errors * tf_listener needs to be initialized * apply requested changes * apply requested changes 3.0/3.0 * fix misplaced ";" * use run time param for gps transform timeout * change timeout var name * make use of stop_on_failure for GPS too * passing emptywaypont vectors are seen as failure * update warning for empty requests * consider utm -> map yaw offset * fix missed RCLCPP info * reorrect action;s name * waypoint stamps need to be updated * Fix segmentation fault on waypoint follower * Parametric frames and matrix multiplications * Replace oriented navsatfix for geographic_msgs/geopose * Remove deprecated oriented navsatfix message * Update branch name on robot_localization dependency * Fix parametric frames logic * Rename functions and adress comments * fix style in underlay.repos * remove duplicate word in underlay.repos * update dependency version of ompl * Template ServiceClient class to accept lifecycle node * Remove link to stackoverflow answer * Remove yaw offset compensation * Fix API change * Fix styling * Minor docs fixes * Fix style divergences * Style fixes * Style fixes v2 * Style fixes v3 * Remove unused variables and timestam overrides * restore goal timestamp override * WIP: Add follow gps waypoints test * Style fixes and gazebo world inertia fix * Reduce velocity smoother timeout * empty commit to rerun tests * Increment circle ci cache idx * Remove extra space in cmakelists.txt * Fix wrong usage of the global action server * update follow gps waypoints action definition * Fix action definition and looping * update params for the unit testing * WIP: update tests * fix tests * fixes to nav2 simple commander * add robot_localization localizer * Bring back from LL client * Update nav2_simple_commander/nav2_simple_commander/robot_navigator.py Co-authored-by: Steve Macenski * missing argument in test function * small test error * style fixes nav2 simple commander * rename cartesian action server --------- Co-authored-by: jediofgever Co-authored-by: Steve Macenski --- nav2_msgs/CMakeLists.txt | 4 +- nav2_msgs/action/FollowGPSWaypoints.action | 17 + nav2_msgs/package.xml | 1 + .../nav2_simple_commander/robot_navigator.py | 30 +- nav2_system_tests/CMakeLists.txt | 1 + .../src/gps_navigation/CMakeLists.txt | 11 + .../gps_navigation/dual_ekf_navsat.launch.py | 63 ++ .../dual_ekf_navsat_params.yaml | 127 ++++ .../gps_navigation/nav2_no_map_params.yaml | 307 ++++++++++ .../src/gps_navigation/test_case_py.launch.py | 132 +++++ .../src/gps_navigation/tester.py | 222 +++++++ .../worlds/turtlebot3_ros2_demo_gps.world | 555 ++++++++++++++++++ .../include/nav2_util/service_client.hpp | 8 +- nav2_waypoint_follower/CMakeLists.txt | 3 + nav2_waypoint_follower/README.md | 19 + .../waypoint_follower.hpp | 84 ++- nav2_waypoint_follower/package.xml | 4 +- .../src/waypoint_follower.cpp | 209 +++++-- tools/underlay.repos | 12 + 19 files changed, 1758 insertions(+), 51 deletions(-) create mode 100644 nav2_msgs/action/FollowGPSWaypoints.action create mode 100644 nav2_system_tests/src/gps_navigation/CMakeLists.txt create mode 100644 nav2_system_tests/src/gps_navigation/dual_ekf_navsat.launch.py create mode 100644 nav2_system_tests/src/gps_navigation/dual_ekf_navsat_params.yaml create mode 100644 nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml create mode 100755 nav2_system_tests/src/gps_navigation/test_case_py.launch.py create mode 100755 nav2_system_tests/src/gps_navigation/tester.py create mode 100644 nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world diff --git a/nav2_msgs/CMakeLists.txt b/nav2_msgs/CMakeLists.txt index 836f7219df..e588ff0fa5 100644 --- a/nav2_msgs/CMakeLists.txt +++ b/nav2_msgs/CMakeLists.txt @@ -8,6 +8,7 @@ find_package(nav_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) +find_package(geographic_msgs) find_package(action_msgs REQUIRED) nav2_package() @@ -49,7 +50,8 @@ rosidl_generate_interfaces(${PROJECT_NAME} "action/Spin.action" "action/DummyBehavior.action" "action/FollowWaypoints.action" - DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs + "action/FollowGPSWaypoints.action" + DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs geographic_msgs ) ament_export_dependencies(rosidl_default_runtime) diff --git a/nav2_msgs/action/FollowGPSWaypoints.action b/nav2_msgs/action/FollowGPSWaypoints.action new file mode 100644 index 0000000000..707e9a2b37 --- /dev/null +++ b/nav2_msgs/action/FollowGPSWaypoints.action @@ -0,0 +1,17 @@ +#goal definition +uint32 number_of_loops +uint32 goal_index 0 +geographic_msgs/GeoPose[] gps_poses +--- +#result definition + +# Error codes +# Note: The expected priority order of the errors should match the message order +uint16 NONE=0 +uint16 UNKNOWN=600 +uint16 TASK_EXECUTOR_FAILED=601 + +MissedWaypoint[] missed_waypoints +--- +#feedback +uint32 current_waypoint diff --git a/nav2_msgs/package.xml b/nav2_msgs/package.xml index bc3391f466..48e555532b 100644 --- a/nav2_msgs/package.xml +++ b/nav2_msgs/package.xml @@ -19,6 +19,7 @@ geometry_msgs action_msgs nav_msgs + geographic_msgs rosidl_interface_packages diff --git a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py index f5abfc582f..76a6c3d79b 100644 --- a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py +++ b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py @@ -25,7 +25,8 @@ from lifecycle_msgs.srv import GetState from nav2_msgs.action import AssistedTeleop, BackUp, Spin from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose -from nav2_msgs.action import FollowPath, FollowWaypoints, NavigateThroughPoses, NavigateToPose +from nav2_msgs.action import FollowPath, FollowWaypoints, FollowGPSWaypoints, \ + NavigateThroughPoses, NavigateToPose from nav2_msgs.action import SmoothPath from nav2_msgs.srv import ClearEntireCostmap, GetCostmap, LoadMap, ManageLifecycleNodes @@ -67,6 +68,8 @@ def __init__(self, node_name='basic_navigator', namespace=''): 'navigate_through_poses') self.nav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose') self.follow_waypoints_client = ActionClient(self, FollowWaypoints, 'follow_waypoints') + self.follow_gps_waypoints_client = ActionClient(self, FollowGPSWaypoints, + 'follow_gps_waypoints') self.follow_path_client = ActionClient(self, FollowPath, 'follow_path') self.compute_path_to_pose_client = ActionClient(self, ComputePathToPose, 'compute_path_to_pose') @@ -182,6 +185,28 @@ def followWaypoints(self, poses): self.result_future = self.goal_handle.get_result_async() return True + def followGpsWaypoints(self, gps_poses): + """Send a `FollowGPSWaypoints` action request.""" + self.debug("Waiting for 'FollowWaypoints' action server") + while not self.follow_gps_waypoints_client.wait_for_server(timeout_sec=1.0): + self.info("'FollowWaypoints' action server not available, waiting...") + + goal_msg = FollowGPSWaypoints.Goal() + goal_msg.gps_poses = gps_poses + + self.info(f'Following {len(goal_msg.gps_poses)} gps goals....') + send_goal_future = self.follow_gps_waypoints_client.send_goal_async(goal_msg, + self._feedbackCallback) + rclpy.spin_until_future_complete(self, send_goal_future) + self.goal_handle = send_goal_future.result() + + if not self.goal_handle.accepted: + self.error(f'Following {len(gps_poses)} gps waypoints request was rejected!') + return False + + self.result_future = self.goal_handle.get_result_async() + return True + def spin(self, spin_dist=1.57, time_allowance=10): self.debug("Waiting for 'Spin' action server") while not self.spin_client.wait_for_server(timeout_sec=1.0): @@ -310,7 +335,8 @@ def getResult(self): def waitUntilNav2Active(self, navigator='bt_navigator', localizer='amcl'): """Block until the full navigation system is up and running.""" - self._waitForNodeToActivate(localizer) + if localizer != "robot_localization": # non-lifecycle node + self._waitForNodeToActivate(localizer) if localizer == 'amcl': self._waitForInitialPose() self._waitForNodeToActivate(navigator) diff --git a/nav2_system_tests/CMakeLists.txt b/nav2_system_tests/CMakeLists.txt index 352f9f2277..2674b65e74 100644 --- a/nav2_system_tests/CMakeLists.txt +++ b/nav2_system_tests/CMakeLists.txt @@ -114,6 +114,7 @@ if(BUILD_TESTING) add_subdirectory(src/system_failure) add_subdirectory(src/updown) add_subdirectory(src/waypoint_follower) + add_subdirectory(src/gps_navigation) add_subdirectory(src/behaviors/spin) add_subdirectory(src/behaviors/wait) add_subdirectory(src/behaviors/backup) diff --git a/nav2_system_tests/src/gps_navigation/CMakeLists.txt b/nav2_system_tests/src/gps_navigation/CMakeLists.txt new file mode 100644 index 0000000000..3342b6cd58 --- /dev/null +++ b/nav2_system_tests/src/gps_navigation/CMakeLists.txt @@ -0,0 +1,11 @@ +ament_add_test(test_gps_waypoint_follower + GENERATE_RESULT_FOR_RETURN_CODE_ZERO + COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_case_py.launch.py" + WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" + TIMEOUT 180 + ENV + TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR} + TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo_gps.world + GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models + BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml +) diff --git a/nav2_system_tests/src/gps_navigation/dual_ekf_navsat.launch.py b/nav2_system_tests/src/gps_navigation/dual_ekf_navsat.launch.py new file mode 100644 index 0000000000..852436615b --- /dev/null +++ b/nav2_system_tests/src/gps_navigation/dual_ekf_navsat.launch.py @@ -0,0 +1,63 @@ +# Copyright 2018 Open Source Robotics Foundation, Inc. +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +import launch_ros.actions +import os +import launch.actions + + +def generate_launch_description(): + launch_dir = os.path.dirname(os.path.realpath(__file__)) + params_file = os.path.join(launch_dir, "dual_ekf_navsat_params.yaml") + os.environ["FILE_PATH"] = str(launch_dir) + return LaunchDescription( + [ + launch.actions.DeclareLaunchArgument( + "output_final_position", default_value="false" + ), + launch.actions.DeclareLaunchArgument( + "output_location", default_value="~/dual_ekf_navsat_example_debug.txt" + ), + launch_ros.actions.Node( + package="robot_localization", + executable="ekf_node", + name="ekf_filter_node_odom", + output="screen", + parameters=[params_file, {"use_sim_time": True}], + remappings=[("odometry/filtered", "odometry/local")], + ), + launch_ros.actions.Node( + package="robot_localization", + executable="ekf_node", + name="ekf_filter_node_map", + output="screen", + parameters=[params_file, {"use_sim_time": True}], + remappings=[("odometry/filtered", "odometry/global")], + ), + launch_ros.actions.Node( + package="robot_localization", + executable="navsat_transform_node", + name="navsat_transform", + output="screen", + parameters=[params_file, {"use_sim_time": True}], + remappings=[ + ("imu/data", "imu/data"), + ("gps/fix", "gps/fix"), + ("gps/filtered", "gps/filtered"), + ("odometry/gps", "odometry/gps"), + ("odometry/filtered", "odometry/global"), + ], + ), + ] + ) diff --git a/nav2_system_tests/src/gps_navigation/dual_ekf_navsat_params.yaml b/nav2_system_tests/src/gps_navigation/dual_ekf_navsat_params.yaml new file mode 100644 index 0000000000..6783a7b1db --- /dev/null +++ b/nav2_system_tests/src/gps_navigation/dual_ekf_navsat_params.yaml @@ -0,0 +1,127 @@ +# For parameter descriptions, please refer to the template parameter files for each node. + +ekf_filter_node_odom: + ros__parameters: + frequency: 30.0 + two_d_mode: true # Recommended to use 2d mode for nav2, since its world representation is 2d + print_diagnostics: true + debug: false + publish_tf: true + + map_frame: map + odom_frame: odom + base_link_frame: base_link + world_frame: odom + + odom0: odom + odom0_config: [false, false, false, + false, false, false, + true, true, true, + false, false, true, + false, false, false] + odom0_queue_size: 10 + odom0_differential: false + odom0_relative: false + + imu0: imu/data + imu0_config: [false, false, false, + false, false, true, + false, false, false, + false, false, false, + false, false, false] + imu0_differential: false # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate + imu0_relative: false + imu0_queue_size: 10 + imu0_remove_gravitational_acceleration: true + + use_control: false + + process_noise_covariance: [1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3] + +ekf_filter_node_map: + ros__parameters: + frequency: 30.0 + two_d_mode: true # Recommended to use 2d mode for nav2, since its world representation is 2d + print_diagnostics: true + debug: false + publish_tf: true + + map_frame: map + odom_frame: odom + base_link_frame: base_link + world_frame: map + + odom0: odom + odom0_config: [false, false, false, + false, false, false, + true, true, true, + false, false, true, + false, false, false] + odom0_queue_size: 10 + odom0_differential: false + odom0_relative: false + + odom1: odometry/gps + odom1_config: [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] + odom1_queue_size: 10 + odom1_differential: false + odom1_relative: false + + imu0: imu/data + imu0_config: [false, false, false, + false, false, true, + false, false, false, + false, false, false, + false, false, false] + imu0_differential: false # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate + imu0_relative: false + imu0_queue_size: 10 + imu0_remove_gravitational_acceleration: true + + use_control: false + + process_noise_covariance: [1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3] + +navsat_transform: + ros__parameters: + frequency: 30.0 + delay: 3.0 + magnetic_declination_radians: 0.0429351 # For lat/long 55.944831, -3.186998 + yaw_offset: 0.0 + zero_altitude: true + broadcast_utm_transform: true + publish_filtered_gps: true + use_odometry_yaw: true + wait_for_datum: false diff --git a/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml b/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml new file mode 100644 index 0000000000..2539cef7b5 --- /dev/null +++ b/nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml @@ -0,0 +1,307 @@ +bt_navigator: + ros__parameters: + global_frame: map + robot_base_frame: base_link + odom_topic: /odom + bt_loop_duration: 10 + default_server_timeout: 20 + navigators: ["navigate_to_pose", "navigate_through_poses"] + navigate_to_pose: + plugin: "nav2_bt_navigator/NavigateToPoseNavigator" + navigate_through_poses: + plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator" + # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: + # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml + # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml + # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. + plugin_lib_names: + - nav2_compute_path_to_pose_action_bt_node + - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_action_bt_node + - nav2_assisted_teleop_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_bt_node + - nav2_clear_costmap_service_bt_node + - nav2_is_stuck_condition_bt_node + - nav2_goal_reached_condition_bt_node + - nav2_goal_updated_condition_bt_node + - nav2_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_condition_bt_node + - nav2_are_error_codes_active_condition_bt_node + - nav2_would_a_controller_recovery_help_condition_bt_node + - nav2_would_a_planner_recovery_help_condition_bt_node + - nav2_would_a_smoother_recovery_help_condition_bt_node + - nav2_initial_pose_received_condition_bt_node + - nav2_reinitialize_global_localization_service_bt_node + - nav2_rate_controller_bt_node + - nav2_distance_controller_bt_node + - nav2_speed_controller_bt_node + - nav2_truncate_path_action_bt_node + - nav2_truncate_path_local_action_bt_node + - nav2_goal_updater_node_bt_node + - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node + - nav2_round_robin_node_bt_node + - nav2_transform_available_condition_bt_node + - nav2_time_expired_condition_bt_node + - nav2_path_expiring_timer_condition + - nav2_distance_traveled_condition_bt_node + - nav2_single_trigger_bt_node + - nav2_goal_updated_controller_bt_node + - nav2_is_battery_low_condition_bt_node + - nav2_navigate_through_poses_action_bt_node + - nav2_navigate_to_pose_action_bt_node + - nav2_remove_passed_goals_action_bt_node + - nav2_planner_selector_bt_node + - nav2_controller_selector_bt_node + - nav2_goal_checker_selector_bt_node + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_assisted_teleop_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node + - nav2_is_battery_charging_condition_bt_node + error_code_names: + - compute_path_error_code + - follow_path_error_code + +controller_server: + ros__parameters: + controller_frequency: 20.0 + min_x_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 + min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 + progress_checker_plugins: ["progress_checker"] + goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" + controller_plugins: ["FollowPath"] + + # Progress checker parameters + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.5 + movement_time_allowance: 10.0 + # Goal checker parameters + #precise_goal_checker: + # plugin: "nav2_controller::SimpleGoalChecker" + # xy_goal_tolerance: 0.25 + # yaw_goal_tolerance: 0.25 + # stateful: True + general_goal_checker: + stateful: True + plugin: "nav2_controller::SimpleGoalChecker" + xy_goal_tolerance: 0.25 + yaw_goal_tolerance: 0.25 + # DWB parameters + FollowPath: + plugin: "dwb_core::DWBLocalPlanner" + debug_trajectory_details: True + min_vel_x: 0.0 + min_vel_y: 0.0 + max_vel_x: 0.26 + max_vel_y: 0.0 + max_vel_theta: 1.0 + min_speed_xy: 0.0 + max_speed_xy: 0.26 + min_speed_theta: 0.0 + # Add high threshold velocity for turtlebot 3 issue. + # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 + acc_lim_x: 2.5 + acc_lim_y: 0.0 + acc_lim_theta: 3.2 + decel_lim_x: -2.5 + decel_lim_y: 0.0 + decel_lim_theta: -3.2 + vx_samples: 20 + vy_samples: 5 + vtheta_samples: 20 + sim_time: 1.7 + linear_granularity: 0.05 + angular_granularity: 0.025 + transform_tolerance: 0.2 + xy_goal_tolerance: 0.25 + trans_stopped_velocity: 0.25 + short_circuit_trajectory_evaluation: True + stateful: True + critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] + BaseObstacle.scale: 0.02 + PathAlign.scale: 32.0 + PathAlign.forward_point_distance: 0.1 + GoalAlign.scale: 24.0 + GoalAlign.forward_point_distance: 0.1 + PathDist.scale: 32.0 + GoalDist.scale: 24.0 + RotateToGoal.scale: 32.0 + RotateToGoal.slowing_factor: 5.0 + RotateToGoal.lookahead_time: -1.0 + +local_costmap: + local_costmap: + ros__parameters: + update_frequency: 5.0 + publish_frequency: 2.0 + global_frame: odom + robot_base_frame: base_link + rolling_window: true + width: 3 + height: 3 + resolution: 0.05 + robot_radius: 0.22 + plugins: ["voxel_layer", "inflation_layer"] + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.55 + voxel_layer: + plugin: "nav2_costmap_2d::VoxelLayer" + enabled: True + publish_voxel_map: True + origin_z: 0.0 + z_resolution: 0.05 + z_voxels: 16 + max_obstacle_height: 2.0 + mark_threshold: 0 + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: True + always_send_full_costmap: True + +global_costmap: + global_costmap: + ros__parameters: + update_frequency: 1.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: base_link + robot_radius: 0.22 + resolution: 0.1 + # When using GPS navigation you will potentially traverse huge environments which are not practical to + # fit on a big static costmap. Thus it is recommended to use a rolling global costmap large enough to + # contain each pair of successive waypoints. See: https://github.com/ros-planning/navigation2/issues/2174 + rolling_window: True + width: 50 + height: 50 + track_unknown_space: true + # no static map + plugins: ["obstacle_layer", "inflation_layer"] + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 + # outdoors there will probably be more inf points + inf_is_valid: true + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.55 + always_send_full_costmap: True + +# The yaml_filename does not need to be specified since it going to be set by defaults in launch. +# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py +# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used. +# map_server: +# ros__parameters: +# yaml_filename: "" + +map_saver: + ros__parameters: + save_map_timeout: 5.0 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: True + +planner_server: + ros__parameters: + expected_planner_frequency: 20.0 + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + +smoother_server: + ros__parameters: + smoother_plugins: ["simple_smoother"] + simple_smoother: + plugin: "nav2_smoother::SimpleSmoother" + tolerance: 1.0e-10 + max_its: 1000 + do_refinement: True + +behavior_server: + ros__parameters: + local_costmap_topic: local_costmap/costmap_raw + global_costmap_topic: global_costmap/costmap_raw + local_footprint_topic: local_costmap/published_footprint + global_footprint_topic: global_costmap/published_footprint + cycle_frequency: 10.0 + behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] + spin: + plugin: "nav2_behaviors/Spin" + backup: + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" + wait: + plugin: "nav2_behaviors/Wait" + assisted_teleop: + plugin: "nav2_behaviors/AssistedTeleop" + local_frame: odom + global_frame: map + robot_base_frame: base_link + transform_tolerance: 0.1 + simulate_ahead_time: 2.0 + max_rotational_vel: 1.0 + min_rotational_vel: 0.4 + rotational_acc_lim: 3.2 + +waypoint_follower: + ros__parameters: + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: True + waypoint_pause_duration: 200 + +velocity_smoother: + ros__parameters: + smoothing_frequency: 20.0 + scale_velocities: False + feedback: "OPEN_LOOP" + max_velocity: [0.26, 0.0, 1.0] + min_velocity: [-0.26, 0.0, -1.0] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: "odom" + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 diff --git a/nav2_system_tests/src/gps_navigation/test_case_py.launch.py b/nav2_system_tests/src/gps_navigation/test_case_py.launch.py new file mode 100755 index 0000000000..cd90fdb620 --- /dev/null +++ b/nav2_system_tests/src/gps_navigation/test_case_py.launch.py @@ -0,0 +1,132 @@ +#! /usr/bin/env python3 +# Copyright (c) 2019 Samsung Research America +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import sys + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch import LaunchService +from launch.actions import ( + ExecuteProcess, + IncludeLaunchDescription, + SetEnvironmentVariable, +) +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +from launch_testing.legacy import LaunchTestService + +from nav2_common.launch import RewrittenYaml + + +def generate_launch_description(): + world = os.getenv("TEST_WORLD") + + launch_dir = os.path.dirname(os.path.realpath(__file__)) + params_file = os.path.join(launch_dir, "nav2_no_map_params.yaml") + bringup_dir = get_package_share_directory("nav2_bringup") + + configured_params = RewrittenYaml( + source_file=params_file, root_key="", param_rewrites="", convert_types=True + ) + + return LaunchDescription( + [ + SetEnvironmentVariable("RCUTILS_LOGGING_BUFFERED_STREAM", "1"), + SetEnvironmentVariable("RCUTILS_LOGGING_USE_STDOUT", "1"), + # Launch gazebo server for simulation + ExecuteProcess( + cmd=[ + "gzserver", + "-s", + "libgazebo_ros_init.so", + "--minimal_comms", + world, + ], + output="screen", + ), + # TODO(orduno) Launch the robot state publisher instead + # using a local copy of TB3 urdf file + Node( + package="tf2_ros", + executable="static_transform_publisher", + output="screen", + arguments=["0", "0", "0", "0", "0", "0", "base_footprint", "base_link"], + ), + Node( + package="tf2_ros", + executable="static_transform_publisher", + output="screen", + arguments=["0", "0", "0", "0", "0", "0", "base_link", "base_scan"], + ), + Node( + package="tf2_ros", + executable="static_transform_publisher", + output="screen", + arguments=[ + "-0.32", + "0", + "0.068", + "0", + "0", + "0", + "base_link", + "imu_link", + ], + ), + Node( + package="tf2_ros", + executable="static_transform_publisher", + output="screen", + arguments=["0", "0", "0", "0", "0", "0", "base_link", "gps_link"], + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(bringup_dir, "launch", "navigation_launch.py") + ), + launch_arguments={ + "use_sim_time": "True", + "params_file": configured_params, + "autostart": "True", + }.items(), + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(launch_dir, "dual_ekf_navsat.launch.py") + ), + ), + ] + ) + + +def main(argv=sys.argv[1:]): + ld = generate_launch_description() + + test1_action = ExecuteProcess( + cmd=[os.path.join(os.getenv("TEST_DIR"), "tester.py")], + name="tester_node", + output="screen", + ) + + lts = LaunchTestService() + lts.add_test_action(ld, test1_action) + ls = LaunchService(argv=argv) + ls.include_launch_description(ld) + return lts.run(ls) + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/nav2_system_tests/src/gps_navigation/tester.py b/nav2_system_tests/src/gps_navigation/tester.py new file mode 100755 index 0000000000..aab8833668 --- /dev/null +++ b/nav2_system_tests/src/gps_navigation/tester.py @@ -0,0 +1,222 @@ +#! /usr/bin/env python3 +# Copyright 2019 Samsung Research America +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import sys +import time + +from action_msgs.msg import GoalStatus +from geographic_msgs.msg import GeoPose +from nav2_msgs.action import ComputePathToPose, FollowGPSWaypoints +from nav2_msgs.srv import ManageLifecycleNodes +from rcl_interfaces.srv import SetParameters +from rclpy.parameter import Parameter + +import rclpy +from rclpy.action import ActionClient +from rclpy.node import Node + + +class GpsWaypointFollowerTest(Node): + def __init__(self): + super().__init__(node_name="nav2_gps_waypoint_tester", namespace="") + self.waypoints = None + self.action_client = ActionClient( + self, FollowGPSWaypoints, "follow_gps_waypoints" + ) + self.goal_handle = None + self.action_result = None + + self.param_cli = self.create_client(SetParameters, + '/waypoint_follower/set_parameters') + + def setWaypoints(self, waypoints): + self.waypoints = [] + for wp in waypoints: + msg = GeoPose() + msg.position.latitude = wp[0] + msg.position.longitude = wp[1] + msg.orientation.w = 1.0 + self.waypoints.append(msg) + + def run(self, block, cancel): + # if not self.waypoints: + # rclpy.error_msg("Did not set valid waypoints before running test!") + # return False + + while not self.action_client.wait_for_server(timeout_sec=1.0): + self.info_msg( + "'follow_gps_waypoints' action server not available, waiting...") + + action_request = FollowGPSWaypoints.Goal() + action_request.gps_poses = self.waypoints + + self.info_msg("Sending goal request...") + send_goal_future = self.action_client.send_goal_async(action_request) + try: + rclpy.spin_until_future_complete(self, send_goal_future) + self.goal_handle = send_goal_future.result() + except Exception as e: # noqa: B902 + self.error_msg(f"Service call failed {e!r}") + + if not self.goal_handle.accepted: + self.error_msg("Goal rejected") + return False + + self.info_msg("Goal accepted") + if not block: + return True + + get_result_future = self.goal_handle.get_result_async() + if cancel: + time.sleep(2) + self.cancel_goal() + + self.info_msg("Waiting for 'follow_gps_waypoints' action to complete") + try: + rclpy.spin_until_future_complete(self, get_result_future) + status = get_result_future.result().status + result = get_result_future.result().result + self.action_result = result + except Exception as e: # noqa: B902 + self.error_msg(f"Service call failed {e!r}") + + if status != GoalStatus.STATUS_SUCCEEDED: + self.info_msg(f"Goal failed with status code: {status}") + return False + if len(result.missed_waypoints) > 0: + self.info_msg( + "Goal failed to process all waypoints," + " missed {0} wps.".format(len(result.missed_waypoints)) + ) + return False + + self.info_msg("Goal succeeded!") + return True + + def setStopFailureParam(self, value): + req = SetParameters.Request() + req.parameters = [Parameter('stop_on_failure', + Parameter.Type.BOOL, value).to_parameter_msg()] + future = self.param_cli.call_async(req) + rclpy.spin_until_future_complete(self, future) + + def shutdown(self): + self.info_msg("Shutting down") + + self.action_client.destroy() + self.info_msg("Destroyed follow_gps_waypoints action client") + + transition_service = "lifecycle_manager_navigation/manage_nodes" + mgr_client = self.create_client( + ManageLifecycleNodes, transition_service) + while not mgr_client.wait_for_service(timeout_sec=1.0): + self.info_msg( + f"{transition_service} service not available, waiting...") + + req = ManageLifecycleNodes.Request() + req.command = ManageLifecycleNodes.Request().SHUTDOWN + future = mgr_client.call_async(req) + try: + rclpy.spin_until_future_complete(self, future) + future.result() + except Exception as e: # noqa: B902 + self.error_msg(f"{transition_service} service call failed {e!r}") + + self.info_msg(f"{transition_service} finished") + + def cancel_goal(self): + cancel_future = self.goal_handle.cancel_goal_async() + rclpy.spin_until_future_complete(self, cancel_future) + + def info_msg(self, msg: str): + self.get_logger().info(msg) + + def warn_msg(self, msg: str): + self.get_logger().warn(msg) + + def error_msg(self, msg: str): + self.get_logger().error(msg) + + +def main(argv=sys.argv[1:]): + rclpy.init() + + # wait a few seconds to make sure entire stacks are up + time.sleep(10) + + wps = [[55.944831, -3.186998], [55.944818, -3.187075], [55.944782, -3.187060]] + + test = GpsWaypointFollowerTest() + test.setWaypoints(wps) + + # wait for poseCallback + + result = test.run(True, False) + assert result + + # preempt with new point + test.setWaypoints([wps[0]]) + result = test.run(False, False) + time.sleep(2) + test.setWaypoints([wps[1]]) + result = test.run(False, False) + + # cancel + time.sleep(2) + test.cancel_goal() + + # set waypoint outside of map + time.sleep(2) + test.setWaypoints([[35.0, -118.0]]) + result = test.run(True, False) + assert not result + result = not result + assert test.action_result.missed_waypoints[0].error_code == \ + ComputePathToPose.Result().GOAL_OUTSIDE_MAP + + # stop on failure test with bogous waypoint + test.setStopFailureParam(True) + bwps = [[55.944831, -3.186998], [35.0, -118.0], [55.944782, -3.187060]] + test.setWaypoints(bwps) + result = test.run(True, False) + assert not result + result = not result + mwps = test.action_result.missed_waypoints + result = (len(mwps) == 1) & (mwps[0] == 1) + test.setStopFailureParam(False) + + # Zero goal test + test.setWaypoints([]) + result = test.run(True, False) + + # Cancel test + test.setWaypoints(wps) + result = test.run(True, True) + assert not result + result = not result + + test.shutdown() + test.info_msg("Done Shutting Down.") + + if not result: + test.info_msg("Exiting failed") + exit(1) + else: + test.info_msg("Exiting passed") + exit(0) + + +if __name__ == "__main__": + main() diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world new file mode 100644 index 0000000000..94b72499a2 --- /dev/null +++ b/nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world @@ -0,0 +1,555 @@ + + + + + + + EARTH_WGS84 + ENU + 55.944831 + -3.186998 + 0.0 + 180.0 + + + + model://ground_plane + + + + model://sun + + + + false + + + + + 0.319654 -0.235002 9.29441 0 1.5138 0.009599 + orbit + perspective + + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + -2.0 -0.5 0.01 0.0 0.0 0.0 + + + + + + + -0.064 0 0.048 0 0 0 + + 0.001 + 0.000 + 0.000 + 0.001 + 0.000 + 0.001 + + 1.0 + + + + -0.064 0 0.048 0 0 0 + + + 0.265 0.265 0.089 + + + + + + -0.064 0 0 0 0 0 + + + model://turtlebot3_waffle/meshes/waffle_base.dae + 0.001 0.001 0.001 + + + + + + + + true + 200 + + + + + 0.0 + 2e-4 + + + + + 0.0 + 2e-4 + + + + + 0.0 + 2e-4 + + + + + + + 0.0 + 1.7e-2 + + + + + 0.0 + 1.7e-2 + + + + + 0.0 + 1.7e-2 + + + + + + false + + + ~/out:=/imu/data + + + + + + + + + -0.052 0 0.111 0 0 0 + + 0.001 + 0.001 + 0.000 + 0.000 + 0.001 + 0.000 + 0.001 + + 0.125 + + + true + 1 + 0 0 0 0 0 0 + + + + + 0.0 + 0.1 + + + + + 0.0 + 0.0 + + + + + + + ~/out:=/gps/fix + + + + + + + + -0.052 0 0.111 0 0 0 + + 0.001 + 0.000 + 0.000 + 0.001 + 0.000 + 0.001 + + 0.125 + + + + -0.064 0 0.121 0 0 0 + + + 0.0508 + 0.055 + + + + + + -0.032 0 0.171 0 0 0 + + + model://turtlebot3_waffle/meshes/lds.dae + 0.001 0.001 0.001 + + + + + + true + false + -0.064 0 0.121 0 0 0 + 5 + + + + 360 + 1.000000 + 0.000000 + 6.280000 + + + + 0.120000 + 3.5 + 0.015000 + + + gaussian + 0.0 + 0.01 + + + + + + ~/out:=scan + + sensor_msgs/LaserScan + + + + + + + + 0.0 0.144 0.023 -1.57 0 0 + + 0.001 + 0.000 + 0.000 + 0.001 + 0.000 + 0.001 + + 0.1 + + + + 0.0 0.144 0.023 -1.57 0 0 + + + 0.033 + 0.018 + + + + + + + 100000.0 + 100000.0 + 0 0 0 + 0.0 + 0.0 + + + + + 0 + 0.2 + 1e+5 + 1 + 0.01 + 0.001 + + + + + + + 0.0 0.144 0.023 0 0 0 + + + model://turtlebot3_waffle/meshes/left_tire.dae + 0.001 0.001 0.001 + + + + + + + + + 0.0 -0.144 0.023 -1.57 0 0 + + 0.001 + 0.000 + 0.000 + 0.001 + 0.000 + 0.001 + + 0.1 + + + + 0.0 -0.144 0.023 -1.57 0 0 + + + 0.033 + 0.018 + + + + + + + 100000.0 + 100000.0 + 0 0 0 + 0.0 + 0.0 + + + + + 0 + 0.2 + 1e+5 + 1 + 0.01 + 0.001 + + + + + + + 0.0 -0.144 0.023 0 0 0 + + + model://turtlebot3_waffle/meshes/right_tire.dae + 0.001 0.001 0.001 + + + + + + + -0.177 -0.064 -0.004 0 0 0 + + 0.001 + + 0.00001 + 0.000 + 0.000 + 0.00001 + 0.000 + 0.00001 + + + + + + 0.005000 + + + + + + 0 + 0.2 + 1e+5 + 1 + 0.01 + 0.001 + + + + + + + + -0.177 0.064 -0.004 0 0 0 + + 0.001 + + 0.00001 + 0.000 + 0.000 + 0.00001 + 0.000 + 0.00001 + + + + + + 0.005000 + + + + + + 0 + 0.2 + 1e+5 + 1 + 0.01 + 0.001 + + + + + + + + base_footprint + base_link + 0.0 0.0 0.010 0 0 0 + + + + base_link + wheel_left_link + 0.0 0.144 0.023 -1.57 0 0 + + 0 0 1 + + + + + base_link + wheel_right_link + 0.0 -0.144 0.023 -1.57 0 0 + + 0 0 1 + + + + + base_link + caster_back_right_link + + + + base_link + caster_back_left_link + + + + base_link + imu_link + -0.032 0 0.068 0 0 0 + + 0 0 1 + + + + + base_link + gps_link + -0.05 0 0.05 0 0 0 + + 0 0 1 + + + + + base_link + base_scan + -0.064 0 0.121 0 0 0 + + 0 0 1 + + + + + + + + /tf:=tf + + + + wheel_left_joint + wheel_right_joint + + + 0.287 + 0.066 + + + 20 + 1.0 + + + true + false + false + + odom + base_link + + + + + + + ~/out:=joint_states + + 250 + wheel_left_joint + wheel_right_joint + + + + + + + diff --git a/nav2_util/include/nav2_util/service_client.hpp b/nav2_util/include/nav2_util/service_client.hpp index be7340e8fb..6f25965d1e 100644 --- a/nav2_util/include/nav2_util/service_client.hpp +++ b/nav2_util/include/nav2_util/service_client.hpp @@ -26,7 +26,7 @@ namespace nav2_util * @class nav2_util::ServiceClient * @brief A simple wrapper on ROS2 services for invoke() and block-style calling */ -template +template class ServiceClient { public: @@ -37,14 +37,14 @@ class ServiceClient */ explicit ServiceClient( const std::string & service_name, - const rclcpp::Node::SharedPtr & provided_node) + const NodeT & provided_node) : service_name_(service_name), node_(provided_node) { callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - client_ = node_->create_client( + client_ = node_->template create_client( service_name, rclcpp::SystemDefaultsQoS(), callback_group_); @@ -147,7 +147,7 @@ class ServiceClient protected: std::string service_name_; - rclcpp::Node::SharedPtr node_; + NodeT node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; typename rclcpp::Client::SharedPtr client_; diff --git a/nav2_waypoint_follower/CMakeLists.txt b/nav2_waypoint_follower/CMakeLists.txt index a3b46942bc..1d5405878b 100644 --- a/nav2_waypoint_follower/CMakeLists.txt +++ b/nav2_waypoint_follower/CMakeLists.txt @@ -22,6 +22,8 @@ find_package(nav2_util REQUIRED) find_package(tf2_ros REQUIRED) find_package(nav2_core REQUIRED) find_package(pluginlib REQUIRED) +find_package(robot_localization REQUIRED) +find_package(geographic_msgs REQUIRED) nav2_package() @@ -57,6 +59,7 @@ set(dependencies image_transport cv_bridge OpenCV + robot_localization ) ament_target_dependencies(${executable_name} diff --git a/nav2_waypoint_follower/README.md b/nav2_waypoint_follower/README.md index cd0a2366b9..5d6a049857 100644 --- a/nav2_waypoint_follower/README.md +++ b/nav2_waypoint_follower/README.md @@ -27,3 +27,22 @@ In the first, the ``nav2_waypoint_follower`` is weakly sufficient to create a pr In the second, the ``nav2_waypoint_follower`` is a nice sample application / proof of concept, but you really need your waypoint following / autonomy system on the robot to carry more weight in making a robust solution. In this case, you should use the ``nav2_behavior_tree`` package to create a custom application-level behavior tree using navigation to complete the task. This can include subtrees like checking for the charge status mid-task for returning to dock or handling more than 1 unit of work in a more complex task. Soon, there will be a ``nav2_bt_waypoint_follower`` (name subject to adjustment) that will allow you to create this application more easily. In this school of thought, the waypoint following application is more closely tied to the system autonomy, or in many cases, is the system autonomy. Neither is better than the other, it highly depends on the tasks your robot(s) are completing, in what type of environment, and with what cloud resources available. Often this distinction is very clear for a given business case. + +## Nav2 GPS Waypoint Follower + +`nav2_waypoint_follower` provides an action server named `FollowGPSWaypoints` which accepts GPS waypoint following requests by using tools provided by `robot_localization` and `nav2_waypoint_follower` itself. + +`robot_localization`'s `navsat_transform_node` provides a service `fromLL`, which is used to convert pure GPS coordinates(longitude, latitude, alitude) +to cartesian coordinates in map frame(x,y), then the existent action named `FollowWaypoints` from `nav2_waypoint_follower` is used to get robot go through each converted waypoints. +The action msg definition for GPS waypoint following can be found [here](../nav2_msgs/action/FollowGPSWaypoints.action). + +In a common use case, an client node can read a set of GPS waypoints from a YAML file an create a client to action server named as `FollowGPSWaypoints`. +For instance, + +```cpp +using ClientT = nav2_msgs::action::FollowGPSWaypoints; +rclcpp_action::Client::SharedPtr gps_waypoint_follower_action_client_; +gps_waypoint_follower_action_client_ = rclcpp_action::create_client(this, "follow_gps_waypoints"); +``` + +All other functionalities provided by `nav2_waypoint_follower` such as WaypointTaskExecutors are usable and can be configured in WaypointTaskExecutor. \ No newline at end of file diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp index e5c59aa20b..8dd0d70cd7 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp @@ -20,18 +20,26 @@ #include #include +#include "rclcpp_action/rclcpp_action.hpp" +#include "pluginlib/class_loader.hpp" +#include "pluginlib/class_list_macros.hpp" +#include "geographic_msgs/msg/geo_pose.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_msgs/action/navigate_to_pose.hpp" #include "nav2_msgs/action/follow_waypoints.hpp" #include "nav2_msgs/msg/missed_waypoint.hpp" #include "nav_msgs/msg/path.hpp" #include "nav2_util/simple_action_server.hpp" -#include "rclcpp_action/rclcpp_action.hpp" - #include "nav2_util/node_utils.hpp" +#include "nav2_util/string_utils.hpp" +#include "nav2_msgs/action/follow_gps_waypoints.hpp" +#include "nav2_util/service_client.hpp" #include "nav2_core/waypoint_task_executor.hpp" -#include "pluginlib/class_loader.hpp" -#include "pluginlib/class_list_macros.hpp" + +#include "robot_localization/srv/from_ll.hpp" +#include "tf2_ros/buffer.h" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" +#include "tf2_ros/transform_listener.h" namespace nav2_waypoint_follower { @@ -63,6 +71,10 @@ class WaypointFollower : public nav2_util::LifecycleNode using ActionServer = nav2_util::SimpleActionServer; using ActionClient = rclcpp_action::Client; + // Shorten the types for GPS waypoint following + using ActionTGPS = nav2_msgs::action::FollowGPSWaypoints; + using ActionServerGPS = nav2_util::SimpleActionServer; + /** * @brief A constructor for nav2_waypoint_follower::WaypointFollower class * @param options Additional options to control creation of the node. @@ -107,15 +119,40 @@ class WaypointFollower : public nav2_util::LifecycleNode */ nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + /** + * @brief Templated function to perform internal logic behind waypoint following, + * Both GPS and non GPS waypoint following callbacks makes use of this function when a client asked to do so. + * Callbacks fills in appropriate types for the tempelated types, see followWaypointCallback funtions for details. + * + * @tparam T action_server + * @tparam V feedback + * @tparam Z result + * @param action_server + * @param poses + * @param feedback + * @param result + */ + template + void followWaypointsHandler(const T & action_server, const V & feedback, const Z & result); + /** * @brief Action server callbacks */ - void followWaypoints(); + void followWaypointsCallback(); /** - * @brief Action client result callback - * @param result Result of action server updated asynchronously + * @brief send robot through each of GPS + * point , which are converted to map frame first then using a client to + * `FollowWaypoints` action. + * + * @param waypoints, acquired from action client */ + void followGPSWaypointsCallback(); + + /** + * @brief Action client result callback + * @param result Result of action server updated asynchronously + */ void resultCallback(const rclcpp_action::ClientGoalHandle::WrappedResult & result); /** @@ -124,6 +161,32 @@ class WaypointFollower : public nav2_util::LifecycleNode */ void goalResponseCallback(const rclcpp_action::ClientGoalHandle::SharedPtr & goal); + /** + * @brief given some gps_poses, converts them to map frame using robot_localization's service `fromLL`. + * Constructs a vector of stamped poses in map frame and returns them. + * + * @param gps_poses, from the action server + * @return std::vector + */ + std::vector convertGPSPosesToMapPoses( + const std::vector & gps_poses); + + + /** + * @brief get the latest poses on the action server goal. If they are GPS poses, + * convert them to the global cartesian frame using /fromLL robot localization + * server + * + * @param action_server, to which the goal was sent + * @return std::vector + */ + template + std::vector getLatestGoalPoses(const T & action_server); + + // Common vars used for both GPS and cartesian point following + std::vector failed_ids_; + std::string global_frame_id_{"map"}; + /** * @brief Callback executed when a parameter change is detected * @param event ParameterEvent message @@ -135,12 +198,17 @@ class WaypointFollower : public nav2_util::LifecycleNode rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; // Our action server - std::unique_ptr action_server_; + std::unique_ptr xyz_action_server_; ActionClient::SharedPtr nav_to_pose_client_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; std::shared_future::SharedPtr> future_goal_handle_; + // Our action server for GPS waypoint following + std::unique_ptr gps_action_server_; + std::unique_ptr>> from_ll_to_map_client_; + bool stop_on_failure_; int loop_rate_; GoalStatus current_goal_status_; diff --git a/nav2_waypoint_follower/package.xml b/nav2_waypoint_follower/package.xml index 42f23858d1..8dfbe41f44 100644 --- a/nav2_waypoint_follower/package.xml +++ b/nav2_waypoint_follower/package.xml @@ -21,7 +21,9 @@ nav2_util nav2_core tf2_ros - + robot_localization + geographic_msgs + ament_lint_common ament_lint_auto ament_cmake_gtest diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index 42342638f0..f462a771a3 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -39,6 +39,8 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options) declare_parameter("action_server_result_timeout", 900.0); + declare_parameter("global_frame_id", "map"); + nav2_util::declare_parameter_if_not_declared( this, std::string("waypoint_task_executor_plugin"), rclcpp::ParameterValue(std::string("wait_at_waypoint"))); @@ -61,6 +63,8 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/) stop_on_failure_ = get_parameter("stop_on_failure").as_bool(); loop_rate_ = get_parameter("loop_rate").as_int(); waypoint_task_executor_id_ = get_parameter("waypoint_task_executor_plugin").as_string(); + global_frame_id_ = get_parameter("global_frame_id").as_string(); + global_frame_id_ = nav2_util::strip_leading_slash(global_frame_id_); callback_group_ = create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, @@ -79,13 +83,30 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/) rcl_action_server_options_t server_options = rcl_action_server_get_default_options(); server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); - action_server_ = std::make_unique( + xyz_action_server_ = std::make_unique( get_node_base_interface(), get_node_clock_interface(), get_node_logging_interface(), get_node_waitables_interface(), "follow_waypoints", std::bind( - &WaypointFollower::followWaypoints, + &WaypointFollower::followWaypointsCallback, + this), nullptr, std::chrono::milliseconds( + 500), false, server_options); + + from_ll_to_map_client_ = std::make_unique< + nav2_util::ServiceClient>>( + "/fromLL", + node); + + gps_action_server_ = std::make_unique( + get_node_base_interface(), + get_node_clock_interface(), + get_node_logging_interface(), + get_node_waitables_interface(), + "follow_gps_waypoints", + std::bind( + &WaypointFollower::followGPSWaypointsCallback, this), nullptr, std::chrono::milliseconds( 500), false, server_options); @@ -113,7 +134,8 @@ WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); - action_server_->activate(); + xyz_action_server_->activate(); + gps_action_server_->activate(); auto node = shared_from_this(); // Add callback for dynamic parameters @@ -131,9 +153,9 @@ WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); - action_server_->deactivate(); + xyz_action_server_->deactivate(); + gps_action_server_->deactivate(); dyn_params_handler_.reset(); - // destroy bond connection destroyBond(); @@ -145,8 +167,10 @@ WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); - action_server_.reset(); + xyz_action_server_.reset(); nav_to_pose_client_.reset(); + gps_action_server_.reset(); + from_ll_to_map_client_.reset(); return nav2_util::CallbackReturn::SUCCESS; } @@ -158,29 +182,55 @@ WaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/) return nav2_util::CallbackReturn::SUCCESS; } -void -WaypointFollower::followWaypoints() +template +std::vector WaypointFollower::getLatestGoalPoses( + const T & action_server) { - auto goal = action_server_->get_current_goal(); - auto feedback = std::make_shared(); - auto result = std::make_shared(); + std::vector poses; + + // compile time static check to decide which block of code to be built + if constexpr (std::is_same>::value) { + // If normal waypoint following callback was called, we build here + poses = action_server->get_current_goal()->poses; + } else { + // If GPS waypoint following callback was called, we build here + poses = convertGPSPosesToMapPoses( + action_server->get_current_goal()->gps_poses); + } + return poses; +} + +template +void WaypointFollower::followWaypointsHandler( + const T & action_server, + const V & feedback, + const Z & result) +{ + auto goal = action_server->get_current_goal(); // handling loops unsigned int current_loop_no = 0; auto no_of_loops = goal->number_of_loops; - // Check if request is valid - if (!action_server_ || !action_server_->is_server_active()) { + std::vector poses; + poses = getLatestGoalPoses(action_server); + + if (!action_server || !action_server->is_server_active()) { RCLCPP_DEBUG(get_logger(), "Action server inactive. Stopping."); return; } RCLCPP_INFO( get_logger(), "Received follow waypoint request with %i waypoints.", - static_cast(goal->poses.size())); + static_cast(poses.size())); - if (goal->poses.size() == 0) { - action_server_->succeeded_current(result); + if (poses.empty()) { + RCLCPP_ERROR( + get_logger(), + "Empty vector of waypoints passed to waypoint following " + "action potentially due to conversation failure or empty request." + ); + action_server->terminate_current(result); return; } @@ -192,20 +242,29 @@ WaypointFollower::followWaypoints() while (rclcpp::ok()) { // Check if asked to stop processing action - if (action_server_->is_cancel_requested()) { + if (action_server->is_cancel_requested()) { auto cancel_future = nav_to_pose_client_->async_cancel_all_goals(); callback_group_executor_.spin_until_future_complete(cancel_future); // for result callback processing callback_group_executor_.spin_some(); - action_server_->terminate_all(); + action_server->terminate_all(); return; } // Check if asked to process another action - if (action_server_->is_preempt_requested()) { + if (action_server->is_preempt_requested()) { RCLCPP_INFO(get_logger(), "Preempting the goal pose."); - goal = action_server_->accept_pending_goal(); - goal_index = goal->goal_index; + goal = action_server->accept_pending_goal(); + poses = getLatestGoalPoses(action_server); + if (poses.empty()) { + RCLCPP_ERROR( + get_logger(), + "Empty vector of Waypoints passed to waypoint following logic. " + "Nothing to execute, returning with failure!"); + action_server->terminate_current(result); + return; + } + goal_index = 0; new_goal = true; } @@ -213,20 +272,24 @@ WaypointFollower::followWaypoints() if (new_goal) { new_goal = false; ClientT::Goal client_goal; - client_goal.pose = goal->poses[goal_index]; + client_goal.pose = poses[goal_index]; + client_goal.pose.header.stamp = this->now(); auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); - send_goal_options.result_callback = - std::bind(&WaypointFollower::resultCallback, this, std::placeholders::_1); - send_goal_options.goal_response_callback = - std::bind(&WaypointFollower::goalResponseCallback, this, std::placeholders::_1); + send_goal_options.result_callback = std::bind( + &WaypointFollower::resultCallback, this, + std::placeholders::_1); + send_goal_options.goal_response_callback = std::bind( + &WaypointFollower::goalResponseCallback, + this, std::placeholders::_1); + future_goal_handle_ = nav_to_pose_client_->async_send_goal(client_goal, send_goal_options); current_goal_status_.status = ActionStatus::PROCESSING; } feedback->current_waypoint = goal_index; - action_server_->publish_feedback(feedback); + action_server->publish_feedback(feedback); if ( current_goal_status_.status == ActionStatus::FAILED || @@ -234,7 +297,7 @@ WaypointFollower::followWaypoints() { nav2_msgs::msg::MissedWaypoint missedWaypoint; missedWaypoint.index = goal_index; - missedWaypoint.goal = goal->poses[goal_index]; + missedWaypoint.goal = poses[goal_index]; missedWaypoint.error_code = current_goal_status_.error_code; result->missed_waypoints.push_back(missedWaypoint); @@ -243,7 +306,7 @@ WaypointFollower::followWaypoints() get_logger(), "Failed to process waypoint %i in waypoint " "list and stop on failure is enabled." " Terminating action.", goal_index); - action_server_->terminate_current(result); + action_server->terminate_current(result); current_goal_status_.error_code = 0; return; } else { @@ -256,7 +319,7 @@ WaypointFollower::followWaypoints() get_logger(), "Succeeded processing waypoint %i, processing waypoint task execution", goal_index); bool is_task_executed = waypoint_task_executor_->processAtWaypoint( - goal->poses[goal_index], goal_index); + poses[goal_index], goal_index); RCLCPP_INFO( get_logger(), "Task execution at waypoint %i %s", goal_index, is_task_executed ? "succeeded" : "failed!"); @@ -264,7 +327,7 @@ WaypointFollower::followWaypoints() if (!is_task_executed) { nav2_msgs::msg::MissedWaypoint missedWaypoint; missedWaypoint.index = goal_index; - missedWaypoint.goal = goal->poses[goal_index]; + missedWaypoint.goal = poses[goal_index]; missedWaypoint.error_code = nav2_msgs::action::FollowWaypoints::Result::TASK_EXECUTOR_FAILED; result->missed_waypoints.push_back(missedWaypoint); @@ -276,7 +339,7 @@ WaypointFollower::followWaypoints() " stop on failure is enabled." " Terminating action.", goal_index); - action_server_->terminate_current(result); + action_server->terminate_current(result); current_goal_status_.error_code = 0; return; } else { @@ -290,12 +353,12 @@ WaypointFollower::followWaypoints() // Update server state goal_index++; new_goal = true; - if (goal_index >= goal->poses.size()) { + if (goal_index >= poses.size()) { if (current_loop_no == no_of_loops) { RCLCPP_INFO( get_logger(), "Completed all %zu waypoints requested.", - goal->poses.size()); - action_server_->succeeded_current(result); + poses.size()); + action_server->succeeded_current(result); current_goal_status_.error_code = 0; return; } @@ -312,6 +375,30 @@ WaypointFollower::followWaypoints() } } +void WaypointFollower::followWaypointsCallback() +{ + auto feedback = std::make_shared(); + auto result = std::make_shared(); + + followWaypointsHandler, + ActionT::Feedback::SharedPtr, + ActionT::Result::SharedPtr>( + xyz_action_server_, + feedback, result); +} + +void WaypointFollower::followGPSWaypointsCallback() +{ + auto feedback = std::make_shared(); + auto result = std::make_shared(); + + followWaypointsHandler, + ActionTGPS::Feedback::SharedPtr, + ActionTGPS::Result::SharedPtr>( + gps_action_server_, + feedback, result); +} + void WaypointFollower::resultCallback( const rclcpp_action::ClientGoalHandle::WrappedResult & result) @@ -379,6 +466,58 @@ WaypointFollower::dynamicParametersCallback(std::vector param return result; } +std::vector +WaypointFollower::convertGPSPosesToMapPoses( + const std::vector & gps_poses) +{ + RCLCPP_INFO( + this->get_logger(), "Converting GPS waypoints to %s Frame..", + global_frame_id_.c_str()); + + std::vector poses_in_map_frame_vector; + int waypoint_index = 0; + for (auto && curr_geopose : gps_poses) { + auto request = std::make_shared(); + auto response = std::make_shared(); + request->ll_point.latitude = curr_geopose.position.latitude; + request->ll_point.longitude = curr_geopose.position.longitude; + request->ll_point.altitude = curr_geopose.position.altitude; + + from_ll_to_map_client_->wait_for_service((std::chrono::seconds(1))); + if (!from_ll_to_map_client_->invoke(request, response)) { + RCLCPP_ERROR( + this->get_logger(), + "fromLL service of robot_localization could not convert %i th GPS waypoint to" + "%s frame, going to skip this point!" + "Make sure you have run navsat_transform_node of robot_localization", + waypoint_index, global_frame_id_.c_str()); + if (stop_on_failure_) { + RCLCPP_ERROR( + this->get_logger(), + "Conversion of %i th GPS waypoint to" + "%s frame failed and stop_on_failure is set to true" + "Not going to execute any of waypoints, exiting with failure!", + waypoint_index, global_frame_id_.c_str()); + return std::vector(); + } + continue; + } else { + geometry_msgs::msg::PoseStamped curr_pose_map_frame; + curr_pose_map_frame.header.frame_id = global_frame_id_; + curr_pose_map_frame.header.stamp = this->now(); + curr_pose_map_frame.pose.position = response->map_point; + curr_pose_map_frame.pose.orientation = curr_geopose.orientation; + poses_in_map_frame_vector.push_back(curr_pose_map_frame); + } + waypoint_index++; + } + RCLCPP_INFO( + this->get_logger(), + "Converted all %i GPS waypoint to %s frame", + static_cast(poses_in_map_frame_vector.size()), global_frame_id_.c_str()); + return poses_in_map_frame_vector; +} + } // namespace nav2_waypoint_follower #include "rclcpp_components/register_node_macro.hpp" diff --git a/tools/underlay.repos b/tools/underlay.repos index 947aa5c66a..2e092f2517 100644 --- a/tools/underlay.repos +++ b/tools/underlay.repos @@ -19,10 +19,22 @@ repositories: # type: git # url: https://github.com/ros/bond_core.git # version: ros2 + # ros/diagnostics: + # type: git + # url: https://github.com/ros/diagnostics.git + # version: ros2-devel + # ros/geographic_info: + # type: git + # url: https://github.com/ros-geographic-info/geographic_info.git + # version: ros2 # ompl/ompl: # type: git # url: https://github.com/ompl/ompl.git # version: main + # robot_localization/robot_localization: + # type: git + # url: https://github.com/cra-ros-pkg/robot_localization.git + # version: ros2 # ros-simulation/gazebo_ros_pkgs: # type: git # url: https://github.com/ros-simulation/gazebo_ros_pkgs.git From c2d84dfe671077bd76781ea356141b6d7ebb86f4 Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Wed, 27 Sep 2023 11:56:39 +0200 Subject: [PATCH 19/31] collision_monitor: dynamic polygon and source enable/disable (#3825) * Rename PushRosNamespace to PushROSNamespace * Fix min_points checking * initial * fix * fix * remove unrelated change * reset * fix format * PR fixes * Add test * fix comments * add to params * publish only if enabled * Add source dynamic enable/disable * add enabled param to sources * fix * add same to collision detector --- .../nav2_collision_monitor/polygon.hpp | 16 ++ .../include/nav2_collision_monitor/source.hpp | 23 +++ .../params/collision_detector_params.yaml | 3 + .../params/collision_monitor_params.yaml | 6 + .../src/collision_detector_node.cpp | 11 +- .../src/collision_monitor_node.cpp | 11 +- nav2_collision_monitor/src/pointcloud.cpp | 1 + nav2_collision_monitor/src/polygon.cpp | 34 +++++ nav2_collision_monitor/src/range.cpp | 1 + nav2_collision_monitor/src/scan.cpp | 1 + nav2_collision_monitor/src/source.cpp | 40 +++++ .../test/collision_monitor_node_test.cpp | 141 ++++++++++++++++++ 12 files changed, 284 insertions(+), 4 deletions(-) diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp index a68fece757..815694d83c 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp @@ -85,6 +85,11 @@ class Polygon * @return Action type for current polygon */ ActionType getActionType() const; + /** + * @brief Obtains polygon enabled state + * @return Whether polygon is enabled + */ + bool getEnabled() const; /** * @brief Obtains polygon minimum points to enter inside polygon causing the action * @return Minimum number of data readings within a zone to trigger the action @@ -191,6 +196,13 @@ class Polygon */ void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg); + /** + * @brief Callback executed when a parameter change is detected + * @param event ParameterEvent message + */ + rcl_interfaces::msg::SetParametersResult dynamicParametersCallback( + std::vector parameters); + /** * @brief Checks if point is inside polygon * @param point Given point to check @@ -204,6 +216,8 @@ class Polygon nav2_util::LifecycleNode::WeakPtr node_; /// @brief Collision monitor node logger stored for further usage rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")}; + /// @brief Dynamic parameters handler + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; // Basic parameters /// @brief Name of polygon @@ -222,6 +236,8 @@ class Polygon double time_before_collision_; /// @brief Time step for robot movement simulation double simulation_time_step_; + /// @brief Whether polygon is enabled + bool enabled_; /// @brief Polygon subscription rclcpp::Subscription::SharedPtr polygon_sub_; /// @brief Footprint subscriber diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp index 8bc750cc71..30d58d53bc 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp @@ -74,7 +74,19 @@ class Source const rclcpp::Time & curr_time, std::vector & data) const = 0; + /** + * @brief Obtains source enabled state + * @return Whether source is enabled + */ + bool getEnabled() const; + protected: + /** + * @brief Source configuration routine. + * @return True in case of everything is configured correctly, or false otherwise + */ + bool configure(); + /** * @brief Supporting routine obtaining ROS-parameters common for all data sources * @param source_topic Output name of source subscription topic @@ -91,12 +103,21 @@ class Source const rclcpp::Time & source_time, const rclcpp::Time & curr_time) const; + /** + * @brief Callback executed when a parameter change is detected + * @param event ParameterEvent message + */ + rcl_interfaces::msg::SetParametersResult dynamicParametersCallback( + std::vector parameters); + // ----- Variables ----- /// @brief Collision Monitor node nav2_util::LifecycleNode::WeakPtr node_; /// @brief Collision monitor node logger stored for further usage rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")}; + /// @brief Dynamic parameters handler + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; // Basic parameters /// @brief Name of data source @@ -116,6 +137,8 @@ class Source /// @brief Whether to correct source data towards to base frame movement, /// considering the difference between current time and latest source time bool base_shift_correction_; + /// @brief Whether source is enabled + bool enabled_; }; // class Source } // namespace nav2_collision_monitor diff --git a/nav2_collision_monitor/params/collision_detector_params.yaml b/nav2_collision_monitor/params/collision_detector_params.yaml index 218ce45239..68b4cd7b50 100644 --- a/nav2_collision_monitor/params/collision_detector_params.yaml +++ b/nav2_collision_monitor/params/collision_detector_params.yaml @@ -14,12 +14,15 @@ collision_detector: min_points: 4 visualize: True polygon_pub_topic: "polygon_front" + enabled: True observation_sources: ["scan"] scan: type: "scan" topic: "scan" + enabled: True pointcloud: type: "pointcloud" topic: "/intel_realsense_r200_depth/points" min_height: 0.1 max_height: 0.5 + enabled: True diff --git a/nav2_collision_monitor/params/collision_monitor_params.yaml b/nav2_collision_monitor/params/collision_monitor_params.yaml index e518ef680e..fcb01f5482 100644 --- a/nav2_collision_monitor/params/collision_monitor_params.yaml +++ b/nav2_collision_monitor/params/collision_monitor_params.yaml @@ -22,6 +22,7 @@ collision_monitor: min_points: 4 visualize: True polygon_pub_topic: "polygon_stop" + enabled: True PolygonSlow: type: "polygon" points: [0.4, 0.4, 0.4, -0.4, -0.4, -0.4, -0.4, 0.4] @@ -30,6 +31,7 @@ collision_monitor: slowdown_ratio: 0.3 visualize: True polygon_pub_topic: "polygon_slowdown" + enabled: True PolygonLimit: type: "polygon" points: [0.5, 0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5] @@ -39,6 +41,7 @@ collision_monitor: angular_limit: 0.5 visualize: True polygon_pub_topic: "polygon_limit" + enabled: True FootprintApproach: type: "polygon" action_type: "approach" @@ -47,12 +50,15 @@ collision_monitor: simulation_time_step: 0.1 min_points: 6 visualize: False + enabled: True observation_sources: ["scan"] scan: type: "scan" topic: "scan" + enabled: True pointcloud: type: "pointcloud" topic: "/intel_realsense_r200_depth/points" min_height: 0.1 max_height: 0.5 + enabled: True diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index 98433ead04..29d380fa05 100644 --- a/nav2_collision_monitor/src/collision_detector_node.cpp +++ b/nav2_collision_monitor/src/collision_detector_node.cpp @@ -304,13 +304,18 @@ void CollisionDetector::process() // Fill collision_points array from different data sources for (std::shared_ptr source : sources_) { - source->getData(curr_time, collision_points); + if (source->getEnabled()) { + source->getData(curr_time, collision_points); + } } std::unique_ptr state_msg = std::make_unique(); for (std::shared_ptr polygon : polygons_) { + if (!polygon->getEnabled()) { + continue; + } state_msg->polygons.push_back(polygon->getName()); state_msg->detections.push_back( polygon->getPointsInside( @@ -326,7 +331,9 @@ void CollisionDetector::process() void CollisionDetector::publishPolygons() const { for (std::shared_ptr polygon : polygons_) { - polygon->publish(); + if (polygon->getEnabled()) { + polygon->publish(); + } } } diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 8b7984a9c7..a1395a7b70 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -373,7 +373,9 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in) // Fill collision_points array from different data sources for (std::shared_ptr source : sources_) { - source->getData(curr_time, collision_points); + if (source->getEnabled()) { + source->getData(curr_time, collision_points); + } } // By default - there is no action @@ -382,6 +384,9 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in) std::shared_ptr action_polygon; for (std::shared_ptr polygon : polygons_) { + if (!polygon->getEnabled()) { + continue; + } if (robot_action.action_type == STOP) { // If robot already should stop, do nothing break; @@ -545,7 +550,9 @@ void CollisionMonitor::notifyActionState( void CollisionMonitor::publishPolygons() const { for (std::shared_ptr polygon : polygons_) { - polygon->publish(); + if (polygon->getEnabled()) { + polygon->publish(); + } } } diff --git a/nav2_collision_monitor/src/pointcloud.cpp b/nav2_collision_monitor/src/pointcloud.cpp index 4582703b2f..f23f5e0bfe 100644 --- a/nav2_collision_monitor/src/pointcloud.cpp +++ b/nav2_collision_monitor/src/pointcloud.cpp @@ -49,6 +49,7 @@ PointCloud::~PointCloud() void PointCloud::configure() { + Source::configure(); auto node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; diff --git a/nav2_collision_monitor/src/polygon.cpp b/nav2_collision_monitor/src/polygon.cpp index 8b7a3c7c00..248bdcec6d 100644 --- a/nav2_collision_monitor/src/polygon.cpp +++ b/nav2_collision_monitor/src/polygon.cpp @@ -48,6 +48,7 @@ Polygon::~Polygon() polygon_sub_.reset(); polygon_pub_.reset(); poly_.clear(); + dyn_params_handler_.reset(); } bool Polygon::configure() @@ -102,6 +103,10 @@ bool Polygon::configure() polygon_pub_topic, polygon_qos); } + // Add callback for dynamic parameters + dyn_params_handler_ = node->add_on_set_parameters_callback( + std::bind(&Polygon::dynamicParametersCallback, this, std::placeholders::_1)); + return true; } @@ -129,6 +134,11 @@ ActionType Polygon::getActionType() const return action_type_; } +bool Polygon::getEnabled() const +{ + return enabled_; +} + int Polygon::getMinPoints() const { return min_points_; @@ -302,6 +312,10 @@ bool Polygon::getCommonParameters(std::string & polygon_pub_topic) return false; } + nav2_util::declare_parameter_if_not_declared( + node, polygon_name_ + ".enabled", rclcpp::ParameterValue(true)); + enabled_ = node->get_parameter(polygon_name_ + ".enabled").as_bool(); + nav2_util::declare_parameter_if_not_declared( node, polygon_name_ + ".min_points", rclcpp::ParameterValue(4)); min_points_ = node->get_parameter(polygon_name_ + ".min_points").as_int(); @@ -487,6 +501,26 @@ void Polygon::updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr m polygon_ = *msg; } +rcl_interfaces::msg::SetParametersResult +Polygon::dynamicParametersCallback( + std::vector parameters) +{ + rcl_interfaces::msg::SetParametersResult result; + + for (auto parameter : parameters) { + const auto & param_type = parameter.get_type(); + const auto & param_name = parameter.get_name(); + + if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) { + if (param_name == polygon_name_ + "." + "enabled") { + enabled_ = parameter.as_bool(); + } + } + } + result.successful = true; + return result; +} + void Polygon::polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg) { RCLCPP_INFO( diff --git a/nav2_collision_monitor/src/range.cpp b/nav2_collision_monitor/src/range.cpp index cd070d70be..56c0a4750f 100644 --- a/nav2_collision_monitor/src/range.cpp +++ b/nav2_collision_monitor/src/range.cpp @@ -49,6 +49,7 @@ Range::~Range() void Range::configure() { + Source::configure(); auto node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; diff --git a/nav2_collision_monitor/src/scan.cpp b/nav2_collision_monitor/src/scan.cpp index 731ee8baa8..603e2f04e6 100644 --- a/nav2_collision_monitor/src/scan.cpp +++ b/nav2_collision_monitor/src/scan.cpp @@ -47,6 +47,7 @@ Scan::~Scan() void Scan::configure() { + Source::configure(); auto node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; diff --git a/nav2_collision_monitor/src/source.cpp b/nav2_collision_monitor/src/source.cpp index df539495f2..8dcf0c85e2 100644 --- a/nav2_collision_monitor/src/source.cpp +++ b/nav2_collision_monitor/src/source.cpp @@ -43,6 +43,17 @@ Source::~Source() { } +bool Source::configure() +{ + auto node = node_.lock(); + + // Add callback for dynamic parameters + dyn_params_handler_ = node->add_on_set_parameters_callback( + std::bind(&Source::dynamicParametersCallback, this, std::placeholders::_1)); + + return true; +} + void Source::getCommonParameters(std::string & source_topic) { auto node = node_.lock(); @@ -54,6 +65,10 @@ void Source::getCommonParameters(std::string & source_topic) node, source_name_ + ".topic", rclcpp::ParameterValue("scan")); // Set deafult topic for laser scanner source_topic = node->get_parameter(source_name_ + ".topic").as_string(); + + nav2_util::declare_parameter_if_not_declared( + node, source_name_ + ".enabled", rclcpp::ParameterValue(true)); + enabled_ = node->get_parameter(source_name_ + ".enabled").as_bool(); } bool Source::sourceValid( @@ -75,4 +90,29 @@ bool Source::sourceValid( return true; } +bool Source::getEnabled() const +{ + return enabled_; +} + +rcl_interfaces::msg::SetParametersResult +Source::dynamicParametersCallback( + std::vector parameters) +{ + rcl_interfaces::msg::SetParametersResult result; + + for (auto parameter : parameters) { + const auto & param_type = parameter.get_type(); + const auto & param_name = parameter.get_name(); + + if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) { + if (param_name == source_name_ + "." + "enabled") { + enabled_ = parameter.as_bool(); + } + } + } + result.successful = true; + return result; +} + } // namespace nav2_collision_monitor diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index e11f3b1b3d..77f1578a67 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -160,6 +160,9 @@ class Tester : public ::testing::Test const std::chrono::nanoseconds & timeout, const rclcpp::Time & stamp); bool waitCmdVel(const std::chrono::nanoseconds & timeout); + bool waitFuture( + rclcpp::Client::SharedFuture, + const std::chrono::nanoseconds & timeout); bool waitActionState(const std::chrono::nanoseconds & timeout); protected: @@ -186,6 +189,9 @@ class Tester : public ::testing::Test // CollisionMonitor Action state rclcpp::Subscription::SharedPtr action_state_sub_; nav2_msgs::msg::CollisionMonitorState::SharedPtr action_state_; + + // Service client for setting CollisionMonitor parameters + rclcpp::Client::SharedPtr parameters_client_; }; // Tester Tester::Tester() @@ -211,6 +217,10 @@ Tester::Tester() action_state_sub_ = cm_->create_subscription( STATE_TOPIC, rclcpp::SystemDefaultsQoS(), std::bind(&Tester::actionStateCallback, this, std::placeholders::_1)); + parameters_client_ = + cm_->create_client( + std::string( + cm_->get_name()) + "/set_parameters"); } Tester::~Tester() @@ -308,6 +318,11 @@ void Tester::addPolygon( rclcpp::Parameter(polygon_name + ".type", "unknown")); } + cm_->declare_parameter( + polygon_name + ".enabled", rclcpp::ParameterValue(true)); + cm_->set_parameter( + rclcpp::Parameter(polygon_name + ".enabled", true)); + cm_->declare_parameter( polygon_name + ".action_type", rclcpp::ParameterValue(at)); cm_->set_parameter( @@ -579,6 +594,22 @@ bool Tester::waitCmdVel(const std::chrono::nanoseconds & timeout) return false; } +bool Tester::waitFuture( + rclcpp::Client::SharedFuture result_future, + const std::chrono::nanoseconds & timeout) +{ + rclcpp::Time start_time = cm_->now(); + while (rclcpp::ok() && cm_->now() - start_time <= rclcpp::Duration(timeout)) { + std::future_status status = result_future.wait_for(10ms); + if (status == std::future_status::ready) { + return true; + } + rclcpp::spin_some(cm_->get_node_base_interface()); + std::this_thread::sleep_for(10ms); + } + return false; +} + bool Tester::waitActionState(const std::chrono::nanoseconds & timeout) { rclcpp::Time start_time = cm_->now(); @@ -961,6 +992,116 @@ TEST_F(Tester, testCeasePublishZeroVel) cm_->stop(); } +TEST_F(Tester, testPolygonNotEnabled) +{ + // Set Collision Monitor parameters. + // Create a STOP polygon + setCommonParameters(); + addPolygon("Stop", POLYGON, 1.0, "stop"); + // Create a Scan source + addSource(SCAN_NAME, SCAN); + setVectors({"Stop"}, {SCAN_NAME}); + + // Start Collision Monitor node + cm_->start(); + + // Check that robot stops when polygon is enabled + rclcpp::Time curr_time = cm_->now(); + sendTransforms(curr_time); + publishScan(0.5, curr_time); + ASSERT_TRUE(waitData(0.5, 500ms, curr_time)); + publishCmdVel(0.5, 0.2, 0.1); + ASSERT_TRUE(waitCmdVel(500ms)); + ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON); + ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); + ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, STOP); + ASSERT_EQ(action_state_->polygon_name, "Stop"); + + // Disable polygon by calling service + auto set_parameters_msg = std::make_shared(); + auto parameter_msg = std::make_shared(); + parameter_msg->name = "Stop.enabled"; + parameter_msg->value.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + parameter_msg->value.bool_value = false; + set_parameters_msg->parameters.push_back(*parameter_msg); + auto result_future = parameters_client_->async_send_request(set_parameters_msg).future.share(); + ASSERT_TRUE(waitFuture(result_future, 2s)); + + // Check that robot does not stop when polygon is disabled + curr_time = cm_->now(); + sendTransforms(curr_time); + publishScan(0.5, curr_time); + ASSERT_TRUE(waitData(0.5, 500ms, curr_time)); + publishCmdVel(0.5, 0.2, 0.1); + ASSERT_TRUE(waitCmdVel(500ms)); + ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5, EPSILON); + ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2, EPSILON); + ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, DO_NOTHING); + ASSERT_EQ(action_state_->polygon_name, ""); + + // Stop Collision Monitor node + cm_->stop(); +} + +TEST_F(Tester, testSourceNotEnabled) +{ + // Set Collision Monitor parameters. + // Create a STOP polygon + setCommonParameters(); + addPolygon("Stop", POLYGON, 1.0, "stop"); + // Create a Scan source + addSource(SCAN_NAME, SCAN); + setVectors({"Stop"}, {SCAN_NAME}); + + // Start Collision Monitor node + cm_->start(); + + // Check that robot stops when source is enabled + rclcpp::Time curr_time = cm_->now(); + sendTransforms(curr_time); + publishScan(0.5, curr_time); + ASSERT_TRUE(waitData(0.5, 500ms, curr_time)); + publishCmdVel(0.5, 0.2, 0.1); + ASSERT_TRUE(waitCmdVel(500ms)); + ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON); + ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); + ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, STOP); + ASSERT_EQ(action_state_->polygon_name, "Stop"); + + // Disable source by calling service + auto set_parameters_msg = std::make_shared(); + auto parameter_msg = std::make_shared(); + parameter_msg->name = std::string(SCAN_NAME) + ".enabled"; + parameter_msg->value.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + parameter_msg->value.bool_value = false; + set_parameters_msg->parameters.push_back(*parameter_msg); + auto result_future = parameters_client_->async_send_request(set_parameters_msg).future.share(); + ASSERT_TRUE(waitFuture(result_future, 2s)); + + // Check that robot does not stop when source is disabled + curr_time = cm_->now(); + sendTransforms(curr_time); + publishScan(0.5, curr_time); + ASSERT_TRUE(waitData(0.5, 500ms, curr_time)); + publishCmdVel(0.5, 0.2, 0.1); + ASSERT_TRUE(waitCmdVel(500ms)); + ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5, EPSILON); + ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2, EPSILON); + ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, DO_NOTHING); + ASSERT_EQ(action_state_->polygon_name, ""); + + // Stop Collision Monitor node + cm_->stop(); +} + TEST_F(Tester, testProcessNonActive) { rclcpp::Time curr_time = cm_->now(); From 6ee59c8fb2cec96688760bf180b17ebd4c8c158d Mon Sep 17 00:00:00 2001 From: thandal Date: Wed, 27 Sep 2023 15:09:34 -0400 Subject: [PATCH 20/31] Update README.md: fix typo (#3842) --- nav2_mppi_controller/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_mppi_controller/README.md b/nav2_mppi_controller/README.md index 2557bcd7d6..684e428fa2 100644 --- a/nav2_mppi_controller/README.md +++ b/nav2_mppi_controller/README.md @@ -176,7 +176,7 @@ controller_server: TrajectoryVisualizer: trajectory_step: 5 time_step: 3 - AckermannConstrains: + AckermannConstraints: min_turning_r: 0.2 critics: ["ConstraintCritic", "ObstaclesCritic", "GoalCritic", "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic", "PathAngleCritic", "PreferForwardCritic"] ConstraintCritic: From 2d6e9a96354c0ea763e70eedd81225635f7b9db5 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 27 Sep 2023 15:51:14 -0700 Subject: [PATCH 21/31] Update CMakeLists.txt (#3843) --- nav2_mppi_controller/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 5cc8a8c0e9..9d8e0d690d 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -48,7 +48,7 @@ if(COMPILER_SUPPORTS_FMA) endif() # If building one the same hardware to be deployed on, try `-march=native`! -add_compile_options(-O3 -finline-limit=10000000 -ffp-contract=fast -ffast-math -mtune=generic) +add_compile_options(-O3 -finline-limit=10000000 -ffp-contract=fast -ffast-math -mtune=generic -mno-avx512f) add_library(mppi_controller SHARED src/controller.cpp From 840960b93478071f603a3f1c3e1c89148ffe65c0 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 28 Sep 2023 12:35:54 -0700 Subject: [PATCH 22/31] Update package.xml --- nav2_mppi_controller/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_mppi_controller/package.xml b/nav2_mppi_controller/package.xml index 5cb4d4cf05..2bfdfd945e 100644 --- a/nav2_mppi_controller/package.xml +++ b/nav2_mppi_controller/package.xml @@ -4,8 +4,8 @@ nav2_mppi_controller 1.2.0 nav2_mppi_controller - Aleksei Budyakov Steve Macenski + Aleksei Budyakov MIT ament_cmake From 42670c0d7bbe3712afde83550a3747fac1f19c4a Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Thu, 28 Sep 2023 20:37:29 +0100 Subject: [PATCH 23/31] Fixes for compiling with clang on macOS (arm64) (#3831) * amcl: declare void parameter for functions with no args Signed-off-by: Rhys Mainwaring * amcl: remove unused variables Signed-off-by: Rhys Mainwaring * behavior_tree: address clang compilation issues Signed-off-by: Rhys Mainwaring * behaviors: add missing override specifier Signed-off-by: Rhys Mainwaring * bt_navigator: add missing override specifier Signed-off-by: Rhys Mainwaring * collision_monitor: address clang compilation issues Signed-off-by: Rhys Mainwaring * collision_monitor: remove unused variables Signed-off-by: Rhys Mainwaring * constrained_smoother: address clang compilation issues Signed-off-by: Rhys Mainwaring * controller: address clang compilation issues Signed-off-by: Rhys Mainwaring * costmap_2d: add missing override specifier Signed-off-by: Rhys Mainwaring * costmap_2d: address clang compilation issues Signed-off-by: Rhys Mainwaring * costmap_2d: fix link issue for order_layer Signed-off-by: Rhys Mainwaring * dwb_controller: fix clang compile issue, replace ulong with uint32_t Signed-off-by: Rhys Mainwaring * map_server: replace std::experimental::filesystem Signed-off-by: Rhys Mainwaring * map_server: remove dependency on stdc++fs Signed-off-by: Rhys Mainwaring * waypoint_follower: address clang compilation issues Signed-off-by: Rhys Mainwaring * waypoint_follower: remove dependency on stdc++fs Signed-off-by: Rhys Mainwaring * waypoint_follower: replace std::experimental::filesystem Signed-off-by: Rhys Mainwaring * smoother: address clang compilation issues Signed-off-by: Rhys Mainwaring * smoother: remove unused variables Signed-off-by: Rhys Mainwaring * system_tests: remove dependency on stdc++fs Signed-off-by: Rhys Mainwaring * rotation_shim_controller: update percentage arg in setSpeedLimit to boolean Signed-off-by: Rhys Mainwaring * planner: remove unused variables Signed-off-by: Rhys Mainwaring * costmap_2d: address clang compilation issues Signed-off-by: Rhys Mainwaring * mppi_controller: replace use of auto as function param with templates Signed-off-by: Rhys Mainwaring * mppi_controller: address clang compilation issues Signed-off-by: Rhys Mainwaring * costmap_2d: resolve clang issue with std::pair non-const copy Signed-off-by: Rhys Mainwaring * smac_planner: suppress unused parameter warnings Signed-off-by: Rhys Mainwaring * behavior_tree: fix code style Signed-off-by: Rhys Mainwaring * costmap_2d: fix code style Signed-off-by: Rhys Mainwaring * mppi_controller: revert reindexing of for-loop Signed-off-by: Rhys Mainwaring * smoother: remove commented code Signed-off-by: Rhys Mainwaring * system_tests: remove commented target link library Signed-off-by: Rhys Mainwaring * collision_monitor: revert parameter type to vector and use explicit constructor Signed-off-by: Rhys Mainwaring --------- Signed-off-by: Rhys Mainwaring --- nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp | 4 +- nav2_amcl/src/pf/pf.c | 5 -- nav2_amcl/src/pf/pf_vector.c | 4 +- .../nav2_behavior_tree/bt_action_node.hpp | 6 +- .../bt_cancel_action_node.hpp | 2 +- .../nav2_behavior_tree/bt_service_node.hpp | 4 +- .../plugins/condition/is_stuck_condition.cpp | 2 +- .../plugins/decorator/speed_controller.cpp | 2 +- .../plugins/drive_on_heading.hpp | 2 +- .../navigators/navigate_to_pose.hpp | 2 +- .../test/collision_detector_node_test.cpp | 1 - .../test/collision_monitor_node_test.cpp | 2 +- .../test/test_constrained_smoother.cpp | 2 +- nav2_controller/src/controller_server.cpp | 2 +- .../denoise/image_processing.hpp | 20 +++-- .../nav2_costmap_2d/inflation_layer.hpp | 2 +- nav2_costmap_2d/plugins/denoise_layer.cpp | 2 +- nav2_costmap_2d/src/clear_costmap_service.cpp | 6 +- .../test/regression/CMakeLists.txt | 3 + .../test/unit/denoise_layer_test.cpp | 6 +- .../test/unit/image_processing_test.cpp | 80 +++++++++++-------- .../nav_2d_utils/test/path_ops_test.cpp | 2 +- nav2_map_server/test/component/CMakeLists.txt | 3 - .../test/component/test_map_saver_node.cpp | 4 +- .../component/test_map_saver_publisher.cpp | 4 +- .../test/component/test_map_server_node.cpp | 4 +- .../test/map_saver_cli/CMakeLists.txt | 1 - .../test/map_saver_cli/test_map_saver_cli.cpp | 20 ++--- nav2_map_server/test/unit/CMakeLists.txt | 1 - nav2_map_server/test/unit/test_map_io.cpp | 4 +- .../test/optimizer_unit_tests.cpp | 2 +- nav2_mppi_controller/test/utils/factory.hpp | 34 +++++--- nav2_mppi_controller/test/utils/utils.hpp | 12 ++- nav2_mppi_controller/test/utils_test.cpp | 2 +- .../test/test_shim_controller.cpp | 2 +- nav2_smac_planner/src/node_lattice.cpp | 4 +- .../test/test_savitzky_golay_smoother.cpp | 4 - nav2_smoother/test/test_smoother_server.cpp | 4 +- nav2_system_tests/src/planning/CMakeLists.txt | 3 - nav2_waypoint_follower/CMakeLists.txt | 2 - .../plugins/photo_at_waypoint.hpp | 4 +- .../plugins/photo_at_waypoint.cpp | 8 +- .../test/test_task_executors.cpp | 4 +- 43 files changed, 152 insertions(+), 135 deletions(-) diff --git a/nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp b/nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp index c3b406cfd4..713478d24d 100644 --- a/nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp +++ b/nav2_amcl/include/nav2_amcl/pf/pf_vector.hpp @@ -49,7 +49,7 @@ typedef struct // Return a zero vector -pf_vector_t pf_vector_zero(); +pf_vector_t pf_vector_zero(void); // Check for NAN or INF in any component // int pf_vector_finite(pf_vector_t a); @@ -71,7 +71,7 @@ pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b); // Return a zero matrix -pf_matrix_t pf_matrix_zero(); +pf_matrix_t pf_matrix_zero(void); // Check for NAN or INF in any component // int pf_matrix_finite(pf_matrix_t a); diff --git a/nav2_amcl/src/pf/pf.c b/nav2_amcl/src/pf/pf.c index de4e3247d1..9d1f5a8289 100644 --- a/nav2_amcl/src/pf/pf.c +++ b/nav2_amcl/src/pf/pf.c @@ -463,7 +463,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set) // Workspace double m[4], c[2][2]; - size_t count; double weight; // Cluster the samples @@ -474,7 +473,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set) for (i = 0; i < set->cluster_max_count; i++) { cluster = set->clusters + i; - cluster->count = 0; cluster->weight = 0; cluster->mean = pf_vector_zero(); cluster->cov = pf_matrix_zero(); @@ -490,7 +488,6 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set) } // Initialize overall filter stats - count = 0; weight = 0.0; set->mean = pf_vector_zero(); set->cov = pf_matrix_zero(); @@ -521,10 +518,8 @@ void pf_cluster_stats(pf_t * pf, pf_sample_set_t * set) cluster = set->clusters + cidx; - cluster->count += 1; cluster->weight += sample->weight; - count += 1; weight += sample->weight; // Compute mean diff --git a/nav2_amcl/src/pf/pf_vector.c b/nav2_amcl/src/pf/pf_vector.c index a7a5cd39c6..00fa384060 100644 --- a/nav2_amcl/src/pf/pf_vector.c +++ b/nav2_amcl/src/pf/pf_vector.c @@ -35,7 +35,7 @@ // Return a zero vector -pf_vector_t pf_vector_zero() +pf_vector_t pf_vector_zero(void) { pf_vector_t c; @@ -130,7 +130,7 @@ pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b) // Return a zero matrix -pf_matrix_t pf_matrix_zero() +pf_matrix_t pf_matrix_zero(void) { int i, j; pf_matrix_t c; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index 64cc20b4e9..30519108cf 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -206,7 +206,8 @@ class BtActionNode : public BT::ActionNodeBase // if new goal was sent and action server has not yet responded // check the future goal handle if (future_goal_handle_) { - auto elapsed = (node_->now() - time_goal_sent_).to_chrono(); + auto elapsed = + (node_->now() - time_goal_sent_).template to_chrono(); if (!is_future_goal_handle_complete(elapsed)) { // return RUNNING if there is still some time before timeout happens if (elapsed < server_timeout_) { @@ -237,7 +238,8 @@ class BtActionNode : public BT::ActionNodeBase { goal_updated_ = false; send_new_goal(); - auto elapsed = (node_->now() - time_goal_sent_).to_chrono(); + auto elapsed = + (node_->now() - time_goal_sent_).template to_chrono(); if (!is_future_goal_handle_complete(elapsed)) { if (elapsed < server_timeout_) { return BT::NodeStatus::RUNNING; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp index d76aa693ff..179c93e4d2 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp @@ -116,7 +116,7 @@ class BtCancelActionNode : public BT::ActionNodeBase return basic; } - void halt() + void halt() override { } diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp index 26efba04c9..a027ac7760 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp @@ -183,7 +183,7 @@ class BtServiceNode : public BT::ActionNodeBase */ virtual BT::NodeStatus check_future() { - auto elapsed = (node_->now() - sent_time_).to_chrono(); + auto elapsed = (node_->now() - sent_time_).template to_chrono(); auto remaining = server_timeout_ - elapsed; if (remaining > std::chrono::milliseconds(0)) { @@ -199,7 +199,7 @@ class BtServiceNode : public BT::ActionNodeBase if (rc == rclcpp::FutureReturnCode::TIMEOUT) { on_wait_for_result(); - elapsed = (node_->now() - sent_time_).to_chrono(); + elapsed = (node_->now() - sent_time_).template to_chrono(); if (elapsed < server_timeout_) { return BT::NodeStatus::RUNNING; } diff --git a/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp b/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp index 211254dafe..a898dec947 100644 --- a/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp @@ -95,7 +95,7 @@ void IsStuckCondition::logStuck(const std::string & msg) const return; } - RCLCPP_INFO(node_->get_logger(), msg.c_str()); + RCLCPP_INFO(node_->get_logger(), "%s", msg.c_str()); prev_msg = msg; } diff --git a/nav2_behavior_tree/plugins/decorator/speed_controller.cpp b/nav2_behavior_tree/plugins/decorator/speed_controller.cpp index e5c96eba2c..f47dfed38a 100644 --- a/nav2_behavior_tree/plugins/decorator/speed_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/speed_controller.cpp @@ -43,7 +43,7 @@ SpeedController::SpeedController( if (min_rate_ <= 0.0 || max_rate_ <= 0.0) { std::string err_msg = "SpeedController node cannot have rate <= 0.0"; - RCLCPP_FATAL(node_->get_logger(), err_msg.c_str()); + RCLCPP_FATAL(node_->get_logger(), "%s", err_msg.c_str()); throw BT::BehaviorTreeException(err_msg); } diff --git a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp index cd32a9f48c..de4aec7532 100644 --- a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp @@ -93,7 +93,7 @@ class DriveOnHeading : public TimedBehavior * @brief Loop function to run behavior * @return Status of behavior */ - ResultStatus onCycleUpdate() + ResultStatus onCycleUpdate() override { rclcpp::Duration time_remaining = end_time_ - this->steady_clock_.now(); if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) { diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp index d256ebf014..4b690bb296 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp @@ -72,7 +72,7 @@ class NavigateToPoseNavigator * @brief Get action name for this navigator * @return string Name of action server */ - std::string getName() {return std::string("navigate_to_pose");} + std::string getName() override {return std::string("navigate_to_pose");} /** * @brief Get navigator's default BT diff --git a/nav2_collision_monitor/test/collision_detector_node_test.cpp b/nav2_collision_monitor/test/collision_detector_node_test.cpp index 3400f1d50d..eab3e17754 100644 --- a/nav2_collision_monitor/test/collision_detector_node_test.cpp +++ b/nav2_collision_monitor/test/collision_detector_node_test.cpp @@ -45,7 +45,6 @@ static constexpr double EPSILON = 1e-5; static const char BASE_FRAME_ID[]{"base_link"}; static const char SOURCE_FRAME_ID[]{"base_source"}; static const char ODOM_FRAME_ID[]{"odom"}; -static const char FOOTPRINT_TOPIC[]{"footprint"}; static const char SCAN_NAME[]{"Scan"}; static const char POINTCLOUD_NAME[]{"PointCloud"}; static const char RANGE_NAME[]{"Range"}; diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index 77f1578a67..e66e33e5cb 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -1163,7 +1163,7 @@ TEST_F(Tester, testSourcesNotSet) setCommonParameters(); addPolygon("Stop", POLYGON, 1.0, "stop"); addSource(SCAN_NAME, SCAN); - cm_->declare_parameter("polygons", rclcpp::ParameterValue({"Stop"})); + cm_->declare_parameter("polygons", rclcpp::ParameterValue(std::vector{"Stop"})); cm_->set_parameter(rclcpp::Parameter("polygons", std::vector{"Stop"})); // Check that Collision Monitor node can not be configured for this parameters set diff --git a/nav2_constrained_smoother/test/test_constrained_smoother.cpp b/nav2_constrained_smoother/test/test_constrained_smoother.cpp index 463af33fd0..1ccae77f77 100644 --- a/nav2_constrained_smoother/test/test_constrained_smoother.cpp +++ b/nav2_constrained_smoother/test/test_constrained_smoother.cpp @@ -100,7 +100,7 @@ class SmootherTest : public ::testing::Test SmootherTest() {SetUp();} ~SmootherTest() {} - void SetUp() + void SetUp() override { node_lifecycle_ = std::make_shared( diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 69b06e3128..bef3e90dad 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -594,7 +594,7 @@ void ControllerServer::computeAndPublishVelocity() // other types will not be resolved with more attempts } catch (nav2_core::NoValidControl & e) { if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) { - RCLCPP_WARN(this->get_logger(), e.what()); + RCLCPP_WARN(this->get_logger(), "%s", e.what()); cmd_vel_2d.twist.angular.x = 0; cmd_vel_2d.twist.angular.y = 0; cmd_vel_2d.twist.angular.z = 0; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp index 4527e07fdd..2cb5a37f1d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/denoise/image_processing.hpp @@ -986,9 +986,10 @@ class GroupsRemover const IsBg & is_background) const { // Creates an image labels in which each obstacles group is labeled with a unique code - auto components = connectedComponents(image, buffer, label_trees, is_background); - const Label groups_count = components.second; - const Image